diff --git a/data/example_log_vr.bin b/data/example_log_vr.bin new file mode 100755 index 000000000..a7b9a7fc6 Binary files /dev/null and b/data/example_log_vr.bin differ diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 5c0e995af..39cb5ebf4 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -7,6 +7,7 @@ #include "Bullet3Common/b3Scalar.h" #include "CollisionShape2TriangleMesh.h" +#include "../OpenGLWindow/ShapeData.h" #include "../OpenGLWindow/SimpleCamera.h" #include "../OpenGLWindow/GLInstanceGraphicsShape.h" @@ -35,6 +36,8 @@ ATTRIBUTE_ALIGNED16( class )MyDebugDrawer : public btIDebugDraw btAlignedObjectArray m_linePoints; btAlignedObjectArray m_lineIndices; + + btVector3 m_currentLineColor; DefaultColors m_ourColors; @@ -133,14 +136,67 @@ public: static btVector4 sColors[4] = { - btVector4(0.3,0.3,1,1), - btVector4(0.6,0.6,1,1), - btVector4(0,1,0,1), - btVector4(0,1,1,1), + btVector4(60./256.,186./256.,84./256.,1), + btVector4(244./256.,194./256.,13./256.,1), + btVector4(219./256.,50./256.,54./256.,1), + btVector4(72./256.,133./256.,237./256.,1), + //btVector4(1,1,0,1), }; + +struct MyHashShape +{ + + int m_shapeKey; + int m_shapeType; + btVector3 m_sphere0Pos; + btVector3 m_sphere1Pos; + btScalar m_radius0; + btScalar m_radius1; + btTransform m_childTransform; + int m_deformFunc; + int m_upAxis; + btScalar m_halfHeight; + + MyHashShape() + :m_shapeKey(0), + m_shapeType(0), + m_sphere0Pos(btVector3(0,0,0)), + m_sphere1Pos(btVector3(0,0,0)), + m_radius0(0), + m_radius1(0), + m_deformFunc(0), + m_upAxis(-1), + m_halfHeight(0) + { + m_childTransform.setIdentity(); + } + + bool equals(const MyHashShape& other) const + { + bool sameShapeType = m_shapeType==other.m_shapeType; + bool sameSphere0= m_sphere0Pos == other.m_sphere0Pos; + bool sameSphere1= m_sphere1Pos == other.m_sphere1Pos; + bool sameRadius0 = m_radius0== other.m_radius0; + bool sameRadius1 = m_radius1== other.m_radius1; + bool sameTransform = m_childTransform== other.m_childTransform; + bool sameUpAxis = m_upAxis == other.m_upAxis; + bool sameHalfHeight = m_halfHeight == other.m_halfHeight; + return sameShapeType && sameSphere0 && sameSphere1 && sameRadius0 && sameRadius1 && sameTransform && sameUpAxis && sameHalfHeight; + } + //to our success + SIMD_FORCE_INLINE unsigned int getHash()const + { + unsigned int key = m_shapeKey; + // Thomas Wang's hash + key += ~(key << 15); key ^= (key >> 10); key += (key << 3); key ^= (key >> 6); key += ~(key << 11); key ^= (key >> 16); + + return key; + } +}; + struct OpenGLGuiHelperInternalData { struct CommonGraphicsApp* m_glApp; @@ -150,12 +206,20 @@ struct OpenGLGuiHelperInternalData btAlignedObjectArray m_rgbaPixelBuffer1; btAlignedObjectArray m_depthBuffer1; - + btHashMap m_hashShapes; + + VisualizerFlagCallback m_visualizerFlagCallback; + + int m_checkedTexture; + int m_checkedTextureGrey; + OpenGLGuiHelperInternalData() :m_vrMode(false), m_vrSkipShadowPass(0), - m_visualizerFlagCallback(0) + m_visualizerFlagCallback(0), + m_checkedTexture(-1), + m_checkedTextureGrey(-1) { } @@ -238,6 +302,7 @@ int OpenGLGuiHelper::registerGraphicsInstance(int shapeIndex, const float* posit void OpenGLGuiHelper::removeAllGraphicsInstances() { + m_data->m_hashShapes.clear(); m_data->m_glApp->m_renderer->removeAllInstances(); } @@ -249,6 +314,45 @@ void OpenGLGuiHelper::removeGraphicsInstance(int graphicsUid) }; } +int OpenGLGuiHelper::createCheckeredTexture(int red,int green, int blue) +{ + int texWidth=1024; + int texHeight=1024; + btAlignedObjectArray texels; + texels.resize(texWidth*texHeight*3); + for (int i=0;igetUserIndex()>=0) return; - btAlignedObjectArray gfxVertices; + if (m_data->m_checkedTexture<0) + { + m_data->m_checkedTexture = createCheckeredTexture(192,192,255); + } + + if (m_data->m_checkedTextureGrey<0) + { + m_data->m_checkedTextureGrey = createCheckeredTexture(192,192,192); + } + + btAlignedObjectArray gfxVertices; btAlignedObjectArray indices; + int strideInBytes = 9*sizeof(float); + //if (collisionShape->getShapeType()==BOX_SHAPE_PROXYTYPE) + { + } + if (collisionShape->getShapeType()==MULTI_SPHERE_SHAPE_PROXYTYPE) + { + btMultiSphereShape* ms = (btMultiSphereShape*) collisionShape; + if (ms->getSphereCount()==2) + { + btAlignedObjectArray transformedVertices; + int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes; + transformedVertices.resize(numVertices*9); + btVector3 sphere0Pos = ms->getSpherePosition(0); + btVector3 sphere1Pos = ms->getSpherePosition(1); + btVector3 fromTo = sphere1Pos-sphere0Pos; + MyHashShape shape; + shape.m_sphere0Pos = sphere0Pos; + shape.m_sphere1Pos = sphere1Pos; + shape.m_radius0 = 2.*ms->getSphereRadius(0); + shape.m_radius1 = 2.*ms->getSphereRadius(1); + shape.m_deformFunc = 1;//vert.dot(fromTo) + int graphicsShapeIndex = -1; + int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape]; + + if (graphicsShapeIndexPtr) + { + //cache hit + graphicsShapeIndex = *graphicsShapeIndexPtr; + } else + { + //cache miss + for (int i=0;i0) + { + btScalar radiusScale = 2.*ms->getSphereRadius(1); + trVer = radiusScale*vert; + trVer+=sphere1Pos; + } else + { + btScalar radiusScale = 2.*ms->getSphereRadius(0); + trVer = radiusScale*vert; + trVer+=sphere0Pos; + } + + transformedVertices[i*9+0] = trVer[0]; + transformedVertices[i*9+1] = trVer[1]; + transformedVertices[i*9+2] = trVer[2]; + transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3]; + transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4]; + transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5]; + transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6]; + transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7]; + transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8]; + } + + int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int); + graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey); + + m_data->m_hashShapes.insert(shape,graphicsShapeIndex); + } + collisionShape->setUserIndex(graphicsShapeIndex); + return; + } + } + + if (collisionShape->getShapeType()==SPHERE_SHAPE_PROXYTYPE) + { + btSphereShape* sphereShape = (btSphereShape*) collisionShape; + btScalar radius = sphereShape->getRadius(); + btScalar sphereSize = 2.*radius; + btVector3 radiusScale(sphereSize,sphereSize,sphereSize); + btAlignedObjectArray transformedVertices; + + + MyHashShape shape; + shape.m_radius0 = sphereSize; + shape.m_deformFunc = 0;////no deform + int graphicsShapeIndex = -1; + int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape]; + + if (graphicsShapeIndexPtr) + { + graphicsShapeIndex = *graphicsShapeIndexPtr; + } else + { + int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes; + transformedVertices.resize(numVertices*9); + for (int i=0;im_checkedTextureGrey); + m_data->m_hashShapes.insert(shape,graphicsShapeIndex); + } + + collisionShape->setUserIndex(graphicsShapeIndex); + return; + } + if (collisionShape->getShapeType()==COMPOUND_SHAPE_PROXYTYPE) + { + btCompoundShape* compound = (btCompoundShape*)collisionShape; + if (compound->getNumChildShapes()==1) + { + if (compound->getChildShape(0)->getShapeType()==SPHERE_SHAPE_PROXYTYPE) + { + btSphereShape* sphereShape = (btSphereShape*) compound->getChildShape(0); + btScalar radius = sphereShape->getRadius(); + btScalar sphereSize = 2.*radius; + btVector3 radiusScale(sphereSize,sphereSize,sphereSize); + + MyHashShape shape; + shape.m_radius0 = sphereSize; + shape.m_deformFunc = 0;//no deform + shape.m_childTransform = compound->getChildTransform(0); + + int graphicsShapeIndex = -1; + int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape]; + + if (graphicsShapeIndexPtr) + { + graphicsShapeIndex = *graphicsShapeIndexPtr; + } + else + { + + btAlignedObjectArray transformedVertices; + int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes; + transformedVertices.resize(numVertices*9); + for (int i=0;igetChildTransform(0)*(radiusScale*vert); + transformedVertices[i*9+0] = trVer[0]; + transformedVertices[i*9+1] = trVer[1]; + transformedVertices[i*9+2] = trVer[2]; + transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3]; + transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4]; + transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5]; + transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6]; + transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7]; + transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8]; + } + + int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int); + graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey); + m_data->m_hashShapes.insert(shape,graphicsShapeIndex); + } + + collisionShape->setUserIndex(graphicsShapeIndex); + return; + } + if (compound->getChildShape(0)->getShapeType()==CAPSULE_SHAPE_PROXYTYPE) + { + btCapsuleShape* sphereShape = (btCapsuleShape*) compound->getChildShape(0); + int up = sphereShape->getUpAxis(); + btScalar halfHeight = sphereShape->getHalfHeight(); + + btScalar radius = sphereShape->getRadius(); + btScalar sphereSize = 2.*radius; + + btVector3 radiusScale = btVector3(sphereSize,sphereSize,sphereSize); + + + MyHashShape shape; + shape.m_radius0 = sphereSize; + shape.m_deformFunc = 2;//no deform + shape.m_childTransform = compound->getChildTransform(0); + shape.m_upAxis = up; + + int graphicsShapeIndex = -1; + int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape]; + + if (graphicsShapeIndexPtr) + { + graphicsShapeIndex = *graphicsShapeIndexPtr; + } + else + { + + btAlignedObjectArray transformedVertices; + int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes; + transformedVertices.resize(numVertices*9); + for (int i=0;igetChildTransform(0)*(radiusScale*vert); + if (trVer[up]>0) + trVer[up]+=halfHeight; + else + trVer[up]-=halfHeight; + + + transformedVertices[i*9+0] = trVer[0]; + transformedVertices[i*9+1] = trVer[1]; + transformedVertices[i*9+2] = trVer[2]; + transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3]; + transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4]; + transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5]; + transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6]; + transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7]; + transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8]; + } + + int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int); + graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey); + m_data->m_hashShapes.insert(shape,graphicsShapeIndex); + } + + collisionShape->setUserIndex(graphicsShapeIndex); + return; + + } + + if (compound->getChildShape(0)->getShapeType()==MULTI_SPHERE_SHAPE_PROXYTYPE) + { + btMultiSphereShape* ms = (btMultiSphereShape*) compound->getChildShape(0); + if (ms->getSphereCount()==2) + { + btAlignedObjectArray transformedVertices; + int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes; + transformedVertices.resize(numVertices*9); + btVector3 sphere0Pos = ms->getSpherePosition(0); + btVector3 sphere1Pos = ms->getSpherePosition(1); + btVector3 fromTo = sphere1Pos-sphere0Pos; + btScalar radiusScale1 = 2.0*ms->getSphereRadius(1); + btScalar radiusScale0 = 2.0*ms->getSphereRadius(0); + + MyHashShape shape; + shape.m_radius0 = radiusScale0; + shape.m_radius1 = radiusScale1; + shape.m_deformFunc = 4; + shape.m_sphere0Pos = sphere0Pos; + shape.m_sphere1Pos = sphere1Pos; + shape.m_childTransform = compound->getChildTransform(0); + + int graphicsShapeIndex = -1; + int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape]; + + if (graphicsShapeIndexPtr) + { + graphicsShapeIndex = *graphicsShapeIndexPtr; + } + else + { + for (int i=0;i0) + { + + trVer = vert*radiusScale1; + trVer+=sphere1Pos; + trVer = compound->getChildTransform(0)*trVer; + } else + { + trVer = vert*radiusScale0; + trVer+=sphere0Pos; + trVer=compound->getChildTransform(0)*trVer; + } + + + + transformedVertices[i*9+0] = trVer[0]; + transformedVertices[i*9+1] = trVer[1]; + transformedVertices[i*9+2] = trVer[2]; + transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3]; + transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4]; + transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5]; + transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6]; + transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7]; + transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8]; + } + + int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int); + graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey); + m_data->m_hashShapes.insert(shape,graphicsShapeIndex); + } + collisionShape->setUserIndex(graphicsShapeIndex); + return; + } + } + } + } + if (collisionShape->getShapeType()==CAPSULE_SHAPE_PROXYTYPE) + { + btCapsuleShape* sphereShape = (btCapsuleShape*) collisionShape;//Y up + int up = sphereShape->getUpAxis(); + btScalar halfHeight = sphereShape->getHalfHeight(); + + btScalar radius = sphereShape->getRadius(); + btScalar sphereSize = 2.*radius; + btVector3 radiusScale(sphereSize,sphereSize,sphereSize); + + + MyHashShape shape; + shape.m_radius0 = sphereSize; + shape.m_deformFunc = 3; + shape.m_upAxis = up; + shape.m_halfHeight = halfHeight; + int graphicsShapeIndex = -1; + int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape]; + + if (graphicsShapeIndexPtr) + { + graphicsShapeIndex = *graphicsShapeIndexPtr; + } + else + { + + btAlignedObjectArray transformedVertices; + int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes; + transformedVertices.resize(numVertices*9); + for (int i=0;i0) + trVer[up]+=halfHeight; + else + trVer[up]-=halfHeight; + + + + transformedVertices[i*9+0] = trVer[0]; + transformedVertices[i*9+1] = trVer[1]; + transformedVertices[i*9+2] = trVer[2]; + transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3]; + transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4]; + transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5]; + transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6]; + transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7]; + transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8]; + } + + int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int); + graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey); + m_data->m_hashShapes.insert(shape,graphicsShapeIndex); + } + collisionShape->setUserIndex(graphicsShapeIndex); + return; + + } + if (collisionShape->getShapeType()==STATIC_PLANE_PROXYTYPE) + { + const btStaticPlaneShape* staticPlaneShape = static_cast(collisionShape); + btScalar planeConst = staticPlaneShape->getPlaneConstant(); + const btVector3& planeNormal = staticPlaneShape->getPlaneNormal(); + btVector3 planeOrigin = planeNormal * planeConst; + btVector3 vec0,vec1; + btPlaneSpace1(planeNormal,vec0,vec1); + + btScalar vecLen = 128; + btVector3 verts[4]; + + verts[0] = planeOrigin + vec0*vecLen + vec1*vecLen; + verts[1] = planeOrigin - vec0*vecLen + vec1*vecLen; + verts[2] = planeOrigin - vec0*vecLen - vec1*vecLen; + verts[3] = planeOrigin + vec0*vecLen - vec1*vecLen; + + int startIndex = 0; + indices.push_back(startIndex+0); + indices.push_back(startIndex+1); + indices.push_back(startIndex+2); + indices.push_back(startIndex+0); + indices.push_back(startIndex+2); + indices.push_back(startIndex+3); + btTransform parentTransform; + parentTransform.setIdentity(); + btVector3 triNormal = parentTransform.getBasis()*planeNormal; + + gfxVertices.resize(4); + + for (int i=0;i<4;i++) + { + btVector3 vtxPos; + btVector3 pos =parentTransform*verts[i]; + + gfxVertices[i].xyzw[0] = pos[0]; + gfxVertices[i].xyzw[1] = pos[1]; + gfxVertices[i].xyzw[2] = pos[2]; + gfxVertices[i].xyzw[3] = 1; + gfxVertices[i].normal[0] = triNormal[0]; + gfxVertices[i].normal[1] = triNormal[1]; + gfxVertices[i].normal[2] = triNormal[2]; + } + + //verts[0] = planeOrigin + vec0*vecLen + vec1*vecLen; + //verts[1] = planeOrigin - vec0*vecLen + vec1*vecLen; + //verts[2] = planeOrigin - vec0*vecLen - vec1*vecLen; + //verts[3] = planeOrigin + vec0*vecLen - vec1*vecLen; + + gfxVertices[0].uv[0] = vecLen/2; + gfxVertices[0].uv[1] = vecLen/2; + gfxVertices[1].uv[0] = -vecLen/2; + gfxVertices[1].uv[1] = vecLen/2; + gfxVertices[2].uv[0] = -vecLen/2; + gfxVertices[2].uv[1] = -vecLen/2; + gfxVertices[3].uv[0] = vecLen/2; + gfxVertices[3].uv[1] = -vecLen/2; + + int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size(),B3_GL_TRIANGLES,m_data->m_checkedTexture); + collisionShape->setUserIndex(shapeId); + return; + } + btTransform startTrans;startTrans.setIdentity(); + //todo: create some textured objects for popular objects, like plane, cube, sphere, capsule { btAlignedObjectArray vertexPositions; @@ -605,7 +1171,12 @@ void OpenGLGuiHelper::autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWor createCollisionShapeGraphicsObject(colObj->getCollisionShape()); int colorIndex = colObj->getBroadphaseHandle()->getUid() & 3; - btVector3 color= sColors[colorIndex]; + btVector3 color; + color = sColors[colorIndex]; + if (colObj->getCollisionShape()->getShapeType()==STATIC_PLANE_PROXYTYPE) + { + color.setValue(1,1,1); + } createCollisionObjectGraphicsObject(colObj,color); } diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.h b/examples/ExampleBrowser/OpenGLGuiHelper.h index 93bc5f3fe..db4a12796 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.h +++ b/examples/ExampleBrowser/OpenGLGuiHelper.h @@ -90,6 +90,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface virtual void dumpFramesToVideo(const char* mp4FileName); + int createCheckeredTexture(int r,int g, int b); }; #endif //OPENGL_GUI_HELPER_H diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp index fcee5a150..d7ed716b0 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp @@ -473,12 +473,12 @@ void ConvertURDF2BulletInternal( int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter); int colGroup=0, colMask=0; - int flags = u2b.getCollisionGroupAndMask(urdfLinkIndex,colGroup, colMask); - if (flags & URDF_HAS_COLLISION_GROUP) + int collisionFlags = u2b.getCollisionGroupAndMask(urdfLinkIndex,colGroup, colMask); + if (collisionFlags & URDF_HAS_COLLISION_GROUP) { collisionFilterGroup = colGroup; } - if (flags & URDF_HAS_COLLISION_MASK) + if (collisionFlags & URDF_HAS_COLLISION_MASK) { collisionFilterMask = colMask; } @@ -498,6 +498,14 @@ void ConvertURDF2BulletInternal( if (mbLinkIndex>=0) //???? double-check +/- 1 { cache.m_bulletMultiBody->getLink(mbLinkIndex).m_collider=col; + if (flags&CUF_USE_SELF_COLLISION_EXCLUDE_PARENT) + { + cache.m_bulletMultiBody->getLink(mbLinkIndex).m_flags |= BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION; + } + if (flags&CUF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS) + { + cache.m_bulletMultiBody->getLink(mbLinkIndex).m_flags |= BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION; + } } else { cache.m_bulletMultiBody->setBaseCollider(col); @@ -539,7 +547,9 @@ void ConvertURDF2Bullet( if (world1 && cache.m_bulletMultiBody) { btMultiBody* mb = cache.m_bulletMultiBody; - mb->setHasSelfCollision(false); + + mb->setHasSelfCollision((flags&CUF_USE_SELF_COLLISION)!=0); + mb->finalizeMultiDof(); btTransform localInertialFrameRoot = cache.m_urdfLinkLocalInertialFrames[urdfLinkIndex]; diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.h b/examples/Importers/ImportURDFDemo/URDF2Bullet.h index de8978faf..ccc63c4d9 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.h +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.h @@ -19,7 +19,9 @@ enum ConvertURDFFlags { // Use inertia values in URDF instead of recomputing them from collision shape. CUF_USE_URDF_INERTIA = 2, CUF_USE_MJCF = 4, - CUF_USE_SELF_COLLISION=8 + CUF_USE_SELF_COLLISION=8, + CUF_USE_SELF_COLLISION_EXCLUDE_PARENT=16, + CUF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS=32, }; void ConvertURDF2Bullet(const URDFImporterInterface& u2b, diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index 5deb8d91c..32cc0e03e 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -192,7 +192,7 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData m_shadowTexture(0), m_renderFrameBuffer(0) { - m_lightPos=b3MakeVector3(-50,30,100); + m_lightPos=b3MakeVector3(-50,50,50); //clear to zero to make it obvious if the matrix is used uninitialized for (int i=0;i<16;i++) diff --git a/examples/OpenGLWindow/ShapeData.h b/examples/OpenGLWindow/ShapeData.h index f538f1e5f..e887912ce 100644 --- a/examples/OpenGLWindow/ShapeData.h +++ b/examples/OpenGLWindow/ShapeData.h @@ -4857,4 +4857,7181 @@ const int point_sphere_indices[]= }; + +const float textured_detailed_sphere_vertices[]= +{ +-0.493414,-0.080891,0.000000,0.000000, -0.986900,-0.161200,0.000000, 1.000000,0.448300, +-0.499267,-0.027069,0.000000,0.000000, -0.998500,-0.054000,0.000000, 1.000000,0.482800, +-0.489673,-0.027069,-0.097402,0.000000, -0.979300,-0.054000,-0.194800, 0.968800,0.482800, +-0.493414,-0.080891,0.000000,0.000000, -0.986900,-0.161200,0.000000, 1.000000,0.448300, +-0.489673,-0.027069,-0.097402,0.000000, -0.979300,-0.054000,-0.194800, 0.968800,0.482800, +-0.483932,-0.080891,-0.096260,0.000000, -0.967900,-0.161200,-0.192500, 0.968800,0.448300, +-0.159651,0.473826,0.000000,0.000000, -0.322300,0.946600,0.000000, 1.000000,0.896600, +-0.107485,0.488310,0.000000,0.000000, -0.218200,0.975900,0.000000, 1.000000,0.931000, +-0.105420,0.488310,-0.020969,0.000000, -0.214000,0.975900,-0.042500, 0.968800,0.931000, +-0.159651,0.473826,0.000000,0.000000, -0.322300,0.946600,0.000000, 1.000000,0.896600, +-0.105420,0.488310,-0.020969,0.000000, -0.214000,0.975900,-0.042500, 0.968800,0.931000, +-0.156583,0.473826,-0.031146,0.000000, -0.316100,0.946600,-0.062900, 0.968800,0.896600, +-0.481775,-0.133764,0.000000,0.000000, -0.963800,-0.266600,0.000000, 1.000000,0.413800, +-0.493414,-0.080891,0.000000,0.000000, -0.986900,-0.161200,0.000000, 1.000000,0.448300, +-0.483932,-0.080891,-0.096260,0.000000, -0.967900,-0.161200,-0.192500, 0.968800,0.448300, +-0.481775,-0.133764,0.000000,0.000000, -0.963800,-0.266600,0.000000, 1.000000,0.413800, +-0.483932,-0.080891,-0.096260,0.000000, -0.967900,-0.161200,-0.192500, 0.968800,0.448300, +-0.472518,-0.133764,-0.093989,0.000000, -0.945200,-0.266600,-0.188000, 0.968800,0.413800, +-0.209945,0.453788,0.000000,0.000000, -0.422700,0.906300,0.000000, 1.000000,0.862100, +-0.159651,0.473826,0.000000,0.000000, -0.322300,0.946600,0.000000, 1.000000,0.896600, +-0.156583,0.473826,-0.031146,0.000000, -0.316100,0.946600,-0.062900, 0.968800,0.896600, +-0.209945,0.453788,0.000000,0.000000, -0.422700,0.906300,0.000000, 1.000000,0.862100, +-0.156583,0.473826,-0.031146,0.000000, -0.316100,0.946600,-0.062900, 0.968800,0.896600, +-0.205911,0.453788,-0.040958,0.000000, -0.414500,0.906300,-0.082400, 0.968800,0.862100, +-0.464489,-0.185069,0.000000,0.000000, -0.929400,-0.369000,0.000000, 1.000000,0.379300, +-0.481775,-0.133764,0.000000,0.000000, -0.963800,-0.266600,0.000000, 1.000000,0.413800, +-0.472518,-0.133764,-0.093989,0.000000, -0.945200,-0.266600,-0.188000, 0.968800,0.413800, +-0.464489,-0.185069,0.000000,0.000000, -0.929400,-0.369000,0.000000, 1.000000,0.379300, +-0.472518,-0.133764,-0.093989,0.000000, -0.945200,-0.266600,-0.188000, 0.968800,0.413800, +-0.455563,-0.185069,-0.090617,0.000000, -0.911600,-0.369000,-0.181300, 0.968800,0.379300, +-0.257777,0.428429,0.000000,0.000000, -0.518000,0.855300,0.000000, 1.000000,0.827600, +-0.209945,0.453788,0.000000,0.000000, -0.422700,0.906300,0.000000, 1.000000,0.862100, +-0.205911,0.453788,-0.040958,0.000000, -0.414500,0.906300,-0.082400, 0.968800,0.862100, +-0.257777,0.428429,0.000000,0.000000, -0.518000,0.855300,0.000000, 1.000000,0.827600, +-0.205911,0.453788,-0.040958,0.000000, -0.414500,0.906300,-0.082400, 0.968800,0.862100, +-0.252824,0.428429,-0.050290,0.000000, -0.508100,0.855300,-0.101000, 0.968800,0.827600, +-0.441756,-0.234204,0.000000,0.000000, -0.884200,-0.467000,0.000000, 1.000000,0.344800, +-0.464489,-0.185069,0.000000,0.000000, -0.929400,-0.369000,0.000000, 1.000000,0.379300, +-0.455563,-0.185069,-0.090617,0.000000, -0.911600,-0.369000,-0.181300, 0.968800,0.379300, +-0.441756,-0.234204,0.000000,0.000000, -0.884200,-0.467000,0.000000, 1.000000,0.344800, +-0.455563,-0.185069,-0.090617,0.000000, -0.911600,-0.369000,-0.181300, 0.968800,0.379300, +-0.433268,-0.234204,-0.086182,0.000000, -0.867200,-0.467000,-0.172500, 0.968800,0.344800, +-0.302587,0.398046,0.000000,0.000000, -0.607300,0.794500,0.000000, 1.000000,0.793100, +-0.257777,0.428429,0.000000,0.000000, -0.518000,0.855300,0.000000, 1.000000,0.827600, +-0.252824,0.428429,-0.050290,0.000000, -0.508100,0.855300,-0.101000, 0.968800,0.827600, +-0.302587,0.398046,0.000000,0.000000, -0.607300,0.794500,0.000000, 1.000000,0.793100, +-0.252824,0.428429,-0.050290,0.000000, -0.508100,0.855300,-0.101000, 0.968800,0.827600, +-0.296773,0.398046,-0.059032,0.000000, -0.595600,0.794500,-0.118500, 0.968800,0.793100, +-0.413844,-0.280594,0.000000,0.000000, -0.828700,-0.559600,0.000000, 1.000000,0.310300, +-0.441756,-0.234204,0.000000,0.000000, -0.884200,-0.467000,0.000000, 1.000000,0.344800, +-0.433268,-0.234204,-0.086182,0.000000, -0.867200,-0.467000,-0.172500, 0.968800,0.344800, +-0.413844,-0.280594,0.000000,0.000000, -0.828700,-0.559600,0.000000, 1.000000,0.310300, +-0.433268,-0.234204,-0.086182,0.000000, -0.867200,-0.467000,-0.172500, 0.968800,0.344800, +-0.405892,-0.280594,-0.080737,0.000000, -0.812800,-0.559600,-0.161700, 0.968800,0.310300, +-0.343850,0.362998,0.000000,0.000000, -0.689400,0.724300,0.000000, 1.000000,0.758600, +-0.302587,0.398046,0.000000,0.000000, -0.607300,0.794500,0.000000, 1.000000,0.793100, +-0.296773,0.398046,-0.059032,0.000000, -0.595600,0.794500,-0.118500, 0.968800,0.793100, +-0.343850,0.362998,0.000000,0.000000, -0.689400,0.724300,0.000000, 1.000000,0.758600, +-0.296773,0.398046,-0.059032,0.000000, -0.595600,0.794500,-0.118500, 0.968800,0.793100, +-0.337243,0.362998,-0.067082,0.000000, -0.676200,0.724300,-0.134500, 0.968800,0.758600, +-0.381081,-0.323693,0.000000,0.000000, -0.763500,-0.645700,0.000000, 1.000000,0.275900, +-0.413844,-0.280594,0.000000,0.000000, -0.828700,-0.559600,0.000000, 1.000000,0.310300, +-0.405892,-0.280594,-0.080737,0.000000, -0.812800,-0.559600,-0.161700, 0.968800,0.310300, +-0.381081,-0.323693,0.000000,0.000000, -0.763500,-0.645700,0.000000, 1.000000,0.275900, +-0.405892,-0.280594,-0.080737,0.000000, -0.812800,-0.559600,-0.161700, 0.968800,0.310300, +-0.373759,-0.323693,-0.074345,0.000000, -0.748900,-0.645700,-0.149000, 0.968800,0.275900, +-0.381081,0.323693,0.000000,0.000000, -0.763500,0.645700,0.000000, 1.000000,0.724100, +-0.343850,0.362998,0.000000,0.000000, -0.689400,0.724300,0.000000, 1.000000,0.758600, +-0.337243,0.362998,-0.067082,0.000000, -0.676200,0.724300,-0.134500, 0.968800,0.758600, +-0.381081,0.323693,0.000000,0.000000, -0.763500,0.645700,0.000000, 1.000000,0.724100, +-0.337243,0.362998,-0.067082,0.000000, -0.676200,0.724300,-0.134500, 0.968800,0.758600, +-0.373758,0.323693,-0.074345,0.000000, -0.748900,0.645700,-0.149000, 0.968800,0.724100, +-0.343850,-0.362998,0.000000,0.000000, -0.689400,-0.724300,0.000000, 1.000000,0.241400, +-0.381081,-0.323693,0.000000,0.000000, -0.763500,-0.645700,0.000000, 1.000000,0.275900, +-0.373759,-0.323693,-0.074345,0.000000, -0.748900,-0.645700,-0.149000, 0.968800,0.275900, +-0.343850,-0.362998,0.000000,0.000000, -0.689400,-0.724300,0.000000, 1.000000,0.241400, +-0.373759,-0.323693,-0.074345,0.000000, -0.748900,-0.645700,-0.149000, 0.968800,0.275900, +-0.337243,-0.362998,-0.067082,0.000000, -0.676200,-0.724300,-0.134500, 0.968800,0.241400, +-0.413844,0.280594,0.000000,0.000000, -0.828700,0.559600,0.000000, 1.000000,0.689700, +-0.381081,0.323693,0.000000,0.000000, -0.763500,0.645700,0.000000, 1.000000,0.724100, +-0.373758,0.323693,-0.074345,0.000000, -0.748900,0.645700,-0.149000, 0.968800,0.724100, +-0.413844,0.280594,0.000000,0.000000, -0.828700,0.559600,0.000000, 1.000000,0.689700, +-0.373758,0.323693,-0.074345,0.000000, -0.748900,0.645700,-0.149000, 0.968800,0.724100, +-0.405892,0.280594,-0.080737,0.000000, -0.812800,0.559600,-0.161700, 0.968800,0.689700, +-0.302588,-0.398046,0.000000,0.000000, -0.607300,-0.794500,0.000000, 1.000000,0.206900, +-0.343850,-0.362998,0.000000,0.000000, -0.689400,-0.724300,0.000000, 1.000000,0.241400, +-0.337243,-0.362998,-0.067082,0.000000, -0.676200,-0.724300,-0.134500, 0.968800,0.241400, +-0.302588,-0.398046,0.000000,0.000000, -0.607300,-0.794500,0.000000, 1.000000,0.206900, +-0.337243,-0.362998,-0.067082,0.000000, -0.676200,-0.724300,-0.134500, 0.968800,0.241400, +-0.296773,-0.398046,-0.059032,0.000000, -0.595600,-0.794500,-0.118500, 0.968800,0.206900, +-0.441756,0.234204,0.000000,0.000000, -0.884200,0.467000,0.000000, 1.000000,0.655200, +-0.413844,0.280594,0.000000,0.000000, -0.828700,0.559600,0.000000, 1.000000,0.689700, +-0.405892,0.280594,-0.080737,0.000000, -0.812800,0.559600,-0.161700, 0.968800,0.689700, +-0.441756,0.234204,0.000000,0.000000, -0.884200,0.467000,0.000000, 1.000000,0.655200, +-0.405892,0.280594,-0.080737,0.000000, -0.812800,0.559600,-0.161700, 0.968800,0.689700, +-0.433268,0.234204,-0.086182,0.000000, -0.867200,0.467000,-0.172500, 0.968800,0.655200, +-0.257777,-0.428429,0.000000,0.000000, -0.518000,-0.855300,0.000000, 1.000000,0.172400, +-0.302588,-0.398046,0.000000,0.000000, -0.607300,-0.794500,0.000000, 1.000000,0.206900, +-0.296773,-0.398046,-0.059032,0.000000, -0.595600,-0.794500,-0.118500, 0.968800,0.206900, +-0.257777,-0.428429,0.000000,0.000000, -0.518000,-0.855300,0.000000, 1.000000,0.172400, +-0.296773,-0.398046,-0.059032,0.000000, -0.595600,-0.794500,-0.118500, 0.968800,0.206900, +-0.252824,-0.428429,-0.050290,0.000000, -0.508100,-0.855300,-0.101000, 0.968800,0.172400, +-0.464489,0.185069,0.000000,0.000000, -0.929400,0.369000,0.000000, 1.000000,0.620700, +-0.441756,0.234204,0.000000,0.000000, -0.884200,0.467000,0.000000, 1.000000,0.655200, +-0.433268,0.234204,-0.086182,0.000000, -0.867200,0.467000,-0.172500, 0.968800,0.655200, +-0.464489,0.185069,0.000000,0.000000, -0.929400,0.369000,0.000000, 1.000000,0.620700, +-0.433268,0.234204,-0.086182,0.000000, -0.867200,0.467000,-0.172500, 0.968800,0.655200, +-0.455563,0.185069,-0.090617,0.000000, -0.911600,0.369000,-0.181300, 0.968800,0.620700, +-0.209945,-0.453788,0.000000,0.000000, -0.422700,-0.906300,0.000000, 1.000000,0.137900, +-0.257777,-0.428429,0.000000,0.000000, -0.518000,-0.855300,0.000000, 1.000000,0.172400, +-0.252824,-0.428429,-0.050290,0.000000, -0.508100,-0.855300,-0.101000, 0.968800,0.172400, +-0.209945,-0.453788,0.000000,0.000000, -0.422700,-0.906300,0.000000, 1.000000,0.137900, +-0.252824,-0.428429,-0.050290,0.000000, -0.508100,-0.855300,-0.101000, 0.968800,0.172400, +-0.205911,-0.453788,-0.040958,0.000000, -0.414500,-0.906300,-0.082400, 0.968800,0.137900, +-0.481775,0.133764,0.000000,0.000000, -0.963800,0.266600,0.000000, 1.000000,0.586200, +-0.464489,0.185069,0.000000,0.000000, -0.929400,0.369000,0.000000, 1.000000,0.620700, +-0.455563,0.185069,-0.090617,0.000000, -0.911600,0.369000,-0.181300, 0.968800,0.620700, +-0.481775,0.133764,0.000000,0.000000, -0.963800,0.266600,0.000000, 1.000000,0.586200, +-0.455563,0.185069,-0.090617,0.000000, -0.911600,0.369000,-0.181300, 0.968800,0.620700, +-0.472518,0.133764,-0.093989,0.000000, -0.945200,0.266600,-0.188000, 0.968800,0.586200, +-0.159651,-0.473826,0.000000,0.000000, -0.322300,-0.946600,0.000000, 1.000000,0.103400, +-0.209945,-0.453788,0.000000,0.000000, -0.422700,-0.906300,0.000000, 1.000000,0.137900, +-0.205911,-0.453788,-0.040958,0.000000, -0.414500,-0.906300,-0.082400, 0.968800,0.137900, +-0.159651,-0.473826,0.000000,0.000000, -0.322300,-0.946600,0.000000, 1.000000,0.103400, +-0.205911,-0.453788,-0.040958,0.000000, -0.414500,-0.906300,-0.082400, 0.968800,0.137900, +-0.156584,-0.473826,-0.031147,0.000000, -0.316100,-0.946600,-0.062900, 0.968800,0.103400, +-0.493414,0.080891,0.000000,0.000000, -0.986900,0.161200,0.000000, 1.000000,0.551700, +-0.481775,0.133764,0.000000,0.000000, -0.963800,0.266600,0.000000, 1.000000,0.586200, +-0.472518,0.133764,-0.093989,0.000000, -0.945200,0.266600,-0.188000, 0.968800,0.586200, +-0.493414,0.080891,0.000000,0.000000, -0.986900,0.161200,0.000000, 1.000000,0.551700, +-0.472518,0.133764,-0.093989,0.000000, -0.945200,0.266600,-0.188000, 0.968800,0.586200, +-0.483932,0.080891,-0.096260,0.000000, -0.967900,0.161200,-0.192500, 0.968800,0.551700, +-0.107486,-0.488310,0.000000,0.000000, -0.218200,-0.975900,0.000000, 1.000000,0.069000, +-0.159651,-0.473826,0.000000,0.000000, -0.322300,-0.946600,0.000000, 1.000000,0.103400, +-0.156584,-0.473826,-0.031147,0.000000, -0.316100,-0.946600,-0.062900, 0.968800,0.103400, +-0.107486,-0.488310,0.000000,0.000000, -0.218200,-0.975900,0.000000, 1.000000,0.069000, +-0.156584,-0.473826,-0.031147,0.000000, -0.316100,-0.946600,-0.062900, 0.968800,0.103400, +-0.105421,-0.488310,-0.020970,0.000000, -0.214000,-0.975900,-0.042500, 0.968800,0.069000, +-0.499267,0.027069,0.000000,0.000000, -0.998500,0.054000,0.000000, 1.000000,0.517200, +-0.493414,0.080891,0.000000,0.000000, -0.986900,0.161200,0.000000, 1.000000,0.551700, +-0.483932,0.080891,-0.096260,0.000000, -0.967900,0.161200,-0.192500, 0.968800,0.551700, +-0.499267,0.027069,0.000000,0.000000, -0.998500,0.054000,0.000000, 1.000000,0.517200, +-0.483932,0.080891,-0.096260,0.000000, -0.967900,0.161200,-0.192500, 0.968800,0.551700, +-0.489673,0.027069,-0.097402,0.000000, -0.979300,0.054000,-0.194800, 0.968800,0.517200, +-0.054060,0.497069,0.000000,0.000000, -0.111500,0.993700,0.000000, 0.427200,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +-0.053021,0.497069,-0.010546,0.000000, -0.109300,0.993700,-0.021700, 0.429000,0.962300, +-0.054060,-0.497069,0.000000,0.000000, -0.111500,-0.993700,0.000000, 1.000000,0.034500, +-0.107486,-0.488310,0.000000,0.000000, -0.218200,-0.975900,0.000000, 1.000000,0.069000, +-0.105421,-0.488310,-0.020970,0.000000, -0.214000,-0.975900,-0.042500, 0.968800,0.069000, +-0.054060,-0.497069,0.000000,0.000000, -0.111500,-0.993700,0.000000, 1.000000,0.034500, +-0.105421,-0.488310,-0.020970,0.000000, -0.214000,-0.975900,-0.042500, 0.968800,0.069000, +-0.053021,-0.497069,-0.010546,0.000000, -0.109300,-0.993700,-0.021700, 0.968800,0.034500, +-0.499267,-0.027069,0.000000,0.000000, -0.998500,-0.054000,0.000000, 1.000000,0.482800, +-0.499267,0.027069,0.000000,0.000000, -0.998500,0.054000,0.000000, 1.000000,0.517200, +-0.489673,0.027069,-0.097402,0.000000, -0.979300,0.054000,-0.194800, 0.968800,0.517200, +-0.499267,-0.027069,0.000000,0.000000, -0.998500,-0.054000,0.000000, 1.000000,0.482800, +-0.489673,0.027069,-0.097402,0.000000, -0.979300,0.054000,-0.194800, 0.968800,0.517200, +-0.489673,-0.027069,-0.097402,0.000000, -0.979300,-0.054000,-0.194800, 0.968800,0.482800, +-0.107485,0.488310,0.000000,0.000000, -0.218200,0.975900,0.000000, 1.000000,0.931000, +-0.054060,0.497069,0.000000,0.000000, -0.111500,0.993700,0.000000, 1.000000,0.965500, +-0.053021,0.497069,-0.010546,0.000000, -0.109300,0.993700,-0.021700, 0.968800,0.965500, +-0.107485,0.488310,0.000000,0.000000, -0.218200,0.975900,0.000000, 1.000000,0.931000, +-0.053021,0.497069,-0.010546,0.000000, -0.109300,0.993700,-0.021700, 0.968800,0.965500, +-0.105420,0.488310,-0.020969,0.000000, -0.214000,0.975900,-0.042500, 0.968800,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +-0.054060,-0.497069,0.000000,0.000000, -0.111500,-0.993700,0.000000, 0.494200,0.053800, +-0.053021,-0.497069,-0.010546,0.000000, -0.109300,-0.993700,-0.021700, 0.491600,0.053800, +-0.489673,0.027069,-0.097402,0.000000, -0.979300,0.054000,-0.194800, 0.968800,0.517200, +-0.483932,0.080891,-0.096260,0.000000, -0.967900,0.161200,-0.192500, 0.968800,0.551700, +-0.455855,0.080891,-0.188821,0.000000, -0.911800,0.161200,-0.377700, 0.937500,0.551700, +-0.489673,0.027069,-0.097402,0.000000, -0.979300,0.054000,-0.194800, 0.968800,0.517200, +-0.455855,0.080891,-0.188821,0.000000, -0.911800,0.161200,-0.377700, 0.937500,0.551700, +-0.461262,0.027069,-0.191061,0.000000, -0.922500,0.054000,-0.382100, 0.937500,0.517200, +-0.053021,0.497069,-0.010546,0.000000, -0.109300,0.993700,-0.021700, 0.429000,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +-0.049945,0.497069,-0.020688,0.000000, -0.103000,0.993700,-0.042600, 0.430800,0.962300, +-0.053021,-0.497069,-0.010546,0.000000, -0.109300,-0.993700,-0.021700, 0.968800,0.034500, +-0.105421,-0.488310,-0.020970,0.000000, -0.214000,-0.975900,-0.042500, 0.968800,0.069000, +-0.099304,-0.488310,-0.041133,0.000000, -0.201600,-0.975900,-0.083500, 0.937500,0.069000, +-0.053021,-0.497069,-0.010546,0.000000, -0.109300,-0.993700,-0.021700, 0.968800,0.034500, +-0.099304,-0.488310,-0.041133,0.000000, -0.201600,-0.975900,-0.083500, 0.937500,0.069000, +-0.049945,-0.497069,-0.020688,0.000000, -0.103000,-0.993700,-0.042600, 0.937500,0.034500, +-0.489673,-0.027069,-0.097402,0.000000, -0.979300,-0.054000,-0.194800, 0.968800,0.482800, +-0.489673,0.027069,-0.097402,0.000000, -0.979300,0.054000,-0.194800, 0.968800,0.517200, +-0.461262,0.027069,-0.191061,0.000000, -0.922500,0.054000,-0.382100, 0.937500,0.517200, +-0.489673,-0.027069,-0.097402,0.000000, -0.979300,-0.054000,-0.194800, 0.968800,0.482800, +-0.461262,0.027069,-0.191061,0.000000, -0.922500,0.054000,-0.382100, 0.937500,0.517200, +-0.461262,-0.027069,-0.191061,0.000000, -0.922500,-0.054000,-0.382100, 0.937500,0.482800, +-0.105420,0.488310,-0.020969,0.000000, -0.214000,0.975900,-0.042500, 0.968800,0.931000, +-0.053021,0.497069,-0.010546,0.000000, -0.109300,0.993700,-0.021700, 0.968800,0.965500, +-0.049945,0.497069,-0.020688,0.000000, -0.103000,0.993700,-0.042600, 0.937500,0.965500, +-0.105420,0.488310,-0.020969,0.000000, -0.214000,0.975900,-0.042500, 0.968800,0.931000, +-0.049945,0.497069,-0.020688,0.000000, -0.103000,0.993700,-0.042600, 0.937500,0.965500, +-0.099303,0.488310,-0.041132,0.000000, -0.201600,0.975900,-0.083500, 0.937500,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +-0.053021,-0.497069,-0.010546,0.000000, -0.109300,-0.993700,-0.021700, 0.491600,0.053800, +-0.049945,-0.497069,-0.020688,0.000000, -0.103000,-0.993700,-0.042600, 0.489000,0.053800, +-0.483932,-0.080891,-0.096260,0.000000, -0.967900,-0.161200,-0.192500, 0.968800,0.448300, +-0.489673,-0.027069,-0.097402,0.000000, -0.979300,-0.054000,-0.194800, 0.968800,0.482800, +-0.461262,-0.027069,-0.191061,0.000000, -0.922500,-0.054000,-0.382100, 0.937500,0.482800, +-0.483932,-0.080891,-0.096260,0.000000, -0.967900,-0.161200,-0.192500, 0.968800,0.448300, +-0.461262,-0.027069,-0.191061,0.000000, -0.922500,-0.054000,-0.382100, 0.937500,0.482800, +-0.455855,-0.080891,-0.188821,0.000000, -0.911800,-0.161200,-0.377700, 0.937500,0.448300, +-0.156583,0.473826,-0.031146,0.000000, -0.316100,0.946600,-0.062900, 0.968800,0.896600, +-0.105420,0.488310,-0.020969,0.000000, -0.214000,0.975900,-0.042500, 0.968800,0.931000, +-0.099303,0.488310,-0.041132,0.000000, -0.201600,0.975900,-0.083500, 0.937500,0.931000, +-0.156583,0.473826,-0.031146,0.000000, -0.316100,0.946600,-0.062900, 0.968800,0.896600, +-0.099303,0.488310,-0.041132,0.000000, -0.201600,0.975900,-0.083500, 0.937500,0.931000, +-0.147498,0.473826,-0.061095,0.000000, -0.297800,0.946600,-0.123300, 0.937500,0.896600, +-0.472518,-0.133764,-0.093989,0.000000, -0.945200,-0.266600,-0.188000, 0.968800,0.413800, +-0.483932,-0.080891,-0.096260,0.000000, -0.967900,-0.161200,-0.192500, 0.968800,0.448300, +-0.455855,-0.080891,-0.188821,0.000000, -0.911800,-0.161200,-0.377700, 0.937500,0.448300, +-0.472518,-0.133764,-0.093989,0.000000, -0.945200,-0.266600,-0.188000, 0.968800,0.413800, +-0.455855,-0.080891,-0.188821,0.000000, -0.911800,-0.161200,-0.377700, 0.937500,0.448300, +-0.445102,-0.133764,-0.184367,0.000000, -0.890400,-0.266600,-0.368800, 0.937500,0.413800, +-0.205911,0.453788,-0.040958,0.000000, -0.414500,0.906300,-0.082400, 0.968800,0.862100, +-0.156583,0.473826,-0.031146,0.000000, -0.316100,0.946600,-0.062900, 0.968800,0.896600, +-0.147498,0.473826,-0.061095,0.000000, -0.297800,0.946600,-0.123300, 0.937500,0.896600, +-0.205911,0.453788,-0.040958,0.000000, -0.414500,0.906300,-0.082400, 0.968800,0.862100, +-0.147498,0.473826,-0.061095,0.000000, -0.297800,0.946600,-0.123300, 0.937500,0.896600, +-0.193963,0.453788,-0.080342,0.000000, -0.390500,0.906300,-0.161700, 0.937500,0.862100, +-0.455563,-0.185069,-0.090617,0.000000, -0.911600,-0.369000,-0.181300, 0.968800,0.379300, +-0.472518,-0.133764,-0.093989,0.000000, -0.945200,-0.266600,-0.188000, 0.968800,0.413800, +-0.445102,-0.133764,-0.184367,0.000000, -0.890400,-0.266600,-0.368800, 0.937500,0.413800, +-0.455563,-0.185069,-0.090617,0.000000, -0.911600,-0.369000,-0.181300, 0.968800,0.379300, +-0.445102,-0.133764,-0.184367,0.000000, -0.890400,-0.266600,-0.368800, 0.937500,0.413800, +-0.429132,-0.185069,-0.177752,0.000000, -0.858700,-0.369000,-0.355700, 0.937500,0.379300, +-0.252824,0.428429,-0.050290,0.000000, -0.508100,0.855300,-0.101000, 0.968800,0.827600, +-0.205911,0.453788,-0.040958,0.000000, -0.414500,0.906300,-0.082400, 0.968800,0.862100, +-0.193963,0.453788,-0.080342,0.000000, -0.390500,0.906300,-0.161700, 0.937500,0.862100, +-0.252824,0.428429,-0.050290,0.000000, -0.508100,0.855300,-0.101000, 0.968800,0.827600, +-0.193963,0.453788,-0.080342,0.000000, -0.390500,0.906300,-0.161700, 0.937500,0.862100, +-0.238155,0.428429,-0.098647,0.000000, -0.478600,0.855300,-0.198200, 0.937500,0.827600, +-0.433268,-0.234204,-0.086182,0.000000, -0.867200,-0.467000,-0.172500, 0.968800,0.344800, +-0.455563,-0.185069,-0.090617,0.000000, -0.911600,-0.369000,-0.181300, 0.968800,0.379300, +-0.429132,-0.185069,-0.177752,0.000000, -0.858700,-0.369000,-0.355700, 0.937500,0.379300, +-0.433268,-0.234204,-0.086182,0.000000, -0.867200,-0.467000,-0.172500, 0.968800,0.344800, +-0.429132,-0.185069,-0.177752,0.000000, -0.858700,-0.369000,-0.355700, 0.937500,0.379300, +-0.408130,-0.234204,-0.169052,0.000000, -0.816900,-0.467000,-0.338400, 0.937500,0.344800, +-0.296773,0.398046,-0.059032,0.000000, -0.595600,0.794500,-0.118500, 0.968800,0.793100, +-0.252824,0.428429,-0.050290,0.000000, -0.508100,0.855300,-0.101000, 0.968800,0.827600, +-0.238155,0.428429,-0.098647,0.000000, -0.478600,0.855300,-0.198200, 0.937500,0.827600, +-0.296773,0.398046,-0.059032,0.000000, -0.595600,0.794500,-0.118500, 0.968800,0.793100, +-0.238155,0.428429,-0.098647,0.000000, -0.478600,0.855300,-0.198200, 0.937500,0.827600, +-0.279554,0.398046,-0.115795,0.000000, -0.561100,0.794500,-0.232400, 0.937500,0.793100, +-0.405892,-0.280594,-0.080737,0.000000, -0.812800,-0.559600,-0.161700, 0.968800,0.310300, +-0.433268,-0.234204,-0.086182,0.000000, -0.867200,-0.467000,-0.172500, 0.968800,0.344800, +-0.408130,-0.234204,-0.169052,0.000000, -0.816900,-0.467000,-0.338400, 0.937500,0.344800, +-0.405892,-0.280594,-0.080737,0.000000, -0.812800,-0.559600,-0.161700, 0.968800,0.310300, +-0.408130,-0.234204,-0.169052,0.000000, -0.816900,-0.467000,-0.338400, 0.937500,0.344800, +-0.382342,-0.280594,-0.158371,0.000000, -0.765600,-0.559600,-0.317100, 0.937500,0.310300, +-0.337243,0.362998,-0.067082,0.000000, -0.676200,0.724300,-0.134500, 0.968800,0.758600, +-0.296773,0.398046,-0.059032,0.000000, -0.595600,0.794500,-0.118500, 0.968800,0.793100, +-0.279554,0.398046,-0.115795,0.000000, -0.561100,0.794500,-0.232400, 0.937500,0.793100, +-0.337243,0.362998,-0.067082,0.000000, -0.676200,0.724300,-0.134500, 0.968800,0.758600, +-0.279554,0.398046,-0.115795,0.000000, -0.561100,0.794500,-0.232400, 0.937500,0.793100, +-0.317676,0.362998,-0.131585,0.000000, -0.637000,0.724300,-0.263800, 0.937500,0.758600, +-0.373759,-0.323693,-0.074345,0.000000, -0.748900,-0.645700,-0.149000, 0.968800,0.275900, +-0.405892,-0.280594,-0.080737,0.000000, -0.812800,-0.559600,-0.161700, 0.968800,0.310300, +-0.382342,-0.280594,-0.158371,0.000000, -0.765600,-0.559600,-0.317100, 0.937500,0.310300, +-0.373759,-0.323693,-0.074345,0.000000, -0.748900,-0.645700,-0.149000, 0.968800,0.275900, +-0.382342,-0.280594,-0.158371,0.000000, -0.765600,-0.559600,-0.317100, 0.937500,0.310300, +-0.352073,-0.323693,-0.145834,0.000000, -0.705400,-0.645700,-0.292200, 0.937500,0.275900, +-0.373758,0.323693,-0.074345,0.000000, -0.748900,0.645700,-0.149000, 0.968800,0.724100, +-0.337243,0.362998,-0.067082,0.000000, -0.676200,0.724300,-0.134500, 0.968800,0.758600, +-0.317676,0.362998,-0.131585,0.000000, -0.637000,0.724300,-0.263800, 0.937500,0.758600, +-0.373758,0.323693,-0.074345,0.000000, -0.748900,0.645700,-0.149000, 0.968800,0.724100, +-0.317676,0.362998,-0.131585,0.000000, -0.637000,0.724300,-0.263800, 0.937500,0.758600, +-0.352073,0.323693,-0.145833,0.000000, -0.705400,0.645700,-0.292200, 0.937500,0.724100, +-0.337243,-0.362998,-0.067082,0.000000, -0.676200,-0.724300,-0.134500, 0.968800,0.241400, +-0.373759,-0.323693,-0.074345,0.000000, -0.748900,-0.645700,-0.149000, 0.968800,0.275900, +-0.352073,-0.323693,-0.145834,0.000000, -0.705400,-0.645700,-0.292200, 0.937500,0.275900, +-0.337243,-0.362998,-0.067082,0.000000, -0.676200,-0.724300,-0.134500, 0.968800,0.241400, +-0.352073,-0.323693,-0.145834,0.000000, -0.705400,-0.645700,-0.292200, 0.937500,0.275900, +-0.317676,-0.362998,-0.131585,0.000000, -0.637000,-0.724300,-0.263800, 0.937500,0.241400, +-0.405892,0.280594,-0.080737,0.000000, -0.812800,0.559600,-0.161700, 0.968800,0.689700, +-0.373758,0.323693,-0.074345,0.000000, -0.748900,0.645700,-0.149000, 0.968800,0.724100, +-0.352073,0.323693,-0.145833,0.000000, -0.705400,0.645700,-0.292200, 0.937500,0.724100, +-0.405892,0.280594,-0.080737,0.000000, -0.812800,0.559600,-0.161700, 0.968800,0.689700, +-0.352073,0.323693,-0.145833,0.000000, -0.705400,0.645700,-0.292200, 0.937500,0.724100, +-0.382342,0.280594,-0.158371,0.000000, -0.765600,0.559600,-0.317100, 0.937500,0.689700, +-0.296773,-0.398046,-0.059032,0.000000, -0.595600,-0.794500,-0.118500, 0.968800,0.206900, +-0.337243,-0.362998,-0.067082,0.000000, -0.676200,-0.724300,-0.134500, 0.968800,0.241400, +-0.317676,-0.362998,-0.131585,0.000000, -0.637000,-0.724300,-0.263800, 0.937500,0.241400, +-0.296773,-0.398046,-0.059032,0.000000, -0.595600,-0.794500,-0.118500, 0.968800,0.206900, +-0.317676,-0.362998,-0.131585,0.000000, -0.637000,-0.724300,-0.263800, 0.937500,0.241400, +-0.279554,-0.398046,-0.115795,0.000000, -0.561100,-0.794500,-0.232400, 0.937500,0.206900, +-0.433268,0.234204,-0.086182,0.000000, -0.867200,0.467000,-0.172500, 0.968800,0.655200, +-0.405892,0.280594,-0.080737,0.000000, -0.812800,0.559600,-0.161700, 0.968800,0.689700, +-0.382342,0.280594,-0.158371,0.000000, -0.765600,0.559600,-0.317100, 0.937500,0.689700, +-0.433268,0.234204,-0.086182,0.000000, -0.867200,0.467000,-0.172500, 0.968800,0.655200, +-0.382342,0.280594,-0.158371,0.000000, -0.765600,0.559600,-0.317100, 0.937500,0.689700, +-0.408130,0.234204,-0.169052,0.000000, -0.816900,0.467000,-0.338400, 0.937500,0.655200, +-0.252824,-0.428429,-0.050290,0.000000, -0.508100,-0.855300,-0.101000, 0.968800,0.172400, +-0.296773,-0.398046,-0.059032,0.000000, -0.595600,-0.794500,-0.118500, 0.968800,0.206900, +-0.279554,-0.398046,-0.115795,0.000000, -0.561100,-0.794500,-0.232400, 0.937500,0.206900, +-0.252824,-0.428429,-0.050290,0.000000, -0.508100,-0.855300,-0.101000, 0.968800,0.172400, +-0.279554,-0.398046,-0.115795,0.000000, -0.561100,-0.794500,-0.232400, 0.937500,0.206900, +-0.238155,-0.428429,-0.098647,0.000000, -0.478600,-0.855300,-0.198200, 0.937500,0.172400, +-0.455563,0.185069,-0.090617,0.000000, -0.911600,0.369000,-0.181300, 0.968800,0.620700, +-0.433268,0.234204,-0.086182,0.000000, -0.867200,0.467000,-0.172500, 0.968800,0.655200, +-0.408130,0.234204,-0.169052,0.000000, -0.816900,0.467000,-0.338400, 0.937500,0.655200, +-0.455563,0.185069,-0.090617,0.000000, -0.911600,0.369000,-0.181300, 0.968800,0.620700, +-0.408130,0.234204,-0.169052,0.000000, -0.816900,0.467000,-0.338400, 0.937500,0.655200, +-0.429132,0.185069,-0.177752,0.000000, -0.858700,0.369000,-0.355700, 0.937500,0.620700, +-0.205911,-0.453788,-0.040958,0.000000, -0.414500,-0.906300,-0.082400, 0.968800,0.137900, +-0.252824,-0.428429,-0.050290,0.000000, -0.508100,-0.855300,-0.101000, 0.968800,0.172400, +-0.238155,-0.428429,-0.098647,0.000000, -0.478600,-0.855300,-0.198200, 0.937500,0.172400, +-0.205911,-0.453788,-0.040958,0.000000, -0.414500,-0.906300,-0.082400, 0.968800,0.137900, +-0.238155,-0.428429,-0.098647,0.000000, -0.478600,-0.855300,-0.198200, 0.937500,0.172400, +-0.193964,-0.453788,-0.080342,0.000000, -0.390500,-0.906300,-0.161700, 0.937500,0.137900, +-0.472518,0.133764,-0.093989,0.000000, -0.945200,0.266600,-0.188000, 0.968800,0.586200, +-0.455563,0.185069,-0.090617,0.000000, -0.911600,0.369000,-0.181300, 0.968800,0.620700, +-0.429132,0.185069,-0.177752,0.000000, -0.858700,0.369000,-0.355700, 0.937500,0.620700, +-0.472518,0.133764,-0.093989,0.000000, -0.945200,0.266600,-0.188000, 0.968800,0.586200, +-0.429132,0.185069,-0.177752,0.000000, -0.858700,0.369000,-0.355700, 0.937500,0.620700, +-0.445102,0.133764,-0.184367,0.000000, -0.890400,0.266600,-0.368800, 0.937500,0.586200, +-0.156584,-0.473826,-0.031147,0.000000, -0.316100,-0.946600,-0.062900, 0.968800,0.103400, +-0.205911,-0.453788,-0.040958,0.000000, -0.414500,-0.906300,-0.082400, 0.968800,0.137900, +-0.193964,-0.453788,-0.080342,0.000000, -0.390500,-0.906300,-0.161700, 0.937500,0.137900, +-0.156584,-0.473826,-0.031147,0.000000, -0.316100,-0.946600,-0.062900, 0.968800,0.103400, +-0.193964,-0.453788,-0.080342,0.000000, -0.390500,-0.906300,-0.161700, 0.937500,0.137900, +-0.147499,-0.473826,-0.061095,0.000000, -0.297800,-0.946600,-0.123300, 0.937500,0.103400, +-0.483932,0.080891,-0.096260,0.000000, -0.967900,0.161200,-0.192500, 0.968800,0.551700, +-0.472518,0.133764,-0.093989,0.000000, -0.945200,0.266600,-0.188000, 0.968800,0.586200, +-0.445102,0.133764,-0.184367,0.000000, -0.890400,0.266600,-0.368800, 0.937500,0.586200, +-0.483932,0.080891,-0.096260,0.000000, -0.967900,0.161200,-0.192500, 0.968800,0.551700, +-0.445102,0.133764,-0.184367,0.000000, -0.890400,0.266600,-0.368800, 0.937500,0.586200, +-0.455855,0.080891,-0.188821,0.000000, -0.911800,0.161200,-0.377700, 0.937500,0.551700, +-0.105421,-0.488310,-0.020970,0.000000, -0.214000,-0.975900,-0.042500, 0.968800,0.069000, +-0.156584,-0.473826,-0.031147,0.000000, -0.316100,-0.946600,-0.062900, 0.968800,0.103400, +-0.147499,-0.473826,-0.061095,0.000000, -0.297800,-0.946600,-0.123300, 0.937500,0.103400, +-0.105421,-0.488310,-0.020970,0.000000, -0.214000,-0.975900,-0.042500, 0.968800,0.069000, +-0.147499,-0.473826,-0.061095,0.000000, -0.297800,-0.946600,-0.123300, 0.937500,0.103400, +-0.099304,-0.488310,-0.041133,0.000000, -0.201600,-0.975900,-0.083500, 0.937500,0.069000, +-0.317676,-0.362998,-0.131585,0.000000, -0.637000,-0.724300,-0.263800, 0.937500,0.241400, +-0.352073,-0.323693,-0.145834,0.000000, -0.705400,-0.645700,-0.292200, 0.937500,0.275900, +-0.316857,-0.323693,-0.211717,0.000000, -0.634900,-0.645700,-0.424200, 0.906300,0.275900, +-0.317676,-0.362998,-0.131585,0.000000, -0.637000,-0.724300,-0.263800, 0.937500,0.241400, +-0.316857,-0.323693,-0.211717,0.000000, -0.634900,-0.645700,-0.424200, 0.906300,0.275900, +-0.285901,-0.362998,-0.191032,0.000000, -0.573300,-0.724300,-0.383000, 0.906300,0.241400, +-0.382342,0.280594,-0.158371,0.000000, -0.765600,0.559600,-0.317100, 0.937500,0.689700, +-0.352073,0.323693,-0.145833,0.000000, -0.705400,0.645700,-0.292200, 0.937500,0.724100, +-0.316857,0.323693,-0.211717,0.000000, -0.634900,0.645700,-0.424200, 0.906300,0.724100, +-0.382342,0.280594,-0.158371,0.000000, -0.765600,0.559600,-0.317100, 0.937500,0.689700, +-0.316857,0.323693,-0.211717,0.000000, -0.634900,0.645700,-0.424200, 0.906300,0.724100, +-0.344099,0.280594,-0.229919,0.000000, -0.689100,0.559600,-0.460400, 0.906300,0.689700, +-0.279554,-0.398046,-0.115795,0.000000, -0.561100,-0.794500,-0.232400, 0.937500,0.206900, +-0.317676,-0.362998,-0.131585,0.000000, -0.637000,-0.724300,-0.263800, 0.937500,0.241400, +-0.285901,-0.362998,-0.191032,0.000000, -0.573300,-0.724300,-0.383000, 0.906300,0.241400, +-0.279554,-0.398046,-0.115795,0.000000, -0.561100,-0.794500,-0.232400, 0.937500,0.206900, +-0.285901,-0.362998,-0.191032,0.000000, -0.573300,-0.724300,-0.383000, 0.906300,0.241400, +-0.251592,-0.398046,-0.168108,0.000000, -0.505000,-0.794500,-0.337400, 0.906300,0.206900, +-0.408130,0.234204,-0.169052,0.000000, -0.816900,0.467000,-0.338400, 0.937500,0.655200, +-0.382342,0.280594,-0.158371,0.000000, -0.765600,0.559600,-0.317100, 0.937500,0.689700, +-0.344099,0.280594,-0.229919,0.000000, -0.689100,0.559600,-0.460400, 0.906300,0.689700, +-0.408130,0.234204,-0.169052,0.000000, -0.816900,0.467000,-0.338400, 0.937500,0.655200, +-0.344099,0.280594,-0.229919,0.000000, -0.689100,0.559600,-0.460400, 0.906300,0.689700, +-0.367307,0.234204,-0.245426,0.000000, -0.735200,0.467000,-0.491300, 0.906300,0.655200, +-0.238155,-0.428429,-0.098647,0.000000, -0.478600,-0.855300,-0.198200, 0.937500,0.172400, +-0.279554,-0.398046,-0.115795,0.000000, -0.561100,-0.794500,-0.232400, 0.937500,0.206900, +-0.251592,-0.398046,-0.168108,0.000000, -0.505000,-0.794500,-0.337400, 0.906300,0.206900, +-0.238155,-0.428429,-0.098647,0.000000, -0.478600,-0.855300,-0.198200, 0.937500,0.172400, +-0.251592,-0.398046,-0.168108,0.000000, -0.505000,-0.794500,-0.337400, 0.906300,0.206900, +-0.214334,-0.428429,-0.143213,0.000000, -0.430700,-0.855300,-0.287800, 0.906300,0.172400, +-0.429132,0.185069,-0.177752,0.000000, -0.858700,0.369000,-0.355700, 0.937500,0.620700, +-0.408130,0.234204,-0.169052,0.000000, -0.816900,0.467000,-0.338400, 0.937500,0.655200, +-0.367307,0.234204,-0.245426,0.000000, -0.735200,0.467000,-0.491300, 0.906300,0.655200, +-0.429132,0.185069,-0.177752,0.000000, -0.858700,0.369000,-0.355700, 0.937500,0.620700, +-0.367307,0.234204,-0.245426,0.000000, -0.735200,0.467000,-0.491300, 0.906300,0.655200, +-0.386208,0.185069,-0.258056,0.000000, -0.772800,0.369000,-0.516300, 0.906200,0.620700, +-0.193964,-0.453788,-0.080342,0.000000, -0.390500,-0.906300,-0.161700, 0.937500,0.137900, +-0.238155,-0.428429,-0.098647,0.000000, -0.478600,-0.855300,-0.198200, 0.937500,0.172400, +-0.214334,-0.428429,-0.143213,0.000000, -0.430700,-0.855300,-0.287800, 0.906300,0.172400, +-0.193964,-0.453788,-0.080342,0.000000, -0.390500,-0.906300,-0.161700, 0.937500,0.137900, +-0.214334,-0.428429,-0.143213,0.000000, -0.430700,-0.855300,-0.287800, 0.906300,0.172400, +-0.174563,-0.453788,-0.116639,0.000000, -0.351400,-0.906300,-0.234800, 0.906300,0.137900, +-0.445102,0.133764,-0.184367,0.000000, -0.890400,0.266600,-0.368800, 0.937500,0.586200, +-0.429132,0.185069,-0.177752,0.000000, -0.858700,0.369000,-0.355700, 0.937500,0.620700, +-0.386208,0.185069,-0.258056,0.000000, -0.772800,0.369000,-0.516300, 0.906200,0.620700, +-0.445102,0.133764,-0.184367,0.000000, -0.890400,0.266600,-0.368800, 0.937500,0.586200, +-0.386208,0.185069,-0.258056,0.000000, -0.772800,0.369000,-0.516300, 0.906200,0.620700, +-0.400582,0.133764,-0.267659,0.000000, -0.801400,0.266600,-0.535400, 0.906300,0.586200, +-0.147499,-0.473826,-0.061095,0.000000, -0.297800,-0.946600,-0.123300, 0.937500,0.103400, +-0.193964,-0.453788,-0.080342,0.000000, -0.390500,-0.906300,-0.161700, 0.937500,0.137900, +-0.174563,-0.453788,-0.116639,0.000000, -0.351400,-0.906300,-0.234800, 0.906300,0.137900, +-0.147499,-0.473826,-0.061095,0.000000, -0.297800,-0.946600,-0.123300, 0.937500,0.103400, +-0.174563,-0.453788,-0.116639,0.000000, -0.351400,-0.906300,-0.234800, 0.906300,0.137900, +-0.132745,-0.473826,-0.088697,0.000000, -0.268000,-0.946600,-0.179100, 0.906300,0.103400, +-0.455855,0.080891,-0.188821,0.000000, -0.911800,0.161200,-0.377700, 0.937500,0.551700, +-0.445102,0.133764,-0.184367,0.000000, -0.890400,0.266600,-0.368800, 0.937500,0.586200, +-0.400582,0.133764,-0.267659,0.000000, -0.801400,0.266600,-0.535400, 0.906300,0.586200, +-0.455855,0.080891,-0.188821,0.000000, -0.911800,0.161200,-0.377700, 0.937500,0.551700, +-0.400582,0.133764,-0.267659,0.000000, -0.801400,0.266600,-0.535400, 0.906300,0.586200, +-0.410258,0.080891,-0.274125,0.000000, -0.820600,0.161200,-0.548300, 0.906300,0.551700, +-0.099304,-0.488310,-0.041133,0.000000, -0.201600,-0.975900,-0.083500, 0.937500,0.069000, +-0.147499,-0.473826,-0.061095,0.000000, -0.297800,-0.946600,-0.123300, 0.937500,0.103400, +-0.132745,-0.473826,-0.088697,0.000000, -0.268000,-0.946600,-0.179100, 0.906300,0.103400, +-0.099304,-0.488310,-0.041133,0.000000, -0.201600,-0.975900,-0.083500, 0.937500,0.069000, +-0.132745,-0.473826,-0.088697,0.000000, -0.268000,-0.946600,-0.179100, 0.906300,0.103400, +-0.089371,-0.488310,-0.059715,0.000000, -0.181400,-0.975900,-0.121200, 0.906300,0.069000, +-0.461262,0.027069,-0.191061,0.000000, -0.922500,0.054000,-0.382100, 0.937500,0.517200, +-0.455855,0.080891,-0.188821,0.000000, -0.911800,0.161200,-0.377700, 0.937500,0.551700, +-0.410258,0.080891,-0.274125,0.000000, -0.820600,0.161200,-0.548300, 0.906300,0.551700, +-0.461262,0.027069,-0.191061,0.000000, -0.922500,0.054000,-0.382100, 0.937500,0.517200, +-0.410258,0.080891,-0.274125,0.000000, -0.820600,0.161200,-0.548300, 0.906300,0.551700, +-0.415125,0.027069,-0.277377,0.000000, -0.830300,0.054000,-0.554700, 0.906300,0.517200, +-0.049945,0.497069,-0.020688,0.000000, -0.103000,0.993700,-0.042600, 0.430800,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +-0.044949,0.497069,-0.030034,0.000000, -0.092700,0.993700,-0.061900, 0.432600,0.962300, +-0.049945,-0.497069,-0.020688,0.000000, -0.103000,-0.993700,-0.042600, 0.937500,0.034500, +-0.099304,-0.488310,-0.041133,0.000000, -0.201600,-0.975900,-0.083500, 0.937500,0.069000, +-0.089371,-0.488310,-0.059715,0.000000, -0.181400,-0.975900,-0.121200, 0.906300,0.069000, +-0.049945,-0.497069,-0.020688,0.000000, -0.103000,-0.993700,-0.042600, 0.937500,0.034500, +-0.089371,-0.488310,-0.059715,0.000000, -0.181400,-0.975900,-0.121200, 0.906300,0.069000, +-0.044949,-0.497069,-0.030034,0.000000, -0.092700,-0.993700,-0.061900, 0.906300,0.034500, +-0.461262,-0.027069,-0.191061,0.000000, -0.922500,-0.054000,-0.382100, 0.937500,0.482800, +-0.461262,0.027069,-0.191061,0.000000, -0.922500,0.054000,-0.382100, 0.937500,0.517200, +-0.415125,0.027069,-0.277377,0.000000, -0.830300,0.054000,-0.554700, 0.906300,0.517200, +-0.461262,-0.027069,-0.191061,0.000000, -0.922500,-0.054000,-0.382100, 0.937500,0.482800, +-0.415125,0.027069,-0.277377,0.000000, -0.830300,0.054000,-0.554700, 0.906300,0.517200, +-0.415125,-0.027069,-0.277377,0.000000, -0.830300,-0.054000,-0.554700, 0.906300,0.482800, +-0.099303,0.488310,-0.041132,0.000000, -0.201600,0.975900,-0.083500, 0.937500,0.931000, +-0.049945,0.497069,-0.020688,0.000000, -0.103000,0.993700,-0.042600, 0.937500,0.965500, +-0.044949,0.497069,-0.030034,0.000000, -0.092700,0.993700,-0.061900, 0.906300,0.965500, +-0.099303,0.488310,-0.041132,0.000000, -0.201600,0.975900,-0.083500, 0.937500,0.931000, +-0.044949,0.497069,-0.030034,0.000000, -0.092700,0.993700,-0.061900, 0.906300,0.965500, +-0.089371,0.488310,-0.059715,0.000000, -0.181400,0.975900,-0.121200, 0.906300,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +-0.049945,-0.497069,-0.020688,0.000000, -0.103000,-0.993700,-0.042600, 0.489000,0.053800, +-0.044949,-0.497069,-0.030034,0.000000, -0.092700,-0.993700,-0.061900, 0.486400,0.053800, +-0.455855,-0.080891,-0.188821,0.000000, -0.911800,-0.161200,-0.377700, 0.937500,0.448300, +-0.461262,-0.027069,-0.191061,0.000000, -0.922500,-0.054000,-0.382100, 0.937500,0.482800, +-0.415125,-0.027069,-0.277377,0.000000, -0.830300,-0.054000,-0.554700, 0.906300,0.482800, +-0.455855,-0.080891,-0.188821,0.000000, -0.911800,-0.161200,-0.377700, 0.937500,0.448300, +-0.415125,-0.027069,-0.277377,0.000000, -0.830300,-0.054000,-0.554700, 0.906300,0.482800, +-0.410258,-0.080891,-0.274125,0.000000, -0.820600,-0.161200,-0.548300, 0.906300,0.448300, +-0.147498,0.473826,-0.061095,0.000000, -0.297800,0.946600,-0.123300, 0.937500,0.896600, +-0.099303,0.488310,-0.041132,0.000000, -0.201600,0.975900,-0.083500, 0.937500,0.931000, +-0.089371,0.488310,-0.059715,0.000000, -0.181400,0.975900,-0.121200, 0.906300,0.931000, +-0.147498,0.473826,-0.061095,0.000000, -0.297800,0.946600,-0.123300, 0.937500,0.896600, +-0.089371,0.488310,-0.059715,0.000000, -0.181400,0.975900,-0.121200, 0.906300,0.931000, +-0.132745,0.473826,-0.088697,0.000000, -0.268000,0.946600,-0.179100, 0.906300,0.896600, +-0.445102,-0.133764,-0.184367,0.000000, -0.890400,-0.266600,-0.368800, 0.937500,0.413800, +-0.455855,-0.080891,-0.188821,0.000000, -0.911800,-0.161200,-0.377700, 0.937500,0.448300, +-0.410258,-0.080891,-0.274125,0.000000, -0.820600,-0.161200,-0.548300, 0.906300,0.448300, +-0.445102,-0.133764,-0.184367,0.000000, -0.890400,-0.266600,-0.368800, 0.937500,0.413800, +-0.410258,-0.080891,-0.274125,0.000000, -0.820600,-0.161200,-0.548300, 0.906300,0.448300, +-0.400582,-0.133764,-0.267659,0.000000, -0.801400,-0.266600,-0.535400, 0.906300,0.413800, +-0.193963,0.453788,-0.080342,0.000000, -0.390500,0.906300,-0.161700, 0.937500,0.862100, +-0.147498,0.473826,-0.061095,0.000000, -0.297800,0.946600,-0.123300, 0.937500,0.896600, +-0.132745,0.473826,-0.088697,0.000000, -0.268000,0.946600,-0.179100, 0.906300,0.896600, +-0.193963,0.453788,-0.080342,0.000000, -0.390500,0.906300,-0.161700, 0.937500,0.862100, +-0.132745,0.473826,-0.088697,0.000000, -0.268000,0.946600,-0.179100, 0.906300,0.896600, +-0.174562,0.453788,-0.116638,0.000000, -0.351400,0.906300,-0.234800, 0.906300,0.862100, +-0.429132,-0.185069,-0.177752,0.000000, -0.858700,-0.369000,-0.355700, 0.937500,0.379300, +-0.445102,-0.133764,-0.184367,0.000000, -0.890400,-0.266600,-0.368800, 0.937500,0.413800, +-0.400582,-0.133764,-0.267659,0.000000, -0.801400,-0.266600,-0.535400, 0.906300,0.413800, +-0.429132,-0.185069,-0.177752,0.000000, -0.858700,-0.369000,-0.355700, 0.937500,0.379300, +-0.400582,-0.133764,-0.267659,0.000000, -0.801400,-0.266600,-0.535400, 0.906300,0.413800, +-0.386208,-0.185069,-0.258056,0.000000, -0.772800,-0.369000,-0.516300, 0.906300,0.379300, +-0.238155,0.428429,-0.098647,0.000000, -0.478600,0.855300,-0.198200, 0.937500,0.827600, +-0.193963,0.453788,-0.080342,0.000000, -0.390500,0.906300,-0.161700, 0.937500,0.862100, +-0.174562,0.453788,-0.116638,0.000000, -0.351400,0.906300,-0.234800, 0.906300,0.862100, +-0.238155,0.428429,-0.098647,0.000000, -0.478600,0.855300,-0.198200, 0.937500,0.827600, +-0.174562,0.453788,-0.116638,0.000000, -0.351400,0.906300,-0.234800, 0.906300,0.862100, +-0.214334,0.428429,-0.143213,0.000000, -0.430700,0.855300,-0.287800, 0.906300,0.827600, +-0.408130,-0.234204,-0.169052,0.000000, -0.816900,-0.467000,-0.338400, 0.937500,0.344800, +-0.429132,-0.185069,-0.177752,0.000000, -0.858700,-0.369000,-0.355700, 0.937500,0.379300, +-0.386208,-0.185069,-0.258056,0.000000, -0.772800,-0.369000,-0.516300, 0.906300,0.379300, +-0.408130,-0.234204,-0.169052,0.000000, -0.816900,-0.467000,-0.338400, 0.937500,0.344800, +-0.386208,-0.185069,-0.258056,0.000000, -0.772800,-0.369000,-0.516300, 0.906300,0.379300, +-0.367307,-0.234204,-0.245427,0.000000, -0.735200,-0.467000,-0.491300, 0.906300,0.344800, +-0.279554,0.398046,-0.115795,0.000000, -0.561100,0.794500,-0.232400, 0.937500,0.793100, +-0.238155,0.428429,-0.098647,0.000000, -0.478600,0.855300,-0.198200, 0.937500,0.827600, +-0.214334,0.428429,-0.143213,0.000000, -0.430700,0.855300,-0.287800, 0.906300,0.827600, +-0.279554,0.398046,-0.115795,0.000000, -0.561100,0.794500,-0.232400, 0.937500,0.793100, +-0.214334,0.428429,-0.143213,0.000000, -0.430700,0.855300,-0.287800, 0.906300,0.827600, +-0.251592,0.398046,-0.168108,0.000000, -0.504900,0.794500,-0.337400, 0.906300,0.793100, +-0.382342,-0.280594,-0.158371,0.000000, -0.765600,-0.559600,-0.317100, 0.937500,0.310300, +-0.408130,-0.234204,-0.169052,0.000000, -0.816900,-0.467000,-0.338400, 0.937500,0.344800, +-0.367307,-0.234204,-0.245427,0.000000, -0.735200,-0.467000,-0.491300, 0.906300,0.344800, +-0.382342,-0.280594,-0.158371,0.000000, -0.765600,-0.559600,-0.317100, 0.937500,0.310300, +-0.367307,-0.234204,-0.245427,0.000000, -0.735200,-0.467000,-0.491300, 0.906300,0.344800, +-0.344099,-0.280594,-0.229919,0.000000, -0.689100,-0.559600,-0.460400, 0.906300,0.310300, +-0.317676,0.362998,-0.131585,0.000000, -0.637000,0.724300,-0.263800, 0.937500,0.758600, +-0.279554,0.398046,-0.115795,0.000000, -0.561100,0.794500,-0.232400, 0.937500,0.793100, +-0.251592,0.398046,-0.168108,0.000000, -0.504900,0.794500,-0.337400, 0.906300,0.793100, +-0.317676,0.362998,-0.131585,0.000000, -0.637000,0.724300,-0.263800, 0.937500,0.758600, +-0.251592,0.398046,-0.168108,0.000000, -0.504900,0.794500,-0.337400, 0.906300,0.793100, +-0.285901,0.362998,-0.191032,0.000000, -0.573300,0.724300,-0.383000, 0.906300,0.758600, +-0.352073,-0.323693,-0.145834,0.000000, -0.705400,-0.645700,-0.292200, 0.937500,0.275900, +-0.382342,-0.280594,-0.158371,0.000000, -0.765600,-0.559600,-0.317100, 0.937500,0.310300, +-0.344099,-0.280594,-0.229919,0.000000, -0.689100,-0.559600,-0.460400, 0.906300,0.310300, +-0.352073,-0.323693,-0.145834,0.000000, -0.705400,-0.645700,-0.292200, 0.937500,0.275900, +-0.344099,-0.280594,-0.229919,0.000000, -0.689100,-0.559600,-0.460400, 0.906300,0.310300, +-0.316857,-0.323693,-0.211717,0.000000, -0.634900,-0.645700,-0.424200, 0.906300,0.275900, +-0.352073,0.323693,-0.145833,0.000000, -0.705400,0.645700,-0.292200, 0.937500,0.724100, +-0.317676,0.362998,-0.131585,0.000000, -0.637000,0.724300,-0.263800, 0.937500,0.758600, +-0.285901,0.362998,-0.191032,0.000000, -0.573300,0.724300,-0.383000, 0.906300,0.758600, +-0.352073,0.323693,-0.145833,0.000000, -0.705400,0.645700,-0.292200, 0.937500,0.724100, +-0.285901,0.362998,-0.191032,0.000000, -0.573300,0.724300,-0.383000, 0.906300,0.758600, +-0.316857,0.323693,-0.211717,0.000000, -0.634900,0.645700,-0.424200, 0.906300,0.724100, +-0.132745,0.473826,-0.088697,0.000000, -0.268000,0.946600,-0.179100, 0.906300,0.896600, +-0.089371,0.488310,-0.059715,0.000000, -0.181400,0.975900,-0.121200, 0.906300,0.931000, +-0.076003,0.488310,-0.076003,0.000000, -0.154300,0.975900,-0.154300, 0.875000,0.931000, +-0.132745,0.473826,-0.088697,0.000000, -0.268000,0.946600,-0.179100, 0.906300,0.896600, +-0.076003,0.488310,-0.076003,0.000000, -0.154300,0.975900,-0.154300, 0.875000,0.931000, +-0.112890,0.473826,-0.112890,0.000000, -0.227900,0.946600,-0.227900, 0.875000,0.896600, +-0.400582,-0.133764,-0.267659,0.000000, -0.801400,-0.266600,-0.535400, 0.906300,0.413800, +-0.410258,-0.080891,-0.274125,0.000000, -0.820600,-0.161200,-0.548300, 0.906300,0.448300, +-0.348896,-0.080891,-0.348895,0.000000, -0.697800,-0.161200,-0.697800, 0.875000,0.448300, +-0.400582,-0.133764,-0.267659,0.000000, -0.801400,-0.266600,-0.535400, 0.906300,0.413800, +-0.348896,-0.080891,-0.348895,0.000000, -0.697800,-0.161200,-0.697800, 0.875000,0.448300, +-0.340667,-0.133764,-0.340666,0.000000, -0.681500,-0.266600,-0.681500, 0.875000,0.413800, +-0.174562,0.453788,-0.116638,0.000000, -0.351400,0.906300,-0.234800, 0.906300,0.862100, +-0.132745,0.473826,-0.088697,0.000000, -0.268000,0.946600,-0.179100, 0.906300,0.896600, +-0.112890,0.473826,-0.112890,0.000000, -0.227900,0.946600,-0.227900, 0.875000,0.896600, +-0.174562,0.453788,-0.116638,0.000000, -0.351400,0.906300,-0.234800, 0.906300,0.862100, +-0.112890,0.473826,-0.112890,0.000000, -0.227900,0.946600,-0.227900, 0.875000,0.896600, +-0.148454,0.453788,-0.148453,0.000000, -0.298900,0.906300,-0.298900, 0.875000,0.862100, +-0.386208,-0.185069,-0.258056,0.000000, -0.772800,-0.369000,-0.516300, 0.906300,0.379300, +-0.400582,-0.133764,-0.267659,0.000000, -0.801400,-0.266600,-0.535400, 0.906300,0.413800, +-0.340667,-0.133764,-0.340666,0.000000, -0.681500,-0.266600,-0.681500, 0.875000,0.413800, +-0.386208,-0.185069,-0.258056,0.000000, -0.772800,-0.369000,-0.516300, 0.906300,0.379300, +-0.340667,-0.133764,-0.340666,0.000000, -0.681500,-0.266600,-0.681500, 0.875000,0.413800, +-0.328443,-0.185069,-0.328443,0.000000, -0.657200,-0.369000,-0.657200, 0.875000,0.379300, +-0.214334,0.428429,-0.143213,0.000000, -0.430700,0.855300,-0.287800, 0.906300,0.827600, +-0.174562,0.453788,-0.116638,0.000000, -0.351400,0.906300,-0.234800, 0.906300,0.862100, +-0.148454,0.453788,-0.148453,0.000000, -0.298900,0.906300,-0.298900, 0.875000,0.862100, +-0.214334,0.428429,-0.143213,0.000000, -0.430700,0.855300,-0.287800, 0.906300,0.827600, +-0.148454,0.453788,-0.148453,0.000000, -0.298900,0.906300,-0.298900, 0.875000,0.862100, +-0.182276,0.428429,-0.182276,0.000000, -0.366300,0.855300,-0.366300, 0.875000,0.827600, +-0.367307,-0.234204,-0.245427,0.000000, -0.735200,-0.467000,-0.491300, 0.906300,0.344800, +-0.386208,-0.185069,-0.258056,0.000000, -0.772800,-0.369000,-0.516300, 0.906300,0.379300, +-0.328443,-0.185069,-0.328443,0.000000, -0.657200,-0.369000,-0.657200, 0.875000,0.379300, +-0.367307,-0.234204,-0.245427,0.000000, -0.735200,-0.467000,-0.491300, 0.906300,0.344800, +-0.328443,-0.185069,-0.328443,0.000000, -0.657200,-0.369000,-0.657200, 0.875000,0.379300, +-0.312369,-0.234204,-0.312369,0.000000, -0.625200,-0.467000,-0.625200, 0.875000,0.344800, +-0.251592,0.398046,-0.168108,0.000000, -0.504900,0.794500,-0.337400, 0.906300,0.793100, +-0.214334,0.428429,-0.143213,0.000000, -0.430700,0.855300,-0.287800, 0.906300,0.827600, +-0.182276,0.428429,-0.182276,0.000000, -0.366300,0.855300,-0.366300, 0.875000,0.827600, +-0.251592,0.398046,-0.168108,0.000000, -0.504900,0.794500,-0.337400, 0.906300,0.793100, +-0.182276,0.428429,-0.182276,0.000000, -0.366300,0.855300,-0.366300, 0.875000,0.827600, +-0.213961,0.398046,-0.213961,0.000000, -0.429400,0.794500,-0.429400, 0.875000,0.793100, +-0.344099,-0.280594,-0.229919,0.000000, -0.689100,-0.559600,-0.460400, 0.906300,0.310300, +-0.367307,-0.234204,-0.245427,0.000000, -0.735200,-0.467000,-0.491300, 0.906300,0.344800, +-0.312369,-0.234204,-0.312369,0.000000, -0.625200,-0.467000,-0.625200, 0.875000,0.344800, +-0.344099,-0.280594,-0.229919,0.000000, -0.689100,-0.559600,-0.460400, 0.906300,0.310300, +-0.312369,-0.234204,-0.312369,0.000000, -0.625200,-0.467000,-0.625200, 0.875000,0.344800, +-0.292632,-0.280594,-0.292632,0.000000, -0.586000,-0.559600,-0.586000, 0.875000,0.310300, +-0.285901,0.362998,-0.191032,0.000000, -0.573300,0.724300,-0.383000, 0.906300,0.758600, +-0.251592,0.398046,-0.168108,0.000000, -0.504900,0.794500,-0.337400, 0.906300,0.793100, +-0.213961,0.398046,-0.213961,0.000000, -0.429400,0.794500,-0.429400, 0.875000,0.793100, +-0.285901,0.362998,-0.191032,0.000000, -0.573300,0.724300,-0.383000, 0.906300,0.758600, +-0.213961,0.398046,-0.213961,0.000000, -0.429400,0.794500,-0.429400, 0.875000,0.793100, +-0.243139,0.362998,-0.243138,0.000000, -0.487500,0.724300,-0.487500, 0.875000,0.758600, +-0.316857,-0.323693,-0.211717,0.000000, -0.634900,-0.645700,-0.424200, 0.906300,0.275900, +-0.344099,-0.280594,-0.229919,0.000000, -0.689100,-0.559600,-0.460400, 0.906300,0.310300, +-0.292632,-0.280594,-0.292632,0.000000, -0.586000,-0.559600,-0.586000, 0.875000,0.310300, +-0.316857,-0.323693,-0.211717,0.000000, -0.634900,-0.645700,-0.424200, 0.906300,0.275900, +-0.292632,-0.280594,-0.292632,0.000000, -0.586000,-0.559600,-0.586000, 0.875000,0.310300, +-0.269465,-0.323693,-0.269464,0.000000, -0.539900,-0.645700,-0.539900, 0.875000,0.275900, +-0.316857,0.323693,-0.211717,0.000000, -0.634900,0.645700,-0.424200, 0.906300,0.724100, +-0.285901,0.362998,-0.191032,0.000000, -0.573300,0.724300,-0.383000, 0.906300,0.758600, +-0.243139,0.362998,-0.243138,0.000000, -0.487500,0.724300,-0.487500, 0.875000,0.758600, +-0.316857,0.323693,-0.211717,0.000000, -0.634900,0.645700,-0.424200, 0.906300,0.724100, +-0.243139,0.362998,-0.243138,0.000000, -0.487500,0.724300,-0.487500, 0.875000,0.758600, +-0.269465,0.323693,-0.269464,0.000000, -0.539900,0.645700,-0.539900, 0.875000,0.724100, +-0.285901,-0.362998,-0.191032,0.000000, -0.573300,-0.724300,-0.383000, 0.906300,0.241400, +-0.316857,-0.323693,-0.211717,0.000000, -0.634900,-0.645700,-0.424200, 0.906300,0.275900, +-0.269465,-0.323693,-0.269464,0.000000, -0.539900,-0.645700,-0.539900, 0.875000,0.275900, +-0.285901,-0.362998,-0.191032,0.000000, -0.573300,-0.724300,-0.383000, 0.906300,0.241400, +-0.269465,-0.323693,-0.269464,0.000000, -0.539900,-0.645700,-0.539900, 0.875000,0.275900, +-0.243139,-0.362998,-0.243138,0.000000, -0.487500,-0.724300,-0.487500, 0.875000,0.241400, +-0.344099,0.280594,-0.229919,0.000000, -0.689100,0.559600,-0.460400, 0.906300,0.689700, +-0.316857,0.323693,-0.211717,0.000000, -0.634900,0.645700,-0.424200, 0.906300,0.724100, +-0.269465,0.323693,-0.269464,0.000000, -0.539900,0.645700,-0.539900, 0.875000,0.724100, +-0.344099,0.280594,-0.229919,0.000000, -0.689100,0.559600,-0.460400, 0.906300,0.689700, +-0.269465,0.323693,-0.269464,0.000000, -0.539900,0.645700,-0.539900, 0.875000,0.724100, +-0.292632,0.280594,-0.292632,0.000000, -0.586000,0.559600,-0.586000, 0.875000,0.689700, +-0.251592,-0.398046,-0.168108,0.000000, -0.505000,-0.794500,-0.337400, 0.906300,0.206900, +-0.285901,-0.362998,-0.191032,0.000000, -0.573300,-0.724300,-0.383000, 0.906300,0.241400, +-0.243139,-0.362998,-0.243138,0.000000, -0.487500,-0.724300,-0.487500, 0.875000,0.241400, +-0.251592,-0.398046,-0.168108,0.000000, -0.505000,-0.794500,-0.337400, 0.906300,0.206900, +-0.243139,-0.362998,-0.243138,0.000000, -0.487500,-0.724300,-0.487500, 0.875000,0.241400, +-0.213961,-0.398046,-0.213961,0.000000, -0.429400,-0.794500,-0.429400, 0.875000,0.206900, +-0.367307,0.234204,-0.245426,0.000000, -0.735200,0.467000,-0.491300, 0.906300,0.655200, +-0.344099,0.280594,-0.229919,0.000000, -0.689100,0.559600,-0.460400, 0.906300,0.689700, +-0.292632,0.280594,-0.292632,0.000000, -0.586000,0.559600,-0.586000, 0.875000,0.689700, +-0.367307,0.234204,-0.245426,0.000000, -0.735200,0.467000,-0.491300, 0.906300,0.655200, +-0.292632,0.280594,-0.292632,0.000000, -0.586000,0.559600,-0.586000, 0.875000,0.689700, +-0.312369,0.234204,-0.312369,0.000000, -0.625200,0.467000,-0.625200, 0.875000,0.655200, +-0.214334,-0.428429,-0.143213,0.000000, -0.430700,-0.855300,-0.287800, 0.906300,0.172400, +-0.251592,-0.398046,-0.168108,0.000000, -0.505000,-0.794500,-0.337400, 0.906300,0.206900, +-0.213961,-0.398046,-0.213961,0.000000, -0.429400,-0.794500,-0.429400, 0.875000,0.206900, +-0.214334,-0.428429,-0.143213,0.000000, -0.430700,-0.855300,-0.287800, 0.906300,0.172400, +-0.213961,-0.398046,-0.213961,0.000000, -0.429400,-0.794500,-0.429400, 0.875000,0.206900, +-0.182276,-0.428429,-0.182276,0.000000, -0.366300,-0.855300,-0.366300, 0.875000,0.172400, +-0.386208,0.185069,-0.258056,0.000000, -0.772800,0.369000,-0.516300, 0.906200,0.620700, +-0.367307,0.234204,-0.245426,0.000000, -0.735200,0.467000,-0.491300, 0.906300,0.655200, +-0.312369,0.234204,-0.312369,0.000000, -0.625200,0.467000,-0.625200, 0.875000,0.655200, +-0.386208,0.185069,-0.258056,0.000000, -0.772800,0.369000,-0.516300, 0.906200,0.620700, +-0.312369,0.234204,-0.312369,0.000000, -0.625200,0.467000,-0.625200, 0.875000,0.655200, +-0.328443,0.185069,-0.328443,0.000000, -0.657200,0.369000,-0.657200, 0.875000,0.620700, +-0.174563,-0.453788,-0.116639,0.000000, -0.351400,-0.906300,-0.234800, 0.906300,0.137900, +-0.214334,-0.428429,-0.143213,0.000000, -0.430700,-0.855300,-0.287800, 0.906300,0.172400, +-0.182276,-0.428429,-0.182276,0.000000, -0.366300,-0.855300,-0.366300, 0.875000,0.172400, +-0.174563,-0.453788,-0.116639,0.000000, -0.351400,-0.906300,-0.234800, 0.906300,0.137900, +-0.182276,-0.428429,-0.182276,0.000000, -0.366300,-0.855300,-0.366300, 0.875000,0.172400, +-0.148454,-0.453788,-0.148453,0.000000, -0.298900,-0.906300,-0.298900, 0.875000,0.137900, +-0.400582,0.133764,-0.267659,0.000000, -0.801400,0.266600,-0.535400, 0.906300,0.586200, +-0.386208,0.185069,-0.258056,0.000000, -0.772800,0.369000,-0.516300, 0.906200,0.620700, +-0.328443,0.185069,-0.328443,0.000000, -0.657200,0.369000,-0.657200, 0.875000,0.620700, +-0.400582,0.133764,-0.267659,0.000000, -0.801400,0.266600,-0.535400, 0.906300,0.586200, +-0.328443,0.185069,-0.328443,0.000000, -0.657200,0.369000,-0.657200, 0.875000,0.620700, +-0.340667,0.133764,-0.340666,0.000000, -0.681500,0.266600,-0.681500, 0.875000,0.586200, +-0.132745,-0.473826,-0.088697,0.000000, -0.268000,-0.946600,-0.179100, 0.906300,0.103400, +-0.174563,-0.453788,-0.116639,0.000000, -0.351400,-0.906300,-0.234800, 0.906300,0.137900, +-0.148454,-0.453788,-0.148453,0.000000, -0.298900,-0.906300,-0.298900, 0.875000,0.137900, +-0.132745,-0.473826,-0.088697,0.000000, -0.268000,-0.946600,-0.179100, 0.906300,0.103400, +-0.148454,-0.453788,-0.148453,0.000000, -0.298900,-0.906300,-0.298900, 0.875000,0.137900, +-0.112890,-0.473826,-0.112890,0.000000, -0.227900,-0.946600,-0.227900, 0.875000,0.103400, +-0.410258,0.080891,-0.274125,0.000000, -0.820600,0.161200,-0.548300, 0.906300,0.551700, +-0.400582,0.133764,-0.267659,0.000000, -0.801400,0.266600,-0.535400, 0.906300,0.586200, +-0.340667,0.133764,-0.340666,0.000000, -0.681500,0.266600,-0.681500, 0.875000,0.586200, +-0.410258,0.080891,-0.274125,0.000000, -0.820600,0.161200,-0.548300, 0.906300,0.551700, +-0.340667,0.133764,-0.340666,0.000000, -0.681500,0.266600,-0.681500, 0.875000,0.586200, +-0.348896,0.080891,-0.348895,0.000000, -0.697800,0.161200,-0.697800, 0.875000,0.551700, +-0.089371,-0.488310,-0.059715,0.000000, -0.181400,-0.975900,-0.121200, 0.906300,0.069000, +-0.132745,-0.473826,-0.088697,0.000000, -0.268000,-0.946600,-0.179100, 0.906300,0.103400, +-0.112890,-0.473826,-0.112890,0.000000, -0.227900,-0.946600,-0.227900, 0.875000,0.103400, +-0.089371,-0.488310,-0.059715,0.000000, -0.181400,-0.975900,-0.121200, 0.906300,0.069000, +-0.112890,-0.473826,-0.112890,0.000000, -0.227900,-0.946600,-0.227900, 0.875000,0.103400, +-0.076004,-0.488310,-0.076003,0.000000, -0.154300,-0.975900,-0.154300, 0.875000,0.069000, +-0.415125,0.027069,-0.277377,0.000000, -0.830300,0.054000,-0.554700, 0.906300,0.517200, +-0.410258,0.080891,-0.274125,0.000000, -0.820600,0.161200,-0.548300, 0.906300,0.551700, +-0.348896,0.080891,-0.348895,0.000000, -0.697800,0.161200,-0.697800, 0.875000,0.551700, +-0.415125,0.027069,-0.277377,0.000000, -0.830300,0.054000,-0.554700, 0.906300,0.517200, +-0.348896,0.080891,-0.348895,0.000000, -0.697800,0.161200,-0.697800, 0.875000,0.551700, +-0.353035,0.027069,-0.353034,0.000000, -0.706100,0.054000,-0.706100, 0.875000,0.517200, +-0.044949,0.497069,-0.030034,0.000000, -0.092700,0.993700,-0.061900, 0.432600,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +-0.038226,0.497069,-0.038226,0.000000, -0.078800,0.993700,-0.078800, 0.434400,0.962300, +-0.044949,-0.497069,-0.030034,0.000000, -0.092700,-0.993700,-0.061900, 0.906300,0.034500, +-0.089371,-0.488310,-0.059715,0.000000, -0.181400,-0.975900,-0.121200, 0.906300,0.069000, +-0.076004,-0.488310,-0.076003,0.000000, -0.154300,-0.975900,-0.154300, 0.875000,0.069000, +-0.044949,-0.497069,-0.030034,0.000000, -0.092700,-0.993700,-0.061900, 0.906300,0.034500, +-0.076004,-0.488310,-0.076003,0.000000, -0.154300,-0.975900,-0.154300, 0.875000,0.069000, +-0.038226,-0.497069,-0.038226,0.000000, -0.078800,-0.993700,-0.078800, 0.875000,0.034500, +-0.415125,-0.027069,-0.277377,0.000000, -0.830300,-0.054000,-0.554700, 0.906300,0.482800, +-0.415125,0.027069,-0.277377,0.000000, -0.830300,0.054000,-0.554700, 0.906300,0.517200, +-0.353035,0.027069,-0.353034,0.000000, -0.706100,0.054000,-0.706100, 0.875000,0.517200, +-0.415125,-0.027069,-0.277377,0.000000, -0.830300,-0.054000,-0.554700, 0.906300,0.482800, +-0.353035,0.027069,-0.353034,0.000000, -0.706100,0.054000,-0.706100, 0.875000,0.517200, +-0.353035,-0.027069,-0.353034,0.000000, -0.706100,-0.054000,-0.706100, 0.875000,0.482800, +-0.089371,0.488310,-0.059715,0.000000, -0.181400,0.975900,-0.121200, 0.906300,0.931000, +-0.044949,0.497069,-0.030034,0.000000, -0.092700,0.993700,-0.061900, 0.906300,0.965500, +-0.038226,0.497069,-0.038226,0.000000, -0.078800,0.993700,-0.078800, 0.875000,0.965500, +-0.089371,0.488310,-0.059715,0.000000, -0.181400,0.975900,-0.121200, 0.906300,0.931000, +-0.038226,0.497069,-0.038226,0.000000, -0.078800,0.993700,-0.078800, 0.875000,0.965500, +-0.076003,0.488310,-0.076003,0.000000, -0.154300,0.975900,-0.154300, 0.875000,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +-0.044949,-0.497069,-0.030034,0.000000, -0.092700,-0.993700,-0.061900, 0.486400,0.053800, +-0.038226,-0.497069,-0.038226,0.000000, -0.078800,-0.993700,-0.078800, 0.483700,0.053800, +-0.410258,-0.080891,-0.274125,0.000000, -0.820600,-0.161200,-0.548300, 0.906300,0.448300, +-0.415125,-0.027069,-0.277377,0.000000, -0.830300,-0.054000,-0.554700, 0.906300,0.482800, +-0.353035,-0.027069,-0.353034,0.000000, -0.706100,-0.054000,-0.706100, 0.875000,0.482800, +-0.410258,-0.080891,-0.274125,0.000000, -0.820600,-0.161200,-0.548300, 0.906300,0.448300, +-0.353035,-0.027069,-0.353034,0.000000, -0.706100,-0.054000,-0.706100, 0.875000,0.482800, +-0.348896,-0.080891,-0.348895,0.000000, -0.697800,-0.161200,-0.697800, 0.875000,0.448300, +-0.328443,0.185069,-0.328443,0.000000, -0.657200,0.369000,-0.657200, 0.875000,0.620700, +-0.312369,0.234204,-0.312369,0.000000, -0.625200,0.467000,-0.625200, 0.875000,0.655200, +-0.245427,0.234204,-0.367307,0.000000, -0.491300,0.467000,-0.735200, 0.843800,0.655200, +-0.328443,0.185069,-0.328443,0.000000, -0.657200,0.369000,-0.657200, 0.875000,0.620700, +-0.245427,0.234204,-0.367307,0.000000, -0.491300,0.467000,-0.735200, 0.843800,0.655200, +-0.258056,0.185069,-0.386207,0.000000, -0.516300,0.369000,-0.772800, 0.843800,0.620700, +-0.148454,-0.453788,-0.148453,0.000000, -0.298900,-0.906300,-0.298900, 0.875000,0.137900, +-0.182276,-0.428429,-0.182276,0.000000, -0.366300,-0.855300,-0.366300, 0.875000,0.172400, +-0.143213,-0.428429,-0.214334,0.000000, -0.287800,-0.855300,-0.430700, 0.843800,0.172400, +-0.148454,-0.453788,-0.148453,0.000000, -0.298900,-0.906300,-0.298900, 0.875000,0.137900, +-0.143213,-0.428429,-0.214334,0.000000, -0.287800,-0.855300,-0.430700, 0.843800,0.172400, +-0.116640,-0.453788,-0.174562,0.000000, -0.234800,-0.906300,-0.351400, 0.843800,0.137900, +-0.340667,0.133764,-0.340666,0.000000, -0.681500,0.266600,-0.681500, 0.875000,0.586200, +-0.328443,0.185069,-0.328443,0.000000, -0.657200,0.369000,-0.657200, 0.875000,0.620700, +-0.258056,0.185069,-0.386207,0.000000, -0.516300,0.369000,-0.772800, 0.843800,0.620700, +-0.340667,0.133764,-0.340666,0.000000, -0.681500,0.266600,-0.681500, 0.875000,0.586200, +-0.258056,0.185069,-0.386207,0.000000, -0.516300,0.369000,-0.772800, 0.843800,0.620700, +-0.267660,0.133764,-0.400581,0.000000, -0.535400,0.266600,-0.801400, 0.843800,0.586200, +-0.112890,-0.473826,-0.112890,0.000000, -0.227900,-0.946600,-0.227900, 0.875000,0.103400, +-0.148454,-0.453788,-0.148453,0.000000, -0.298900,-0.906300,-0.298900, 0.875000,0.137900, +-0.116640,-0.453788,-0.174562,0.000000, -0.234800,-0.906300,-0.351400, 0.843800,0.137900, +-0.112890,-0.473826,-0.112890,0.000000, -0.227900,-0.946600,-0.227900, 0.875000,0.103400, +-0.116640,-0.453788,-0.174562,0.000000, -0.234800,-0.906300,-0.351400, 0.843800,0.137900, +-0.088698,-0.473826,-0.132745,0.000000, -0.179100,-0.946600,-0.268000, 0.843800,0.103400, +-0.348896,0.080891,-0.348895,0.000000, -0.697800,0.161200,-0.697800, 0.875000,0.551700, +-0.340667,0.133764,-0.340666,0.000000, -0.681500,0.266600,-0.681500, 0.875000,0.586200, +-0.267660,0.133764,-0.400581,0.000000, -0.535400,0.266600,-0.801400, 0.843800,0.586200, +-0.348896,0.080891,-0.348895,0.000000, -0.697800,0.161200,-0.697800, 0.875000,0.551700, +-0.267660,0.133764,-0.400581,0.000000, -0.535400,0.266600,-0.801400, 0.843800,0.586200, +-0.274126,0.080891,-0.410257,0.000000, -0.548300,0.161200,-0.820600, 0.843800,0.551700, +-0.076004,-0.488310,-0.076003,0.000000, -0.154300,-0.975900,-0.154300, 0.875000,0.069000, +-0.112890,-0.473826,-0.112890,0.000000, -0.227900,-0.946600,-0.227900, 0.875000,0.103400, +-0.088698,-0.473826,-0.132745,0.000000, -0.179100,-0.946600,-0.268000, 0.843800,0.103400, +-0.076004,-0.488310,-0.076003,0.000000, -0.154300,-0.975900,-0.154300, 0.875000,0.069000, +-0.088698,-0.473826,-0.132745,0.000000, -0.179100,-0.946600,-0.268000, 0.843800,0.103400, +-0.059716,-0.488310,-0.089370,0.000000, -0.121200,-0.975900,-0.181400, 0.843800,0.069000, +-0.353035,0.027069,-0.353034,0.000000, -0.706100,0.054000,-0.706100, 0.875000,0.517200, +-0.348896,0.080891,-0.348895,0.000000, -0.697800,0.161200,-0.697800, 0.875000,0.551700, +-0.274126,0.080891,-0.410257,0.000000, -0.548300,0.161200,-0.820600, 0.843800,0.551700, +-0.353035,0.027069,-0.353034,0.000000, -0.706100,0.054000,-0.706100, 0.875000,0.517200, +-0.274126,0.080891,-0.410257,0.000000, -0.548300,0.161200,-0.820600, 0.843800,0.551700, +-0.277378,0.027069,-0.415125,0.000000, -0.554700,0.054000,-0.830300, 0.843800,0.517200, +-0.038226,0.497069,-0.038226,0.000000, -0.078800,0.993700,-0.078800, 0.434400,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +-0.030034,0.497069,-0.044948,0.000000, -0.061900,0.993700,-0.092700, 0.436200,0.962300, +-0.038226,-0.497069,-0.038226,0.000000, -0.078800,-0.993700,-0.078800, 0.875000,0.034500, +-0.076004,-0.488310,-0.076003,0.000000, -0.154300,-0.975900,-0.154300, 0.875000,0.069000, +-0.059716,-0.488310,-0.089370,0.000000, -0.121200,-0.975900,-0.181400, 0.843800,0.069000, +-0.038226,-0.497069,-0.038226,0.000000, -0.078800,-0.993700,-0.078800, 0.875000,0.034500, +-0.059716,-0.488310,-0.089370,0.000000, -0.121200,-0.975900,-0.181400, 0.843800,0.069000, +-0.030034,-0.497069,-0.044949,0.000000, -0.061900,-0.993700,-0.092700, 0.843800,0.034500, +-0.353035,-0.027069,-0.353034,0.000000, -0.706100,-0.054000,-0.706100, 0.875000,0.482800, +-0.353035,0.027069,-0.353034,0.000000, -0.706100,0.054000,-0.706100, 0.875000,0.517200, +-0.277378,0.027069,-0.415125,0.000000, -0.554700,0.054000,-0.830300, 0.843800,0.517200, +-0.353035,-0.027069,-0.353034,0.000000, -0.706100,-0.054000,-0.706100, 0.875000,0.482800, +-0.277378,0.027069,-0.415125,0.000000, -0.554700,0.054000,-0.830300, 0.843800,0.517200, +-0.277378,-0.027069,-0.415125,0.000000, -0.554700,-0.054000,-0.830300, 0.843800,0.482800, +-0.076003,0.488310,-0.076003,0.000000, -0.154300,0.975900,-0.154300, 0.875000,0.931000, +-0.038226,0.497069,-0.038226,0.000000, -0.078800,0.993700,-0.078800, 0.875000,0.965500, +-0.030034,0.497069,-0.044948,0.000000, -0.061900,0.993700,-0.092700, 0.843800,0.965500, +-0.076003,0.488310,-0.076003,0.000000, -0.154300,0.975900,-0.154300, 0.875000,0.931000, +-0.030034,0.497069,-0.044948,0.000000, -0.061900,0.993700,-0.092700, 0.843800,0.965500, +-0.059716,0.488310,-0.089370,0.000000, -0.121200,0.975900,-0.181400, 0.843800,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +-0.038226,-0.497069,-0.038226,0.000000, -0.078800,-0.993700,-0.078800, 0.483700,0.053800, +-0.030034,-0.497069,-0.044949,0.000000, -0.061900,-0.993700,-0.092700, 0.481100,0.053800, +-0.348896,-0.080891,-0.348895,0.000000, -0.697800,-0.161200,-0.697800, 0.875000,0.448300, +-0.353035,-0.027069,-0.353034,0.000000, -0.706100,-0.054000,-0.706100, 0.875000,0.482800, +-0.277378,-0.027069,-0.415125,0.000000, -0.554700,-0.054000,-0.830300, 0.843800,0.482800, +-0.348896,-0.080891,-0.348895,0.000000, -0.697800,-0.161200,-0.697800, 0.875000,0.448300, +-0.277378,-0.027069,-0.415125,0.000000, -0.554700,-0.054000,-0.830300, 0.843800,0.482800, +-0.274126,-0.080891,-0.410257,0.000000, -0.548300,-0.161200,-0.820600, 0.843800,0.448300, +-0.112890,0.473826,-0.112890,0.000000, -0.227900,0.946600,-0.227900, 0.875000,0.896600, +-0.076003,0.488310,-0.076003,0.000000, -0.154300,0.975900,-0.154300, 0.875000,0.931000, +-0.059716,0.488310,-0.089370,0.000000, -0.121200,0.975900,-0.181400, 0.843800,0.931000, +-0.112890,0.473826,-0.112890,0.000000, -0.227900,0.946600,-0.227900, 0.875000,0.896600, +-0.059716,0.488310,-0.089370,0.000000, -0.121200,0.975900,-0.181400, 0.843800,0.931000, +-0.088698,0.473826,-0.132745,0.000000, -0.179100,0.946600,-0.268000, 0.843800,0.896600, +-0.340667,-0.133764,-0.340666,0.000000, -0.681500,-0.266600,-0.681500, 0.875000,0.413800, +-0.348896,-0.080891,-0.348895,0.000000, -0.697800,-0.161200,-0.697800, 0.875000,0.448300, +-0.274126,-0.080891,-0.410257,0.000000, -0.548300,-0.161200,-0.820600, 0.843800,0.448300, +-0.340667,-0.133764,-0.340666,0.000000, -0.681500,-0.266600,-0.681500, 0.875000,0.413800, +-0.274126,-0.080891,-0.410257,0.000000, -0.548300,-0.161200,-0.820600, 0.843800,0.448300, +-0.267660,-0.133764,-0.400581,0.000000, -0.535400,-0.266600,-0.801400, 0.843800,0.413800, +-0.148454,0.453788,-0.148453,0.000000, -0.298900,0.906300,-0.298900, 0.875000,0.862100, +-0.112890,0.473826,-0.112890,0.000000, -0.227900,0.946600,-0.227900, 0.875000,0.896600, +-0.088698,0.473826,-0.132745,0.000000, -0.179100,0.946600,-0.268000, 0.843800,0.896600, +-0.148454,0.453788,-0.148453,0.000000, -0.298900,0.906300,-0.298900, 0.875000,0.862100, +-0.088698,0.473826,-0.132745,0.000000, -0.179100,0.946600,-0.268000, 0.843800,0.896600, +-0.116639,0.453788,-0.174562,0.000000, -0.234800,0.906300,-0.351400, 0.843800,0.862100, +-0.328443,-0.185069,-0.328443,0.000000, -0.657200,-0.369000,-0.657200, 0.875000,0.379300, +-0.340667,-0.133764,-0.340666,0.000000, -0.681500,-0.266600,-0.681500, 0.875000,0.413800, +-0.267660,-0.133764,-0.400581,0.000000, -0.535400,-0.266600,-0.801400, 0.843800,0.413800, +-0.328443,-0.185069,-0.328443,0.000000, -0.657200,-0.369000,-0.657200, 0.875000,0.379300, +-0.267660,-0.133764,-0.400581,0.000000, -0.535400,-0.266600,-0.801400, 0.843800,0.413800, +-0.258056,-0.185069,-0.386207,0.000000, -0.516300,-0.369000,-0.772800, 0.843800,0.379300, +-0.182276,0.428429,-0.182276,0.000000, -0.366300,0.855300,-0.366300, 0.875000,0.827600, +-0.148454,0.453788,-0.148453,0.000000, -0.298900,0.906300,-0.298900, 0.875000,0.862100, +-0.116639,0.453788,-0.174562,0.000000, -0.234800,0.906300,-0.351400, 0.843800,0.862100, +-0.182276,0.428429,-0.182276,0.000000, -0.366300,0.855300,-0.366300, 0.875000,0.827600, +-0.116639,0.453788,-0.174562,0.000000, -0.234800,0.906300,-0.351400, 0.843800,0.862100, +-0.143213,0.428429,-0.214334,0.000000, -0.287800,0.855300,-0.430700, 0.843800,0.827600, +-0.312369,-0.234204,-0.312369,0.000000, -0.625200,-0.467000,-0.625200, 0.875000,0.344800, +-0.328443,-0.185069,-0.328443,0.000000, -0.657200,-0.369000,-0.657200, 0.875000,0.379300, +-0.258056,-0.185069,-0.386207,0.000000, -0.516300,-0.369000,-0.772800, 0.843800,0.379300, +-0.312369,-0.234204,-0.312369,0.000000, -0.625200,-0.467000,-0.625200, 0.875000,0.344800, +-0.258056,-0.185069,-0.386207,0.000000, -0.516300,-0.369000,-0.772800, 0.843800,0.379300, +-0.245427,-0.234204,-0.367307,0.000000, -0.491300,-0.467000,-0.735200, 0.843800,0.344800, +-0.213961,0.398046,-0.213961,0.000000, -0.429400,0.794500,-0.429400, 0.875000,0.793100, +-0.182276,0.428429,-0.182276,0.000000, -0.366300,0.855300,-0.366300, 0.875000,0.827600, +-0.143213,0.428429,-0.214334,0.000000, -0.287800,0.855300,-0.430700, 0.843800,0.827600, +-0.213961,0.398046,-0.213961,0.000000, -0.429400,0.794500,-0.429400, 0.875000,0.793100, +-0.143213,0.428429,-0.214334,0.000000, -0.287800,0.855300,-0.430700, 0.843800,0.827600, +-0.168108,0.398046,-0.251592,0.000000, -0.337400,0.794500,-0.504900, 0.843800,0.793100, +-0.292632,-0.280594,-0.292632,0.000000, -0.586000,-0.559600,-0.586000, 0.875000,0.310300, +-0.312369,-0.234204,-0.312369,0.000000, -0.625200,-0.467000,-0.625200, 0.875000,0.344800, +-0.245427,-0.234204,-0.367307,0.000000, -0.491300,-0.467000,-0.735200, 0.843800,0.344800, +-0.292632,-0.280594,-0.292632,0.000000, -0.586000,-0.559600,-0.586000, 0.875000,0.310300, +-0.245427,-0.234204,-0.367307,0.000000, -0.491300,-0.467000,-0.735200, 0.843800,0.344800, +-0.229920,-0.280594,-0.344099,0.000000, -0.460400,-0.559600,-0.689100, 0.843800,0.310300, +-0.243139,0.362998,-0.243138,0.000000, -0.487500,0.724300,-0.487500, 0.875000,0.758600, +-0.213961,0.398046,-0.213961,0.000000, -0.429400,0.794500,-0.429400, 0.875000,0.793100, +-0.168108,0.398046,-0.251592,0.000000, -0.337400,0.794500,-0.504900, 0.843800,0.793100, +-0.243139,0.362998,-0.243138,0.000000, -0.487500,0.724300,-0.487500, 0.875000,0.758600, +-0.168108,0.398046,-0.251592,0.000000, -0.337400,0.794500,-0.504900, 0.843800,0.793100, +-0.191033,0.362998,-0.285900,0.000000, -0.383000,0.724300,-0.573300, 0.843800,0.758600, +-0.269465,-0.323693,-0.269464,0.000000, -0.539900,-0.645700,-0.539900, 0.875000,0.275900, +-0.292632,-0.280594,-0.292632,0.000000, -0.586000,-0.559600,-0.586000, 0.875000,0.310300, +-0.229920,-0.280594,-0.344099,0.000000, -0.460400,-0.559600,-0.689100, 0.843800,0.310300, +-0.269465,-0.323693,-0.269464,0.000000, -0.539900,-0.645700,-0.539900, 0.875000,0.275900, +-0.229920,-0.280594,-0.344099,0.000000, -0.460400,-0.559600,-0.689100, 0.843800,0.310300, +-0.211718,-0.323693,-0.316857,0.000000, -0.424200,-0.645700,-0.634900, 0.843800,0.275900, +-0.269465,0.323693,-0.269464,0.000000, -0.539900,0.645700,-0.539900, 0.875000,0.724100, +-0.243139,0.362998,-0.243138,0.000000, -0.487500,0.724300,-0.487500, 0.875000,0.758600, +-0.191033,0.362998,-0.285900,0.000000, -0.383000,0.724300,-0.573300, 0.843800,0.758600, +-0.269465,0.323693,-0.269464,0.000000, -0.539900,0.645700,-0.539900, 0.875000,0.724100, +-0.191033,0.362998,-0.285900,0.000000, -0.383000,0.724300,-0.573300, 0.843800,0.758600, +-0.211718,0.323693,-0.316857,0.000000, -0.424200,0.645700,-0.634900, 0.843800,0.724100, +-0.243139,-0.362998,-0.243138,0.000000, -0.487500,-0.724300,-0.487500, 0.875000,0.241400, +-0.269465,-0.323693,-0.269464,0.000000, -0.539900,-0.645700,-0.539900, 0.875000,0.275900, +-0.211718,-0.323693,-0.316857,0.000000, -0.424200,-0.645700,-0.634900, 0.843800,0.275900, +-0.243139,-0.362998,-0.243138,0.000000, -0.487500,-0.724300,-0.487500, 0.875000,0.241400, +-0.211718,-0.323693,-0.316857,0.000000, -0.424200,-0.645700,-0.634900, 0.843800,0.275900, +-0.191033,-0.362998,-0.285901,0.000000, -0.383000,-0.724300,-0.573300, 0.843800,0.241400, +-0.292632,0.280594,-0.292632,0.000000, -0.586000,0.559600,-0.586000, 0.875000,0.689700, +-0.269465,0.323693,-0.269464,0.000000, -0.539900,0.645700,-0.539900, 0.875000,0.724100, +-0.211718,0.323693,-0.316857,0.000000, -0.424200,0.645700,-0.634900, 0.843800,0.724100, +-0.292632,0.280594,-0.292632,0.000000, -0.586000,0.559600,-0.586000, 0.875000,0.689700, +-0.211718,0.323693,-0.316857,0.000000, -0.424200,0.645700,-0.634900, 0.843800,0.724100, +-0.229920,0.280594,-0.344099,0.000000, -0.460400,0.559600,-0.689100, 0.843800,0.689700, +-0.213961,-0.398046,-0.213961,0.000000, -0.429400,-0.794500,-0.429400, 0.875000,0.206900, +-0.243139,-0.362998,-0.243138,0.000000, -0.487500,-0.724300,-0.487500, 0.875000,0.241400, +-0.191033,-0.362998,-0.285901,0.000000, -0.383000,-0.724300,-0.573300, 0.843800,0.241400, +-0.213961,-0.398046,-0.213961,0.000000, -0.429400,-0.794500,-0.429400, 0.875000,0.206900, +-0.191033,-0.362998,-0.285901,0.000000, -0.383000,-0.724300,-0.573300, 0.843800,0.241400, +-0.168108,-0.398046,-0.251592,0.000000, -0.337400,-0.794500,-0.505000, 0.843800,0.206900, +-0.312369,0.234204,-0.312369,0.000000, -0.625200,0.467000,-0.625200, 0.875000,0.655200, +-0.292632,0.280594,-0.292632,0.000000, -0.586000,0.559600,-0.586000, 0.875000,0.689700, +-0.229920,0.280594,-0.344099,0.000000, -0.460400,0.559600,-0.689100, 0.843800,0.689700, +-0.312369,0.234204,-0.312369,0.000000, -0.625200,0.467000,-0.625200, 0.875000,0.655200, +-0.229920,0.280594,-0.344099,0.000000, -0.460400,0.559600,-0.689100, 0.843800,0.689700, +-0.245427,0.234204,-0.367307,0.000000, -0.491300,0.467000,-0.735200, 0.843800,0.655200, +-0.182276,-0.428429,-0.182276,0.000000, -0.366300,-0.855300,-0.366300, 0.875000,0.172400, +-0.213961,-0.398046,-0.213961,0.000000, -0.429400,-0.794500,-0.429400, 0.875000,0.206900, +-0.168108,-0.398046,-0.251592,0.000000, -0.337400,-0.794500,-0.505000, 0.843800,0.206900, +-0.182276,-0.428429,-0.182276,0.000000, -0.366300,-0.855300,-0.366300, 0.875000,0.172400, +-0.168108,-0.398046,-0.251592,0.000000, -0.337400,-0.794500,-0.505000, 0.843800,0.206900, +-0.143213,-0.428429,-0.214334,0.000000, -0.287800,-0.855300,-0.430700, 0.843800,0.172400, +-0.245427,-0.234204,-0.367307,0.000000, -0.491300,-0.467000,-0.735200, 0.843800,0.344800, +-0.258056,-0.185069,-0.386207,0.000000, -0.516300,-0.369000,-0.772800, 0.843800,0.379300, +-0.177752,-0.185069,-0.429131,0.000000, -0.355700,-0.369000,-0.858700, 0.812500,0.379300, +-0.245427,-0.234204,-0.367307,0.000000, -0.491300,-0.467000,-0.735200, 0.843800,0.344800, +-0.177752,-0.185069,-0.429131,0.000000, -0.355700,-0.369000,-0.858700, 0.812500,0.379300, +-0.169053,-0.234204,-0.408129,0.000000, -0.338400,-0.467000,-0.816900, 0.812500,0.344800, +-0.168108,0.398046,-0.251592,0.000000, -0.337400,0.794500,-0.504900, 0.843800,0.793100, +-0.143213,0.428429,-0.214334,0.000000, -0.287800,0.855300,-0.430700, 0.843800,0.827600, +-0.098647,0.428429,-0.238155,0.000000, -0.198200,0.855300,-0.478600, 0.812500,0.827600, +-0.168108,0.398046,-0.251592,0.000000, -0.337400,0.794500,-0.504900, 0.843800,0.793100, +-0.098647,0.428429,-0.238155,0.000000, -0.198200,0.855300,-0.478600, 0.812500,0.827600, +-0.115796,0.398046,-0.279554,0.000000, -0.232400,0.794500,-0.561100, 0.812500,0.793100, +-0.229920,-0.280594,-0.344099,0.000000, -0.460400,-0.559600,-0.689100, 0.843800,0.310300, +-0.245427,-0.234204,-0.367307,0.000000, -0.491300,-0.467000,-0.735200, 0.843800,0.344800, +-0.169053,-0.234204,-0.408129,0.000000, -0.338400,-0.467000,-0.816900, 0.812500,0.344800, +-0.229920,-0.280594,-0.344099,0.000000, -0.460400,-0.559600,-0.689100, 0.843800,0.310300, +-0.169053,-0.234204,-0.408129,0.000000, -0.338400,-0.467000,-0.816900, 0.812500,0.344800, +-0.158371,-0.280594,-0.382342,0.000000, -0.317100,-0.559600,-0.765600, 0.812500,0.310300, +-0.191033,0.362998,-0.285900,0.000000, -0.383000,0.724300,-0.573300, 0.843800,0.758600, +-0.168108,0.398046,-0.251592,0.000000, -0.337400,0.794500,-0.504900, 0.843800,0.793100, +-0.115796,0.398046,-0.279554,0.000000, -0.232400,0.794500,-0.561100, 0.812500,0.793100, +-0.191033,0.362998,-0.285900,0.000000, -0.383000,0.724300,-0.573300, 0.843800,0.758600, +-0.115796,0.398046,-0.279554,0.000000, -0.232400,0.794500,-0.561100, 0.812500,0.793100, +-0.131586,0.362998,-0.317676,0.000000, -0.263800,0.724300,-0.637000, 0.812500,0.758600, +-0.211718,-0.323693,-0.316857,0.000000, -0.424200,-0.645700,-0.634900, 0.843800,0.275900, +-0.229920,-0.280594,-0.344099,0.000000, -0.460400,-0.559600,-0.689100, 0.843800,0.310300, +-0.158371,-0.280594,-0.382342,0.000000, -0.317100,-0.559600,-0.765600, 0.812500,0.310300, +-0.211718,-0.323693,-0.316857,0.000000, -0.424200,-0.645700,-0.634900, 0.843800,0.275900, +-0.158371,-0.280594,-0.382342,0.000000, -0.317100,-0.559600,-0.765600, 0.812500,0.310300, +-0.145834,-0.323693,-0.352073,0.000000, -0.292200,-0.645700,-0.705400, 0.812500,0.275900, +-0.211718,0.323693,-0.316857,0.000000, -0.424200,0.645700,-0.634900, 0.843800,0.724100, +-0.191033,0.362998,-0.285900,0.000000, -0.383000,0.724300,-0.573300, 0.843800,0.758600, +-0.131586,0.362998,-0.317676,0.000000, -0.263800,0.724300,-0.637000, 0.812500,0.758600, +-0.211718,0.323693,-0.316857,0.000000, -0.424200,0.645700,-0.634900, 0.843800,0.724100, +-0.131586,0.362998,-0.317676,0.000000, -0.263800,0.724300,-0.637000, 0.812500,0.758600, +-0.145834,0.323693,-0.352073,0.000000, -0.292200,0.645700,-0.705400, 0.812500,0.724100, +-0.191033,-0.362998,-0.285901,0.000000, -0.383000,-0.724300,-0.573300, 0.843800,0.241400, +-0.211718,-0.323693,-0.316857,0.000000, -0.424200,-0.645700,-0.634900, 0.843800,0.275900, +-0.145834,-0.323693,-0.352073,0.000000, -0.292200,-0.645700,-0.705400, 0.812500,0.275900, +-0.191033,-0.362998,-0.285901,0.000000, -0.383000,-0.724300,-0.573300, 0.843800,0.241400, +-0.145834,-0.323693,-0.352073,0.000000, -0.292200,-0.645700,-0.705400, 0.812500,0.275900, +-0.131586,-0.362998,-0.317676,0.000000, -0.263800,-0.724300,-0.637000, 0.812500,0.241400, +-0.229920,0.280594,-0.344099,0.000000, -0.460400,0.559600,-0.689100, 0.843800,0.689700, +-0.211718,0.323693,-0.316857,0.000000, -0.424200,0.645700,-0.634900, 0.843800,0.724100, +-0.145834,0.323693,-0.352073,0.000000, -0.292200,0.645700,-0.705400, 0.812500,0.724100, +-0.229920,0.280594,-0.344099,0.000000, -0.460400,0.559600,-0.689100, 0.843800,0.689700, +-0.145834,0.323693,-0.352073,0.000000, -0.292200,0.645700,-0.705400, 0.812500,0.724100, +-0.158371,0.280594,-0.382342,0.000000, -0.317100,0.559600,-0.765600, 0.812500,0.689700, +-0.168108,-0.398046,-0.251592,0.000000, -0.337400,-0.794500,-0.505000, 0.843800,0.206900, +-0.191033,-0.362998,-0.285901,0.000000, -0.383000,-0.724300,-0.573300, 0.843800,0.241400, +-0.131586,-0.362998,-0.317676,0.000000, -0.263800,-0.724300,-0.637000, 0.812500,0.241400, +-0.168108,-0.398046,-0.251592,0.000000, -0.337400,-0.794500,-0.505000, 0.843800,0.206900, +-0.131586,-0.362998,-0.317676,0.000000, -0.263800,-0.724300,-0.637000, 0.812500,0.241400, +-0.115796,-0.398046,-0.279554,0.000000, -0.232400,-0.794500,-0.561100, 0.812500,0.206900, +-0.245427,0.234204,-0.367307,0.000000, -0.491300,0.467000,-0.735200, 0.843800,0.655200, +-0.229920,0.280594,-0.344099,0.000000, -0.460400,0.559600,-0.689100, 0.843800,0.689700, +-0.158371,0.280594,-0.382342,0.000000, -0.317100,0.559600,-0.765600, 0.812500,0.689700, +-0.245427,0.234204,-0.367307,0.000000, -0.491300,0.467000,-0.735200, 0.843800,0.655200, +-0.158371,0.280594,-0.382342,0.000000, -0.317100,0.559600,-0.765600, 0.812500,0.689700, +-0.169053,0.234204,-0.408129,0.000000, -0.338400,0.467000,-0.816900, 0.812500,0.655200, +-0.143213,-0.428429,-0.214334,0.000000, -0.287800,-0.855300,-0.430700, 0.843800,0.172400, +-0.168108,-0.398046,-0.251592,0.000000, -0.337400,-0.794500,-0.505000, 0.843800,0.206900, +-0.115796,-0.398046,-0.279554,0.000000, -0.232400,-0.794500,-0.561100, 0.812500,0.206900, +-0.143213,-0.428429,-0.214334,0.000000, -0.287800,-0.855300,-0.430700, 0.843800,0.172400, +-0.115796,-0.398046,-0.279554,0.000000, -0.232400,-0.794500,-0.561100, 0.812500,0.206900, +-0.098647,-0.428429,-0.238155,0.000000, -0.198200,-0.855300,-0.478600, 0.812500,0.172400, +-0.258056,0.185069,-0.386207,0.000000, -0.516300,0.369000,-0.772800, 0.843800,0.620700, +-0.245427,0.234204,-0.367307,0.000000, -0.491300,0.467000,-0.735200, 0.843800,0.655200, +-0.169053,0.234204,-0.408129,0.000000, -0.338400,0.467000,-0.816900, 0.812500,0.655200, +-0.258056,0.185069,-0.386207,0.000000, -0.516300,0.369000,-0.772800, 0.843800,0.620700, +-0.169053,0.234204,-0.408129,0.000000, -0.338400,0.467000,-0.816900, 0.812500,0.655200, +-0.177752,0.185069,-0.429131,0.000000, -0.355700,0.369000,-0.858700, 0.812500,0.620700, +-0.116640,-0.453788,-0.174562,0.000000, -0.234800,-0.906300,-0.351400, 0.843800,0.137900, +-0.143213,-0.428429,-0.214334,0.000000, -0.287800,-0.855300,-0.430700, 0.843800,0.172400, +-0.098647,-0.428429,-0.238155,0.000000, -0.198200,-0.855300,-0.478600, 0.812500,0.172400, +-0.116640,-0.453788,-0.174562,0.000000, -0.234800,-0.906300,-0.351400, 0.843800,0.137900, +-0.098647,-0.428429,-0.238155,0.000000, -0.198200,-0.855300,-0.478600, 0.812500,0.172400, +-0.080343,-0.453788,-0.193963,0.000000, -0.161700,-0.906300,-0.390500, 0.812500,0.137900, +-0.267660,0.133764,-0.400581,0.000000, -0.535400,0.266600,-0.801400, 0.843800,0.586200, +-0.258056,0.185069,-0.386207,0.000000, -0.516300,0.369000,-0.772800, 0.843800,0.620700, +-0.177752,0.185069,-0.429131,0.000000, -0.355700,0.369000,-0.858700, 0.812500,0.620700, +-0.267660,0.133764,-0.400581,0.000000, -0.535400,0.266600,-0.801400, 0.843800,0.586200, +-0.177752,0.185069,-0.429131,0.000000, -0.355700,0.369000,-0.858700, 0.812500,0.620700, +-0.184367,0.133764,-0.445101,0.000000, -0.368800,0.266600,-0.890400, 0.812500,0.586200, +-0.088698,-0.473826,-0.132745,0.000000, -0.179100,-0.946600,-0.268000, 0.843800,0.103400, +-0.116640,-0.453788,-0.174562,0.000000, -0.234800,-0.906300,-0.351400, 0.843800,0.137900, +-0.080343,-0.453788,-0.193963,0.000000, -0.161700,-0.906300,-0.390500, 0.812500,0.137900, +-0.088698,-0.473826,-0.132745,0.000000, -0.179100,-0.946600,-0.268000, 0.843800,0.103400, +-0.080343,-0.453788,-0.193963,0.000000, -0.161700,-0.906300,-0.390500, 0.812500,0.137900, +-0.061096,-0.473826,-0.147498,0.000000, -0.123300,-0.946600,-0.297800, 0.812500,0.103400, +-0.274126,0.080891,-0.410257,0.000000, -0.548300,0.161200,-0.820600, 0.843800,0.551700, +-0.267660,0.133764,-0.400581,0.000000, -0.535400,0.266600,-0.801400, 0.843800,0.586200, +-0.184367,0.133764,-0.445101,0.000000, -0.368800,0.266600,-0.890400, 0.812500,0.586200, +-0.274126,0.080891,-0.410257,0.000000, -0.548300,0.161200,-0.820600, 0.843800,0.551700, +-0.184367,0.133764,-0.445101,0.000000, -0.368800,0.266600,-0.890400, 0.812500,0.586200, +-0.188821,0.080891,-0.455854,0.000000, -0.377700,0.161200,-0.911800, 0.812500,0.551700, +-0.059716,-0.488310,-0.089370,0.000000, -0.121200,-0.975900,-0.181400, 0.843800,0.069000, +-0.088698,-0.473826,-0.132745,0.000000, -0.179100,-0.946600,-0.268000, 0.843800,0.103400, +-0.061096,-0.473826,-0.147498,0.000000, -0.123300,-0.946600,-0.297800, 0.812500,0.103400, +-0.059716,-0.488310,-0.089370,0.000000, -0.121200,-0.975900,-0.181400, 0.843800,0.069000, +-0.061096,-0.473826,-0.147498,0.000000, -0.123300,-0.946600,-0.297800, 0.812500,0.103400, +-0.041133,-0.488310,-0.099303,0.000000, -0.083500,-0.975900,-0.201600, 0.812500,0.069000, +-0.277378,0.027069,-0.415125,0.000000, -0.554700,0.054000,-0.830300, 0.843800,0.517200, +-0.274126,0.080891,-0.410257,0.000000, -0.548300,0.161200,-0.820600, 0.843800,0.551700, +-0.188821,0.080891,-0.455854,0.000000, -0.377700,0.161200,-0.911800, 0.812500,0.551700, +-0.277378,0.027069,-0.415125,0.000000, -0.554700,0.054000,-0.830300, 0.843800,0.517200, +-0.188821,0.080891,-0.455854,0.000000, -0.377700,0.161200,-0.911800, 0.812500,0.551700, +-0.191061,0.027069,-0.461262,0.000000, -0.382100,0.054000,-0.922500, 0.812500,0.517200, +-0.030034,0.497069,-0.044948,0.000000, -0.061900,0.993700,-0.092700, 0.436200,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +-0.020688,0.497069,-0.049944,0.000000, -0.042600,0.993700,-0.103000, 0.438100,0.962300, +-0.030034,-0.497069,-0.044949,0.000000, -0.061900,-0.993700,-0.092700, 0.843800,0.034500, +-0.059716,-0.488310,-0.089370,0.000000, -0.121200,-0.975900,-0.181400, 0.843800,0.069000, +-0.041133,-0.488310,-0.099303,0.000000, -0.083500,-0.975900,-0.201600, 0.812500,0.069000, +-0.030034,-0.497069,-0.044949,0.000000, -0.061900,-0.993700,-0.092700, 0.843800,0.034500, +-0.041133,-0.488310,-0.099303,0.000000, -0.083500,-0.975900,-0.201600, 0.812500,0.069000, +-0.020688,-0.497069,-0.049945,0.000000, -0.042600,-0.993700,-0.103000, 0.812500,0.034500, +-0.277378,-0.027069,-0.415125,0.000000, -0.554700,-0.054000,-0.830300, 0.843800,0.482800, +-0.277378,0.027069,-0.415125,0.000000, -0.554700,0.054000,-0.830300, 0.843800,0.517200, +-0.191061,0.027069,-0.461262,0.000000, -0.382100,0.054000,-0.922500, 0.812500,0.517200, +-0.277378,-0.027069,-0.415125,0.000000, -0.554700,-0.054000,-0.830300, 0.843800,0.482800, +-0.191061,0.027069,-0.461262,0.000000, -0.382100,0.054000,-0.922500, 0.812500,0.517200, +-0.191061,-0.027069,-0.461262,0.000000, -0.382100,-0.054000,-0.922500, 0.812500,0.482800, +-0.059716,0.488310,-0.089370,0.000000, -0.121200,0.975900,-0.181400, 0.843800,0.931000, +-0.030034,0.497069,-0.044948,0.000000, -0.061900,0.993700,-0.092700, 0.843800,0.965500, +-0.020688,0.497069,-0.049944,0.000000, -0.042600,0.993700,-0.103000, 0.812500,0.965500, +-0.059716,0.488310,-0.089370,0.000000, -0.121200,0.975900,-0.181400, 0.843800,0.931000, +-0.020688,0.497069,-0.049944,0.000000, -0.042600,0.993700,-0.103000, 0.812500,0.965500, +-0.041133,0.488310,-0.099303,0.000000, -0.083500,0.975900,-0.201600, 0.812500,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +-0.030034,-0.497069,-0.044949,0.000000, -0.061900,-0.993700,-0.092700, 0.481100,0.053800, +-0.020688,-0.497069,-0.049945,0.000000, -0.042600,-0.993700,-0.103000, 0.478500,0.053800, +-0.274126,-0.080891,-0.410257,0.000000, -0.548300,-0.161200,-0.820600, 0.843800,0.448300, +-0.277378,-0.027069,-0.415125,0.000000, -0.554700,-0.054000,-0.830300, 0.843800,0.482800, +-0.191061,-0.027069,-0.461262,0.000000, -0.382100,-0.054000,-0.922500, 0.812500,0.482800, +-0.274126,-0.080891,-0.410257,0.000000, -0.548300,-0.161200,-0.820600, 0.843800,0.448300, +-0.191061,-0.027069,-0.461262,0.000000, -0.382100,-0.054000,-0.922500, 0.812500,0.482800, +-0.188821,-0.080891,-0.455854,0.000000, -0.377700,-0.161200,-0.911800, 0.812500,0.448300, +-0.088698,0.473826,-0.132745,0.000000, -0.179100,0.946600,-0.268000, 0.843800,0.896600, +-0.059716,0.488310,-0.089370,0.000000, -0.121200,0.975900,-0.181400, 0.843800,0.931000, +-0.041133,0.488310,-0.099303,0.000000, -0.083500,0.975900,-0.201600, 0.812500,0.931000, +-0.088698,0.473826,-0.132745,0.000000, -0.179100,0.946600,-0.268000, 0.843800,0.896600, +-0.041133,0.488310,-0.099303,0.000000, -0.083500,0.975900,-0.201600, 0.812500,0.931000, +-0.061096,0.473826,-0.147498,0.000000, -0.123300,0.946600,-0.297800, 0.812500,0.896600, +-0.267660,-0.133764,-0.400581,0.000000, -0.535400,-0.266600,-0.801400, 0.843800,0.413800, +-0.274126,-0.080891,-0.410257,0.000000, -0.548300,-0.161200,-0.820600, 0.843800,0.448300, +-0.188821,-0.080891,-0.455854,0.000000, -0.377700,-0.161200,-0.911800, 0.812500,0.448300, +-0.267660,-0.133764,-0.400581,0.000000, -0.535400,-0.266600,-0.801400, 0.843800,0.413800, +-0.188821,-0.080891,-0.455854,0.000000, -0.377700,-0.161200,-0.911800, 0.812500,0.448300, +-0.184367,-0.133764,-0.445101,0.000000, -0.368800,-0.266600,-0.890400, 0.812500,0.413800, +-0.116639,0.453788,-0.174562,0.000000, -0.234800,0.906300,-0.351400, 0.843800,0.862100, +-0.088698,0.473826,-0.132745,0.000000, -0.179100,0.946600,-0.268000, 0.843800,0.896600, +-0.061096,0.473826,-0.147498,0.000000, -0.123300,0.946600,-0.297800, 0.812500,0.896600, +-0.116639,0.453788,-0.174562,0.000000, -0.234800,0.906300,-0.351400, 0.843800,0.862100, +-0.061096,0.473826,-0.147498,0.000000, -0.123300,0.946600,-0.297800, 0.812500,0.896600, +-0.080343,0.453788,-0.193963,0.000000, -0.161700,0.906300,-0.390500, 0.812500,0.862100, +-0.258056,-0.185069,-0.386207,0.000000, -0.516300,-0.369000,-0.772800, 0.843800,0.379300, +-0.267660,-0.133764,-0.400581,0.000000, -0.535400,-0.266600,-0.801400, 0.843800,0.413800, +-0.184367,-0.133764,-0.445101,0.000000, -0.368800,-0.266600,-0.890400, 0.812500,0.413800, +-0.258056,-0.185069,-0.386207,0.000000, -0.516300,-0.369000,-0.772800, 0.843800,0.379300, +-0.184367,-0.133764,-0.445101,0.000000, -0.368800,-0.266600,-0.890400, 0.812500,0.413800, +-0.177752,-0.185069,-0.429131,0.000000, -0.355700,-0.369000,-0.858700, 0.812500,0.379300, +-0.143213,0.428429,-0.214334,0.000000, -0.287800,0.855300,-0.430700, 0.843800,0.827600, +-0.116639,0.453788,-0.174562,0.000000, -0.234800,0.906300,-0.351400, 0.843800,0.862100, +-0.080343,0.453788,-0.193963,0.000000, -0.161700,0.906300,-0.390500, 0.812500,0.862100, +-0.143213,0.428429,-0.214334,0.000000, -0.287800,0.855300,-0.430700, 0.843800,0.827600, +-0.080343,0.453788,-0.193963,0.000000, -0.161700,0.906300,-0.390500, 0.812500,0.862100, +-0.098647,0.428429,-0.238155,0.000000, -0.198200,0.855300,-0.478600, 0.812500,0.827600, +-0.041133,-0.488310,-0.099303,0.000000, -0.083500,-0.975900,-0.201600, 0.812500,0.069000, +-0.061096,-0.473826,-0.147498,0.000000, -0.123300,-0.946600,-0.297800, 0.812500,0.103400, +-0.031147,-0.473826,-0.156583,0.000000, -0.062900,-0.946600,-0.316100, 0.781300,0.103400, +-0.041133,-0.488310,-0.099303,0.000000, -0.083500,-0.975900,-0.201600, 0.812500,0.069000, +-0.031147,-0.473826,-0.156583,0.000000, -0.062900,-0.946600,-0.316100, 0.781300,0.103400, +-0.020970,-0.488310,-0.105420,0.000000, -0.042500,-0.975900,-0.214000, 0.781300,0.069000, +-0.191061,0.027069,-0.461262,0.000000, -0.382100,0.054000,-0.922500, 0.812500,0.517200, +-0.188821,0.080891,-0.455854,0.000000, -0.377700,0.161200,-0.911800, 0.812500,0.551700, +-0.096261,0.080891,-0.483932,0.000000, -0.192500,0.161200,-0.967900, 0.781300,0.551700, +-0.191061,0.027069,-0.461262,0.000000, -0.382100,0.054000,-0.922500, 0.812500,0.517200, +-0.096261,0.080891,-0.483932,0.000000, -0.192500,0.161200,-0.967900, 0.781300,0.551700, +-0.097402,0.027069,-0.489673,0.000000, -0.194800,0.054000,-0.979300, 0.781300,0.517200, +-0.020688,0.497069,-0.049944,0.000000, -0.042600,0.993700,-0.103000, 0.438100,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +-0.010547,0.497069,-0.053020,0.000000, -0.021700,0.993700,-0.109300, 0.439900,0.962300, +-0.020688,-0.497069,-0.049945,0.000000, -0.042600,-0.993700,-0.103000, 0.812500,0.034500, +-0.041133,-0.488310,-0.099303,0.000000, -0.083500,-0.975900,-0.201600, 0.812500,0.069000, +-0.020970,-0.488310,-0.105420,0.000000, -0.042500,-0.975900,-0.214000, 0.781300,0.069000, +-0.020688,-0.497069,-0.049945,0.000000, -0.042600,-0.993700,-0.103000, 0.812500,0.034500, +-0.020970,-0.488310,-0.105420,0.000000, -0.042500,-0.975900,-0.214000, 0.781300,0.069000, +-0.010547,-0.497069,-0.053020,0.000000, -0.021700,-0.993700,-0.109300, 0.781300,0.034500, +-0.191061,-0.027069,-0.461262,0.000000, -0.382100,-0.054000,-0.922500, 0.812500,0.482800, +-0.191061,0.027069,-0.461262,0.000000, -0.382100,0.054000,-0.922500, 0.812500,0.517200, +-0.097402,0.027069,-0.489673,0.000000, -0.194800,0.054000,-0.979300, 0.781300,0.517200, +-0.191061,-0.027069,-0.461262,0.000000, -0.382100,-0.054000,-0.922500, 0.812500,0.482800, +-0.097402,0.027069,-0.489673,0.000000, -0.194800,0.054000,-0.979300, 0.781300,0.517200, +-0.097402,-0.027069,-0.489673,0.000000, -0.194800,-0.054000,-0.979300, 0.781300,0.482800, +-0.041133,0.488310,-0.099303,0.000000, -0.083500,0.975900,-0.201600, 0.812500,0.931000, +-0.020688,0.497069,-0.049944,0.000000, -0.042600,0.993700,-0.103000, 0.812500,0.965500, +-0.010547,0.497069,-0.053020,0.000000, -0.021700,0.993700,-0.109300, 0.781300,0.965500, +-0.041133,0.488310,-0.099303,0.000000, -0.083500,0.975900,-0.201600, 0.812500,0.931000, +-0.010547,0.497069,-0.053020,0.000000, -0.021700,0.993700,-0.109300, 0.781300,0.965500, +-0.020970,0.488310,-0.105420,0.000000, -0.042500,0.975900,-0.214000, 0.781300,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +-0.020688,-0.497069,-0.049945,0.000000, -0.042600,-0.993700,-0.103000, 0.478500,0.053800, +-0.010547,-0.497069,-0.053020,0.000000, -0.021700,-0.993700,-0.109300, 0.475900,0.053800, +-0.188821,-0.080891,-0.455854,0.000000, -0.377700,-0.161200,-0.911800, 0.812500,0.448300, +-0.191061,-0.027069,-0.461262,0.000000, -0.382100,-0.054000,-0.922500, 0.812500,0.482800, +-0.097402,-0.027069,-0.489673,0.000000, -0.194800,-0.054000,-0.979300, 0.781300,0.482800, +-0.188821,-0.080891,-0.455854,0.000000, -0.377700,-0.161200,-0.911800, 0.812500,0.448300, +-0.097402,-0.027069,-0.489673,0.000000, -0.194800,-0.054000,-0.979300, 0.781300,0.482800, +-0.096261,-0.080891,-0.483932,0.000000, -0.192500,-0.161200,-0.967900, 0.781300,0.448300, +-0.061096,0.473826,-0.147498,0.000000, -0.123300,0.946600,-0.297800, 0.812500,0.896600, +-0.041133,0.488310,-0.099303,0.000000, -0.083500,0.975900,-0.201600, 0.812500,0.931000, +-0.020970,0.488310,-0.105420,0.000000, -0.042500,0.975900,-0.214000, 0.781300,0.931000, +-0.061096,0.473826,-0.147498,0.000000, -0.123300,0.946600,-0.297800, 0.812500,0.896600, +-0.020970,0.488310,-0.105420,0.000000, -0.042500,0.975900,-0.214000, 0.781300,0.931000, +-0.031147,0.473826,-0.156583,0.000000, -0.062900,0.946600,-0.316100, 0.781300,0.896600, +-0.184367,-0.133764,-0.445101,0.000000, -0.368800,-0.266600,-0.890400, 0.812500,0.413800, +-0.188821,-0.080891,-0.455854,0.000000, -0.377700,-0.161200,-0.911800, 0.812500,0.448300, +-0.096261,-0.080891,-0.483932,0.000000, -0.192500,-0.161200,-0.967900, 0.781300,0.448300, +-0.184367,-0.133764,-0.445101,0.000000, -0.368800,-0.266600,-0.890400, 0.812500,0.413800, +-0.096261,-0.080891,-0.483932,0.000000, -0.192500,-0.161200,-0.967900, 0.781300,0.448300, +-0.093990,-0.133764,-0.472517,0.000000, -0.188000,-0.266600,-0.945200, 0.781300,0.413800, +-0.080343,0.453788,-0.193963,0.000000, -0.161700,0.906300,-0.390500, 0.812500,0.862100, +-0.061096,0.473826,-0.147498,0.000000, -0.123300,0.946600,-0.297800, 0.812500,0.896600, +-0.031147,0.473826,-0.156583,0.000000, -0.062900,0.946600,-0.316100, 0.781300,0.896600, +-0.080343,0.453788,-0.193963,0.000000, -0.161700,0.906300,-0.390500, 0.812500,0.862100, +-0.031147,0.473826,-0.156583,0.000000, -0.062900,0.946600,-0.316100, 0.781300,0.896600, +-0.040959,0.453788,-0.205910,0.000000, -0.082400,0.906300,-0.414500, 0.781300,0.862100, +-0.177752,-0.185069,-0.429131,0.000000, -0.355700,-0.369000,-0.858700, 0.812500,0.379300, +-0.184367,-0.133764,-0.445101,0.000000, -0.368800,-0.266600,-0.890400, 0.812500,0.413800, +-0.093990,-0.133764,-0.472517,0.000000, -0.188000,-0.266600,-0.945200, 0.781300,0.413800, +-0.177752,-0.185069,-0.429131,0.000000, -0.355700,-0.369000,-0.858700, 0.812500,0.379300, +-0.093990,-0.133764,-0.472517,0.000000, -0.188000,-0.266600,-0.945200, 0.781300,0.413800, +-0.090618,-0.185069,-0.455563,0.000000, -0.181300,-0.369000,-0.911600, 0.781300,0.379300, +-0.098647,0.428429,-0.238155,0.000000, -0.198200,0.855300,-0.478600, 0.812500,0.827600, +-0.080343,0.453788,-0.193963,0.000000, -0.161700,0.906300,-0.390500, 0.812500,0.862100, +-0.040959,0.453788,-0.205910,0.000000, -0.082400,0.906300,-0.414500, 0.781300,0.862100, +-0.098647,0.428429,-0.238155,0.000000, -0.198200,0.855300,-0.478600, 0.812500,0.827600, +-0.040959,0.453788,-0.205910,0.000000, -0.082400,0.906300,-0.414500, 0.781300,0.862100, +-0.050290,0.428429,-0.252824,0.000000, -0.101000,0.855300,-0.508100, 0.781300,0.827600, +-0.169053,-0.234204,-0.408129,0.000000, -0.338400,-0.467000,-0.816900, 0.812500,0.344800, +-0.177752,-0.185069,-0.429131,0.000000, -0.355700,-0.369000,-0.858700, 0.812500,0.379300, +-0.090618,-0.185069,-0.455563,0.000000, -0.181300,-0.369000,-0.911600, 0.781300,0.379300, +-0.169053,-0.234204,-0.408129,0.000000, -0.338400,-0.467000,-0.816900, 0.812500,0.344800, +-0.090618,-0.185069,-0.455563,0.000000, -0.181300,-0.369000,-0.911600, 0.781300,0.379300, +-0.086182,-0.234204,-0.433268,0.000000, -0.172500,-0.467000,-0.867200, 0.781300,0.344800, +-0.115796,0.398046,-0.279554,0.000000, -0.232400,0.794500,-0.561100, 0.812500,0.793100, +-0.098647,0.428429,-0.238155,0.000000, -0.198200,0.855300,-0.478600, 0.812500,0.827600, +-0.050290,0.428429,-0.252824,0.000000, -0.101000,0.855300,-0.508100, 0.781300,0.827600, +-0.115796,0.398046,-0.279554,0.000000, -0.232400,0.794500,-0.561100, 0.812500,0.793100, +-0.050290,0.428429,-0.252824,0.000000, -0.101000,0.855300,-0.508100, 0.781300,0.827600, +-0.059032,0.398046,-0.296773,0.000000, -0.118500,0.794500,-0.595600, 0.781300,0.793100, +-0.158371,-0.280594,-0.382342,0.000000, -0.317100,-0.559600,-0.765600, 0.812500,0.310300, +-0.169053,-0.234204,-0.408129,0.000000, -0.338400,-0.467000,-0.816900, 0.812500,0.344800, +-0.086182,-0.234204,-0.433268,0.000000, -0.172500,-0.467000,-0.867200, 0.781300,0.344800, +-0.158371,-0.280594,-0.382342,0.000000, -0.317100,-0.559600,-0.765600, 0.812500,0.310300, +-0.086182,-0.234204,-0.433268,0.000000, -0.172500,-0.467000,-0.867200, 0.781300,0.344800, +-0.080738,-0.280594,-0.405892,0.000000, -0.161700,-0.559600,-0.812800, 0.781300,0.310300, +-0.131586,0.362998,-0.317676,0.000000, -0.263800,0.724300,-0.637000, 0.812500,0.758600, +-0.115796,0.398046,-0.279554,0.000000, -0.232400,0.794500,-0.561100, 0.812500,0.793100, +-0.059032,0.398046,-0.296773,0.000000, -0.118500,0.794500,-0.595600, 0.781300,0.793100, +-0.131586,0.362998,-0.317676,0.000000, -0.263800,0.724300,-0.637000, 0.812500,0.758600, +-0.059032,0.398046,-0.296773,0.000000, -0.118500,0.794500,-0.595600, 0.781300,0.793100, +-0.067082,0.362998,-0.337242,0.000000, -0.134500,0.724300,-0.676200, 0.781300,0.758600, +-0.145834,-0.323693,-0.352073,0.000000, -0.292200,-0.645700,-0.705400, 0.812500,0.275900, +-0.158371,-0.280594,-0.382342,0.000000, -0.317100,-0.559600,-0.765600, 0.812500,0.310300, +-0.080738,-0.280594,-0.405892,0.000000, -0.161700,-0.559600,-0.812800, 0.781300,0.310300, +-0.145834,-0.323693,-0.352073,0.000000, -0.292200,-0.645700,-0.705400, 0.812500,0.275900, +-0.080738,-0.280594,-0.405892,0.000000, -0.161700,-0.559600,-0.812800, 0.781300,0.310300, +-0.074345,-0.323693,-0.373758,0.000000, -0.149000,-0.645700,-0.748900, 0.781300,0.275900, +-0.145834,0.323693,-0.352073,0.000000, -0.292200,0.645700,-0.705400, 0.812500,0.724100, +-0.131586,0.362998,-0.317676,0.000000, -0.263800,0.724300,-0.637000, 0.812500,0.758600, +-0.067082,0.362998,-0.337242,0.000000, -0.134500,0.724300,-0.676200, 0.781300,0.758600, +-0.145834,0.323693,-0.352073,0.000000, -0.292200,0.645700,-0.705400, 0.812500,0.724100, +-0.067082,0.362998,-0.337242,0.000000, -0.134500,0.724300,-0.676200, 0.781300,0.758600, +-0.074345,0.323693,-0.373758,0.000000, -0.149000,0.645700,-0.748900, 0.781300,0.724100, +-0.131586,-0.362998,-0.317676,0.000000, -0.263800,-0.724300,-0.637000, 0.812500,0.241400, +-0.145834,-0.323693,-0.352073,0.000000, -0.292200,-0.645700,-0.705400, 0.812500,0.275900, +-0.074345,-0.323693,-0.373758,0.000000, -0.149000,-0.645700,-0.748900, 0.781300,0.275900, +-0.131586,-0.362998,-0.317676,0.000000, -0.263800,-0.724300,-0.637000, 0.812500,0.241400, +-0.074345,-0.323693,-0.373758,0.000000, -0.149000,-0.645700,-0.748900, 0.781300,0.275900, +-0.067082,-0.362998,-0.337243,0.000000, -0.134500,-0.724300,-0.676200, 0.781300,0.241400, +-0.158371,0.280594,-0.382342,0.000000, -0.317100,0.559600,-0.765600, 0.812500,0.689700, +-0.145834,0.323693,-0.352073,0.000000, -0.292200,0.645700,-0.705400, 0.812500,0.724100, +-0.074345,0.323693,-0.373758,0.000000, -0.149000,0.645700,-0.748900, 0.781300,0.724100, +-0.158371,0.280594,-0.382342,0.000000, -0.317100,0.559600,-0.765600, 0.812500,0.689700, +-0.074345,0.323693,-0.373758,0.000000, -0.149000,0.645700,-0.748900, 0.781300,0.724100, +-0.080738,0.280594,-0.405892,0.000000, -0.161700,0.559600,-0.812800, 0.781300,0.689700, +-0.115796,-0.398046,-0.279554,0.000000, -0.232400,-0.794500,-0.561100, 0.812500,0.206900, +-0.131586,-0.362998,-0.317676,0.000000, -0.263800,-0.724300,-0.637000, 0.812500,0.241400, +-0.067082,-0.362998,-0.337243,0.000000, -0.134500,-0.724300,-0.676200, 0.781300,0.241400, +-0.115796,-0.398046,-0.279554,0.000000, -0.232400,-0.794500,-0.561100, 0.812500,0.206900, +-0.067082,-0.362998,-0.337243,0.000000, -0.134500,-0.724300,-0.676200, 0.781300,0.241400, +-0.059032,-0.398046,-0.296773,0.000000, -0.118500,-0.794500,-0.595600, 0.781300,0.206900, +-0.169053,0.234204,-0.408129,0.000000, -0.338400,0.467000,-0.816900, 0.812500,0.655200, +-0.158371,0.280594,-0.382342,0.000000, -0.317100,0.559600,-0.765600, 0.812500,0.689700, +-0.080738,0.280594,-0.405892,0.000000, -0.161700,0.559600,-0.812800, 0.781300,0.689700, +-0.169053,0.234204,-0.408129,0.000000, -0.338400,0.467000,-0.816900, 0.812500,0.655200, +-0.080738,0.280594,-0.405892,0.000000, -0.161700,0.559600,-0.812800, 0.781300,0.689700, +-0.086182,0.234204,-0.433268,0.000000, -0.172500,0.467000,-0.867200, 0.781300,0.655200, +-0.098647,-0.428429,-0.238155,0.000000, -0.198200,-0.855300,-0.478600, 0.812500,0.172400, +-0.115796,-0.398046,-0.279554,0.000000, -0.232400,-0.794500,-0.561100, 0.812500,0.206900, +-0.059032,-0.398046,-0.296773,0.000000, -0.118500,-0.794500,-0.595600, 0.781300,0.206900, +-0.098647,-0.428429,-0.238155,0.000000, -0.198200,-0.855300,-0.478600, 0.812500,0.172400, +-0.059032,-0.398046,-0.296773,0.000000, -0.118500,-0.794500,-0.595600, 0.781300,0.206900, +-0.050290,-0.428429,-0.252824,0.000000, -0.101000,-0.855300,-0.508100, 0.781300,0.172400, +-0.177752,0.185069,-0.429131,0.000000, -0.355700,0.369000,-0.858700, 0.812500,0.620700, +-0.169053,0.234204,-0.408129,0.000000, -0.338400,0.467000,-0.816900, 0.812500,0.655200, +-0.086182,0.234204,-0.433268,0.000000, -0.172500,0.467000,-0.867200, 0.781300,0.655200, +-0.177752,0.185069,-0.429131,0.000000, -0.355700,0.369000,-0.858700, 0.812500,0.620700, +-0.086182,0.234204,-0.433268,0.000000, -0.172500,0.467000,-0.867200, 0.781300,0.655200, +-0.090618,0.185069,-0.455563,0.000000, -0.181300,0.369000,-0.911600, 0.781300,0.620700, +-0.080343,-0.453788,-0.193963,0.000000, -0.161700,-0.906300,-0.390500, 0.812500,0.137900, +-0.098647,-0.428429,-0.238155,0.000000, -0.198200,-0.855300,-0.478600, 0.812500,0.172400, +-0.050290,-0.428429,-0.252824,0.000000, -0.101000,-0.855300,-0.508100, 0.781300,0.172400, +-0.080343,-0.453788,-0.193963,0.000000, -0.161700,-0.906300,-0.390500, 0.812500,0.137900, +-0.050290,-0.428429,-0.252824,0.000000, -0.101000,-0.855300,-0.508100, 0.781300,0.172400, +-0.040959,-0.453788,-0.205911,0.000000, -0.082400,-0.906300,-0.414500, 0.781300,0.137900, +-0.184367,0.133764,-0.445101,0.000000, -0.368800,0.266600,-0.890400, 0.812500,0.586200, +-0.177752,0.185069,-0.429131,0.000000, -0.355700,0.369000,-0.858700, 0.812500,0.620700, +-0.090618,0.185069,-0.455563,0.000000, -0.181300,0.369000,-0.911600, 0.781300,0.620700, +-0.184367,0.133764,-0.445101,0.000000, -0.368800,0.266600,-0.890400, 0.812500,0.586200, +-0.090618,0.185069,-0.455563,0.000000, -0.181300,0.369000,-0.911600, 0.781300,0.620700, +-0.093990,0.133764,-0.472517,0.000000, -0.188000,0.266600,-0.945200, 0.781300,0.586200, +-0.061096,-0.473826,-0.147498,0.000000, -0.123300,-0.946600,-0.297800, 0.812500,0.103400, +-0.080343,-0.453788,-0.193963,0.000000, -0.161700,-0.906300,-0.390500, 0.812500,0.137900, +-0.040959,-0.453788,-0.205911,0.000000, -0.082400,-0.906300,-0.414500, 0.781300,0.137900, +-0.061096,-0.473826,-0.147498,0.000000, -0.123300,-0.946600,-0.297800, 0.812500,0.103400, +-0.040959,-0.453788,-0.205911,0.000000, -0.082400,-0.906300,-0.414500, 0.781300,0.137900, +-0.031147,-0.473826,-0.156583,0.000000, -0.062900,-0.946600,-0.316100, 0.781300,0.103400, +-0.188821,0.080891,-0.455854,0.000000, -0.377700,0.161200,-0.911800, 0.812500,0.551700, +-0.184367,0.133764,-0.445101,0.000000, -0.368800,0.266600,-0.890400, 0.812500,0.586200, +-0.093990,0.133764,-0.472517,0.000000, -0.188000,0.266600,-0.945200, 0.781300,0.586200, +-0.188821,0.080891,-0.455854,0.000000, -0.377700,0.161200,-0.911800, 0.812500,0.551700, +-0.093990,0.133764,-0.472517,0.000000, -0.188000,0.266600,-0.945200, 0.781300,0.586200, +-0.096261,0.080891,-0.483932,0.000000, -0.192500,0.161200,-0.967900, 0.781300,0.551700, +-0.067082,-0.362998,-0.337243,0.000000, -0.134500,-0.724300,-0.676200, 0.781300,0.241400, +-0.074345,-0.323693,-0.373758,0.000000, -0.149000,-0.645700,-0.748900, 0.781300,0.275900, +-0.000000,-0.323693,-0.381081,0.000000, 0.000000,-0.645700,-0.763500, 0.750000,0.275900, +-0.067082,-0.362998,-0.337243,0.000000, -0.134500,-0.724300,-0.676200, 0.781300,0.241400, +-0.000000,-0.323693,-0.381081,0.000000, 0.000000,-0.645700,-0.763500, 0.750000,0.275900, +-0.000000,-0.362998,-0.343850,0.000000, 0.000000,-0.724300,-0.689400, 0.750000,0.241400, +-0.080738,0.280594,-0.405892,0.000000, -0.161700,0.559600,-0.812800, 0.781300,0.689700, +-0.074345,0.323693,-0.373758,0.000000, -0.149000,0.645700,-0.748900, 0.781300,0.724100, +-0.000000,0.323693,-0.381081,0.000000, 0.000000,0.645700,-0.763500, 0.750000,0.724100, +-0.080738,0.280594,-0.405892,0.000000, -0.161700,0.559600,-0.812800, 0.781300,0.689700, +-0.000000,0.323693,-0.381081,0.000000, 0.000000,0.645700,-0.763500, 0.750000,0.724100, +-0.000000,0.280594,-0.413844,0.000000, 0.000000,0.559600,-0.828700, 0.750000,0.689700, +-0.059032,-0.398046,-0.296773,0.000000, -0.118500,-0.794500,-0.595600, 0.781300,0.206900, +-0.067082,-0.362998,-0.337243,0.000000, -0.134500,-0.724300,-0.676200, 0.781300,0.241400, +-0.000000,-0.362998,-0.343850,0.000000, 0.000000,-0.724300,-0.689400, 0.750000,0.241400, +-0.059032,-0.398046,-0.296773,0.000000, -0.118500,-0.794500,-0.595600, 0.781300,0.206900, +-0.000000,-0.362998,-0.343850,0.000000, 0.000000,-0.724300,-0.689400, 0.750000,0.241400, +-0.000000,-0.398046,-0.302587,0.000000, 0.000000,-0.794500,-0.607300, 0.750000,0.206900, +-0.086182,0.234204,-0.433268,0.000000, -0.172500,0.467000,-0.867200, 0.781300,0.655200, +-0.080738,0.280594,-0.405892,0.000000, -0.161700,0.559600,-0.812800, 0.781300,0.689700, +-0.000000,0.280594,-0.413844,0.000000, 0.000000,0.559600,-0.828700, 0.750000,0.689700, +-0.086182,0.234204,-0.433268,0.000000, -0.172500,0.467000,-0.867200, 0.781300,0.655200, +-0.000000,0.280594,-0.413844,0.000000, 0.000000,0.559600,-0.828700, 0.750000,0.689700, +-0.000000,0.234204,-0.441756,0.000000, 0.000000,0.467000,-0.884200, 0.750000,0.655200, +-0.050290,-0.428429,-0.252824,0.000000, -0.101000,-0.855300,-0.508100, 0.781300,0.172400, +-0.059032,-0.398046,-0.296773,0.000000, -0.118500,-0.794500,-0.595600, 0.781300,0.206900, +-0.000000,-0.398046,-0.302587,0.000000, 0.000000,-0.794500,-0.607300, 0.750000,0.206900, +-0.050290,-0.428429,-0.252824,0.000000, -0.101000,-0.855300,-0.508100, 0.781300,0.172400, +-0.000000,-0.398046,-0.302587,0.000000, 0.000000,-0.794500,-0.607300, 0.750000,0.206900, +-0.000000,-0.428429,-0.257776,0.000000, 0.000000,-0.855300,-0.518000, 0.750000,0.172400, +-0.090618,0.185069,-0.455563,0.000000, -0.181300,0.369000,-0.911600, 0.781300,0.620700, +-0.086182,0.234204,-0.433268,0.000000, -0.172500,0.467000,-0.867200, 0.781300,0.655200, +-0.000000,0.234204,-0.441756,0.000000, 0.000000,0.467000,-0.884200, 0.750000,0.655200, +-0.090618,0.185069,-0.455563,0.000000, -0.181300,0.369000,-0.911600, 0.781300,0.620700, +-0.000000,0.234204,-0.441756,0.000000, 0.000000,0.467000,-0.884200, 0.750000,0.655200, +-0.000000,0.185069,-0.464488,0.000000, 0.000000,0.369000,-0.929400, 0.750000,0.620700, +-0.040959,-0.453788,-0.205911,0.000000, -0.082400,-0.906300,-0.414500, 0.781300,0.137900, +-0.050290,-0.428429,-0.252824,0.000000, -0.101000,-0.855300,-0.508100, 0.781300,0.172400, +-0.000000,-0.428429,-0.257776,0.000000, 0.000000,-0.855300,-0.518000, 0.750000,0.172400, +-0.040959,-0.453788,-0.205911,0.000000, -0.082400,-0.906300,-0.414500, 0.781300,0.137900, +-0.000000,-0.428429,-0.257776,0.000000, 0.000000,-0.855300,-0.518000, 0.750000,0.172400, +-0.000000,-0.453788,-0.209945,0.000000, 0.000000,-0.906300,-0.422700, 0.750000,0.137900, +-0.093990,0.133764,-0.472517,0.000000, -0.188000,0.266600,-0.945200, 0.781300,0.586200, +-0.090618,0.185069,-0.455563,0.000000, -0.181300,0.369000,-0.911600, 0.781300,0.620700, +-0.000000,0.185069,-0.464488,0.000000, 0.000000,0.369000,-0.929400, 0.750000,0.620700, +-0.093990,0.133764,-0.472517,0.000000, -0.188000,0.266600,-0.945200, 0.781300,0.586200, +-0.000000,0.185069,-0.464488,0.000000, 0.000000,0.369000,-0.929400, 0.750000,0.620700, +-0.000000,0.133764,-0.481775,0.000000, 0.000000,0.266600,-0.963800, 0.750000,0.586200, +-0.031147,-0.473826,-0.156583,0.000000, -0.062900,-0.946600,-0.316100, 0.781300,0.103400, +-0.040959,-0.453788,-0.205911,0.000000, -0.082400,-0.906300,-0.414500, 0.781300,0.137900, +-0.000000,-0.453788,-0.209945,0.000000, 0.000000,-0.906300,-0.422700, 0.750000,0.137900, +-0.031147,-0.473826,-0.156583,0.000000, -0.062900,-0.946600,-0.316100, 0.781300,0.103400, +-0.000000,-0.453788,-0.209945,0.000000, 0.000000,-0.906300,-0.422700, 0.750000,0.137900, +-0.000000,-0.473826,-0.159651,0.000000, 0.000000,-0.946600,-0.322300, 0.750000,0.103400, +-0.096261,0.080891,-0.483932,0.000000, -0.192500,0.161200,-0.967900, 0.781300,0.551700, +-0.093990,0.133764,-0.472517,0.000000, -0.188000,0.266600,-0.945200, 0.781300,0.586200, +-0.000000,0.133764,-0.481775,0.000000, 0.000000,0.266600,-0.963800, 0.750000,0.586200, +-0.096261,0.080891,-0.483932,0.000000, -0.192500,0.161200,-0.967900, 0.781300,0.551700, +-0.000000,0.133764,-0.481775,0.000000, 0.000000,0.266600,-0.963800, 0.750000,0.586200, +-0.000000,0.080891,-0.493412,0.000000, 0.000000,0.161200,-0.986900, 0.750000,0.551700, +-0.020970,-0.488310,-0.105420,0.000000, -0.042500,-0.975900,-0.214000, 0.781300,0.069000, +-0.031147,-0.473826,-0.156583,0.000000, -0.062900,-0.946600,-0.316100, 0.781300,0.103400, +-0.000000,-0.473826,-0.159651,0.000000, 0.000000,-0.946600,-0.322300, 0.750000,0.103400, +-0.020970,-0.488310,-0.105420,0.000000, -0.042500,-0.975900,-0.214000, 0.781300,0.069000, +-0.000000,-0.473826,-0.159651,0.000000, 0.000000,-0.946600,-0.322300, 0.750000,0.103400, +-0.000000,-0.488310,-0.107485,0.000000, 0.000000,-0.975900,-0.218200, 0.750000,0.069000, +-0.097402,0.027069,-0.489673,0.000000, -0.194800,0.054000,-0.979300, 0.781300,0.517200, +-0.096261,0.080891,-0.483932,0.000000, -0.192500,0.161200,-0.967900, 0.781300,0.551700, +-0.000000,0.080891,-0.493412,0.000000, 0.000000,0.161200,-0.986900, 0.750000,0.551700, +-0.097402,0.027069,-0.489673,0.000000, -0.194800,0.054000,-0.979300, 0.781300,0.517200, +-0.000000,0.080891,-0.493412,0.000000, 0.000000,0.161200,-0.986900, 0.750000,0.551700, +-0.000000,0.027069,-0.499266,0.000000, 0.000000,0.054000,-0.998500, 0.750000,0.517200, +-0.010547,0.497069,-0.053020,0.000000, -0.021700,0.993700,-0.109300, 0.439900,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +-0.000000,0.497069,-0.054059,0.000000, 0.000000,0.993700,-0.111500, 0.441700,0.962300, +-0.010547,-0.497069,-0.053020,0.000000, -0.021700,-0.993700,-0.109300, 0.781300,0.034500, +-0.020970,-0.488310,-0.105420,0.000000, -0.042500,-0.975900,-0.214000, 0.781300,0.069000, +-0.000000,-0.488310,-0.107485,0.000000, 0.000000,-0.975900,-0.218200, 0.750000,0.069000, +-0.010547,-0.497069,-0.053020,0.000000, -0.021700,-0.993700,-0.109300, 0.781300,0.034500, +-0.000000,-0.488310,-0.107485,0.000000, 0.000000,-0.975900,-0.218200, 0.750000,0.069000, +-0.000000,-0.497069,-0.054060,0.000000, 0.000000,-0.993700,-0.111500, 0.750000,0.034500, +-0.097402,-0.027069,-0.489673,0.000000, -0.194800,-0.054000,-0.979300, 0.781300,0.482800, +-0.097402,0.027069,-0.489673,0.000000, -0.194800,0.054000,-0.979300, 0.781300,0.517200, +-0.000000,0.027069,-0.499266,0.000000, 0.000000,0.054000,-0.998500, 0.750000,0.517200, +-0.097402,-0.027069,-0.489673,0.000000, -0.194800,-0.054000,-0.979300, 0.781300,0.482800, +-0.000000,0.027069,-0.499266,0.000000, 0.000000,0.054000,-0.998500, 0.750000,0.517200, +-0.000000,-0.027069,-0.499266,0.000000, 0.000000,-0.054000,-0.998500, 0.750000,0.482800, +-0.020970,0.488310,-0.105420,0.000000, -0.042500,0.975900,-0.214000, 0.781300,0.931000, +-0.010547,0.497069,-0.053020,0.000000, -0.021700,0.993700,-0.109300, 0.781300,0.965500, +-0.000000,0.497069,-0.054059,0.000000, 0.000000,0.993700,-0.111500, 0.750000,0.965500, +-0.020970,0.488310,-0.105420,0.000000, -0.042500,0.975900,-0.214000, 0.781300,0.931000, +-0.000000,0.497069,-0.054059,0.000000, 0.000000,0.993700,-0.111500, 0.750000,0.965500, +-0.000000,0.488310,-0.107485,0.000000, 0.000000,0.975900,-0.218200, 0.750000,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +-0.010547,-0.497069,-0.053020,0.000000, -0.021700,-0.993700,-0.109300, 0.475900,0.053800, +-0.000000,-0.497069,-0.054060,0.000000, 0.000000,-0.993700,-0.111500, 0.473300,0.053800, +-0.096261,-0.080891,-0.483932,0.000000, -0.192500,-0.161200,-0.967900, 0.781300,0.448300, +-0.097402,-0.027069,-0.489673,0.000000, -0.194800,-0.054000,-0.979300, 0.781300,0.482800, +-0.000000,-0.027069,-0.499266,0.000000, 0.000000,-0.054000,-0.998500, 0.750000,0.482800, +-0.096261,-0.080891,-0.483932,0.000000, -0.192500,-0.161200,-0.967900, 0.781300,0.448300, +-0.000000,-0.027069,-0.499266,0.000000, 0.000000,-0.054000,-0.998500, 0.750000,0.482800, +-0.000000,-0.080891,-0.493412,0.000000, 0.000000,-0.161200,-0.986900, 0.750000,0.448300, +-0.031147,0.473826,-0.156583,0.000000, -0.062900,0.946600,-0.316100, 0.781300,0.896600, +-0.020970,0.488310,-0.105420,0.000000, -0.042500,0.975900,-0.214000, 0.781300,0.931000, +-0.000000,0.488310,-0.107485,0.000000, 0.000000,0.975900,-0.218200, 0.750000,0.931000, +-0.031147,0.473826,-0.156583,0.000000, -0.062900,0.946600,-0.316100, 0.781300,0.896600, +-0.000000,0.488310,-0.107485,0.000000, 0.000000,0.975900,-0.218200, 0.750000,0.931000, +-0.000000,0.473826,-0.159651,0.000000, 0.000000,0.946600,-0.322300, 0.750000,0.896600, +-0.093990,-0.133764,-0.472517,0.000000, -0.188000,-0.266600,-0.945200, 0.781300,0.413800, +-0.096261,-0.080891,-0.483932,0.000000, -0.192500,-0.161200,-0.967900, 0.781300,0.448300, +-0.000000,-0.080891,-0.493412,0.000000, 0.000000,-0.161200,-0.986900, 0.750000,0.448300, +-0.093990,-0.133764,-0.472517,0.000000, -0.188000,-0.266600,-0.945200, 0.781300,0.413800, +-0.000000,-0.080891,-0.493412,0.000000, 0.000000,-0.161200,-0.986900, 0.750000,0.448300, +-0.000000,-0.133764,-0.481775,0.000000, 0.000000,-0.266600,-0.963800, 0.750000,0.413800, +-0.040959,0.453788,-0.205910,0.000000, -0.082400,0.906300,-0.414500, 0.781300,0.862100, +-0.031147,0.473826,-0.156583,0.000000, -0.062900,0.946600,-0.316100, 0.781300,0.896600, +-0.000000,0.473826,-0.159651,0.000000, 0.000000,0.946600,-0.322300, 0.750000,0.896600, +-0.040959,0.453788,-0.205910,0.000000, -0.082400,0.906300,-0.414500, 0.781300,0.862100, +-0.000000,0.473826,-0.159651,0.000000, 0.000000,0.946600,-0.322300, 0.750000,0.896600, +-0.000000,0.453788,-0.209944,0.000000, 0.000000,0.906300,-0.422700, 0.750000,0.862100, +-0.090618,-0.185069,-0.455563,0.000000, -0.181300,-0.369000,-0.911600, 0.781300,0.379300, +-0.093990,-0.133764,-0.472517,0.000000, -0.188000,-0.266600,-0.945200, 0.781300,0.413800, +-0.000000,-0.133764,-0.481775,0.000000, 0.000000,-0.266600,-0.963800, 0.750000,0.413800, +-0.090618,-0.185069,-0.455563,0.000000, -0.181300,-0.369000,-0.911600, 0.781300,0.379300, +-0.000000,-0.133764,-0.481775,0.000000, 0.000000,-0.266600,-0.963800, 0.750000,0.413800, +-0.000000,-0.185069,-0.464488,0.000000, 0.000000,-0.369000,-0.929400, 0.750000,0.379300, +-0.050290,0.428429,-0.252824,0.000000, -0.101000,0.855300,-0.508100, 0.781300,0.827600, +-0.040959,0.453788,-0.205910,0.000000, -0.082400,0.906300,-0.414500, 0.781300,0.862100, +-0.000000,0.453788,-0.209944,0.000000, 0.000000,0.906300,-0.422700, 0.750000,0.862100, +-0.050290,0.428429,-0.252824,0.000000, -0.101000,0.855300,-0.508100, 0.781300,0.827600, +-0.000000,0.453788,-0.209944,0.000000, 0.000000,0.906300,-0.422700, 0.750000,0.862100, +-0.000000,0.428429,-0.257776,0.000000, 0.000000,0.855300,-0.518000, 0.750000,0.827600, +-0.086182,-0.234204,-0.433268,0.000000, -0.172500,-0.467000,-0.867200, 0.781300,0.344800, +-0.090618,-0.185069,-0.455563,0.000000, -0.181300,-0.369000,-0.911600, 0.781300,0.379300, +-0.000000,-0.185069,-0.464488,0.000000, 0.000000,-0.369000,-0.929400, 0.750000,0.379300, +-0.086182,-0.234204,-0.433268,0.000000, -0.172500,-0.467000,-0.867200, 0.781300,0.344800, +-0.000000,-0.185069,-0.464488,0.000000, 0.000000,-0.369000,-0.929400, 0.750000,0.379300, +-0.000000,-0.234204,-0.441756,0.000000, 0.000000,-0.467000,-0.884200, 0.750000,0.344800, +-0.059032,0.398046,-0.296773,0.000000, -0.118500,0.794500,-0.595600, 0.781300,0.793100, +-0.050290,0.428429,-0.252824,0.000000, -0.101000,0.855300,-0.508100, 0.781300,0.827600, +-0.000000,0.428429,-0.257776,0.000000, 0.000000,0.855300,-0.518000, 0.750000,0.827600, +-0.059032,0.398046,-0.296773,0.000000, -0.118500,0.794500,-0.595600, 0.781300,0.793100, +-0.000000,0.428429,-0.257776,0.000000, 0.000000,0.855300,-0.518000, 0.750000,0.827600, +-0.000000,0.398046,-0.302586,0.000000, 0.000000,0.794500,-0.607300, 0.750000,0.793100, +-0.080738,-0.280594,-0.405892,0.000000, -0.161700,-0.559600,-0.812800, 0.781300,0.310300, +-0.086182,-0.234204,-0.433268,0.000000, -0.172500,-0.467000,-0.867200, 0.781300,0.344800, +-0.000000,-0.234204,-0.441756,0.000000, 0.000000,-0.467000,-0.884200, 0.750000,0.344800, +-0.080738,-0.280594,-0.405892,0.000000, -0.161700,-0.559600,-0.812800, 0.781300,0.310300, +-0.000000,-0.234204,-0.441756,0.000000, 0.000000,-0.467000,-0.884200, 0.750000,0.344800, +-0.000000,-0.280594,-0.413844,0.000000, 0.000000,-0.559600,-0.828700, 0.750000,0.310300, +-0.067082,0.362998,-0.337242,0.000000, -0.134500,0.724300,-0.676200, 0.781300,0.758600, +-0.059032,0.398046,-0.296773,0.000000, -0.118500,0.794500,-0.595600, 0.781300,0.793100, +-0.000000,0.398046,-0.302586,0.000000, 0.000000,0.794500,-0.607300, 0.750000,0.793100, +-0.067082,0.362998,-0.337242,0.000000, -0.134500,0.724300,-0.676200, 0.781300,0.758600, +-0.000000,0.398046,-0.302586,0.000000, 0.000000,0.794500,-0.607300, 0.750000,0.793100, +-0.000000,0.362998,-0.343849,0.000000, 0.000000,0.724300,-0.689400, 0.750000,0.758600, +-0.074345,-0.323693,-0.373758,0.000000, -0.149000,-0.645700,-0.748900, 0.781300,0.275900, +-0.080738,-0.280594,-0.405892,0.000000, -0.161700,-0.559600,-0.812800, 0.781300,0.310300, +-0.000000,-0.280594,-0.413844,0.000000, 0.000000,-0.559600,-0.828700, 0.750000,0.310300, +-0.074345,-0.323693,-0.373758,0.000000, -0.149000,-0.645700,-0.748900, 0.781300,0.275900, +-0.000000,-0.280594,-0.413844,0.000000, 0.000000,-0.559600,-0.828700, 0.750000,0.310300, +-0.000000,-0.323693,-0.381081,0.000000, 0.000000,-0.645700,-0.763500, 0.750000,0.275900, +-0.074345,0.323693,-0.373758,0.000000, -0.149000,0.645700,-0.748900, 0.781300,0.724100, +-0.067082,0.362998,-0.337242,0.000000, -0.134500,0.724300,-0.676200, 0.781300,0.758600, +-0.000000,0.362998,-0.343849,0.000000, 0.000000,0.724300,-0.689400, 0.750000,0.758600, +-0.074345,0.323693,-0.373758,0.000000, -0.149000,0.645700,-0.748900, 0.781300,0.724100, +-0.000000,0.362998,-0.343849,0.000000, 0.000000,0.724300,-0.689400, 0.750000,0.758600, +-0.000000,0.323693,-0.381081,0.000000, 0.000000,0.645700,-0.763500, 0.750000,0.724100, +-0.000000,0.473826,-0.159651,0.000000, 0.000000,0.946600,-0.322300, 0.750000,0.896600, +-0.000000,0.488310,-0.107485,0.000000, 0.000000,0.975900,-0.218200, 0.750000,0.931000, +0.020969,0.488310,-0.105420,0.000000, 0.042500,0.975900,-0.214000, 0.718800,0.931000, +-0.000000,0.473826,-0.159651,0.000000, 0.000000,0.946600,-0.322300, 0.750000,0.896600, +0.020969,0.488310,-0.105420,0.000000, 0.042500,0.975900,-0.214000, 0.718800,0.931000, +0.031146,0.473826,-0.156583,0.000000, 0.062900,0.946600,-0.316100, 0.718800,0.896600, +-0.000000,-0.133764,-0.481775,0.000000, 0.000000,-0.266600,-0.963800, 0.750000,0.413800, +-0.000000,-0.080891,-0.493412,0.000000, 0.000000,-0.161200,-0.986900, 0.750000,0.448300, +0.096259,-0.080891,-0.483932,0.000000, 0.192500,-0.161200,-0.967900, 0.718800,0.448300, +-0.000000,-0.133764,-0.481775,0.000000, 0.000000,-0.266600,-0.963800, 0.750000,0.413800, +0.096259,-0.080891,-0.483932,0.000000, 0.192500,-0.161200,-0.967900, 0.718800,0.448300, +0.093989,-0.133764,-0.472517,0.000000, 0.188000,-0.266600,-0.945200, 0.718800,0.413800, +-0.000000,0.453788,-0.209944,0.000000, 0.000000,0.906300,-0.422700, 0.750000,0.862100, +-0.000000,0.473826,-0.159651,0.000000, 0.000000,0.946600,-0.322300, 0.750000,0.896600, +0.031146,0.473826,-0.156583,0.000000, 0.062900,0.946600,-0.316100, 0.718800,0.896600, +-0.000000,0.453788,-0.209944,0.000000, 0.000000,0.906300,-0.422700, 0.750000,0.862100, +0.031146,0.473826,-0.156583,0.000000, 0.062900,0.946600,-0.316100, 0.718800,0.896600, +0.040957,0.453788,-0.205910,0.000000, 0.082400,0.906300,-0.414500, 0.718800,0.862100, +-0.000000,-0.185069,-0.464488,0.000000, 0.000000,-0.369000,-0.929400, 0.750000,0.379300, +-0.000000,-0.133764,-0.481775,0.000000, 0.000000,-0.266600,-0.963800, 0.750000,0.413800, +0.093989,-0.133764,-0.472517,0.000000, 0.188000,-0.266600,-0.945200, 0.718800,0.413800, +-0.000000,-0.185069,-0.464488,0.000000, 0.000000,-0.369000,-0.929400, 0.750000,0.379300, +0.093989,-0.133764,-0.472517,0.000000, 0.188000,-0.266600,-0.945200, 0.718800,0.413800, +0.090617,-0.185069,-0.455563,0.000000, 0.181300,-0.369000,-0.911600, 0.718800,0.379300, +-0.000000,0.428429,-0.257776,0.000000, 0.000000,0.855300,-0.518000, 0.750000,0.827600, +-0.000000,0.453788,-0.209944,0.000000, 0.000000,0.906300,-0.422700, 0.750000,0.862100, +0.040957,0.453788,-0.205910,0.000000, 0.082400,0.906300,-0.414500, 0.718800,0.862100, +-0.000000,0.428429,-0.257776,0.000000, 0.000000,0.855300,-0.518000, 0.750000,0.827600, +0.040957,0.453788,-0.205910,0.000000, 0.082400,0.906300,-0.414500, 0.718800,0.862100, +0.050290,0.428429,-0.252824,0.000000, 0.101000,0.855300,-0.508100, 0.718800,0.827600, +-0.000000,-0.234204,-0.441756,0.000000, 0.000000,-0.467000,-0.884200, 0.750000,0.344800, +-0.000000,-0.185069,-0.464488,0.000000, 0.000000,-0.369000,-0.929400, 0.750000,0.379300, +0.090617,-0.185069,-0.455563,0.000000, 0.181300,-0.369000,-0.911600, 0.718800,0.379300, +-0.000000,-0.234204,-0.441756,0.000000, 0.000000,-0.467000,-0.884200, 0.750000,0.344800, +0.090617,-0.185069,-0.455563,0.000000, 0.181300,-0.369000,-0.911600, 0.718800,0.379300, +0.086182,-0.234204,-0.433268,0.000000, 0.172500,-0.467000,-0.867200, 0.718800,0.344800, +-0.000000,0.398046,-0.302586,0.000000, 0.000000,0.794500,-0.607300, 0.750000,0.793100, +-0.000000,0.428429,-0.257776,0.000000, 0.000000,0.855300,-0.518000, 0.750000,0.827600, +0.050290,0.428429,-0.252824,0.000000, 0.101000,0.855300,-0.508100, 0.718800,0.827600, +-0.000000,0.398046,-0.302586,0.000000, 0.000000,0.794500,-0.607300, 0.750000,0.793100, +0.050290,0.428429,-0.252824,0.000000, 0.101000,0.855300,-0.508100, 0.718800,0.827600, +0.059032,0.398046,-0.296773,0.000000, 0.118500,0.794500,-0.595600, 0.718800,0.793100, +-0.000000,-0.280594,-0.413844,0.000000, 0.000000,-0.559600,-0.828700, 0.750000,0.310300, +-0.000000,-0.234204,-0.441756,0.000000, 0.000000,-0.467000,-0.884200, 0.750000,0.344800, +0.086182,-0.234204,-0.433268,0.000000, 0.172500,-0.467000,-0.867200, 0.718800,0.344800, +-0.000000,-0.280594,-0.413844,0.000000, 0.000000,-0.559600,-0.828700, 0.750000,0.310300, +0.086182,-0.234204,-0.433268,0.000000, 0.172500,-0.467000,-0.867200, 0.718800,0.344800, +0.080737,-0.280594,-0.405892,0.000000, 0.161700,-0.559600,-0.812800, 0.718800,0.310300, +-0.000000,0.362998,-0.343849,0.000000, 0.000000,0.724300,-0.689400, 0.750000,0.758600, +-0.000000,0.398046,-0.302586,0.000000, 0.000000,0.794500,-0.607300, 0.750000,0.793100, +0.059032,0.398046,-0.296773,0.000000, 0.118500,0.794500,-0.595600, 0.718800,0.793100, +-0.000000,0.362998,-0.343849,0.000000, 0.000000,0.724300,-0.689400, 0.750000,0.758600, +0.059032,0.398046,-0.296773,0.000000, 0.118500,0.794500,-0.595600, 0.718800,0.793100, +0.067081,0.362998,-0.337242,0.000000, 0.134500,0.724300,-0.676200, 0.718800,0.758600, +-0.000000,-0.323693,-0.381081,0.000000, 0.000000,-0.645700,-0.763500, 0.750000,0.275900, +-0.000000,-0.280594,-0.413844,0.000000, 0.000000,-0.559600,-0.828700, 0.750000,0.310300, +0.080737,-0.280594,-0.405892,0.000000, 0.161700,-0.559600,-0.812800, 0.718800,0.310300, +-0.000000,-0.323693,-0.381081,0.000000, 0.000000,-0.645700,-0.763500, 0.750000,0.275900, +0.080737,-0.280594,-0.405892,0.000000, 0.161700,-0.559600,-0.812800, 0.718800,0.310300, +0.074345,-0.323693,-0.373758,0.000000, 0.149000,-0.645700,-0.748900, 0.718800,0.275900, +-0.000000,0.323693,-0.381081,0.000000, 0.000000,0.645700,-0.763500, 0.750000,0.724100, +-0.000000,0.362998,-0.343849,0.000000, 0.000000,0.724300,-0.689400, 0.750000,0.758600, +0.067081,0.362998,-0.337242,0.000000, 0.134500,0.724300,-0.676200, 0.718800,0.758600, +-0.000000,0.323693,-0.381081,0.000000, 0.000000,0.645700,-0.763500, 0.750000,0.724100, +0.067081,0.362998,-0.337242,0.000000, 0.134500,0.724300,-0.676200, 0.718800,0.758600, +0.074345,0.323693,-0.373758,0.000000, 0.149000,0.645700,-0.748900, 0.718800,0.724100, +-0.000000,-0.362998,-0.343850,0.000000, 0.000000,-0.724300,-0.689400, 0.750000,0.241400, +-0.000000,-0.323693,-0.381081,0.000000, 0.000000,-0.645700,-0.763500, 0.750000,0.275900, +0.074345,-0.323693,-0.373758,0.000000, 0.149000,-0.645700,-0.748900, 0.718800,0.275900, +-0.000000,-0.362998,-0.343850,0.000000, 0.000000,-0.724300,-0.689400, 0.750000,0.241400, +0.074345,-0.323693,-0.373758,0.000000, 0.149000,-0.645700,-0.748900, 0.718800,0.275900, +0.067081,-0.362998,-0.337243,0.000000, 0.134500,-0.724300,-0.676200, 0.718800,0.241400, +-0.000000,0.280594,-0.413844,0.000000, 0.000000,0.559600,-0.828700, 0.750000,0.689700, +-0.000000,0.323693,-0.381081,0.000000, 0.000000,0.645700,-0.763500, 0.750000,0.724100, +0.074345,0.323693,-0.373758,0.000000, 0.149000,0.645700,-0.748900, 0.718800,0.724100, +-0.000000,0.280594,-0.413844,0.000000, 0.000000,0.559600,-0.828700, 0.750000,0.689700, +0.074345,0.323693,-0.373758,0.000000, 0.149000,0.645700,-0.748900, 0.718800,0.724100, +0.080737,0.280594,-0.405892,0.000000, 0.161700,0.559600,-0.812800, 0.718800,0.689700, +-0.000000,-0.398046,-0.302587,0.000000, 0.000000,-0.794500,-0.607300, 0.750000,0.206900, +-0.000000,-0.362998,-0.343850,0.000000, 0.000000,-0.724300,-0.689400, 0.750000,0.241400, +0.067081,-0.362998,-0.337243,0.000000, 0.134500,-0.724300,-0.676200, 0.718800,0.241400, +-0.000000,-0.398046,-0.302587,0.000000, 0.000000,-0.794500,-0.607300, 0.750000,0.206900, +0.067081,-0.362998,-0.337243,0.000000, 0.134500,-0.724300,-0.676200, 0.718800,0.241400, +0.059032,-0.398046,-0.296773,0.000000, 0.118500,-0.794500,-0.595600, 0.718800,0.206900, +-0.000000,0.234204,-0.441756,0.000000, 0.000000,0.467000,-0.884200, 0.750000,0.655200, +-0.000000,0.280594,-0.413844,0.000000, 0.000000,0.559600,-0.828700, 0.750000,0.689700, +0.080737,0.280594,-0.405892,0.000000, 0.161700,0.559600,-0.812800, 0.718800,0.689700, +-0.000000,0.234204,-0.441756,0.000000, 0.000000,0.467000,-0.884200, 0.750000,0.655200, +0.080737,0.280594,-0.405892,0.000000, 0.161700,0.559600,-0.812800, 0.718800,0.689700, +0.086182,0.234204,-0.433268,0.000000, 0.172500,0.467000,-0.867200, 0.718800,0.655200, +-0.000000,-0.428429,-0.257776,0.000000, 0.000000,-0.855300,-0.518000, 0.750000,0.172400, +-0.000000,-0.398046,-0.302587,0.000000, 0.000000,-0.794500,-0.607300, 0.750000,0.206900, +0.059032,-0.398046,-0.296773,0.000000, 0.118500,-0.794500,-0.595600, 0.718800,0.206900, +-0.000000,-0.428429,-0.257776,0.000000, 0.000000,-0.855300,-0.518000, 0.750000,0.172400, +0.059032,-0.398046,-0.296773,0.000000, 0.118500,-0.794500,-0.595600, 0.718800,0.206900, +0.050290,-0.428429,-0.252824,0.000000, 0.101000,-0.855300,-0.508100, 0.718800,0.172400, +-0.000000,0.185069,-0.464488,0.000000, 0.000000,0.369000,-0.929400, 0.750000,0.620700, +-0.000000,0.234204,-0.441756,0.000000, 0.000000,0.467000,-0.884200, 0.750000,0.655200, +0.086182,0.234204,-0.433268,0.000000, 0.172500,0.467000,-0.867200, 0.718800,0.655200, +-0.000000,0.185069,-0.464488,0.000000, 0.000000,0.369000,-0.929400, 0.750000,0.620700, +0.086182,0.234204,-0.433268,0.000000, 0.172500,0.467000,-0.867200, 0.718800,0.655200, +0.090617,0.185069,-0.455563,0.000000, 0.181300,0.369000,-0.911600, 0.718800,0.620700, +-0.000000,-0.453788,-0.209945,0.000000, 0.000000,-0.906300,-0.422700, 0.750000,0.137900, +-0.000000,-0.428429,-0.257776,0.000000, 0.000000,-0.855300,-0.518000, 0.750000,0.172400, +0.050290,-0.428429,-0.252824,0.000000, 0.101000,-0.855300,-0.508100, 0.718800,0.172400, +-0.000000,-0.453788,-0.209945,0.000000, 0.000000,-0.906300,-0.422700, 0.750000,0.137900, +0.050290,-0.428429,-0.252824,0.000000, 0.101000,-0.855300,-0.508100, 0.718800,0.172400, +0.040957,-0.453788,-0.205911,0.000000, 0.082400,-0.906300,-0.414500, 0.718800,0.137900, +-0.000000,0.133764,-0.481775,0.000000, 0.000000,0.266600,-0.963800, 0.750000,0.586200, +-0.000000,0.185069,-0.464488,0.000000, 0.000000,0.369000,-0.929400, 0.750000,0.620700, +0.090617,0.185069,-0.455563,0.000000, 0.181300,0.369000,-0.911600, 0.718800,0.620700, +-0.000000,0.133764,-0.481775,0.000000, 0.000000,0.266600,-0.963800, 0.750000,0.586200, +0.090617,0.185069,-0.455563,0.000000, 0.181300,0.369000,-0.911600, 0.718800,0.620700, +0.093989,0.133764,-0.472517,0.000000, 0.188000,0.266600,-0.945200, 0.718800,0.586200, +-0.000000,-0.473826,-0.159651,0.000000, 0.000000,-0.946600,-0.322300, 0.750000,0.103400, +-0.000000,-0.453788,-0.209945,0.000000, 0.000000,-0.906300,-0.422700, 0.750000,0.137900, +0.040957,-0.453788,-0.205911,0.000000, 0.082400,-0.906300,-0.414500, 0.718800,0.137900, +-0.000000,-0.473826,-0.159651,0.000000, 0.000000,-0.946600,-0.322300, 0.750000,0.103400, +0.040957,-0.453788,-0.205911,0.000000, 0.082400,-0.906300,-0.414500, 0.718800,0.137900, +0.031146,-0.473826,-0.156583,0.000000, 0.062900,-0.946600,-0.316100, 0.718800,0.103400, +-0.000000,0.080891,-0.493412,0.000000, 0.000000,0.161200,-0.986900, 0.750000,0.551700, +-0.000000,0.133764,-0.481775,0.000000, 0.000000,0.266600,-0.963800, 0.750000,0.586200, +0.093989,0.133764,-0.472517,0.000000, 0.188000,0.266600,-0.945200, 0.718800,0.586200, +-0.000000,0.080891,-0.493412,0.000000, 0.000000,0.161200,-0.986900, 0.750000,0.551700, +0.093989,0.133764,-0.472517,0.000000, 0.188000,0.266600,-0.945200, 0.718800,0.586200, +0.096259,0.080891,-0.483932,0.000000, 0.192500,0.161200,-0.967900, 0.718800,0.551700, +-0.000000,-0.488310,-0.107485,0.000000, 0.000000,-0.975900,-0.218200, 0.750000,0.069000, +-0.000000,-0.473826,-0.159651,0.000000, 0.000000,-0.946600,-0.322300, 0.750000,0.103400, +0.031146,-0.473826,-0.156583,0.000000, 0.062900,-0.946600,-0.316100, 0.718800,0.103400, +-0.000000,-0.488310,-0.107485,0.000000, 0.000000,-0.975900,-0.218200, 0.750000,0.069000, +0.031146,-0.473826,-0.156583,0.000000, 0.062900,-0.946600,-0.316100, 0.718800,0.103400, +0.020969,-0.488310,-0.105420,0.000000, 0.042500,-0.975900,-0.214000, 0.718800,0.069000, +-0.000000,0.027069,-0.499266,0.000000, 0.000000,0.054000,-0.998500, 0.750000,0.517200, +-0.000000,0.080891,-0.493412,0.000000, 0.000000,0.161200,-0.986900, 0.750000,0.551700, +0.096259,0.080891,-0.483932,0.000000, 0.192500,0.161200,-0.967900, 0.718800,0.551700, +-0.000000,0.027069,-0.499266,0.000000, 0.000000,0.054000,-0.998500, 0.750000,0.517200, +0.096259,0.080891,-0.483932,0.000000, 0.192500,0.161200,-0.967900, 0.718800,0.551700, +0.097401,0.027069,-0.489673,0.000000, 0.194800,0.054000,-0.979300, 0.718800,0.517200, +-0.000000,0.497069,-0.054059,0.000000, 0.000000,0.993700,-0.111500, 0.441700,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +0.010546,0.497069,-0.053020,0.000000, 0.021700,0.993700,-0.109300, 0.443500,0.962300, +-0.000000,-0.497069,-0.054060,0.000000, 0.000000,-0.993700,-0.111500, 0.750000,0.034500, +-0.000000,-0.488310,-0.107485,0.000000, 0.000000,-0.975900,-0.218200, 0.750000,0.069000, +0.020969,-0.488310,-0.105420,0.000000, 0.042500,-0.975900,-0.214000, 0.718800,0.069000, +-0.000000,-0.497069,-0.054060,0.000000, 0.000000,-0.993700,-0.111500, 0.750000,0.034500, +0.020969,-0.488310,-0.105420,0.000000, 0.042500,-0.975900,-0.214000, 0.718800,0.069000, +0.010546,-0.497069,-0.053020,0.000000, 0.021700,-0.993700,-0.109300, 0.718800,0.034500, +-0.000000,-0.027069,-0.499266,0.000000, 0.000000,-0.054000,-0.998500, 0.750000,0.482800, +-0.000000,0.027069,-0.499266,0.000000, 0.000000,0.054000,-0.998500, 0.750000,0.517200, +0.097401,0.027069,-0.489673,0.000000, 0.194800,0.054000,-0.979300, 0.718800,0.517200, +-0.000000,-0.027069,-0.499266,0.000000, 0.000000,-0.054000,-0.998500, 0.750000,0.482800, +0.097401,0.027069,-0.489673,0.000000, 0.194800,0.054000,-0.979300, 0.718800,0.517200, +0.097401,-0.027069,-0.489673,0.000000, 0.194800,-0.054000,-0.979300, 0.718800,0.482800, +-0.000000,0.488310,-0.107485,0.000000, 0.000000,0.975900,-0.218200, 0.750000,0.931000, +-0.000000,0.497069,-0.054059,0.000000, 0.000000,0.993700,-0.111500, 0.750000,0.965500, +0.010546,0.497069,-0.053020,0.000000, 0.021700,0.993700,-0.109300, 0.718800,0.965500, +-0.000000,0.488310,-0.107485,0.000000, 0.000000,0.975900,-0.218200, 0.750000,0.931000, +0.010546,0.497069,-0.053020,0.000000, 0.021700,0.993700,-0.109300, 0.718800,0.965500, +0.020969,0.488310,-0.105420,0.000000, 0.042500,0.975900,-0.214000, 0.718800,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +-0.000000,-0.497069,-0.054060,0.000000, 0.000000,-0.993700,-0.111500, 0.473300,0.053800, +0.010546,-0.497069,-0.053020,0.000000, 0.021700,-0.993700,-0.109300, 0.470600,0.053800, +-0.000000,-0.080891,-0.493412,0.000000, 0.000000,-0.161200,-0.986900, 0.750000,0.448300, +-0.000000,-0.027069,-0.499266,0.000000, 0.000000,-0.054000,-0.998500, 0.750000,0.482800, +0.097401,-0.027069,-0.489673,0.000000, 0.194800,-0.054000,-0.979300, 0.718800,0.482800, +-0.000000,-0.080891,-0.493412,0.000000, 0.000000,-0.161200,-0.986900, 0.750000,0.448300, +0.097401,-0.027069,-0.489673,0.000000, 0.194800,-0.054000,-0.979300, 0.718800,0.482800, +0.096259,-0.080891,-0.483932,0.000000, 0.192500,-0.161200,-0.967900, 0.718800,0.448300, +0.090617,0.185069,-0.455563,0.000000, 0.181300,0.369000,-0.911600, 0.718800,0.620700, +0.086182,0.234204,-0.433268,0.000000, 0.172500,0.467000,-0.867200, 0.718800,0.655200, +0.169052,0.234204,-0.408129,0.000000, 0.338400,0.467000,-0.816900, 0.687500,0.655200, +0.090617,0.185069,-0.455563,0.000000, 0.181300,0.369000,-0.911600, 0.718800,0.620700, +0.169052,0.234204,-0.408129,0.000000, 0.338400,0.467000,-0.816900, 0.687500,0.655200, +0.177751,0.185069,-0.429130,0.000000, 0.355700,0.369000,-0.858700, 0.687500,0.620700, +0.040957,-0.453788,-0.205911,0.000000, 0.082400,-0.906300,-0.414500, 0.718800,0.137900, +0.050290,-0.428429,-0.252824,0.000000, 0.101000,-0.855300,-0.508100, 0.718800,0.172400, +0.098646,-0.428429,-0.238155,0.000000, 0.198200,-0.855300,-0.478600, 0.687500,0.172400, +0.040957,-0.453788,-0.205911,0.000000, 0.082400,-0.906300,-0.414500, 0.718800,0.137900, +0.098646,-0.428429,-0.238155,0.000000, 0.198200,-0.855300,-0.478600, 0.687500,0.172400, +0.080342,-0.453788,-0.193963,0.000000, 0.161700,-0.906300,-0.390500, 0.687500,0.137900, +0.093989,0.133764,-0.472517,0.000000, 0.188000,0.266600,-0.945200, 0.718800,0.586200, +0.090617,0.185069,-0.455563,0.000000, 0.181300,0.369000,-0.911600, 0.718800,0.620700, +0.177751,0.185069,-0.429130,0.000000, 0.355700,0.369000,-0.858700, 0.687500,0.620700, +0.093989,0.133764,-0.472517,0.000000, 0.188000,0.266600,-0.945200, 0.718800,0.586200, +0.177751,0.185069,-0.429130,0.000000, 0.355700,0.369000,-0.858700, 0.687500,0.620700, +0.184366,0.133764,-0.445101,0.000000, 0.368800,0.266600,-0.890400, 0.687500,0.586200, +0.031146,-0.473826,-0.156583,0.000000, 0.062900,-0.946600,-0.316100, 0.718800,0.103400, +0.040957,-0.453788,-0.205911,0.000000, 0.082400,-0.906300,-0.414500, 0.718800,0.137900, +0.080342,-0.453788,-0.193963,0.000000, 0.161700,-0.906300,-0.390500, 0.687500,0.137900, +0.031146,-0.473826,-0.156583,0.000000, 0.062900,-0.946600,-0.316100, 0.718800,0.103400, +0.080342,-0.453788,-0.193963,0.000000, 0.161700,-0.906300,-0.390500, 0.687500,0.137900, +0.061095,-0.473826,-0.147498,0.000000, 0.123300,-0.946600,-0.297800, 0.687500,0.103400, +0.096259,0.080891,-0.483932,0.000000, 0.192500,0.161200,-0.967900, 0.718800,0.551700, +0.093989,0.133764,-0.472517,0.000000, 0.188000,0.266600,-0.945200, 0.718800,0.586200, +0.184366,0.133764,-0.445101,0.000000, 0.368800,0.266600,-0.890400, 0.687500,0.586200, +0.096259,0.080891,-0.483932,0.000000, 0.192500,0.161200,-0.967900, 0.718800,0.551700, +0.184366,0.133764,-0.445101,0.000000, 0.368800,0.266600,-0.890400, 0.687500,0.586200, +0.188820,0.080891,-0.455854,0.000000, 0.377700,0.161200,-0.911800, 0.687500,0.551700, +0.020969,-0.488310,-0.105420,0.000000, 0.042500,-0.975900,-0.214000, 0.718800,0.069000, +0.031146,-0.473826,-0.156583,0.000000, 0.062900,-0.946600,-0.316100, 0.718800,0.103400, +0.061095,-0.473826,-0.147498,0.000000, 0.123300,-0.946600,-0.297800, 0.687500,0.103400, +0.020969,-0.488310,-0.105420,0.000000, 0.042500,-0.975900,-0.214000, 0.718800,0.069000, +0.061095,-0.473826,-0.147498,0.000000, 0.123300,-0.946600,-0.297800, 0.687500,0.103400, +0.041132,-0.488310,-0.099303,0.000000, 0.083500,-0.975900,-0.201600, 0.687500,0.069000, +0.097401,0.027069,-0.489673,0.000000, 0.194800,0.054000,-0.979300, 0.718800,0.517200, +0.096259,0.080891,-0.483932,0.000000, 0.192500,0.161200,-0.967900, 0.718800,0.551700, +0.188820,0.080891,-0.455854,0.000000, 0.377700,0.161200,-0.911800, 0.687500,0.551700, +0.097401,0.027069,-0.489673,0.000000, 0.194800,0.054000,-0.979300, 0.718800,0.517200, +0.188820,0.080891,-0.455854,0.000000, 0.377700,0.161200,-0.911800, 0.687500,0.551700, +0.191060,0.027069,-0.461262,0.000000, 0.382100,0.054000,-0.922500, 0.687500,0.517200, +0.010546,0.497069,-0.053020,0.000000, 0.021700,0.993700,-0.109300, 0.443500,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +0.020687,0.497069,-0.049944,0.000000, 0.042600,0.993700,-0.103000, 0.445300,0.962300, +0.010546,-0.497069,-0.053020,0.000000, 0.021700,-0.993700,-0.109300, 0.718800,0.034500, +0.020969,-0.488310,-0.105420,0.000000, 0.042500,-0.975900,-0.214000, 0.718800,0.069000, +0.041132,-0.488310,-0.099303,0.000000, 0.083500,-0.975900,-0.201600, 0.687500,0.069000, +0.010546,-0.497069,-0.053020,0.000000, 0.021700,-0.993700,-0.109300, 0.718800,0.034500, +0.041132,-0.488310,-0.099303,0.000000, 0.083500,-0.975900,-0.201600, 0.687500,0.069000, +0.020687,-0.497069,-0.049945,0.000000, 0.042600,-0.993700,-0.103000, 0.687500,0.034500, +0.097401,-0.027069,-0.489673,0.000000, 0.194800,-0.054000,-0.979300, 0.718800,0.482800, +0.097401,0.027069,-0.489673,0.000000, 0.194800,0.054000,-0.979300, 0.718800,0.517200, +0.191060,0.027069,-0.461262,0.000000, 0.382100,0.054000,-0.922500, 0.687500,0.517200, +0.097401,-0.027069,-0.489673,0.000000, 0.194800,-0.054000,-0.979300, 0.718800,0.482800, +0.191060,0.027069,-0.461262,0.000000, 0.382100,0.054000,-0.922500, 0.687500,0.517200, +0.191060,-0.027069,-0.461262,0.000000, 0.382100,-0.054000,-0.922500, 0.687500,0.482800, +0.020969,0.488310,-0.105420,0.000000, 0.042500,0.975900,-0.214000, 0.718800,0.931000, +0.010546,0.497069,-0.053020,0.000000, 0.021700,0.993700,-0.109300, 0.718800,0.965500, +0.020687,0.497069,-0.049944,0.000000, 0.042600,0.993700,-0.103000, 0.687500,0.965500, +0.020969,0.488310,-0.105420,0.000000, 0.042500,0.975900,-0.214000, 0.718800,0.931000, +0.020687,0.497069,-0.049944,0.000000, 0.042600,0.993700,-0.103000, 0.687500,0.965500, +0.041132,0.488310,-0.099303,0.000000, 0.083500,0.975900,-0.201600, 0.687500,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +0.010546,-0.497069,-0.053020,0.000000, 0.021700,-0.993700,-0.109300, 0.470600,0.053800, +0.020687,-0.497069,-0.049945,0.000000, 0.042600,-0.993700,-0.103000, 0.468000,0.053800, +0.096259,-0.080891,-0.483932,0.000000, 0.192500,-0.161200,-0.967900, 0.718800,0.448300, +0.097401,-0.027069,-0.489673,0.000000, 0.194800,-0.054000,-0.979300, 0.718800,0.482800, +0.191060,-0.027069,-0.461262,0.000000, 0.382100,-0.054000,-0.922500, 0.687500,0.482800, +0.096259,-0.080891,-0.483932,0.000000, 0.192500,-0.161200,-0.967900, 0.718800,0.448300, +0.191060,-0.027069,-0.461262,0.000000, 0.382100,-0.054000,-0.922500, 0.687500,0.482800, +0.188820,-0.080891,-0.455854,0.000000, 0.377700,-0.161200,-0.911800, 0.687500,0.448300, +0.031146,0.473826,-0.156583,0.000000, 0.062900,0.946600,-0.316100, 0.718800,0.896600, +0.020969,0.488310,-0.105420,0.000000, 0.042500,0.975900,-0.214000, 0.718800,0.931000, +0.041132,0.488310,-0.099303,0.000000, 0.083500,0.975900,-0.201600, 0.687500,0.931000, +0.031146,0.473826,-0.156583,0.000000, 0.062900,0.946600,-0.316100, 0.718800,0.896600, +0.041132,0.488310,-0.099303,0.000000, 0.083500,0.975900,-0.201600, 0.687500,0.931000, +0.061095,0.473826,-0.147498,0.000000, 0.123300,0.946600,-0.297800, 0.687500,0.896600, +0.093989,-0.133764,-0.472517,0.000000, 0.188000,-0.266600,-0.945200, 0.718800,0.413800, +0.096259,-0.080891,-0.483932,0.000000, 0.192500,-0.161200,-0.967900, 0.718800,0.448300, +0.188820,-0.080891,-0.455854,0.000000, 0.377700,-0.161200,-0.911800, 0.687500,0.448300, +0.093989,-0.133764,-0.472517,0.000000, 0.188000,-0.266600,-0.945200, 0.718800,0.413800, +0.188820,-0.080891,-0.455854,0.000000, 0.377700,-0.161200,-0.911800, 0.687500,0.448300, +0.184366,-0.133764,-0.445101,0.000000, 0.368800,-0.266600,-0.890400, 0.687500,0.413800, +0.040957,0.453788,-0.205910,0.000000, 0.082400,0.906300,-0.414500, 0.718800,0.862100, +0.031146,0.473826,-0.156583,0.000000, 0.062900,0.946600,-0.316100, 0.718800,0.896600, +0.061095,0.473826,-0.147498,0.000000, 0.123300,0.946600,-0.297800, 0.687500,0.896600, +0.040957,0.453788,-0.205910,0.000000, 0.082400,0.906300,-0.414500, 0.718800,0.862100, +0.061095,0.473826,-0.147498,0.000000, 0.123300,0.946600,-0.297800, 0.687500,0.896600, +0.080342,0.453788,-0.193963,0.000000, 0.161700,0.906300,-0.390500, 0.687500,0.862100, +0.090617,-0.185069,-0.455563,0.000000, 0.181300,-0.369000,-0.911600, 0.718800,0.379300, +0.093989,-0.133764,-0.472517,0.000000, 0.188000,-0.266600,-0.945200, 0.718800,0.413800, +0.184366,-0.133764,-0.445101,0.000000, 0.368800,-0.266600,-0.890400, 0.687500,0.413800, +0.090617,-0.185069,-0.455563,0.000000, 0.181300,-0.369000,-0.911600, 0.718800,0.379300, +0.184366,-0.133764,-0.445101,0.000000, 0.368800,-0.266600,-0.890400, 0.687500,0.413800, +0.177751,-0.185069,-0.429130,0.000000, 0.355700,-0.369000,-0.858700, 0.687500,0.379300, +0.050290,0.428429,-0.252824,0.000000, 0.101000,0.855300,-0.508100, 0.718800,0.827600, +0.040957,0.453788,-0.205910,0.000000, 0.082400,0.906300,-0.414500, 0.718800,0.862100, +0.080342,0.453788,-0.193963,0.000000, 0.161700,0.906300,-0.390500, 0.687500,0.862100, +0.050290,0.428429,-0.252824,0.000000, 0.101000,0.855300,-0.508100, 0.718800,0.827600, +0.080342,0.453788,-0.193963,0.000000, 0.161700,0.906300,-0.390500, 0.687500,0.862100, +0.098646,0.428429,-0.238155,0.000000, 0.198200,0.855300,-0.478600, 0.687500,0.827600, +0.086182,-0.234204,-0.433268,0.000000, 0.172500,-0.467000,-0.867200, 0.718800,0.344800, +0.090617,-0.185069,-0.455563,0.000000, 0.181300,-0.369000,-0.911600, 0.718800,0.379300, +0.177751,-0.185069,-0.429130,0.000000, 0.355700,-0.369000,-0.858700, 0.687500,0.379300, +0.086182,-0.234204,-0.433268,0.000000, 0.172500,-0.467000,-0.867200, 0.718800,0.344800, +0.177751,-0.185069,-0.429130,0.000000, 0.355700,-0.369000,-0.858700, 0.687500,0.379300, +0.169052,-0.234204,-0.408129,0.000000, 0.338400,-0.467000,-0.816900, 0.687500,0.344800, +0.059032,0.398046,-0.296773,0.000000, 0.118500,0.794500,-0.595600, 0.718800,0.793100, +0.050290,0.428429,-0.252824,0.000000, 0.101000,0.855300,-0.508100, 0.718800,0.827600, +0.098646,0.428429,-0.238155,0.000000, 0.198200,0.855300,-0.478600, 0.687500,0.827600, +0.059032,0.398046,-0.296773,0.000000, 0.118500,0.794500,-0.595600, 0.718800,0.793100, +0.098646,0.428429,-0.238155,0.000000, 0.198200,0.855300,-0.478600, 0.687500,0.827600, +0.115795,0.398046,-0.279554,0.000000, 0.232400,0.794500,-0.561100, 0.687500,0.793100, +0.080737,-0.280594,-0.405892,0.000000, 0.161700,-0.559600,-0.812800, 0.718800,0.310300, +0.086182,-0.234204,-0.433268,0.000000, 0.172500,-0.467000,-0.867200, 0.718800,0.344800, +0.169052,-0.234204,-0.408129,0.000000, 0.338400,-0.467000,-0.816900, 0.687500,0.344800, +0.080737,-0.280594,-0.405892,0.000000, 0.161700,-0.559600,-0.812800, 0.718800,0.310300, +0.169052,-0.234204,-0.408129,0.000000, 0.338400,-0.467000,-0.816900, 0.687500,0.344800, +0.158371,-0.280594,-0.382342,0.000000, 0.317100,-0.559600,-0.765600, 0.687500,0.310300, +0.067081,0.362998,-0.337242,0.000000, 0.134500,0.724300,-0.676200, 0.718800,0.758600, +0.059032,0.398046,-0.296773,0.000000, 0.118500,0.794500,-0.595600, 0.718800,0.793100, +0.115795,0.398046,-0.279554,0.000000, 0.232400,0.794500,-0.561100, 0.687500,0.793100, +0.067081,0.362998,-0.337242,0.000000, 0.134500,0.724300,-0.676200, 0.718800,0.758600, +0.115795,0.398046,-0.279554,0.000000, 0.232400,0.794500,-0.561100, 0.687500,0.793100, +0.131585,0.362998,-0.317675,0.000000, 0.263800,0.724300,-0.637000, 0.687500,0.758600, +0.074345,-0.323693,-0.373758,0.000000, 0.149000,-0.645700,-0.748900, 0.718800,0.275900, +0.080737,-0.280594,-0.405892,0.000000, 0.161700,-0.559600,-0.812800, 0.718800,0.310300, +0.158371,-0.280594,-0.382342,0.000000, 0.317100,-0.559600,-0.765600, 0.687500,0.310300, +0.074345,-0.323693,-0.373758,0.000000, 0.149000,-0.645700,-0.748900, 0.718800,0.275900, +0.158371,-0.280594,-0.382342,0.000000, 0.317100,-0.559600,-0.765600, 0.687500,0.310300, +0.145833,-0.323693,-0.352073,0.000000, 0.292200,-0.645700,-0.705400, 0.687500,0.275900, +0.074345,0.323693,-0.373758,0.000000, 0.149000,0.645700,-0.748900, 0.718800,0.724100, +0.067081,0.362998,-0.337242,0.000000, 0.134500,0.724300,-0.676200, 0.718800,0.758600, +0.131585,0.362998,-0.317675,0.000000, 0.263800,0.724300,-0.637000, 0.687500,0.758600, +0.074345,0.323693,-0.373758,0.000000, 0.149000,0.645700,-0.748900, 0.718800,0.724100, +0.131585,0.362998,-0.317675,0.000000, 0.263800,0.724300,-0.637000, 0.687500,0.758600, +0.145832,0.323693,-0.352073,0.000000, 0.292200,0.645700,-0.705400, 0.687500,0.724100, +0.067081,-0.362998,-0.337243,0.000000, 0.134500,-0.724300,-0.676200, 0.718800,0.241400, +0.074345,-0.323693,-0.373758,0.000000, 0.149000,-0.645700,-0.748900, 0.718800,0.275900, +0.145833,-0.323693,-0.352073,0.000000, 0.292200,-0.645700,-0.705400, 0.687500,0.275900, +0.067081,-0.362998,-0.337243,0.000000, 0.134500,-0.724300,-0.676200, 0.718800,0.241400, +0.145833,-0.323693,-0.352073,0.000000, 0.292200,-0.645700,-0.705400, 0.687500,0.275900, +0.131585,-0.362998,-0.317676,0.000000, 0.263800,-0.724300,-0.637000, 0.687500,0.241400, +0.080737,0.280594,-0.405892,0.000000, 0.161700,0.559600,-0.812800, 0.718800,0.689700, +0.074345,0.323693,-0.373758,0.000000, 0.149000,0.645700,-0.748900, 0.718800,0.724100, +0.145832,0.323693,-0.352073,0.000000, 0.292200,0.645700,-0.705400, 0.687500,0.724100, +0.080737,0.280594,-0.405892,0.000000, 0.161700,0.559600,-0.812800, 0.718800,0.689700, +0.145832,0.323693,-0.352073,0.000000, 0.292200,0.645700,-0.705400, 0.687500,0.724100, +0.158371,0.280594,-0.382342,0.000000, 0.317100,0.559600,-0.765600, 0.687500,0.689700, +0.059032,-0.398046,-0.296773,0.000000, 0.118500,-0.794500,-0.595600, 0.718800,0.206900, +0.067081,-0.362998,-0.337243,0.000000, 0.134500,-0.724300,-0.676200, 0.718800,0.241400, +0.131585,-0.362998,-0.317676,0.000000, 0.263800,-0.724300,-0.637000, 0.687500,0.241400, +0.059032,-0.398046,-0.296773,0.000000, 0.118500,-0.794500,-0.595600, 0.718800,0.206900, +0.131585,-0.362998,-0.317676,0.000000, 0.263800,-0.724300,-0.637000, 0.687500,0.241400, +0.115795,-0.398046,-0.279554,0.000000, 0.232400,-0.794500,-0.561100, 0.687500,0.206900, +0.086182,0.234204,-0.433268,0.000000, 0.172500,0.467000,-0.867200, 0.718800,0.655200, +0.080737,0.280594,-0.405892,0.000000, 0.161700,0.559600,-0.812800, 0.718800,0.689700, +0.158371,0.280594,-0.382342,0.000000, 0.317100,0.559600,-0.765600, 0.687500,0.689700, +0.086182,0.234204,-0.433268,0.000000, 0.172500,0.467000,-0.867200, 0.718800,0.655200, +0.158371,0.280594,-0.382342,0.000000, 0.317100,0.559600,-0.765600, 0.687500,0.689700, +0.169052,0.234204,-0.408129,0.000000, 0.338400,0.467000,-0.816900, 0.687500,0.655200, +0.050290,-0.428429,-0.252824,0.000000, 0.101000,-0.855300,-0.508100, 0.718800,0.172400, +0.059032,-0.398046,-0.296773,0.000000, 0.118500,-0.794500,-0.595600, 0.718800,0.206900, +0.115795,-0.398046,-0.279554,0.000000, 0.232400,-0.794500,-0.561100, 0.687500,0.206900, +0.050290,-0.428429,-0.252824,0.000000, 0.101000,-0.855300,-0.508100, 0.718800,0.172400, +0.115795,-0.398046,-0.279554,0.000000, 0.232400,-0.794500,-0.561100, 0.687500,0.206900, +0.098646,-0.428429,-0.238155,0.000000, 0.198200,-0.855300,-0.478600, 0.687500,0.172400, +0.169052,-0.234204,-0.408129,0.000000, 0.338400,-0.467000,-0.816900, 0.687500,0.344800, +0.177751,-0.185069,-0.429130,0.000000, 0.355700,-0.369000,-0.858700, 0.687500,0.379300, +0.258055,-0.185069,-0.386207,0.000000, 0.516300,-0.369000,-0.772800, 0.656300,0.379300, +0.169052,-0.234204,-0.408129,0.000000, 0.338400,-0.467000,-0.816900, 0.687500,0.344800, +0.258055,-0.185069,-0.386207,0.000000, 0.516300,-0.369000,-0.772800, 0.656300,0.379300, +0.245426,-0.234204,-0.367306,0.000000, 0.491300,-0.467000,-0.735200, 0.656300,0.344800, +0.115795,0.398046,-0.279554,0.000000, 0.232400,0.794500,-0.561100, 0.687500,0.793100, +0.098646,0.428429,-0.238155,0.000000, 0.198200,0.855300,-0.478600, 0.687500,0.827600, +0.143212,0.428429,-0.214334,0.000000, 0.287800,0.855300,-0.430700, 0.656300,0.827600, +0.115795,0.398046,-0.279554,0.000000, 0.232400,0.794500,-0.561100, 0.687500,0.793100, +0.143212,0.428429,-0.214334,0.000000, 0.287800,0.855300,-0.430700, 0.656300,0.827600, +0.168107,0.398046,-0.251592,0.000000, 0.337400,0.794500,-0.504900, 0.656300,0.793100, +0.158371,-0.280594,-0.382342,0.000000, 0.317100,-0.559600,-0.765600, 0.687500,0.310300, +0.169052,-0.234204,-0.408129,0.000000, 0.338400,-0.467000,-0.816900, 0.687500,0.344800, +0.245426,-0.234204,-0.367306,0.000000, 0.491300,-0.467000,-0.735200, 0.656300,0.344800, +0.158371,-0.280594,-0.382342,0.000000, 0.317100,-0.559600,-0.765600, 0.687500,0.310300, +0.245426,-0.234204,-0.367306,0.000000, 0.491300,-0.467000,-0.735200, 0.656300,0.344800, +0.229919,-0.280594,-0.344099,0.000000, 0.460400,-0.559600,-0.689100, 0.656300,0.310300, +0.131585,0.362998,-0.317675,0.000000, 0.263800,0.724300,-0.637000, 0.687500,0.758600, +0.115795,0.398046,-0.279554,0.000000, 0.232400,0.794500,-0.561100, 0.687500,0.793100, +0.168107,0.398046,-0.251592,0.000000, 0.337400,0.794500,-0.504900, 0.656300,0.793100, +0.131585,0.362998,-0.317675,0.000000, 0.263800,0.724300,-0.637000, 0.687500,0.758600, +0.168107,0.398046,-0.251592,0.000000, 0.337400,0.794500,-0.504900, 0.656300,0.793100, +0.191032,0.362998,-0.285900,0.000000, 0.383000,0.724300,-0.573300, 0.656300,0.758600, +0.145833,-0.323693,-0.352073,0.000000, 0.292200,-0.645700,-0.705400, 0.687500,0.275900, +0.158371,-0.280594,-0.382342,0.000000, 0.317100,-0.559600,-0.765600, 0.687500,0.310300, +0.229919,-0.280594,-0.344099,0.000000, 0.460400,-0.559600,-0.689100, 0.656300,0.310300, +0.145833,-0.323693,-0.352073,0.000000, 0.292200,-0.645700,-0.705400, 0.687500,0.275900, +0.229919,-0.280594,-0.344099,0.000000, 0.460400,-0.559600,-0.689100, 0.656300,0.310300, +0.211717,-0.323693,-0.316857,0.000000, 0.424200,-0.645700,-0.634900, 0.656300,0.275900, +0.145832,0.323693,-0.352073,0.000000, 0.292200,0.645700,-0.705400, 0.687500,0.724100, +0.131585,0.362998,-0.317675,0.000000, 0.263800,0.724300,-0.637000, 0.687500,0.758600, +0.191032,0.362998,-0.285900,0.000000, 0.383000,0.724300,-0.573300, 0.656300,0.758600, +0.145832,0.323693,-0.352073,0.000000, 0.292200,0.645700,-0.705400, 0.687500,0.724100, +0.191032,0.362998,-0.285900,0.000000, 0.383000,0.724300,-0.573300, 0.656300,0.758600, +0.211717,0.323693,-0.316857,0.000000, 0.424200,0.645700,-0.634900, 0.656300,0.724100, +0.131585,-0.362998,-0.317676,0.000000, 0.263800,-0.724300,-0.637000, 0.687500,0.241400, +0.145833,-0.323693,-0.352073,0.000000, 0.292200,-0.645700,-0.705400, 0.687500,0.275900, +0.211717,-0.323693,-0.316857,0.000000, 0.424200,-0.645700,-0.634900, 0.656300,0.275900, +0.131585,-0.362998,-0.317676,0.000000, 0.263800,-0.724300,-0.637000, 0.687500,0.241400, +0.211717,-0.323693,-0.316857,0.000000, 0.424200,-0.645700,-0.634900, 0.656300,0.275900, +0.191032,-0.362998,-0.285900,0.000000, 0.383000,-0.724300,-0.573300, 0.656300,0.241400, +0.158371,0.280594,-0.382342,0.000000, 0.317100,0.559600,-0.765600, 0.687500,0.689700, +0.145832,0.323693,-0.352073,0.000000, 0.292200,0.645700,-0.705400, 0.687500,0.724100, +0.211717,0.323693,-0.316857,0.000000, 0.424200,0.645700,-0.634900, 0.656300,0.724100, +0.158371,0.280594,-0.382342,0.000000, 0.317100,0.559600,-0.765600, 0.687500,0.689700, +0.211717,0.323693,-0.316857,0.000000, 0.424200,0.645700,-0.634900, 0.656300,0.724100, +0.229919,0.280594,-0.344099,0.000000, 0.460400,0.559600,-0.689100, 0.656300,0.689700, +0.115795,-0.398046,-0.279554,0.000000, 0.232400,-0.794500,-0.561100, 0.687500,0.206900, +0.131585,-0.362998,-0.317676,0.000000, 0.263800,-0.724300,-0.637000, 0.687500,0.241400, +0.191032,-0.362998,-0.285900,0.000000, 0.383000,-0.724300,-0.573300, 0.656300,0.241400, +0.115795,-0.398046,-0.279554,0.000000, 0.232400,-0.794500,-0.561100, 0.687500,0.206900, +0.191032,-0.362998,-0.285900,0.000000, 0.383000,-0.724300,-0.573300, 0.656300,0.241400, +0.168108,-0.398046,-0.251592,0.000000, 0.337400,-0.794500,-0.505000, 0.656300,0.206900, +0.169052,0.234204,-0.408129,0.000000, 0.338400,0.467000,-0.816900, 0.687500,0.655200, +0.158371,0.280594,-0.382342,0.000000, 0.317100,0.559600,-0.765600, 0.687500,0.689700, +0.229919,0.280594,-0.344099,0.000000, 0.460400,0.559600,-0.689100, 0.656300,0.689700, +0.169052,0.234204,-0.408129,0.000000, 0.338400,0.467000,-0.816900, 0.687500,0.655200, +0.229919,0.280594,-0.344099,0.000000, 0.460400,0.559600,-0.689100, 0.656300,0.689700, +0.245426,0.234204,-0.367306,0.000000, 0.491300,0.467000,-0.735200, 0.656300,0.655200, +0.098646,-0.428429,-0.238155,0.000000, 0.198200,-0.855300,-0.478600, 0.687500,0.172400, +0.115795,-0.398046,-0.279554,0.000000, 0.232400,-0.794500,-0.561100, 0.687500,0.206900, +0.168108,-0.398046,-0.251592,0.000000, 0.337400,-0.794500,-0.505000, 0.656300,0.206900, +0.098646,-0.428429,-0.238155,0.000000, 0.198200,-0.855300,-0.478600, 0.687500,0.172400, +0.168108,-0.398046,-0.251592,0.000000, 0.337400,-0.794500,-0.505000, 0.656300,0.206900, +0.143212,-0.428429,-0.214334,0.000000, 0.287800,-0.855300,-0.430700, 0.656300,0.172400, +0.177751,0.185069,-0.429130,0.000000, 0.355700,0.369000,-0.858700, 0.687500,0.620700, +0.169052,0.234204,-0.408129,0.000000, 0.338400,0.467000,-0.816900, 0.687500,0.655200, +0.245426,0.234204,-0.367306,0.000000, 0.491300,0.467000,-0.735200, 0.656300,0.655200, +0.177751,0.185069,-0.429130,0.000000, 0.355700,0.369000,-0.858700, 0.687500,0.620700, +0.245426,0.234204,-0.367306,0.000000, 0.491300,0.467000,-0.735200, 0.656300,0.655200, +0.258055,0.185069,-0.386207,0.000000, 0.516300,0.369000,-0.772800, 0.656300,0.620700, +0.080342,-0.453788,-0.193963,0.000000, 0.161700,-0.906300,-0.390500, 0.687500,0.137900, +0.098646,-0.428429,-0.238155,0.000000, 0.198200,-0.855300,-0.478600, 0.687500,0.172400, +0.143212,-0.428429,-0.214334,0.000000, 0.287800,-0.855300,-0.430700, 0.656300,0.172400, +0.080342,-0.453788,-0.193963,0.000000, 0.161700,-0.906300,-0.390500, 0.687500,0.137900, +0.143212,-0.428429,-0.214334,0.000000, 0.287800,-0.855300,-0.430700, 0.656300,0.172400, +0.116638,-0.453788,-0.174562,0.000000, 0.234800,-0.906300,-0.351400, 0.656300,0.137900, +0.184366,0.133764,-0.445101,0.000000, 0.368800,0.266600,-0.890400, 0.687500,0.586200, +0.177751,0.185069,-0.429130,0.000000, 0.355700,0.369000,-0.858700, 0.687500,0.620700, +0.258055,0.185069,-0.386207,0.000000, 0.516300,0.369000,-0.772800, 0.656300,0.620700, +0.184366,0.133764,-0.445101,0.000000, 0.368800,0.266600,-0.890400, 0.687500,0.586200, +0.258055,0.185069,-0.386207,0.000000, 0.516300,0.369000,-0.772800, 0.656300,0.620700, +0.267659,0.133764,-0.400580,0.000000, 0.535400,0.266600,-0.801400, 0.656300,0.586200, +0.061095,-0.473826,-0.147498,0.000000, 0.123300,-0.946600,-0.297800, 0.687500,0.103400, +0.080342,-0.453788,-0.193963,0.000000, 0.161700,-0.906300,-0.390500, 0.687500,0.137900, +0.116638,-0.453788,-0.174562,0.000000, 0.234800,-0.906300,-0.351400, 0.656300,0.137900, +0.061095,-0.473826,-0.147498,0.000000, 0.123300,-0.946600,-0.297800, 0.687500,0.103400, +0.116638,-0.453788,-0.174562,0.000000, 0.234800,-0.906300,-0.351400, 0.656300,0.137900, +0.088697,-0.473826,-0.132745,0.000000, 0.179100,-0.946600,-0.268000, 0.656300,0.103400, +0.188820,0.080891,-0.455854,0.000000, 0.377700,0.161200,-0.911800, 0.687500,0.551700, +0.184366,0.133764,-0.445101,0.000000, 0.368800,0.266600,-0.890400, 0.687500,0.586200, +0.267659,0.133764,-0.400580,0.000000, 0.535400,0.266600,-0.801400, 0.656300,0.586200, +0.188820,0.080891,-0.455854,0.000000, 0.377700,0.161200,-0.911800, 0.687500,0.551700, +0.267659,0.133764,-0.400580,0.000000, 0.535400,0.266600,-0.801400, 0.656300,0.586200, +0.274125,0.080891,-0.410257,0.000000, 0.548300,0.161200,-0.820600, 0.656300,0.551700, +0.041132,-0.488310,-0.099303,0.000000, 0.083500,-0.975900,-0.201600, 0.687500,0.069000, +0.061095,-0.473826,-0.147498,0.000000, 0.123300,-0.946600,-0.297800, 0.687500,0.103400, +0.088697,-0.473826,-0.132745,0.000000, 0.179100,-0.946600,-0.268000, 0.656300,0.103400, +0.041132,-0.488310,-0.099303,0.000000, 0.083500,-0.975900,-0.201600, 0.687500,0.069000, +0.088697,-0.473826,-0.132745,0.000000, 0.179100,-0.946600,-0.268000, 0.656300,0.103400, +0.059715,-0.488310,-0.089370,0.000000, 0.121200,-0.975900,-0.181400, 0.656300,0.069000, +0.191060,0.027069,-0.461262,0.000000, 0.382100,0.054000,-0.922500, 0.687500,0.517200, +0.188820,0.080891,-0.455854,0.000000, 0.377700,0.161200,-0.911800, 0.687500,0.551700, +0.274125,0.080891,-0.410257,0.000000, 0.548300,0.161200,-0.820600, 0.656300,0.551700, +0.191060,0.027069,-0.461262,0.000000, 0.382100,0.054000,-0.922500, 0.687500,0.517200, +0.274125,0.080891,-0.410257,0.000000, 0.548300,0.161200,-0.820600, 0.656300,0.551700, +0.277377,0.027069,-0.415125,0.000000, 0.554700,0.054000,-0.830300, 0.656300,0.517200, +0.020687,0.497069,-0.049944,0.000000, 0.042600,0.993700,-0.103000, 0.445300,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +0.030033,0.497069,-0.044948,0.000000, 0.061900,0.993700,-0.092700, 0.447100,0.962300, +0.020687,-0.497069,-0.049945,0.000000, 0.042600,-0.993700,-0.103000, 0.687500,0.034500, +0.041132,-0.488310,-0.099303,0.000000, 0.083500,-0.975900,-0.201600, 0.687500,0.069000, +0.059715,-0.488310,-0.089370,0.000000, 0.121200,-0.975900,-0.181400, 0.656300,0.069000, +0.020687,-0.497069,-0.049945,0.000000, 0.042600,-0.993700,-0.103000, 0.687500,0.034500, +0.059715,-0.488310,-0.089370,0.000000, 0.121200,-0.975900,-0.181400, 0.656300,0.069000, +0.030034,-0.497069,-0.044949,0.000000, 0.061900,-0.993700,-0.092700, 0.656300,0.034500, +0.191060,-0.027069,-0.461262,0.000000, 0.382100,-0.054000,-0.922500, 0.687500,0.482800, +0.191060,0.027069,-0.461262,0.000000, 0.382100,0.054000,-0.922500, 0.687500,0.517200, +0.277377,0.027069,-0.415125,0.000000, 0.554700,0.054000,-0.830300, 0.656300,0.517200, +0.191060,-0.027069,-0.461262,0.000000, 0.382100,-0.054000,-0.922500, 0.687500,0.482800, +0.277377,0.027069,-0.415125,0.000000, 0.554700,0.054000,-0.830300, 0.656300,0.517200, +0.277377,-0.027069,-0.415125,0.000000, 0.554700,-0.054000,-0.830300, 0.656300,0.482800, +0.041132,0.488310,-0.099303,0.000000, 0.083500,0.975900,-0.201600, 0.687500,0.931000, +0.020687,0.497069,-0.049944,0.000000, 0.042600,0.993700,-0.103000, 0.687500,0.965500, +0.030033,0.497069,-0.044948,0.000000, 0.061900,0.993700,-0.092700, 0.656300,0.965500, +0.041132,0.488310,-0.099303,0.000000, 0.083500,0.975900,-0.201600, 0.687500,0.931000, +0.030033,0.497069,-0.044948,0.000000, 0.061900,0.993700,-0.092700, 0.656300,0.965500, +0.059715,0.488310,-0.089370,0.000000, 0.121200,0.975900,-0.181400, 0.656300,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +0.020687,-0.497069,-0.049945,0.000000, 0.042600,-0.993700,-0.103000, 0.468000,0.053800, +0.030034,-0.497069,-0.044949,0.000000, 0.061900,-0.993700,-0.092700, 0.465400,0.053800, +0.188820,-0.080891,-0.455854,0.000000, 0.377700,-0.161200,-0.911800, 0.687500,0.448300, +0.191060,-0.027069,-0.461262,0.000000, 0.382100,-0.054000,-0.922500, 0.687500,0.482800, +0.277377,-0.027069,-0.415125,0.000000, 0.554700,-0.054000,-0.830300, 0.656300,0.482800, +0.188820,-0.080891,-0.455854,0.000000, 0.377700,-0.161200,-0.911800, 0.687500,0.448300, +0.277377,-0.027069,-0.415125,0.000000, 0.554700,-0.054000,-0.830300, 0.656300,0.482800, +0.274125,-0.080891,-0.410257,0.000000, 0.548300,-0.161200,-0.820600, 0.656300,0.448300, +0.061095,0.473826,-0.147498,0.000000, 0.123300,0.946600,-0.297800, 0.687500,0.896600, +0.041132,0.488310,-0.099303,0.000000, 0.083500,0.975900,-0.201600, 0.687500,0.931000, +0.059715,0.488310,-0.089370,0.000000, 0.121200,0.975900,-0.181400, 0.656300,0.931000, +0.061095,0.473826,-0.147498,0.000000, 0.123300,0.946600,-0.297800, 0.687500,0.896600, +0.059715,0.488310,-0.089370,0.000000, 0.121200,0.975900,-0.181400, 0.656300,0.931000, +0.088697,0.473826,-0.132745,0.000000, 0.179100,0.946600,-0.268000, 0.656300,0.896600, +0.184366,-0.133764,-0.445101,0.000000, 0.368800,-0.266600,-0.890400, 0.687500,0.413800, +0.188820,-0.080891,-0.455854,0.000000, 0.377700,-0.161200,-0.911800, 0.687500,0.448300, +0.274125,-0.080891,-0.410257,0.000000, 0.548300,-0.161200,-0.820600, 0.656300,0.448300, +0.184366,-0.133764,-0.445101,0.000000, 0.368800,-0.266600,-0.890400, 0.687500,0.413800, +0.274125,-0.080891,-0.410257,0.000000, 0.548300,-0.161200,-0.820600, 0.656300,0.448300, +0.267659,-0.133764,-0.400580,0.000000, 0.535400,-0.266600,-0.801400, 0.656300,0.413800, +0.080342,0.453788,-0.193963,0.000000, 0.161700,0.906300,-0.390500, 0.687500,0.862100, +0.061095,0.473826,-0.147498,0.000000, 0.123300,0.946600,-0.297800, 0.687500,0.896600, +0.088697,0.473826,-0.132745,0.000000, 0.179100,0.946600,-0.268000, 0.656300,0.896600, +0.080342,0.453788,-0.193963,0.000000, 0.161700,0.906300,-0.390500, 0.687500,0.862100, +0.088697,0.473826,-0.132745,0.000000, 0.179100,0.946600,-0.268000, 0.656300,0.896600, +0.116638,0.453788,-0.174562,0.000000, 0.234800,0.906300,-0.351400, 0.656300,0.862100, +0.177751,-0.185069,-0.429130,0.000000, 0.355700,-0.369000,-0.858700, 0.687500,0.379300, +0.184366,-0.133764,-0.445101,0.000000, 0.368800,-0.266600,-0.890400, 0.687500,0.413800, +0.267659,-0.133764,-0.400580,0.000000, 0.535400,-0.266600,-0.801400, 0.656300,0.413800, +0.177751,-0.185069,-0.429130,0.000000, 0.355700,-0.369000,-0.858700, 0.687500,0.379300, +0.267659,-0.133764,-0.400580,0.000000, 0.535400,-0.266600,-0.801400, 0.656300,0.413800, +0.258055,-0.185069,-0.386207,0.000000, 0.516300,-0.369000,-0.772800, 0.656300,0.379300, +0.098646,0.428429,-0.238155,0.000000, 0.198200,0.855300,-0.478600, 0.687500,0.827600, +0.080342,0.453788,-0.193963,0.000000, 0.161700,0.906300,-0.390500, 0.687500,0.862100, +0.116638,0.453788,-0.174562,0.000000, 0.234800,0.906300,-0.351400, 0.656300,0.862100, +0.098646,0.428429,-0.238155,0.000000, 0.198200,0.855300,-0.478600, 0.687500,0.827600, +0.116638,0.453788,-0.174562,0.000000, 0.234800,0.906300,-0.351400, 0.656300,0.862100, +0.143212,0.428429,-0.214334,0.000000, 0.287800,0.855300,-0.430700, 0.656300,0.827600, +0.059715,-0.488310,-0.089370,0.000000, 0.121200,-0.975900,-0.181400, 0.656300,0.069000, +0.088697,-0.473826,-0.132745,0.000000, 0.179100,-0.946600,-0.268000, 0.656300,0.103400, +0.112889,-0.473826,-0.112890,0.000000, 0.227900,-0.946600,-0.227900, 0.625000,0.103400, +0.059715,-0.488310,-0.089370,0.000000, 0.121200,-0.975900,-0.181400, 0.656300,0.069000, +0.112889,-0.473826,-0.112890,0.000000, 0.227900,-0.946600,-0.227900, 0.625000,0.103400, +0.076003,-0.488310,-0.076003,0.000000, 0.154300,-0.975900,-0.154300, 0.625000,0.069000, +0.277377,0.027069,-0.415125,0.000000, 0.554700,0.054000,-0.830300, 0.656300,0.517200, +0.274125,0.080891,-0.410257,0.000000, 0.548300,0.161200,-0.820600, 0.656300,0.551700, +0.348895,0.080891,-0.348895,0.000000, 0.697800,0.161200,-0.697800, 0.625000,0.551700, +0.277377,0.027069,-0.415125,0.000000, 0.554700,0.054000,-0.830300, 0.656300,0.517200, +0.348895,0.080891,-0.348895,0.000000, 0.697800,0.161200,-0.697800, 0.625000,0.551700, +0.353034,0.027069,-0.353034,0.000000, 0.706100,0.054000,-0.706100, 0.625000,0.517200, +0.030033,0.497069,-0.044948,0.000000, 0.061900,0.993700,-0.092700, 0.447100,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +0.038225,0.497069,-0.038226,0.000000, 0.078800,0.993700,-0.078800, 0.449000,0.962300, +0.030034,-0.497069,-0.044949,0.000000, 0.061900,-0.993700,-0.092700, 0.656300,0.034500, +0.059715,-0.488310,-0.089370,0.000000, 0.121200,-0.975900,-0.181400, 0.656300,0.069000, +0.076003,-0.488310,-0.076003,0.000000, 0.154300,-0.975900,-0.154300, 0.625000,0.069000, +0.030034,-0.497069,-0.044949,0.000000, 0.061900,-0.993700,-0.092700, 0.656300,0.034500, +0.076003,-0.488310,-0.076003,0.000000, 0.154300,-0.975900,-0.154300, 0.625000,0.069000, +0.038226,-0.497069,-0.038226,0.000000, 0.078800,-0.993700,-0.078800, 0.625000,0.034500, +0.277377,-0.027069,-0.415125,0.000000, 0.554700,-0.054000,-0.830300, 0.656300,0.482800, +0.277377,0.027069,-0.415125,0.000000, 0.554700,0.054000,-0.830300, 0.656300,0.517200, +0.353034,0.027069,-0.353034,0.000000, 0.706100,0.054000,-0.706100, 0.625000,0.517200, +0.277377,-0.027069,-0.415125,0.000000, 0.554700,-0.054000,-0.830300, 0.656300,0.482800, +0.353034,0.027069,-0.353034,0.000000, 0.706100,0.054000,-0.706100, 0.625000,0.517200, +0.353034,-0.027069,-0.353034,0.000000, 0.706100,-0.054000,-0.706100, 0.625000,0.482800, +0.059715,0.488310,-0.089370,0.000000, 0.121200,0.975900,-0.181400, 0.656300,0.931000, +0.030033,0.497069,-0.044948,0.000000, 0.061900,0.993700,-0.092700, 0.656300,0.965500, +0.038225,0.497069,-0.038226,0.000000, 0.078800,0.993700,-0.078800, 0.625000,0.965500, +0.059715,0.488310,-0.089370,0.000000, 0.121200,0.975900,-0.181400, 0.656300,0.931000, +0.038225,0.497069,-0.038226,0.000000, 0.078800,0.993700,-0.078800, 0.625000,0.965500, +0.076003,0.488310,-0.076003,0.000000, 0.154300,0.975900,-0.154300, 0.625000,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +0.030034,-0.497069,-0.044949,0.000000, 0.061900,-0.993700,-0.092700, 0.465400,0.053800, +0.038226,-0.497069,-0.038226,0.000000, 0.078800,-0.993700,-0.078800, 0.462800,0.053800, +0.274125,-0.080891,-0.410257,0.000000, 0.548300,-0.161200,-0.820600, 0.656300,0.448300, +0.277377,-0.027069,-0.415125,0.000000, 0.554700,-0.054000,-0.830300, 0.656300,0.482800, +0.353034,-0.027069,-0.353034,0.000000, 0.706100,-0.054000,-0.706100, 0.625000,0.482800, +0.274125,-0.080891,-0.410257,0.000000, 0.548300,-0.161200,-0.820600, 0.656300,0.448300, +0.353034,-0.027069,-0.353034,0.000000, 0.706100,-0.054000,-0.706100, 0.625000,0.482800, +0.348895,-0.080891,-0.348895,0.000000, 0.697800,-0.161200,-0.697800, 0.625000,0.448300, +0.088697,0.473826,-0.132745,0.000000, 0.179100,0.946600,-0.268000, 0.656300,0.896600, +0.059715,0.488310,-0.089370,0.000000, 0.121200,0.975900,-0.181400, 0.656300,0.931000, +0.076003,0.488310,-0.076003,0.000000, 0.154300,0.975900,-0.154300, 0.625000,0.931000, +0.088697,0.473826,-0.132745,0.000000, 0.179100,0.946600,-0.268000, 0.656300,0.896600, +0.076003,0.488310,-0.076003,0.000000, 0.154300,0.975900,-0.154300, 0.625000,0.931000, +0.112889,0.473826,-0.112890,0.000000, 0.227900,0.946600,-0.227900, 0.625000,0.896600, +0.267659,-0.133764,-0.400580,0.000000, 0.535400,-0.266600,-0.801400, 0.656300,0.413800, +0.274125,-0.080891,-0.410257,0.000000, 0.548300,-0.161200,-0.820600, 0.656300,0.448300, +0.348895,-0.080891,-0.348895,0.000000, 0.697800,-0.161200,-0.697800, 0.625000,0.448300, +0.267659,-0.133764,-0.400580,0.000000, 0.535400,-0.266600,-0.801400, 0.656300,0.413800, +0.348895,-0.080891,-0.348895,0.000000, 0.697800,-0.161200,-0.697800, 0.625000,0.448300, +0.340665,-0.133764,-0.340666,0.000000, 0.681500,-0.266600,-0.681500, 0.625000,0.413800, +0.116638,0.453788,-0.174562,0.000000, 0.234800,0.906300,-0.351400, 0.656300,0.862100, +0.088697,0.473826,-0.132745,0.000000, 0.179100,0.946600,-0.268000, 0.656300,0.896600, +0.112889,0.473826,-0.112890,0.000000, 0.227900,0.946600,-0.227900, 0.625000,0.896600, +0.116638,0.453788,-0.174562,0.000000, 0.234800,0.906300,-0.351400, 0.656300,0.862100, +0.112889,0.473826,-0.112890,0.000000, 0.227900,0.946600,-0.227900, 0.625000,0.896600, +0.148453,0.453788,-0.148453,0.000000, 0.298900,0.906300,-0.298900, 0.625000,0.862100, +0.258055,-0.185069,-0.386207,0.000000, 0.516300,-0.369000,-0.772800, 0.656300,0.379300, +0.267659,-0.133764,-0.400580,0.000000, 0.535400,-0.266600,-0.801400, 0.656300,0.413800, +0.340665,-0.133764,-0.340666,0.000000, 0.681500,-0.266600,-0.681500, 0.625000,0.413800, +0.258055,-0.185069,-0.386207,0.000000, 0.516300,-0.369000,-0.772800, 0.656300,0.379300, +0.340665,-0.133764,-0.340666,0.000000, 0.681500,-0.266600,-0.681500, 0.625000,0.413800, +0.328442,-0.185069,-0.328443,0.000000, 0.657200,-0.369000,-0.657200, 0.625000,0.379300, +0.143212,0.428429,-0.214334,0.000000, 0.287800,0.855300,-0.430700, 0.656300,0.827600, +0.116638,0.453788,-0.174562,0.000000, 0.234800,0.906300,-0.351400, 0.656300,0.862100, +0.148453,0.453788,-0.148453,0.000000, 0.298900,0.906300,-0.298900, 0.625000,0.862100, +0.143212,0.428429,-0.214334,0.000000, 0.287800,0.855300,-0.430700, 0.656300,0.827600, +0.148453,0.453788,-0.148453,0.000000, 0.298900,0.906300,-0.298900, 0.625000,0.862100, +0.182275,0.428429,-0.182276,0.000000, 0.366300,0.855300,-0.366300, 0.625000,0.827600, +0.245426,-0.234204,-0.367306,0.000000, 0.491300,-0.467000,-0.735200, 0.656300,0.344800, +0.258055,-0.185069,-0.386207,0.000000, 0.516300,-0.369000,-0.772800, 0.656300,0.379300, +0.328442,-0.185069,-0.328443,0.000000, 0.657200,-0.369000,-0.657200, 0.625000,0.379300, +0.245426,-0.234204,-0.367306,0.000000, 0.491300,-0.467000,-0.735200, 0.656300,0.344800, +0.328442,-0.185069,-0.328443,0.000000, 0.657200,-0.369000,-0.657200, 0.625000,0.379300, +0.312368,-0.234204,-0.312368,0.000000, 0.625200,-0.467000,-0.625200, 0.625000,0.344800, +0.168107,0.398046,-0.251592,0.000000, 0.337400,0.794500,-0.504900, 0.656300,0.793100, +0.143212,0.428429,-0.214334,0.000000, 0.287800,0.855300,-0.430700, 0.656300,0.827600, +0.182275,0.428429,-0.182276,0.000000, 0.366300,0.855300,-0.366300, 0.625000,0.827600, +0.168107,0.398046,-0.251592,0.000000, 0.337400,0.794500,-0.504900, 0.656300,0.793100, +0.182275,0.428429,-0.182276,0.000000, 0.366300,0.855300,-0.366300, 0.625000,0.827600, +0.213960,0.398046,-0.213961,0.000000, 0.429400,0.794500,-0.429400, 0.625000,0.793100, +0.229919,-0.280594,-0.344099,0.000000, 0.460400,-0.559600,-0.689100, 0.656300,0.310300, +0.245426,-0.234204,-0.367306,0.000000, 0.491300,-0.467000,-0.735200, 0.656300,0.344800, +0.312368,-0.234204,-0.312368,0.000000, 0.625200,-0.467000,-0.625200, 0.625000,0.344800, +0.229919,-0.280594,-0.344099,0.000000, 0.460400,-0.559600,-0.689100, 0.656300,0.310300, +0.312368,-0.234204,-0.312368,0.000000, 0.625200,-0.467000,-0.625200, 0.625000,0.344800, +0.292632,-0.280594,-0.292632,0.000000, 0.586000,-0.559600,-0.586000, 0.625000,0.310300, +0.191032,0.362998,-0.285900,0.000000, 0.383000,0.724300,-0.573300, 0.656300,0.758600, +0.168107,0.398046,-0.251592,0.000000, 0.337400,0.794500,-0.504900, 0.656300,0.793100, +0.213960,0.398046,-0.213961,0.000000, 0.429400,0.794500,-0.429400, 0.625000,0.793100, +0.191032,0.362998,-0.285900,0.000000, 0.383000,0.724300,-0.573300, 0.656300,0.758600, +0.213960,0.398046,-0.213961,0.000000, 0.429400,0.794500,-0.429400, 0.625000,0.793100, +0.243137,0.362998,-0.243138,0.000000, 0.487500,0.724300,-0.487500, 0.625000,0.758600, +0.211717,-0.323693,-0.316857,0.000000, 0.424200,-0.645700,-0.634900, 0.656300,0.275900, +0.229919,-0.280594,-0.344099,0.000000, 0.460400,-0.559600,-0.689100, 0.656300,0.310300, +0.292632,-0.280594,-0.292632,0.000000, 0.586000,-0.559600,-0.586000, 0.625000,0.310300, +0.211717,-0.323693,-0.316857,0.000000, 0.424200,-0.645700,-0.634900, 0.656300,0.275900, +0.292632,-0.280594,-0.292632,0.000000, 0.586000,-0.559600,-0.586000, 0.625000,0.310300, +0.269464,-0.323693,-0.269464,0.000000, 0.539900,-0.645700,-0.539900, 0.625000,0.275900, +0.211717,0.323693,-0.316857,0.000000, 0.424200,0.645700,-0.634900, 0.656300,0.724100, +0.191032,0.362998,-0.285900,0.000000, 0.383000,0.724300,-0.573300, 0.656300,0.758600, +0.243137,0.362998,-0.243138,0.000000, 0.487500,0.724300,-0.487500, 0.625000,0.758600, +0.211717,0.323693,-0.316857,0.000000, 0.424200,0.645700,-0.634900, 0.656300,0.724100, +0.243137,0.362998,-0.243138,0.000000, 0.487500,0.724300,-0.487500, 0.625000,0.758600, +0.269464,0.323693,-0.269464,0.000000, 0.539900,0.645700,-0.539900, 0.625000,0.724100, +0.191032,-0.362998,-0.285900,0.000000, 0.383000,-0.724300,-0.573300, 0.656300,0.241400, +0.211717,-0.323693,-0.316857,0.000000, 0.424200,-0.645700,-0.634900, 0.656300,0.275900, +0.269464,-0.323693,-0.269464,0.000000, 0.539900,-0.645700,-0.539900, 0.625000,0.275900, +0.191032,-0.362998,-0.285900,0.000000, 0.383000,-0.724300,-0.573300, 0.656300,0.241400, +0.269464,-0.323693,-0.269464,0.000000, 0.539900,-0.645700,-0.539900, 0.625000,0.275900, +0.243137,-0.362998,-0.243138,0.000000, 0.487500,-0.724300,-0.487500, 0.625000,0.241400, +0.229919,0.280594,-0.344099,0.000000, 0.460400,0.559600,-0.689100, 0.656300,0.689700, +0.211717,0.323693,-0.316857,0.000000, 0.424200,0.645700,-0.634900, 0.656300,0.724100, +0.269464,0.323693,-0.269464,0.000000, 0.539900,0.645700,-0.539900, 0.625000,0.724100, +0.229919,0.280594,-0.344099,0.000000, 0.460400,0.559600,-0.689100, 0.656300,0.689700, +0.269464,0.323693,-0.269464,0.000000, 0.539900,0.645700,-0.539900, 0.625000,0.724100, +0.292632,0.280594,-0.292632,0.000000, 0.586000,0.559600,-0.586000, 0.625000,0.689700, +0.168108,-0.398046,-0.251592,0.000000, 0.337400,-0.794500,-0.505000, 0.656300,0.206900, +0.191032,-0.362998,-0.285900,0.000000, 0.383000,-0.724300,-0.573300, 0.656300,0.241400, +0.243137,-0.362998,-0.243138,0.000000, 0.487500,-0.724300,-0.487500, 0.625000,0.241400, +0.168108,-0.398046,-0.251592,0.000000, 0.337400,-0.794500,-0.505000, 0.656300,0.206900, +0.243137,-0.362998,-0.243138,0.000000, 0.487500,-0.724300,-0.487500, 0.625000,0.241400, +0.213960,-0.398046,-0.213961,0.000000, 0.429400,-0.794500,-0.429400, 0.625000,0.206900, +0.245426,0.234204,-0.367306,0.000000, 0.491300,0.467000,-0.735200, 0.656300,0.655200, +0.229919,0.280594,-0.344099,0.000000, 0.460400,0.559600,-0.689100, 0.656300,0.689700, +0.292632,0.280594,-0.292632,0.000000, 0.586000,0.559600,-0.586000, 0.625000,0.689700, +0.245426,0.234204,-0.367306,0.000000, 0.491300,0.467000,-0.735200, 0.656300,0.655200, +0.292632,0.280594,-0.292632,0.000000, 0.586000,0.559600,-0.586000, 0.625000,0.689700, +0.312368,0.234204,-0.312368,0.000000, 0.625200,0.467000,-0.625200, 0.625000,0.655200, +0.143212,-0.428429,-0.214334,0.000000, 0.287800,-0.855300,-0.430700, 0.656300,0.172400, +0.168108,-0.398046,-0.251592,0.000000, 0.337400,-0.794500,-0.505000, 0.656300,0.206900, +0.213960,-0.398046,-0.213961,0.000000, 0.429400,-0.794500,-0.429400, 0.625000,0.206900, +0.143212,-0.428429,-0.214334,0.000000, 0.287800,-0.855300,-0.430700, 0.656300,0.172400, +0.213960,-0.398046,-0.213961,0.000000, 0.429400,-0.794500,-0.429400, 0.625000,0.206900, +0.182275,-0.428429,-0.182276,0.000000, 0.366300,-0.855300,-0.366300, 0.625000,0.172400, +0.258055,0.185069,-0.386207,0.000000, 0.516300,0.369000,-0.772800, 0.656300,0.620700, +0.245426,0.234204,-0.367306,0.000000, 0.491300,0.467000,-0.735200, 0.656300,0.655200, +0.312368,0.234204,-0.312368,0.000000, 0.625200,0.467000,-0.625200, 0.625000,0.655200, +0.258055,0.185069,-0.386207,0.000000, 0.516300,0.369000,-0.772800, 0.656300,0.620700, +0.312368,0.234204,-0.312368,0.000000, 0.625200,0.467000,-0.625200, 0.625000,0.655200, +0.328442,0.185069,-0.328443,0.000000, 0.657200,0.369000,-0.657200, 0.625000,0.620700, +0.116638,-0.453788,-0.174562,0.000000, 0.234800,-0.906300,-0.351400, 0.656300,0.137900, +0.143212,-0.428429,-0.214334,0.000000, 0.287800,-0.855300,-0.430700, 0.656300,0.172400, +0.182275,-0.428429,-0.182276,0.000000, 0.366300,-0.855300,-0.366300, 0.625000,0.172400, +0.116638,-0.453788,-0.174562,0.000000, 0.234800,-0.906300,-0.351400, 0.656300,0.137900, +0.182275,-0.428429,-0.182276,0.000000, 0.366300,-0.855300,-0.366300, 0.625000,0.172400, +0.148453,-0.453788,-0.148453,0.000000, 0.298900,-0.906300,-0.298900, 0.625000,0.137900, +0.267659,0.133764,-0.400580,0.000000, 0.535400,0.266600,-0.801400, 0.656300,0.586200, +0.258055,0.185069,-0.386207,0.000000, 0.516300,0.369000,-0.772800, 0.656300,0.620700, +0.328442,0.185069,-0.328443,0.000000, 0.657200,0.369000,-0.657200, 0.625000,0.620700, +0.267659,0.133764,-0.400580,0.000000, 0.535400,0.266600,-0.801400, 0.656300,0.586200, +0.328442,0.185069,-0.328443,0.000000, 0.657200,0.369000,-0.657200, 0.625000,0.620700, +0.340665,0.133764,-0.340666,0.000000, 0.681500,0.266600,-0.681500, 0.625000,0.586200, +0.088697,-0.473826,-0.132745,0.000000, 0.179100,-0.946600,-0.268000, 0.656300,0.103400, +0.116638,-0.453788,-0.174562,0.000000, 0.234800,-0.906300,-0.351400, 0.656300,0.137900, +0.148453,-0.453788,-0.148453,0.000000, 0.298900,-0.906300,-0.298900, 0.625000,0.137900, +0.088697,-0.473826,-0.132745,0.000000, 0.179100,-0.946600,-0.268000, 0.656300,0.103400, +0.148453,-0.453788,-0.148453,0.000000, 0.298900,-0.906300,-0.298900, 0.625000,0.137900, +0.112889,-0.473826,-0.112890,0.000000, 0.227900,-0.946600,-0.227900, 0.625000,0.103400, +0.274125,0.080891,-0.410257,0.000000, 0.548300,0.161200,-0.820600, 0.656300,0.551700, +0.267659,0.133764,-0.400580,0.000000, 0.535400,0.266600,-0.801400, 0.656300,0.586200, +0.340665,0.133764,-0.340666,0.000000, 0.681500,0.266600,-0.681500, 0.625000,0.586200, +0.274125,0.080891,-0.410257,0.000000, 0.548300,0.161200,-0.820600, 0.656300,0.551700, +0.340665,0.133764,-0.340666,0.000000, 0.681500,0.266600,-0.681500, 0.625000,0.586200, +0.348895,0.080891,-0.348895,0.000000, 0.697800,0.161200,-0.697800, 0.625000,0.551700, +0.269464,0.323693,-0.269464,0.000000, 0.539900,0.645700,-0.539900, 0.625000,0.724100, +0.243137,0.362998,-0.243138,0.000000, 0.487500,0.724300,-0.487500, 0.625000,0.758600, +0.285899,0.362998,-0.191032,0.000000, 0.573300,0.724300,-0.383000, 0.593800,0.758600, +0.269464,0.323693,-0.269464,0.000000, 0.539900,0.645700,-0.539900, 0.625000,0.724100, +0.285899,0.362998,-0.191032,0.000000, 0.573300,0.724300,-0.383000, 0.593800,0.758600, +0.316857,0.323693,-0.211717,0.000000, 0.634900,0.645700,-0.424200, 0.593800,0.724100, +0.243137,-0.362998,-0.243138,0.000000, 0.487500,-0.724300,-0.487500, 0.625000,0.241400, +0.269464,-0.323693,-0.269464,0.000000, 0.539900,-0.645700,-0.539900, 0.625000,0.275900, +0.316857,-0.323693,-0.211717,0.000000, 0.634900,-0.645700,-0.424200, 0.593800,0.275900, +0.243137,-0.362998,-0.243138,0.000000, 0.487500,-0.724300,-0.487500, 0.625000,0.241400, +0.316857,-0.323693,-0.211717,0.000000, 0.634900,-0.645700,-0.424200, 0.593800,0.275900, +0.285900,-0.362998,-0.191032,0.000000, 0.573300,-0.724300,-0.383000, 0.593800,0.241400, +0.292632,0.280594,-0.292632,0.000000, 0.586000,0.559600,-0.586000, 0.625000,0.689700, +0.269464,0.323693,-0.269464,0.000000, 0.539900,0.645700,-0.539900, 0.625000,0.724100, +0.316857,0.323693,-0.211717,0.000000, 0.634900,0.645700,-0.424200, 0.593800,0.724100, +0.292632,0.280594,-0.292632,0.000000, 0.586000,0.559600,-0.586000, 0.625000,0.689700, +0.316857,0.323693,-0.211717,0.000000, 0.634900,0.645700,-0.424200, 0.593800,0.724100, +0.344098,0.280594,-0.229919,0.000000, 0.689100,0.559600,-0.460400, 0.593800,0.689700, +0.213960,-0.398046,-0.213961,0.000000, 0.429400,-0.794500,-0.429400, 0.625000,0.206900, +0.243137,-0.362998,-0.243138,0.000000, 0.487500,-0.724300,-0.487500, 0.625000,0.241400, +0.285900,-0.362998,-0.191032,0.000000, 0.573300,-0.724300,-0.383000, 0.593800,0.241400, +0.213960,-0.398046,-0.213961,0.000000, 0.429400,-0.794500,-0.429400, 0.625000,0.206900, +0.285900,-0.362998,-0.191032,0.000000, 0.573300,-0.724300,-0.383000, 0.593800,0.241400, +0.251591,-0.398046,-0.168108,0.000000, 0.505000,-0.794500,-0.337400, 0.593800,0.206900, +0.312368,0.234204,-0.312368,0.000000, 0.625200,0.467000,-0.625200, 0.625000,0.655200, +0.292632,0.280594,-0.292632,0.000000, 0.586000,0.559600,-0.586000, 0.625000,0.689700, +0.344098,0.280594,-0.229919,0.000000, 0.689100,0.559600,-0.460400, 0.593800,0.689700, +0.312368,0.234204,-0.312368,0.000000, 0.625200,0.467000,-0.625200, 0.625000,0.655200, +0.344098,0.280594,-0.229919,0.000000, 0.689100,0.559600,-0.460400, 0.593800,0.689700, +0.367306,0.234204,-0.245426,0.000000, 0.735200,0.467000,-0.491300, 0.593800,0.655200, +0.182275,-0.428429,-0.182276,0.000000, 0.366300,-0.855300,-0.366300, 0.625000,0.172400, +0.213960,-0.398046,-0.213961,0.000000, 0.429400,-0.794500,-0.429400, 0.625000,0.206900, +0.251591,-0.398046,-0.168108,0.000000, 0.505000,-0.794500,-0.337400, 0.593800,0.206900, +0.182275,-0.428429,-0.182276,0.000000, 0.366300,-0.855300,-0.366300, 0.625000,0.172400, +0.251591,-0.398046,-0.168108,0.000000, 0.505000,-0.794500,-0.337400, 0.593800,0.206900, +0.214333,-0.428429,-0.143213,0.000000, 0.430700,-0.855300,-0.287800, 0.593800,0.172400, +0.328442,0.185069,-0.328443,0.000000, 0.657200,0.369000,-0.657200, 0.625000,0.620700, +0.312368,0.234204,-0.312368,0.000000, 0.625200,0.467000,-0.625200, 0.625000,0.655200, +0.367306,0.234204,-0.245426,0.000000, 0.735200,0.467000,-0.491300, 0.593800,0.655200, +0.328442,0.185069,-0.328443,0.000000, 0.657200,0.369000,-0.657200, 0.625000,0.620700, +0.367306,0.234204,-0.245426,0.000000, 0.735200,0.467000,-0.491300, 0.593800,0.655200, +0.386207,0.185069,-0.258056,0.000000, 0.772800,0.369000,-0.516300, 0.593800,0.620700, +0.148453,-0.453788,-0.148453,0.000000, 0.298900,-0.906300,-0.298900, 0.625000,0.137900, +0.182275,-0.428429,-0.182276,0.000000, 0.366300,-0.855300,-0.366300, 0.625000,0.172400, +0.214333,-0.428429,-0.143213,0.000000, 0.430700,-0.855300,-0.287800, 0.593800,0.172400, +0.148453,-0.453788,-0.148453,0.000000, 0.298900,-0.906300,-0.298900, 0.625000,0.137900, +0.214333,-0.428429,-0.143213,0.000000, 0.430700,-0.855300,-0.287800, 0.593800,0.172400, +0.174562,-0.453788,-0.116639,0.000000, 0.351400,-0.906300,-0.234800, 0.593800,0.137900, +0.340665,0.133764,-0.340666,0.000000, 0.681500,0.266600,-0.681500, 0.625000,0.586200, +0.328442,0.185069,-0.328443,0.000000, 0.657200,0.369000,-0.657200, 0.625000,0.620700, +0.386207,0.185069,-0.258056,0.000000, 0.772800,0.369000,-0.516300, 0.593800,0.620700, +0.340665,0.133764,-0.340666,0.000000, 0.681500,0.266600,-0.681500, 0.625000,0.586200, +0.386207,0.185069,-0.258056,0.000000, 0.772800,0.369000,-0.516300, 0.593800,0.620700, +0.400580,0.133764,-0.267659,0.000000, 0.801400,0.266600,-0.535400, 0.593800,0.586200, +0.112889,-0.473826,-0.112890,0.000000, 0.227900,-0.946600,-0.227900, 0.625000,0.103400, +0.148453,-0.453788,-0.148453,0.000000, 0.298900,-0.906300,-0.298900, 0.625000,0.137900, +0.174562,-0.453788,-0.116639,0.000000, 0.351400,-0.906300,-0.234800, 0.593800,0.137900, +0.112889,-0.473826,-0.112890,0.000000, 0.227900,-0.946600,-0.227900, 0.625000,0.103400, +0.174562,-0.453788,-0.116639,0.000000, 0.351400,-0.906300,-0.234800, 0.593800,0.137900, +0.132744,-0.473826,-0.088697,0.000000, 0.268000,-0.946600,-0.179100, 0.593800,0.103400, +0.348895,0.080891,-0.348895,0.000000, 0.697800,0.161200,-0.697800, 0.625000,0.551700, +0.340665,0.133764,-0.340666,0.000000, 0.681500,0.266600,-0.681500, 0.625000,0.586200, +0.400580,0.133764,-0.267659,0.000000, 0.801400,0.266600,-0.535400, 0.593800,0.586200, +0.348895,0.080891,-0.348895,0.000000, 0.697800,0.161200,-0.697800, 0.625000,0.551700, +0.400580,0.133764,-0.267659,0.000000, 0.801400,0.266600,-0.535400, 0.593800,0.586200, +0.410257,0.080891,-0.274125,0.000000, 0.820600,0.161200,-0.548300, 0.593800,0.551700, +0.076003,-0.488310,-0.076003,0.000000, 0.154300,-0.975900,-0.154300, 0.625000,0.069000, +0.112889,-0.473826,-0.112890,0.000000, 0.227900,-0.946600,-0.227900, 0.625000,0.103400, +0.132744,-0.473826,-0.088697,0.000000, 0.268000,-0.946600,-0.179100, 0.593800,0.103400, +0.076003,-0.488310,-0.076003,0.000000, 0.154300,-0.975900,-0.154300, 0.625000,0.069000, +0.132744,-0.473826,-0.088697,0.000000, 0.268000,-0.946600,-0.179100, 0.593800,0.103400, +0.089370,-0.488310,-0.059715,0.000000, 0.181400,-0.975900,-0.121200, 0.593800,0.069000, +0.353034,0.027069,-0.353034,0.000000, 0.706100,0.054000,-0.706100, 0.625000,0.517200, +0.348895,0.080891,-0.348895,0.000000, 0.697800,0.161200,-0.697800, 0.625000,0.551700, +0.410257,0.080891,-0.274125,0.000000, 0.820600,0.161200,-0.548300, 0.593800,0.551700, +0.353034,0.027069,-0.353034,0.000000, 0.706100,0.054000,-0.706100, 0.625000,0.517200, +0.410257,0.080891,-0.274125,0.000000, 0.820600,0.161200,-0.548300, 0.593800,0.551700, +0.415124,0.027069,-0.277377,0.000000, 0.830300,0.054000,-0.554700, 0.593800,0.517200, +0.038225,0.497069,-0.038226,0.000000, 0.078800,0.993700,-0.078800, 0.449000,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +0.044948,0.497069,-0.030034,0.000000, 0.092700,0.993700,-0.061900, 0.450800,0.962300, +0.038226,-0.497069,-0.038226,0.000000, 0.078800,-0.993700,-0.078800, 0.625000,0.034500, +0.076003,-0.488310,-0.076003,0.000000, 0.154300,-0.975900,-0.154300, 0.625000,0.069000, +0.089370,-0.488310,-0.059715,0.000000, 0.181400,-0.975900,-0.121200, 0.593800,0.069000, +0.038226,-0.497069,-0.038226,0.000000, 0.078800,-0.993700,-0.078800, 0.625000,0.034500, +0.089370,-0.488310,-0.059715,0.000000, 0.181400,-0.975900,-0.121200, 0.593800,0.069000, +0.044948,-0.497069,-0.030034,0.000000, 0.092700,-0.993700,-0.061900, 0.593800,0.034500, +0.353034,-0.027069,-0.353034,0.000000, 0.706100,-0.054000,-0.706100, 0.625000,0.482800, +0.353034,0.027069,-0.353034,0.000000, 0.706100,0.054000,-0.706100, 0.625000,0.517200, +0.415124,0.027069,-0.277377,0.000000, 0.830300,0.054000,-0.554700, 0.593800,0.517200, +0.353034,-0.027069,-0.353034,0.000000, 0.706100,-0.054000,-0.706100, 0.625000,0.482800, +0.415124,0.027069,-0.277377,0.000000, 0.830300,0.054000,-0.554700, 0.593800,0.517200, +0.415124,-0.027069,-0.277377,0.000000, 0.830300,-0.054000,-0.554700, 0.593800,0.482800, +0.076003,0.488310,-0.076003,0.000000, 0.154300,0.975900,-0.154300, 0.625000,0.931000, +0.038225,0.497069,-0.038226,0.000000, 0.078800,0.993700,-0.078800, 0.625000,0.965500, +0.044948,0.497069,-0.030034,0.000000, 0.092700,0.993700,-0.061900, 0.593800,0.965500, +0.076003,0.488310,-0.076003,0.000000, 0.154300,0.975900,-0.154300, 0.625000,0.931000, +0.044948,0.497069,-0.030034,0.000000, 0.092700,0.993700,-0.061900, 0.593800,0.965500, +0.089370,0.488310,-0.059715,0.000000, 0.181400,0.975900,-0.121200, 0.593800,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +0.038226,-0.497069,-0.038226,0.000000, 0.078800,-0.993700,-0.078800, 0.462800,0.053800, +0.044948,-0.497069,-0.030034,0.000000, 0.092700,-0.993700,-0.061900, 0.460200,0.053800, +0.348895,-0.080891,-0.348895,0.000000, 0.697800,-0.161200,-0.697800, 0.625000,0.448300, +0.353034,-0.027069,-0.353034,0.000000, 0.706100,-0.054000,-0.706100, 0.625000,0.482800, +0.415124,-0.027069,-0.277377,0.000000, 0.830300,-0.054000,-0.554700, 0.593800,0.482800, +0.348895,-0.080891,-0.348895,0.000000, 0.697800,-0.161200,-0.697800, 0.625000,0.448300, +0.415124,-0.027069,-0.277377,0.000000, 0.830300,-0.054000,-0.554700, 0.593800,0.482800, +0.410257,-0.080891,-0.274125,0.000000, 0.820600,-0.161200,-0.548300, 0.593800,0.448300, +0.112889,0.473826,-0.112890,0.000000, 0.227900,0.946600,-0.227900, 0.625000,0.896600, +0.076003,0.488310,-0.076003,0.000000, 0.154300,0.975900,-0.154300, 0.625000,0.931000, +0.089370,0.488310,-0.059715,0.000000, 0.181400,0.975900,-0.121200, 0.593800,0.931000, +0.112889,0.473826,-0.112890,0.000000, 0.227900,0.946600,-0.227900, 0.625000,0.896600, +0.089370,0.488310,-0.059715,0.000000, 0.181400,0.975900,-0.121200, 0.593800,0.931000, +0.132744,0.473826,-0.088697,0.000000, 0.268000,0.946600,-0.179100, 0.593800,0.896600, +0.340665,-0.133764,-0.340666,0.000000, 0.681500,-0.266600,-0.681500, 0.625000,0.413800, +0.348895,-0.080891,-0.348895,0.000000, 0.697800,-0.161200,-0.697800, 0.625000,0.448300, +0.410257,-0.080891,-0.274125,0.000000, 0.820600,-0.161200,-0.548300, 0.593800,0.448300, +0.340665,-0.133764,-0.340666,0.000000, 0.681500,-0.266600,-0.681500, 0.625000,0.413800, +0.410257,-0.080891,-0.274125,0.000000, 0.820600,-0.161200,-0.548300, 0.593800,0.448300, +0.400580,-0.133764,-0.267659,0.000000, 0.801400,-0.266600,-0.535400, 0.593800,0.413800, +0.148453,0.453788,-0.148453,0.000000, 0.298900,0.906300,-0.298900, 0.625000,0.862100, +0.112889,0.473826,-0.112890,0.000000, 0.227900,0.946600,-0.227900, 0.625000,0.896600, +0.132744,0.473826,-0.088697,0.000000, 0.268000,0.946600,-0.179100, 0.593800,0.896600, +0.148453,0.453788,-0.148453,0.000000, 0.298900,0.906300,-0.298900, 0.625000,0.862100, +0.132744,0.473826,-0.088697,0.000000, 0.268000,0.946600,-0.179100, 0.593800,0.896600, +0.174562,0.453788,-0.116638,0.000000, 0.351400,0.906300,-0.234800, 0.593800,0.862100, +0.328442,-0.185069,-0.328443,0.000000, 0.657200,-0.369000,-0.657200, 0.625000,0.379300, +0.340665,-0.133764,-0.340666,0.000000, 0.681500,-0.266600,-0.681500, 0.625000,0.413800, +0.400580,-0.133764,-0.267659,0.000000, 0.801400,-0.266600,-0.535400, 0.593800,0.413800, +0.328442,-0.185069,-0.328443,0.000000, 0.657200,-0.369000,-0.657200, 0.625000,0.379300, +0.400580,-0.133764,-0.267659,0.000000, 0.801400,-0.266600,-0.535400, 0.593800,0.413800, +0.386207,-0.185069,-0.258056,0.000000, 0.772800,-0.369000,-0.516300, 0.593800,0.379300, +0.182275,0.428429,-0.182276,0.000000, 0.366300,0.855300,-0.366300, 0.625000,0.827600, +0.148453,0.453788,-0.148453,0.000000, 0.298900,0.906300,-0.298900, 0.625000,0.862100, +0.174562,0.453788,-0.116638,0.000000, 0.351400,0.906300,-0.234800, 0.593800,0.862100, +0.182275,0.428429,-0.182276,0.000000, 0.366300,0.855300,-0.366300, 0.625000,0.827600, +0.174562,0.453788,-0.116638,0.000000, 0.351400,0.906300,-0.234800, 0.593800,0.862100, +0.214333,0.428429,-0.143213,0.000000, 0.430700,0.855300,-0.287800, 0.593800,0.827600, +0.312368,-0.234204,-0.312368,0.000000, 0.625200,-0.467000,-0.625200, 0.625000,0.344800, +0.328442,-0.185069,-0.328443,0.000000, 0.657200,-0.369000,-0.657200, 0.625000,0.379300, +0.386207,-0.185069,-0.258056,0.000000, 0.772800,-0.369000,-0.516300, 0.593800,0.379300, +0.312368,-0.234204,-0.312368,0.000000, 0.625200,-0.467000,-0.625200, 0.625000,0.344800, +0.386207,-0.185069,-0.258056,0.000000, 0.772800,-0.369000,-0.516300, 0.593800,0.379300, +0.367306,-0.234204,-0.245426,0.000000, 0.735200,-0.467000,-0.491300, 0.593800,0.344800, +0.213960,0.398046,-0.213961,0.000000, 0.429400,0.794500,-0.429400, 0.625000,0.793100, +0.182275,0.428429,-0.182276,0.000000, 0.366300,0.855300,-0.366300, 0.625000,0.827600, +0.214333,0.428429,-0.143213,0.000000, 0.430700,0.855300,-0.287800, 0.593800,0.827600, +0.213960,0.398046,-0.213961,0.000000, 0.429400,0.794500,-0.429400, 0.625000,0.793100, +0.214333,0.428429,-0.143213,0.000000, 0.430700,0.855300,-0.287800, 0.593800,0.827600, +0.251591,0.398046,-0.168108,0.000000, 0.504900,0.794500,-0.337400, 0.593800,0.793100, +0.292632,-0.280594,-0.292632,0.000000, 0.586000,-0.559600,-0.586000, 0.625000,0.310300, +0.312368,-0.234204,-0.312368,0.000000, 0.625200,-0.467000,-0.625200, 0.625000,0.344800, +0.367306,-0.234204,-0.245426,0.000000, 0.735200,-0.467000,-0.491300, 0.593800,0.344800, +0.292632,-0.280594,-0.292632,0.000000, 0.586000,-0.559600,-0.586000, 0.625000,0.310300, +0.367306,-0.234204,-0.245426,0.000000, 0.735200,-0.467000,-0.491300, 0.593800,0.344800, +0.344099,-0.280594,-0.229919,0.000000, 0.689100,-0.559600,-0.460400, 0.593800,0.310300, +0.243137,0.362998,-0.243138,0.000000, 0.487500,0.724300,-0.487500, 0.625000,0.758600, +0.213960,0.398046,-0.213961,0.000000, 0.429400,0.794500,-0.429400, 0.625000,0.793100, +0.251591,0.398046,-0.168108,0.000000, 0.504900,0.794500,-0.337400, 0.593800,0.793100, +0.243137,0.362998,-0.243138,0.000000, 0.487500,0.724300,-0.487500, 0.625000,0.758600, +0.251591,0.398046,-0.168108,0.000000, 0.504900,0.794500,-0.337400, 0.593800,0.793100, +0.285899,0.362998,-0.191032,0.000000, 0.573300,0.724300,-0.383000, 0.593800,0.758600, +0.269464,-0.323693,-0.269464,0.000000, 0.539900,-0.645700,-0.539900, 0.625000,0.275900, +0.292632,-0.280594,-0.292632,0.000000, 0.586000,-0.559600,-0.586000, 0.625000,0.310300, +0.344099,-0.280594,-0.229919,0.000000, 0.689100,-0.559600,-0.460400, 0.593800,0.310300, +0.269464,-0.323693,-0.269464,0.000000, 0.539900,-0.645700,-0.539900, 0.625000,0.275900, +0.344099,-0.280594,-0.229919,0.000000, 0.689100,-0.559600,-0.460400, 0.593800,0.310300, +0.316857,-0.323693,-0.211717,0.000000, 0.634900,-0.645700,-0.424200, 0.593800,0.275900, +0.410257,-0.080891,-0.274125,0.000000, 0.820600,-0.161200,-0.548300, 0.593800,0.448300, +0.415124,-0.027069,-0.277377,0.000000, 0.830300,-0.054000,-0.554700, 0.593800,0.482800, +0.461262,-0.027069,-0.191061,0.000000, 0.922500,-0.054000,-0.382100, 0.562500,0.482800, +0.410257,-0.080891,-0.274125,0.000000, 0.820600,-0.161200,-0.548300, 0.593800,0.448300, +0.461262,-0.027069,-0.191061,0.000000, 0.922500,-0.054000,-0.382100, 0.562500,0.482800, +0.455853,-0.080891,-0.188821,0.000000, 0.911800,-0.161200,-0.377700, 0.562500,0.448300, +0.132744,0.473826,-0.088697,0.000000, 0.268000,0.946600,-0.179100, 0.593800,0.896600, +0.089370,0.488310,-0.059715,0.000000, 0.181400,0.975900,-0.121200, 0.593800,0.931000, +0.099303,0.488310,-0.041132,0.000000, 0.201600,0.975900,-0.083500, 0.562500,0.931000, +0.132744,0.473826,-0.088697,0.000000, 0.268000,0.946600,-0.179100, 0.593800,0.896600, +0.099303,0.488310,-0.041132,0.000000, 0.201600,0.975900,-0.083500, 0.562500,0.931000, +0.147497,0.473826,-0.061095,0.000000, 0.297800,0.946600,-0.123300, 0.562500,0.896600, +0.400580,-0.133764,-0.267659,0.000000, 0.801400,-0.266600,-0.535400, 0.593800,0.413800, +0.410257,-0.080891,-0.274125,0.000000, 0.820600,-0.161200,-0.548300, 0.593800,0.448300, +0.455853,-0.080891,-0.188821,0.000000, 0.911800,-0.161200,-0.377700, 0.562500,0.448300, +0.400580,-0.133764,-0.267659,0.000000, 0.801400,-0.266600,-0.535400, 0.593800,0.413800, +0.455853,-0.080891,-0.188821,0.000000, 0.911800,-0.161200,-0.377700, 0.562500,0.448300, +0.445101,-0.133764,-0.184367,0.000000, 0.890400,-0.266600,-0.368800, 0.562500,0.413800, +0.174562,0.453788,-0.116638,0.000000, 0.351400,0.906300,-0.234800, 0.593800,0.862100, +0.132744,0.473826,-0.088697,0.000000, 0.268000,0.946600,-0.179100, 0.593800,0.896600, +0.147497,0.473826,-0.061095,0.000000, 0.297800,0.946600,-0.123300, 0.562500,0.896600, +0.174562,0.453788,-0.116638,0.000000, 0.351400,0.906300,-0.234800, 0.593800,0.862100, +0.147497,0.473826,-0.061095,0.000000, 0.297800,0.946600,-0.123300, 0.562500,0.896600, +0.193962,0.453788,-0.080342,0.000000, 0.390500,0.906300,-0.161700, 0.562500,0.862100, +0.386207,-0.185069,-0.258056,0.000000, 0.772800,-0.369000,-0.516300, 0.593800,0.379300, +0.400580,-0.133764,-0.267659,0.000000, 0.801400,-0.266600,-0.535400, 0.593800,0.413800, +0.445101,-0.133764,-0.184367,0.000000, 0.890400,-0.266600,-0.368800, 0.562500,0.413800, +0.386207,-0.185069,-0.258056,0.000000, 0.772800,-0.369000,-0.516300, 0.593800,0.379300, +0.445101,-0.133764,-0.184367,0.000000, 0.890400,-0.266600,-0.368800, 0.562500,0.413800, +0.429130,-0.185069,-0.177751,0.000000, 0.858700,-0.369000,-0.355700, 0.562500,0.379300, +0.214333,0.428429,-0.143213,0.000000, 0.430700,0.855300,-0.287800, 0.593800,0.827600, +0.174562,0.453788,-0.116638,0.000000, 0.351400,0.906300,-0.234800, 0.593800,0.862100, +0.193962,0.453788,-0.080342,0.000000, 0.390500,0.906300,-0.161700, 0.562500,0.862100, +0.214333,0.428429,-0.143213,0.000000, 0.430700,0.855300,-0.287800, 0.593800,0.827600, +0.193962,0.453788,-0.080342,0.000000, 0.390500,0.906300,-0.161700, 0.562500,0.862100, +0.238154,0.428429,-0.098647,0.000000, 0.478600,0.855300,-0.198200, 0.562500,0.827600, +0.367306,-0.234204,-0.245426,0.000000, 0.735200,-0.467000,-0.491300, 0.593800,0.344800, +0.386207,-0.185069,-0.258056,0.000000, 0.772800,-0.369000,-0.516300, 0.593800,0.379300, +0.429130,-0.185069,-0.177751,0.000000, 0.858700,-0.369000,-0.355700, 0.562500,0.379300, +0.367306,-0.234204,-0.245426,0.000000, 0.735200,-0.467000,-0.491300, 0.593800,0.344800, +0.429130,-0.185069,-0.177751,0.000000, 0.858700,-0.369000,-0.355700, 0.562500,0.379300, +0.408128,-0.234204,-0.169052,0.000000, 0.816900,-0.467000,-0.338400, 0.562500,0.344800, +0.251591,0.398046,-0.168108,0.000000, 0.504900,0.794500,-0.337400, 0.593800,0.793100, +0.214333,0.428429,-0.143213,0.000000, 0.430700,0.855300,-0.287800, 0.593800,0.827600, +0.238154,0.428429,-0.098647,0.000000, 0.478600,0.855300,-0.198200, 0.562500,0.827600, +0.251591,0.398046,-0.168108,0.000000, 0.504900,0.794500,-0.337400, 0.593800,0.793100, +0.238154,0.428429,-0.098647,0.000000, 0.478600,0.855300,-0.198200, 0.562500,0.827600, +0.279553,0.398046,-0.115795,0.000000, 0.561100,0.794500,-0.232400, 0.562500,0.793100, +0.344099,-0.280594,-0.229919,0.000000, 0.689100,-0.559600,-0.460400, 0.593800,0.310300, +0.367306,-0.234204,-0.245426,0.000000, 0.735200,-0.467000,-0.491300, 0.593800,0.344800, +0.408128,-0.234204,-0.169052,0.000000, 0.816900,-0.467000,-0.338400, 0.562500,0.344800, +0.344099,-0.280594,-0.229919,0.000000, 0.689100,-0.559600,-0.460400, 0.593800,0.310300, +0.408128,-0.234204,-0.169052,0.000000, 0.816900,-0.467000,-0.338400, 0.562500,0.344800, +0.382342,-0.280594,-0.158371,0.000000, 0.765600,-0.559600,-0.317100, 0.562500,0.310300, +0.285899,0.362998,-0.191032,0.000000, 0.573300,0.724300,-0.383000, 0.593800,0.758600, +0.251591,0.398046,-0.168108,0.000000, 0.504900,0.794500,-0.337400, 0.593800,0.793100, +0.279553,0.398046,-0.115795,0.000000, 0.561100,0.794500,-0.232400, 0.562500,0.793100, +0.285899,0.362998,-0.191032,0.000000, 0.573300,0.724300,-0.383000, 0.593800,0.758600, +0.279553,0.398046,-0.115795,0.000000, 0.561100,0.794500,-0.232400, 0.562500,0.793100, +0.317674,0.362998,-0.131585,0.000000, 0.637000,0.724300,-0.263800, 0.562500,0.758600, +0.316857,-0.323693,-0.211717,0.000000, 0.634900,-0.645700,-0.424200, 0.593800,0.275900, +0.344099,-0.280594,-0.229919,0.000000, 0.689100,-0.559600,-0.460400, 0.593800,0.310300, +0.382342,-0.280594,-0.158371,0.000000, 0.765600,-0.559600,-0.317100, 0.562500,0.310300, +0.316857,-0.323693,-0.211717,0.000000, 0.634900,-0.645700,-0.424200, 0.593800,0.275900, +0.382342,-0.280594,-0.158371,0.000000, 0.765600,-0.559600,-0.317100, 0.562500,0.310300, +0.352072,-0.323693,-0.145833,0.000000, 0.705400,-0.645700,-0.292200, 0.562500,0.275900, +0.316857,0.323693,-0.211717,0.000000, 0.634900,0.645700,-0.424200, 0.593800,0.724100, +0.285899,0.362998,-0.191032,0.000000, 0.573300,0.724300,-0.383000, 0.593800,0.758600, +0.317674,0.362998,-0.131585,0.000000, 0.637000,0.724300,-0.263800, 0.562500,0.758600, +0.316857,0.323693,-0.211717,0.000000, 0.634900,0.645700,-0.424200, 0.593800,0.724100, +0.317674,0.362998,-0.131585,0.000000, 0.637000,0.724300,-0.263800, 0.562500,0.758600, +0.352072,0.323693,-0.145833,0.000000, 0.705400,0.645700,-0.292200, 0.562500,0.724100, +0.285900,-0.362998,-0.191032,0.000000, 0.573300,-0.724300,-0.383000, 0.593800,0.241400, +0.316857,-0.323693,-0.211717,0.000000, 0.634900,-0.645700,-0.424200, 0.593800,0.275900, +0.352072,-0.323693,-0.145833,0.000000, 0.705400,-0.645700,-0.292200, 0.562500,0.275900, +0.285900,-0.362998,-0.191032,0.000000, 0.573300,-0.724300,-0.383000, 0.593800,0.241400, +0.352072,-0.323693,-0.145833,0.000000, 0.705400,-0.645700,-0.292200, 0.562500,0.275900, +0.317675,-0.362998,-0.131585,0.000000, 0.637000,-0.724300,-0.263800, 0.562500,0.241400, +0.344098,0.280594,-0.229919,0.000000, 0.689100,0.559600,-0.460400, 0.593800,0.689700, +0.316857,0.323693,-0.211717,0.000000, 0.634900,0.645700,-0.424200, 0.593800,0.724100, +0.352072,0.323693,-0.145833,0.000000, 0.705400,0.645700,-0.292200, 0.562500,0.724100, +0.344098,0.280594,-0.229919,0.000000, 0.689100,0.559600,-0.460400, 0.593800,0.689700, +0.352072,0.323693,-0.145833,0.000000, 0.705400,0.645700,-0.292200, 0.562500,0.724100, +0.382342,0.280594,-0.158371,0.000000, 0.765600,0.559600,-0.317100, 0.562500,0.689700, +0.251591,-0.398046,-0.168108,0.000000, 0.505000,-0.794500,-0.337400, 0.593800,0.206900, +0.285900,-0.362998,-0.191032,0.000000, 0.573300,-0.724300,-0.383000, 0.593800,0.241400, +0.317675,-0.362998,-0.131585,0.000000, 0.637000,-0.724300,-0.263800, 0.562500,0.241400, +0.251591,-0.398046,-0.168108,0.000000, 0.505000,-0.794500,-0.337400, 0.593800,0.206900, +0.317675,-0.362998,-0.131585,0.000000, 0.637000,-0.724300,-0.263800, 0.562500,0.241400, +0.279553,-0.398046,-0.115795,0.000000, 0.561100,-0.794500,-0.232400, 0.562500,0.206900, +0.367306,0.234204,-0.245426,0.000000, 0.735200,0.467000,-0.491300, 0.593800,0.655200, +0.344098,0.280594,-0.229919,0.000000, 0.689100,0.559600,-0.460400, 0.593800,0.689700, +0.382342,0.280594,-0.158371,0.000000, 0.765600,0.559600,-0.317100, 0.562500,0.689700, +0.367306,0.234204,-0.245426,0.000000, 0.735200,0.467000,-0.491300, 0.593800,0.655200, +0.382342,0.280594,-0.158371,0.000000, 0.765600,0.559600,-0.317100, 0.562500,0.689700, +0.408128,0.234204,-0.169052,0.000000, 0.816900,0.467000,-0.338400, 0.562500,0.655200, +0.214333,-0.428429,-0.143213,0.000000, 0.430700,-0.855300,-0.287800, 0.593800,0.172400, +0.251591,-0.398046,-0.168108,0.000000, 0.505000,-0.794500,-0.337400, 0.593800,0.206900, +0.279553,-0.398046,-0.115795,0.000000, 0.561100,-0.794500,-0.232400, 0.562500,0.206900, +0.214333,-0.428429,-0.143213,0.000000, 0.430700,-0.855300,-0.287800, 0.593800,0.172400, +0.279553,-0.398046,-0.115795,0.000000, 0.561100,-0.794500,-0.232400, 0.562500,0.206900, +0.238154,-0.428429,-0.098647,0.000000, 0.478600,-0.855300,-0.198200, 0.562500,0.172400, +0.386207,0.185069,-0.258056,0.000000, 0.772800,0.369000,-0.516300, 0.593800,0.620700, +0.367306,0.234204,-0.245426,0.000000, 0.735200,0.467000,-0.491300, 0.593800,0.655200, +0.408128,0.234204,-0.169052,0.000000, 0.816900,0.467000,-0.338400, 0.562500,0.655200, +0.386207,0.185069,-0.258056,0.000000, 0.772800,0.369000,-0.516300, 0.593800,0.620700, +0.408128,0.234204,-0.169052,0.000000, 0.816900,0.467000,-0.338400, 0.562500,0.655200, +0.429130,0.185069,-0.177751,0.000000, 0.858700,0.369000,-0.355700, 0.562500,0.620700, +0.174562,-0.453788,-0.116639,0.000000, 0.351400,-0.906300,-0.234800, 0.593800,0.137900, +0.214333,-0.428429,-0.143213,0.000000, 0.430700,-0.855300,-0.287800, 0.593800,0.172400, +0.238154,-0.428429,-0.098647,0.000000, 0.478600,-0.855300,-0.198200, 0.562500,0.172400, +0.174562,-0.453788,-0.116639,0.000000, 0.351400,-0.906300,-0.234800, 0.593800,0.137900, +0.238154,-0.428429,-0.098647,0.000000, 0.478600,-0.855300,-0.198200, 0.562500,0.172400, +0.193963,-0.453788,-0.080342,0.000000, 0.390500,-0.906300,-0.161700, 0.562500,0.137900, +0.400580,0.133764,-0.267659,0.000000, 0.801400,0.266600,-0.535400, 0.593800,0.586200, +0.386207,0.185069,-0.258056,0.000000, 0.772800,0.369000,-0.516300, 0.593800,0.620700, +0.429130,0.185069,-0.177751,0.000000, 0.858700,0.369000,-0.355700, 0.562500,0.620700, +0.400580,0.133764,-0.267659,0.000000, 0.801400,0.266600,-0.535400, 0.593800,0.586200, +0.429130,0.185069,-0.177751,0.000000, 0.858700,0.369000,-0.355700, 0.562500,0.620700, +0.445101,0.133764,-0.184367,0.000000, 0.890400,0.266600,-0.368800, 0.562500,0.586200, +0.132744,-0.473826,-0.088697,0.000000, 0.268000,-0.946600,-0.179100, 0.593800,0.103400, +0.174562,-0.453788,-0.116639,0.000000, 0.351400,-0.906300,-0.234800, 0.593800,0.137900, +0.193963,-0.453788,-0.080342,0.000000, 0.390500,-0.906300,-0.161700, 0.562500,0.137900, +0.132744,-0.473826,-0.088697,0.000000, 0.268000,-0.946600,-0.179100, 0.593800,0.103400, +0.193963,-0.453788,-0.080342,0.000000, 0.390500,-0.906300,-0.161700, 0.562500,0.137900, +0.147498,-0.473826,-0.061095,0.000000, 0.297800,-0.946600,-0.123300, 0.562500,0.103400, +0.410257,0.080891,-0.274125,0.000000, 0.820600,0.161200,-0.548300, 0.593800,0.551700, +0.400580,0.133764,-0.267659,0.000000, 0.801400,0.266600,-0.535400, 0.593800,0.586200, +0.445101,0.133764,-0.184367,0.000000, 0.890400,0.266600,-0.368800, 0.562500,0.586200, +0.410257,0.080891,-0.274125,0.000000, 0.820600,0.161200,-0.548300, 0.593800,0.551700, +0.445101,0.133764,-0.184367,0.000000, 0.890400,0.266600,-0.368800, 0.562500,0.586200, +0.455853,0.080891,-0.188821,0.000000, 0.911800,0.161200,-0.377700, 0.562500,0.551700, +0.089370,-0.488310,-0.059715,0.000000, 0.181400,-0.975900,-0.121200, 0.593800,0.069000, +0.132744,-0.473826,-0.088697,0.000000, 0.268000,-0.946600,-0.179100, 0.593800,0.103400, +0.147498,-0.473826,-0.061095,0.000000, 0.297800,-0.946600,-0.123300, 0.562500,0.103400, +0.089370,-0.488310,-0.059715,0.000000, 0.181400,-0.975900,-0.121200, 0.593800,0.069000, +0.147498,-0.473826,-0.061095,0.000000, 0.297800,-0.946600,-0.123300, 0.562500,0.103400, +0.099303,-0.488310,-0.041133,0.000000, 0.201600,-0.975900,-0.083500, 0.562500,0.069000, +0.415124,0.027069,-0.277377,0.000000, 0.830300,0.054000,-0.554700, 0.593800,0.517200, +0.410257,0.080891,-0.274125,0.000000, 0.820600,0.161200,-0.548300, 0.593800,0.551700, +0.455853,0.080891,-0.188821,0.000000, 0.911800,0.161200,-0.377700, 0.562500,0.551700, +0.415124,0.027069,-0.277377,0.000000, 0.830300,0.054000,-0.554700, 0.593800,0.517200, +0.455853,0.080891,-0.188821,0.000000, 0.911800,0.161200,-0.377700, 0.562500,0.551700, +0.461262,0.027069,-0.191061,0.000000, 0.922500,0.054000,-0.382100, 0.562500,0.517200, +0.044948,0.497069,-0.030034,0.000000, 0.092700,0.993700,-0.061900, 0.450800,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +0.049943,0.497069,-0.020688,0.000000, 0.103000,0.993700,-0.042600, 0.452600,0.962300, +0.044948,-0.497069,-0.030034,0.000000, 0.092700,-0.993700,-0.061900, 0.593800,0.034500, +0.089370,-0.488310,-0.059715,0.000000, 0.181400,-0.975900,-0.121200, 0.593800,0.069000, +0.099303,-0.488310,-0.041133,0.000000, 0.201600,-0.975900,-0.083500, 0.562500,0.069000, +0.044948,-0.497069,-0.030034,0.000000, 0.092700,-0.993700,-0.061900, 0.593800,0.034500, +0.099303,-0.488310,-0.041133,0.000000, 0.201600,-0.975900,-0.083500, 0.562500,0.069000, +0.049944,-0.497069,-0.020688,0.000000, 0.103000,-0.993700,-0.042600, 0.562500,0.034500, +0.415124,-0.027069,-0.277377,0.000000, 0.830300,-0.054000,-0.554700, 0.593800,0.482800, +0.415124,0.027069,-0.277377,0.000000, 0.830300,0.054000,-0.554700, 0.593800,0.517200, +0.461262,0.027069,-0.191061,0.000000, 0.922500,0.054000,-0.382100, 0.562500,0.517200, +0.415124,-0.027069,-0.277377,0.000000, 0.830300,-0.054000,-0.554700, 0.593800,0.482800, +0.461262,0.027069,-0.191061,0.000000, 0.922500,0.054000,-0.382100, 0.562500,0.517200, +0.461262,-0.027069,-0.191061,0.000000, 0.922500,-0.054000,-0.382100, 0.562500,0.482800, +0.089370,0.488310,-0.059715,0.000000, 0.181400,0.975900,-0.121200, 0.593800,0.931000, +0.044948,0.497069,-0.030034,0.000000, 0.092700,0.993700,-0.061900, 0.593800,0.965500, +0.049943,0.497069,-0.020688,0.000000, 0.103000,0.993700,-0.042600, 0.562500,0.965500, +0.089370,0.488310,-0.059715,0.000000, 0.181400,0.975900,-0.121200, 0.593800,0.931000, +0.049943,0.497069,-0.020688,0.000000, 0.103000,0.993700,-0.042600, 0.562500,0.965500, +0.099303,0.488310,-0.041132,0.000000, 0.201600,0.975900,-0.083500, 0.562500,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +0.044948,-0.497069,-0.030034,0.000000, 0.092700,-0.993700,-0.061900, 0.460200,0.053800, +0.049944,-0.497069,-0.020688,0.000000, 0.103000,-0.993700,-0.042600, 0.457500,0.053800, +0.238154,-0.428429,-0.098647,0.000000, 0.478600,-0.855300,-0.198200, 0.562500,0.172400, +0.279553,-0.398046,-0.115795,0.000000, 0.561100,-0.794500,-0.232400, 0.562500,0.206900, +0.296772,-0.398046,-0.059032,0.000000, 0.595600,-0.794500,-0.118500, 0.531200,0.206900, +0.238154,-0.428429,-0.098647,0.000000, 0.478600,-0.855300,-0.198200, 0.562500,0.172400, +0.296772,-0.398046,-0.059032,0.000000, 0.595600,-0.794500,-0.118500, 0.531200,0.206900, +0.252823,-0.428429,-0.050290,0.000000, 0.508100,-0.855300,-0.101000, 0.531200,0.172400, +0.429130,0.185069,-0.177751,0.000000, 0.858700,0.369000,-0.355700, 0.562500,0.620700, +0.408128,0.234204,-0.169052,0.000000, 0.816900,0.467000,-0.338400, 0.562500,0.655200, +0.433267,0.234204,-0.086182,0.000000, 0.867200,0.467000,-0.172500, 0.531200,0.655200, +0.429130,0.185069,-0.177751,0.000000, 0.858700,0.369000,-0.355700, 0.562500,0.620700, +0.433267,0.234204,-0.086182,0.000000, 0.867200,0.467000,-0.172500, 0.531200,0.655200, +0.455563,0.185069,-0.090617,0.000000, 0.911600,0.369000,-0.181300, 0.531200,0.620700, +0.193963,-0.453788,-0.080342,0.000000, 0.390500,-0.906300,-0.161700, 0.562500,0.137900, +0.238154,-0.428429,-0.098647,0.000000, 0.478600,-0.855300,-0.198200, 0.562500,0.172400, +0.252823,-0.428429,-0.050290,0.000000, 0.508100,-0.855300,-0.101000, 0.531200,0.172400, +0.193963,-0.453788,-0.080342,0.000000, 0.390500,-0.906300,-0.161700, 0.562500,0.137900, +0.252823,-0.428429,-0.050290,0.000000, 0.508100,-0.855300,-0.101000, 0.531200,0.172400, +0.205910,-0.453788,-0.040958,0.000000, 0.414500,-0.906300,-0.082400, 0.531200,0.137900, +0.445101,0.133764,-0.184367,0.000000, 0.890400,0.266600,-0.368800, 0.562500,0.586200, +0.429130,0.185069,-0.177751,0.000000, 0.858700,0.369000,-0.355700, 0.562500,0.620700, +0.455563,0.185069,-0.090617,0.000000, 0.911600,0.369000,-0.181300, 0.531200,0.620700, +0.445101,0.133764,-0.184367,0.000000, 0.890400,0.266600,-0.368800, 0.562500,0.586200, +0.455563,0.185069,-0.090617,0.000000, 0.911600,0.369000,-0.181300, 0.531200,0.620700, +0.472517,0.133764,-0.093989,0.000000, 0.945200,0.266600,-0.188000, 0.531200,0.586200, +0.147498,-0.473826,-0.061095,0.000000, 0.297800,-0.946600,-0.123300, 0.562500,0.103400, +0.193963,-0.453788,-0.080342,0.000000, 0.390500,-0.906300,-0.161700, 0.562500,0.137900, +0.205910,-0.453788,-0.040958,0.000000, 0.414500,-0.906300,-0.082400, 0.531200,0.137900, +0.147498,-0.473826,-0.061095,0.000000, 0.297800,-0.946600,-0.123300, 0.562500,0.103400, +0.205910,-0.453788,-0.040958,0.000000, 0.414500,-0.906300,-0.082400, 0.531200,0.137900, +0.156583,-0.473826,-0.031147,0.000000, 0.316100,-0.946600,-0.062900, 0.531300,0.103400, +0.455853,0.080891,-0.188821,0.000000, 0.911800,0.161200,-0.377700, 0.562500,0.551700, +0.445101,0.133764,-0.184367,0.000000, 0.890400,0.266600,-0.368800, 0.562500,0.586200, +0.472517,0.133764,-0.093989,0.000000, 0.945200,0.266600,-0.188000, 0.531200,0.586200, +0.455853,0.080891,-0.188821,0.000000, 0.911800,0.161200,-0.377700, 0.562500,0.551700, +0.472517,0.133764,-0.093989,0.000000, 0.945200,0.266600,-0.188000, 0.531200,0.586200, +0.483932,0.080891,-0.096260,0.000000, 0.967900,0.161200,-0.192500, 0.531200,0.551700, +0.099303,-0.488310,-0.041133,0.000000, 0.201600,-0.975900,-0.083500, 0.562500,0.069000, +0.147498,-0.473826,-0.061095,0.000000, 0.297800,-0.946600,-0.123300, 0.562500,0.103400, +0.156583,-0.473826,-0.031147,0.000000, 0.316100,-0.946600,-0.062900, 0.531300,0.103400, +0.099303,-0.488310,-0.041133,0.000000, 0.201600,-0.975900,-0.083500, 0.562500,0.069000, +0.156583,-0.473826,-0.031147,0.000000, 0.316100,-0.946600,-0.062900, 0.531300,0.103400, +0.105420,-0.488310,-0.020970,0.000000, 0.214000,-0.975900,-0.042500, 0.531300,0.069000, +0.461262,0.027069,-0.191061,0.000000, 0.922500,0.054000,-0.382100, 0.562500,0.517200, +0.455853,0.080891,-0.188821,0.000000, 0.911800,0.161200,-0.377700, 0.562500,0.551700, +0.483932,0.080891,-0.096260,0.000000, 0.967900,0.161200,-0.192500, 0.531200,0.551700, +0.461262,0.027069,-0.191061,0.000000, 0.922500,0.054000,-0.382100, 0.562500,0.517200, +0.483932,0.080891,-0.096260,0.000000, 0.967900,0.161200,-0.192500, 0.531200,0.551700, +0.489673,0.027069,-0.097402,0.000000, 0.979300,0.054000,-0.194800, 0.531200,0.517200, +0.049943,0.497069,-0.020688,0.000000, 0.103000,0.993700,-0.042600, 0.452600,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +0.053020,0.497069,-0.010546,0.000000, 0.109300,0.993700,-0.021700, 0.454400,0.962300, +0.049944,-0.497069,-0.020688,0.000000, 0.103000,-0.993700,-0.042600, 0.562500,0.034500, +0.099303,-0.488310,-0.041133,0.000000, 0.201600,-0.975900,-0.083500, 0.562500,0.069000, +0.105420,-0.488310,-0.020970,0.000000, 0.214000,-0.975900,-0.042500, 0.531300,0.069000, +0.049944,-0.497069,-0.020688,0.000000, 0.103000,-0.993700,-0.042600, 0.562500,0.034500, +0.105420,-0.488310,-0.020970,0.000000, 0.214000,-0.975900,-0.042500, 0.531300,0.069000, +0.053020,-0.497069,-0.010546,0.000000, 0.109300,-0.993700,-0.021700, 0.531300,0.034500, +0.461262,-0.027069,-0.191061,0.000000, 0.922500,-0.054000,-0.382100, 0.562500,0.482800, +0.461262,0.027069,-0.191061,0.000000, 0.922500,0.054000,-0.382100, 0.562500,0.517200, +0.489673,0.027069,-0.097402,0.000000, 0.979300,0.054000,-0.194800, 0.531200,0.517200, +0.461262,-0.027069,-0.191061,0.000000, 0.922500,-0.054000,-0.382100, 0.562500,0.482800, +0.489673,0.027069,-0.097402,0.000000, 0.979300,0.054000,-0.194800, 0.531200,0.517200, +0.489673,-0.027069,-0.097402,0.000000, 0.979300,-0.054000,-0.194800, 0.531200,0.482800, +0.099303,0.488310,-0.041132,0.000000, 0.201600,0.975900,-0.083500, 0.562500,0.931000, +0.049943,0.497069,-0.020688,0.000000, 0.103000,0.993700,-0.042600, 0.562500,0.965500, +0.053020,0.497069,-0.010546,0.000000, 0.109300,0.993700,-0.021700, 0.531300,0.965500, +0.099303,0.488310,-0.041132,0.000000, 0.201600,0.975900,-0.083500, 0.562500,0.931000, +0.053020,0.497069,-0.010546,0.000000, 0.109300,0.993700,-0.021700, 0.531300,0.965500, +0.105419,0.488310,-0.020969,0.000000, 0.214000,0.975900,-0.042500, 0.531300,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +0.049944,-0.497069,-0.020688,0.000000, 0.103000,-0.993700,-0.042600, 0.457500,0.053800, +0.053020,-0.497069,-0.010546,0.000000, 0.109300,-0.993700,-0.021700, 0.454900,0.053800, +0.455853,-0.080891,-0.188821,0.000000, 0.911800,-0.161200,-0.377700, 0.562500,0.448300, +0.461262,-0.027069,-0.191061,0.000000, 0.922500,-0.054000,-0.382100, 0.562500,0.482800, +0.489673,-0.027069,-0.097402,0.000000, 0.979300,-0.054000,-0.194800, 0.531200,0.482800, +0.455853,-0.080891,-0.188821,0.000000, 0.911800,-0.161200,-0.377700, 0.562500,0.448300, +0.489673,-0.027069,-0.097402,0.000000, 0.979300,-0.054000,-0.194800, 0.531200,0.482800, +0.483932,-0.080891,-0.096260,0.000000, 0.967900,-0.161200,-0.192500, 0.531200,0.448300, +0.147497,0.473826,-0.061095,0.000000, 0.297800,0.946600,-0.123300, 0.562500,0.896600, +0.099303,0.488310,-0.041132,0.000000, 0.201600,0.975900,-0.083500, 0.562500,0.931000, +0.105419,0.488310,-0.020969,0.000000, 0.214000,0.975900,-0.042500, 0.531300,0.931000, +0.147497,0.473826,-0.061095,0.000000, 0.297800,0.946600,-0.123300, 0.562500,0.896600, +0.105419,0.488310,-0.020969,0.000000, 0.214000,0.975900,-0.042500, 0.531300,0.931000, +0.156582,0.473826,-0.031146,0.000000, 0.316100,0.946600,-0.062900, 0.531300,0.896600, +0.445101,-0.133764,-0.184367,0.000000, 0.890400,-0.266600,-0.368800, 0.562500,0.413800, +0.455853,-0.080891,-0.188821,0.000000, 0.911800,-0.161200,-0.377700, 0.562500,0.448300, +0.483932,-0.080891,-0.096260,0.000000, 0.967900,-0.161200,-0.192500, 0.531200,0.448300, +0.445101,-0.133764,-0.184367,0.000000, 0.890400,-0.266600,-0.368800, 0.562500,0.413800, +0.483932,-0.080891,-0.096260,0.000000, 0.967900,-0.161200,-0.192500, 0.531200,0.448300, +0.472517,-0.133764,-0.093989,0.000000, 0.945200,-0.266600,-0.188000, 0.531200,0.413800, +0.193962,0.453788,-0.080342,0.000000, 0.390500,0.906300,-0.161700, 0.562500,0.862100, +0.147497,0.473826,-0.061095,0.000000, 0.297800,0.946600,-0.123300, 0.562500,0.896600, +0.156582,0.473826,-0.031146,0.000000, 0.316100,0.946600,-0.062900, 0.531300,0.896600, +0.193962,0.453788,-0.080342,0.000000, 0.390500,0.906300,-0.161700, 0.562500,0.862100, +0.156582,0.473826,-0.031146,0.000000, 0.316100,0.946600,-0.062900, 0.531300,0.896600, +0.205910,0.453788,-0.040958,0.000000, 0.414500,0.906300,-0.082400, 0.531300,0.862100, +0.429130,-0.185069,-0.177751,0.000000, 0.858700,-0.369000,-0.355700, 0.562500,0.379300, +0.445101,-0.133764,-0.184367,0.000000, 0.890400,-0.266600,-0.368800, 0.562500,0.413800, +0.472517,-0.133764,-0.093989,0.000000, 0.945200,-0.266600,-0.188000, 0.531200,0.413800, +0.429130,-0.185069,-0.177751,0.000000, 0.858700,-0.369000,-0.355700, 0.562500,0.379300, +0.472517,-0.133764,-0.093989,0.000000, 0.945200,-0.266600,-0.188000, 0.531200,0.413800, +0.455563,-0.185069,-0.090617,0.000000, 0.911600,-0.369000,-0.181300, 0.531200,0.379300, +0.238154,0.428429,-0.098647,0.000000, 0.478600,0.855300,-0.198200, 0.562500,0.827600, +0.193962,0.453788,-0.080342,0.000000, 0.390500,0.906300,-0.161700, 0.562500,0.862100, +0.205910,0.453788,-0.040958,0.000000, 0.414500,0.906300,-0.082400, 0.531300,0.862100, +0.238154,0.428429,-0.098647,0.000000, 0.478600,0.855300,-0.198200, 0.562500,0.827600, +0.205910,0.453788,-0.040958,0.000000, 0.414500,0.906300,-0.082400, 0.531300,0.862100, +0.252823,0.428429,-0.050290,0.000000, 0.508100,0.855300,-0.101000, 0.531300,0.827600, +0.408128,-0.234204,-0.169052,0.000000, 0.816900,-0.467000,-0.338400, 0.562500,0.344800, +0.429130,-0.185069,-0.177751,0.000000, 0.858700,-0.369000,-0.355700, 0.562500,0.379300, +0.455563,-0.185069,-0.090617,0.000000, 0.911600,-0.369000,-0.181300, 0.531200,0.379300, +0.408128,-0.234204,-0.169052,0.000000, 0.816900,-0.467000,-0.338400, 0.562500,0.344800, +0.455563,-0.185069,-0.090617,0.000000, 0.911600,-0.369000,-0.181300, 0.531200,0.379300, +0.433267,-0.234204,-0.086182,0.000000, 0.867200,-0.467000,-0.172500, 0.531200,0.344800, +0.279553,0.398046,-0.115795,0.000000, 0.561100,0.794500,-0.232400, 0.562500,0.793100, +0.238154,0.428429,-0.098647,0.000000, 0.478600,0.855300,-0.198200, 0.562500,0.827600, +0.252823,0.428429,-0.050290,0.000000, 0.508100,0.855300,-0.101000, 0.531300,0.827600, +0.279553,0.398046,-0.115795,0.000000, 0.561100,0.794500,-0.232400, 0.562500,0.793100, +0.252823,0.428429,-0.050290,0.000000, 0.508100,0.855300,-0.101000, 0.531300,0.827600, +0.296772,0.398046,-0.059032,0.000000, 0.595600,0.794500,-0.118500, 0.531300,0.793100, +0.382342,-0.280594,-0.158371,0.000000, 0.765600,-0.559600,-0.317100, 0.562500,0.310300, +0.408128,-0.234204,-0.169052,0.000000, 0.816900,-0.467000,-0.338400, 0.562500,0.344800, +0.433267,-0.234204,-0.086182,0.000000, 0.867200,-0.467000,-0.172500, 0.531200,0.344800, +0.382342,-0.280594,-0.158371,0.000000, 0.765600,-0.559600,-0.317100, 0.562500,0.310300, +0.433267,-0.234204,-0.086182,0.000000, 0.867200,-0.467000,-0.172500, 0.531200,0.344800, +0.405892,-0.280594,-0.080737,0.000000, 0.812800,-0.559600,-0.161700, 0.531200,0.310300, +0.317674,0.362998,-0.131585,0.000000, 0.637000,0.724300,-0.263800, 0.562500,0.758600, +0.279553,0.398046,-0.115795,0.000000, 0.561100,0.794500,-0.232400, 0.562500,0.793100, +0.296772,0.398046,-0.059032,0.000000, 0.595600,0.794500,-0.118500, 0.531300,0.793100, +0.317674,0.362998,-0.131585,0.000000, 0.637000,0.724300,-0.263800, 0.562500,0.758600, +0.296772,0.398046,-0.059032,0.000000, 0.595600,0.794500,-0.118500, 0.531300,0.793100, +0.337242,0.362998,-0.067082,0.000000, 0.676200,0.724300,-0.134500, 0.531300,0.758600, +0.352072,-0.323693,-0.145833,0.000000, 0.705400,-0.645700,-0.292200, 0.562500,0.275900, +0.382342,-0.280594,-0.158371,0.000000, 0.765600,-0.559600,-0.317100, 0.562500,0.310300, +0.405892,-0.280594,-0.080737,0.000000, 0.812800,-0.559600,-0.161700, 0.531200,0.310300, +0.352072,-0.323693,-0.145833,0.000000, 0.705400,-0.645700,-0.292200, 0.562500,0.275900, +0.405892,-0.280594,-0.080737,0.000000, 0.812800,-0.559600,-0.161700, 0.531200,0.310300, +0.373758,-0.323693,-0.074345,0.000000, 0.748900,-0.645700,-0.149000, 0.531200,0.275900, +0.352072,0.323693,-0.145833,0.000000, 0.705400,0.645700,-0.292200, 0.562500,0.724100, +0.317674,0.362998,-0.131585,0.000000, 0.637000,0.724300,-0.263800, 0.562500,0.758600, +0.337242,0.362998,-0.067082,0.000000, 0.676200,0.724300,-0.134500, 0.531300,0.758600, +0.352072,0.323693,-0.145833,0.000000, 0.705400,0.645700,-0.292200, 0.562500,0.724100, +0.337242,0.362998,-0.067082,0.000000, 0.676200,0.724300,-0.134500, 0.531300,0.758600, +0.373758,0.323693,-0.074345,0.000000, 0.748900,0.645700,-0.149000, 0.531200,0.724100, +0.317675,-0.362998,-0.131585,0.000000, 0.637000,-0.724300,-0.263800, 0.562500,0.241400, +0.352072,-0.323693,-0.145833,0.000000, 0.705400,-0.645700,-0.292200, 0.562500,0.275900, +0.373758,-0.323693,-0.074345,0.000000, 0.748900,-0.645700,-0.149000, 0.531200,0.275900, +0.317675,-0.362998,-0.131585,0.000000, 0.637000,-0.724300,-0.263800, 0.562500,0.241400, +0.373758,-0.323693,-0.074345,0.000000, 0.748900,-0.645700,-0.149000, 0.531200,0.275900, +0.337242,-0.362998,-0.067082,0.000000, 0.676200,-0.724300,-0.134500, 0.531200,0.241400, +0.382342,0.280594,-0.158371,0.000000, 0.765600,0.559600,-0.317100, 0.562500,0.689700, +0.352072,0.323693,-0.145833,0.000000, 0.705400,0.645700,-0.292200, 0.562500,0.724100, +0.373758,0.323693,-0.074345,0.000000, 0.748900,0.645700,-0.149000, 0.531200,0.724100, +0.382342,0.280594,-0.158371,0.000000, 0.765600,0.559600,-0.317100, 0.562500,0.689700, +0.373758,0.323693,-0.074345,0.000000, 0.748900,0.645700,-0.149000, 0.531200,0.724100, +0.405892,0.280594,-0.080737,0.000000, 0.812800,0.559600,-0.161700, 0.531300,0.689700, +0.279553,-0.398046,-0.115795,0.000000, 0.561100,-0.794500,-0.232400, 0.562500,0.206900, +0.317675,-0.362998,-0.131585,0.000000, 0.637000,-0.724300,-0.263800, 0.562500,0.241400, +0.337242,-0.362998,-0.067082,0.000000, 0.676200,-0.724300,-0.134500, 0.531200,0.241400, +0.279553,-0.398046,-0.115795,0.000000, 0.561100,-0.794500,-0.232400, 0.562500,0.206900, +0.337242,-0.362998,-0.067082,0.000000, 0.676200,-0.724300,-0.134500, 0.531200,0.241400, +0.296772,-0.398046,-0.059032,0.000000, 0.595600,-0.794500,-0.118500, 0.531200,0.206900, +0.408128,0.234204,-0.169052,0.000000, 0.816900,0.467000,-0.338400, 0.562500,0.655200, +0.382342,0.280594,-0.158371,0.000000, 0.765600,0.559600,-0.317100, 0.562500,0.689700, +0.405892,0.280594,-0.080737,0.000000, 0.812800,0.559600,-0.161700, 0.531300,0.689700, +0.408128,0.234204,-0.169052,0.000000, 0.816900,0.467000,-0.338400, 0.562500,0.655200, +0.405892,0.280594,-0.080737,0.000000, 0.812800,0.559600,-0.161700, 0.531300,0.689700, +0.433267,0.234204,-0.086182,0.000000, 0.867200,0.467000,-0.172500, 0.531200,0.655200, +0.433267,-0.234204,-0.086182,0.000000, 0.867200,-0.467000,-0.172500, 0.531200,0.344800, +0.455563,-0.185069,-0.090617,0.000000, 0.911600,-0.369000,-0.181300, 0.531200,0.379300, +0.464487,-0.185069,0.000000,0.000000, 0.929400,-0.369000,0.000000, 0.500000,0.379300, +0.433267,-0.234204,-0.086182,0.000000, 0.867200,-0.467000,-0.172500, 0.531200,0.344800, +0.464487,-0.185069,0.000000,0.000000, 0.929400,-0.369000,0.000000, 0.500000,0.379300, +0.441755,-0.234204,0.000000,0.000000, 0.884200,-0.467000,0.000000, 0.500000,0.344800, +0.296772,0.398046,-0.059032,0.000000, 0.595600,0.794500,-0.118500, 0.531300,0.793100, +0.252823,0.428429,-0.050290,0.000000, 0.508100,0.855300,-0.101000, 0.531300,0.827600, +0.257776,0.428429,-0.000000,0.000000, 0.518000,0.855300,0.000000, 0.500000,0.827600, +0.296772,0.398046,-0.059032,0.000000, 0.595600,0.794500,-0.118500, 0.531300,0.793100, +0.257776,0.428429,-0.000000,0.000000, 0.518000,0.855300,0.000000, 0.500000,0.827600, +0.302586,0.398046,0.000000,0.000000, 0.607300,0.794500,0.000000, 0.500000,0.793100, +0.405892,-0.280594,-0.080737,0.000000, 0.812800,-0.559600,-0.161700, 0.531200,0.310300, +0.433267,-0.234204,-0.086182,0.000000, 0.867200,-0.467000,-0.172500, 0.531200,0.344800, +0.441755,-0.234204,0.000000,0.000000, 0.884200,-0.467000,0.000000, 0.500000,0.344800, +0.405892,-0.280594,-0.080737,0.000000, 0.812800,-0.559600,-0.161700, 0.531200,0.310300, +0.441755,-0.234204,0.000000,0.000000, 0.884200,-0.467000,0.000000, 0.500000,0.344800, +0.413844,-0.280594,0.000000,0.000000, 0.828700,-0.559600,0.000000, 0.500000,0.310300, +0.337242,0.362998,-0.067082,0.000000, 0.676200,0.724300,-0.134500, 0.531300,0.758600, +0.296772,0.398046,-0.059032,0.000000, 0.595600,0.794500,-0.118500, 0.531300,0.793100, +0.302586,0.398046,0.000000,0.000000, 0.607300,0.794500,0.000000, 0.500000,0.793100, +0.337242,0.362998,-0.067082,0.000000, 0.676200,0.724300,-0.134500, 0.531300,0.758600, +0.302586,0.398046,0.000000,0.000000, 0.607300,0.794500,0.000000, 0.500000,0.793100, +0.343848,0.362998,-0.000000,0.000000, 0.689400,0.724300,0.000000, 0.500000,0.758600, +0.373758,-0.323693,-0.074345,0.000000, 0.748900,-0.645700,-0.149000, 0.531200,0.275900, +0.405892,-0.280594,-0.080737,0.000000, 0.812800,-0.559600,-0.161700, 0.531200,0.310300, +0.413844,-0.280594,0.000000,0.000000, 0.828700,-0.559600,0.000000, 0.500000,0.310300, +0.373758,-0.323693,-0.074345,0.000000, 0.748900,-0.645700,-0.149000, 0.531200,0.275900, +0.413844,-0.280594,0.000000,0.000000, 0.828700,-0.559600,0.000000, 0.500000,0.310300, +0.381080,-0.323693,0.000000,0.000000, 0.763500,-0.645700,0.000000, 0.500000,0.275900, +0.373758,0.323693,-0.074345,0.000000, 0.748900,0.645700,-0.149000, 0.531200,0.724100, +0.337242,0.362998,-0.067082,0.000000, 0.676200,0.724300,-0.134500, 0.531300,0.758600, +0.343848,0.362998,-0.000000,0.000000, 0.689400,0.724300,0.000000, 0.500000,0.758600, +0.373758,0.323693,-0.074345,0.000000, 0.748900,0.645700,-0.149000, 0.531200,0.724100, +0.343848,0.362998,-0.000000,0.000000, 0.689400,0.724300,0.000000, 0.500000,0.758600, +0.381080,0.323693,0.000000,0.000000, 0.763500,0.645700,0.000000, 0.500000,0.724100, +0.337242,-0.362998,-0.067082,0.000000, 0.676200,-0.724300,-0.134500, 0.531200,0.241400, +0.373758,-0.323693,-0.074345,0.000000, 0.748900,-0.645700,-0.149000, 0.531200,0.275900, +0.381080,-0.323693,0.000000,0.000000, 0.763500,-0.645700,0.000000, 0.500000,0.275900, +0.337242,-0.362998,-0.067082,0.000000, 0.676200,-0.724300,-0.134500, 0.531200,0.241400, +0.381080,-0.323693,0.000000,0.000000, 0.763500,-0.645700,0.000000, 0.500000,0.275900, +0.343849,-0.362998,0.000000,0.000000, 0.689400,-0.724300,0.000000, 0.500000,0.241400, +0.405892,0.280594,-0.080737,0.000000, 0.812800,0.559600,-0.161700, 0.531300,0.689700, +0.373758,0.323693,-0.074345,0.000000, 0.748900,0.645700,-0.149000, 0.531200,0.724100, +0.381080,0.323693,0.000000,0.000000, 0.763500,0.645700,0.000000, 0.500000,0.724100, +0.405892,0.280594,-0.080737,0.000000, 0.812800,0.559600,-0.161700, 0.531300,0.689700, +0.381080,0.323693,0.000000,0.000000, 0.763500,0.645700,0.000000, 0.500000,0.724100, +0.413844,0.280594,0.000000,0.000000, 0.828700,0.559600,0.000000, 0.500000,0.689700, +0.296772,-0.398046,-0.059032,0.000000, 0.595600,-0.794500,-0.118500, 0.531200,0.206900, +0.337242,-0.362998,-0.067082,0.000000, 0.676200,-0.724300,-0.134500, 0.531200,0.241400, +0.343849,-0.362998,0.000000,0.000000, 0.689400,-0.724300,0.000000, 0.500000,0.241400, +0.296772,-0.398046,-0.059032,0.000000, 0.595600,-0.794500,-0.118500, 0.531200,0.206900, +0.343849,-0.362998,0.000000,0.000000, 0.689400,-0.724300,0.000000, 0.500000,0.241400, +0.302586,-0.398046,0.000000,0.000000, 0.607300,-0.794500,0.000000, 0.500000,0.206900, +0.433267,0.234204,-0.086182,0.000000, 0.867200,0.467000,-0.172500, 0.531200,0.655200, +0.405892,0.280594,-0.080737,0.000000, 0.812800,0.559600,-0.161700, 0.531300,0.689700, +0.413844,0.280594,0.000000,0.000000, 0.828700,0.559600,0.000000, 0.500000,0.689700, +0.433267,0.234204,-0.086182,0.000000, 0.867200,0.467000,-0.172500, 0.531200,0.655200, +0.413844,0.280594,0.000000,0.000000, 0.828700,0.559600,0.000000, 0.500000,0.689700, +0.441755,0.234204,0.000000,0.000000, 0.884200,0.467000,0.000000, 0.500000,0.655200, +0.252823,-0.428429,-0.050290,0.000000, 0.508100,-0.855300,-0.101000, 0.531200,0.172400, +0.296772,-0.398046,-0.059032,0.000000, 0.595600,-0.794500,-0.118500, 0.531200,0.206900, +0.302586,-0.398046,0.000000,0.000000, 0.607300,-0.794500,0.000000, 0.500000,0.206900, +0.252823,-0.428429,-0.050290,0.000000, 0.508100,-0.855300,-0.101000, 0.531200,0.172400, +0.302586,-0.398046,0.000000,0.000000, 0.607300,-0.794500,0.000000, 0.500000,0.206900, +0.257776,-0.428429,0.000000,0.000000, 0.518000,-0.855300,0.000000, 0.500000,0.172400, +0.455563,0.185069,-0.090617,0.000000, 0.911600,0.369000,-0.181300, 0.531200,0.620700, +0.433267,0.234204,-0.086182,0.000000, 0.867200,0.467000,-0.172500, 0.531200,0.655200, +0.441755,0.234204,0.000000,0.000000, 0.884200,0.467000,0.000000, 0.500000,0.655200, +0.455563,0.185069,-0.090617,0.000000, 0.911600,0.369000,-0.181300, 0.531200,0.620700, +0.441755,0.234204,0.000000,0.000000, 0.884200,0.467000,0.000000, 0.500000,0.655200, +0.464487,0.185069,0.000000,0.000000, 0.929400,0.369000,0.000000, 0.500000,0.620700, +0.205910,-0.453788,-0.040958,0.000000, 0.414500,-0.906300,-0.082400, 0.531200,0.137900, +0.252823,-0.428429,-0.050290,0.000000, 0.508100,-0.855300,-0.101000, 0.531200,0.172400, +0.257776,-0.428429,0.000000,0.000000, 0.518000,-0.855300,0.000000, 0.500000,0.172400, +0.205910,-0.453788,-0.040958,0.000000, 0.414500,-0.906300,-0.082400, 0.531200,0.137900, +0.257776,-0.428429,0.000000,0.000000, 0.518000,-0.855300,0.000000, 0.500000,0.172400, +0.209944,-0.453788,0.000000,0.000000, 0.422700,-0.906300,0.000000, 0.500000,0.137900, +0.472517,0.133764,-0.093989,0.000000, 0.945200,0.266600,-0.188000, 0.531200,0.586200, +0.455563,0.185069,-0.090617,0.000000, 0.911600,0.369000,-0.181300, 0.531200,0.620700, +0.464487,0.185069,0.000000,0.000000, 0.929400,0.369000,0.000000, 0.500000,0.620700, +0.472517,0.133764,-0.093989,0.000000, 0.945200,0.266600,-0.188000, 0.531200,0.586200, +0.464487,0.185069,0.000000,0.000000, 0.929400,0.369000,0.000000, 0.500000,0.620700, +0.481774,0.133764,0.000000,0.000000, 0.963800,0.266600,0.000000, 0.500000,0.586200, +0.156583,-0.473826,-0.031147,0.000000, 0.316100,-0.946600,-0.062900, 0.531300,0.103400, +0.205910,-0.453788,-0.040958,0.000000, 0.414500,-0.906300,-0.082400, 0.531200,0.137900, +0.209944,-0.453788,0.000000,0.000000, 0.422700,-0.906300,0.000000, 0.500000,0.137900, +0.156583,-0.473826,-0.031147,0.000000, 0.316100,-0.946600,-0.062900, 0.531300,0.103400, +0.209944,-0.453788,0.000000,0.000000, 0.422700,-0.906300,0.000000, 0.500000,0.137900, +0.159650,-0.473826,-0.000000,0.000000, 0.322300,-0.946600,0.000000, 0.500000,0.103400, +0.483932,0.080891,-0.096260,0.000000, 0.967900,0.161200,-0.192500, 0.531200,0.551700, +0.472517,0.133764,-0.093989,0.000000, 0.945200,0.266600,-0.188000, 0.531200,0.586200, +0.481774,0.133764,0.000000,0.000000, 0.963800,0.266600,0.000000, 0.500000,0.586200, +0.483932,0.080891,-0.096260,0.000000, 0.967900,0.161200,-0.192500, 0.531200,0.551700, +0.481774,0.133764,0.000000,0.000000, 0.963800,0.266600,0.000000, 0.500000,0.586200, +0.493412,0.080891,0.000000,0.000000, 0.986900,0.161200,0.000000, 0.500000,0.551700, +0.105420,-0.488310,-0.020970,0.000000, 0.214000,-0.975900,-0.042500, 0.531300,0.069000, +0.156583,-0.473826,-0.031147,0.000000, 0.316100,-0.946600,-0.062900, 0.531300,0.103400, +0.159650,-0.473826,-0.000000,0.000000, 0.322300,-0.946600,0.000000, 0.500000,0.103400, +0.105420,-0.488310,-0.020970,0.000000, 0.214000,-0.975900,-0.042500, 0.531300,0.069000, +0.159650,-0.473826,-0.000000,0.000000, 0.322300,-0.946600,0.000000, 0.500000,0.103400, +0.107484,-0.488310,0.000000,0.000000, 0.218200,-0.975900,0.000000, 0.500000,0.069000, +0.489673,0.027069,-0.097402,0.000000, 0.979300,0.054000,-0.194800, 0.531200,0.517200, +0.483932,0.080891,-0.096260,0.000000, 0.967900,0.161200,-0.192500, 0.531200,0.551700, +0.493412,0.080891,0.000000,0.000000, 0.986900,0.161200,0.000000, 0.500000,0.551700, +0.489673,0.027069,-0.097402,0.000000, 0.979300,0.054000,-0.194800, 0.531200,0.517200, +0.493412,0.080891,0.000000,0.000000, 0.986900,0.161200,0.000000, 0.500000,0.551700, +0.499265,0.027069,0.000000,0.000000, 0.998500,0.054000,0.000000, 0.500000,0.517200, +0.053020,0.497069,-0.010546,0.000000, 0.109300,0.993700,-0.021700, 0.454400,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +0.054058,0.497069,0.000000,0.000000, 0.111500,0.993700,0.000000, 0.456200,0.962300, +0.053020,-0.497069,-0.010546,0.000000, 0.109300,-0.993700,-0.021700, 0.531300,0.034500, +0.105420,-0.488310,-0.020970,0.000000, 0.214000,-0.975900,-0.042500, 0.531300,0.069000, +0.107484,-0.488310,0.000000,0.000000, 0.218200,-0.975900,0.000000, 0.500000,0.069000, +0.053020,-0.497069,-0.010546,0.000000, 0.109300,-0.993700,-0.021700, 0.531300,0.034500, +0.107484,-0.488310,0.000000,0.000000, 0.218200,-0.975900,0.000000, 0.500000,0.069000, +0.054059,-0.497069,0.000000,0.000000, 0.111500,-0.993700,0.000000, 0.500000,0.034500, +0.489673,-0.027069,-0.097402,0.000000, 0.979300,-0.054000,-0.194800, 0.531200,0.482800, +0.489673,0.027069,-0.097402,0.000000, 0.979300,0.054000,-0.194800, 0.531200,0.517200, +0.499265,0.027069,0.000000,0.000000, 0.998500,0.054000,0.000000, 0.500000,0.517200, +0.489673,-0.027069,-0.097402,0.000000, 0.979300,-0.054000,-0.194800, 0.531200,0.482800, +0.499265,0.027069,0.000000,0.000000, 0.998500,0.054000,0.000000, 0.500000,0.517200, +0.499265,-0.027069,0.000000,0.000000, 0.998500,-0.054000,0.000000, 0.500000,0.482800, +0.105419,0.488310,-0.020969,0.000000, 0.214000,0.975900,-0.042500, 0.531300,0.931000, +0.053020,0.497069,-0.010546,0.000000, 0.109300,0.993700,-0.021700, 0.531300,0.965500, +0.054058,0.497069,0.000000,0.000000, 0.111500,0.993700,0.000000, 0.500000,0.965500, +0.105419,0.488310,-0.020969,0.000000, 0.214000,0.975900,-0.042500, 0.531300,0.931000, +0.054058,0.497069,0.000000,0.000000, 0.111500,0.993700,0.000000, 0.500000,0.965500, +0.107484,0.488310,0.000000,0.000000, 0.218200,0.975900,0.000000, 0.500000,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.495500,0.051000, +0.053020,-0.497069,-0.010546,0.000000, 0.109300,-0.993700,-0.021700, 0.454900,0.053800, +0.054059,-0.497069,0.000000,0.000000, 0.111500,-0.993700,0.000000, 0.452300,0.053800, +0.483932,-0.080891,-0.096260,0.000000, 0.967900,-0.161200,-0.192500, 0.531200,0.448300, +0.489673,-0.027069,-0.097402,0.000000, 0.979300,-0.054000,-0.194800, 0.531200,0.482800, +0.499265,-0.027069,0.000000,0.000000, 0.998500,-0.054000,0.000000, 0.500000,0.482800, +0.483932,-0.080891,-0.096260,0.000000, 0.967900,-0.161200,-0.192500, 0.531200,0.448300, +0.499265,-0.027069,0.000000,0.000000, 0.998500,-0.054000,0.000000, 0.500000,0.482800, +0.493412,-0.080891,0.000000,0.000000, 0.986900,-0.161200,0.000000, 0.500000,0.448300, +0.156582,0.473826,-0.031146,0.000000, 0.316100,0.946600,-0.062900, 0.531300,0.896600, +0.105419,0.488310,-0.020969,0.000000, 0.214000,0.975900,-0.042500, 0.531300,0.931000, +0.107484,0.488310,0.000000,0.000000, 0.218200,0.975900,0.000000, 0.500000,0.931000, +0.156582,0.473826,-0.031146,0.000000, 0.316100,0.946600,-0.062900, 0.531300,0.896600, +0.107484,0.488310,0.000000,0.000000, 0.218200,0.975900,0.000000, 0.500000,0.931000, +0.159650,0.473826,0.000000,0.000000, 0.322300,0.946600,0.000000, 0.500000,0.896600, +0.472517,-0.133764,-0.093989,0.000000, 0.945200,-0.266600,-0.188000, 0.531200,0.413800, +0.483932,-0.080891,-0.096260,0.000000, 0.967900,-0.161200,-0.192500, 0.531200,0.448300, +0.493412,-0.080891,0.000000,0.000000, 0.986900,-0.161200,0.000000, 0.500000,0.448300, +0.472517,-0.133764,-0.093989,0.000000, 0.945200,-0.266600,-0.188000, 0.531200,0.413800, +0.493412,-0.080891,0.000000,0.000000, 0.986900,-0.161200,0.000000, 0.500000,0.448300, +0.481774,-0.133764,0.000000,0.000000, 0.963800,-0.266600,0.000000, 0.500000,0.413800, +0.205910,0.453788,-0.040958,0.000000, 0.414500,0.906300,-0.082400, 0.531300,0.862100, +0.156582,0.473826,-0.031146,0.000000, 0.316100,0.946600,-0.062900, 0.531300,0.896600, +0.159650,0.473826,0.000000,0.000000, 0.322300,0.946600,0.000000, 0.500000,0.896600, +0.205910,0.453788,-0.040958,0.000000, 0.414500,0.906300,-0.082400, 0.531300,0.862100, +0.159650,0.473826,0.000000,0.000000, 0.322300,0.946600,0.000000, 0.500000,0.896600, +0.209944,0.453788,0.000000,0.000000, 0.422700,0.906300,0.000000, 0.500000,0.862100, +0.455563,-0.185069,-0.090617,0.000000, 0.911600,-0.369000,-0.181300, 0.531200,0.379300, +0.472517,-0.133764,-0.093989,0.000000, 0.945200,-0.266600,-0.188000, 0.531200,0.413800, +0.481774,-0.133764,0.000000,0.000000, 0.963800,-0.266600,0.000000, 0.500000,0.413800, +0.455563,-0.185069,-0.090617,0.000000, 0.911600,-0.369000,-0.181300, 0.531200,0.379300, +0.481774,-0.133764,0.000000,0.000000, 0.963800,-0.266600,0.000000, 0.500000,0.413800, +0.464487,-0.185069,0.000000,0.000000, 0.929400,-0.369000,0.000000, 0.500000,0.379300, +0.252823,0.428429,-0.050290,0.000000, 0.508100,0.855300,-0.101000, 0.531300,0.827600, +0.205910,0.453788,-0.040958,0.000000, 0.414500,0.906300,-0.082400, 0.531300,0.862100, +0.209944,0.453788,0.000000,0.000000, 0.422700,0.906300,0.000000, 0.500000,0.862100, +0.252823,0.428429,-0.050290,0.000000, 0.508100,0.855300,-0.101000, 0.531300,0.827600, +0.209944,0.453788,0.000000,0.000000, 0.422700,0.906300,0.000000, 0.500000,0.862100, +0.257776,0.428429,-0.000000,0.000000, 0.518000,0.855300,0.000000, 0.500000,0.827600, +0.107484,-0.488310,0.000000,0.000000, 0.218200,-0.975900,0.000000, 0.500000,0.069000, +0.159650,-0.473826,-0.000000,0.000000, 0.322300,-0.946600,0.000000, 0.500000,0.103400, +0.156583,-0.473826,0.031147,0.000000, 0.316100,-0.946600,0.062900, 0.468700,0.103400, +0.107484,-0.488310,0.000000,0.000000, 0.218200,-0.975900,0.000000, 0.500000,0.069000, +0.156583,-0.473826,0.031147,0.000000, 0.316100,-0.946600,0.062900, 0.468700,0.103400, +0.105420,-0.488310,0.020970,0.000000, 0.214000,-0.975900,0.042500, 0.468700,0.069000, +0.499265,0.027069,0.000000,0.000000, 0.998500,0.054000,0.000000, 0.500000,0.517200, +0.493412,0.080891,0.000000,0.000000, 0.986900,0.161200,0.000000, 0.500000,0.551700, +0.483932,0.080891,0.096260,0.000000, 0.967900,0.161200,0.192500, 0.468700,0.551700, +0.499265,0.027069,0.000000,0.000000, 0.998500,0.054000,0.000000, 0.500000,0.517200, +0.483932,0.080891,0.096260,0.000000, 0.967900,0.161200,0.192500, 0.468700,0.551700, +0.489673,0.027069,0.097402,0.000000, 0.979300,0.054000,0.194800, 0.468700,0.517200, +0.054058,0.497069,0.000000,0.000000, 0.111500,0.993700,0.000000, 0.456200,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +0.053020,0.497069,0.010546,0.000000, 0.109300,0.993700,0.021700, 0.458000,0.962300, +0.054059,-0.497069,0.000000,0.000000, 0.111500,-0.993700,0.000000, 0.500000,0.034500, +0.107484,-0.488310,0.000000,0.000000, 0.218200,-0.975900,0.000000, 0.500000,0.069000, +0.105420,-0.488310,0.020970,0.000000, 0.214000,-0.975900,0.042500, 0.468700,0.069000, +0.054059,-0.497069,0.000000,0.000000, 0.111500,-0.993700,0.000000, 0.500000,0.034500, +0.105420,-0.488310,0.020970,0.000000, 0.214000,-0.975900,0.042500, 0.468700,0.069000, +0.053020,-0.497069,0.010546,0.000000, 0.109300,-0.993700,0.021700, 0.468700,0.034500, +0.499265,-0.027069,0.000000,0.000000, 0.998500,-0.054000,0.000000, 0.500000,0.482800, +0.499265,0.027069,0.000000,0.000000, 0.998500,0.054000,0.000000, 0.500000,0.517200, +0.489673,0.027069,0.097402,0.000000, 0.979300,0.054000,0.194800, 0.468700,0.517200, +0.499265,-0.027069,0.000000,0.000000, 0.998500,-0.054000,0.000000, 0.500000,0.482800, +0.489673,0.027069,0.097402,0.000000, 0.979300,0.054000,0.194800, 0.468700,0.517200, +0.489673,-0.027069,0.097402,0.000000, 0.979300,-0.054000,0.194800, 0.468700,0.482800, +0.107484,0.488310,0.000000,0.000000, 0.218200,0.975900,0.000000, 0.500000,0.931000, +0.054058,0.497069,0.000000,0.000000, 0.111500,0.993700,0.000000, 0.500000,0.965500, +0.053020,0.497069,0.010546,0.000000, 0.109300,0.993700,0.021700, 0.468700,0.965500, +0.107484,0.488310,0.000000,0.000000, 0.218200,0.975900,0.000000, 0.500000,0.931000, +0.053020,0.497069,0.010546,0.000000, 0.109300,0.993700,0.021700, 0.468700,0.965500, +0.105419,0.488310,0.020970,0.000000, 0.214000,0.975900,0.042500, 0.468700,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +0.054059,-0.497069,0.000000,0.000000, 0.111500,-0.993700,0.000000, 0.452300,0.053800, +0.053020,-0.497069,0.010546,0.000000, 0.109300,-0.993700,0.021700, 0.449700,0.053800, +0.493412,-0.080891,0.000000,0.000000, 0.986900,-0.161200,0.000000, 0.500000,0.448300, +0.499265,-0.027069,0.000000,0.000000, 0.998500,-0.054000,0.000000, 0.500000,0.482800, +0.489673,-0.027069,0.097402,0.000000, 0.979300,-0.054000,0.194800, 0.468700,0.482800, +0.493412,-0.080891,0.000000,0.000000, 0.986900,-0.161200,0.000000, 0.500000,0.448300, +0.489673,-0.027069,0.097402,0.000000, 0.979300,-0.054000,0.194800, 0.468700,0.482800, +0.483932,-0.080891,0.096260,0.000000, 0.967900,-0.161200,0.192500, 0.468700,0.448300, +0.159650,0.473826,0.000000,0.000000, 0.322300,0.946600,0.000000, 0.500000,0.896600, +0.107484,0.488310,0.000000,0.000000, 0.218200,0.975900,0.000000, 0.500000,0.931000, +0.105419,0.488310,0.020970,0.000000, 0.214000,0.975900,0.042500, 0.468700,0.931000, +0.159650,0.473826,0.000000,0.000000, 0.322300,0.946600,0.000000, 0.500000,0.896600, +0.105419,0.488310,0.020970,0.000000, 0.214000,0.975900,0.042500, 0.468700,0.931000, +0.156582,0.473826,0.031146,0.000000, 0.316100,0.946600,0.062900, 0.468700,0.896600, +0.481774,-0.133764,0.000000,0.000000, 0.963800,-0.266600,0.000000, 0.500000,0.413800, +0.493412,-0.080891,0.000000,0.000000, 0.986900,-0.161200,0.000000, 0.500000,0.448300, +0.483932,-0.080891,0.096260,0.000000, 0.967900,-0.161200,0.192500, 0.468700,0.448300, +0.481774,-0.133764,0.000000,0.000000, 0.963800,-0.266600,0.000000, 0.500000,0.413800, +0.483932,-0.080891,0.096260,0.000000, 0.967900,-0.161200,0.192500, 0.468700,0.448300, +0.472517,-0.133764,0.093989,0.000000, 0.945200,-0.266600,0.188000, 0.468700,0.413800, +0.209944,0.453788,0.000000,0.000000, 0.422700,0.906300,0.000000, 0.500000,0.862100, +0.159650,0.473826,0.000000,0.000000, 0.322300,0.946600,0.000000, 0.500000,0.896600, +0.156582,0.473826,0.031146,0.000000, 0.316100,0.946600,0.062900, 0.468700,0.896600, +0.209944,0.453788,0.000000,0.000000, 0.422700,0.906300,0.000000, 0.500000,0.862100, +0.156582,0.473826,0.031146,0.000000, 0.316100,0.946600,0.062900, 0.468700,0.896600, +0.205910,0.453788,0.040958,0.000000, 0.414500,0.906300,0.082400, 0.468700,0.862100, +0.464487,-0.185069,0.000000,0.000000, 0.929400,-0.369000,0.000000, 0.500000,0.379300, +0.481774,-0.133764,0.000000,0.000000, 0.963800,-0.266600,0.000000, 0.500000,0.413800, +0.472517,-0.133764,0.093989,0.000000, 0.945200,-0.266600,0.188000, 0.468700,0.413800, +0.464487,-0.185069,0.000000,0.000000, 0.929400,-0.369000,0.000000, 0.500000,0.379300, +0.472517,-0.133764,0.093989,0.000000, 0.945200,-0.266600,0.188000, 0.468700,0.413800, +0.455563,-0.185069,0.090617,0.000000, 0.911600,-0.369000,0.181300, 0.468700,0.379300, +0.257776,0.428429,-0.000000,0.000000, 0.518000,0.855300,0.000000, 0.500000,0.827600, +0.209944,0.453788,0.000000,0.000000, 0.422700,0.906300,0.000000, 0.500000,0.862100, +0.205910,0.453788,0.040958,0.000000, 0.414500,0.906300,0.082400, 0.468700,0.862100, +0.257776,0.428429,-0.000000,0.000000, 0.518000,0.855300,0.000000, 0.500000,0.827600, +0.205910,0.453788,0.040958,0.000000, 0.414500,0.906300,0.082400, 0.468700,0.862100, +0.252823,0.428429,0.050290,0.000000, 0.508100,0.855300,0.101000, 0.468700,0.827600, +0.441755,-0.234204,0.000000,0.000000, 0.884200,-0.467000,0.000000, 0.500000,0.344800, +0.464487,-0.185069,0.000000,0.000000, 0.929400,-0.369000,0.000000, 0.500000,0.379300, +0.455563,-0.185069,0.090617,0.000000, 0.911600,-0.369000,0.181300, 0.468700,0.379300, +0.441755,-0.234204,0.000000,0.000000, 0.884200,-0.467000,0.000000, 0.500000,0.344800, +0.455563,-0.185069,0.090617,0.000000, 0.911600,-0.369000,0.181300, 0.468700,0.379300, +0.433267,-0.234204,0.086182,0.000000, 0.867200,-0.467000,0.172500, 0.468700,0.344800, +0.302586,0.398046,0.000000,0.000000, 0.607300,0.794500,0.000000, 0.500000,0.793100, +0.257776,0.428429,-0.000000,0.000000, 0.518000,0.855300,0.000000, 0.500000,0.827600, +0.252823,0.428429,0.050290,0.000000, 0.508100,0.855300,0.101000, 0.468700,0.827600, +0.302586,0.398046,0.000000,0.000000, 0.607300,0.794500,0.000000, 0.500000,0.793100, +0.252823,0.428429,0.050290,0.000000, 0.508100,0.855300,0.101000, 0.468700,0.827600, +0.296772,0.398046,0.059032,0.000000, 0.595600,0.794500,0.118500, 0.468700,0.793100, +0.413844,-0.280594,0.000000,0.000000, 0.828700,-0.559600,0.000000, 0.500000,0.310300, +0.441755,-0.234204,0.000000,0.000000, 0.884200,-0.467000,0.000000, 0.500000,0.344800, +0.433267,-0.234204,0.086182,0.000000, 0.867200,-0.467000,0.172500, 0.468700,0.344800, +0.413844,-0.280594,0.000000,0.000000, 0.828700,-0.559600,0.000000, 0.500000,0.310300, +0.433267,-0.234204,0.086182,0.000000, 0.867200,-0.467000,0.172500, 0.468700,0.344800, +0.405892,-0.280594,0.080737,0.000000, 0.812800,-0.559600,0.161700, 0.468700,0.310300, +0.343848,0.362998,-0.000000,0.000000, 0.689400,0.724300,0.000000, 0.500000,0.758600, +0.302586,0.398046,0.000000,0.000000, 0.607300,0.794500,0.000000, 0.500000,0.793100, +0.296772,0.398046,0.059032,0.000000, 0.595600,0.794500,0.118500, 0.468700,0.793100, +0.343848,0.362998,-0.000000,0.000000, 0.689400,0.724300,0.000000, 0.500000,0.758600, +0.296772,0.398046,0.059032,0.000000, 0.595600,0.794500,0.118500, 0.468700,0.793100, +0.337242,0.362998,0.067082,0.000000, 0.676200,0.724300,0.134500, 0.468800,0.758600, +0.381080,-0.323693,0.000000,0.000000, 0.763500,-0.645700,0.000000, 0.500000,0.275900, +0.413844,-0.280594,0.000000,0.000000, 0.828700,-0.559600,0.000000, 0.500000,0.310300, +0.405892,-0.280594,0.080737,0.000000, 0.812800,-0.559600,0.161700, 0.468700,0.310300, +0.381080,-0.323693,0.000000,0.000000, 0.763500,-0.645700,0.000000, 0.500000,0.275900, +0.405892,-0.280594,0.080737,0.000000, 0.812800,-0.559600,0.161700, 0.468700,0.310300, +0.373758,-0.323693,0.074345,0.000000, 0.748900,-0.645700,0.149000, 0.468700,0.275900, +0.381080,0.323693,0.000000,0.000000, 0.763500,0.645700,0.000000, 0.500000,0.724100, +0.343848,0.362998,-0.000000,0.000000, 0.689400,0.724300,0.000000, 0.500000,0.758600, +0.337242,0.362998,0.067082,0.000000, 0.676200,0.724300,0.134500, 0.468800,0.758600, +0.381080,0.323693,0.000000,0.000000, 0.763500,0.645700,0.000000, 0.500000,0.724100, +0.337242,0.362998,0.067082,0.000000, 0.676200,0.724300,0.134500, 0.468800,0.758600, +0.373758,0.323693,0.074345,0.000000, 0.748900,0.645700,0.149000, 0.468700,0.724100, +0.343849,-0.362998,0.000000,0.000000, 0.689400,-0.724300,0.000000, 0.500000,0.241400, +0.381080,-0.323693,0.000000,0.000000, 0.763500,-0.645700,0.000000, 0.500000,0.275900, +0.373758,-0.323693,0.074345,0.000000, 0.748900,-0.645700,0.149000, 0.468700,0.275900, +0.343849,-0.362998,0.000000,0.000000, 0.689400,-0.724300,0.000000, 0.500000,0.241400, +0.373758,-0.323693,0.074345,0.000000, 0.748900,-0.645700,0.149000, 0.468700,0.275900, +0.337242,-0.362998,0.067082,0.000000, 0.676200,-0.724300,0.134500, 0.468700,0.241400, +0.413844,0.280594,0.000000,0.000000, 0.828700,0.559600,0.000000, 0.500000,0.689700, +0.381080,0.323693,0.000000,0.000000, 0.763500,0.645700,0.000000, 0.500000,0.724100, +0.373758,0.323693,0.074345,0.000000, 0.748900,0.645700,0.149000, 0.468700,0.724100, +0.413844,0.280594,0.000000,0.000000, 0.828700,0.559600,0.000000, 0.500000,0.689700, +0.373758,0.323693,0.074345,0.000000, 0.748900,0.645700,0.149000, 0.468700,0.724100, +0.405892,0.280594,0.080737,0.000000, 0.812800,0.559600,0.161700, 0.468700,0.689700, +0.302586,-0.398046,0.000000,0.000000, 0.607300,-0.794500,0.000000, 0.500000,0.206900, +0.343849,-0.362998,0.000000,0.000000, 0.689400,-0.724300,0.000000, 0.500000,0.241400, +0.337242,-0.362998,0.067082,0.000000, 0.676200,-0.724300,0.134500, 0.468700,0.241400, +0.302586,-0.398046,0.000000,0.000000, 0.607300,-0.794500,0.000000, 0.500000,0.206900, +0.337242,-0.362998,0.067082,0.000000, 0.676200,-0.724300,0.134500, 0.468700,0.241400, +0.296772,-0.398046,0.059032,0.000000, 0.595600,-0.794500,0.118500, 0.468700,0.206900, +0.441755,0.234204,0.000000,0.000000, 0.884200,0.467000,0.000000, 0.500000,0.655200, +0.413844,0.280594,0.000000,0.000000, 0.828700,0.559600,0.000000, 0.500000,0.689700, +0.405892,0.280594,0.080737,0.000000, 0.812800,0.559600,0.161700, 0.468700,0.689700, +0.441755,0.234204,0.000000,0.000000, 0.884200,0.467000,0.000000, 0.500000,0.655200, +0.405892,0.280594,0.080737,0.000000, 0.812800,0.559600,0.161700, 0.468700,0.689700, +0.433267,0.234204,0.086182,0.000000, 0.867200,0.467000,0.172500, 0.468700,0.655200, +0.257776,-0.428429,0.000000,0.000000, 0.518000,-0.855300,0.000000, 0.500000,0.172400, +0.302586,-0.398046,0.000000,0.000000, 0.607300,-0.794500,0.000000, 0.500000,0.206900, +0.296772,-0.398046,0.059032,0.000000, 0.595600,-0.794500,0.118500, 0.468700,0.206900, +0.257776,-0.428429,0.000000,0.000000, 0.518000,-0.855300,0.000000, 0.500000,0.172400, +0.296772,-0.398046,0.059032,0.000000, 0.595600,-0.794500,0.118500, 0.468700,0.206900, +0.252823,-0.428429,0.050290,0.000000, 0.508100,-0.855300,0.101000, 0.468700,0.172400, +0.464487,0.185069,0.000000,0.000000, 0.929400,0.369000,0.000000, 0.500000,0.620700, +0.441755,0.234204,0.000000,0.000000, 0.884200,0.467000,0.000000, 0.500000,0.655200, +0.433267,0.234204,0.086182,0.000000, 0.867200,0.467000,0.172500, 0.468700,0.655200, +0.464487,0.185069,0.000000,0.000000, 0.929400,0.369000,0.000000, 0.500000,0.620700, +0.433267,0.234204,0.086182,0.000000, 0.867200,0.467000,0.172500, 0.468700,0.655200, +0.455563,0.185069,0.090617,0.000000, 0.911600,0.369000,0.181300, 0.468700,0.620700, +0.209944,-0.453788,0.000000,0.000000, 0.422700,-0.906300,0.000000, 0.500000,0.137900, +0.257776,-0.428429,0.000000,0.000000, 0.518000,-0.855300,0.000000, 0.500000,0.172400, +0.252823,-0.428429,0.050290,0.000000, 0.508100,-0.855300,0.101000, 0.468700,0.172400, +0.209944,-0.453788,0.000000,0.000000, 0.422700,-0.906300,0.000000, 0.500000,0.137900, +0.252823,-0.428429,0.050290,0.000000, 0.508100,-0.855300,0.101000, 0.468700,0.172400, +0.205910,-0.453788,0.040958,0.000000, 0.414500,-0.906300,0.082400, 0.468700,0.137900, +0.481774,0.133764,0.000000,0.000000, 0.963800,0.266600,0.000000, 0.500000,0.586200, +0.464487,0.185069,0.000000,0.000000, 0.929400,0.369000,0.000000, 0.500000,0.620700, +0.455563,0.185069,0.090617,0.000000, 0.911600,0.369000,0.181300, 0.468700,0.620700, +0.481774,0.133764,0.000000,0.000000, 0.963800,0.266600,0.000000, 0.500000,0.586200, +0.455563,0.185069,0.090617,0.000000, 0.911600,0.369000,0.181300, 0.468700,0.620700, +0.472517,0.133764,0.093989,0.000000, 0.945200,0.266600,0.188000, 0.468700,0.586200, +0.159650,-0.473826,-0.000000,0.000000, 0.322300,-0.946600,0.000000, 0.500000,0.103400, +0.209944,-0.453788,0.000000,0.000000, 0.422700,-0.906300,0.000000, 0.500000,0.137900, +0.205910,-0.453788,0.040958,0.000000, 0.414500,-0.906300,0.082400, 0.468700,0.137900, +0.159650,-0.473826,-0.000000,0.000000, 0.322300,-0.946600,0.000000, 0.500000,0.103400, +0.205910,-0.453788,0.040958,0.000000, 0.414500,-0.906300,0.082400, 0.468700,0.137900, +0.156583,-0.473826,0.031147,0.000000, 0.316100,-0.946600,0.062900, 0.468700,0.103400, +0.493412,0.080891,0.000000,0.000000, 0.986900,0.161200,0.000000, 0.500000,0.551700, +0.481774,0.133764,0.000000,0.000000, 0.963800,0.266600,0.000000, 0.500000,0.586200, +0.472517,0.133764,0.093989,0.000000, 0.945200,0.266600,0.188000, 0.468700,0.586200, +0.493412,0.080891,0.000000,0.000000, 0.986900,0.161200,0.000000, 0.500000,0.551700, +0.472517,0.133764,0.093989,0.000000, 0.945200,0.266600,0.188000, 0.468700,0.586200, +0.483932,0.080891,0.096260,0.000000, 0.967900,0.161200,0.192500, 0.468700,0.551700, +0.373758,0.323693,0.074345,0.000000, 0.748900,0.645700,0.149000, 0.468700,0.724100, +0.337242,0.362998,0.067082,0.000000, 0.676200,0.724300,0.134500, 0.468800,0.758600, +0.317674,0.362998,0.131585,0.000000, 0.637000,0.724300,0.263800, 0.437500,0.758600, +0.373758,0.323693,0.074345,0.000000, 0.748900,0.645700,0.149000, 0.468700,0.724100, +0.317674,0.362998,0.131585,0.000000, 0.637000,0.724300,0.263800, 0.437500,0.758600, +0.352072,0.323693,0.145833,0.000000, 0.705400,0.645700,0.292200, 0.437500,0.724100, +0.337242,-0.362998,0.067082,0.000000, 0.676200,-0.724300,0.134500, 0.468700,0.241400, +0.373758,-0.323693,0.074345,0.000000, 0.748900,-0.645700,0.149000, 0.468700,0.275900, +0.352072,-0.323693,0.145834,0.000000, 0.705400,-0.645700,0.292200, 0.437500,0.275900, +0.337242,-0.362998,0.067082,0.000000, 0.676200,-0.724300,0.134500, 0.468700,0.241400, +0.352072,-0.323693,0.145834,0.000000, 0.705400,-0.645700,0.292200, 0.437500,0.275900, +0.317675,-0.362998,0.131585,0.000000, 0.637000,-0.724300,0.263800, 0.437500,0.241400, +0.405892,0.280594,0.080737,0.000000, 0.812800,0.559600,0.161700, 0.468700,0.689700, +0.373758,0.323693,0.074345,0.000000, 0.748900,0.645700,0.149000, 0.468700,0.724100, +0.352072,0.323693,0.145833,0.000000, 0.705400,0.645700,0.292200, 0.437500,0.724100, +0.405892,0.280594,0.080737,0.000000, 0.812800,0.559600,0.161700, 0.468700,0.689700, +0.352072,0.323693,0.145833,0.000000, 0.705400,0.645700,0.292200, 0.437500,0.724100, +0.382342,0.280594,0.158371,0.000000, 0.765600,0.559600,0.317100, 0.437500,0.689700, +0.296772,-0.398046,0.059032,0.000000, 0.595600,-0.794500,0.118500, 0.468700,0.206900, +0.337242,-0.362998,0.067082,0.000000, 0.676200,-0.724300,0.134500, 0.468700,0.241400, +0.317675,-0.362998,0.131585,0.000000, 0.637000,-0.724300,0.263800, 0.437500,0.241400, +0.296772,-0.398046,0.059032,0.000000, 0.595600,-0.794500,0.118500, 0.468700,0.206900, +0.317675,-0.362998,0.131585,0.000000, 0.637000,-0.724300,0.263800, 0.437500,0.241400, +0.279553,-0.398046,0.115795,0.000000, 0.561100,-0.794500,0.232400, 0.437500,0.206900, +0.433267,0.234204,0.086182,0.000000, 0.867200,0.467000,0.172500, 0.468700,0.655200, +0.405892,0.280594,0.080737,0.000000, 0.812800,0.559600,0.161700, 0.468700,0.689700, +0.382342,0.280594,0.158371,0.000000, 0.765600,0.559600,0.317100, 0.437500,0.689700, +0.433267,0.234204,0.086182,0.000000, 0.867200,0.467000,0.172500, 0.468700,0.655200, +0.382342,0.280594,0.158371,0.000000, 0.765600,0.559600,0.317100, 0.437500,0.689700, +0.408128,0.234204,0.169052,0.000000, 0.816900,0.467000,0.338400, 0.437500,0.655200, +0.252823,-0.428429,0.050290,0.000000, 0.508100,-0.855300,0.101000, 0.468700,0.172400, +0.296772,-0.398046,0.059032,0.000000, 0.595600,-0.794500,0.118500, 0.468700,0.206900, +0.279553,-0.398046,0.115795,0.000000, 0.561100,-0.794500,0.232400, 0.437500,0.206900, +0.252823,-0.428429,0.050290,0.000000, 0.508100,-0.855300,0.101000, 0.468700,0.172400, +0.279553,-0.398046,0.115795,0.000000, 0.561100,-0.794500,0.232400, 0.437500,0.206900, +0.238154,-0.428429,0.098647,0.000000, 0.478600,-0.855300,0.198200, 0.437500,0.172400, +0.455563,0.185069,0.090617,0.000000, 0.911600,0.369000,0.181300, 0.468700,0.620700, +0.433267,0.234204,0.086182,0.000000, 0.867200,0.467000,0.172500, 0.468700,0.655200, +0.408128,0.234204,0.169052,0.000000, 0.816900,0.467000,0.338400, 0.437500,0.655200, +0.455563,0.185069,0.090617,0.000000, 0.911600,0.369000,0.181300, 0.468700,0.620700, +0.408128,0.234204,0.169052,0.000000, 0.816900,0.467000,0.338400, 0.437500,0.655200, +0.429130,0.185069,0.177752,0.000000, 0.858700,0.369000,0.355700, 0.437500,0.620700, +0.205910,-0.453788,0.040958,0.000000, 0.414500,-0.906300,0.082400, 0.468700,0.137900, +0.252823,-0.428429,0.050290,0.000000, 0.508100,-0.855300,0.101000, 0.468700,0.172400, +0.238154,-0.428429,0.098647,0.000000, 0.478600,-0.855300,0.198200, 0.437500,0.172400, +0.205910,-0.453788,0.040958,0.000000, 0.414500,-0.906300,0.082400, 0.468700,0.137900, +0.238154,-0.428429,0.098647,0.000000, 0.478600,-0.855300,0.198200, 0.437500,0.172400, +0.193963,-0.453788,0.080342,0.000000, 0.390500,-0.906300,0.161700, 0.437500,0.137900, +0.472517,0.133764,0.093989,0.000000, 0.945200,0.266600,0.188000, 0.468700,0.586200, +0.455563,0.185069,0.090617,0.000000, 0.911600,0.369000,0.181300, 0.468700,0.620700, +0.429130,0.185069,0.177752,0.000000, 0.858700,0.369000,0.355700, 0.437500,0.620700, +0.472517,0.133764,0.093989,0.000000, 0.945200,0.266600,0.188000, 0.468700,0.586200, +0.429130,0.185069,0.177752,0.000000, 0.858700,0.369000,0.355700, 0.437500,0.620700, +0.445101,0.133764,0.184367,0.000000, 0.890400,0.266600,0.368800, 0.437500,0.586200, +0.156583,-0.473826,0.031147,0.000000, 0.316100,-0.946600,0.062900, 0.468700,0.103400, +0.205910,-0.453788,0.040958,0.000000, 0.414500,-0.906300,0.082400, 0.468700,0.137900, +0.193963,-0.453788,0.080342,0.000000, 0.390500,-0.906300,0.161700, 0.437500,0.137900, +0.156583,-0.473826,0.031147,0.000000, 0.316100,-0.946600,0.062900, 0.468700,0.103400, +0.193963,-0.453788,0.080342,0.000000, 0.390500,-0.906300,0.161700, 0.437500,0.137900, +0.147498,-0.473826,0.061095,0.000000, 0.297800,-0.946600,0.123300, 0.437500,0.103400, +0.483932,0.080891,0.096260,0.000000, 0.967900,0.161200,0.192500, 0.468700,0.551700, +0.472517,0.133764,0.093989,0.000000, 0.945200,0.266600,0.188000, 0.468700,0.586200, +0.445101,0.133764,0.184367,0.000000, 0.890400,0.266600,0.368800, 0.437500,0.586200, +0.483932,0.080891,0.096260,0.000000, 0.967900,0.161200,0.192500, 0.468700,0.551700, +0.445101,0.133764,0.184367,0.000000, 0.890400,0.266600,0.368800, 0.437500,0.586200, +0.455853,0.080891,0.188821,0.000000, 0.911800,0.161200,0.377700, 0.437500,0.551700, +0.105420,-0.488310,0.020970,0.000000, 0.214000,-0.975900,0.042500, 0.468700,0.069000, +0.156583,-0.473826,0.031147,0.000000, 0.316100,-0.946600,0.062900, 0.468700,0.103400, +0.147498,-0.473826,0.061095,0.000000, 0.297800,-0.946600,0.123300, 0.437500,0.103400, +0.105420,-0.488310,0.020970,0.000000, 0.214000,-0.975900,0.042500, 0.468700,0.069000, +0.147498,-0.473826,0.061095,0.000000, 0.297800,-0.946600,0.123300, 0.437500,0.103400, +0.099303,-0.488310,0.041133,0.000000, 0.201600,-0.975900,0.083500, 0.437500,0.069000, +0.489673,0.027069,0.097402,0.000000, 0.979300,0.054000,0.194800, 0.468700,0.517200, +0.483932,0.080891,0.096260,0.000000, 0.967900,0.161200,0.192500, 0.468700,0.551700, +0.455853,0.080891,0.188821,0.000000, 0.911800,0.161200,0.377700, 0.437500,0.551700, +0.489673,0.027069,0.097402,0.000000, 0.979300,0.054000,0.194800, 0.468700,0.517200, +0.455853,0.080891,0.188821,0.000000, 0.911800,0.161200,0.377700, 0.437500,0.551700, +0.461261,0.027069,0.191061,0.000000, 0.922500,0.054000,0.382100, 0.437500,0.517200, +0.053020,0.497069,0.010546,0.000000, 0.109300,0.993700,0.021700, 0.458000,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +0.049943,0.497069,0.020688,0.000000, 0.103000,0.993700,0.042600, 0.459900,0.962300, +0.053020,-0.497069,0.010546,0.000000, 0.109300,-0.993700,0.021700, 0.468700,0.034500, +0.105420,-0.488310,0.020970,0.000000, 0.214000,-0.975900,0.042500, 0.468700,0.069000, +0.099303,-0.488310,0.041133,0.000000, 0.201600,-0.975900,0.083500, 0.437500,0.069000, +0.053020,-0.497069,0.010546,0.000000, 0.109300,-0.993700,0.021700, 0.468700,0.034500, +0.099303,-0.488310,0.041133,0.000000, 0.201600,-0.975900,0.083500, 0.437500,0.069000, +0.049944,-0.497069,0.020688,0.000000, 0.103000,-0.993700,0.042600, 0.437500,0.034500, +0.489673,-0.027069,0.097402,0.000000, 0.979300,-0.054000,0.194800, 0.468700,0.482800, +0.489673,0.027069,0.097402,0.000000, 0.979300,0.054000,0.194800, 0.468700,0.517200, +0.461261,0.027069,0.191061,0.000000, 0.922500,0.054000,0.382100, 0.437500,0.517200, +0.489673,-0.027069,0.097402,0.000000, 0.979300,-0.054000,0.194800, 0.468700,0.482800, +0.461261,0.027069,0.191061,0.000000, 0.922500,0.054000,0.382100, 0.437500,0.517200, +0.461261,-0.027069,0.191061,0.000000, 0.922500,-0.054000,0.382100, 0.437500,0.482800, +0.105419,0.488310,0.020970,0.000000, 0.214000,0.975900,0.042500, 0.468700,0.931000, +0.053020,0.497069,0.010546,0.000000, 0.109300,0.993700,0.021700, 0.468700,0.965500, +0.049943,0.497069,0.020688,0.000000, 0.103000,0.993700,0.042600, 0.437500,0.965500, +0.105419,0.488310,0.020970,0.000000, 0.214000,0.975900,0.042500, 0.468700,0.931000, +0.049943,0.497069,0.020688,0.000000, 0.103000,0.993700,0.042600, 0.437500,0.965500, +0.099303,0.488310,0.041132,0.000000, 0.201600,0.975900,0.083500, 0.437500,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +0.053020,-0.497069,0.010546,0.000000, 0.109300,-0.993700,0.021700, 0.449700,0.053800, +0.049944,-0.497069,0.020688,0.000000, 0.103000,-0.993700,0.042600, 0.447100,0.053800, +0.483932,-0.080891,0.096260,0.000000, 0.967900,-0.161200,0.192500, 0.468700,0.448300, +0.489673,-0.027069,0.097402,0.000000, 0.979300,-0.054000,0.194800, 0.468700,0.482800, +0.461261,-0.027069,0.191061,0.000000, 0.922500,-0.054000,0.382100, 0.437500,0.482800, +0.483932,-0.080891,0.096260,0.000000, 0.967900,-0.161200,0.192500, 0.468700,0.448300, +0.461261,-0.027069,0.191061,0.000000, 0.922500,-0.054000,0.382100, 0.437500,0.482800, +0.455853,-0.080891,0.188821,0.000000, 0.911800,-0.161200,0.377700, 0.437500,0.448300, +0.156582,0.473826,0.031146,0.000000, 0.316100,0.946600,0.062900, 0.468700,0.896600, +0.105419,0.488310,0.020970,0.000000, 0.214000,0.975900,0.042500, 0.468700,0.931000, +0.099303,0.488310,0.041132,0.000000, 0.201600,0.975900,0.083500, 0.437500,0.931000, +0.156582,0.473826,0.031146,0.000000, 0.316100,0.946600,0.062900, 0.468700,0.896600, +0.099303,0.488310,0.041132,0.000000, 0.201600,0.975900,0.083500, 0.437500,0.931000, +0.147497,0.473826,0.061095,0.000000, 0.297800,0.946600,0.123300, 0.437500,0.896600, +0.472517,-0.133764,0.093989,0.000000, 0.945200,-0.266600,0.188000, 0.468700,0.413800, +0.483932,-0.080891,0.096260,0.000000, 0.967900,-0.161200,0.192500, 0.468700,0.448300, +0.455853,-0.080891,0.188821,0.000000, 0.911800,-0.161200,0.377700, 0.437500,0.448300, +0.472517,-0.133764,0.093989,0.000000, 0.945200,-0.266600,0.188000, 0.468700,0.413800, +0.455853,-0.080891,0.188821,0.000000, 0.911800,-0.161200,0.377700, 0.437500,0.448300, +0.445101,-0.133764,0.184367,0.000000, 0.890400,-0.266600,0.368800, 0.437500,0.413800, +0.205910,0.453788,0.040958,0.000000, 0.414500,0.906300,0.082400, 0.468700,0.862100, +0.156582,0.473826,0.031146,0.000000, 0.316100,0.946600,0.062900, 0.468700,0.896600, +0.147497,0.473826,0.061095,0.000000, 0.297800,0.946600,0.123300, 0.437500,0.896600, +0.205910,0.453788,0.040958,0.000000, 0.414500,0.906300,0.082400, 0.468700,0.862100, +0.147497,0.473826,0.061095,0.000000, 0.297800,0.946600,0.123300, 0.437500,0.896600, +0.193962,0.453788,0.080342,0.000000, 0.390500,0.906300,0.161700, 0.437500,0.862100, +0.455563,-0.185069,0.090617,0.000000, 0.911600,-0.369000,0.181300, 0.468700,0.379300, +0.472517,-0.133764,0.093989,0.000000, 0.945200,-0.266600,0.188000, 0.468700,0.413800, +0.445101,-0.133764,0.184367,0.000000, 0.890400,-0.266600,0.368800, 0.437500,0.413800, +0.455563,-0.185069,0.090617,0.000000, 0.911600,-0.369000,0.181300, 0.468700,0.379300, +0.445101,-0.133764,0.184367,0.000000, 0.890400,-0.266600,0.368800, 0.437500,0.413800, +0.429130,-0.185069,0.177752,0.000000, 0.858700,-0.369000,0.355700, 0.437500,0.379300, +0.252823,0.428429,0.050290,0.000000, 0.508100,0.855300,0.101000, 0.468700,0.827600, +0.205910,0.453788,0.040958,0.000000, 0.414500,0.906300,0.082400, 0.468700,0.862100, +0.193962,0.453788,0.080342,0.000000, 0.390500,0.906300,0.161700, 0.437500,0.862100, +0.252823,0.428429,0.050290,0.000000, 0.508100,0.855300,0.101000, 0.468700,0.827600, +0.193962,0.453788,0.080342,0.000000, 0.390500,0.906300,0.161700, 0.437500,0.862100, +0.238154,0.428429,0.098646,0.000000, 0.478600,0.855300,0.198200, 0.437500,0.827600, +0.433267,-0.234204,0.086182,0.000000, 0.867200,-0.467000,0.172500, 0.468700,0.344800, +0.455563,-0.185069,0.090617,0.000000, 0.911600,-0.369000,0.181300, 0.468700,0.379300, +0.429130,-0.185069,0.177752,0.000000, 0.858700,-0.369000,0.355700, 0.437500,0.379300, +0.433267,-0.234204,0.086182,0.000000, 0.867200,-0.467000,0.172500, 0.468700,0.344800, +0.429130,-0.185069,0.177752,0.000000, 0.858700,-0.369000,0.355700, 0.437500,0.379300, +0.408128,-0.234204,0.169052,0.000000, 0.816900,-0.467000,0.338400, 0.437500,0.344800, +0.296772,0.398046,0.059032,0.000000, 0.595600,0.794500,0.118500, 0.468700,0.793100, +0.252823,0.428429,0.050290,0.000000, 0.508100,0.855300,0.101000, 0.468700,0.827600, +0.238154,0.428429,0.098646,0.000000, 0.478600,0.855300,0.198200, 0.437500,0.827600, +0.296772,0.398046,0.059032,0.000000, 0.595600,0.794500,0.118500, 0.468700,0.793100, +0.238154,0.428429,0.098646,0.000000, 0.478600,0.855300,0.198200, 0.437500,0.827600, +0.279553,0.398046,0.115795,0.000000, 0.561100,0.794500,0.232400, 0.437500,0.793100, +0.405892,-0.280594,0.080737,0.000000, 0.812800,-0.559600,0.161700, 0.468700,0.310300, +0.433267,-0.234204,0.086182,0.000000, 0.867200,-0.467000,0.172500, 0.468700,0.344800, +0.408128,-0.234204,0.169052,0.000000, 0.816900,-0.467000,0.338400, 0.437500,0.344800, +0.405892,-0.280594,0.080737,0.000000, 0.812800,-0.559600,0.161700, 0.468700,0.310300, +0.408128,-0.234204,0.169052,0.000000, 0.816900,-0.467000,0.338400, 0.437500,0.344800, +0.382342,-0.280594,0.158371,0.000000, 0.765600,-0.559600,0.317100, 0.437500,0.310300, +0.337242,0.362998,0.067082,0.000000, 0.676200,0.724300,0.134500, 0.468800,0.758600, +0.296772,0.398046,0.059032,0.000000, 0.595600,0.794500,0.118500, 0.468700,0.793100, +0.279553,0.398046,0.115795,0.000000, 0.561100,0.794500,0.232400, 0.437500,0.793100, +0.337242,0.362998,0.067082,0.000000, 0.676200,0.724300,0.134500, 0.468800,0.758600, +0.279553,0.398046,0.115795,0.000000, 0.561100,0.794500,0.232400, 0.437500,0.793100, +0.317674,0.362998,0.131585,0.000000, 0.637000,0.724300,0.263800, 0.437500,0.758600, +0.373758,-0.323693,0.074345,0.000000, 0.748900,-0.645700,0.149000, 0.468700,0.275900, +0.405892,-0.280594,0.080737,0.000000, 0.812800,-0.559600,0.161700, 0.468700,0.310300, +0.382342,-0.280594,0.158371,0.000000, 0.765600,-0.559600,0.317100, 0.437500,0.310300, +0.373758,-0.323693,0.074345,0.000000, 0.748900,-0.645700,0.149000, 0.468700,0.275900, +0.382342,-0.280594,0.158371,0.000000, 0.765600,-0.559600,0.317100, 0.437500,0.310300, +0.352072,-0.323693,0.145834,0.000000, 0.705400,-0.645700,0.292200, 0.437500,0.275900, +0.455853,-0.080891,0.188821,0.000000, 0.911800,-0.161200,0.377700, 0.437500,0.448300, +0.461261,-0.027069,0.191061,0.000000, 0.922500,-0.054000,0.382100, 0.437500,0.482800, +0.415124,-0.027069,0.277377,0.000000, 0.830300,-0.054000,0.554700, 0.406200,0.482800, +0.455853,-0.080891,0.188821,0.000000, 0.911800,-0.161200,0.377700, 0.437500,0.448300, +0.415124,-0.027069,0.277377,0.000000, 0.830300,-0.054000,0.554700, 0.406200,0.482800, +0.410257,-0.080891,0.274125,0.000000, 0.820600,-0.161200,0.548300, 0.406200,0.448300, +0.147497,0.473826,0.061095,0.000000, 0.297800,0.946600,0.123300, 0.437500,0.896600, +0.099303,0.488310,0.041132,0.000000, 0.201600,0.975900,0.083500, 0.437500,0.931000, +0.089370,0.488310,0.059715,0.000000, 0.181400,0.975900,0.121200, 0.406200,0.931000, +0.147497,0.473826,0.061095,0.000000, 0.297800,0.946600,0.123300, 0.437500,0.896600, +0.089370,0.488310,0.059715,0.000000, 0.181400,0.975900,0.121200, 0.406200,0.931000, +0.132744,0.473826,0.088697,0.000000, 0.268000,0.946600,0.179100, 0.406200,0.896600, +0.445101,-0.133764,0.184367,0.000000, 0.890400,-0.266600,0.368800, 0.437500,0.413800, +0.455853,-0.080891,0.188821,0.000000, 0.911800,-0.161200,0.377700, 0.437500,0.448300, +0.410257,-0.080891,0.274125,0.000000, 0.820600,-0.161200,0.548300, 0.406200,0.448300, +0.445101,-0.133764,0.184367,0.000000, 0.890400,-0.266600,0.368800, 0.437500,0.413800, +0.410257,-0.080891,0.274125,0.000000, 0.820600,-0.161200,0.548300, 0.406200,0.448300, +0.400580,-0.133764,0.267659,0.000000, 0.801400,-0.266600,0.535400, 0.406200,0.413800, +0.193962,0.453788,0.080342,0.000000, 0.390500,0.906300,0.161700, 0.437500,0.862100, +0.147497,0.473826,0.061095,0.000000, 0.297800,0.946600,0.123300, 0.437500,0.896600, +0.132744,0.473826,0.088697,0.000000, 0.268000,0.946600,0.179100, 0.406200,0.896600, +0.193962,0.453788,0.080342,0.000000, 0.390500,0.906300,0.161700, 0.437500,0.862100, +0.132744,0.473826,0.088697,0.000000, 0.268000,0.946600,0.179100, 0.406200,0.896600, +0.174562,0.453788,0.116638,0.000000, 0.351400,0.906300,0.234800, 0.406200,0.862100, +0.429130,-0.185069,0.177752,0.000000, 0.858700,-0.369000,0.355700, 0.437500,0.379300, +0.445101,-0.133764,0.184367,0.000000, 0.890400,-0.266600,0.368800, 0.437500,0.413800, +0.400580,-0.133764,0.267659,0.000000, 0.801400,-0.266600,0.535400, 0.406200,0.413800, +0.429130,-0.185069,0.177752,0.000000, 0.858700,-0.369000,0.355700, 0.437500,0.379300, +0.400580,-0.133764,0.267659,0.000000, 0.801400,-0.266600,0.535400, 0.406200,0.413800, +0.386207,-0.185069,0.258056,0.000000, 0.772800,-0.369000,0.516300, 0.406200,0.379300, +0.238154,0.428429,0.098646,0.000000, 0.478600,0.855300,0.198200, 0.437500,0.827600, +0.193962,0.453788,0.080342,0.000000, 0.390500,0.906300,0.161700, 0.437500,0.862100, +0.174562,0.453788,0.116638,0.000000, 0.351400,0.906300,0.234800, 0.406200,0.862100, +0.238154,0.428429,0.098646,0.000000, 0.478600,0.855300,0.198200, 0.437500,0.827600, +0.174562,0.453788,0.116638,0.000000, 0.351400,0.906300,0.234800, 0.406200,0.862100, +0.214333,0.428429,0.143213,0.000000, 0.430700,0.855300,0.287800, 0.406200,0.827600, +0.408128,-0.234204,0.169052,0.000000, 0.816900,-0.467000,0.338400, 0.437500,0.344800, +0.429130,-0.185069,0.177752,0.000000, 0.858700,-0.369000,0.355700, 0.437500,0.379300, +0.386207,-0.185069,0.258056,0.000000, 0.772800,-0.369000,0.516300, 0.406200,0.379300, +0.408128,-0.234204,0.169052,0.000000, 0.816900,-0.467000,0.338400, 0.437500,0.344800, +0.386207,-0.185069,0.258056,0.000000, 0.772800,-0.369000,0.516300, 0.406200,0.379300, +0.367306,-0.234204,0.245426,0.000000, 0.735200,-0.467000,0.491300, 0.406200,0.344800, +0.279553,0.398046,0.115795,0.000000, 0.561100,0.794500,0.232400, 0.437500,0.793100, +0.238154,0.428429,0.098646,0.000000, 0.478600,0.855300,0.198200, 0.437500,0.827600, +0.214333,0.428429,0.143213,0.000000, 0.430700,0.855300,0.287800, 0.406200,0.827600, +0.279553,0.398046,0.115795,0.000000, 0.561100,0.794500,0.232400, 0.437500,0.793100, +0.214333,0.428429,0.143213,0.000000, 0.430700,0.855300,0.287800, 0.406200,0.827600, +0.251591,0.398046,0.168108,0.000000, 0.505000,0.794500,0.337400, 0.406200,0.793100, +0.382342,-0.280594,0.158371,0.000000, 0.765600,-0.559600,0.317100, 0.437500,0.310300, +0.408128,-0.234204,0.169052,0.000000, 0.816900,-0.467000,0.338400, 0.437500,0.344800, +0.367306,-0.234204,0.245426,0.000000, 0.735200,-0.467000,0.491300, 0.406200,0.344800, +0.382342,-0.280594,0.158371,0.000000, 0.765600,-0.559600,0.317100, 0.437500,0.310300, +0.367306,-0.234204,0.245426,0.000000, 0.735200,-0.467000,0.491300, 0.406200,0.344800, +0.344098,-0.280594,0.229919,0.000000, 0.689100,-0.559600,0.460400, 0.406200,0.310300, +0.317674,0.362998,0.131585,0.000000, 0.637000,0.724300,0.263800, 0.437500,0.758600, +0.279553,0.398046,0.115795,0.000000, 0.561100,0.794500,0.232400, 0.437500,0.793100, +0.251591,0.398046,0.168108,0.000000, 0.505000,0.794500,0.337400, 0.406200,0.793100, +0.317674,0.362998,0.131585,0.000000, 0.637000,0.724300,0.263800, 0.437500,0.758600, +0.251591,0.398046,0.168108,0.000000, 0.505000,0.794500,0.337400, 0.406200,0.793100, +0.285899,0.362998,0.191032,0.000000, 0.573300,0.724300,0.383000, 0.406200,0.758600, +0.352072,-0.323693,0.145834,0.000000, 0.705400,-0.645700,0.292200, 0.437500,0.275900, +0.382342,-0.280594,0.158371,0.000000, 0.765600,-0.559600,0.317100, 0.437500,0.310300, +0.344098,-0.280594,0.229919,0.000000, 0.689100,-0.559600,0.460400, 0.406200,0.310300, +0.352072,-0.323693,0.145834,0.000000, 0.705400,-0.645700,0.292200, 0.437500,0.275900, +0.344098,-0.280594,0.229919,0.000000, 0.689100,-0.559600,0.460400, 0.406200,0.310300, +0.316857,-0.323693,0.211717,0.000000, 0.634900,-0.645700,0.424200, 0.406200,0.275900, +0.352072,0.323693,0.145833,0.000000, 0.705400,0.645700,0.292200, 0.437500,0.724100, +0.317674,0.362998,0.131585,0.000000, 0.637000,0.724300,0.263800, 0.437500,0.758600, +0.285899,0.362998,0.191032,0.000000, 0.573300,0.724300,0.383000, 0.406200,0.758600, +0.352072,0.323693,0.145833,0.000000, 0.705400,0.645700,0.292200, 0.437500,0.724100, +0.285899,0.362998,0.191032,0.000000, 0.573300,0.724300,0.383000, 0.406200,0.758600, +0.316857,0.323693,0.211717,0.000000, 0.634900,0.645700,0.424200, 0.406200,0.724100, +0.317675,-0.362998,0.131585,0.000000, 0.637000,-0.724300,0.263800, 0.437500,0.241400, +0.352072,-0.323693,0.145834,0.000000, 0.705400,-0.645700,0.292200, 0.437500,0.275900, +0.316857,-0.323693,0.211717,0.000000, 0.634900,-0.645700,0.424200, 0.406200,0.275900, +0.317675,-0.362998,0.131585,0.000000, 0.637000,-0.724300,0.263800, 0.437500,0.241400, +0.316857,-0.323693,0.211717,0.000000, 0.634900,-0.645700,0.424200, 0.406200,0.275900, +0.285900,-0.362998,0.191032,0.000000, 0.573300,-0.724300,0.383000, 0.406200,0.241400, +0.382342,0.280594,0.158371,0.000000, 0.765600,0.559600,0.317100, 0.437500,0.689700, +0.352072,0.323693,0.145833,0.000000, 0.705400,0.645700,0.292200, 0.437500,0.724100, +0.316857,0.323693,0.211717,0.000000, 0.634900,0.645700,0.424200, 0.406200,0.724100, +0.382342,0.280594,0.158371,0.000000, 0.765600,0.559600,0.317100, 0.437500,0.689700, +0.316857,0.323693,0.211717,0.000000, 0.634900,0.645700,0.424200, 0.406200,0.724100, +0.344098,0.280594,0.229919,0.000000, 0.689100,0.559600,0.460400, 0.406200,0.689700, +0.279553,-0.398046,0.115795,0.000000, 0.561100,-0.794500,0.232400, 0.437500,0.206900, +0.317675,-0.362998,0.131585,0.000000, 0.637000,-0.724300,0.263800, 0.437500,0.241400, +0.285900,-0.362998,0.191032,0.000000, 0.573300,-0.724300,0.383000, 0.406200,0.241400, +0.279553,-0.398046,0.115795,0.000000, 0.561100,-0.794500,0.232400, 0.437500,0.206900, +0.285900,-0.362998,0.191032,0.000000, 0.573300,-0.724300,0.383000, 0.406200,0.241400, +0.251591,-0.398046,0.168108,0.000000, 0.504900,-0.794500,0.337400, 0.406200,0.206900, +0.408128,0.234204,0.169052,0.000000, 0.816900,0.467000,0.338400, 0.437500,0.655200, +0.382342,0.280594,0.158371,0.000000, 0.765600,0.559600,0.317100, 0.437500,0.689700, +0.344098,0.280594,0.229919,0.000000, 0.689100,0.559600,0.460400, 0.406200,0.689700, +0.408128,0.234204,0.169052,0.000000, 0.816900,0.467000,0.338400, 0.437500,0.655200, +0.344098,0.280594,0.229919,0.000000, 0.689100,0.559600,0.460400, 0.406200,0.689700, +0.367306,0.234204,0.245426,0.000000, 0.735200,0.467000,0.491300, 0.406200,0.655200, +0.238154,-0.428429,0.098647,0.000000, 0.478600,-0.855300,0.198200, 0.437500,0.172400, +0.279553,-0.398046,0.115795,0.000000, 0.561100,-0.794500,0.232400, 0.437500,0.206900, +0.251591,-0.398046,0.168108,0.000000, 0.504900,-0.794500,0.337400, 0.406200,0.206900, +0.238154,-0.428429,0.098647,0.000000, 0.478600,-0.855300,0.198200, 0.437500,0.172400, +0.251591,-0.398046,0.168108,0.000000, 0.504900,-0.794500,0.337400, 0.406200,0.206900, +0.214333,-0.428429,0.143213,0.000000, 0.430700,-0.855300,0.287800, 0.406200,0.172400, +0.429130,0.185069,0.177752,0.000000, 0.858700,0.369000,0.355700, 0.437500,0.620700, +0.408128,0.234204,0.169052,0.000000, 0.816900,0.467000,0.338400, 0.437500,0.655200, +0.367306,0.234204,0.245426,0.000000, 0.735200,0.467000,0.491300, 0.406200,0.655200, +0.429130,0.185069,0.177752,0.000000, 0.858700,0.369000,0.355700, 0.437500,0.620700, +0.367306,0.234204,0.245426,0.000000, 0.735200,0.467000,0.491300, 0.406200,0.655200, +0.386207,0.185069,0.258056,0.000000, 0.772800,0.369000,0.516300, 0.406200,0.620700, +0.193963,-0.453788,0.080342,0.000000, 0.390500,-0.906300,0.161700, 0.437500,0.137900, +0.238154,-0.428429,0.098647,0.000000, 0.478600,-0.855300,0.198200, 0.437500,0.172400, +0.214333,-0.428429,0.143213,0.000000, 0.430700,-0.855300,0.287800, 0.406200,0.172400, +0.193963,-0.453788,0.080342,0.000000, 0.390500,-0.906300,0.161700, 0.437500,0.137900, +0.214333,-0.428429,0.143213,0.000000, 0.430700,-0.855300,0.287800, 0.406200,0.172400, +0.174562,-0.453788,0.116639,0.000000, 0.351400,-0.906300,0.234800, 0.406200,0.137900, +0.445101,0.133764,0.184367,0.000000, 0.890400,0.266600,0.368800, 0.437500,0.586200, +0.429130,0.185069,0.177752,0.000000, 0.858700,0.369000,0.355700, 0.437500,0.620700, +0.386207,0.185069,0.258056,0.000000, 0.772800,0.369000,0.516300, 0.406200,0.620700, +0.445101,0.133764,0.184367,0.000000, 0.890400,0.266600,0.368800, 0.437500,0.586200, +0.386207,0.185069,0.258056,0.000000, 0.772800,0.369000,0.516300, 0.406200,0.620700, +0.400580,0.133764,0.267659,0.000000, 0.801400,0.266600,0.535400, 0.406200,0.586200, +0.147498,-0.473826,0.061095,0.000000, 0.297800,-0.946600,0.123300, 0.437500,0.103400, +0.193963,-0.453788,0.080342,0.000000, 0.390500,-0.906300,0.161700, 0.437500,0.137900, +0.174562,-0.453788,0.116639,0.000000, 0.351400,-0.906300,0.234800, 0.406200,0.137900, +0.147498,-0.473826,0.061095,0.000000, 0.297800,-0.946600,0.123300, 0.437500,0.103400, +0.174562,-0.453788,0.116639,0.000000, 0.351400,-0.906300,0.234800, 0.406200,0.137900, +0.132744,-0.473826,0.088697,0.000000, 0.268000,-0.946600,0.179100, 0.406200,0.103400, +0.455853,0.080891,0.188821,0.000000, 0.911800,0.161200,0.377700, 0.437500,0.551700, +0.445101,0.133764,0.184367,0.000000, 0.890400,0.266600,0.368800, 0.437500,0.586200, +0.400580,0.133764,0.267659,0.000000, 0.801400,0.266600,0.535400, 0.406200,0.586200, +0.455853,0.080891,0.188821,0.000000, 0.911800,0.161200,0.377700, 0.437500,0.551700, +0.400580,0.133764,0.267659,0.000000, 0.801400,0.266600,0.535400, 0.406200,0.586200, +0.410257,0.080891,0.274125,0.000000, 0.820600,0.161200,0.548300, 0.406200,0.551700, +0.099303,-0.488310,0.041133,0.000000, 0.201600,-0.975900,0.083500, 0.437500,0.069000, +0.147498,-0.473826,0.061095,0.000000, 0.297800,-0.946600,0.123300, 0.437500,0.103400, +0.132744,-0.473826,0.088697,0.000000, 0.268000,-0.946600,0.179100, 0.406200,0.103400, +0.099303,-0.488310,0.041133,0.000000, 0.201600,-0.975900,0.083500, 0.437500,0.069000, +0.132744,-0.473826,0.088697,0.000000, 0.268000,-0.946600,0.179100, 0.406200,0.103400, +0.089370,-0.488310,0.059715,0.000000, 0.181400,-0.975900,0.121200, 0.406200,0.069000, +0.461261,0.027069,0.191061,0.000000, 0.922500,0.054000,0.382100, 0.437500,0.517200, +0.455853,0.080891,0.188821,0.000000, 0.911800,0.161200,0.377700, 0.437500,0.551700, +0.410257,0.080891,0.274125,0.000000, 0.820600,0.161200,0.548300, 0.406200,0.551700, +0.461261,0.027069,0.191061,0.000000, 0.922500,0.054000,0.382100, 0.437500,0.517200, +0.410257,0.080891,0.274125,0.000000, 0.820600,0.161200,0.548300, 0.406200,0.551700, +0.415124,0.027069,0.277377,0.000000, 0.830300,0.054000,0.554700, 0.406200,0.517200, +0.049943,0.497069,0.020688,0.000000, 0.103000,0.993700,0.042600, 0.459900,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +0.044948,0.497069,0.030034,0.000000, 0.092700,0.993700,0.061900, 0.461700,0.962300, +0.049944,-0.497069,0.020688,0.000000, 0.103000,-0.993700,0.042600, 0.437500,0.034500, +0.099303,-0.488310,0.041133,0.000000, 0.201600,-0.975900,0.083500, 0.437500,0.069000, +0.089370,-0.488310,0.059715,0.000000, 0.181400,-0.975900,0.121200, 0.406200,0.069000, +0.049944,-0.497069,0.020688,0.000000, 0.103000,-0.993700,0.042600, 0.437500,0.034500, +0.089370,-0.488310,0.059715,0.000000, 0.181400,-0.975900,0.121200, 0.406200,0.069000, +0.044948,-0.497069,0.030034,0.000000, 0.092700,-0.993700,0.061900, 0.406200,0.034500, +0.461261,-0.027069,0.191061,0.000000, 0.922500,-0.054000,0.382100, 0.437500,0.482800, +0.461261,0.027069,0.191061,0.000000, 0.922500,0.054000,0.382100, 0.437500,0.517200, +0.415124,0.027069,0.277377,0.000000, 0.830300,0.054000,0.554700, 0.406200,0.517200, +0.461261,-0.027069,0.191061,0.000000, 0.922500,-0.054000,0.382100, 0.437500,0.482800, +0.415124,0.027069,0.277377,0.000000, 0.830300,0.054000,0.554700, 0.406200,0.517200, +0.415124,-0.027069,0.277377,0.000000, 0.830300,-0.054000,0.554700, 0.406200,0.482800, +0.099303,0.488310,0.041132,0.000000, 0.201600,0.975900,0.083500, 0.437500,0.931000, +0.049943,0.497069,0.020688,0.000000, 0.103000,0.993700,0.042600, 0.437500,0.965500, +0.044948,0.497069,0.030034,0.000000, 0.092700,0.993700,0.061900, 0.406200,0.965500, +0.099303,0.488310,0.041132,0.000000, 0.201600,0.975900,0.083500, 0.437500,0.931000, +0.044948,0.497069,0.030034,0.000000, 0.092700,0.993700,0.061900, 0.406200,0.965500, +0.089370,0.488310,0.059715,0.000000, 0.181400,0.975900,0.121200, 0.406200,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +0.049944,-0.497069,0.020688,0.000000, 0.103000,-0.993700,0.042600, 0.447100,0.053800, +0.044948,-0.497069,0.030034,0.000000, 0.092700,-0.993700,0.061900, 0.444400,0.053800, +0.214333,-0.428429,0.143213,0.000000, 0.430700,-0.855300,0.287800, 0.406200,0.172400, +0.251591,-0.398046,0.168108,0.000000, 0.504900,-0.794500,0.337400, 0.406200,0.206900, +0.213960,-0.398046,0.213961,0.000000, 0.429400,-0.794500,0.429400, 0.375000,0.206900, +0.214333,-0.428429,0.143213,0.000000, 0.430700,-0.855300,0.287800, 0.406200,0.172400, +0.213960,-0.398046,0.213961,0.000000, 0.429400,-0.794500,0.429400, 0.375000,0.206900, +0.182275,-0.428429,0.182276,0.000000, 0.366300,-0.855300,0.366300, 0.375000,0.172400, +0.386207,0.185069,0.258056,0.000000, 0.772800,0.369000,0.516300, 0.406200,0.620700, +0.367306,0.234204,0.245426,0.000000, 0.735200,0.467000,0.491300, 0.406200,0.655200, +0.312368,0.234204,0.312368,0.000000, 0.625200,0.467000,0.625200, 0.375000,0.655200, +0.386207,0.185069,0.258056,0.000000, 0.772800,0.369000,0.516300, 0.406200,0.620700, +0.312368,0.234204,0.312368,0.000000, 0.625200,0.467000,0.625200, 0.375000,0.655200, +0.328442,0.185069,0.328443,0.000000, 0.657200,0.369000,0.657200, 0.375000,0.620700, +0.174562,-0.453788,0.116639,0.000000, 0.351400,-0.906300,0.234800, 0.406200,0.137900, +0.214333,-0.428429,0.143213,0.000000, 0.430700,-0.855300,0.287800, 0.406200,0.172400, +0.182275,-0.428429,0.182276,0.000000, 0.366300,-0.855300,0.366300, 0.375000,0.172400, +0.174562,-0.453788,0.116639,0.000000, 0.351400,-0.906300,0.234800, 0.406200,0.137900, +0.182275,-0.428429,0.182276,0.000000, 0.366300,-0.855300,0.366300, 0.375000,0.172400, +0.148453,-0.453788,0.148453,0.000000, 0.298900,-0.906300,0.298900, 0.375000,0.137900, +0.400580,0.133764,0.267659,0.000000, 0.801400,0.266600,0.535400, 0.406200,0.586200, +0.386207,0.185069,0.258056,0.000000, 0.772800,0.369000,0.516300, 0.406200,0.620700, +0.328442,0.185069,0.328443,0.000000, 0.657200,0.369000,0.657200, 0.375000,0.620700, +0.400580,0.133764,0.267659,0.000000, 0.801400,0.266600,0.535400, 0.406200,0.586200, +0.328442,0.185069,0.328443,0.000000, 0.657200,0.369000,0.657200, 0.375000,0.620700, +0.340665,0.133764,0.340666,0.000000, 0.681500,0.266600,0.681500, 0.375000,0.586200, +0.132744,-0.473826,0.088697,0.000000, 0.268000,-0.946600,0.179100, 0.406200,0.103400, +0.174562,-0.453788,0.116639,0.000000, 0.351400,-0.906300,0.234800, 0.406200,0.137900, +0.148453,-0.453788,0.148453,0.000000, 0.298900,-0.906300,0.298900, 0.375000,0.137900, +0.132744,-0.473826,0.088697,0.000000, 0.268000,-0.946600,0.179100, 0.406200,0.103400, +0.148453,-0.453788,0.148453,0.000000, 0.298900,-0.906300,0.298900, 0.375000,0.137900, +0.112889,-0.473826,0.112890,0.000000, 0.227900,-0.946600,0.227900, 0.375000,0.103400, +0.410257,0.080891,0.274125,0.000000, 0.820600,0.161200,0.548300, 0.406200,0.551700, +0.400580,0.133764,0.267659,0.000000, 0.801400,0.266600,0.535400, 0.406200,0.586200, +0.340665,0.133764,0.340666,0.000000, 0.681500,0.266600,0.681500, 0.375000,0.586200, +0.410257,0.080891,0.274125,0.000000, 0.820600,0.161200,0.548300, 0.406200,0.551700, +0.340665,0.133764,0.340666,0.000000, 0.681500,0.266600,0.681500, 0.375000,0.586200, +0.348895,0.080891,0.348895,0.000000, 0.697800,0.161200,0.697800, 0.375000,0.551700, +0.089370,-0.488310,0.059715,0.000000, 0.181400,-0.975900,0.121200, 0.406200,0.069000, +0.132744,-0.473826,0.088697,0.000000, 0.268000,-0.946600,0.179100, 0.406200,0.103400, +0.112889,-0.473826,0.112890,0.000000, 0.227900,-0.946600,0.227900, 0.375000,0.103400, +0.089370,-0.488310,0.059715,0.000000, 0.181400,-0.975900,0.121200, 0.406200,0.069000, +0.112889,-0.473826,0.112890,0.000000, 0.227900,-0.946600,0.227900, 0.375000,0.103400, +0.076003,-0.488310,0.076003,0.000000, 0.154300,-0.975900,0.154300, 0.375000,0.069000, +0.415124,0.027069,0.277377,0.000000, 0.830300,0.054000,0.554700, 0.406200,0.517200, +0.410257,0.080891,0.274125,0.000000, 0.820600,0.161200,0.548300, 0.406200,0.551700, +0.348895,0.080891,0.348895,0.000000, 0.697800,0.161200,0.697800, 0.375000,0.551700, +0.415124,0.027069,0.277377,0.000000, 0.830300,0.054000,0.554700, 0.406200,0.517200, +0.348895,0.080891,0.348895,0.000000, 0.697800,0.161200,0.697800, 0.375000,0.551700, +0.353034,0.027069,0.353034,0.000000, 0.706100,0.054000,0.706100, 0.375000,0.517200, +0.044948,0.497069,0.030034,0.000000, 0.092700,0.993700,0.061900, 0.461700,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +0.038225,0.497069,0.038226,0.000000, 0.078800,0.993700,0.078800, 0.463500,0.962300, +0.044948,-0.497069,0.030034,0.000000, 0.092700,-0.993700,0.061900, 0.406200,0.034500, +0.089370,-0.488310,0.059715,0.000000, 0.181400,-0.975900,0.121200, 0.406200,0.069000, +0.076003,-0.488310,0.076003,0.000000, 0.154300,-0.975900,0.154300, 0.375000,0.069000, +0.044948,-0.497069,0.030034,0.000000, 0.092700,-0.993700,0.061900, 0.406200,0.034500, +0.076003,-0.488310,0.076003,0.000000, 0.154300,-0.975900,0.154300, 0.375000,0.069000, +0.038226,-0.497069,0.038226,0.000000, 0.078800,-0.993700,0.078800, 0.375000,0.034500, +0.415124,-0.027069,0.277377,0.000000, 0.830300,-0.054000,0.554700, 0.406200,0.482800, +0.415124,0.027069,0.277377,0.000000, 0.830300,0.054000,0.554700, 0.406200,0.517200, +0.353034,0.027069,0.353034,0.000000, 0.706100,0.054000,0.706100, 0.375000,0.517200, +0.415124,-0.027069,0.277377,0.000000, 0.830300,-0.054000,0.554700, 0.406200,0.482800, +0.353034,0.027069,0.353034,0.000000, 0.706100,0.054000,0.706100, 0.375000,0.517200, +0.353034,-0.027069,0.353034,0.000000, 0.706100,-0.054000,0.706100, 0.375000,0.482800, +0.089370,0.488310,0.059715,0.000000, 0.181400,0.975900,0.121200, 0.406200,0.931000, +0.044948,0.497069,0.030034,0.000000, 0.092700,0.993700,0.061900, 0.406200,0.965500, +0.038225,0.497069,0.038226,0.000000, 0.078800,0.993700,0.078800, 0.375000,0.965500, +0.089370,0.488310,0.059715,0.000000, 0.181400,0.975900,0.121200, 0.406200,0.931000, +0.038225,0.497069,0.038226,0.000000, 0.078800,0.993700,0.078800, 0.375000,0.965500, +0.076003,0.488310,0.076003,0.000000, 0.154300,0.975900,0.154300, 0.375000,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +0.044948,-0.497069,0.030034,0.000000, 0.092700,-0.993700,0.061900, 0.444400,0.053800, +0.038226,-0.497069,0.038226,0.000000, 0.078800,-0.993700,0.078800, 0.441800,0.053800, +0.410257,-0.080891,0.274125,0.000000, 0.820600,-0.161200,0.548300, 0.406200,0.448300, +0.415124,-0.027069,0.277377,0.000000, 0.830300,-0.054000,0.554700, 0.406200,0.482800, +0.353034,-0.027069,0.353034,0.000000, 0.706100,-0.054000,0.706100, 0.375000,0.482800, +0.410257,-0.080891,0.274125,0.000000, 0.820600,-0.161200,0.548300, 0.406200,0.448300, +0.353034,-0.027069,0.353034,0.000000, 0.706100,-0.054000,0.706100, 0.375000,0.482800, +0.348895,-0.080891,0.348895,0.000000, 0.697800,-0.161200,0.697800, 0.375000,0.448300, +0.132744,0.473826,0.088697,0.000000, 0.268000,0.946600,0.179100, 0.406200,0.896600, +0.089370,0.488310,0.059715,0.000000, 0.181400,0.975900,0.121200, 0.406200,0.931000, +0.076003,0.488310,0.076003,0.000000, 0.154300,0.975900,0.154300, 0.375000,0.931000, +0.132744,0.473826,0.088697,0.000000, 0.268000,0.946600,0.179100, 0.406200,0.896600, +0.076003,0.488310,0.076003,0.000000, 0.154300,0.975900,0.154300, 0.375000,0.931000, +0.112889,0.473826,0.112889,0.000000, 0.227900,0.946600,0.227900, 0.375000,0.896600, +0.400580,-0.133764,0.267659,0.000000, 0.801400,-0.266600,0.535400, 0.406200,0.413800, +0.410257,-0.080891,0.274125,0.000000, 0.820600,-0.161200,0.548300, 0.406200,0.448300, +0.348895,-0.080891,0.348895,0.000000, 0.697800,-0.161200,0.697800, 0.375000,0.448300, +0.400580,-0.133764,0.267659,0.000000, 0.801400,-0.266600,0.535400, 0.406200,0.413800, +0.348895,-0.080891,0.348895,0.000000, 0.697800,-0.161200,0.697800, 0.375000,0.448300, +0.340665,-0.133764,0.340666,0.000000, 0.681500,-0.266600,0.681500, 0.375000,0.413800, +0.174562,0.453788,0.116638,0.000000, 0.351400,0.906300,0.234800, 0.406200,0.862100, +0.132744,0.473826,0.088697,0.000000, 0.268000,0.946600,0.179100, 0.406200,0.896600, +0.112889,0.473826,0.112889,0.000000, 0.227900,0.946600,0.227900, 0.375000,0.896600, +0.174562,0.453788,0.116638,0.000000, 0.351400,0.906300,0.234800, 0.406200,0.862100, +0.112889,0.473826,0.112889,0.000000, 0.227900,0.946600,0.227900, 0.375000,0.896600, +0.148453,0.453788,0.148453,0.000000, 0.298900,0.906300,0.298900, 0.375000,0.862100, +0.386207,-0.185069,0.258056,0.000000, 0.772800,-0.369000,0.516300, 0.406200,0.379300, +0.400580,-0.133764,0.267659,0.000000, 0.801400,-0.266600,0.535400, 0.406200,0.413800, +0.340665,-0.133764,0.340666,0.000000, 0.681500,-0.266600,0.681500, 0.375000,0.413800, +0.386207,-0.185069,0.258056,0.000000, 0.772800,-0.369000,0.516300, 0.406200,0.379300, +0.340665,-0.133764,0.340666,0.000000, 0.681500,-0.266600,0.681500, 0.375000,0.413800, +0.328442,-0.185069,0.328443,0.000000, 0.657200,-0.369000,0.657200, 0.375000,0.379300, +0.214333,0.428429,0.143213,0.000000, 0.430700,0.855300,0.287800, 0.406200,0.827600, +0.174562,0.453788,0.116638,0.000000, 0.351400,0.906300,0.234800, 0.406200,0.862100, +0.148453,0.453788,0.148453,0.000000, 0.298900,0.906300,0.298900, 0.375000,0.862100, +0.214333,0.428429,0.143213,0.000000, 0.430700,0.855300,0.287800, 0.406200,0.827600, +0.148453,0.453788,0.148453,0.000000, 0.298900,0.906300,0.298900, 0.375000,0.862100, +0.182275,0.428429,0.182276,0.000000, 0.366300,0.855300,0.366300, 0.375000,0.827600, +0.367306,-0.234204,0.245426,0.000000, 0.735200,-0.467000,0.491300, 0.406200,0.344800, +0.386207,-0.185069,0.258056,0.000000, 0.772800,-0.369000,0.516300, 0.406200,0.379300, +0.328442,-0.185069,0.328443,0.000000, 0.657200,-0.369000,0.657200, 0.375000,0.379300, +0.367306,-0.234204,0.245426,0.000000, 0.735200,-0.467000,0.491300, 0.406200,0.344800, +0.328442,-0.185069,0.328443,0.000000, 0.657200,-0.369000,0.657200, 0.375000,0.379300, +0.312368,-0.234204,0.312368,0.000000, 0.625200,-0.467000,0.625200, 0.375000,0.344800, +0.251591,0.398046,0.168108,0.000000, 0.505000,0.794500,0.337400, 0.406200,0.793100, +0.214333,0.428429,0.143213,0.000000, 0.430700,0.855300,0.287800, 0.406200,0.827600, +0.182275,0.428429,0.182276,0.000000, 0.366300,0.855300,0.366300, 0.375000,0.827600, +0.251591,0.398046,0.168108,0.000000, 0.505000,0.794500,0.337400, 0.406200,0.793100, +0.182275,0.428429,0.182276,0.000000, 0.366300,0.855300,0.366300, 0.375000,0.827600, +0.213960,0.398046,0.213961,0.000000, 0.429400,0.794500,0.429400, 0.375000,0.793100, +0.344098,-0.280594,0.229919,0.000000, 0.689100,-0.559600,0.460400, 0.406200,0.310300, +0.367306,-0.234204,0.245426,0.000000, 0.735200,-0.467000,0.491300, 0.406200,0.344800, +0.312368,-0.234204,0.312368,0.000000, 0.625200,-0.467000,0.625200, 0.375000,0.344800, +0.344098,-0.280594,0.229919,0.000000, 0.689100,-0.559600,0.460400, 0.406200,0.310300, +0.312368,-0.234204,0.312368,0.000000, 0.625200,-0.467000,0.625200, 0.375000,0.344800, +0.292632,-0.280594,0.292632,0.000000, 0.586000,-0.559600,0.586000, 0.375000,0.310300, +0.285899,0.362998,0.191032,0.000000, 0.573300,0.724300,0.383000, 0.406200,0.758600, +0.251591,0.398046,0.168108,0.000000, 0.505000,0.794500,0.337400, 0.406200,0.793100, +0.213960,0.398046,0.213961,0.000000, 0.429400,0.794500,0.429400, 0.375000,0.793100, +0.285899,0.362998,0.191032,0.000000, 0.573300,0.724300,0.383000, 0.406200,0.758600, +0.213960,0.398046,0.213961,0.000000, 0.429400,0.794500,0.429400, 0.375000,0.793100, +0.243137,0.362998,0.243138,0.000000, 0.487500,0.724300,0.487500, 0.375000,0.758600, +0.316857,-0.323693,0.211717,0.000000, 0.634900,-0.645700,0.424200, 0.406200,0.275900, +0.344098,-0.280594,0.229919,0.000000, 0.689100,-0.559600,0.460400, 0.406200,0.310300, +0.292632,-0.280594,0.292632,0.000000, 0.586000,-0.559600,0.586000, 0.375000,0.310300, +0.316857,-0.323693,0.211717,0.000000, 0.634900,-0.645700,0.424200, 0.406200,0.275900, +0.292632,-0.280594,0.292632,0.000000, 0.586000,-0.559600,0.586000, 0.375000,0.310300, +0.269464,-0.323693,0.269464,0.000000, 0.539900,-0.645700,0.539900, 0.375000,0.275900, +0.316857,0.323693,0.211717,0.000000, 0.634900,0.645700,0.424200, 0.406200,0.724100, +0.285899,0.362998,0.191032,0.000000, 0.573300,0.724300,0.383000, 0.406200,0.758600, +0.243137,0.362998,0.243138,0.000000, 0.487500,0.724300,0.487500, 0.375000,0.758600, +0.316857,0.323693,0.211717,0.000000, 0.634900,0.645700,0.424200, 0.406200,0.724100, +0.243137,0.362998,0.243138,0.000000, 0.487500,0.724300,0.487500, 0.375000,0.758600, +0.269464,0.323693,0.269464,0.000000, 0.539900,0.645700,0.539900, 0.375000,0.724100, +0.285900,-0.362998,0.191032,0.000000, 0.573300,-0.724300,0.383000, 0.406200,0.241400, +0.316857,-0.323693,0.211717,0.000000, 0.634900,-0.645700,0.424200, 0.406200,0.275900, +0.269464,-0.323693,0.269464,0.000000, 0.539900,-0.645700,0.539900, 0.375000,0.275900, +0.285900,-0.362998,0.191032,0.000000, 0.573300,-0.724300,0.383000, 0.406200,0.241400, +0.269464,-0.323693,0.269464,0.000000, 0.539900,-0.645700,0.539900, 0.375000,0.275900, +0.243137,-0.362998,0.243138,0.000000, 0.487500,-0.724300,0.487500, 0.375000,0.241400, +0.344098,0.280594,0.229919,0.000000, 0.689100,0.559600,0.460400, 0.406200,0.689700, +0.316857,0.323693,0.211717,0.000000, 0.634900,0.645700,0.424200, 0.406200,0.724100, +0.269464,0.323693,0.269464,0.000000, 0.539900,0.645700,0.539900, 0.375000,0.724100, +0.344098,0.280594,0.229919,0.000000, 0.689100,0.559600,0.460400, 0.406200,0.689700, +0.269464,0.323693,0.269464,0.000000, 0.539900,0.645700,0.539900, 0.375000,0.724100, +0.292632,0.280594,0.292632,0.000000, 0.586000,0.559600,0.586000, 0.375000,0.689700, +0.251591,-0.398046,0.168108,0.000000, 0.504900,-0.794500,0.337400, 0.406200,0.206900, +0.285900,-0.362998,0.191032,0.000000, 0.573300,-0.724300,0.383000, 0.406200,0.241400, +0.243137,-0.362998,0.243138,0.000000, 0.487500,-0.724300,0.487500, 0.375000,0.241400, +0.251591,-0.398046,0.168108,0.000000, 0.504900,-0.794500,0.337400, 0.406200,0.206900, +0.243137,-0.362998,0.243138,0.000000, 0.487500,-0.724300,0.487500, 0.375000,0.241400, +0.213960,-0.398046,0.213961,0.000000, 0.429400,-0.794500,0.429400, 0.375000,0.206900, +0.367306,0.234204,0.245426,0.000000, 0.735200,0.467000,0.491300, 0.406200,0.655200, +0.344098,0.280594,0.229919,0.000000, 0.689100,0.559600,0.460400, 0.406200,0.689700, +0.292632,0.280594,0.292632,0.000000, 0.586000,0.559600,0.586000, 0.375000,0.689700, +0.367306,0.234204,0.245426,0.000000, 0.735200,0.467000,0.491300, 0.406200,0.655200, +0.292632,0.280594,0.292632,0.000000, 0.586000,0.559600,0.586000, 0.375000,0.689700, +0.312368,0.234204,0.312368,0.000000, 0.625200,0.467000,0.625200, 0.375000,0.655200, +0.182275,0.428429,0.182276,0.000000, 0.366300,0.855300,0.366300, 0.375000,0.827600, +0.148453,0.453788,0.148453,0.000000, 0.298900,0.906300,0.298900, 0.375000,0.862100, +0.116638,0.453788,0.174562,0.000000, 0.234800,0.906300,0.351400, 0.343700,0.862100, +0.182275,0.428429,0.182276,0.000000, 0.366300,0.855300,0.366300, 0.375000,0.827600, +0.116638,0.453788,0.174562,0.000000, 0.234800,0.906300,0.351400, 0.343700,0.862100, +0.143212,0.428429,0.214333,0.000000, 0.287800,0.855300,0.430700, 0.343700,0.827600, +0.312368,-0.234204,0.312368,0.000000, 0.625200,-0.467000,0.625200, 0.375000,0.344800, +0.328442,-0.185069,0.328443,0.000000, 0.657200,-0.369000,0.657200, 0.375000,0.379300, +0.258055,-0.185069,0.386207,0.000000, 0.516300,-0.369000,0.772800, 0.343700,0.379300, +0.312368,-0.234204,0.312368,0.000000, 0.625200,-0.467000,0.625200, 0.375000,0.344800, +0.258055,-0.185069,0.386207,0.000000, 0.516300,-0.369000,0.772800, 0.343700,0.379300, +0.245426,-0.234204,0.367306,0.000000, 0.491300,-0.467000,0.735200, 0.343700,0.344800, +0.213960,0.398046,0.213961,0.000000, 0.429400,0.794500,0.429400, 0.375000,0.793100, +0.182275,0.428429,0.182276,0.000000, 0.366300,0.855300,0.366300, 0.375000,0.827600, +0.143212,0.428429,0.214333,0.000000, 0.287800,0.855300,0.430700, 0.343700,0.827600, +0.213960,0.398046,0.213961,0.000000, 0.429400,0.794500,0.429400, 0.375000,0.793100, +0.143212,0.428429,0.214333,0.000000, 0.287800,0.855300,0.430700, 0.343700,0.827600, +0.168107,0.398046,0.251592,0.000000, 0.337400,0.794500,0.505000, 0.343700,0.793100, +0.292632,-0.280594,0.292632,0.000000, 0.586000,-0.559600,0.586000, 0.375000,0.310300, +0.312368,-0.234204,0.312368,0.000000, 0.625200,-0.467000,0.625200, 0.375000,0.344800, +0.245426,-0.234204,0.367306,0.000000, 0.491300,-0.467000,0.735200, 0.343700,0.344800, +0.292632,-0.280594,0.292632,0.000000, 0.586000,-0.559600,0.586000, 0.375000,0.310300, +0.245426,-0.234204,0.367306,0.000000, 0.491300,-0.467000,0.735200, 0.343700,0.344800, +0.229919,-0.280594,0.344099,0.000000, 0.460400,-0.559600,0.689100, 0.343700,0.310300, +0.243137,0.362998,0.243138,0.000000, 0.487500,0.724300,0.487500, 0.375000,0.758600, +0.213960,0.398046,0.213961,0.000000, 0.429400,0.794500,0.429400, 0.375000,0.793100, +0.168107,0.398046,0.251592,0.000000, 0.337400,0.794500,0.505000, 0.343700,0.793100, +0.243137,0.362998,0.243138,0.000000, 0.487500,0.724300,0.487500, 0.375000,0.758600, +0.168107,0.398046,0.251592,0.000000, 0.337400,0.794500,0.505000, 0.343700,0.793100, +0.191032,0.362998,0.285900,0.000000, 0.383000,0.724300,0.573300, 0.343700,0.758600, +0.269464,-0.323693,0.269464,0.000000, 0.539900,-0.645700,0.539900, 0.375000,0.275900, +0.292632,-0.280594,0.292632,0.000000, 0.586000,-0.559600,0.586000, 0.375000,0.310300, +0.229919,-0.280594,0.344099,0.000000, 0.460400,-0.559600,0.689100, 0.343700,0.310300, +0.269464,-0.323693,0.269464,0.000000, 0.539900,-0.645700,0.539900, 0.375000,0.275900, +0.229919,-0.280594,0.344099,0.000000, 0.460400,-0.559600,0.689100, 0.343700,0.310300, +0.211717,-0.323693,0.316857,0.000000, 0.424200,-0.645700,0.634900, 0.343700,0.275900, +0.269464,0.323693,0.269464,0.000000, 0.539900,0.645700,0.539900, 0.375000,0.724100, +0.243137,0.362998,0.243138,0.000000, 0.487500,0.724300,0.487500, 0.375000,0.758600, +0.191032,0.362998,0.285900,0.000000, 0.383000,0.724300,0.573300, 0.343700,0.758600, +0.269464,0.323693,0.269464,0.000000, 0.539900,0.645700,0.539900, 0.375000,0.724100, +0.191032,0.362998,0.285900,0.000000, 0.383000,0.724300,0.573300, 0.343700,0.758600, +0.211717,0.323693,0.316857,0.000000, 0.424200,0.645700,0.634900, 0.343700,0.724100, +0.243137,-0.362998,0.243138,0.000000, 0.487500,-0.724300,0.487500, 0.375000,0.241400, +0.269464,-0.323693,0.269464,0.000000, 0.539900,-0.645700,0.539900, 0.375000,0.275900, +0.211717,-0.323693,0.316857,0.000000, 0.424200,-0.645700,0.634900, 0.343700,0.275900, +0.243137,-0.362998,0.243138,0.000000, 0.487500,-0.724300,0.487500, 0.375000,0.241400, +0.211717,-0.323693,0.316857,0.000000, 0.424200,-0.645700,0.634900, 0.343700,0.275900, +0.191032,-0.362998,0.285900,0.000000, 0.383000,-0.724300,0.573300, 0.343700,0.241400, +0.292632,0.280594,0.292632,0.000000, 0.586000,0.559600,0.586000, 0.375000,0.689700, +0.269464,0.323693,0.269464,0.000000, 0.539900,0.645700,0.539900, 0.375000,0.724100, +0.211717,0.323693,0.316857,0.000000, 0.424200,0.645700,0.634900, 0.343700,0.724100, +0.292632,0.280594,0.292632,0.000000, 0.586000,0.559600,0.586000, 0.375000,0.689700, +0.211717,0.323693,0.316857,0.000000, 0.424200,0.645700,0.634900, 0.343700,0.724100, +0.229919,0.280594,0.344099,0.000000, 0.460400,0.559600,0.689100, 0.343700,0.689700, +0.213960,-0.398046,0.213961,0.000000, 0.429400,-0.794500,0.429400, 0.375000,0.206900, +0.243137,-0.362998,0.243138,0.000000, 0.487500,-0.724300,0.487500, 0.375000,0.241400, +0.191032,-0.362998,0.285900,0.000000, 0.383000,-0.724300,0.573300, 0.343700,0.241400, +0.213960,-0.398046,0.213961,0.000000, 0.429400,-0.794500,0.429400, 0.375000,0.206900, +0.191032,-0.362998,0.285900,0.000000, 0.383000,-0.724300,0.573300, 0.343700,0.241400, +0.168107,-0.398046,0.251592,0.000000, 0.337400,-0.794500,0.505000, 0.343700,0.206900, +0.312368,0.234204,0.312368,0.000000, 0.625200,0.467000,0.625200, 0.375000,0.655200, +0.292632,0.280594,0.292632,0.000000, 0.586000,0.559600,0.586000, 0.375000,0.689700, +0.229919,0.280594,0.344099,0.000000, 0.460400,0.559600,0.689100, 0.343700,0.689700, +0.312368,0.234204,0.312368,0.000000, 0.625200,0.467000,0.625200, 0.375000,0.655200, +0.229919,0.280594,0.344099,0.000000, 0.460400,0.559600,0.689100, 0.343700,0.689700, +0.245426,0.234204,0.367306,0.000000, 0.491300,0.467000,0.735200, 0.343700,0.655200, +0.182275,-0.428429,0.182276,0.000000, 0.366300,-0.855300,0.366300, 0.375000,0.172400, +0.213960,-0.398046,0.213961,0.000000, 0.429400,-0.794500,0.429400, 0.375000,0.206900, +0.168107,-0.398046,0.251592,0.000000, 0.337400,-0.794500,0.505000, 0.343700,0.206900, +0.182275,-0.428429,0.182276,0.000000, 0.366300,-0.855300,0.366300, 0.375000,0.172400, +0.168107,-0.398046,0.251592,0.000000, 0.337400,-0.794500,0.505000, 0.343700,0.206900, +0.143212,-0.428429,0.214334,0.000000, 0.287800,-0.855300,0.430700, 0.343700,0.172400, +0.328442,0.185069,0.328443,0.000000, 0.657200,0.369000,0.657200, 0.375000,0.620700, +0.312368,0.234204,0.312368,0.000000, 0.625200,0.467000,0.625200, 0.375000,0.655200, +0.245426,0.234204,0.367306,0.000000, 0.491300,0.467000,0.735200, 0.343700,0.655200, +0.328442,0.185069,0.328443,0.000000, 0.657200,0.369000,0.657200, 0.375000,0.620700, +0.245426,0.234204,0.367306,0.000000, 0.491300,0.467000,0.735200, 0.343700,0.655200, +0.258055,0.185069,0.386207,0.000000, 0.516300,0.369000,0.772800, 0.343700,0.620700, +0.148453,-0.453788,0.148453,0.000000, 0.298900,-0.906300,0.298900, 0.375000,0.137900, +0.182275,-0.428429,0.182276,0.000000, 0.366300,-0.855300,0.366300, 0.375000,0.172400, +0.143212,-0.428429,0.214334,0.000000, 0.287800,-0.855300,0.430700, 0.343700,0.172400, +0.148453,-0.453788,0.148453,0.000000, 0.298900,-0.906300,0.298900, 0.375000,0.137900, +0.143212,-0.428429,0.214334,0.000000, 0.287800,-0.855300,0.430700, 0.343700,0.172400, +0.116638,-0.453788,0.174562,0.000000, 0.234800,-0.906300,0.351400, 0.343700,0.137900, +0.340665,0.133764,0.340666,0.000000, 0.681500,0.266600,0.681500, 0.375000,0.586200, +0.328442,0.185069,0.328443,0.000000, 0.657200,0.369000,0.657200, 0.375000,0.620700, +0.258055,0.185069,0.386207,0.000000, 0.516300,0.369000,0.772800, 0.343700,0.620700, +0.340665,0.133764,0.340666,0.000000, 0.681500,0.266600,0.681500, 0.375000,0.586200, +0.258055,0.185069,0.386207,0.000000, 0.516300,0.369000,0.772800, 0.343700,0.620700, +0.267659,0.133764,0.400581,0.000000, 0.535400,0.266600,0.801400, 0.343700,0.586200, +0.112889,-0.473826,0.112890,0.000000, 0.227900,-0.946600,0.227900, 0.375000,0.103400, +0.148453,-0.453788,0.148453,0.000000, 0.298900,-0.906300,0.298900, 0.375000,0.137900, +0.116638,-0.453788,0.174562,0.000000, 0.234800,-0.906300,0.351400, 0.343700,0.137900, +0.112889,-0.473826,0.112890,0.000000, 0.227900,-0.946600,0.227900, 0.375000,0.103400, +0.116638,-0.453788,0.174562,0.000000, 0.234800,-0.906300,0.351400, 0.343700,0.137900, +0.088697,-0.473826,0.132745,0.000000, 0.179100,-0.946600,0.268000, 0.343700,0.103400, +0.348895,0.080891,0.348895,0.000000, 0.697800,0.161200,0.697800, 0.375000,0.551700, +0.340665,0.133764,0.340666,0.000000, 0.681500,0.266600,0.681500, 0.375000,0.586200, +0.267659,0.133764,0.400581,0.000000, 0.535400,0.266600,0.801400, 0.343700,0.586200, +0.348895,0.080891,0.348895,0.000000, 0.697800,0.161200,0.697800, 0.375000,0.551700, +0.267659,0.133764,0.400581,0.000000, 0.535400,0.266600,0.801400, 0.343700,0.586200, +0.274125,0.080891,0.410257,0.000000, 0.548300,0.161200,0.820600, 0.343700,0.551700, +0.076003,-0.488310,0.076003,0.000000, 0.154300,-0.975900,0.154300, 0.375000,0.069000, +0.112889,-0.473826,0.112890,0.000000, 0.227900,-0.946600,0.227900, 0.375000,0.103400, +0.088697,-0.473826,0.132745,0.000000, 0.179100,-0.946600,0.268000, 0.343700,0.103400, +0.076003,-0.488310,0.076003,0.000000, 0.154300,-0.975900,0.154300, 0.375000,0.069000, +0.088697,-0.473826,0.132745,0.000000, 0.179100,-0.946600,0.268000, 0.343700,0.103400, +0.059715,-0.488310,0.089370,0.000000, 0.121200,-0.975900,0.181400, 0.343700,0.069000, +0.353034,0.027069,0.353034,0.000000, 0.706100,0.054000,0.706100, 0.375000,0.517200, +0.348895,0.080891,0.348895,0.000000, 0.697800,0.161200,0.697800, 0.375000,0.551700, +0.274125,0.080891,0.410257,0.000000, 0.548300,0.161200,0.820600, 0.343700,0.551700, +0.353034,0.027069,0.353034,0.000000, 0.706100,0.054000,0.706100, 0.375000,0.517200, +0.274125,0.080891,0.410257,0.000000, 0.548300,0.161200,0.820600, 0.343700,0.551700, +0.277377,0.027069,0.415125,0.000000, 0.554700,0.054000,0.830300, 0.343700,0.517200, +0.038225,0.497069,0.038226,0.000000, 0.078800,0.993700,0.078800, 0.463500,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +0.030033,0.497069,0.044948,0.000000, 0.061900,0.993700,0.092700, 0.465300,0.962300, +0.038226,-0.497069,0.038226,0.000000, 0.078800,-0.993700,0.078800, 0.375000,0.034500, +0.076003,-0.488310,0.076003,0.000000, 0.154300,-0.975900,0.154300, 0.375000,0.069000, +0.059715,-0.488310,0.089370,0.000000, 0.121200,-0.975900,0.181400, 0.343700,0.069000, +0.038226,-0.497069,0.038226,0.000000, 0.078800,-0.993700,0.078800, 0.375000,0.034500, +0.059715,-0.488310,0.089370,0.000000, 0.121200,-0.975900,0.181400, 0.343700,0.069000, +0.030034,-0.497069,0.044949,0.000000, 0.061900,-0.993700,0.092700, 0.343700,0.034500, +0.353034,-0.027069,0.353034,0.000000, 0.706100,-0.054000,0.706100, 0.375000,0.482800, +0.353034,0.027069,0.353034,0.000000, 0.706100,0.054000,0.706100, 0.375000,0.517200, +0.277377,0.027069,0.415125,0.000000, 0.554700,0.054000,0.830300, 0.343700,0.517200, +0.353034,-0.027069,0.353034,0.000000, 0.706100,-0.054000,0.706100, 0.375000,0.482800, +0.277377,0.027069,0.415125,0.000000, 0.554700,0.054000,0.830300, 0.343700,0.517200, +0.277377,-0.027069,0.415125,0.000000, 0.554700,-0.054000,0.830300, 0.343700,0.482800, +0.076003,0.488310,0.076003,0.000000, 0.154300,0.975900,0.154300, 0.375000,0.931000, +0.038225,0.497069,0.038226,0.000000, 0.078800,0.993700,0.078800, 0.375000,0.965500, +0.030033,0.497069,0.044948,0.000000, 0.061900,0.993700,0.092700, 0.343700,0.965500, +0.076003,0.488310,0.076003,0.000000, 0.154300,0.975900,0.154300, 0.375000,0.931000, +0.030033,0.497069,0.044948,0.000000, 0.061900,0.993700,0.092700, 0.343700,0.965500, +0.059715,0.488310,0.089370,0.000000, 0.121200,0.975900,0.181400, 0.343700,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +0.038226,-0.497069,0.038226,0.000000, 0.078800,-0.993700,0.078800, 0.441800,0.053800, +0.030034,-0.497069,0.044949,0.000000, 0.061900,-0.993700,0.092700, 0.439200,0.053800, +0.348895,-0.080891,0.348895,0.000000, 0.697800,-0.161200,0.697800, 0.375000,0.448300, +0.353034,-0.027069,0.353034,0.000000, 0.706100,-0.054000,0.706100, 0.375000,0.482800, +0.277377,-0.027069,0.415125,0.000000, 0.554700,-0.054000,0.830300, 0.343700,0.482800, +0.348895,-0.080891,0.348895,0.000000, 0.697800,-0.161200,0.697800, 0.375000,0.448300, +0.277377,-0.027069,0.415125,0.000000, 0.554700,-0.054000,0.830300, 0.343700,0.482800, +0.274125,-0.080891,0.410257,0.000000, 0.548300,-0.161200,0.820600, 0.343700,0.448300, +0.112889,0.473826,0.112889,0.000000, 0.227900,0.946600,0.227900, 0.375000,0.896600, +0.076003,0.488310,0.076003,0.000000, 0.154300,0.975900,0.154300, 0.375000,0.931000, +0.059715,0.488310,0.089370,0.000000, 0.121200,0.975900,0.181400, 0.343700,0.931000, +0.112889,0.473826,0.112889,0.000000, 0.227900,0.946600,0.227900, 0.375000,0.896600, +0.059715,0.488310,0.089370,0.000000, 0.121200,0.975900,0.181400, 0.343700,0.931000, +0.088697,0.473826,0.132745,0.000000, 0.179100,0.946600,0.268000, 0.343700,0.896600, +0.340665,-0.133764,0.340666,0.000000, 0.681500,-0.266600,0.681500, 0.375000,0.413800, +0.348895,-0.080891,0.348895,0.000000, 0.697800,-0.161200,0.697800, 0.375000,0.448300, +0.274125,-0.080891,0.410257,0.000000, 0.548300,-0.161200,0.820600, 0.343700,0.448300, +0.340665,-0.133764,0.340666,0.000000, 0.681500,-0.266600,0.681500, 0.375000,0.413800, +0.274125,-0.080891,0.410257,0.000000, 0.548300,-0.161200,0.820600, 0.343700,0.448300, +0.267659,-0.133764,0.400581,0.000000, 0.535400,-0.266600,0.801400, 0.343700,0.413800, +0.148453,0.453788,0.148453,0.000000, 0.298900,0.906300,0.298900, 0.375000,0.862100, +0.112889,0.473826,0.112889,0.000000, 0.227900,0.946600,0.227900, 0.375000,0.896600, +0.088697,0.473826,0.132745,0.000000, 0.179100,0.946600,0.268000, 0.343700,0.896600, +0.148453,0.453788,0.148453,0.000000, 0.298900,0.906300,0.298900, 0.375000,0.862100, +0.088697,0.473826,0.132745,0.000000, 0.179100,0.946600,0.268000, 0.343700,0.896600, +0.116638,0.453788,0.174562,0.000000, 0.234800,0.906300,0.351400, 0.343700,0.862100, +0.328442,-0.185069,0.328443,0.000000, 0.657200,-0.369000,0.657200, 0.375000,0.379300, +0.340665,-0.133764,0.340666,0.000000, 0.681500,-0.266600,0.681500, 0.375000,0.413800, +0.267659,-0.133764,0.400581,0.000000, 0.535400,-0.266600,0.801400, 0.343700,0.413800, +0.328442,-0.185069,0.328443,0.000000, 0.657200,-0.369000,0.657200, 0.375000,0.379300, +0.267659,-0.133764,0.400581,0.000000, 0.535400,-0.266600,0.801400, 0.343700,0.413800, +0.258055,-0.185069,0.386207,0.000000, 0.516300,-0.369000,0.772800, 0.343700,0.379300, +0.274125,0.080891,0.410257,0.000000, 0.548300,0.161200,0.820600, 0.343700,0.551700, +0.267659,0.133764,0.400581,0.000000, 0.535400,0.266600,0.801400, 0.343700,0.586200, +0.184366,0.133764,0.445101,0.000000, 0.368800,0.266600,0.890400, 0.312500,0.586200, +0.274125,0.080891,0.410257,0.000000, 0.548300,0.161200,0.820600, 0.343700,0.551700, +0.184366,0.133764,0.445101,0.000000, 0.368800,0.266600,0.890400, 0.312500,0.586200, +0.188820,0.080891,0.455853,0.000000, 0.377700,0.161200,0.911800, 0.312500,0.551700, +0.059715,-0.488310,0.089370,0.000000, 0.121200,-0.975900,0.181400, 0.343700,0.069000, +0.088697,-0.473826,0.132745,0.000000, 0.179100,-0.946600,0.268000, 0.343700,0.103400, +0.061095,-0.473826,0.147498,0.000000, 0.123300,-0.946600,0.297800, 0.312500,0.103400, +0.059715,-0.488310,0.089370,0.000000, 0.121200,-0.975900,0.181400, 0.343700,0.069000, +0.061095,-0.473826,0.147498,0.000000, 0.123300,-0.946600,0.297800, 0.312500,0.103400, +0.041132,-0.488310,0.099303,0.000000, 0.083500,-0.975900,0.201600, 0.312500,0.069000, +0.277377,0.027069,0.415125,0.000000, 0.554700,0.054000,0.830300, 0.343700,0.517200, +0.274125,0.080891,0.410257,0.000000, 0.548300,0.161200,0.820600, 0.343700,0.551700, +0.188820,0.080891,0.455853,0.000000, 0.377700,0.161200,0.911800, 0.312500,0.551700, +0.277377,0.027069,0.415125,0.000000, 0.554700,0.054000,0.830300, 0.343700,0.517200, +0.188820,0.080891,0.455853,0.000000, 0.377700,0.161200,0.911800, 0.312500,0.551700, +0.191060,0.027069,0.461262,0.000000, 0.382100,0.054000,0.922500, 0.312500,0.517200, +0.030033,0.497069,0.044948,0.000000, 0.061900,0.993700,0.092700, 0.465300,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +0.020687,0.497069,0.049944,0.000000, 0.042600,0.993700,0.103000, 0.467100,0.962300, +0.030034,-0.497069,0.044949,0.000000, 0.061900,-0.993700,0.092700, 0.343700,0.034500, +0.059715,-0.488310,0.089370,0.000000, 0.121200,-0.975900,0.181400, 0.343700,0.069000, +0.041132,-0.488310,0.099303,0.000000, 0.083500,-0.975900,0.201600, 0.312500,0.069000, +0.030034,-0.497069,0.044949,0.000000, 0.061900,-0.993700,0.092700, 0.343700,0.034500, +0.041132,-0.488310,0.099303,0.000000, 0.083500,-0.975900,0.201600, 0.312500,0.069000, +0.020687,-0.497069,0.049945,0.000000, 0.042600,-0.993700,0.103000, 0.312500,0.034500, +0.277377,-0.027069,0.415125,0.000000, 0.554700,-0.054000,0.830300, 0.343700,0.482800, +0.277377,0.027069,0.415125,0.000000, 0.554700,0.054000,0.830300, 0.343700,0.517200, +0.191060,0.027069,0.461262,0.000000, 0.382100,0.054000,0.922500, 0.312500,0.517200, +0.277377,-0.027069,0.415125,0.000000, 0.554700,-0.054000,0.830300, 0.343700,0.482800, +0.191060,0.027069,0.461262,0.000000, 0.382100,0.054000,0.922500, 0.312500,0.517200, +0.191060,-0.027069,0.461262,0.000000, 0.382100,-0.054000,0.922500, 0.312500,0.482800, +0.059715,0.488310,0.089370,0.000000, 0.121200,0.975900,0.181400, 0.343700,0.931000, +0.030033,0.497069,0.044948,0.000000, 0.061900,0.993700,0.092700, 0.343700,0.965500, +0.020687,0.497069,0.049944,0.000000, 0.042600,0.993700,0.103000, 0.312500,0.965500, +0.059715,0.488310,0.089370,0.000000, 0.121200,0.975900,0.181400, 0.343700,0.931000, +0.020687,0.497069,0.049944,0.000000, 0.042600,0.993700,0.103000, 0.312500,0.965500, +0.041132,0.488310,0.099303,0.000000, 0.083500,0.975900,0.201600, 0.312500,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +0.030034,-0.497069,0.044949,0.000000, 0.061900,-0.993700,0.092700, 0.439200,0.053800, +0.020687,-0.497069,0.049945,0.000000, 0.042600,-0.993700,0.103000, 0.436600,0.053800, +0.274125,-0.080891,0.410257,0.000000, 0.548300,-0.161200,0.820600, 0.343700,0.448300, +0.277377,-0.027069,0.415125,0.000000, 0.554700,-0.054000,0.830300, 0.343700,0.482800, +0.191060,-0.027069,0.461262,0.000000, 0.382100,-0.054000,0.922500, 0.312500,0.482800, +0.274125,-0.080891,0.410257,0.000000, 0.548300,-0.161200,0.820600, 0.343700,0.448300, +0.191060,-0.027069,0.461262,0.000000, 0.382100,-0.054000,0.922500, 0.312500,0.482800, +0.188820,-0.080891,0.455853,0.000000, 0.377700,-0.161200,0.911800, 0.312500,0.448300, +0.088697,0.473826,0.132745,0.000000, 0.179100,0.946600,0.268000, 0.343700,0.896600, +0.059715,0.488310,0.089370,0.000000, 0.121200,0.975900,0.181400, 0.343700,0.931000, +0.041132,0.488310,0.099303,0.000000, 0.083500,0.975900,0.201600, 0.312500,0.931000, +0.088697,0.473826,0.132745,0.000000, 0.179100,0.946600,0.268000, 0.343700,0.896600, +0.041132,0.488310,0.099303,0.000000, 0.083500,0.975900,0.201600, 0.312500,0.931000, +0.061095,0.473826,0.147498,0.000000, 0.123300,0.946600,0.297800, 0.312500,0.896600, +0.267659,-0.133764,0.400581,0.000000, 0.535400,-0.266600,0.801400, 0.343700,0.413800, +0.274125,-0.080891,0.410257,0.000000, 0.548300,-0.161200,0.820600, 0.343700,0.448300, +0.188820,-0.080891,0.455853,0.000000, 0.377700,-0.161200,0.911800, 0.312500,0.448300, +0.267659,-0.133764,0.400581,0.000000, 0.535400,-0.266600,0.801400, 0.343700,0.413800, +0.188820,-0.080891,0.455853,0.000000, 0.377700,-0.161200,0.911800, 0.312500,0.448300, +0.184366,-0.133764,0.445101,0.000000, 0.368800,-0.266600,0.890400, 0.312500,0.413800, +0.116638,0.453788,0.174562,0.000000, 0.234800,0.906300,0.351400, 0.343700,0.862100, +0.088697,0.473826,0.132745,0.000000, 0.179100,0.946600,0.268000, 0.343700,0.896600, +0.061095,0.473826,0.147498,0.000000, 0.123300,0.946600,0.297800, 0.312500,0.896600, +0.116638,0.453788,0.174562,0.000000, 0.234800,0.906300,0.351400, 0.343700,0.862100, +0.061095,0.473826,0.147498,0.000000, 0.123300,0.946600,0.297800, 0.312500,0.896600, +0.080342,0.453788,0.193963,0.000000, 0.161700,0.906300,0.390500, 0.312500,0.862100, +0.258055,-0.185069,0.386207,0.000000, 0.516300,-0.369000,0.772800, 0.343700,0.379300, +0.267659,-0.133764,0.400581,0.000000, 0.535400,-0.266600,0.801400, 0.343700,0.413800, +0.184366,-0.133764,0.445101,0.000000, 0.368800,-0.266600,0.890400, 0.312500,0.413800, +0.258055,-0.185069,0.386207,0.000000, 0.516300,-0.369000,0.772800, 0.343700,0.379300, +0.184366,-0.133764,0.445101,0.000000, 0.368800,-0.266600,0.890400, 0.312500,0.413800, +0.177751,-0.185069,0.429130,0.000000, 0.355700,-0.369000,0.858700, 0.312500,0.379300, +0.143212,0.428429,0.214333,0.000000, 0.287800,0.855300,0.430700, 0.343700,0.827600, +0.116638,0.453788,0.174562,0.000000, 0.234800,0.906300,0.351400, 0.343700,0.862100, +0.080342,0.453788,0.193963,0.000000, 0.161700,0.906300,0.390500, 0.312500,0.862100, +0.143212,0.428429,0.214333,0.000000, 0.287800,0.855300,0.430700, 0.343700,0.827600, +0.080342,0.453788,0.193963,0.000000, 0.161700,0.906300,0.390500, 0.312500,0.862100, +0.098646,0.428429,0.238155,0.000000, 0.198200,0.855300,0.478600, 0.312500,0.827600, +0.245426,-0.234204,0.367306,0.000000, 0.491300,-0.467000,0.735200, 0.343700,0.344800, +0.258055,-0.185069,0.386207,0.000000, 0.516300,-0.369000,0.772800, 0.343700,0.379300, +0.177751,-0.185069,0.429130,0.000000, 0.355700,-0.369000,0.858700, 0.312500,0.379300, +0.245426,-0.234204,0.367306,0.000000, 0.491300,-0.467000,0.735200, 0.343700,0.344800, +0.177751,-0.185069,0.429130,0.000000, 0.355700,-0.369000,0.858700, 0.312500,0.379300, +0.169052,-0.234204,0.408129,0.000000, 0.338400,-0.467000,0.816900, 0.312500,0.344800, +0.168107,0.398046,0.251592,0.000000, 0.337400,0.794500,0.505000, 0.343700,0.793100, +0.143212,0.428429,0.214333,0.000000, 0.287800,0.855300,0.430700, 0.343700,0.827600, +0.098646,0.428429,0.238155,0.000000, 0.198200,0.855300,0.478600, 0.312500,0.827600, +0.168107,0.398046,0.251592,0.000000, 0.337400,0.794500,0.505000, 0.343700,0.793100, +0.098646,0.428429,0.238155,0.000000, 0.198200,0.855300,0.478600, 0.312500,0.827600, +0.115795,0.398046,0.279554,0.000000, 0.232400,0.794500,0.561100, 0.312500,0.793100, +0.229919,-0.280594,0.344099,0.000000, 0.460400,-0.559600,0.689100, 0.343700,0.310300, +0.245426,-0.234204,0.367306,0.000000, 0.491300,-0.467000,0.735200, 0.343700,0.344800, +0.169052,-0.234204,0.408129,0.000000, 0.338400,-0.467000,0.816900, 0.312500,0.344800, +0.229919,-0.280594,0.344099,0.000000, 0.460400,-0.559600,0.689100, 0.343700,0.310300, +0.169052,-0.234204,0.408129,0.000000, 0.338400,-0.467000,0.816900, 0.312500,0.344800, +0.158370,-0.280594,0.382342,0.000000, 0.317100,-0.559600,0.765600, 0.312500,0.310300, +0.191032,0.362998,0.285900,0.000000, 0.383000,0.724300,0.573300, 0.343700,0.758600, +0.168107,0.398046,0.251592,0.000000, 0.337400,0.794500,0.505000, 0.343700,0.793100, +0.115795,0.398046,0.279554,0.000000, 0.232400,0.794500,0.561100, 0.312500,0.793100, +0.191032,0.362998,0.285900,0.000000, 0.383000,0.724300,0.573300, 0.343700,0.758600, +0.115795,0.398046,0.279554,0.000000, 0.232400,0.794500,0.561100, 0.312500,0.793100, +0.131585,0.362998,0.317675,0.000000, 0.263800,0.724300,0.637000, 0.312500,0.758600, +0.211717,-0.323693,0.316857,0.000000, 0.424200,-0.645700,0.634900, 0.343700,0.275900, +0.229919,-0.280594,0.344099,0.000000, 0.460400,-0.559600,0.689100, 0.343700,0.310300, +0.158370,-0.280594,0.382342,0.000000, 0.317100,-0.559600,0.765600, 0.312500,0.310300, +0.211717,-0.323693,0.316857,0.000000, 0.424200,-0.645700,0.634900, 0.343700,0.275900, +0.158370,-0.280594,0.382342,0.000000, 0.317100,-0.559600,0.765600, 0.312500,0.310300, +0.145832,-0.323693,0.352073,0.000000, 0.292200,-0.645700,0.705400, 0.312500,0.275900, +0.211717,0.323693,0.316857,0.000000, 0.424200,0.645700,0.634900, 0.343700,0.724100, +0.191032,0.362998,0.285900,0.000000, 0.383000,0.724300,0.573300, 0.343700,0.758600, +0.131585,0.362998,0.317675,0.000000, 0.263800,0.724300,0.637000, 0.312500,0.758600, +0.211717,0.323693,0.316857,0.000000, 0.424200,0.645700,0.634900, 0.343700,0.724100, +0.131585,0.362998,0.317675,0.000000, 0.263800,0.724300,0.637000, 0.312500,0.758600, +0.145832,0.323693,0.352073,0.000000, 0.292200,0.645700,0.705400, 0.312500,0.724100, +0.191032,-0.362998,0.285900,0.000000, 0.383000,-0.724300,0.573300, 0.343700,0.241400, +0.211717,-0.323693,0.316857,0.000000, 0.424200,-0.645700,0.634900, 0.343700,0.275900, +0.145832,-0.323693,0.352073,0.000000, 0.292200,-0.645700,0.705400, 0.312500,0.275900, +0.191032,-0.362998,0.285900,0.000000, 0.383000,-0.724300,0.573300, 0.343700,0.241400, +0.145832,-0.323693,0.352073,0.000000, 0.292200,-0.645700,0.705400, 0.312500,0.275900, +0.131585,-0.362998,0.317676,0.000000, 0.263800,-0.724300,0.637000, 0.312500,0.241400, +0.229919,0.280594,0.344099,0.000000, 0.460400,0.559600,0.689100, 0.343700,0.689700, +0.211717,0.323693,0.316857,0.000000, 0.424200,0.645700,0.634900, 0.343700,0.724100, +0.145832,0.323693,0.352073,0.000000, 0.292200,0.645700,0.705400, 0.312500,0.724100, +0.229919,0.280594,0.344099,0.000000, 0.460400,0.559600,0.689100, 0.343700,0.689700, +0.145832,0.323693,0.352073,0.000000, 0.292200,0.645700,0.705400, 0.312500,0.724100, +0.158370,0.280594,0.382342,0.000000, 0.317100,0.559600,0.765600, 0.312500,0.689700, +0.168107,-0.398046,0.251592,0.000000, 0.337400,-0.794500,0.505000, 0.343700,0.206900, +0.191032,-0.362998,0.285900,0.000000, 0.383000,-0.724300,0.573300, 0.343700,0.241400, +0.131585,-0.362998,0.317676,0.000000, 0.263800,-0.724300,0.637000, 0.312500,0.241400, +0.168107,-0.398046,0.251592,0.000000, 0.337400,-0.794500,0.505000, 0.343700,0.206900, +0.131585,-0.362998,0.317676,0.000000, 0.263800,-0.724300,0.637000, 0.312500,0.241400, +0.115795,-0.398046,0.279554,0.000000, 0.232400,-0.794500,0.561100, 0.312500,0.206900, +0.245426,0.234204,0.367306,0.000000, 0.491300,0.467000,0.735200, 0.343700,0.655200, +0.229919,0.280594,0.344099,0.000000, 0.460400,0.559600,0.689100, 0.343700,0.689700, +0.158370,0.280594,0.382342,0.000000, 0.317100,0.559600,0.765600, 0.312500,0.689700, +0.245426,0.234204,0.367306,0.000000, 0.491300,0.467000,0.735200, 0.343700,0.655200, +0.158370,0.280594,0.382342,0.000000, 0.317100,0.559600,0.765600, 0.312500,0.689700, +0.169052,0.234204,0.408129,0.000000, 0.338400,0.467000,0.816900, 0.312500,0.655200, +0.143212,-0.428429,0.214334,0.000000, 0.287800,-0.855300,0.430700, 0.343700,0.172400, +0.168107,-0.398046,0.251592,0.000000, 0.337400,-0.794500,0.505000, 0.343700,0.206900, +0.115795,-0.398046,0.279554,0.000000, 0.232400,-0.794500,0.561100, 0.312500,0.206900, +0.143212,-0.428429,0.214334,0.000000, 0.287800,-0.855300,0.430700, 0.343700,0.172400, +0.115795,-0.398046,0.279554,0.000000, 0.232400,-0.794500,0.561100, 0.312500,0.206900, +0.098646,-0.428429,0.238155,0.000000, 0.198200,-0.855300,0.478600, 0.312500,0.172400, +0.258055,0.185069,0.386207,0.000000, 0.516300,0.369000,0.772800, 0.343700,0.620700, +0.245426,0.234204,0.367306,0.000000, 0.491300,0.467000,0.735200, 0.343700,0.655200, +0.169052,0.234204,0.408129,0.000000, 0.338400,0.467000,0.816900, 0.312500,0.655200, +0.258055,0.185069,0.386207,0.000000, 0.516300,0.369000,0.772800, 0.343700,0.620700, +0.169052,0.234204,0.408129,0.000000, 0.338400,0.467000,0.816900, 0.312500,0.655200, +0.177751,0.185069,0.429130,0.000000, 0.355700,0.369000,0.858700, 0.312500,0.620700, +0.116638,-0.453788,0.174562,0.000000, 0.234800,-0.906300,0.351400, 0.343700,0.137900, +0.143212,-0.428429,0.214334,0.000000, 0.287800,-0.855300,0.430700, 0.343700,0.172400, +0.098646,-0.428429,0.238155,0.000000, 0.198200,-0.855300,0.478600, 0.312500,0.172400, +0.116638,-0.453788,0.174562,0.000000, 0.234800,-0.906300,0.351400, 0.343700,0.137900, +0.098646,-0.428429,0.238155,0.000000, 0.198200,-0.855300,0.478600, 0.312500,0.172400, +0.080342,-0.453788,0.193963,0.000000, 0.161700,-0.906300,0.390500, 0.312500,0.137900, +0.267659,0.133764,0.400581,0.000000, 0.535400,0.266600,0.801400, 0.343700,0.586200, +0.258055,0.185069,0.386207,0.000000, 0.516300,0.369000,0.772800, 0.343700,0.620700, +0.177751,0.185069,0.429130,0.000000, 0.355700,0.369000,0.858700, 0.312500,0.620700, +0.267659,0.133764,0.400581,0.000000, 0.535400,0.266600,0.801400, 0.343700,0.586200, +0.177751,0.185069,0.429130,0.000000, 0.355700,0.369000,0.858700, 0.312500,0.620700, +0.184366,0.133764,0.445101,0.000000, 0.368800,0.266600,0.890400, 0.312500,0.586200, +0.088697,-0.473826,0.132745,0.000000, 0.179100,-0.946600,0.268000, 0.343700,0.103400, +0.116638,-0.453788,0.174562,0.000000, 0.234800,-0.906300,0.351400, 0.343700,0.137900, +0.080342,-0.453788,0.193963,0.000000, 0.161700,-0.906300,0.390500, 0.312500,0.137900, +0.088697,-0.473826,0.132745,0.000000, 0.179100,-0.946600,0.268000, 0.343700,0.103400, +0.080342,-0.453788,0.193963,0.000000, 0.161700,-0.906300,0.390500, 0.312500,0.137900, +0.061095,-0.473826,0.147498,0.000000, 0.123300,-0.946600,0.297800, 0.312500,0.103400, +0.145832,-0.323693,0.352073,0.000000, 0.292200,-0.645700,0.705400, 0.312500,0.275900, +0.158370,-0.280594,0.382342,0.000000, 0.317100,-0.559600,0.765600, 0.312500,0.310300, +0.080737,-0.280594,0.405892,0.000000, 0.161700,-0.559600,0.812800, 0.281200,0.310300, +0.145832,-0.323693,0.352073,0.000000, 0.292200,-0.645700,0.705400, 0.312500,0.275900, +0.080737,-0.280594,0.405892,0.000000, 0.161700,-0.559600,0.812800, 0.281200,0.310300, +0.074345,-0.323693,0.373758,0.000000, 0.149000,-0.645700,0.748900, 0.281200,0.275900, +0.145832,0.323693,0.352073,0.000000, 0.292200,0.645700,0.705400, 0.312500,0.724100, +0.131585,0.362998,0.317675,0.000000, 0.263800,0.724300,0.637000, 0.312500,0.758600, +0.067081,0.362998,0.337242,0.000000, 0.134500,0.724300,0.676200, 0.281200,0.758600, +0.145832,0.323693,0.352073,0.000000, 0.292200,0.645700,0.705400, 0.312500,0.724100, +0.067081,0.362998,0.337242,0.000000, 0.134500,0.724300,0.676200, 0.281200,0.758600, +0.074345,0.323693,0.373758,0.000000, 0.149000,0.645700,0.748900, 0.281200,0.724100, +0.131585,-0.362998,0.317676,0.000000, 0.263800,-0.724300,0.637000, 0.312500,0.241400, +0.145832,-0.323693,0.352073,0.000000, 0.292200,-0.645700,0.705400, 0.312500,0.275900, +0.074345,-0.323693,0.373758,0.000000, 0.149000,-0.645700,0.748900, 0.281200,0.275900, +0.131585,-0.362998,0.317676,0.000000, 0.263800,-0.724300,0.637000, 0.312500,0.241400, +0.074345,-0.323693,0.373758,0.000000, 0.149000,-0.645700,0.748900, 0.281200,0.275900, +0.067081,-0.362998,0.337243,0.000000, 0.134500,-0.724300,0.676200, 0.281200,0.241400, +0.158370,0.280594,0.382342,0.000000, 0.317100,0.559600,0.765600, 0.312500,0.689700, +0.145832,0.323693,0.352073,0.000000, 0.292200,0.645700,0.705400, 0.312500,0.724100, +0.074345,0.323693,0.373758,0.000000, 0.149000,0.645700,0.748900, 0.281200,0.724100, +0.158370,0.280594,0.382342,0.000000, 0.317100,0.559600,0.765600, 0.312500,0.689700, +0.074345,0.323693,0.373758,0.000000, 0.149000,0.645700,0.748900, 0.281200,0.724100, +0.080737,0.280594,0.405892,0.000000, 0.161700,0.559600,0.812800, 0.281200,0.689700, +0.115795,-0.398046,0.279554,0.000000, 0.232400,-0.794500,0.561100, 0.312500,0.206900, +0.131585,-0.362998,0.317676,0.000000, 0.263800,-0.724300,0.637000, 0.312500,0.241400, +0.067081,-0.362998,0.337243,0.000000, 0.134500,-0.724300,0.676200, 0.281200,0.241400, +0.115795,-0.398046,0.279554,0.000000, 0.232400,-0.794500,0.561100, 0.312500,0.206900, +0.067081,-0.362998,0.337243,0.000000, 0.134500,-0.724300,0.676200, 0.281200,0.241400, +0.059031,-0.398046,0.296773,0.000000, 0.118500,-0.794500,0.595600, 0.281200,0.206900, +0.169052,0.234204,0.408129,0.000000, 0.338400,0.467000,0.816900, 0.312500,0.655200, +0.158370,0.280594,0.382342,0.000000, 0.317100,0.559600,0.765600, 0.312500,0.689700, +0.080737,0.280594,0.405892,0.000000, 0.161700,0.559600,0.812800, 0.281200,0.689700, +0.169052,0.234204,0.408129,0.000000, 0.338400,0.467000,0.816900, 0.312500,0.655200, +0.080737,0.280594,0.405892,0.000000, 0.161700,0.559600,0.812800, 0.281200,0.689700, +0.086181,0.234204,0.433267,0.000000, 0.172500,0.467000,0.867200, 0.281200,0.655200, +0.098646,-0.428429,0.238155,0.000000, 0.198200,-0.855300,0.478600, 0.312500,0.172400, +0.115795,-0.398046,0.279554,0.000000, 0.232400,-0.794500,0.561100, 0.312500,0.206900, +0.059031,-0.398046,0.296773,0.000000, 0.118500,-0.794500,0.595600, 0.281200,0.206900, +0.098646,-0.428429,0.238155,0.000000, 0.198200,-0.855300,0.478600, 0.312500,0.172400, +0.059031,-0.398046,0.296773,0.000000, 0.118500,-0.794500,0.595600, 0.281200,0.206900, +0.050289,-0.428429,0.252824,0.000000, 0.101000,-0.855300,0.508100, 0.281200,0.172400, +0.177751,0.185069,0.429130,0.000000, 0.355700,0.369000,0.858700, 0.312500,0.620700, +0.169052,0.234204,0.408129,0.000000, 0.338400,0.467000,0.816900, 0.312500,0.655200, +0.086181,0.234204,0.433267,0.000000, 0.172500,0.467000,0.867200, 0.281200,0.655200, +0.177751,0.185069,0.429130,0.000000, 0.355700,0.369000,0.858700, 0.312500,0.620700, +0.086181,0.234204,0.433267,0.000000, 0.172500,0.467000,0.867200, 0.281200,0.655200, +0.090617,0.185069,0.455563,0.000000, 0.181300,0.369000,0.911600, 0.281200,0.620700, +0.080342,-0.453788,0.193963,0.000000, 0.161700,-0.906300,0.390500, 0.312500,0.137900, +0.098646,-0.428429,0.238155,0.000000, 0.198200,-0.855300,0.478600, 0.312500,0.172400, +0.050289,-0.428429,0.252824,0.000000, 0.101000,-0.855300,0.508100, 0.281200,0.172400, +0.080342,-0.453788,0.193963,0.000000, 0.161700,-0.906300,0.390500, 0.312500,0.137900, +0.050289,-0.428429,0.252824,0.000000, 0.101000,-0.855300,0.508100, 0.281200,0.172400, +0.040957,-0.453788,0.205910,0.000000, 0.082400,-0.906300,0.414500, 0.281200,0.137900, +0.184366,0.133764,0.445101,0.000000, 0.368800,0.266600,0.890400, 0.312500,0.586200, +0.177751,0.185069,0.429130,0.000000, 0.355700,0.369000,0.858700, 0.312500,0.620700, +0.090617,0.185069,0.455563,0.000000, 0.181300,0.369000,0.911600, 0.281200,0.620700, +0.184366,0.133764,0.445101,0.000000, 0.368800,0.266600,0.890400, 0.312500,0.586200, +0.090617,0.185069,0.455563,0.000000, 0.181300,0.369000,0.911600, 0.281200,0.620700, +0.093989,0.133764,0.472517,0.000000, 0.188000,0.266600,0.945200, 0.281200,0.586200, +0.061095,-0.473826,0.147498,0.000000, 0.123300,-0.946600,0.297800, 0.312500,0.103400, +0.080342,-0.453788,0.193963,0.000000, 0.161700,-0.906300,0.390500, 0.312500,0.137900, +0.040957,-0.453788,0.205910,0.000000, 0.082400,-0.906300,0.414500, 0.281200,0.137900, +0.061095,-0.473826,0.147498,0.000000, 0.123300,-0.946600,0.297800, 0.312500,0.103400, +0.040957,-0.453788,0.205910,0.000000, 0.082400,-0.906300,0.414500, 0.281200,0.137900, +0.031146,-0.473826,0.156583,0.000000, 0.062900,-0.946600,0.316100, 0.281200,0.103400, +0.188820,0.080891,0.455853,0.000000, 0.377700,0.161200,0.911800, 0.312500,0.551700, +0.184366,0.133764,0.445101,0.000000, 0.368800,0.266600,0.890400, 0.312500,0.586200, +0.093989,0.133764,0.472517,0.000000, 0.188000,0.266600,0.945200, 0.281200,0.586200, +0.188820,0.080891,0.455853,0.000000, 0.377700,0.161200,0.911800, 0.312500,0.551700, +0.093989,0.133764,0.472517,0.000000, 0.188000,0.266600,0.945200, 0.281200,0.586200, +0.096259,0.080891,0.483932,0.000000, 0.192500,0.161200,0.967900, 0.281200,0.551700, +0.041132,-0.488310,0.099303,0.000000, 0.083500,-0.975900,0.201600, 0.312500,0.069000, +0.061095,-0.473826,0.147498,0.000000, 0.123300,-0.946600,0.297800, 0.312500,0.103400, +0.031146,-0.473826,0.156583,0.000000, 0.062900,-0.946600,0.316100, 0.281200,0.103400, +0.041132,-0.488310,0.099303,0.000000, 0.083500,-0.975900,0.201600, 0.312500,0.069000, +0.031146,-0.473826,0.156583,0.000000, 0.062900,-0.946600,0.316100, 0.281200,0.103400, +0.020969,-0.488310,0.105420,0.000000, 0.042500,-0.975900,0.214000, 0.281200,0.069000, +0.191060,0.027069,0.461262,0.000000, 0.382100,0.054000,0.922500, 0.312500,0.517200, +0.188820,0.080891,0.455853,0.000000, 0.377700,0.161200,0.911800, 0.312500,0.551700, +0.096259,0.080891,0.483932,0.000000, 0.192500,0.161200,0.967900, 0.281200,0.551700, +0.191060,0.027069,0.461262,0.000000, 0.382100,0.054000,0.922500, 0.312500,0.517200, +0.096259,0.080891,0.483932,0.000000, 0.192500,0.161200,0.967900, 0.281200,0.551700, +0.097401,0.027069,0.489673,0.000000, 0.194800,0.054000,0.979300, 0.281200,0.517200, +0.020687,0.497069,0.049944,0.000000, 0.042600,0.993700,0.103000, 0.467100,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +0.010546,0.497069,0.053020,0.000000, 0.021700,0.993700,0.109300, 0.468900,0.962300, +0.020687,-0.497069,0.049945,0.000000, 0.042600,-0.993700,0.103000, 0.312500,0.034500, +0.041132,-0.488310,0.099303,0.000000, 0.083500,-0.975900,0.201600, 0.312500,0.069000, +0.020969,-0.488310,0.105420,0.000000, 0.042500,-0.975900,0.214000, 0.281200,0.069000, +0.020687,-0.497069,0.049945,0.000000, 0.042600,-0.993700,0.103000, 0.312500,0.034500, +0.020969,-0.488310,0.105420,0.000000, 0.042500,-0.975900,0.214000, 0.281200,0.069000, +0.010546,-0.497069,0.053020,0.000000, 0.021700,-0.993700,0.109300, 0.281200,0.034500, +0.191060,-0.027069,0.461262,0.000000, 0.382100,-0.054000,0.922500, 0.312500,0.482800, +0.191060,0.027069,0.461262,0.000000, 0.382100,0.054000,0.922500, 0.312500,0.517200, +0.097401,0.027069,0.489673,0.000000, 0.194800,0.054000,0.979300, 0.281200,0.517200, +0.191060,-0.027069,0.461262,0.000000, 0.382100,-0.054000,0.922500, 0.312500,0.482800, +0.097401,0.027069,0.489673,0.000000, 0.194800,0.054000,0.979300, 0.281200,0.517200, +0.097401,-0.027069,0.489673,0.000000, 0.194800,-0.054000,0.979300, 0.281200,0.482800, +0.041132,0.488310,0.099303,0.000000, 0.083500,0.975900,0.201600, 0.312500,0.931000, +0.020687,0.497069,0.049944,0.000000, 0.042600,0.993700,0.103000, 0.312500,0.965500, +0.010546,0.497069,0.053020,0.000000, 0.021700,0.993700,0.109300, 0.281200,0.965500, +0.041132,0.488310,0.099303,0.000000, 0.083500,0.975900,0.201600, 0.312500,0.931000, +0.010546,0.497069,0.053020,0.000000, 0.021700,0.993700,0.109300, 0.281200,0.965500, +0.020969,0.488310,0.105420,0.000000, 0.042500,0.975900,0.214000, 0.281200,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +0.020687,-0.497069,0.049945,0.000000, 0.042600,-0.993700,0.103000, 0.436600,0.053800, +0.010546,-0.497069,0.053020,0.000000, 0.021700,-0.993700,0.109300, 0.434000,0.053800, +0.188820,-0.080891,0.455853,0.000000, 0.377700,-0.161200,0.911800, 0.312500,0.448300, +0.191060,-0.027069,0.461262,0.000000, 0.382100,-0.054000,0.922500, 0.312500,0.482800, +0.097401,-0.027069,0.489673,0.000000, 0.194800,-0.054000,0.979300, 0.281200,0.482800, +0.188820,-0.080891,0.455853,0.000000, 0.377700,-0.161200,0.911800, 0.312500,0.448300, +0.097401,-0.027069,0.489673,0.000000, 0.194800,-0.054000,0.979300, 0.281200,0.482800, +0.096259,-0.080891,0.483932,0.000000, 0.192500,-0.161200,0.967900, 0.281200,0.448300, +0.061095,0.473826,0.147498,0.000000, 0.123300,0.946600,0.297800, 0.312500,0.896600, +0.041132,0.488310,0.099303,0.000000, 0.083500,0.975900,0.201600, 0.312500,0.931000, +0.020969,0.488310,0.105420,0.000000, 0.042500,0.975900,0.214000, 0.281200,0.931000, +0.061095,0.473826,0.147498,0.000000, 0.123300,0.946600,0.297800, 0.312500,0.896600, +0.020969,0.488310,0.105420,0.000000, 0.042500,0.975900,0.214000, 0.281200,0.931000, +0.031146,0.473826,0.156583,0.000000, 0.062900,0.946600,0.316100, 0.281200,0.896600, +0.184366,-0.133764,0.445101,0.000000, 0.368800,-0.266600,0.890400, 0.312500,0.413800, +0.188820,-0.080891,0.455853,0.000000, 0.377700,-0.161200,0.911800, 0.312500,0.448300, +0.096259,-0.080891,0.483932,0.000000, 0.192500,-0.161200,0.967900, 0.281200,0.448300, +0.184366,-0.133764,0.445101,0.000000, 0.368800,-0.266600,0.890400, 0.312500,0.413800, +0.096259,-0.080891,0.483932,0.000000, 0.192500,-0.161200,0.967900, 0.281200,0.448300, +0.093989,-0.133764,0.472517,0.000000, 0.188000,-0.266600,0.945200, 0.281200,0.413800, +0.080342,0.453788,0.193963,0.000000, 0.161700,0.906300,0.390500, 0.312500,0.862100, +0.061095,0.473826,0.147498,0.000000, 0.123300,0.946600,0.297800, 0.312500,0.896600, +0.031146,0.473826,0.156583,0.000000, 0.062900,0.946600,0.316100, 0.281200,0.896600, +0.080342,0.453788,0.193963,0.000000, 0.161700,0.906300,0.390500, 0.312500,0.862100, +0.031146,0.473826,0.156583,0.000000, 0.062900,0.946600,0.316100, 0.281200,0.896600, +0.040957,0.453788,0.205910,0.000000, 0.082400,0.906300,0.414500, 0.281200,0.862100, +0.177751,-0.185069,0.429130,0.000000, 0.355700,-0.369000,0.858700, 0.312500,0.379300, +0.184366,-0.133764,0.445101,0.000000, 0.368800,-0.266600,0.890400, 0.312500,0.413800, +0.093989,-0.133764,0.472517,0.000000, 0.188000,-0.266600,0.945200, 0.281200,0.413800, +0.177751,-0.185069,0.429130,0.000000, 0.355700,-0.369000,0.858700, 0.312500,0.379300, +0.093989,-0.133764,0.472517,0.000000, 0.188000,-0.266600,0.945200, 0.281200,0.413800, +0.090617,-0.185069,0.455563,0.000000, 0.181300,-0.369000,0.911600, 0.281200,0.379300, +0.098646,0.428429,0.238155,0.000000, 0.198200,0.855300,0.478600, 0.312500,0.827600, +0.080342,0.453788,0.193963,0.000000, 0.161700,0.906300,0.390500, 0.312500,0.862100, +0.040957,0.453788,0.205910,0.000000, 0.082400,0.906300,0.414500, 0.281200,0.862100, +0.098646,0.428429,0.238155,0.000000, 0.198200,0.855300,0.478600, 0.312500,0.827600, +0.040957,0.453788,0.205910,0.000000, 0.082400,0.906300,0.414500, 0.281200,0.862100, +0.050289,0.428429,0.252823,0.000000, 0.101000,0.855300,0.508100, 0.281200,0.827600, +0.169052,-0.234204,0.408129,0.000000, 0.338400,-0.467000,0.816900, 0.312500,0.344800, +0.177751,-0.185069,0.429130,0.000000, 0.355700,-0.369000,0.858700, 0.312500,0.379300, +0.090617,-0.185069,0.455563,0.000000, 0.181300,-0.369000,0.911600, 0.281200,0.379300, +0.169052,-0.234204,0.408129,0.000000, 0.338400,-0.467000,0.816900, 0.312500,0.344800, +0.090617,-0.185069,0.455563,0.000000, 0.181300,-0.369000,0.911600, 0.281200,0.379300, +0.086181,-0.234204,0.433267,0.000000, 0.172500,-0.467000,0.867200, 0.281200,0.344800, +0.115795,0.398046,0.279554,0.000000, 0.232400,0.794500,0.561100, 0.312500,0.793100, +0.098646,0.428429,0.238155,0.000000, 0.198200,0.855300,0.478600, 0.312500,0.827600, +0.050289,0.428429,0.252823,0.000000, 0.101000,0.855300,0.508100, 0.281200,0.827600, +0.115795,0.398046,0.279554,0.000000, 0.232400,0.794500,0.561100, 0.312500,0.793100, +0.050289,0.428429,0.252823,0.000000, 0.101000,0.855300,0.508100, 0.281200,0.827600, +0.059032,0.398046,0.296773,0.000000, 0.118500,0.794500,0.595600, 0.281200,0.793100, +0.158370,-0.280594,0.382342,0.000000, 0.317100,-0.559600,0.765600, 0.312500,0.310300, +0.169052,-0.234204,0.408129,0.000000, 0.338400,-0.467000,0.816900, 0.312500,0.344800, +0.086181,-0.234204,0.433267,0.000000, 0.172500,-0.467000,0.867200, 0.281200,0.344800, +0.158370,-0.280594,0.382342,0.000000, 0.317100,-0.559600,0.765600, 0.312500,0.310300, +0.086181,-0.234204,0.433267,0.000000, 0.172500,-0.467000,0.867200, 0.281200,0.344800, +0.080737,-0.280594,0.405892,0.000000, 0.161700,-0.559600,0.812800, 0.281200,0.310300, +0.131585,0.362998,0.317675,0.000000, 0.263800,0.724300,0.637000, 0.312500,0.758600, +0.115795,0.398046,0.279554,0.000000, 0.232400,0.794500,0.561100, 0.312500,0.793100, +0.059032,0.398046,0.296773,0.000000, 0.118500,0.794500,0.595600, 0.281200,0.793100, +0.131585,0.362998,0.317675,0.000000, 0.263800,0.724300,0.637000, 0.312500,0.758600, +0.059032,0.398046,0.296773,0.000000, 0.118500,0.794500,0.595600, 0.281200,0.793100, +0.067081,0.362998,0.337242,0.000000, 0.134500,0.724300,0.676200, 0.281200,0.758600, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +0.010546,-0.497069,0.053020,0.000000, 0.021700,-0.993700,0.109300, 0.434000,0.053800, +-0.000000,-0.497069,0.054060,0.000000, 0.000000,-0.993700,0.111500, 0.431300,0.053800, +0.096259,-0.080891,0.483932,0.000000, 0.192500,-0.161200,0.967900, 0.281200,0.448300, +0.097401,-0.027069,0.489673,0.000000, 0.194800,-0.054000,0.979300, 0.281200,0.482800, +-0.000000,-0.027069,0.499266,0.000000, 0.000000,-0.054000,0.998500, 0.250000,0.482800, +0.096259,-0.080891,0.483932,0.000000, 0.192500,-0.161200,0.967900, 0.281200,0.448300, +-0.000000,-0.027069,0.499266,0.000000, 0.000000,-0.054000,0.998500, 0.250000,0.482800, +-0.000000,-0.080891,0.493412,0.000000, 0.000000,-0.161200,0.986900, 0.250000,0.448300, +0.031146,0.473826,0.156583,0.000000, 0.062900,0.946600,0.316100, 0.281200,0.896600, +0.020969,0.488310,0.105420,0.000000, 0.042500,0.975900,0.214000, 0.281200,0.931000, +-0.000000,0.488310,0.107484,0.000000, 0.000000,0.975900,0.218200, 0.250000,0.931000, +0.031146,0.473826,0.156583,0.000000, 0.062900,0.946600,0.316100, 0.281200,0.896600, +-0.000000,0.488310,0.107484,0.000000, 0.000000,0.975900,0.218200, 0.250000,0.931000, +-0.000000,0.473826,0.159650,0.000000, 0.000000,0.946600,0.322300, 0.250000,0.896600, +0.093989,-0.133764,0.472517,0.000000, 0.188000,-0.266600,0.945200, 0.281200,0.413800, +0.096259,-0.080891,0.483932,0.000000, 0.192500,-0.161200,0.967900, 0.281200,0.448300, +-0.000000,-0.080891,0.493412,0.000000, 0.000000,-0.161200,0.986900, 0.250000,0.448300, +0.093989,-0.133764,0.472517,0.000000, 0.188000,-0.266600,0.945200, 0.281200,0.413800, +-0.000000,-0.080891,0.493412,0.000000, 0.000000,-0.161200,0.986900, 0.250000,0.448300, +-0.000000,-0.133764,0.481775,0.000000, 0.000000,-0.266600,0.963800, 0.250000,0.413800, +0.040957,0.453788,0.205910,0.000000, 0.082400,0.906300,0.414500, 0.281200,0.862100, +0.031146,0.473826,0.156583,0.000000, 0.062900,0.946600,0.316100, 0.281200,0.896600, +-0.000000,0.473826,0.159650,0.000000, 0.000000,0.946600,0.322300, 0.250000,0.896600, +0.040957,0.453788,0.205910,0.000000, 0.082400,0.906300,0.414500, 0.281200,0.862100, +-0.000000,0.473826,0.159650,0.000000, 0.000000,0.946600,0.322300, 0.250000,0.896600, +-0.000000,0.453788,0.209944,0.000000, 0.000000,0.906300,0.422700, 0.250000,0.862100, +0.090617,-0.185069,0.455563,0.000000, 0.181300,-0.369000,0.911600, 0.281200,0.379300, +0.093989,-0.133764,0.472517,0.000000, 0.188000,-0.266600,0.945200, 0.281200,0.413800, +-0.000000,-0.133764,0.481775,0.000000, 0.000000,-0.266600,0.963800, 0.250000,0.413800, +0.090617,-0.185069,0.455563,0.000000, 0.181300,-0.369000,0.911600, 0.281200,0.379300, +-0.000000,-0.133764,0.481775,0.000000, 0.000000,-0.266600,0.963800, 0.250000,0.413800, +-0.000000,-0.185069,0.464487,0.000000, 0.000000,-0.369000,0.929400, 0.250000,0.379300, +0.050289,0.428429,0.252823,0.000000, 0.101000,0.855300,0.508100, 0.281200,0.827600, +0.040957,0.453788,0.205910,0.000000, 0.082400,0.906300,0.414500, 0.281200,0.862100, +-0.000000,0.453788,0.209944,0.000000, 0.000000,0.906300,0.422700, 0.250000,0.862100, +0.050289,0.428429,0.252823,0.000000, 0.101000,0.855300,0.508100, 0.281200,0.827600, +-0.000000,0.453788,0.209944,0.000000, 0.000000,0.906300,0.422700, 0.250000,0.862100, +-0.000000,0.428429,0.257776,0.000000, 0.000000,0.855300,0.518000, 0.250000,0.827600, +0.086181,-0.234204,0.433267,0.000000, 0.172500,-0.467000,0.867200, 0.281200,0.344800, +0.090617,-0.185069,0.455563,0.000000, 0.181300,-0.369000,0.911600, 0.281200,0.379300, +-0.000000,-0.185069,0.464487,0.000000, 0.000000,-0.369000,0.929400, 0.250000,0.379300, +0.086181,-0.234204,0.433267,0.000000, 0.172500,-0.467000,0.867200, 0.281200,0.344800, +-0.000000,-0.185069,0.464487,0.000000, 0.000000,-0.369000,0.929400, 0.250000,0.379300, +-0.000000,-0.234204,0.441756,0.000000, 0.000000,-0.467000,0.884200, 0.250000,0.344800, +0.059032,0.398046,0.296773,0.000000, 0.118500,0.794500,0.595600, 0.281200,0.793100, +0.050289,0.428429,0.252823,0.000000, 0.101000,0.855300,0.508100, 0.281200,0.827600, +-0.000000,0.428429,0.257776,0.000000, 0.000000,0.855300,0.518000, 0.250000,0.827600, +0.059032,0.398046,0.296773,0.000000, 0.118500,0.794500,0.595600, 0.281200,0.793100, +-0.000000,0.428429,0.257776,0.000000, 0.000000,0.855300,0.518000, 0.250000,0.827600, +-0.000000,0.398046,0.302586,0.000000, 0.000000,0.794500,0.607300, 0.250000,0.793100, +0.080737,-0.280594,0.405892,0.000000, 0.161700,-0.559600,0.812800, 0.281200,0.310300, +0.086181,-0.234204,0.433267,0.000000, 0.172500,-0.467000,0.867200, 0.281200,0.344800, +-0.000000,-0.234204,0.441756,0.000000, 0.000000,-0.467000,0.884200, 0.250000,0.344800, +0.080737,-0.280594,0.405892,0.000000, 0.161700,-0.559600,0.812800, 0.281200,0.310300, +-0.000000,-0.234204,0.441756,0.000000, 0.000000,-0.467000,0.884200, 0.250000,0.344800, +-0.000000,-0.280594,0.413844,0.000000, 0.000000,-0.559600,0.828700, 0.250000,0.310300, +0.067081,0.362998,0.337242,0.000000, 0.134500,0.724300,0.676200, 0.281200,0.758600, +0.059032,0.398046,0.296773,0.000000, 0.118500,0.794500,0.595600, 0.281200,0.793100, +-0.000000,0.398046,0.302586,0.000000, 0.000000,0.794500,0.607300, 0.250000,0.793100, +0.067081,0.362998,0.337242,0.000000, 0.134500,0.724300,0.676200, 0.281200,0.758600, +-0.000000,0.398046,0.302586,0.000000, 0.000000,0.794500,0.607300, 0.250000,0.793100, +-0.000000,0.362998,0.343849,0.000000, 0.000000,0.724300,0.689400, 0.250000,0.758600, +0.074345,-0.323693,0.373758,0.000000, 0.149000,-0.645700,0.748900, 0.281200,0.275900, +0.080737,-0.280594,0.405892,0.000000, 0.161700,-0.559600,0.812800, 0.281200,0.310300, +-0.000000,-0.280594,0.413844,0.000000, 0.000000,-0.559600,0.828700, 0.250000,0.310300, +0.074345,-0.323693,0.373758,0.000000, 0.149000,-0.645700,0.748900, 0.281200,0.275900, +-0.000000,-0.280594,0.413844,0.000000, 0.000000,-0.559600,0.828700, 0.250000,0.310300, +-0.000000,-0.323693,0.381081,0.000000, 0.000000,-0.645700,0.763500, 0.250000,0.275900, +0.074345,0.323693,0.373758,0.000000, 0.149000,0.645700,0.748900, 0.281200,0.724100, +0.067081,0.362998,0.337242,0.000000, 0.134500,0.724300,0.676200, 0.281200,0.758600, +-0.000000,0.362998,0.343849,0.000000, 0.000000,0.724300,0.689400, 0.250000,0.758600, +0.074345,0.323693,0.373758,0.000000, 0.149000,0.645700,0.748900, 0.281200,0.724100, +-0.000000,0.362998,0.343849,0.000000, 0.000000,0.724300,0.689400, 0.250000,0.758600, +-0.000000,0.323693,0.381081,0.000000, 0.000000,0.645700,0.763500, 0.250000,0.724100, +0.067081,-0.362998,0.337243,0.000000, 0.134500,-0.724300,0.676200, 0.281200,0.241400, +0.074345,-0.323693,0.373758,0.000000, 0.149000,-0.645700,0.748900, 0.281200,0.275900, +-0.000000,-0.323693,0.381081,0.000000, 0.000000,-0.645700,0.763500, 0.250000,0.275900, +0.067081,-0.362998,0.337243,0.000000, 0.134500,-0.724300,0.676200, 0.281200,0.241400, +-0.000000,-0.323693,0.381081,0.000000, 0.000000,-0.645700,0.763500, 0.250000,0.275900, +-0.000000,-0.362998,0.343849,0.000000, 0.000000,-0.724300,0.689500, 0.250000,0.241400, +0.080737,0.280594,0.405892,0.000000, 0.161700,0.559600,0.812800, 0.281200,0.689700, +0.074345,0.323693,0.373758,0.000000, 0.149000,0.645700,0.748900, 0.281200,0.724100, +-0.000000,0.323693,0.381081,0.000000, 0.000000,0.645700,0.763500, 0.250000,0.724100, +0.080737,0.280594,0.405892,0.000000, 0.161700,0.559600,0.812800, 0.281200,0.689700, +-0.000000,0.323693,0.381081,0.000000, 0.000000,0.645700,0.763500, 0.250000,0.724100, +-0.000000,0.280594,0.413844,0.000000, 0.000000,0.559600,0.828700, 0.250000,0.689700, +0.059031,-0.398046,0.296773,0.000000, 0.118500,-0.794500,0.595600, 0.281200,0.206900, +0.067081,-0.362998,0.337243,0.000000, 0.134500,-0.724300,0.676200, 0.281200,0.241400, +-0.000000,-0.362998,0.343849,0.000000, 0.000000,-0.724300,0.689500, 0.250000,0.241400, +0.059031,-0.398046,0.296773,0.000000, 0.118500,-0.794500,0.595600, 0.281200,0.206900, +-0.000000,-0.362998,0.343849,0.000000, 0.000000,-0.724300,0.689500, 0.250000,0.241400, +-0.000000,-0.398046,0.302586,0.000000, 0.000000,-0.794500,0.607300, 0.250000,0.206900, +0.086181,0.234204,0.433267,0.000000, 0.172500,0.467000,0.867200, 0.281200,0.655200, +0.080737,0.280594,0.405892,0.000000, 0.161700,0.559600,0.812800, 0.281200,0.689700, +-0.000000,0.280594,0.413844,0.000000, 0.000000,0.559600,0.828700, 0.250000,0.689700, +0.086181,0.234204,0.433267,0.000000, 0.172500,0.467000,0.867200, 0.281200,0.655200, +-0.000000,0.280594,0.413844,0.000000, 0.000000,0.559600,0.828700, 0.250000,0.689700, +-0.000000,0.234204,0.441756,0.000000, 0.000000,0.467000,0.884200, 0.250000,0.655200, +0.050289,-0.428429,0.252824,0.000000, 0.101000,-0.855300,0.508100, 0.281200,0.172400, +0.059031,-0.398046,0.296773,0.000000, 0.118500,-0.794500,0.595600, 0.281200,0.206900, +-0.000000,-0.398046,0.302586,0.000000, 0.000000,-0.794500,0.607300, 0.250000,0.206900, +0.050289,-0.428429,0.252824,0.000000, 0.101000,-0.855300,0.508100, 0.281200,0.172400, +-0.000000,-0.398046,0.302586,0.000000, 0.000000,-0.794500,0.607300, 0.250000,0.206900, +-0.000000,-0.428429,0.257776,0.000000, 0.000000,-0.855300,0.518000, 0.250000,0.172400, +0.090617,0.185069,0.455563,0.000000, 0.181300,0.369000,0.911600, 0.281200,0.620700, +0.086181,0.234204,0.433267,0.000000, 0.172500,0.467000,0.867200, 0.281200,0.655200, +-0.000000,0.234204,0.441756,0.000000, 0.000000,0.467000,0.884200, 0.250000,0.655200, +0.090617,0.185069,0.455563,0.000000, 0.181300,0.369000,0.911600, 0.281200,0.620700, +-0.000000,0.234204,0.441756,0.000000, 0.000000,0.467000,0.884200, 0.250000,0.655200, +-0.000000,0.185069,0.464487,0.000000, 0.000000,0.369000,0.929400, 0.250000,0.620700, +0.040957,-0.453788,0.205910,0.000000, 0.082400,-0.906300,0.414500, 0.281200,0.137900, +0.050289,-0.428429,0.252824,0.000000, 0.101000,-0.855300,0.508100, 0.281200,0.172400, +-0.000000,-0.428429,0.257776,0.000000, 0.000000,-0.855300,0.518000, 0.250000,0.172400, +0.040957,-0.453788,0.205910,0.000000, 0.082400,-0.906300,0.414500, 0.281200,0.137900, +-0.000000,-0.428429,0.257776,0.000000, 0.000000,-0.855300,0.518000, 0.250000,0.172400, +-0.000000,-0.453788,0.209944,0.000000, 0.000000,-0.906300,0.422700, 0.250000,0.137900, +0.093989,0.133764,0.472517,0.000000, 0.188000,0.266600,0.945200, 0.281200,0.586200, +0.090617,0.185069,0.455563,0.000000, 0.181300,0.369000,0.911600, 0.281200,0.620700, +-0.000000,0.185069,0.464487,0.000000, 0.000000,0.369000,0.929400, 0.250000,0.620700, +0.093989,0.133764,0.472517,0.000000, 0.188000,0.266600,0.945200, 0.281200,0.586200, +-0.000000,0.185069,0.464487,0.000000, 0.000000,0.369000,0.929400, 0.250000,0.620700, +-0.000000,0.133764,0.481775,0.000000, 0.000000,0.266600,0.963800, 0.250000,0.586200, +0.031146,-0.473826,0.156583,0.000000, 0.062900,-0.946600,0.316100, 0.281200,0.103400, +0.040957,-0.453788,0.205910,0.000000, 0.082400,-0.906300,0.414500, 0.281200,0.137900, +-0.000000,-0.453788,0.209944,0.000000, 0.000000,-0.906300,0.422700, 0.250000,0.137900, +0.031146,-0.473826,0.156583,0.000000, 0.062900,-0.946600,0.316100, 0.281200,0.103400, +-0.000000,-0.453788,0.209944,0.000000, 0.000000,-0.906300,0.422700, 0.250000,0.137900, +-0.000000,-0.473826,0.159651,0.000000, 0.000000,-0.946600,0.322300, 0.250000,0.103400, +0.096259,0.080891,0.483932,0.000000, 0.192500,0.161200,0.967900, 0.281200,0.551700, +0.093989,0.133764,0.472517,0.000000, 0.188000,0.266600,0.945200, 0.281200,0.586200, +-0.000000,0.133764,0.481775,0.000000, 0.000000,0.266600,0.963800, 0.250000,0.586200, +0.096259,0.080891,0.483932,0.000000, 0.192500,0.161200,0.967900, 0.281200,0.551700, +-0.000000,0.133764,0.481775,0.000000, 0.000000,0.266600,0.963800, 0.250000,0.586200, +-0.000000,0.080891,0.493412,0.000000, 0.000000,0.161200,0.986900, 0.250000,0.551700, +0.020969,-0.488310,0.105420,0.000000, 0.042500,-0.975900,0.214000, 0.281200,0.069000, +0.031146,-0.473826,0.156583,0.000000, 0.062900,-0.946600,0.316100, 0.281200,0.103400, +-0.000000,-0.473826,0.159651,0.000000, 0.000000,-0.946600,0.322300, 0.250000,0.103400, +0.020969,-0.488310,0.105420,0.000000, 0.042500,-0.975900,0.214000, 0.281200,0.069000, +-0.000000,-0.473826,0.159651,0.000000, 0.000000,-0.946600,0.322300, 0.250000,0.103400, +-0.000000,-0.488310,0.107485,0.000000, 0.000000,-0.975900,0.218200, 0.250000,0.069000, +0.097401,0.027069,0.489673,0.000000, 0.194800,0.054000,0.979300, 0.281200,0.517200, +0.096259,0.080891,0.483932,0.000000, 0.192500,0.161200,0.967900, 0.281200,0.551700, +-0.000000,0.080891,0.493412,0.000000, 0.000000,0.161200,0.986900, 0.250000,0.551700, +0.097401,0.027069,0.489673,0.000000, 0.194800,0.054000,0.979300, 0.281200,0.517200, +-0.000000,0.080891,0.493412,0.000000, 0.000000,0.161200,0.986900, 0.250000,0.551700, +-0.000000,0.027069,0.499266,0.000000, 0.000000,0.054000,0.998500, 0.250000,0.517200, +0.010546,0.497069,0.053020,0.000000, 0.021700,0.993700,0.109300, 0.468900,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +-0.000000,0.497069,0.054059,0.000000, 0.000000,0.993700,0.111500, 0.470800,0.962300, +0.010546,-0.497069,0.053020,0.000000, 0.021700,-0.993700,0.109300, 0.281200,0.034500, +0.020969,-0.488310,0.105420,0.000000, 0.042500,-0.975900,0.214000, 0.281200,0.069000, +-0.000000,-0.488310,0.107485,0.000000, 0.000000,-0.975900,0.218200, 0.250000,0.069000, +0.010546,-0.497069,0.053020,0.000000, 0.021700,-0.993700,0.109300, 0.281200,0.034500, +-0.000000,-0.488310,0.107485,0.000000, 0.000000,-0.975900,0.218200, 0.250000,0.069000, +-0.000000,-0.497069,0.054060,0.000000, 0.000000,-0.993700,0.111500, 0.250000,0.034500, +0.097401,-0.027069,0.489673,0.000000, 0.194800,-0.054000,0.979300, 0.281200,0.482800, +0.097401,0.027069,0.489673,0.000000, 0.194800,0.054000,0.979300, 0.281200,0.517200, +-0.000000,0.027069,0.499266,0.000000, 0.000000,0.054000,0.998500, 0.250000,0.517200, +0.097401,-0.027069,0.489673,0.000000, 0.194800,-0.054000,0.979300, 0.281200,0.482800, +-0.000000,0.027069,0.499266,0.000000, 0.000000,0.054000,0.998500, 0.250000,0.517200, +-0.000000,-0.027069,0.499266,0.000000, 0.000000,-0.054000,0.998500, 0.250000,0.482800, +0.020969,0.488310,0.105420,0.000000, 0.042500,0.975900,0.214000, 0.281200,0.931000, +0.010546,0.497069,0.053020,0.000000, 0.021700,0.993700,0.109300, 0.281200,0.965500, +-0.000000,0.497069,0.054059,0.000000, 0.000000,0.993700,0.111500, 0.250000,0.965500, +0.020969,0.488310,0.105420,0.000000, 0.042500,0.975900,0.214000, 0.281200,0.931000, +-0.000000,0.497069,0.054059,0.000000, 0.000000,0.993700,0.111500, 0.250000,0.965500, +-0.000000,0.488310,0.107484,0.000000, 0.000000,0.975900,0.218200, 0.250000,0.931000, +-0.000000,-0.428429,0.257776,0.000000, 0.000000,-0.855300,0.518000, 0.250000,0.172400, +-0.000000,-0.398046,0.302586,0.000000, 0.000000,-0.794500,0.607300, 0.250000,0.206900, +-0.059032,-0.398046,0.296773,0.000000, -0.118500,-0.794500,0.595600, 0.218700,0.206900, +-0.000000,-0.428429,0.257776,0.000000, 0.000000,-0.855300,0.518000, 0.250000,0.172400, +-0.059032,-0.398046,0.296773,0.000000, -0.118500,-0.794500,0.595600, 0.218700,0.206900, +-0.050290,-0.428429,0.252824,0.000000, -0.101000,-0.855300,0.508100, 0.218700,0.172400, +-0.000000,0.185069,0.464487,0.000000, 0.000000,0.369000,0.929400, 0.250000,0.620700, +-0.000000,0.234204,0.441756,0.000000, 0.000000,0.467000,0.884200, 0.250000,0.655200, +-0.086182,0.234204,0.433267,0.000000, -0.172500,0.467000,0.867200, 0.218700,0.655200, +-0.000000,0.185069,0.464487,0.000000, 0.000000,0.369000,0.929400, 0.250000,0.620700, +-0.086182,0.234204,0.433267,0.000000, -0.172500,0.467000,0.867200, 0.218700,0.655200, +-0.090618,0.185069,0.455563,0.000000, -0.181300,0.369000,0.911600, 0.218700,0.620700, +-0.000000,-0.453788,0.209944,0.000000, 0.000000,-0.906300,0.422700, 0.250000,0.137900, +-0.000000,-0.428429,0.257776,0.000000, 0.000000,-0.855300,0.518000, 0.250000,0.172400, +-0.050290,-0.428429,0.252824,0.000000, -0.101000,-0.855300,0.508100, 0.218700,0.172400, +-0.000000,-0.453788,0.209944,0.000000, 0.000000,-0.906300,0.422700, 0.250000,0.137900, +-0.050290,-0.428429,0.252824,0.000000, -0.101000,-0.855300,0.508100, 0.218700,0.172400, +-0.040959,-0.453788,0.205910,0.000000, -0.082400,-0.906300,0.414500, 0.218700,0.137900, +-0.000000,0.133764,0.481775,0.000000, 0.000000,0.266600,0.963800, 0.250000,0.586200, +-0.000000,0.185069,0.464487,0.000000, 0.000000,0.369000,0.929400, 0.250000,0.620700, +-0.090618,0.185069,0.455563,0.000000, -0.181300,0.369000,0.911600, 0.218700,0.620700, +-0.000000,0.133764,0.481775,0.000000, 0.000000,0.266600,0.963800, 0.250000,0.586200, +-0.090618,0.185069,0.455563,0.000000, -0.181300,0.369000,0.911600, 0.218700,0.620700, +-0.093990,0.133764,0.472517,0.000000, -0.188000,0.266600,0.945200, 0.218700,0.586200, +-0.000000,-0.473826,0.159651,0.000000, 0.000000,-0.946600,0.322300, 0.250000,0.103400, +-0.000000,-0.453788,0.209944,0.000000, 0.000000,-0.906300,0.422700, 0.250000,0.137900, +-0.040959,-0.453788,0.205910,0.000000, -0.082400,-0.906300,0.414500, 0.218700,0.137900, +-0.000000,-0.473826,0.159651,0.000000, 0.000000,-0.946600,0.322300, 0.250000,0.103400, +-0.040959,-0.453788,0.205910,0.000000, -0.082400,-0.906300,0.414500, 0.218700,0.137900, +-0.031147,-0.473826,0.156583,0.000000, -0.062900,-0.946600,0.316100, 0.218700,0.103400, +-0.000000,0.080891,0.493412,0.000000, 0.000000,0.161200,0.986900, 0.250000,0.551700, +-0.000000,0.133764,0.481775,0.000000, 0.000000,0.266600,0.963800, 0.250000,0.586200, +-0.093990,0.133764,0.472517,0.000000, -0.188000,0.266600,0.945200, 0.218700,0.586200, +-0.000000,0.080891,0.493412,0.000000, 0.000000,0.161200,0.986900, 0.250000,0.551700, +-0.093990,0.133764,0.472517,0.000000, -0.188000,0.266600,0.945200, 0.218700,0.586200, +-0.096261,0.080891,0.483932,0.000000, -0.192500,0.161200,0.967900, 0.218700,0.551700, +-0.000000,-0.488310,0.107485,0.000000, 0.000000,-0.975900,0.218200, 0.250000,0.069000, +-0.000000,-0.473826,0.159651,0.000000, 0.000000,-0.946600,0.322300, 0.250000,0.103400, +-0.031147,-0.473826,0.156583,0.000000, -0.062900,-0.946600,0.316100, 0.218700,0.103400, +-0.000000,-0.488310,0.107485,0.000000, 0.000000,-0.975900,0.218200, 0.250000,0.069000, +-0.031147,-0.473826,0.156583,0.000000, -0.062900,-0.946600,0.316100, 0.218700,0.103400, +-0.020970,-0.488310,0.105420,0.000000, -0.042500,-0.975900,0.214000, 0.218700,0.069000, +-0.000000,0.027069,0.499266,0.000000, 0.000000,0.054000,0.998500, 0.250000,0.517200, +-0.000000,0.080891,0.493412,0.000000, 0.000000,0.161200,0.986900, 0.250000,0.551700, +-0.096261,0.080891,0.483932,0.000000, -0.192500,0.161200,0.967900, 0.218700,0.551700, +-0.000000,0.027069,0.499266,0.000000, 0.000000,0.054000,0.998500, 0.250000,0.517200, +-0.096261,0.080891,0.483932,0.000000, -0.192500,0.161200,0.967900, 0.218700,0.551700, +-0.097402,0.027069,0.489673,0.000000, -0.194800,0.054000,0.979300, 0.218700,0.517200, +-0.000000,0.497069,0.054059,0.000000, 0.000000,0.993700,0.111500, 0.470800,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +-0.010547,0.497069,0.053020,0.000000, -0.021700,0.993700,0.109300, 0.472600,0.962300, +-0.000000,-0.497069,0.054060,0.000000, 0.000000,-0.993700,0.111500, 0.250000,0.034500, +-0.000000,-0.488310,0.107485,0.000000, 0.000000,-0.975900,0.218200, 0.250000,0.069000, +-0.020970,-0.488310,0.105420,0.000000, -0.042500,-0.975900,0.214000, 0.218700,0.069000, +-0.000000,-0.497069,0.054060,0.000000, 0.000000,-0.993700,0.111500, 0.250000,0.034500, +-0.020970,-0.488310,0.105420,0.000000, -0.042500,-0.975900,0.214000, 0.218700,0.069000, +-0.010547,-0.497069,0.053020,0.000000, -0.021700,-0.993700,0.109300, 0.218700,0.034500, +-0.000000,-0.027069,0.499266,0.000000, 0.000000,-0.054000,0.998500, 0.250000,0.482800, +-0.000000,0.027069,0.499266,0.000000, 0.000000,0.054000,0.998500, 0.250000,0.517200, +-0.097402,0.027069,0.489673,0.000000, -0.194800,0.054000,0.979300, 0.218700,0.517200, +-0.000000,-0.027069,0.499266,0.000000, 0.000000,-0.054000,0.998500, 0.250000,0.482800, +-0.097402,0.027069,0.489673,0.000000, -0.194800,0.054000,0.979300, 0.218700,0.517200, +-0.097402,-0.027069,0.489673,0.000000, -0.194800,-0.054000,0.979300, 0.218700,0.482800, +-0.000000,0.488310,0.107484,0.000000, 0.000000,0.975900,0.218200, 0.250000,0.931000, +-0.000000,0.497069,0.054059,0.000000, 0.000000,0.993700,0.111500, 0.250000,0.965500, +-0.010547,0.497069,0.053020,0.000000, -0.021700,0.993700,0.109300, 0.218700,0.965500, +-0.000000,0.488310,0.107484,0.000000, 0.000000,0.975900,0.218200, 0.250000,0.931000, +-0.010547,0.497069,0.053020,0.000000, -0.021700,0.993700,0.109300, 0.218700,0.965500, +-0.020970,0.488310,0.105420,0.000000, -0.042500,0.975900,0.214000, 0.218700,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +-0.000000,-0.497069,0.054060,0.000000, 0.000000,-0.993700,0.111500, 0.431300,0.053800, +-0.010547,-0.497069,0.053020,0.000000, -0.021700,-0.993700,0.109300, 0.428700,0.053800, +-0.000000,-0.080891,0.493412,0.000000, 0.000000,-0.161200,0.986900, 0.250000,0.448300, +-0.000000,-0.027069,0.499266,0.000000, 0.000000,-0.054000,0.998500, 0.250000,0.482800, +-0.097402,-0.027069,0.489673,0.000000, -0.194800,-0.054000,0.979300, 0.218700,0.482800, +-0.000000,-0.080891,0.493412,0.000000, 0.000000,-0.161200,0.986900, 0.250000,0.448300, +-0.097402,-0.027069,0.489673,0.000000, -0.194800,-0.054000,0.979300, 0.218700,0.482800, +-0.096261,-0.080891,0.483932,0.000000, -0.192500,-0.161200,0.967900, 0.218700,0.448300, +-0.000000,0.473826,0.159650,0.000000, 0.000000,0.946600,0.322300, 0.250000,0.896600, +-0.000000,0.488310,0.107484,0.000000, 0.000000,0.975900,0.218200, 0.250000,0.931000, +-0.020970,0.488310,0.105420,0.000000, -0.042500,0.975900,0.214000, 0.218700,0.931000, +-0.000000,0.473826,0.159650,0.000000, 0.000000,0.946600,0.322300, 0.250000,0.896600, +-0.020970,0.488310,0.105420,0.000000, -0.042500,0.975900,0.214000, 0.218700,0.931000, +-0.031147,0.473826,0.156583,0.000000, -0.062900,0.946600,0.316100, 0.218700,0.896600, +-0.000000,-0.133764,0.481775,0.000000, 0.000000,-0.266600,0.963800, 0.250000,0.413800, +-0.000000,-0.080891,0.493412,0.000000, 0.000000,-0.161200,0.986900, 0.250000,0.448300, +-0.096261,-0.080891,0.483932,0.000000, -0.192500,-0.161200,0.967900, 0.218700,0.448300, +-0.000000,-0.133764,0.481775,0.000000, 0.000000,-0.266600,0.963800, 0.250000,0.413800, +-0.096261,-0.080891,0.483932,0.000000, -0.192500,-0.161200,0.967900, 0.218700,0.448300, +-0.093990,-0.133764,0.472517,0.000000, -0.188000,-0.266600,0.945200, 0.218700,0.413800, +-0.000000,0.453788,0.209944,0.000000, 0.000000,0.906300,0.422700, 0.250000,0.862100, +-0.000000,0.473826,0.159650,0.000000, 0.000000,0.946600,0.322300, 0.250000,0.896600, +-0.031147,0.473826,0.156583,0.000000, -0.062900,0.946600,0.316100, 0.218700,0.896600, +-0.000000,0.453788,0.209944,0.000000, 0.000000,0.906300,0.422700, 0.250000,0.862100, +-0.031147,0.473826,0.156583,0.000000, -0.062900,0.946600,0.316100, 0.218700,0.896600, +-0.040959,0.453788,0.205910,0.000000, -0.082400,0.906300,0.414500, 0.218700,0.862100, +-0.000000,-0.185069,0.464487,0.000000, 0.000000,-0.369000,0.929400, 0.250000,0.379300, +-0.000000,-0.133764,0.481775,0.000000, 0.000000,-0.266600,0.963800, 0.250000,0.413800, +-0.093990,-0.133764,0.472517,0.000000, -0.188000,-0.266600,0.945200, 0.218700,0.413800, +-0.000000,-0.185069,0.464487,0.000000, 0.000000,-0.369000,0.929400, 0.250000,0.379300, +-0.093990,-0.133764,0.472517,0.000000, -0.188000,-0.266600,0.945200, 0.218700,0.413800, +-0.090618,-0.185069,0.455563,0.000000, -0.181300,-0.369000,0.911600, 0.218700,0.379300, +-0.000000,0.428429,0.257776,0.000000, 0.000000,0.855300,0.518000, 0.250000,0.827600, +-0.000000,0.453788,0.209944,0.000000, 0.000000,0.906300,0.422700, 0.250000,0.862100, +-0.040959,0.453788,0.205910,0.000000, -0.082400,0.906300,0.414500, 0.218700,0.862100, +-0.000000,0.428429,0.257776,0.000000, 0.000000,0.855300,0.518000, 0.250000,0.827600, +-0.040959,0.453788,0.205910,0.000000, -0.082400,0.906300,0.414500, 0.218700,0.862100, +-0.050290,0.428429,0.252823,0.000000, -0.101000,0.855300,0.508100, 0.218700,0.827600, +-0.000000,-0.234204,0.441756,0.000000, 0.000000,-0.467000,0.884200, 0.250000,0.344800, +-0.000000,-0.185069,0.464487,0.000000, 0.000000,-0.369000,0.929400, 0.250000,0.379300, +-0.090618,-0.185069,0.455563,0.000000, -0.181300,-0.369000,0.911600, 0.218700,0.379300, +-0.000000,-0.234204,0.441756,0.000000, 0.000000,-0.467000,0.884200, 0.250000,0.344800, +-0.090618,-0.185069,0.455563,0.000000, -0.181300,-0.369000,0.911600, 0.218700,0.379300, +-0.086182,-0.234204,0.433267,0.000000, -0.172500,-0.467000,0.867200, 0.218700,0.344800, +-0.000000,0.398046,0.302586,0.000000, 0.000000,0.794500,0.607300, 0.250000,0.793100, +-0.000000,0.428429,0.257776,0.000000, 0.000000,0.855300,0.518000, 0.250000,0.827600, +-0.050290,0.428429,0.252823,0.000000, -0.101000,0.855300,0.508100, 0.218700,0.827600, +-0.000000,0.398046,0.302586,0.000000, 0.000000,0.794500,0.607300, 0.250000,0.793100, +-0.050290,0.428429,0.252823,0.000000, -0.101000,0.855300,0.508100, 0.218700,0.827600, +-0.059032,0.398046,0.296773,0.000000, -0.118500,0.794500,0.595600, 0.218700,0.793100, +-0.000000,-0.280594,0.413844,0.000000, 0.000000,-0.559600,0.828700, 0.250000,0.310300, +-0.000000,-0.234204,0.441756,0.000000, 0.000000,-0.467000,0.884200, 0.250000,0.344800, +-0.086182,-0.234204,0.433267,0.000000, -0.172500,-0.467000,0.867200, 0.218700,0.344800, +-0.000000,-0.280594,0.413844,0.000000, 0.000000,-0.559600,0.828700, 0.250000,0.310300, +-0.086182,-0.234204,0.433267,0.000000, -0.172500,-0.467000,0.867200, 0.218700,0.344800, +-0.080738,-0.280594,0.405892,0.000000, -0.161700,-0.559600,0.812800, 0.218700,0.310300, +-0.000000,0.362998,0.343849,0.000000, 0.000000,0.724300,0.689400, 0.250000,0.758600, +-0.000000,0.398046,0.302586,0.000000, 0.000000,0.794500,0.607300, 0.250000,0.793100, +-0.059032,0.398046,0.296773,0.000000, -0.118500,0.794500,0.595600, 0.218700,0.793100, +-0.000000,0.362998,0.343849,0.000000, 0.000000,0.724300,0.689400, 0.250000,0.758600, +-0.059032,0.398046,0.296773,0.000000, -0.118500,0.794500,0.595600, 0.218700,0.793100, +-0.067082,0.362998,0.337242,0.000000, -0.134500,0.724300,0.676200, 0.218700,0.758600, +-0.000000,-0.323693,0.381081,0.000000, 0.000000,-0.645700,0.763500, 0.250000,0.275900, +-0.000000,-0.280594,0.413844,0.000000, 0.000000,-0.559600,0.828700, 0.250000,0.310300, +-0.080738,-0.280594,0.405892,0.000000, -0.161700,-0.559600,0.812800, 0.218700,0.310300, +-0.000000,-0.323693,0.381081,0.000000, 0.000000,-0.645700,0.763500, 0.250000,0.275900, +-0.080738,-0.280594,0.405892,0.000000, -0.161700,-0.559600,0.812800, 0.218700,0.310300, +-0.074345,-0.323693,0.373758,0.000000, -0.149000,-0.645700,0.748900, 0.218700,0.275900, +-0.000000,0.323693,0.381081,0.000000, 0.000000,0.645700,0.763500, 0.250000,0.724100, +-0.000000,0.362998,0.343849,0.000000, 0.000000,0.724300,0.689400, 0.250000,0.758600, +-0.067082,0.362998,0.337242,0.000000, -0.134500,0.724300,0.676200, 0.218700,0.758600, +-0.000000,0.323693,0.381081,0.000000, 0.000000,0.645700,0.763500, 0.250000,0.724100, +-0.067082,0.362998,0.337242,0.000000, -0.134500,0.724300,0.676200, 0.218700,0.758600, +-0.074345,0.323693,0.373758,0.000000, -0.149000,0.645700,0.748900, 0.218700,0.724100, +-0.000000,-0.362998,0.343849,0.000000, 0.000000,-0.724300,0.689500, 0.250000,0.241400, +-0.000000,-0.323693,0.381081,0.000000, 0.000000,-0.645700,0.763500, 0.250000,0.275900, +-0.074345,-0.323693,0.373758,0.000000, -0.149000,-0.645700,0.748900, 0.218700,0.275900, +-0.000000,-0.362998,0.343849,0.000000, 0.000000,-0.724300,0.689500, 0.250000,0.241400, +-0.074345,-0.323693,0.373758,0.000000, -0.149000,-0.645700,0.748900, 0.218700,0.275900, +-0.067082,-0.362998,0.337242,0.000000, -0.134500,-0.724300,0.676200, 0.218700,0.241400, +-0.000000,0.280594,0.413844,0.000000, 0.000000,0.559600,0.828700, 0.250000,0.689700, +-0.000000,0.323693,0.381081,0.000000, 0.000000,0.645700,0.763500, 0.250000,0.724100, +-0.074345,0.323693,0.373758,0.000000, -0.149000,0.645700,0.748900, 0.218700,0.724100, +-0.000000,0.280594,0.413844,0.000000, 0.000000,0.559600,0.828700, 0.250000,0.689700, +-0.074345,0.323693,0.373758,0.000000, -0.149000,0.645700,0.748900, 0.218700,0.724100, +-0.080738,0.280594,0.405892,0.000000, -0.161700,0.559600,0.812800, 0.218700,0.689700, +-0.000000,-0.398046,0.302586,0.000000, 0.000000,-0.794500,0.607300, 0.250000,0.206900, +-0.000000,-0.362998,0.343849,0.000000, 0.000000,-0.724300,0.689500, 0.250000,0.241400, +-0.067082,-0.362998,0.337242,0.000000, -0.134500,-0.724300,0.676200, 0.218700,0.241400, +-0.000000,-0.398046,0.302586,0.000000, 0.000000,-0.794500,0.607300, 0.250000,0.206900, +-0.067082,-0.362998,0.337242,0.000000, -0.134500,-0.724300,0.676200, 0.218700,0.241400, +-0.059032,-0.398046,0.296773,0.000000, -0.118500,-0.794500,0.595600, 0.218700,0.206900, +-0.000000,0.234204,0.441756,0.000000, 0.000000,0.467000,0.884200, 0.250000,0.655200, +-0.000000,0.280594,0.413844,0.000000, 0.000000,0.559600,0.828700, 0.250000,0.689700, +-0.080738,0.280594,0.405892,0.000000, -0.161700,0.559600,0.812800, 0.218700,0.689700, +-0.000000,0.234204,0.441756,0.000000, 0.000000,0.467000,0.884200, 0.250000,0.655200, +-0.080738,0.280594,0.405892,0.000000, -0.161700,0.559600,0.812800, 0.218700,0.689700, +-0.086182,0.234204,0.433267,0.000000, -0.172500,0.467000,0.867200, 0.218700,0.655200, +-0.050290,0.428429,0.252823,0.000000, -0.101000,0.855300,0.508100, 0.218700,0.827600, +-0.040959,0.453788,0.205910,0.000000, -0.082400,0.906300,0.414500, 0.218700,0.862100, +-0.080343,0.453788,0.193963,0.000000, -0.161700,0.906300,0.390500, 0.187500,0.862100, +-0.050290,0.428429,0.252823,0.000000, -0.101000,0.855300,0.508100, 0.218700,0.827600, +-0.080343,0.453788,0.193963,0.000000, -0.161700,0.906300,0.390500, 0.187500,0.862100, +-0.098647,0.428429,0.238154,0.000000, -0.198200,0.855300,0.478600, 0.187500,0.827600, +-0.086182,-0.234204,0.433267,0.000000, -0.172500,-0.467000,0.867200, 0.218700,0.344800, +-0.090618,-0.185069,0.455563,0.000000, -0.181300,-0.369000,0.911600, 0.218700,0.379300, +-0.177752,-0.185069,0.429130,0.000000, -0.355700,-0.369000,0.858700, 0.187500,0.379300, +-0.086182,-0.234204,0.433267,0.000000, -0.172500,-0.467000,0.867200, 0.218700,0.344800, +-0.177752,-0.185069,0.429130,0.000000, -0.355700,-0.369000,0.858700, 0.187500,0.379300, +-0.169053,-0.234204,0.408128,0.000000, -0.338400,-0.467000,0.816900, 0.187500,0.344800, +-0.059032,0.398046,0.296773,0.000000, -0.118500,0.794500,0.595600, 0.218700,0.793100, +-0.050290,0.428429,0.252823,0.000000, -0.101000,0.855300,0.508100, 0.218700,0.827600, +-0.098647,0.428429,0.238154,0.000000, -0.198200,0.855300,0.478600, 0.187500,0.827600, +-0.059032,0.398046,0.296773,0.000000, -0.118500,0.794500,0.595600, 0.218700,0.793100, +-0.098647,0.428429,0.238154,0.000000, -0.198200,0.855300,0.478600, 0.187500,0.827600, +-0.115796,0.398046,0.279554,0.000000, -0.232400,0.794500,0.561100, 0.187500,0.793100, +-0.080738,-0.280594,0.405892,0.000000, -0.161700,-0.559600,0.812800, 0.218700,0.310300, +-0.086182,-0.234204,0.433267,0.000000, -0.172500,-0.467000,0.867200, 0.218700,0.344800, +-0.169053,-0.234204,0.408128,0.000000, -0.338400,-0.467000,0.816900, 0.187500,0.344800, +-0.080738,-0.280594,0.405892,0.000000, -0.161700,-0.559600,0.812800, 0.218700,0.310300, +-0.169053,-0.234204,0.408128,0.000000, -0.338400,-0.467000,0.816900, 0.187500,0.344800, +-0.158371,-0.280594,0.382342,0.000000, -0.317100,-0.559600,0.765600, 0.187500,0.310300, +-0.067082,0.362998,0.337242,0.000000, -0.134500,0.724300,0.676200, 0.218700,0.758600, +-0.059032,0.398046,0.296773,0.000000, -0.118500,0.794500,0.595600, 0.218700,0.793100, +-0.115796,0.398046,0.279554,0.000000, -0.232400,0.794500,0.561100, 0.187500,0.793100, +-0.067082,0.362998,0.337242,0.000000, -0.134500,0.724300,0.676200, 0.218700,0.758600, +-0.115796,0.398046,0.279554,0.000000, -0.232400,0.794500,0.561100, 0.187500,0.793100, +-0.131586,0.362998,0.317675,0.000000, -0.263800,0.724300,0.637000, 0.187500,0.758600, +-0.074345,-0.323693,0.373758,0.000000, -0.149000,-0.645700,0.748900, 0.218700,0.275900, +-0.080738,-0.280594,0.405892,0.000000, -0.161700,-0.559600,0.812800, 0.218700,0.310300, +-0.158371,-0.280594,0.382342,0.000000, -0.317100,-0.559600,0.765600, 0.187500,0.310300, +-0.074345,-0.323693,0.373758,0.000000, -0.149000,-0.645700,0.748900, 0.218700,0.275900, +-0.158371,-0.280594,0.382342,0.000000, -0.317100,-0.559600,0.765600, 0.187500,0.310300, +-0.145834,-0.323693,0.352073,0.000000, -0.292200,-0.645700,0.705400, 0.187500,0.275900, +-0.074345,0.323693,0.373758,0.000000, -0.149000,0.645700,0.748900, 0.218700,0.724100, +-0.067082,0.362998,0.337242,0.000000, -0.134500,0.724300,0.676200, 0.218700,0.758600, +-0.131586,0.362998,0.317675,0.000000, -0.263800,0.724300,0.637000, 0.187500,0.758600, +-0.074345,0.323693,0.373758,0.000000, -0.149000,0.645700,0.748900, 0.218700,0.724100, +-0.131586,0.362998,0.317675,0.000000, -0.263800,0.724300,0.637000, 0.187500,0.758600, +-0.145834,0.323693,0.352073,0.000000, -0.292200,0.645700,0.705400, 0.187500,0.724100, +-0.067082,-0.362998,0.337242,0.000000, -0.134500,-0.724300,0.676200, 0.218700,0.241400, +-0.074345,-0.323693,0.373758,0.000000, -0.149000,-0.645700,0.748900, 0.218700,0.275900, +-0.145834,-0.323693,0.352073,0.000000, -0.292200,-0.645700,0.705400, 0.187500,0.275900, +-0.067082,-0.362998,0.337242,0.000000, -0.134500,-0.724300,0.676200, 0.218700,0.241400, +-0.145834,-0.323693,0.352073,0.000000, -0.292200,-0.645700,0.705400, 0.187500,0.275900, +-0.131586,-0.362998,0.317675,0.000000, -0.263800,-0.724300,0.637000, 0.187500,0.241400, +-0.080738,0.280594,0.405892,0.000000, -0.161700,0.559600,0.812800, 0.218700,0.689700, +-0.074345,0.323693,0.373758,0.000000, -0.149000,0.645700,0.748900, 0.218700,0.724100, +-0.145834,0.323693,0.352073,0.000000, -0.292200,0.645700,0.705400, 0.187500,0.724100, +-0.080738,0.280594,0.405892,0.000000, -0.161700,0.559600,0.812800, 0.218700,0.689700, +-0.145834,0.323693,0.352073,0.000000, -0.292200,0.645700,0.705400, 0.187500,0.724100, +-0.158371,0.280594,0.382342,0.000000, -0.317100,0.559600,0.765600, 0.187500,0.689700, +-0.059032,-0.398046,0.296773,0.000000, -0.118500,-0.794500,0.595600, 0.218700,0.206900, +-0.067082,-0.362998,0.337242,0.000000, -0.134500,-0.724300,0.676200, 0.218700,0.241400, +-0.131586,-0.362998,0.317675,0.000000, -0.263800,-0.724300,0.637000, 0.187500,0.241400, +-0.059032,-0.398046,0.296773,0.000000, -0.118500,-0.794500,0.595600, 0.218700,0.206900, +-0.131586,-0.362998,0.317675,0.000000, -0.263800,-0.724300,0.637000, 0.187500,0.241400, +-0.115796,-0.398046,0.279554,0.000000, -0.232400,-0.794500,0.561100, 0.187500,0.206900, +-0.086182,0.234204,0.433267,0.000000, -0.172500,0.467000,0.867200, 0.218700,0.655200, +-0.080738,0.280594,0.405892,0.000000, -0.161700,0.559600,0.812800, 0.218700,0.689700, +-0.158371,0.280594,0.382342,0.000000, -0.317100,0.559600,0.765600, 0.187500,0.689700, +-0.086182,0.234204,0.433267,0.000000, -0.172500,0.467000,0.867200, 0.218700,0.655200, +-0.158371,0.280594,0.382342,0.000000, -0.317100,0.559600,0.765600, 0.187500,0.689700, +-0.169053,0.234204,0.408128,0.000000, -0.338400,0.467000,0.816900, 0.187500,0.655200, +-0.050290,-0.428429,0.252824,0.000000, -0.101000,-0.855300,0.508100, 0.218700,0.172400, +-0.059032,-0.398046,0.296773,0.000000, -0.118500,-0.794500,0.595600, 0.218700,0.206900, +-0.115796,-0.398046,0.279554,0.000000, -0.232400,-0.794500,0.561100, 0.187500,0.206900, +-0.050290,-0.428429,0.252824,0.000000, -0.101000,-0.855300,0.508100, 0.218700,0.172400, +-0.115796,-0.398046,0.279554,0.000000, -0.232400,-0.794500,0.561100, 0.187500,0.206900, +-0.098647,-0.428429,0.238155,0.000000, -0.198200,-0.855300,0.478600, 0.187500,0.172400, +-0.090618,0.185069,0.455563,0.000000, -0.181300,0.369000,0.911600, 0.218700,0.620700, +-0.086182,0.234204,0.433267,0.000000, -0.172500,0.467000,0.867200, 0.218700,0.655200, +-0.169053,0.234204,0.408128,0.000000, -0.338400,0.467000,0.816900, 0.187500,0.655200, +-0.090618,0.185069,0.455563,0.000000, -0.181300,0.369000,0.911600, 0.218700,0.620700, +-0.169053,0.234204,0.408128,0.000000, -0.338400,0.467000,0.816900, 0.187500,0.655200, +-0.177752,0.185069,0.429130,0.000000, -0.355700,0.369000,0.858700, 0.187500,0.620700, +-0.040959,-0.453788,0.205910,0.000000, -0.082400,-0.906300,0.414500, 0.218700,0.137900, +-0.050290,-0.428429,0.252824,0.000000, -0.101000,-0.855300,0.508100, 0.218700,0.172400, +-0.098647,-0.428429,0.238155,0.000000, -0.198200,-0.855300,0.478600, 0.187500,0.172400, +-0.040959,-0.453788,0.205910,0.000000, -0.082400,-0.906300,0.414500, 0.218700,0.137900, +-0.098647,-0.428429,0.238155,0.000000, -0.198200,-0.855300,0.478600, 0.187500,0.172400, +-0.080343,-0.453788,0.193963,0.000000, -0.161700,-0.906300,0.390500, 0.187500,0.137900, +-0.093990,0.133764,0.472517,0.000000, -0.188000,0.266600,0.945200, 0.218700,0.586200, +-0.090618,0.185069,0.455563,0.000000, -0.181300,0.369000,0.911600, 0.218700,0.620700, +-0.177752,0.185069,0.429130,0.000000, -0.355700,0.369000,0.858700, 0.187500,0.620700, +-0.093990,0.133764,0.472517,0.000000, -0.188000,0.266600,0.945200, 0.218700,0.586200, +-0.177752,0.185069,0.429130,0.000000, -0.355700,0.369000,0.858700, 0.187500,0.620700, +-0.184367,0.133764,0.445101,0.000000, -0.368800,0.266600,0.890400, 0.187500,0.586200, +-0.031147,-0.473826,0.156583,0.000000, -0.062900,-0.946600,0.316100, 0.218700,0.103400, +-0.040959,-0.453788,0.205910,0.000000, -0.082400,-0.906300,0.414500, 0.218700,0.137900, +-0.080343,-0.453788,0.193963,0.000000, -0.161700,-0.906300,0.390500, 0.187500,0.137900, +-0.031147,-0.473826,0.156583,0.000000, -0.062900,-0.946600,0.316100, 0.218700,0.103400, +-0.080343,-0.453788,0.193963,0.000000, -0.161700,-0.906300,0.390500, 0.187500,0.137900, +-0.061096,-0.473826,0.147498,0.000000, -0.123300,-0.946600,0.297800, 0.187500,0.103400, +-0.096261,0.080891,0.483932,0.000000, -0.192500,0.161200,0.967900, 0.218700,0.551700, +-0.093990,0.133764,0.472517,0.000000, -0.188000,0.266600,0.945200, 0.218700,0.586200, +-0.184367,0.133764,0.445101,0.000000, -0.368800,0.266600,0.890400, 0.187500,0.586200, +-0.096261,0.080891,0.483932,0.000000, -0.192500,0.161200,0.967900, 0.218700,0.551700, +-0.184367,0.133764,0.445101,0.000000, -0.368800,0.266600,0.890400, 0.187500,0.586200, +-0.188821,0.080891,0.455853,0.000000, -0.377700,0.161200,0.911800, 0.187500,0.551700, +-0.020970,-0.488310,0.105420,0.000000, -0.042500,-0.975900,0.214000, 0.218700,0.069000, +-0.031147,-0.473826,0.156583,0.000000, -0.062900,-0.946600,0.316100, 0.218700,0.103400, +-0.061096,-0.473826,0.147498,0.000000, -0.123300,-0.946600,0.297800, 0.187500,0.103400, +-0.020970,-0.488310,0.105420,0.000000, -0.042500,-0.975900,0.214000, 0.218700,0.069000, +-0.061096,-0.473826,0.147498,0.000000, -0.123300,-0.946600,0.297800, 0.187500,0.103400, +-0.041133,-0.488310,0.099303,0.000000, -0.083500,-0.975900,0.201600, 0.187500,0.069000, +-0.097402,0.027069,0.489673,0.000000, -0.194800,0.054000,0.979300, 0.218700,0.517200, +-0.096261,0.080891,0.483932,0.000000, -0.192500,0.161200,0.967900, 0.218700,0.551700, +-0.188821,0.080891,0.455853,0.000000, -0.377700,0.161200,0.911800, 0.187500,0.551700, +-0.097402,0.027069,0.489673,0.000000, -0.194800,0.054000,0.979300, 0.218700,0.517200, +-0.188821,0.080891,0.455853,0.000000, -0.377700,0.161200,0.911800, 0.187500,0.551700, +-0.191061,0.027069,0.461262,0.000000, -0.382100,0.054000,0.922500, 0.187500,0.517200, +-0.010547,0.497069,0.053020,0.000000, -0.021700,0.993700,0.109300, 0.472600,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +-0.020688,0.497069,0.049944,0.000000, -0.042600,0.993700,0.103000, 0.474400,0.962300, +-0.010547,-0.497069,0.053020,0.000000, -0.021700,-0.993700,0.109300, 0.218700,0.034500, +-0.020970,-0.488310,0.105420,0.000000, -0.042500,-0.975900,0.214000, 0.218700,0.069000, +-0.041133,-0.488310,0.099303,0.000000, -0.083500,-0.975900,0.201600, 0.187500,0.069000, +-0.010547,-0.497069,0.053020,0.000000, -0.021700,-0.993700,0.109300, 0.218700,0.034500, +-0.041133,-0.488310,0.099303,0.000000, -0.083500,-0.975900,0.201600, 0.187500,0.069000, +-0.020688,-0.497069,0.049945,0.000000, -0.042600,-0.993700,0.103000, 0.187500,0.034500, +-0.097402,-0.027069,0.489673,0.000000, -0.194800,-0.054000,0.979300, 0.218700,0.482800, +-0.097402,0.027069,0.489673,0.000000, -0.194800,0.054000,0.979300, 0.218700,0.517200, +-0.191061,0.027069,0.461262,0.000000, -0.382100,0.054000,0.922500, 0.187500,0.517200, +-0.097402,-0.027069,0.489673,0.000000, -0.194800,-0.054000,0.979300, 0.218700,0.482800, +-0.191061,0.027069,0.461262,0.000000, -0.382100,0.054000,0.922500, 0.187500,0.517200, +-0.191061,-0.027069,0.461262,0.000000, -0.382100,-0.054000,0.922500, 0.187500,0.482800, +-0.020970,0.488310,0.105420,0.000000, -0.042500,0.975900,0.214000, 0.218700,0.931000, +-0.010547,0.497069,0.053020,0.000000, -0.021700,0.993700,0.109300, 0.218700,0.965500, +-0.020688,0.497069,0.049944,0.000000, -0.042600,0.993700,0.103000, 0.187500,0.965500, +-0.020970,0.488310,0.105420,0.000000, -0.042500,0.975900,0.214000, 0.218700,0.931000, +-0.020688,0.497069,0.049944,0.000000, -0.042600,0.993700,0.103000, 0.187500,0.965500, +-0.041133,0.488310,0.099303,0.000000, -0.083500,0.975900,0.201600, 0.187500,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +-0.010547,-0.497069,0.053020,0.000000, -0.021700,-0.993700,0.109300, 0.428700,0.053800, +-0.020688,-0.497069,0.049945,0.000000, -0.042600,-0.993700,0.103000, 0.426100,0.053800, +-0.096261,-0.080891,0.483932,0.000000, -0.192500,-0.161200,0.967900, 0.218700,0.448300, +-0.097402,-0.027069,0.489673,0.000000, -0.194800,-0.054000,0.979300, 0.218700,0.482800, +-0.191061,-0.027069,0.461262,0.000000, -0.382100,-0.054000,0.922500, 0.187500,0.482800, +-0.096261,-0.080891,0.483932,0.000000, -0.192500,-0.161200,0.967900, 0.218700,0.448300, +-0.191061,-0.027069,0.461262,0.000000, -0.382100,-0.054000,0.922500, 0.187500,0.482800, +-0.188821,-0.080891,0.455853,0.000000, -0.377700,-0.161200,0.911800, 0.187500,0.448300, +-0.031147,0.473826,0.156583,0.000000, -0.062900,0.946600,0.316100, 0.218700,0.896600, +-0.020970,0.488310,0.105420,0.000000, -0.042500,0.975900,0.214000, 0.218700,0.931000, +-0.041133,0.488310,0.099303,0.000000, -0.083500,0.975900,0.201600, 0.187500,0.931000, +-0.031147,0.473826,0.156583,0.000000, -0.062900,0.946600,0.316100, 0.218700,0.896600, +-0.041133,0.488310,0.099303,0.000000, -0.083500,0.975900,0.201600, 0.187500,0.931000, +-0.061096,0.473826,0.147498,0.000000, -0.123300,0.946600,0.297800, 0.187500,0.896600, +-0.093990,-0.133764,0.472517,0.000000, -0.188000,-0.266600,0.945200, 0.218700,0.413800, +-0.096261,-0.080891,0.483932,0.000000, -0.192500,-0.161200,0.967900, 0.218700,0.448300, +-0.188821,-0.080891,0.455853,0.000000, -0.377700,-0.161200,0.911800, 0.187500,0.448300, +-0.093990,-0.133764,0.472517,0.000000, -0.188000,-0.266600,0.945200, 0.218700,0.413800, +-0.188821,-0.080891,0.455853,0.000000, -0.377700,-0.161200,0.911800, 0.187500,0.448300, +-0.184367,-0.133764,0.445101,0.000000, -0.368800,-0.266600,0.890400, 0.187500,0.413800, +-0.040959,0.453788,0.205910,0.000000, -0.082400,0.906300,0.414500, 0.218700,0.862100, +-0.031147,0.473826,0.156583,0.000000, -0.062900,0.946600,0.316100, 0.218700,0.896600, +-0.061096,0.473826,0.147498,0.000000, -0.123300,0.946600,0.297800, 0.187500,0.896600, +-0.040959,0.453788,0.205910,0.000000, -0.082400,0.906300,0.414500, 0.218700,0.862100, +-0.061096,0.473826,0.147498,0.000000, -0.123300,0.946600,0.297800, 0.187500,0.896600, +-0.080343,0.453788,0.193963,0.000000, -0.161700,0.906300,0.390500, 0.187500,0.862100, +-0.090618,-0.185069,0.455563,0.000000, -0.181300,-0.369000,0.911600, 0.218700,0.379300, +-0.093990,-0.133764,0.472517,0.000000, -0.188000,-0.266600,0.945200, 0.218700,0.413800, +-0.184367,-0.133764,0.445101,0.000000, -0.368800,-0.266600,0.890400, 0.187500,0.413800, +-0.090618,-0.185069,0.455563,0.000000, -0.181300,-0.369000,0.911600, 0.218700,0.379300, +-0.184367,-0.133764,0.445101,0.000000, -0.368800,-0.266600,0.890400, 0.187500,0.413800, +-0.177752,-0.185069,0.429130,0.000000, -0.355700,-0.369000,0.858700, 0.187500,0.379300, +-0.188821,0.080891,0.455853,0.000000, -0.377700,0.161200,0.911800, 0.187500,0.551700, +-0.184367,0.133764,0.445101,0.000000, -0.368800,0.266600,0.890400, 0.187500,0.586200, +-0.267660,0.133764,0.400580,0.000000, -0.535400,0.266600,0.801400, 0.156200,0.586200, +-0.188821,0.080891,0.455853,0.000000, -0.377700,0.161200,0.911800, 0.187500,0.551700, +-0.267660,0.133764,0.400580,0.000000, -0.535400,0.266600,0.801400, 0.156200,0.586200, +-0.274125,0.080891,0.410257,0.000000, -0.548300,0.161200,0.820600, 0.156200,0.551700, +-0.041133,-0.488310,0.099303,0.000000, -0.083500,-0.975900,0.201600, 0.187500,0.069000, +-0.061096,-0.473826,0.147498,0.000000, -0.123300,-0.946600,0.297800, 0.187500,0.103400, +-0.088698,-0.473826,0.132745,0.000000, -0.179100,-0.946600,0.268000, 0.156200,0.103400, +-0.041133,-0.488310,0.099303,0.000000, -0.083500,-0.975900,0.201600, 0.187500,0.069000, +-0.088698,-0.473826,0.132745,0.000000, -0.179100,-0.946600,0.268000, 0.156200,0.103400, +-0.059716,-0.488310,0.089370,0.000000, -0.121200,-0.975900,0.181400, 0.156200,0.069000, +-0.191061,0.027069,0.461262,0.000000, -0.382100,0.054000,0.922500, 0.187500,0.517200, +-0.188821,0.080891,0.455853,0.000000, -0.377700,0.161200,0.911800, 0.187500,0.551700, +-0.274125,0.080891,0.410257,0.000000, -0.548300,0.161200,0.820600, 0.156200,0.551700, +-0.191061,0.027069,0.461262,0.000000, -0.382100,0.054000,0.922500, 0.187500,0.517200, +-0.274125,0.080891,0.410257,0.000000, -0.548300,0.161200,0.820600, 0.156200,0.551700, +-0.277378,0.027069,0.415125,0.000000, -0.554700,0.054000,0.830300, 0.156200,0.517200, +-0.020688,0.497069,0.049944,0.000000, -0.042600,0.993700,0.103000, 0.474400,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +-0.030034,0.497069,0.044948,0.000000, -0.061900,0.993700,0.092700, 0.476200,0.962300, +-0.020688,-0.497069,0.049945,0.000000, -0.042600,-0.993700,0.103000, 0.187500,0.034500, +-0.041133,-0.488310,0.099303,0.000000, -0.083500,-0.975900,0.201600, 0.187500,0.069000, +-0.059716,-0.488310,0.089370,0.000000, -0.121200,-0.975900,0.181400, 0.156200,0.069000, +-0.020688,-0.497069,0.049945,0.000000, -0.042600,-0.993700,0.103000, 0.187500,0.034500, +-0.059716,-0.488310,0.089370,0.000000, -0.121200,-0.975900,0.181400, 0.156200,0.069000, +-0.030034,-0.497069,0.044949,0.000000, -0.061900,-0.993700,0.092700, 0.156200,0.034500, +-0.191061,-0.027069,0.461262,0.000000, -0.382100,-0.054000,0.922500, 0.187500,0.482800, +-0.191061,0.027069,0.461262,0.000000, -0.382100,0.054000,0.922500, 0.187500,0.517200, +-0.277378,0.027069,0.415125,0.000000, -0.554700,0.054000,0.830300, 0.156200,0.517200, +-0.191061,-0.027069,0.461262,0.000000, -0.382100,-0.054000,0.922500, 0.187500,0.482800, +-0.277378,0.027069,0.415125,0.000000, -0.554700,0.054000,0.830300, 0.156200,0.517200, +-0.277378,-0.027069,0.415125,0.000000, -0.554700,-0.054000,0.830300, 0.156200,0.482800, +-0.041133,0.488310,0.099303,0.000000, -0.083500,0.975900,0.201600, 0.187500,0.931000, +-0.020688,0.497069,0.049944,0.000000, -0.042600,0.993700,0.103000, 0.187500,0.965500, +-0.030034,0.497069,0.044948,0.000000, -0.061900,0.993700,0.092700, 0.156200,0.965500, +-0.041133,0.488310,0.099303,0.000000, -0.083500,0.975900,0.201600, 0.187500,0.931000, +-0.030034,0.497069,0.044948,0.000000, -0.061900,0.993700,0.092700, 0.156200,0.965500, +-0.059716,0.488310,0.089370,0.000000, -0.121200,0.975900,0.181400, 0.156200,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +-0.020688,-0.497069,0.049945,0.000000, -0.042600,-0.993700,0.103000, 0.426100,0.053800, +-0.030034,-0.497069,0.044949,0.000000, -0.061900,-0.993700,0.092700, 0.423500,0.053800, +-0.188821,-0.080891,0.455853,0.000000, -0.377700,-0.161200,0.911800, 0.187500,0.448300, +-0.191061,-0.027069,0.461262,0.000000, -0.382100,-0.054000,0.922500, 0.187500,0.482800, +-0.277378,-0.027069,0.415125,0.000000, -0.554700,-0.054000,0.830300, 0.156200,0.482800, +-0.188821,-0.080891,0.455853,0.000000, -0.377700,-0.161200,0.911800, 0.187500,0.448300, +-0.277378,-0.027069,0.415125,0.000000, -0.554700,-0.054000,0.830300, 0.156200,0.482800, +-0.274125,-0.080891,0.410257,0.000000, -0.548300,-0.161200,0.820600, 0.156200,0.448300, +-0.061096,0.473826,0.147498,0.000000, -0.123300,0.946600,0.297800, 0.187500,0.896600, +-0.041133,0.488310,0.099303,0.000000, -0.083500,0.975900,0.201600, 0.187500,0.931000, +-0.059716,0.488310,0.089370,0.000000, -0.121200,0.975900,0.181400, 0.156200,0.931000, +-0.061096,0.473826,0.147498,0.000000, -0.123300,0.946600,0.297800, 0.187500,0.896600, +-0.059716,0.488310,0.089370,0.000000, -0.121200,0.975900,0.181400, 0.156200,0.931000, +-0.088698,0.473826,0.132745,0.000000, -0.179100,0.946600,0.268000, 0.156200,0.896600, +-0.184367,-0.133764,0.445101,0.000000, -0.368800,-0.266600,0.890400, 0.187500,0.413800, +-0.188821,-0.080891,0.455853,0.000000, -0.377700,-0.161200,0.911800, 0.187500,0.448300, +-0.274125,-0.080891,0.410257,0.000000, -0.548300,-0.161200,0.820600, 0.156200,0.448300, +-0.184367,-0.133764,0.445101,0.000000, -0.368800,-0.266600,0.890400, 0.187500,0.413800, +-0.274125,-0.080891,0.410257,0.000000, -0.548300,-0.161200,0.820600, 0.156200,0.448300, +-0.267660,-0.133764,0.400580,0.000000, -0.535400,-0.266600,0.801400, 0.156200,0.413800, +-0.080343,0.453788,0.193963,0.000000, -0.161700,0.906300,0.390500, 0.187500,0.862100, +-0.061096,0.473826,0.147498,0.000000, -0.123300,0.946600,0.297800, 0.187500,0.896600, +-0.088698,0.473826,0.132745,0.000000, -0.179100,0.946600,0.268000, 0.156200,0.896600, +-0.080343,0.453788,0.193963,0.000000, -0.161700,0.906300,0.390500, 0.187500,0.862100, +-0.088698,0.473826,0.132745,0.000000, -0.179100,0.946600,0.268000, 0.156200,0.896600, +-0.116639,0.453788,0.174562,0.000000, -0.234800,0.906300,0.351400, 0.156200,0.862100, +-0.177752,-0.185069,0.429130,0.000000, -0.355700,-0.369000,0.858700, 0.187500,0.379300, +-0.184367,-0.133764,0.445101,0.000000, -0.368800,-0.266600,0.890400, 0.187500,0.413800, +-0.267660,-0.133764,0.400580,0.000000, -0.535400,-0.266600,0.801400, 0.156200,0.413800, +-0.177752,-0.185069,0.429130,0.000000, -0.355700,-0.369000,0.858700, 0.187500,0.379300, +-0.267660,-0.133764,0.400580,0.000000, -0.535400,-0.266600,0.801400, 0.156200,0.413800, +-0.258056,-0.185069,0.386207,0.000000, -0.516300,-0.369000,0.772800, 0.156200,0.379300, +-0.098647,0.428429,0.238154,0.000000, -0.198200,0.855300,0.478600, 0.187500,0.827600, +-0.080343,0.453788,0.193963,0.000000, -0.161700,0.906300,0.390500, 0.187500,0.862100, +-0.116639,0.453788,0.174562,0.000000, -0.234800,0.906300,0.351400, 0.156200,0.862100, +-0.098647,0.428429,0.238154,0.000000, -0.198200,0.855300,0.478600, 0.187500,0.827600, +-0.116639,0.453788,0.174562,0.000000, -0.234800,0.906300,0.351400, 0.156200,0.862100, +-0.143213,0.428429,0.214333,0.000000, -0.287800,0.855300,0.430700, 0.156200,0.827600, +-0.169053,-0.234204,0.408128,0.000000, -0.338400,-0.467000,0.816900, 0.187500,0.344800, +-0.177752,-0.185069,0.429130,0.000000, -0.355700,-0.369000,0.858700, 0.187500,0.379300, +-0.258056,-0.185069,0.386207,0.000000, -0.516300,-0.369000,0.772800, 0.156200,0.379300, +-0.169053,-0.234204,0.408128,0.000000, -0.338400,-0.467000,0.816900, 0.187500,0.344800, +-0.258056,-0.185069,0.386207,0.000000, -0.516300,-0.369000,0.772800, 0.156200,0.379300, +-0.245427,-0.234204,0.367306,0.000000, -0.491300,-0.467000,0.735200, 0.156200,0.344800, +-0.115796,0.398046,0.279554,0.000000, -0.232400,0.794500,0.561100, 0.187500,0.793100, +-0.098647,0.428429,0.238154,0.000000, -0.198200,0.855300,0.478600, 0.187500,0.827600, +-0.143213,0.428429,0.214333,0.000000, -0.287800,0.855300,0.430700, 0.156200,0.827600, +-0.115796,0.398046,0.279554,0.000000, -0.232400,0.794500,0.561100, 0.187500,0.793100, +-0.143213,0.428429,0.214333,0.000000, -0.287800,0.855300,0.430700, 0.156200,0.827600, +-0.168108,0.398046,0.251592,0.000000, -0.337400,0.794500,0.505000, 0.156200,0.793100, +-0.158371,-0.280594,0.382342,0.000000, -0.317100,-0.559600,0.765600, 0.187500,0.310300, +-0.169053,-0.234204,0.408128,0.000000, -0.338400,-0.467000,0.816900, 0.187500,0.344800, +-0.245427,-0.234204,0.367306,0.000000, -0.491300,-0.467000,0.735200, 0.156200,0.344800, +-0.158371,-0.280594,0.382342,0.000000, -0.317100,-0.559600,0.765600, 0.187500,0.310300, +-0.245427,-0.234204,0.367306,0.000000, -0.491300,-0.467000,0.735200, 0.156200,0.344800, +-0.229920,-0.280594,0.344099,0.000000, -0.460400,-0.559600,0.689100, 0.156200,0.310300, +-0.131586,0.362998,0.317675,0.000000, -0.263800,0.724300,0.637000, 0.187500,0.758600, +-0.115796,0.398046,0.279554,0.000000, -0.232400,0.794500,0.561100, 0.187500,0.793100, +-0.168108,0.398046,0.251592,0.000000, -0.337400,0.794500,0.505000, 0.156200,0.793100, +-0.131586,0.362998,0.317675,0.000000, -0.263800,0.724300,0.637000, 0.187500,0.758600, +-0.168108,0.398046,0.251592,0.000000, -0.337400,0.794500,0.505000, 0.156200,0.793100, +-0.191033,0.362998,0.285900,0.000000, -0.383000,0.724300,0.573300, 0.156200,0.758600, +-0.145834,-0.323693,0.352073,0.000000, -0.292200,-0.645700,0.705400, 0.187500,0.275900, +-0.158371,-0.280594,0.382342,0.000000, -0.317100,-0.559600,0.765600, 0.187500,0.310300, +-0.229920,-0.280594,0.344099,0.000000, -0.460400,-0.559600,0.689100, 0.156200,0.310300, +-0.145834,-0.323693,0.352073,0.000000, -0.292200,-0.645700,0.705400, 0.187500,0.275900, +-0.229920,-0.280594,0.344099,0.000000, -0.460400,-0.559600,0.689100, 0.156200,0.310300, +-0.211718,-0.323693,0.316857,0.000000, -0.424200,-0.645700,0.634900, 0.156200,0.275900, +-0.145834,0.323693,0.352073,0.000000, -0.292200,0.645700,0.705400, 0.187500,0.724100, +-0.131586,0.362998,0.317675,0.000000, -0.263800,0.724300,0.637000, 0.187500,0.758600, +-0.191033,0.362998,0.285900,0.000000, -0.383000,0.724300,0.573300, 0.156200,0.758600, +-0.145834,0.323693,0.352073,0.000000, -0.292200,0.645700,0.705400, 0.187500,0.724100, +-0.191033,0.362998,0.285900,0.000000, -0.383000,0.724300,0.573300, 0.156200,0.758600, +-0.211718,0.323693,0.316857,0.000000, -0.424200,0.645700,0.634900, 0.156200,0.724100, +-0.131586,-0.362998,0.317675,0.000000, -0.263800,-0.724300,0.637000, 0.187500,0.241400, +-0.145834,-0.323693,0.352073,0.000000, -0.292200,-0.645700,0.705400, 0.187500,0.275900, +-0.211718,-0.323693,0.316857,0.000000, -0.424200,-0.645700,0.634900, 0.156200,0.275900, +-0.131586,-0.362998,0.317675,0.000000, -0.263800,-0.724300,0.637000, 0.187500,0.241400, +-0.211718,-0.323693,0.316857,0.000000, -0.424200,-0.645700,0.634900, 0.156200,0.275900, +-0.191033,-0.362998,0.285900,0.000000, -0.383000,-0.724300,0.573300, 0.156200,0.241400, +-0.158371,0.280594,0.382342,0.000000, -0.317100,0.559600,0.765600, 0.187500,0.689700, +-0.145834,0.323693,0.352073,0.000000, -0.292200,0.645700,0.705400, 0.187500,0.724100, +-0.211718,0.323693,0.316857,0.000000, -0.424200,0.645700,0.634900, 0.156200,0.724100, +-0.158371,0.280594,0.382342,0.000000, -0.317100,0.559600,0.765600, 0.187500,0.689700, +-0.211718,0.323693,0.316857,0.000000, -0.424200,0.645700,0.634900, 0.156200,0.724100, +-0.229920,0.280594,0.344099,0.000000, -0.460400,0.559600,0.689100, 0.156200,0.689700, +-0.115796,-0.398046,0.279554,0.000000, -0.232400,-0.794500,0.561100, 0.187500,0.206900, +-0.131586,-0.362998,0.317675,0.000000, -0.263800,-0.724300,0.637000, 0.187500,0.241400, +-0.191033,-0.362998,0.285900,0.000000, -0.383000,-0.724300,0.573300, 0.156200,0.241400, +-0.115796,-0.398046,0.279554,0.000000, -0.232400,-0.794500,0.561100, 0.187500,0.206900, +-0.191033,-0.362998,0.285900,0.000000, -0.383000,-0.724300,0.573300, 0.156200,0.241400, +-0.168108,-0.398046,0.251592,0.000000, -0.337400,-0.794500,0.504900, 0.156200,0.206900, +-0.169053,0.234204,0.408128,0.000000, -0.338400,0.467000,0.816900, 0.187500,0.655200, +-0.158371,0.280594,0.382342,0.000000, -0.317100,0.559600,0.765600, 0.187500,0.689700, +-0.229920,0.280594,0.344099,0.000000, -0.460400,0.559600,0.689100, 0.156200,0.689700, +-0.169053,0.234204,0.408128,0.000000, -0.338400,0.467000,0.816900, 0.187500,0.655200, +-0.229920,0.280594,0.344099,0.000000, -0.460400,0.559600,0.689100, 0.156200,0.689700, +-0.245427,0.234204,0.367306,0.000000, -0.491300,0.467000,0.735200, 0.156200,0.655200, +-0.098647,-0.428429,0.238155,0.000000, -0.198200,-0.855300,0.478600, 0.187500,0.172400, +-0.115796,-0.398046,0.279554,0.000000, -0.232400,-0.794500,0.561100, 0.187500,0.206900, +-0.168108,-0.398046,0.251592,0.000000, -0.337400,-0.794500,0.504900, 0.156200,0.206900, +-0.098647,-0.428429,0.238155,0.000000, -0.198200,-0.855300,0.478600, 0.187500,0.172400, +-0.168108,-0.398046,0.251592,0.000000, -0.337400,-0.794500,0.504900, 0.156200,0.206900, +-0.143213,-0.428429,0.214334,0.000000, -0.287800,-0.855300,0.430700, 0.156200,0.172400, +-0.177752,0.185069,0.429130,0.000000, -0.355700,0.369000,0.858700, 0.187500,0.620700, +-0.169053,0.234204,0.408128,0.000000, -0.338400,0.467000,0.816900, 0.187500,0.655200, +-0.245427,0.234204,0.367306,0.000000, -0.491300,0.467000,0.735200, 0.156200,0.655200, +-0.177752,0.185069,0.429130,0.000000, -0.355700,0.369000,0.858700, 0.187500,0.620700, +-0.245427,0.234204,0.367306,0.000000, -0.491300,0.467000,0.735200, 0.156200,0.655200, +-0.258056,0.185069,0.386207,0.000000, -0.516300,0.369000,0.772800, 0.156200,0.620700, +-0.080343,-0.453788,0.193963,0.000000, -0.161700,-0.906300,0.390500, 0.187500,0.137900, +-0.098647,-0.428429,0.238155,0.000000, -0.198200,-0.855300,0.478600, 0.187500,0.172400, +-0.143213,-0.428429,0.214334,0.000000, -0.287800,-0.855300,0.430700, 0.156200,0.172400, +-0.080343,-0.453788,0.193963,0.000000, -0.161700,-0.906300,0.390500, 0.187500,0.137900, +-0.143213,-0.428429,0.214334,0.000000, -0.287800,-0.855300,0.430700, 0.156200,0.172400, +-0.116639,-0.453788,0.174562,0.000000, -0.234800,-0.906300,0.351400, 0.156200,0.137900, +-0.184367,0.133764,0.445101,0.000000, -0.368800,0.266600,0.890400, 0.187500,0.586200, +-0.177752,0.185069,0.429130,0.000000, -0.355700,0.369000,0.858700, 0.187500,0.620700, +-0.258056,0.185069,0.386207,0.000000, -0.516300,0.369000,0.772800, 0.156200,0.620700, +-0.184367,0.133764,0.445101,0.000000, -0.368800,0.266600,0.890400, 0.187500,0.586200, +-0.258056,0.185069,0.386207,0.000000, -0.516300,0.369000,0.772800, 0.156200,0.620700, +-0.267660,0.133764,0.400580,0.000000, -0.535400,0.266600,0.801400, 0.156200,0.586200, +-0.061096,-0.473826,0.147498,0.000000, -0.123300,-0.946600,0.297800, 0.187500,0.103400, +-0.080343,-0.453788,0.193963,0.000000, -0.161700,-0.906300,0.390500, 0.187500,0.137900, +-0.116639,-0.453788,0.174562,0.000000, -0.234800,-0.906300,0.351400, 0.156200,0.137900, +-0.061096,-0.473826,0.147498,0.000000, -0.123300,-0.946600,0.297800, 0.187500,0.103400, +-0.116639,-0.453788,0.174562,0.000000, -0.234800,-0.906300,0.351400, 0.156200,0.137900, +-0.088698,-0.473826,0.132745,0.000000, -0.179100,-0.946600,0.268000, 0.156200,0.103400, +-0.211718,-0.323693,0.316857,0.000000, -0.424200,-0.645700,0.634900, 0.156200,0.275900, +-0.229920,-0.280594,0.344099,0.000000, -0.460400,-0.559600,0.689100, 0.156200,0.310300, +-0.292632,-0.280594,0.292632,0.000000, -0.586000,-0.559600,0.586000, 0.125000,0.310300, +-0.211718,-0.323693,0.316857,0.000000, -0.424200,-0.645700,0.634900, 0.156200,0.275900, +-0.292632,-0.280594,0.292632,0.000000, -0.586000,-0.559600,0.586000, 0.125000,0.310300, +-0.269465,-0.323693,0.269464,0.000000, -0.539900,-0.645700,0.539900, 0.125000,0.275900, +-0.211718,0.323693,0.316857,0.000000, -0.424200,0.645700,0.634900, 0.156200,0.724100, +-0.191033,0.362998,0.285900,0.000000, -0.383000,0.724300,0.573300, 0.156200,0.758600, +-0.243139,0.362998,0.243138,0.000000, -0.487500,0.724300,0.487500, 0.125000,0.758600, +-0.211718,0.323693,0.316857,0.000000, -0.424200,0.645700,0.634900, 0.156200,0.724100, +-0.243139,0.362998,0.243138,0.000000, -0.487500,0.724300,0.487500, 0.125000,0.758600, +-0.269465,0.323693,0.269464,0.000000, -0.539900,0.645700,0.539900, 0.125000,0.724100, +-0.191033,-0.362998,0.285900,0.000000, -0.383000,-0.724300,0.573300, 0.156200,0.241400, +-0.211718,-0.323693,0.316857,0.000000, -0.424200,-0.645700,0.634900, 0.156200,0.275900, +-0.269465,-0.323693,0.269464,0.000000, -0.539900,-0.645700,0.539900, 0.125000,0.275900, +-0.191033,-0.362998,0.285900,0.000000, -0.383000,-0.724300,0.573300, 0.156200,0.241400, +-0.269465,-0.323693,0.269464,0.000000, -0.539900,-0.645700,0.539900, 0.125000,0.275900, +-0.243139,-0.362998,0.243138,0.000000, -0.487500,-0.724300,0.487500, 0.125000,0.241400, +-0.229920,0.280594,0.344099,0.000000, -0.460400,0.559600,0.689100, 0.156200,0.689700, +-0.211718,0.323693,0.316857,0.000000, -0.424200,0.645700,0.634900, 0.156200,0.724100, +-0.269465,0.323693,0.269464,0.000000, -0.539900,0.645700,0.539900, 0.125000,0.724100, +-0.229920,0.280594,0.344099,0.000000, -0.460400,0.559600,0.689100, 0.156200,0.689700, +-0.269465,0.323693,0.269464,0.000000, -0.539900,0.645700,0.539900, 0.125000,0.724100, +-0.292632,0.280594,0.292632,0.000000, -0.586000,0.559600,0.586000, 0.125000,0.689700, +-0.168108,-0.398046,0.251592,0.000000, -0.337400,-0.794500,0.504900, 0.156200,0.206900, +-0.191033,-0.362998,0.285900,0.000000, -0.383000,-0.724300,0.573300, 0.156200,0.241400, +-0.243139,-0.362998,0.243138,0.000000, -0.487500,-0.724300,0.487500, 0.125000,0.241400, +-0.168108,-0.398046,0.251592,0.000000, -0.337400,-0.794500,0.504900, 0.156200,0.206900, +-0.243139,-0.362998,0.243138,0.000000, -0.487500,-0.724300,0.487500, 0.125000,0.241400, +-0.213961,-0.398046,0.213961,0.000000, -0.429400,-0.794500,0.429400, 0.125000,0.206900, +-0.245427,0.234204,0.367306,0.000000, -0.491300,0.467000,0.735200, 0.156200,0.655200, +-0.229920,0.280594,0.344099,0.000000, -0.460400,0.559600,0.689100, 0.156200,0.689700, +-0.292632,0.280594,0.292632,0.000000, -0.586000,0.559600,0.586000, 0.125000,0.689700, +-0.245427,0.234204,0.367306,0.000000, -0.491300,0.467000,0.735200, 0.156200,0.655200, +-0.292632,0.280594,0.292632,0.000000, -0.586000,0.559600,0.586000, 0.125000,0.689700, +-0.312369,0.234204,0.312368,0.000000, -0.625200,0.467000,0.625200, 0.125000,0.655200, +-0.143213,-0.428429,0.214334,0.000000, -0.287800,-0.855300,0.430700, 0.156200,0.172400, +-0.168108,-0.398046,0.251592,0.000000, -0.337400,-0.794500,0.504900, 0.156200,0.206900, +-0.213961,-0.398046,0.213961,0.000000, -0.429400,-0.794500,0.429400, 0.125000,0.206900, +-0.143213,-0.428429,0.214334,0.000000, -0.287800,-0.855300,0.430700, 0.156200,0.172400, +-0.213961,-0.398046,0.213961,0.000000, -0.429400,-0.794500,0.429400, 0.125000,0.206900, +-0.182276,-0.428429,0.182276,0.000000, -0.366300,-0.855300,0.366300, 0.125000,0.172400, +-0.258056,0.185069,0.386207,0.000000, -0.516300,0.369000,0.772800, 0.156200,0.620700, +-0.245427,0.234204,0.367306,0.000000, -0.491300,0.467000,0.735200, 0.156200,0.655200, +-0.312369,0.234204,0.312368,0.000000, -0.625200,0.467000,0.625200, 0.125000,0.655200, +-0.258056,0.185069,0.386207,0.000000, -0.516300,0.369000,0.772800, 0.156200,0.620700, +-0.312369,0.234204,0.312368,0.000000, -0.625200,0.467000,0.625200, 0.125000,0.655200, +-0.328443,0.185069,0.328443,0.000000, -0.657200,0.369000,0.657200, 0.125000,0.620700, +-0.116639,-0.453788,0.174562,0.000000, -0.234800,-0.906300,0.351400, 0.156200,0.137900, +-0.143213,-0.428429,0.214334,0.000000, -0.287800,-0.855300,0.430700, 0.156200,0.172400, +-0.182276,-0.428429,0.182276,0.000000, -0.366300,-0.855300,0.366300, 0.125000,0.172400, +-0.116639,-0.453788,0.174562,0.000000, -0.234800,-0.906300,0.351400, 0.156200,0.137900, +-0.182276,-0.428429,0.182276,0.000000, -0.366300,-0.855300,0.366300, 0.125000,0.172400, +-0.148454,-0.453788,0.148453,0.000000, -0.298900,-0.906300,0.298900, 0.125000,0.137900, +-0.267660,0.133764,0.400580,0.000000, -0.535400,0.266600,0.801400, 0.156200,0.586200, +-0.258056,0.185069,0.386207,0.000000, -0.516300,0.369000,0.772800, 0.156200,0.620700, +-0.328443,0.185069,0.328443,0.000000, -0.657200,0.369000,0.657200, 0.125000,0.620700, +-0.267660,0.133764,0.400580,0.000000, -0.535400,0.266600,0.801400, 0.156200,0.586200, +-0.328443,0.185069,0.328443,0.000000, -0.657200,0.369000,0.657200, 0.125000,0.620700, +-0.340667,0.133764,0.340666,0.000000, -0.681500,0.266600,0.681500, 0.125000,0.586200, +-0.088698,-0.473826,0.132745,0.000000, -0.179100,-0.946600,0.268000, 0.156200,0.103400, +-0.116639,-0.453788,0.174562,0.000000, -0.234800,-0.906300,0.351400, 0.156200,0.137900, +-0.148454,-0.453788,0.148453,0.000000, -0.298900,-0.906300,0.298900, 0.125000,0.137900, +-0.088698,-0.473826,0.132745,0.000000, -0.179100,-0.946600,0.268000, 0.156200,0.103400, +-0.148454,-0.453788,0.148453,0.000000, -0.298900,-0.906300,0.298900, 0.125000,0.137900, +-0.112890,-0.473826,0.112890,0.000000, -0.227900,-0.946600,0.227900, 0.125000,0.103400, +-0.274125,0.080891,0.410257,0.000000, -0.548300,0.161200,0.820600, 0.156200,0.551700, +-0.267660,0.133764,0.400580,0.000000, -0.535400,0.266600,0.801400, 0.156200,0.586200, +-0.340667,0.133764,0.340666,0.000000, -0.681500,0.266600,0.681500, 0.125000,0.586200, +-0.274125,0.080891,0.410257,0.000000, -0.548300,0.161200,0.820600, 0.156200,0.551700, +-0.340667,0.133764,0.340666,0.000000, -0.681500,0.266600,0.681500, 0.125000,0.586200, +-0.348895,0.080891,0.348895,0.000000, -0.697800,0.161200,0.697800, 0.125000,0.551700, +-0.059716,-0.488310,0.089370,0.000000, -0.121200,-0.975900,0.181400, 0.156200,0.069000, +-0.088698,-0.473826,0.132745,0.000000, -0.179100,-0.946600,0.268000, 0.156200,0.103400, +-0.112890,-0.473826,0.112890,0.000000, -0.227900,-0.946600,0.227900, 0.125000,0.103400, +-0.059716,-0.488310,0.089370,0.000000, -0.121200,-0.975900,0.181400, 0.156200,0.069000, +-0.112890,-0.473826,0.112890,0.000000, -0.227900,-0.946600,0.227900, 0.125000,0.103400, +-0.076004,-0.488310,0.076003,0.000000, -0.154300,-0.975900,0.154300, 0.125000,0.069000, +-0.277378,0.027069,0.415125,0.000000, -0.554700,0.054000,0.830300, 0.156200,0.517200, +-0.274125,0.080891,0.410257,0.000000, -0.548300,0.161200,0.820600, 0.156200,0.551700, +-0.348895,0.080891,0.348895,0.000000, -0.697800,0.161200,0.697800, 0.125000,0.551700, +-0.277378,0.027069,0.415125,0.000000, -0.554700,0.054000,0.830300, 0.156200,0.517200, +-0.348895,0.080891,0.348895,0.000000, -0.697800,0.161200,0.697800, 0.125000,0.551700, +-0.353035,0.027069,0.353034,0.000000, -0.706100,0.054000,0.706100, 0.125000,0.517200, +-0.030034,0.497069,0.044948,0.000000, -0.061900,0.993700,0.092700, 0.476200,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +-0.038226,0.497069,0.038226,0.000000, -0.078800,0.993700,0.078800, 0.478000,0.962300, +-0.030034,-0.497069,0.044949,0.000000, -0.061900,-0.993700,0.092700, 0.156200,0.034500, +-0.059716,-0.488310,0.089370,0.000000, -0.121200,-0.975900,0.181400, 0.156200,0.069000, +-0.076004,-0.488310,0.076003,0.000000, -0.154300,-0.975900,0.154300, 0.125000,0.069000, +-0.030034,-0.497069,0.044949,0.000000, -0.061900,-0.993700,0.092700, 0.156200,0.034500, +-0.076004,-0.488310,0.076003,0.000000, -0.154300,-0.975900,0.154300, 0.125000,0.069000, +-0.038226,-0.497069,0.038226,0.000000, -0.078800,-0.993700,0.078800, 0.125000,0.034500, +-0.277378,-0.027069,0.415125,0.000000, -0.554700,-0.054000,0.830300, 0.156200,0.482800, +-0.277378,0.027069,0.415125,0.000000, -0.554700,0.054000,0.830300, 0.156200,0.517200, +-0.353035,0.027069,0.353034,0.000000, -0.706100,0.054000,0.706100, 0.125000,0.517200, +-0.277378,-0.027069,0.415125,0.000000, -0.554700,-0.054000,0.830300, 0.156200,0.482800, +-0.353035,0.027069,0.353034,0.000000, -0.706100,0.054000,0.706100, 0.125000,0.517200, +-0.353035,-0.027069,0.353034,0.000000, -0.706100,-0.054000,0.706100, 0.125000,0.482800, +-0.059716,0.488310,0.089370,0.000000, -0.121200,0.975900,0.181400, 0.156200,0.931000, +-0.030034,0.497069,0.044948,0.000000, -0.061900,0.993700,0.092700, 0.156200,0.965500, +-0.038226,0.497069,0.038226,0.000000, -0.078800,0.993700,0.078800, 0.125000,0.965500, +-0.059716,0.488310,0.089370,0.000000, -0.121200,0.975900,0.181400, 0.156200,0.931000, +-0.038226,0.497069,0.038226,0.000000, -0.078800,0.993700,0.078800, 0.125000,0.965500, +-0.076003,0.488310,0.076003,0.000000, -0.154300,0.975900,0.154300, 0.125000,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +-0.030034,-0.497069,0.044949,0.000000, -0.061900,-0.993700,0.092700, 0.423500,0.053800, +-0.038226,-0.497069,0.038226,0.000000, -0.078800,-0.993700,0.078800, 0.420900,0.053800, +-0.274125,-0.080891,0.410257,0.000000, -0.548300,-0.161200,0.820600, 0.156200,0.448300, +-0.277378,-0.027069,0.415125,0.000000, -0.554700,-0.054000,0.830300, 0.156200,0.482800, +-0.353035,-0.027069,0.353034,0.000000, -0.706100,-0.054000,0.706100, 0.125000,0.482800, +-0.274125,-0.080891,0.410257,0.000000, -0.548300,-0.161200,0.820600, 0.156200,0.448300, +-0.353035,-0.027069,0.353034,0.000000, -0.706100,-0.054000,0.706100, 0.125000,0.482800, +-0.348895,-0.080891,0.348895,0.000000, -0.697800,-0.161200,0.697800, 0.125000,0.448300, +-0.088698,0.473826,0.132745,0.000000, -0.179100,0.946600,0.268000, 0.156200,0.896600, +-0.059716,0.488310,0.089370,0.000000, -0.121200,0.975900,0.181400, 0.156200,0.931000, +-0.076003,0.488310,0.076003,0.000000, -0.154300,0.975900,0.154300, 0.125000,0.931000, +-0.088698,0.473826,0.132745,0.000000, -0.179100,0.946600,0.268000, 0.156200,0.896600, +-0.076003,0.488310,0.076003,0.000000, -0.154300,0.975900,0.154300, 0.125000,0.931000, +-0.112890,0.473826,0.112889,0.000000, -0.227900,0.946600,0.227900, 0.125000,0.896600, +-0.267660,-0.133764,0.400580,0.000000, -0.535400,-0.266600,0.801400, 0.156200,0.413800, +-0.274125,-0.080891,0.410257,0.000000, -0.548300,-0.161200,0.820600, 0.156200,0.448300, +-0.348895,-0.080891,0.348895,0.000000, -0.697800,-0.161200,0.697800, 0.125000,0.448300, +-0.267660,-0.133764,0.400580,0.000000, -0.535400,-0.266600,0.801400, 0.156200,0.413800, +-0.348895,-0.080891,0.348895,0.000000, -0.697800,-0.161200,0.697800, 0.125000,0.448300, +-0.340667,-0.133764,0.340666,0.000000, -0.681500,-0.266600,0.681500, 0.125000,0.413800, +-0.116639,0.453788,0.174562,0.000000, -0.234800,0.906300,0.351400, 0.156200,0.862100, +-0.088698,0.473826,0.132745,0.000000, -0.179100,0.946600,0.268000, 0.156200,0.896600, +-0.112890,0.473826,0.112889,0.000000, -0.227900,0.946600,0.227900, 0.125000,0.896600, +-0.116639,0.453788,0.174562,0.000000, -0.234800,0.906300,0.351400, 0.156200,0.862100, +-0.112890,0.473826,0.112889,0.000000, -0.227900,0.946600,0.227900, 0.125000,0.896600, +-0.148454,0.453788,0.148453,0.000000, -0.298900,0.906300,0.298900, 0.125000,0.862100, +-0.258056,-0.185069,0.386207,0.000000, -0.516300,-0.369000,0.772800, 0.156200,0.379300, +-0.267660,-0.133764,0.400580,0.000000, -0.535400,-0.266600,0.801400, 0.156200,0.413800, +-0.340667,-0.133764,0.340666,0.000000, -0.681500,-0.266600,0.681500, 0.125000,0.413800, +-0.258056,-0.185069,0.386207,0.000000, -0.516300,-0.369000,0.772800, 0.156200,0.379300, +-0.340667,-0.133764,0.340666,0.000000, -0.681500,-0.266600,0.681500, 0.125000,0.413800, +-0.328443,-0.185069,0.328443,0.000000, -0.657200,-0.369000,0.657200, 0.125000,0.379300, +-0.143213,0.428429,0.214333,0.000000, -0.287800,0.855300,0.430700, 0.156200,0.827600, +-0.116639,0.453788,0.174562,0.000000, -0.234800,0.906300,0.351400, 0.156200,0.862100, +-0.148454,0.453788,0.148453,0.000000, -0.298900,0.906300,0.298900, 0.125000,0.862100, +-0.143213,0.428429,0.214333,0.000000, -0.287800,0.855300,0.430700, 0.156200,0.827600, +-0.148454,0.453788,0.148453,0.000000, -0.298900,0.906300,0.298900, 0.125000,0.862100, +-0.182276,0.428429,0.182276,0.000000, -0.366300,0.855300,0.366300, 0.125000,0.827600, +-0.245427,-0.234204,0.367306,0.000000, -0.491300,-0.467000,0.735200, 0.156200,0.344800, +-0.258056,-0.185069,0.386207,0.000000, -0.516300,-0.369000,0.772800, 0.156200,0.379300, +-0.328443,-0.185069,0.328443,0.000000, -0.657200,-0.369000,0.657200, 0.125000,0.379300, +-0.245427,-0.234204,0.367306,0.000000, -0.491300,-0.467000,0.735200, 0.156200,0.344800, +-0.328443,-0.185069,0.328443,0.000000, -0.657200,-0.369000,0.657200, 0.125000,0.379300, +-0.312369,-0.234204,0.312368,0.000000, -0.625200,-0.467000,0.625200, 0.125000,0.344800, +-0.168108,0.398046,0.251592,0.000000, -0.337400,0.794500,0.505000, 0.156200,0.793100, +-0.143213,0.428429,0.214333,0.000000, -0.287800,0.855300,0.430700, 0.156200,0.827600, +-0.182276,0.428429,0.182276,0.000000, -0.366300,0.855300,0.366300, 0.125000,0.827600, +-0.168108,0.398046,0.251592,0.000000, -0.337400,0.794500,0.505000, 0.156200,0.793100, +-0.182276,0.428429,0.182276,0.000000, -0.366300,0.855300,0.366300, 0.125000,0.827600, +-0.213961,0.398046,0.213961,0.000000, -0.429400,0.794500,0.429400, 0.125000,0.793100, +-0.229920,-0.280594,0.344099,0.000000, -0.460400,-0.559600,0.689100, 0.156200,0.310300, +-0.245427,-0.234204,0.367306,0.000000, -0.491300,-0.467000,0.735200, 0.156200,0.344800, +-0.312369,-0.234204,0.312368,0.000000, -0.625200,-0.467000,0.625200, 0.125000,0.344800, +-0.229920,-0.280594,0.344099,0.000000, -0.460400,-0.559600,0.689100, 0.156200,0.310300, +-0.312369,-0.234204,0.312368,0.000000, -0.625200,-0.467000,0.625200, 0.125000,0.344800, +-0.292632,-0.280594,0.292632,0.000000, -0.586000,-0.559600,0.586000, 0.125000,0.310300, +-0.191033,0.362998,0.285900,0.000000, -0.383000,0.724300,0.573300, 0.156200,0.758600, +-0.168108,0.398046,0.251592,0.000000, -0.337400,0.794500,0.505000, 0.156200,0.793100, +-0.213961,0.398046,0.213961,0.000000, -0.429400,0.794500,0.429400, 0.125000,0.793100, +-0.191033,0.362998,0.285900,0.000000, -0.383000,0.724300,0.573300, 0.156200,0.758600, +-0.213961,0.398046,0.213961,0.000000, -0.429400,0.794500,0.429400, 0.125000,0.793100, +-0.243139,0.362998,0.243138,0.000000, -0.487500,0.724300,0.487500, 0.125000,0.758600, +-0.076003,0.488310,0.076003,0.000000, -0.154300,0.975900,0.154300, 0.125000,0.931000, +-0.038226,0.497069,0.038226,0.000000, -0.078800,0.993700,0.078800, 0.125000,0.965500, +-0.044949,0.497069,0.030034,0.000000, -0.092700,0.993700,0.061900, 0.093700,0.965500, +-0.076003,0.488310,0.076003,0.000000, -0.154300,0.975900,0.154300, 0.125000,0.931000, +-0.044949,0.497069,0.030034,0.000000, -0.092700,0.993700,0.061900, 0.093700,0.965500, +-0.089370,0.488310,0.059715,0.000000, -0.181400,0.975900,0.121200, 0.093700,0.931000, +-0.348895,-0.080891,0.348895,0.000000, -0.697800,-0.161200,0.697800, 0.125000,0.448300, +-0.353035,-0.027069,0.353034,0.000000, -0.706100,-0.054000,0.706100, 0.125000,0.482800, +-0.415125,-0.027069,0.277377,0.000000, -0.830300,-0.054000,0.554700, 0.093700,0.482800, +-0.348895,-0.080891,0.348895,0.000000, -0.697800,-0.161200,0.697800, 0.125000,0.448300, +-0.415125,-0.027069,0.277377,0.000000, -0.830300,-0.054000,0.554700, 0.093700,0.482800, +-0.410258,-0.080891,0.274125,0.000000, -0.820600,-0.161200,0.548300, 0.093700,0.448300, +-0.038226,-0.497069,0.038226,0.000000, -0.078800,-0.993700,0.078800, 0.125000,0.034500, +-0.076004,-0.488310,0.076003,0.000000, -0.154300,-0.975900,0.154300, 0.125000,0.069000, +-0.089371,-0.488310,0.059715,0.000000, -0.181400,-0.975900,0.121200, 0.093700,0.069000, +-0.038226,-0.497069,0.038226,0.000000, -0.078800,-0.993700,0.078800, 0.125000,0.034500, +-0.089371,-0.488310,0.059715,0.000000, -0.181400,-0.975900,0.121200, 0.093700,0.069000, +-0.044949,-0.497069,0.030034,0.000000, -0.092700,-0.993700,0.061900, 0.093700,0.034500, +-0.112890,0.473826,0.112889,0.000000, -0.227900,0.946600,0.227900, 0.125000,0.896600, +-0.076003,0.488310,0.076003,0.000000, -0.154300,0.975900,0.154300, 0.125000,0.931000, +-0.089370,0.488310,0.059715,0.000000, -0.181400,0.975900,0.121200, 0.093700,0.931000, +-0.112890,0.473826,0.112889,0.000000, -0.227900,0.946600,0.227900, 0.125000,0.896600, +-0.089370,0.488310,0.059715,0.000000, -0.181400,0.975900,0.121200, 0.093700,0.931000, +-0.132745,0.473826,0.088697,0.000000, -0.268000,0.946600,0.179100, 0.093700,0.896600, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +-0.038226,-0.497069,0.038226,0.000000, -0.078800,-0.993700,0.078800, 0.420900,0.053800, +-0.044949,-0.497069,0.030034,0.000000, -0.092700,-0.993700,0.061900, 0.418200,0.053800, +-0.148454,0.453788,0.148453,0.000000, -0.298900,0.906300,0.298900, 0.125000,0.862100, +-0.112890,0.473826,0.112889,0.000000, -0.227900,0.946600,0.227900, 0.125000,0.896600, +-0.132745,0.473826,0.088697,0.000000, -0.268000,0.946600,0.179100, 0.093700,0.896600, +-0.148454,0.453788,0.148453,0.000000, -0.298900,0.906300,0.298900, 0.125000,0.862100, +-0.132745,0.473826,0.088697,0.000000, -0.268000,0.946600,0.179100, 0.093700,0.896600, +-0.174562,0.453788,0.116638,0.000000, -0.351400,0.906300,0.234800, 0.093700,0.862100, +-0.182276,0.428429,0.182276,0.000000, -0.366300,0.855300,0.366300, 0.125000,0.827600, +-0.148454,0.453788,0.148453,0.000000, -0.298900,0.906300,0.298900, 0.125000,0.862100, +-0.174562,0.453788,0.116638,0.000000, -0.351400,0.906300,0.234800, 0.093700,0.862100, +-0.182276,0.428429,0.182276,0.000000, -0.366300,0.855300,0.366300, 0.125000,0.827600, +-0.174562,0.453788,0.116638,0.000000, -0.351400,0.906300,0.234800, 0.093700,0.862100, +-0.214334,0.428429,0.143213,0.000000, -0.430700,0.855300,0.287800, 0.093700,0.827600, +-0.340667,-0.133764,0.340666,0.000000, -0.681500,-0.266600,0.681500, 0.125000,0.413800, +-0.348895,-0.080891,0.348895,0.000000, -0.697800,-0.161200,0.697800, 0.125000,0.448300, +-0.410258,-0.080891,0.274125,0.000000, -0.820600,-0.161200,0.548300, 0.093700,0.448300, +-0.340667,-0.133764,0.340666,0.000000, -0.681500,-0.266600,0.681500, 0.125000,0.413800, +-0.410258,-0.080891,0.274125,0.000000, -0.820600,-0.161200,0.548300, 0.093700,0.448300, +-0.400581,-0.133764,0.267659,0.000000, -0.801400,-0.266600,0.535400, 0.093700,0.413800, +-0.213961,0.398046,0.213961,0.000000, -0.429400,0.794500,0.429400, 0.125000,0.793100, +-0.182276,0.428429,0.182276,0.000000, -0.366300,0.855300,0.366300, 0.125000,0.827600, +-0.214334,0.428429,0.143213,0.000000, -0.430700,0.855300,0.287800, 0.093700,0.827600, +-0.213961,0.398046,0.213961,0.000000, -0.429400,0.794500,0.429400, 0.125000,0.793100, +-0.214334,0.428429,0.143213,0.000000, -0.430700,0.855300,0.287800, 0.093700,0.827600, +-0.251592,0.398046,0.168108,0.000000, -0.505000,0.794500,0.337400, 0.093700,0.793100, +-0.328443,-0.185069,0.328443,0.000000, -0.657200,-0.369000,0.657200, 0.125000,0.379300, +-0.340667,-0.133764,0.340666,0.000000, -0.681500,-0.266600,0.681500, 0.125000,0.413800, +-0.400581,-0.133764,0.267659,0.000000, -0.801400,-0.266600,0.535400, 0.093700,0.413800, +-0.328443,-0.185069,0.328443,0.000000, -0.657200,-0.369000,0.657200, 0.125000,0.379300, +-0.400581,-0.133764,0.267659,0.000000, -0.801400,-0.266600,0.535400, 0.093700,0.413800, +-0.386208,-0.185069,0.258056,0.000000, -0.772800,-0.369000,0.516300, 0.093700,0.379300, +-0.243139,0.362998,0.243138,0.000000, -0.487500,0.724300,0.487500, 0.125000,0.758600, +-0.213961,0.398046,0.213961,0.000000, -0.429400,0.794500,0.429400, 0.125000,0.793100, +-0.251592,0.398046,0.168108,0.000000, -0.505000,0.794500,0.337400, 0.093700,0.793100, +-0.243139,0.362998,0.243138,0.000000, -0.487500,0.724300,0.487500, 0.125000,0.758600, +-0.251592,0.398046,0.168108,0.000000, -0.505000,0.794500,0.337400, 0.093700,0.793100, +-0.285901,0.362998,0.191032,0.000000, -0.573300,0.724300,0.383000, 0.093700,0.758600, +-0.312369,-0.234204,0.312368,0.000000, -0.625200,-0.467000,0.625200, 0.125000,0.344800, +-0.328443,-0.185069,0.328443,0.000000, -0.657200,-0.369000,0.657200, 0.125000,0.379300, +-0.386208,-0.185069,0.258056,0.000000, -0.772800,-0.369000,0.516300, 0.093700,0.379300, +-0.312369,-0.234204,0.312368,0.000000, -0.625200,-0.467000,0.625200, 0.125000,0.344800, +-0.386208,-0.185069,0.258056,0.000000, -0.772800,-0.369000,0.516300, 0.093700,0.379300, +-0.367307,-0.234204,0.245426,0.000000, -0.735200,-0.467000,0.491300, 0.093700,0.344800, +-0.269465,0.323693,0.269464,0.000000, -0.539900,0.645700,0.539900, 0.125000,0.724100, +-0.243139,0.362998,0.243138,0.000000, -0.487500,0.724300,0.487500, 0.125000,0.758600, +-0.285901,0.362998,0.191032,0.000000, -0.573300,0.724300,0.383000, 0.093700,0.758600, +-0.269465,0.323693,0.269464,0.000000, -0.539900,0.645700,0.539900, 0.125000,0.724100, +-0.285901,0.362998,0.191032,0.000000, -0.573300,0.724300,0.383000, 0.093700,0.758600, +-0.316857,0.323693,0.211717,0.000000, -0.634900,0.645700,0.424200, 0.093700,0.724100, +-0.292632,-0.280594,0.292632,0.000000, -0.586000,-0.559600,0.586000, 0.125000,0.310300, +-0.312369,-0.234204,0.312368,0.000000, -0.625200,-0.467000,0.625200, 0.125000,0.344800, +-0.367307,-0.234204,0.245426,0.000000, -0.735200,-0.467000,0.491300, 0.093700,0.344800, +-0.292632,-0.280594,0.292632,0.000000, -0.586000,-0.559600,0.586000, 0.125000,0.310300, +-0.367307,-0.234204,0.245426,0.000000, -0.735200,-0.467000,0.491300, 0.093700,0.344800, +-0.344099,-0.280594,0.229919,0.000000, -0.689100,-0.559600,0.460400, 0.093700,0.310300, +-0.292632,0.280594,0.292632,0.000000, -0.586000,0.559600,0.586000, 0.125000,0.689700, +-0.269465,0.323693,0.269464,0.000000, -0.539900,0.645700,0.539900, 0.125000,0.724100, +-0.316857,0.323693,0.211717,0.000000, -0.634900,0.645700,0.424200, 0.093700,0.724100, +-0.292632,0.280594,0.292632,0.000000, -0.586000,0.559600,0.586000, 0.125000,0.689700, +-0.316857,0.323693,0.211717,0.000000, -0.634900,0.645700,0.424200, 0.093700,0.724100, +-0.344099,0.280594,0.229919,0.000000, -0.689100,0.559600,0.460400, 0.093700,0.689700, +-0.269465,-0.323693,0.269464,0.000000, -0.539900,-0.645700,0.539900, 0.125000,0.275900, +-0.292632,-0.280594,0.292632,0.000000, -0.586000,-0.559600,0.586000, 0.125000,0.310300, +-0.344099,-0.280594,0.229919,0.000000, -0.689100,-0.559600,0.460400, 0.093700,0.310300, +-0.269465,-0.323693,0.269464,0.000000, -0.539900,-0.645700,0.539900, 0.125000,0.275900, +-0.344099,-0.280594,0.229919,0.000000, -0.689100,-0.559600,0.460400, 0.093700,0.310300, +-0.316857,-0.323693,0.211717,0.000000, -0.634900,-0.645700,0.424200, 0.093700,0.275900, +-0.312369,0.234204,0.312368,0.000000, -0.625200,0.467000,0.625200, 0.125000,0.655200, +-0.292632,0.280594,0.292632,0.000000, -0.586000,0.559600,0.586000, 0.125000,0.689700, +-0.344099,0.280594,0.229919,0.000000, -0.689100,0.559600,0.460400, 0.093700,0.689700, +-0.312369,0.234204,0.312368,0.000000, -0.625200,0.467000,0.625200, 0.125000,0.655200, +-0.344099,0.280594,0.229919,0.000000, -0.689100,0.559600,0.460400, 0.093700,0.689700, +-0.367307,0.234204,0.245426,0.000000, -0.735200,0.467000,0.491300, 0.093700,0.655200, +-0.243139,-0.362998,0.243138,0.000000, -0.487500,-0.724300,0.487500, 0.125000,0.241400, +-0.269465,-0.323693,0.269464,0.000000, -0.539900,-0.645700,0.539900, 0.125000,0.275900, +-0.316857,-0.323693,0.211717,0.000000, -0.634900,-0.645700,0.424200, 0.093700,0.275900, +-0.243139,-0.362998,0.243138,0.000000, -0.487500,-0.724300,0.487500, 0.125000,0.241400, +-0.316857,-0.323693,0.211717,0.000000, -0.634900,-0.645700,0.424200, 0.093700,0.275900, +-0.285901,-0.362998,0.191032,0.000000, -0.573300,-0.724300,0.383000, 0.093700,0.241400, +-0.328443,0.185069,0.328443,0.000000, -0.657200,0.369000,0.657200, 0.125000,0.620700, +-0.312369,0.234204,0.312368,0.000000, -0.625200,0.467000,0.625200, 0.125000,0.655200, +-0.367307,0.234204,0.245426,0.000000, -0.735200,0.467000,0.491300, 0.093700,0.655200, +-0.328443,0.185069,0.328443,0.000000, -0.657200,0.369000,0.657200, 0.125000,0.620700, +-0.367307,0.234204,0.245426,0.000000, -0.735200,0.467000,0.491300, 0.093700,0.655200, +-0.386208,0.185069,0.258056,0.000000, -0.772800,0.369000,0.516300, 0.093700,0.620700, +-0.213961,-0.398046,0.213961,0.000000, -0.429400,-0.794500,0.429400, 0.125000,0.206900, +-0.243139,-0.362998,0.243138,0.000000, -0.487500,-0.724300,0.487500, 0.125000,0.241400, +-0.285901,-0.362998,0.191032,0.000000, -0.573300,-0.724300,0.383000, 0.093700,0.241400, +-0.213961,-0.398046,0.213961,0.000000, -0.429400,-0.794500,0.429400, 0.125000,0.206900, +-0.285901,-0.362998,0.191032,0.000000, -0.573300,-0.724300,0.383000, 0.093700,0.241400, +-0.251592,-0.398046,0.168108,0.000000, -0.505000,-0.794500,0.337400, 0.093700,0.206900, +-0.340667,0.133764,0.340666,0.000000, -0.681500,0.266600,0.681500, 0.125000,0.586200, +-0.328443,0.185069,0.328443,0.000000, -0.657200,0.369000,0.657200, 0.125000,0.620700, +-0.386208,0.185069,0.258056,0.000000, -0.772800,0.369000,0.516300, 0.093700,0.620700, +-0.340667,0.133764,0.340666,0.000000, -0.681500,0.266600,0.681500, 0.125000,0.586200, +-0.386208,0.185069,0.258056,0.000000, -0.772800,0.369000,0.516300, 0.093700,0.620700, +-0.400581,0.133764,0.267659,0.000000, -0.801400,0.266600,0.535400, 0.093700,0.586200, +-0.182276,-0.428429,0.182276,0.000000, -0.366300,-0.855300,0.366300, 0.125000,0.172400, +-0.213961,-0.398046,0.213961,0.000000, -0.429400,-0.794500,0.429400, 0.125000,0.206900, +-0.251592,-0.398046,0.168108,0.000000, -0.505000,-0.794500,0.337400, 0.093700,0.206900, +-0.182276,-0.428429,0.182276,0.000000, -0.366300,-0.855300,0.366300, 0.125000,0.172400, +-0.251592,-0.398046,0.168108,0.000000, -0.505000,-0.794500,0.337400, 0.093700,0.206900, +-0.214334,-0.428429,0.143213,0.000000, -0.430700,-0.855300,0.287800, 0.093700,0.172400, +-0.348895,0.080891,0.348895,0.000000, -0.697800,0.161200,0.697800, 0.125000,0.551700, +-0.340667,0.133764,0.340666,0.000000, -0.681500,0.266600,0.681500, 0.125000,0.586200, +-0.400581,0.133764,0.267659,0.000000, -0.801400,0.266600,0.535400, 0.093700,0.586200, +-0.348895,0.080891,0.348895,0.000000, -0.697800,0.161200,0.697800, 0.125000,0.551700, +-0.400581,0.133764,0.267659,0.000000, -0.801400,0.266600,0.535400, 0.093700,0.586200, +-0.410258,0.080891,0.274125,0.000000, -0.820600,0.161200,0.548300, 0.093700,0.551700, +-0.148454,-0.453788,0.148453,0.000000, -0.298900,-0.906300,0.298900, 0.125000,0.137900, +-0.182276,-0.428429,0.182276,0.000000, -0.366300,-0.855300,0.366300, 0.125000,0.172400, +-0.214334,-0.428429,0.143213,0.000000, -0.430700,-0.855300,0.287800, 0.093700,0.172400, +-0.148454,-0.453788,0.148453,0.000000, -0.298900,-0.906300,0.298900, 0.125000,0.137900, +-0.214334,-0.428429,0.143213,0.000000, -0.430700,-0.855300,0.287800, 0.093700,0.172400, +-0.174562,-0.453788,0.116638,0.000000, -0.351400,-0.906300,0.234800, 0.093700,0.137900, +-0.353035,0.027069,0.353034,0.000000, -0.706100,0.054000,0.706100, 0.125000,0.517200, +-0.348895,0.080891,0.348895,0.000000, -0.697800,0.161200,0.697800, 0.125000,0.551700, +-0.410258,0.080891,0.274125,0.000000, -0.820600,0.161200,0.548300, 0.093700,0.551700, +-0.353035,0.027069,0.353034,0.000000, -0.706100,0.054000,0.706100, 0.125000,0.517200, +-0.410258,0.080891,0.274125,0.000000, -0.820600,0.161200,0.548300, 0.093700,0.551700, +-0.415125,0.027069,0.277377,0.000000, -0.830300,0.054000,0.554700, 0.093700,0.517200, +-0.112890,-0.473826,0.112890,0.000000, -0.227900,-0.946600,0.227900, 0.125000,0.103400, +-0.148454,-0.453788,0.148453,0.000000, -0.298900,-0.906300,0.298900, 0.125000,0.137900, +-0.174562,-0.453788,0.116638,0.000000, -0.351400,-0.906300,0.234800, 0.093700,0.137900, +-0.112890,-0.473826,0.112890,0.000000, -0.227900,-0.946600,0.227900, 0.125000,0.103400, +-0.174562,-0.453788,0.116638,0.000000, -0.351400,-0.906300,0.234800, 0.093700,0.137900, +-0.132745,-0.473826,0.088697,0.000000, -0.268000,-0.946600,0.179100, 0.093700,0.103400, +-0.038226,0.497069,0.038226,0.000000, -0.078800,0.993700,0.078800, 0.478000,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +-0.044949,0.497069,0.030034,0.000000, -0.092700,0.993700,0.061900, 0.479800,0.962300, +-0.353035,-0.027069,0.353034,0.000000, -0.706100,-0.054000,0.706100, 0.125000,0.482800, +-0.353035,0.027069,0.353034,0.000000, -0.706100,0.054000,0.706100, 0.125000,0.517200, +-0.415125,0.027069,0.277377,0.000000, -0.830300,0.054000,0.554700, 0.093700,0.517200, +-0.353035,-0.027069,0.353034,0.000000, -0.706100,-0.054000,0.706100, 0.125000,0.482800, +-0.415125,0.027069,0.277377,0.000000, -0.830300,0.054000,0.554700, 0.093700,0.517200, +-0.415125,-0.027069,0.277377,0.000000, -0.830300,-0.054000,0.554700, 0.093700,0.482800, +-0.076004,-0.488310,0.076003,0.000000, -0.154300,-0.975900,0.154300, 0.125000,0.069000, +-0.112890,-0.473826,0.112890,0.000000, -0.227900,-0.946600,0.227900, 0.125000,0.103400, +-0.132745,-0.473826,0.088697,0.000000, -0.268000,-0.946600,0.179100, 0.093700,0.103400, +-0.076004,-0.488310,0.076003,0.000000, -0.154300,-0.975900,0.154300, 0.125000,0.069000, +-0.132745,-0.473826,0.088697,0.000000, -0.268000,-0.946600,0.179100, 0.093700,0.103400, +-0.089371,-0.488310,0.059715,0.000000, -0.181400,-0.975900,0.121200, 0.093700,0.069000, +-0.285901,-0.362998,0.191032,0.000000, -0.573300,-0.724300,0.383000, 0.093700,0.241400, +-0.316857,-0.323693,0.211717,0.000000, -0.634900,-0.645700,0.424200, 0.093700,0.275900, +-0.352073,-0.323693,0.145833,0.000000, -0.705400,-0.645700,0.292200, 0.062500,0.275900, +-0.285901,-0.362998,0.191032,0.000000, -0.573300,-0.724300,0.383000, 0.093700,0.241400, +-0.352073,-0.323693,0.145833,0.000000, -0.705400,-0.645700,0.292200, 0.062500,0.275900, +-0.317676,-0.362998,0.131585,0.000000, -0.637000,-0.724300,0.263800, 0.062500,0.241400, +-0.344099,0.280594,0.229919,0.000000, -0.689100,0.559600,0.460400, 0.093700,0.689700, +-0.316857,0.323693,0.211717,0.000000, -0.634900,0.645700,0.424200, 0.093700,0.724100, +-0.352073,0.323693,0.145833,0.000000, -0.705400,0.645700,0.292200, 0.062500,0.724100, +-0.344099,0.280594,0.229919,0.000000, -0.689100,0.559600,0.460400, 0.093700,0.689700, +-0.352073,0.323693,0.145833,0.000000, -0.705400,0.645700,0.292200, 0.062500,0.724100, +-0.382342,0.280594,0.158371,0.000000, -0.765600,0.559600,0.317100, 0.062500,0.689700, +-0.251592,-0.398046,0.168108,0.000000, -0.505000,-0.794500,0.337400, 0.093700,0.206900, +-0.285901,-0.362998,0.191032,0.000000, -0.573300,-0.724300,0.383000, 0.093700,0.241400, +-0.317676,-0.362998,0.131585,0.000000, -0.637000,-0.724300,0.263800, 0.062500,0.241400, +-0.251592,-0.398046,0.168108,0.000000, -0.505000,-0.794500,0.337400, 0.093700,0.206900, +-0.317676,-0.362998,0.131585,0.000000, -0.637000,-0.724300,0.263800, 0.062500,0.241400, +-0.279554,-0.398046,0.115795,0.000000, -0.561100,-0.794500,0.232400, 0.062500,0.206900, +-0.367307,0.234204,0.245426,0.000000, -0.735200,0.467000,0.491300, 0.093700,0.655200, +-0.344099,0.280594,0.229919,0.000000, -0.689100,0.559600,0.460400, 0.093700,0.689700, +-0.382342,0.280594,0.158371,0.000000, -0.765600,0.559600,0.317100, 0.062500,0.689700, +-0.367307,0.234204,0.245426,0.000000, -0.735200,0.467000,0.491300, 0.093700,0.655200, +-0.382342,0.280594,0.158371,0.000000, -0.765600,0.559600,0.317100, 0.062500,0.689700, +-0.408129,0.234204,0.169052,0.000000, -0.816900,0.467000,0.338400, 0.062500,0.655200, +-0.214334,-0.428429,0.143213,0.000000, -0.430700,-0.855300,0.287800, 0.093700,0.172400, +-0.251592,-0.398046,0.168108,0.000000, -0.505000,-0.794500,0.337400, 0.093700,0.206900, +-0.279554,-0.398046,0.115795,0.000000, -0.561100,-0.794500,0.232400, 0.062500,0.206900, +-0.214334,-0.428429,0.143213,0.000000, -0.430700,-0.855300,0.287800, 0.093700,0.172400, +-0.279554,-0.398046,0.115795,0.000000, -0.561100,-0.794500,0.232400, 0.062500,0.206900, +-0.238155,-0.428429,0.098646,0.000000, -0.478600,-0.855300,0.198200, 0.062500,0.172400, +-0.386208,0.185069,0.258056,0.000000, -0.772800,0.369000,0.516300, 0.093700,0.620700, +-0.367307,0.234204,0.245426,0.000000, -0.735200,0.467000,0.491300, 0.093700,0.655200, +-0.408129,0.234204,0.169052,0.000000, -0.816900,0.467000,0.338400, 0.062500,0.655200, +-0.386208,0.185069,0.258056,0.000000, -0.772800,0.369000,0.516300, 0.093700,0.620700, +-0.408129,0.234204,0.169052,0.000000, -0.816900,0.467000,0.338400, 0.062500,0.655200, +-0.429131,0.185069,0.177751,0.000000, -0.858700,0.369000,0.355700, 0.062500,0.620700, +-0.174562,-0.453788,0.116638,0.000000, -0.351400,-0.906300,0.234800, 0.093700,0.137900, +-0.214334,-0.428429,0.143213,0.000000, -0.430700,-0.855300,0.287800, 0.093700,0.172400, +-0.238155,-0.428429,0.098646,0.000000, -0.478600,-0.855300,0.198200, 0.062500,0.172400, +-0.174562,-0.453788,0.116638,0.000000, -0.351400,-0.906300,0.234800, 0.093700,0.137900, +-0.238155,-0.428429,0.098646,0.000000, -0.478600,-0.855300,0.198200, 0.062500,0.172400, +-0.193963,-0.453788,0.080342,0.000000, -0.390500,-0.906300,0.161700, 0.062500,0.137900, +-0.400581,0.133764,0.267659,0.000000, -0.801400,0.266600,0.535400, 0.093700,0.586200, +-0.386208,0.185069,0.258056,0.000000, -0.772800,0.369000,0.516300, 0.093700,0.620700, +-0.429131,0.185069,0.177751,0.000000, -0.858700,0.369000,0.355700, 0.062500,0.620700, +-0.400581,0.133764,0.267659,0.000000, -0.801400,0.266600,0.535400, 0.093700,0.586200, +-0.429131,0.185069,0.177751,0.000000, -0.858700,0.369000,0.355700, 0.062500,0.620700, +-0.445102,0.133764,0.184367,0.000000, -0.890400,0.266600,0.368800, 0.062500,0.586200, +-0.132745,-0.473826,0.088697,0.000000, -0.268000,-0.946600,0.179100, 0.093700,0.103400, +-0.174562,-0.453788,0.116638,0.000000, -0.351400,-0.906300,0.234800, 0.093700,0.137900, +-0.193963,-0.453788,0.080342,0.000000, -0.390500,-0.906300,0.161700, 0.062500,0.137900, +-0.132745,-0.473826,0.088697,0.000000, -0.268000,-0.946600,0.179100, 0.093700,0.103400, +-0.193963,-0.453788,0.080342,0.000000, -0.390500,-0.906300,0.161700, 0.062500,0.137900, +-0.147499,-0.473826,0.061095,0.000000, -0.297800,-0.946600,0.123300, 0.062500,0.103400, +-0.410258,0.080891,0.274125,0.000000, -0.820600,0.161200,0.548300, 0.093700,0.551700, +-0.400581,0.133764,0.267659,0.000000, -0.801400,0.266600,0.535400, 0.093700,0.586200, +-0.445102,0.133764,0.184367,0.000000, -0.890400,0.266600,0.368800, 0.062500,0.586200, +-0.410258,0.080891,0.274125,0.000000, -0.820600,0.161200,0.548300, 0.093700,0.551700, +-0.445102,0.133764,0.184367,0.000000, -0.890400,0.266600,0.368800, 0.062500,0.586200, +-0.455854,0.080891,0.188820,0.000000, -0.911800,0.161200,0.377700, 0.062500,0.551700, +-0.089371,-0.488310,0.059715,0.000000, -0.181400,-0.975900,0.121200, 0.093700,0.069000, +-0.132745,-0.473826,0.088697,0.000000, -0.268000,-0.946600,0.179100, 0.093700,0.103400, +-0.147499,-0.473826,0.061095,0.000000, -0.297800,-0.946600,0.123300, 0.062500,0.103400, +-0.089371,-0.488310,0.059715,0.000000, -0.181400,-0.975900,0.121200, 0.093700,0.069000, +-0.147499,-0.473826,0.061095,0.000000, -0.297800,-0.946600,0.123300, 0.062500,0.103400, +-0.099303,-0.488310,0.041132,0.000000, -0.201600,-0.975900,0.083500, 0.062500,0.069000, +-0.415125,0.027069,0.277377,0.000000, -0.830300,0.054000,0.554700, 0.093700,0.517200, +-0.410258,0.080891,0.274125,0.000000, -0.820600,0.161200,0.548300, 0.093700,0.551700, +-0.455854,0.080891,0.188820,0.000000, -0.911800,0.161200,0.377700, 0.062500,0.551700, +-0.415125,0.027069,0.277377,0.000000, -0.830300,0.054000,0.554700, 0.093700,0.517200, +-0.455854,0.080891,0.188820,0.000000, -0.911800,0.161200,0.377700, 0.062500,0.551700, +-0.461262,0.027069,0.191060,0.000000, -0.922500,0.054000,0.382100, 0.062500,0.517200, +-0.044949,0.497069,0.030034,0.000000, -0.092700,0.993700,0.061900, 0.479800,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +-0.049945,0.497069,0.020688,0.000000, -0.103000,0.993700,0.042600, 0.481700,0.962300, +-0.044949,-0.497069,0.030034,0.000000, -0.092700,-0.993700,0.061900, 0.093700,0.034500, +-0.089371,-0.488310,0.059715,0.000000, -0.181400,-0.975900,0.121200, 0.093700,0.069000, +-0.099303,-0.488310,0.041132,0.000000, -0.201600,-0.975900,0.083500, 0.062500,0.069000, +-0.044949,-0.497069,0.030034,0.000000, -0.092700,-0.993700,0.061900, 0.093700,0.034500, +-0.099303,-0.488310,0.041132,0.000000, -0.201600,-0.975900,0.083500, 0.062500,0.069000, +-0.049945,-0.497069,0.020688,0.000000, -0.103000,-0.993700,0.042600, 0.062500,0.034500, +-0.415125,-0.027069,0.277377,0.000000, -0.830300,-0.054000,0.554700, 0.093700,0.482800, +-0.415125,0.027069,0.277377,0.000000, -0.830300,0.054000,0.554700, 0.093700,0.517200, +-0.461262,0.027069,0.191060,0.000000, -0.922500,0.054000,0.382100, 0.062500,0.517200, +-0.415125,-0.027069,0.277377,0.000000, -0.830300,-0.054000,0.554700, 0.093700,0.482800, +-0.461262,0.027069,0.191060,0.000000, -0.922500,0.054000,0.382100, 0.062500,0.517200, +-0.461262,-0.027069,0.191060,0.000000, -0.922500,-0.054000,0.382100, 0.062500,0.482800, +-0.089370,0.488310,0.059715,0.000000, -0.181400,0.975900,0.121200, 0.093700,0.931000, +-0.044949,0.497069,0.030034,0.000000, -0.092700,0.993700,0.061900, 0.093700,0.965500, +-0.049945,0.497069,0.020688,0.000000, -0.103000,0.993700,0.042600, 0.062500,0.965500, +-0.089370,0.488310,0.059715,0.000000, -0.181400,0.975900,0.121200, 0.093700,0.931000, +-0.049945,0.497069,0.020688,0.000000, -0.103000,0.993700,0.042600, 0.062500,0.965500, +-0.099303,0.488310,0.041132,0.000000, -0.201600,0.975900,0.083500, 0.062500,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +-0.044949,-0.497069,0.030034,0.000000, -0.092700,-0.993700,0.061900, 0.418200,0.053800, +-0.049945,-0.497069,0.020688,0.000000, -0.103000,-0.993700,0.042600, 0.415600,0.053800, +-0.410258,-0.080891,0.274125,0.000000, -0.820600,-0.161200,0.548300, 0.093700,0.448300, +-0.415125,-0.027069,0.277377,0.000000, -0.830300,-0.054000,0.554700, 0.093700,0.482800, +-0.461262,-0.027069,0.191060,0.000000, -0.922500,-0.054000,0.382100, 0.062500,0.482800, +-0.410258,-0.080891,0.274125,0.000000, -0.820600,-0.161200,0.548300, 0.093700,0.448300, +-0.461262,-0.027069,0.191060,0.000000, -0.922500,-0.054000,0.382100, 0.062500,0.482800, +-0.455854,-0.080891,0.188820,0.000000, -0.911800,-0.161200,0.377700, 0.062500,0.448300, +-0.132745,0.473826,0.088697,0.000000, -0.268000,0.946600,0.179100, 0.093700,0.896600, +-0.089370,0.488310,0.059715,0.000000, -0.181400,0.975900,0.121200, 0.093700,0.931000, +-0.099303,0.488310,0.041132,0.000000, -0.201600,0.975900,0.083500, 0.062500,0.931000, +-0.132745,0.473826,0.088697,0.000000, -0.268000,0.946600,0.179100, 0.093700,0.896600, +-0.099303,0.488310,0.041132,0.000000, -0.201600,0.975900,0.083500, 0.062500,0.931000, +-0.147498,0.473826,0.061095,0.000000, -0.297800,0.946600,0.123300, 0.062500,0.896600, +-0.400581,-0.133764,0.267659,0.000000, -0.801400,-0.266600,0.535400, 0.093700,0.413800, +-0.410258,-0.080891,0.274125,0.000000, -0.820600,-0.161200,0.548300, 0.093700,0.448300, +-0.455854,-0.080891,0.188820,0.000000, -0.911800,-0.161200,0.377700, 0.062500,0.448300, +-0.400581,-0.133764,0.267659,0.000000, -0.801400,-0.266600,0.535400, 0.093700,0.413800, +-0.455854,-0.080891,0.188820,0.000000, -0.911800,-0.161200,0.377700, 0.062500,0.448300, +-0.445102,-0.133764,0.184367,0.000000, -0.890400,-0.266600,0.368800, 0.062500,0.413800, +-0.174562,0.453788,0.116638,0.000000, -0.351400,0.906300,0.234800, 0.093700,0.862100, +-0.132745,0.473826,0.088697,0.000000, -0.268000,0.946600,0.179100, 0.093700,0.896600, +-0.147498,0.473826,0.061095,0.000000, -0.297800,0.946600,0.123300, 0.062500,0.896600, +-0.174562,0.453788,0.116638,0.000000, -0.351400,0.906300,0.234800, 0.093700,0.862100, +-0.147498,0.473826,0.061095,0.000000, -0.297800,0.946600,0.123300, 0.062500,0.896600, +-0.193963,0.453788,0.080342,0.000000, -0.390500,0.906300,0.161700, 0.062500,0.862100, +-0.386208,-0.185069,0.258056,0.000000, -0.772800,-0.369000,0.516300, 0.093700,0.379300, +-0.400581,-0.133764,0.267659,0.000000, -0.801400,-0.266600,0.535400, 0.093700,0.413800, +-0.445102,-0.133764,0.184367,0.000000, -0.890400,-0.266600,0.368800, 0.062500,0.413800, +-0.386208,-0.185069,0.258056,0.000000, -0.772800,-0.369000,0.516300, 0.093700,0.379300, +-0.445102,-0.133764,0.184367,0.000000, -0.890400,-0.266600,0.368800, 0.062500,0.413800, +-0.429131,-0.185069,0.177751,0.000000, -0.858700,-0.369000,0.355700, 0.062500,0.379300, +-0.214334,0.428429,0.143213,0.000000, -0.430700,0.855300,0.287800, 0.093700,0.827600, +-0.174562,0.453788,0.116638,0.000000, -0.351400,0.906300,0.234800, 0.093700,0.862100, +-0.193963,0.453788,0.080342,0.000000, -0.390500,0.906300,0.161700, 0.062500,0.862100, +-0.214334,0.428429,0.143213,0.000000, -0.430700,0.855300,0.287800, 0.093700,0.827600, +-0.193963,0.453788,0.080342,0.000000, -0.390500,0.906300,0.161700, 0.062500,0.862100, +-0.238155,0.428429,0.098646,0.000000, -0.478600,0.855300,0.198200, 0.062500,0.827600, +-0.367307,-0.234204,0.245426,0.000000, -0.735200,-0.467000,0.491300, 0.093700,0.344800, +-0.386208,-0.185069,0.258056,0.000000, -0.772800,-0.369000,0.516300, 0.093700,0.379300, +-0.429131,-0.185069,0.177751,0.000000, -0.858700,-0.369000,0.355700, 0.062500,0.379300, +-0.367307,-0.234204,0.245426,0.000000, -0.735200,-0.467000,0.491300, 0.093700,0.344800, +-0.429131,-0.185069,0.177751,0.000000, -0.858700,-0.369000,0.355700, 0.062500,0.379300, +-0.408129,-0.234204,0.169052,0.000000, -0.816900,-0.467000,0.338400, 0.062500,0.344800, +-0.251592,0.398046,0.168108,0.000000, -0.505000,0.794500,0.337400, 0.093700,0.793100, +-0.214334,0.428429,0.143213,0.000000, -0.430700,0.855300,0.287800, 0.093700,0.827600, +-0.238155,0.428429,0.098646,0.000000, -0.478600,0.855300,0.198200, 0.062500,0.827600, +-0.251592,0.398046,0.168108,0.000000, -0.505000,0.794500,0.337400, 0.093700,0.793100, +-0.238155,0.428429,0.098646,0.000000, -0.478600,0.855300,0.198200, 0.062500,0.827600, +-0.279554,0.398046,0.115795,0.000000, -0.561100,0.794500,0.232400, 0.062500,0.793100, +-0.344099,-0.280594,0.229919,0.000000, -0.689100,-0.559600,0.460400, 0.093700,0.310300, +-0.367307,-0.234204,0.245426,0.000000, -0.735200,-0.467000,0.491300, 0.093700,0.344800, +-0.408129,-0.234204,0.169052,0.000000, -0.816900,-0.467000,0.338400, 0.062500,0.344800, +-0.344099,-0.280594,0.229919,0.000000, -0.689100,-0.559600,0.460400, 0.093700,0.310300, +-0.408129,-0.234204,0.169052,0.000000, -0.816900,-0.467000,0.338400, 0.062500,0.344800, +-0.382342,-0.280594,0.158371,0.000000, -0.765600,-0.559600,0.317100, 0.062500,0.310300, +-0.285901,0.362998,0.191032,0.000000, -0.573300,0.724300,0.383000, 0.093700,0.758600, +-0.251592,0.398046,0.168108,0.000000, -0.505000,0.794500,0.337400, 0.093700,0.793100, +-0.279554,0.398046,0.115795,0.000000, -0.561100,0.794500,0.232400, 0.062500,0.793100, +-0.285901,0.362998,0.191032,0.000000, -0.573300,0.724300,0.383000, 0.093700,0.758600, +-0.279554,0.398046,0.115795,0.000000, -0.561100,0.794500,0.232400, 0.062500,0.793100, +-0.317676,0.362998,0.131585,0.000000, -0.637000,0.724300,0.263800, 0.062500,0.758600, +-0.316857,-0.323693,0.211717,0.000000, -0.634900,-0.645700,0.424200, 0.093700,0.275900, +-0.344099,-0.280594,0.229919,0.000000, -0.689100,-0.559600,0.460400, 0.093700,0.310300, +-0.382342,-0.280594,0.158371,0.000000, -0.765600,-0.559600,0.317100, 0.062500,0.310300, +-0.316857,-0.323693,0.211717,0.000000, -0.634900,-0.645700,0.424200, 0.093700,0.275900, +-0.382342,-0.280594,0.158371,0.000000, -0.765600,-0.559600,0.317100, 0.062500,0.310300, +-0.352073,-0.323693,0.145833,0.000000, -0.705400,-0.645700,0.292200, 0.062500,0.275900, +-0.316857,0.323693,0.211717,0.000000, -0.634900,0.645700,0.424200, 0.093700,0.724100, +-0.285901,0.362998,0.191032,0.000000, -0.573300,0.724300,0.383000, 0.093700,0.758600, +-0.317676,0.362998,0.131585,0.000000, -0.637000,0.724300,0.263800, 0.062500,0.758600, +-0.316857,0.323693,0.211717,0.000000, -0.634900,0.645700,0.424200, 0.093700,0.724100, +-0.317676,0.362998,0.131585,0.000000, -0.637000,0.724300,0.263800, 0.062500,0.758600, +-0.352073,0.323693,0.145833,0.000000, -0.705400,0.645700,0.292200, 0.062500,0.724100, +-0.445102,-0.133764,0.184367,0.000000, -0.890400,-0.266600,0.368800, 0.062500,0.413800, +-0.455854,-0.080891,0.188820,0.000000, -0.911800,-0.161200,0.377700, 0.062500,0.448300, +-0.483932,-0.080891,0.096260,0.000000, -0.967900,-0.161200,0.192500, 0.031200,0.448300, +-0.445102,-0.133764,0.184367,0.000000, -0.890400,-0.266600,0.368800, 0.062500,0.413800, +-0.483932,-0.080891,0.096260,0.000000, -0.967900,-0.161200,0.192500, 0.031200,0.448300, +-0.472517,-0.133764,0.093989,0.000000, -0.945200,-0.266600,0.188000, 0.031200,0.413800, +-0.193963,0.453788,0.080342,0.000000, -0.390500,0.906300,0.161700, 0.062500,0.862100, +-0.147498,0.473826,0.061095,0.000000, -0.297800,0.946600,0.123300, 0.062500,0.896600, +-0.156583,0.473826,0.031146,0.000000, -0.316100,0.946600,0.062900, 0.031200,0.896600, +-0.193963,0.453788,0.080342,0.000000, -0.390500,0.906300,0.161700, 0.062500,0.862100, +-0.156583,0.473826,0.031146,0.000000, -0.316100,0.946600,0.062900, 0.031200,0.896600, +-0.205911,0.453788,0.040958,0.000000, -0.414500,0.906300,0.082400, 0.031200,0.862100, +-0.429131,-0.185069,0.177751,0.000000, -0.858700,-0.369000,0.355700, 0.062500,0.379300, +-0.445102,-0.133764,0.184367,0.000000, -0.890400,-0.266600,0.368800, 0.062500,0.413800, +-0.472517,-0.133764,0.093989,0.000000, -0.945200,-0.266600,0.188000, 0.031200,0.413800, +-0.429131,-0.185069,0.177751,0.000000, -0.858700,-0.369000,0.355700, 0.062500,0.379300, +-0.472517,-0.133764,0.093989,0.000000, -0.945200,-0.266600,0.188000, 0.031200,0.413800, +-0.455563,-0.185069,0.090617,0.000000, -0.911600,-0.369000,0.181300, 0.031200,0.379300, +-0.238155,0.428429,0.098646,0.000000, -0.478600,0.855300,0.198200, 0.062500,0.827600, +-0.193963,0.453788,0.080342,0.000000, -0.390500,0.906300,0.161700, 0.062500,0.862100, +-0.205911,0.453788,0.040958,0.000000, -0.414500,0.906300,0.082400, 0.031200,0.862100, +-0.238155,0.428429,0.098646,0.000000, -0.478600,0.855300,0.198200, 0.062500,0.827600, +-0.205911,0.453788,0.040958,0.000000, -0.414500,0.906300,0.082400, 0.031200,0.862100, +-0.252824,0.428429,0.050290,0.000000, -0.508100,0.855300,0.101000, 0.031200,0.827600, +-0.408129,-0.234204,0.169052,0.000000, -0.816900,-0.467000,0.338400, 0.062500,0.344800, +-0.429131,-0.185069,0.177751,0.000000, -0.858700,-0.369000,0.355700, 0.062500,0.379300, +-0.455563,-0.185069,0.090617,0.000000, -0.911600,-0.369000,0.181300, 0.031200,0.379300, +-0.408129,-0.234204,0.169052,0.000000, -0.816900,-0.467000,0.338400, 0.062500,0.344800, +-0.455563,-0.185069,0.090617,0.000000, -0.911600,-0.369000,0.181300, 0.031200,0.379300, +-0.433268,-0.234204,0.086182,0.000000, -0.867200,-0.467000,0.172500, 0.031200,0.344800, +-0.279554,0.398046,0.115795,0.000000, -0.561100,0.794500,0.232400, 0.062500,0.793100, +-0.238155,0.428429,0.098646,0.000000, -0.478600,0.855300,0.198200, 0.062500,0.827600, +-0.252824,0.428429,0.050290,0.000000, -0.508100,0.855300,0.101000, 0.031200,0.827600, +-0.279554,0.398046,0.115795,0.000000, -0.561100,0.794500,0.232400, 0.062500,0.793100, +-0.252824,0.428429,0.050290,0.000000, -0.508100,0.855300,0.101000, 0.031200,0.827600, +-0.296773,0.398046,0.059032,0.000000, -0.595600,0.794500,0.118500, 0.031200,0.793100, +-0.382342,-0.280594,0.158371,0.000000, -0.765600,-0.559600,0.317100, 0.062500,0.310300, +-0.408129,-0.234204,0.169052,0.000000, -0.816900,-0.467000,0.338400, 0.062500,0.344800, +-0.433268,-0.234204,0.086182,0.000000, -0.867200,-0.467000,0.172500, 0.031200,0.344800, +-0.382342,-0.280594,0.158371,0.000000, -0.765600,-0.559600,0.317100, 0.062500,0.310300, +-0.433268,-0.234204,0.086182,0.000000, -0.867200,-0.467000,0.172500, 0.031200,0.344800, +-0.405892,-0.280594,0.080737,0.000000, -0.812800,-0.559600,0.161700, 0.031200,0.310300, +-0.317676,0.362998,0.131585,0.000000, -0.637000,0.724300,0.263800, 0.062500,0.758600, +-0.279554,0.398046,0.115795,0.000000, -0.561100,0.794500,0.232400, 0.062500,0.793100, +-0.296773,0.398046,0.059032,0.000000, -0.595600,0.794500,0.118500, 0.031200,0.793100, +-0.317676,0.362998,0.131585,0.000000, -0.637000,0.724300,0.263800, 0.062500,0.758600, +-0.296773,0.398046,0.059032,0.000000, -0.595600,0.794500,0.118500, 0.031200,0.793100, +-0.337243,0.362998,0.067082,0.000000, -0.676200,0.724300,0.134500, 0.031200,0.758600, +-0.352073,-0.323693,0.145833,0.000000, -0.705400,-0.645700,0.292200, 0.062500,0.275900, +-0.382342,-0.280594,0.158371,0.000000, -0.765600,-0.559600,0.317100, 0.062500,0.310300, +-0.405892,-0.280594,0.080737,0.000000, -0.812800,-0.559600,0.161700, 0.031200,0.310300, +-0.352073,-0.323693,0.145833,0.000000, -0.705400,-0.645700,0.292200, 0.062500,0.275900, +-0.405892,-0.280594,0.080737,0.000000, -0.812800,-0.559600,0.161700, 0.031200,0.310300, +-0.373758,-0.323693,0.074345,0.000000, -0.748900,-0.645700,0.149000, 0.031200,0.275900, +-0.352073,0.323693,0.145833,0.000000, -0.705400,0.645700,0.292200, 0.062500,0.724100, +-0.317676,0.362998,0.131585,0.000000, -0.637000,0.724300,0.263800, 0.062500,0.758600, +-0.337243,0.362998,0.067082,0.000000, -0.676200,0.724300,0.134500, 0.031200,0.758600, +-0.352073,0.323693,0.145833,0.000000, -0.705400,0.645700,0.292200, 0.062500,0.724100, +-0.337243,0.362998,0.067082,0.000000, -0.676200,0.724300,0.134500, 0.031200,0.758600, +-0.373758,0.323693,0.074345,0.000000, -0.748900,0.645700,0.149000, 0.031200,0.724100, +-0.317676,-0.362998,0.131585,0.000000, -0.637000,-0.724300,0.263800, 0.062500,0.241400, +-0.352073,-0.323693,0.145833,0.000000, -0.705400,-0.645700,0.292200, 0.062500,0.275900, +-0.373758,-0.323693,0.074345,0.000000, -0.748900,-0.645700,0.149000, 0.031200,0.275900, +-0.317676,-0.362998,0.131585,0.000000, -0.637000,-0.724300,0.263800, 0.062500,0.241400, +-0.373758,-0.323693,0.074345,0.000000, -0.748900,-0.645700,0.149000, 0.031200,0.275900, +-0.337243,-0.362998,0.067082,0.000000, -0.676200,-0.724300,0.134500, 0.031200,0.241400, +-0.382342,0.280594,0.158371,0.000000, -0.765600,0.559600,0.317100, 0.062500,0.689700, +-0.352073,0.323693,0.145833,0.000000, -0.705400,0.645700,0.292200, 0.062500,0.724100, +-0.373758,0.323693,0.074345,0.000000, -0.748900,0.645700,0.149000, 0.031200,0.724100, +-0.382342,0.280594,0.158371,0.000000, -0.765600,0.559600,0.317100, 0.062500,0.689700, +-0.373758,0.323693,0.074345,0.000000, -0.748900,0.645700,0.149000, 0.031200,0.724100, +-0.405892,0.280594,0.080737,0.000000, -0.812800,0.559600,0.161700, 0.031200,0.689700, +-0.279554,-0.398046,0.115795,0.000000, -0.561100,-0.794500,0.232400, 0.062500,0.206900, +-0.317676,-0.362998,0.131585,0.000000, -0.637000,-0.724300,0.263800, 0.062500,0.241400, +-0.337243,-0.362998,0.067082,0.000000, -0.676200,-0.724300,0.134500, 0.031200,0.241400, +-0.279554,-0.398046,0.115795,0.000000, -0.561100,-0.794500,0.232400, 0.062500,0.206900, +-0.337243,-0.362998,0.067082,0.000000, -0.676200,-0.724300,0.134500, 0.031200,0.241400, +-0.296773,-0.398046,0.059032,0.000000, -0.595600,-0.794500,0.118500, 0.031200,0.206900, +-0.408129,0.234204,0.169052,0.000000, -0.816900,0.467000,0.338400, 0.062500,0.655200, +-0.382342,0.280594,0.158371,0.000000, -0.765600,0.559600,0.317100, 0.062500,0.689700, +-0.405892,0.280594,0.080737,0.000000, -0.812800,0.559600,0.161700, 0.031200,0.689700, +-0.408129,0.234204,0.169052,0.000000, -0.816900,0.467000,0.338400, 0.062500,0.655200, +-0.405892,0.280594,0.080737,0.000000, -0.812800,0.559600,0.161700, 0.031200,0.689700, +-0.433268,0.234204,0.086182,0.000000, -0.867200,0.467000,0.172500, 0.031200,0.655200, +-0.238155,-0.428429,0.098646,0.000000, -0.478600,-0.855300,0.198200, 0.062500,0.172400, +-0.279554,-0.398046,0.115795,0.000000, -0.561100,-0.794500,0.232400, 0.062500,0.206900, +-0.296773,-0.398046,0.059032,0.000000, -0.595600,-0.794500,0.118500, 0.031200,0.206900, +-0.238155,-0.428429,0.098646,0.000000, -0.478600,-0.855300,0.198200, 0.062500,0.172400, +-0.296773,-0.398046,0.059032,0.000000, -0.595600,-0.794500,0.118500, 0.031200,0.206900, +-0.252824,-0.428429,0.050290,0.000000, -0.508100,-0.855300,0.101000, 0.031200,0.172400, +-0.429131,0.185069,0.177751,0.000000, -0.858700,0.369000,0.355700, 0.062500,0.620700, +-0.408129,0.234204,0.169052,0.000000, -0.816900,0.467000,0.338400, 0.062500,0.655200, +-0.433268,0.234204,0.086182,0.000000, -0.867200,0.467000,0.172500, 0.031200,0.655200, +-0.429131,0.185069,0.177751,0.000000, -0.858700,0.369000,0.355700, 0.062500,0.620700, +-0.433268,0.234204,0.086182,0.000000, -0.867200,0.467000,0.172500, 0.031200,0.655200, +-0.455563,0.185069,0.090617,0.000000, -0.911600,0.369000,0.181300, 0.031200,0.620700, +-0.193963,-0.453788,0.080342,0.000000, -0.390500,-0.906300,0.161700, 0.062500,0.137900, +-0.238155,-0.428429,0.098646,0.000000, -0.478600,-0.855300,0.198200, 0.062500,0.172400, +-0.252824,-0.428429,0.050290,0.000000, -0.508100,-0.855300,0.101000, 0.031200,0.172400, +-0.193963,-0.453788,0.080342,0.000000, -0.390500,-0.906300,0.161700, 0.062500,0.137900, +-0.252824,-0.428429,0.050290,0.000000, -0.508100,-0.855300,0.101000, 0.031200,0.172400, +-0.205911,-0.453788,0.040958,0.000000, -0.414500,-0.906300,0.082400, 0.031200,0.137900, +-0.445102,0.133764,0.184367,0.000000, -0.890400,0.266600,0.368800, 0.062500,0.586200, +-0.429131,0.185069,0.177751,0.000000, -0.858700,0.369000,0.355700, 0.062500,0.620700, +-0.455563,0.185069,0.090617,0.000000, -0.911600,0.369000,0.181300, 0.031200,0.620700, +-0.445102,0.133764,0.184367,0.000000, -0.890400,0.266600,0.368800, 0.062500,0.586200, +-0.455563,0.185069,0.090617,0.000000, -0.911600,0.369000,0.181300, 0.031200,0.620700, +-0.472517,0.133764,0.093989,0.000000, -0.945200,0.266600,0.188000, 0.031200,0.586200, +-0.147499,-0.473826,0.061095,0.000000, -0.297800,-0.946600,0.123300, 0.062500,0.103400, +-0.193963,-0.453788,0.080342,0.000000, -0.390500,-0.906300,0.161700, 0.062500,0.137900, +-0.205911,-0.453788,0.040958,0.000000, -0.414500,-0.906300,0.082400, 0.031200,0.137900, +-0.147499,-0.473826,0.061095,0.000000, -0.297800,-0.946600,0.123300, 0.062500,0.103400, +-0.205911,-0.453788,0.040958,0.000000, -0.414500,-0.906300,0.082400, 0.031200,0.137900, +-0.156584,-0.473826,0.031147,0.000000, -0.316100,-0.946600,0.062900, 0.031200,0.103400, +-0.455854,0.080891,0.188820,0.000000, -0.911800,0.161200,0.377700, 0.062500,0.551700, +-0.445102,0.133764,0.184367,0.000000, -0.890400,0.266600,0.368800, 0.062500,0.586200, +-0.472517,0.133764,0.093989,0.000000, -0.945200,0.266600,0.188000, 0.031200,0.586200, +-0.455854,0.080891,0.188820,0.000000, -0.911800,0.161200,0.377700, 0.062500,0.551700, +-0.472517,0.133764,0.093989,0.000000, -0.945200,0.266600,0.188000, 0.031200,0.586200, +-0.483932,0.080891,0.096260,0.000000, -0.967900,0.161200,0.192500, 0.031200,0.551700, +-0.099303,-0.488310,0.041132,0.000000, -0.201600,-0.975900,0.083500, 0.062500,0.069000, +-0.147499,-0.473826,0.061095,0.000000, -0.297800,-0.946600,0.123300, 0.062500,0.103400, +-0.156584,-0.473826,0.031147,0.000000, -0.316100,-0.946600,0.062900, 0.031200,0.103400, +-0.099303,-0.488310,0.041132,0.000000, -0.201600,-0.975900,0.083500, 0.062500,0.069000, +-0.156584,-0.473826,0.031147,0.000000, -0.316100,-0.946600,0.062900, 0.031200,0.103400, +-0.105420,-0.488310,0.020970,0.000000, -0.214000,-0.975900,0.042500, 0.031200,0.069000, +-0.461262,0.027069,0.191060,0.000000, -0.922500,0.054000,0.382100, 0.062500,0.517200, +-0.455854,0.080891,0.188820,0.000000, -0.911800,0.161200,0.377700, 0.062500,0.551700, +-0.483932,0.080891,0.096260,0.000000, -0.967900,0.161200,0.192500, 0.031200,0.551700, +-0.461262,0.027069,0.191060,0.000000, -0.922500,0.054000,0.382100, 0.062500,0.517200, +-0.483932,0.080891,0.096260,0.000000, -0.967900,0.161200,0.192500, 0.031200,0.551700, +-0.489673,0.027069,0.097402,0.000000, -0.979300,0.054000,0.194800, 0.031200,0.517200, +-0.049945,0.497069,0.020688,0.000000, -0.103000,0.993700,0.042600, 0.481700,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.482000,0.960300, +-0.053020,0.497069,0.010546,0.000000, -0.109300,0.993700,0.021700, 0.483500,0.962300, +-0.049945,-0.497069,0.020688,0.000000, -0.103000,-0.993700,0.042600, 0.062500,0.034500, +-0.099303,-0.488310,0.041132,0.000000, -0.201600,-0.975900,0.083500, 0.062500,0.069000, +-0.105420,-0.488310,0.020970,0.000000, -0.214000,-0.975900,0.042500, 0.031200,0.069000, +-0.049945,-0.497069,0.020688,0.000000, -0.103000,-0.993700,0.042600, 0.062500,0.034500, +-0.105420,-0.488310,0.020970,0.000000, -0.214000,-0.975900,0.042500, 0.031200,0.069000, +-0.053021,-0.497069,0.010546,0.000000, -0.109300,-0.993700,0.021700, 0.031200,0.034500, +-0.461262,-0.027069,0.191060,0.000000, -0.922500,-0.054000,0.382100, 0.062500,0.482800, +-0.461262,0.027069,0.191060,0.000000, -0.922500,0.054000,0.382100, 0.062500,0.517200, +-0.489673,0.027069,0.097402,0.000000, -0.979300,0.054000,0.194800, 0.031200,0.517200, +-0.461262,-0.027069,0.191060,0.000000, -0.922500,-0.054000,0.382100, 0.062500,0.482800, +-0.489673,0.027069,0.097402,0.000000, -0.979300,0.054000,0.194800, 0.031200,0.517200, +-0.489673,-0.027069,0.097402,0.000000, -0.979300,-0.054000,0.194800, 0.031200,0.482800, +-0.099303,0.488310,0.041132,0.000000, -0.201600,0.975900,0.083500, 0.062500,0.931000, +-0.049945,0.497069,0.020688,0.000000, -0.103000,0.993700,0.042600, 0.062500,0.965500, +-0.053020,0.497069,0.010546,0.000000, -0.109300,0.993700,0.021700, 0.031200,0.965500, +-0.099303,0.488310,0.041132,0.000000, -0.201600,0.975900,0.083500, 0.062500,0.931000, +-0.053020,0.497069,0.010546,0.000000, -0.109300,0.993700,0.021700, 0.031200,0.965500, +-0.105420,0.488310,0.020969,0.000000, -0.214000,0.975900,0.042500, 0.031200,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +-0.049945,-0.497069,0.020688,0.000000, -0.103000,-0.993700,0.042600, 0.415600,0.053800, +-0.053021,-0.497069,0.010546,0.000000, -0.109300,-0.993700,0.021700, 0.413000,0.053800, +-0.455854,-0.080891,0.188820,0.000000, -0.911800,-0.161200,0.377700, 0.062500,0.448300, +-0.461262,-0.027069,0.191060,0.000000, -0.922500,-0.054000,0.382100, 0.062500,0.482800, +-0.489673,-0.027069,0.097402,0.000000, -0.979300,-0.054000,0.194800, 0.031200,0.482800, +-0.455854,-0.080891,0.188820,0.000000, -0.911800,-0.161200,0.377700, 0.062500,0.448300, +-0.489673,-0.027069,0.097402,0.000000, -0.979300,-0.054000,0.194800, 0.031200,0.482800, +-0.483932,-0.080891,0.096260,0.000000, -0.967900,-0.161200,0.192500, 0.031200,0.448300, +-0.147498,0.473826,0.061095,0.000000, -0.297800,0.946600,0.123300, 0.062500,0.896600, +-0.099303,0.488310,0.041132,0.000000, -0.201600,0.975900,0.083500, 0.062500,0.931000, +-0.105420,0.488310,0.020969,0.000000, -0.214000,0.975900,0.042500, 0.031200,0.931000, +-0.147498,0.473826,0.061095,0.000000, -0.297800,0.946600,0.123300, 0.062500,0.896600, +-0.105420,0.488310,0.020969,0.000000, -0.214000,0.975900,0.042500, 0.031200,0.931000, +-0.156583,0.473826,0.031146,0.000000, -0.316100,0.946600,0.062900, 0.031200,0.896600, +-0.205911,-0.453788,0.040958,0.000000, -0.414500,-0.906300,0.082400, 0.031200,0.137900, +-0.252824,-0.428429,0.050290,0.000000, -0.508100,-0.855300,0.101000, 0.031200,0.172400, +-0.257777,-0.428429,0.000000,0.000000, -0.518000,-0.855300,0.000000, 0.000000,0.172400, +-0.205911,-0.453788,0.040958,0.000000, -0.414500,-0.906300,0.082400, 0.031200,0.137900, +-0.257777,-0.428429,0.000000,0.000000, -0.518000,-0.855300,0.000000, 0.000000,0.172400, +-0.209945,-0.453788,0.000000,0.000000, -0.422700,-0.906300,0.000000, 0.000000,0.137900, +-0.472517,0.133764,0.093989,0.000000, -0.945200,0.266600,0.188000, 0.031200,0.586200, +-0.455563,0.185069,0.090617,0.000000, -0.911600,0.369000,0.181300, 0.031200,0.620700, +-0.464489,0.185069,0.000000,0.000000, -0.929400,0.369000,0.000000, 0.000000,0.620700, +-0.472517,0.133764,0.093989,0.000000, -0.945200,0.266600,0.188000, 0.031200,0.586200, +-0.464489,0.185069,0.000000,0.000000, -0.929400,0.369000,0.000000, 0.000000,0.620700, +-0.481775,0.133764,0.000000,0.000000, -0.963800,0.266600,0.000000, 0.000000,0.586200, +-0.156584,-0.473826,0.031147,0.000000, -0.316100,-0.946600,0.062900, 0.031200,0.103400, +-0.205911,-0.453788,0.040958,0.000000, -0.414500,-0.906300,0.082400, 0.031200,0.137900, +-0.209945,-0.453788,0.000000,0.000000, -0.422700,-0.906300,0.000000, 0.000000,0.137900, +-0.156584,-0.473826,0.031147,0.000000, -0.316100,-0.946600,0.062900, 0.031200,0.103400, +-0.209945,-0.453788,0.000000,0.000000, -0.422700,-0.906300,0.000000, 0.000000,0.137900, +-0.159651,-0.473826,0.000000,0.000000, -0.322300,-0.946600,0.000000, 0.000000,0.103400, +-0.483932,0.080891,0.096260,0.000000, -0.967900,0.161200,0.192500, 0.031200,0.551700, +-0.472517,0.133764,0.093989,0.000000, -0.945200,0.266600,0.188000, 0.031200,0.586200, +-0.481775,0.133764,0.000000,0.000000, -0.963800,0.266600,0.000000, 0.000000,0.586200, +-0.483932,0.080891,0.096260,0.000000, -0.967900,0.161200,0.192500, 0.031200,0.551700, +-0.481775,0.133764,0.000000,0.000000, -0.963800,0.266600,0.000000, 0.000000,0.586200, +-0.493414,0.080891,0.000000,0.000000, -0.986900,0.161200,0.000000, 0.000000,0.551700, +-0.105420,-0.488310,0.020970,0.000000, -0.214000,-0.975900,0.042500, 0.031200,0.069000, +-0.156584,-0.473826,0.031147,0.000000, -0.316100,-0.946600,0.062900, 0.031200,0.103400, +-0.159651,-0.473826,0.000000,0.000000, -0.322300,-0.946600,0.000000, 0.000000,0.103400, +-0.105420,-0.488310,0.020970,0.000000, -0.214000,-0.975900,0.042500, 0.031200,0.069000, +-0.159651,-0.473826,0.000000,0.000000, -0.322300,-0.946600,0.000000, 0.000000,0.103400, +-0.107486,-0.488310,0.000000,0.000000, -0.218200,-0.975900,0.000000, 0.000000,0.069000, +-0.489673,0.027069,0.097402,0.000000, -0.979300,0.054000,0.194800, 0.031200,0.517200, +-0.483932,0.080891,0.096260,0.000000, -0.967900,0.161200,0.192500, 0.031200,0.551700, +-0.493414,0.080891,0.000000,0.000000, -0.986900,0.161200,0.000000, 0.000000,0.551700, +-0.489673,0.027069,0.097402,0.000000, -0.979300,0.054000,0.194800, 0.031200,0.517200, +-0.493414,0.080891,0.000000,0.000000, -0.986900,0.161200,0.000000, 0.000000,0.551700, +-0.499267,0.027069,0.000000,0.000000, -0.998500,0.054000,0.000000, 0.000000,0.517200, +-0.053020,0.497069,0.010546,0.000000, -0.109300,0.993700,0.021700, 0.425300,0.962300, +-0.000000,0.500000,0.000000,0.000000, 0.000000,1.000000,0.000000, 0.423900,0.960300, +-0.054060,0.497069,0.000000,0.000000, -0.111500,0.993700,0.000000, 0.427200,0.962300, +-0.053021,-0.497069,0.010546,0.000000, -0.109300,-0.993700,0.021700, 0.031200,0.034500, +-0.105420,-0.488310,0.020970,0.000000, -0.214000,-0.975900,0.042500, 0.031200,0.069000, +-0.107486,-0.488310,0.000000,0.000000, -0.218200,-0.975900,0.000000, 0.000000,0.069000, +-0.053021,-0.497069,0.010546,0.000000, -0.109300,-0.993700,0.021700, 0.031200,0.034500, +-0.107486,-0.488310,0.000000,0.000000, -0.218200,-0.975900,0.000000, 0.000000,0.069000, +-0.054060,-0.497069,0.000000,0.000000, -0.111500,-0.993700,0.000000, 0.000000,0.034500, +-0.489673,-0.027069,0.097402,0.000000, -0.979300,-0.054000,0.194800, 0.031200,0.482800, +-0.489673,0.027069,0.097402,0.000000, -0.979300,0.054000,0.194800, 0.031200,0.517200, +-0.499267,0.027069,0.000000,0.000000, -0.998500,0.054000,0.000000, 0.000000,0.517200, +-0.489673,-0.027069,0.097402,0.000000, -0.979300,-0.054000,0.194800, 0.031200,0.482800, +-0.499267,0.027069,0.000000,0.000000, -0.998500,0.054000,0.000000, 0.000000,0.517200, +-0.499267,-0.027069,0.000000,0.000000, -0.998500,-0.054000,0.000000, 0.000000,0.482800, +-0.105420,0.488310,0.020969,0.000000, -0.214000,0.975900,0.042500, 1.031200,0.931000, +-0.053020,0.497069,0.010546,0.000000, -0.109300,0.993700,0.021700, 1.031200,0.965500, +-0.054060,0.497069,0.000000,0.000000, -0.111500,0.993700,0.000000, 1.000000,0.965500, +-0.105420,0.488310,0.020969,0.000000, -0.214000,0.975900,0.042500, 1.031200,0.931000, +-0.054060,0.497069,0.000000,0.000000, -0.111500,0.993700,0.000000, 1.000000,0.965500, +-0.107485,0.488310,0.000000,0.000000, -0.218200,0.975900,0.000000, 1.000000,0.931000, +-0.000000,-0.500000,0.000000,0.000000, 0.000000,-1.000000,0.000000, 0.411700,0.051000, +-0.053021,-0.497069,0.010546,0.000000, -0.109300,-0.993700,0.021700, 0.413000,0.053800, +-0.054060,-0.497069,0.000000,0.000000, -0.111500,-0.993700,0.000000, 0.410400,0.053800, +-0.483932,-0.080891,0.096260,0.000000, -0.967900,-0.161200,0.192500, 0.031200,0.448300, +-0.489673,-0.027069,0.097402,0.000000, -0.979300,-0.054000,0.194800, 0.031200,0.482800, +-0.499267,-0.027069,0.000000,0.000000, -0.998500,-0.054000,0.000000, 0.000000,0.482800, +-0.483932,-0.080891,0.096260,0.000000, -0.967900,-0.161200,0.192500, 0.031200,0.448300, +-0.499267,-0.027069,0.000000,0.000000, -0.998500,-0.054000,0.000000, 0.000000,0.482800, +-0.493414,-0.080891,0.000000,0.000000, -0.986900,-0.161200,0.000000, 0.000000,0.448300, +-0.156583,0.473826,0.031146,0.000000, -0.316100,0.946600,0.062900, 1.031200,0.896600, +-0.105420,0.488310,0.020969,0.000000, -0.214000,0.975900,0.042500, 1.031200,0.931000, +-0.107485,0.488310,0.000000,0.000000, -0.218200,0.975900,0.000000, 1.000000,0.931000, +-0.156583,0.473826,0.031146,0.000000, -0.316100,0.946600,0.062900, 1.031200,0.896600, +-0.107485,0.488310,0.000000,0.000000, -0.218200,0.975900,0.000000, 1.000000,0.931000, +-0.159651,0.473826,0.000000,0.000000, -0.322300,0.946600,0.000000, 1.000000,0.896600, +-0.472517,-0.133764,0.093989,0.000000, -0.945200,-0.266600,0.188000, 0.031200,0.413800, +-0.483932,-0.080891,0.096260,0.000000, -0.967900,-0.161200,0.192500, 0.031200,0.448300, +-0.493414,-0.080891,0.000000,0.000000, -0.986900,-0.161200,0.000000, 0.000000,0.448300, +-0.472517,-0.133764,0.093989,0.000000, -0.945200,-0.266600,0.188000, 0.031200,0.413800, +-0.493414,-0.080891,0.000000,0.000000, -0.986900,-0.161200,0.000000, 0.000000,0.448300, +-0.481775,-0.133764,0.000000,0.000000, -0.963800,-0.266600,0.000000, 0.000000,0.413800, +-0.205911,0.453788,0.040958,0.000000, -0.414500,0.906300,0.082400, 0.031200,0.862100, +-0.156583,0.473826,0.031146,0.000000, -0.316100,0.946600,0.062900, 0.031200,0.896600, +-0.159651,0.473826,0.000000,0.000000, -0.322300,0.946600,0.000000, 0.000000,0.896600, +-0.205911,0.453788,0.040958,0.000000, -0.414500,0.906300,0.082400, 0.031200,0.862100, +-0.159651,0.473826,0.000000,0.000000, -0.322300,0.946600,0.000000, 0.000000,0.896600, +-0.209945,0.453788,0.000000,0.000000, -0.422700,0.906300,0.000000, 0.000000,0.862100, +-0.455563,-0.185069,0.090617,0.000000, -0.911600,-0.369000,0.181300, 0.031200,0.379300, +-0.472517,-0.133764,0.093989,0.000000, -0.945200,-0.266600,0.188000, 0.031200,0.413800, +-0.481775,-0.133764,0.000000,0.000000, -0.963800,-0.266600,0.000000, 0.000000,0.413800, +-0.455563,-0.185069,0.090617,0.000000, -0.911600,-0.369000,0.181300, 0.031200,0.379300, +-0.481775,-0.133764,0.000000,0.000000, -0.963800,-0.266600,0.000000, 0.000000,0.413800, +-0.464489,-0.185069,0.000000,0.000000, -0.929400,-0.369000,0.000000, 0.000000,0.379300, +-0.252824,0.428429,0.050290,0.000000, -0.508100,0.855300,0.101000, 0.031200,0.827600, +-0.205911,0.453788,0.040958,0.000000, -0.414500,0.906300,0.082400, 0.031200,0.862100, +-0.209945,0.453788,0.000000,0.000000, -0.422700,0.906300,0.000000, 0.000000,0.862100, +-0.252824,0.428429,0.050290,0.000000, -0.508100,0.855300,0.101000, 0.031200,0.827600, +-0.209945,0.453788,0.000000,0.000000, -0.422700,0.906300,0.000000, 0.000000,0.862100, +-0.257777,0.428429,0.000000,0.000000, -0.518000,0.855300,0.000000, 0.000000,0.827600, +-0.433268,-0.234204,0.086182,0.000000, -0.867200,-0.467000,0.172500, 0.031200,0.344800, +-0.455563,-0.185069,0.090617,0.000000, -0.911600,-0.369000,0.181300, 0.031200,0.379300, +-0.464489,-0.185069,0.000000,0.000000, -0.929400,-0.369000,0.000000, 0.000000,0.379300, +-0.433268,-0.234204,0.086182,0.000000, -0.867200,-0.467000,0.172500, 0.031200,0.344800, +-0.464489,-0.185069,0.000000,0.000000, -0.929400,-0.369000,0.000000, 0.000000,0.379300, +-0.441756,-0.234204,0.000000,0.000000, -0.884200,-0.467000,0.000000, 0.000000,0.344800, +-0.296773,0.398046,0.059032,0.000000, -0.595600,0.794500,0.118500, 0.031200,0.793100, +-0.252824,0.428429,0.050290,0.000000, -0.508100,0.855300,0.101000, 0.031200,0.827600, +-0.257777,0.428429,0.000000,0.000000, -0.518000,0.855300,0.000000, 0.000000,0.827600, +-0.296773,0.398046,0.059032,0.000000, -0.595600,0.794500,0.118500, 0.031200,0.793100, +-0.257777,0.428429,0.000000,0.000000, -0.518000,0.855300,0.000000, 0.000000,0.827600, +-0.302587,0.398046,0.000000,0.000000, -0.607300,0.794500,0.000000, 0.000000,0.793100, +-0.405892,-0.280594,0.080737,0.000000, -0.812800,-0.559600,0.161700, 0.031200,0.310300, +-0.433268,-0.234204,0.086182,0.000000, -0.867200,-0.467000,0.172500, 0.031200,0.344800, +-0.441756,-0.234204,0.000000,0.000000, -0.884200,-0.467000,0.000000, 0.000000,0.344800, +-0.405892,-0.280594,0.080737,0.000000, -0.812800,-0.559600,0.161700, 0.031200,0.310300, +-0.441756,-0.234204,0.000000,0.000000, -0.884200,-0.467000,0.000000, 0.000000,0.344800, +-0.413844,-0.280594,0.000000,0.000000, -0.828700,-0.559600,0.000000, 0.000000,0.310300, +-0.337243,0.362998,0.067082,0.000000, -0.676200,0.724300,0.134500, 0.031200,0.758600, +-0.296773,0.398046,0.059032,0.000000, -0.595600,0.794500,0.118500, 0.031200,0.793100, +-0.302587,0.398046,0.000000,0.000000, -0.607300,0.794500,0.000000, 0.000000,0.793100, +-0.337243,0.362998,0.067082,0.000000, -0.676200,0.724300,0.134500, 0.031200,0.758600, +-0.302587,0.398046,0.000000,0.000000, -0.607300,0.794500,0.000000, 0.000000,0.793100, +-0.343850,0.362998,0.000000,0.000000, -0.689400,0.724300,0.000000, 0.000000,0.758600, +-0.373758,-0.323693,0.074345,0.000000, -0.748900,-0.645700,0.149000, 0.031200,0.275900, +-0.405892,-0.280594,0.080737,0.000000, -0.812800,-0.559600,0.161700, 0.031200,0.310300, +-0.413844,-0.280594,0.000000,0.000000, -0.828700,-0.559600,0.000000, 0.000000,0.310300, +-0.373758,-0.323693,0.074345,0.000000, -0.748900,-0.645700,0.149000, 0.031200,0.275900, +-0.413844,-0.280594,0.000000,0.000000, -0.828700,-0.559600,0.000000, 0.000000,0.310300, +-0.381081,-0.323693,0.000000,0.000000, -0.763500,-0.645700,0.000000, 0.000000,0.275900, +-0.373758,0.323693,0.074345,0.000000, -0.748900,0.645700,0.149000, 0.031200,0.724100, +-0.337243,0.362998,0.067082,0.000000, -0.676200,0.724300,0.134500, 0.031200,0.758600, +-0.343850,0.362998,0.000000,0.000000, -0.689400,0.724300,0.000000, 0.000000,0.758600, +-0.373758,0.323693,0.074345,0.000000, -0.748900,0.645700,0.149000, 0.031200,0.724100, +-0.343850,0.362998,0.000000,0.000000, -0.689400,0.724300,0.000000, 0.000000,0.758600, +-0.381081,0.323693,0.000000,0.000000, -0.763500,0.645700,0.000000, 0.000000,0.724100, +-0.337243,-0.362998,0.067082,0.000000, -0.676200,-0.724300,0.134500, 0.031200,0.241400, +-0.373758,-0.323693,0.074345,0.000000, -0.748900,-0.645700,0.149000, 0.031200,0.275900, +-0.381081,-0.323693,0.000000,0.000000, -0.763500,-0.645700,0.000000, 0.000000,0.275900, +-0.337243,-0.362998,0.067082,0.000000, -0.676200,-0.724300,0.134500, 0.031200,0.241400, +-0.381081,-0.323693,0.000000,0.000000, -0.763500,-0.645700,0.000000, 0.000000,0.275900, +-0.343850,-0.362998,0.000000,0.000000, -0.689400,-0.724300,0.000000, 0.000000,0.241400, +-0.405892,0.280594,0.080737,0.000000, -0.812800,0.559600,0.161700, 0.031200,0.689700, +-0.373758,0.323693,0.074345,0.000000, -0.748900,0.645700,0.149000, 0.031200,0.724100, +-0.381081,0.323693,0.000000,0.000000, -0.763500,0.645700,0.000000, 0.000000,0.724100, +-0.405892,0.280594,0.080737,0.000000, -0.812800,0.559600,0.161700, 0.031200,0.689700, +-0.381081,0.323693,0.000000,0.000000, -0.763500,0.645700,0.000000, 0.000000,0.724100, +-0.413844,0.280594,0.000000,0.000000, -0.828700,0.559600,0.000000, 0.000000,0.689700, +-0.296773,-0.398046,0.059032,0.000000, -0.595600,-0.794500,0.118500, 0.031200,0.206900, +-0.337243,-0.362998,0.067082,0.000000, -0.676200,-0.724300,0.134500, 0.031200,0.241400, +-0.343850,-0.362998,0.000000,0.000000, -0.689400,-0.724300,0.000000, 0.000000,0.241400, +-0.296773,-0.398046,0.059032,0.000000, -0.595600,-0.794500,0.118500, 0.031200,0.206900, +-0.343850,-0.362998,0.000000,0.000000, -0.689400,-0.724300,0.000000, 0.000000,0.241400, +-0.302588,-0.398046,0.000000,0.000000, -0.607300,-0.794500,0.000000, 0.000000,0.206900, +-0.433268,0.234204,0.086182,0.000000, -0.867200,0.467000,0.172500, 0.031200,0.655200, +-0.405892,0.280594,0.080737,0.000000, -0.812800,0.559600,0.161700, 0.031200,0.689700, +-0.413844,0.280594,0.000000,0.000000, -0.828700,0.559600,0.000000, 0.000000,0.689700, +-0.433268,0.234204,0.086182,0.000000, -0.867200,0.467000,0.172500, 0.031200,0.655200, +-0.413844,0.280594,0.000000,0.000000, -0.828700,0.559600,0.000000, 0.000000,0.689700, +-0.441756,0.234204,0.000000,0.000000, -0.884200,0.467000,0.000000, 0.000000,0.655200, +-0.252824,-0.428429,0.050290,0.000000, -0.508100,-0.855300,0.101000, 0.031200,0.172400, +-0.296773,-0.398046,0.059032,0.000000, -0.595600,-0.794500,0.118500, 0.031200,0.206900, +-0.302588,-0.398046,0.000000,0.000000, -0.607300,-0.794500,0.000000, 0.000000,0.206900, +-0.252824,-0.428429,0.050290,0.000000, -0.508100,-0.855300,0.101000, 0.031200,0.172400, +-0.302588,-0.398046,0.000000,0.000000, -0.607300,-0.794500,0.000000, 0.000000,0.206900, +-0.257777,-0.428429,0.000000,0.000000, -0.518000,-0.855300,0.000000, 0.000000,0.172400, +-0.455563,0.185069,0.090617,0.000000, -0.911600,0.369000,0.181300, 0.031200,0.620700, +-0.433268,0.234204,0.086182,0.000000, -0.867200,0.467000,0.172500, 0.031200,0.655200, +-0.441756,0.234204,0.000000,0.000000, -0.884200,0.467000,0.000000, 0.000000,0.655200, +-0.455563,0.185069,0.090617,0.000000, -0.911600,0.369000,0.181300, 0.031200,0.620700, +-0.441756,0.234204,0.000000,0.000000, -0.884200,0.467000,0.000000, 0.000000,0.655200, +-0.464489,0.185069,0.000000,0.000000, -0.929400,0.369000,0.000000, 0.000000,0.620700, +}; + +const int textured_detailed_sphere_indices[]= +{ +0,1,2, +3,4,5, +6,7,8, +9,10,11, +12,13,14, +15,16,17, +18,19,20, +21,22,23, +24,25,26, +27,28,29, +30,31,32, +33,34,35, +36,37,38, +39,40,41, +42,43,44, +45,46,47, +48,49,50, +51,52,53, +54,55,56, +57,58,59, +60,61,62, +63,64,65, +66,67,68, +69,70,71, +72,73,74, +75,76,77, +78,79,80, +81,82,83, +84,85,86, +87,88,89, +90,91,92, +93,94,95, +96,97,98, +99,100,101, +102,103,104, +105,106,107, +108,109,110, +111,112,113, +114,115,116, +117,118,119, +120,121,122, +123,124,125, +126,127,128, +129,130,131, +132,133,134, +135,136,137, +138,139,140, +141,142,143, +144,145,146, +147,148,149, +150,151,152, +153,154,155, +156,157,158, +159,160,161, +162,163,164, +165,166,167, +168,169,170, +171,172,173, +174,175,176, +177,178,179, +180,181,182, +183,184,185, +186,187,188, +189,190,191, +192,193,194, +195,196,197, +198,199,200, +201,202,203, +204,205,206, +207,208,209, +210,211,212, +213,214,215, +216,217,218, +219,220,221, +222,223,224, +225,226,227, +228,229,230, +231,232,233, +234,235,236, +237,238,239, +240,241,242, +243,244,245, +246,247,248, +249,250,251, +252,253,254, +255,256,257, +258,259,260, +261,262,263, +264,265,266, +267,268,269, +270,271,272, +273,274,275, +276,277,278, +279,280,281, +282,283,284, +285,286,287, +288,289,290, +291,292,293, +294,295,296, +297,298,299, +300,301,302, +303,304,305, +306,307,308, +309,310,311, +312,313,314, +315,316,317, +318,319,320, +321,322,323, +324,325,326, +327,328,329, +330,331,332, +333,334,335, +336,337,338, +339,340,341, +342,343,344, +345,346,347, +348,349,350, +351,352,353, +354,355,356, +357,358,359, +360,361,362, +363,364,365, +366,367,368, +369,370,371, +372,373,374, +375,376,377, +378,379,380, +381,382,383, +384,385,386, +387,388,389, +390,391,392, +393,394,395, +396,397,398, +399,400,401, +402,403,404, +405,406,407, +408,409,410, +411,412,413, +414,415,416, +417,418,419, +420,421,422, +423,424,425, +426,427,428, +429,430,431, +432,433,434, +435,436,437, +438,439,440, +441,442,443, +444,445,446, +447,448,449, +450,451,452, +453,454,455, +456,457,458, +459,460,461, +462,463,464, +465,466,467, +468,469,470, +471,472,473, +474,475,476, +477,478,479, +480,481,482, +483,484,485, +486,487,488, +489,490,491, +492,493,494, +495,496,497, +498,499,500, +501,502,503, +504,505,506, +507,508,509, +510,511,512, +513,514,515, +516,517,518, +519,520,521, +522,523,524, +525,526,527, +528,529,530, +531,532,533, +534,535,536, +537,538,539, +540,541,542, +543,544,545, +546,547,548, +549,550,551, +552,553,554, +555,556,557, +558,559,560, +561,562,563, +564,565,566, +567,568,569, +570,571,572, +573,574,575, +576,577,578, +579,580,581, +582,583,584, +585,586,587, +588,589,590, +591,592,593, +594,595,596, +597,598,599, +600,601,602, +603,604,605, +606,607,608, +609,610,611, +612,613,614, +615,616,617, +618,619,620, +621,622,623, +624,625,626, +627,628,629, +630,631,632, +633,634,635, +636,637,638, +639,640,641, +642,643,644, +645,646,647, +648,649,650, +651,652,653, +654,655,656, +657,658,659, +660,661,662, +663,664,665, +666,667,668, +669,670,671, +672,673,674, +675,676,677, +678,679,680, +681,682,683, +684,685,686, +687,688,689, +690,691,692, +693,694,695, +696,697,698, +699,700,701, +702,703,704, +705,706,707, +708,709,710, +711,712,713, +714,715,716, +717,718,719, +720,721,722, +723,724,725, +726,727,728, +729,730,731, +732,733,734, +735,736,737, +738,739,740, +741,742,743, +744,745,746, +747,748,749, +750,751,752, +753,754,755, +756,757,758, +759,760,761, +762,763,764, +765,766,767, +768,769,770, +771,772,773, +774,775,776, +777,778,779, +780,781,782, +783,784,785, +786,787,788, +789,790,791, +792,793,794, +795,796,797, +798,799,800, +801,802,803, +804,805,806, +807,808,809, +810,811,812, +813,814,815, +816,817,818, +819,820,821, +822,823,824, +825,826,827, +828,829,830, +831,832,833, +834,835,836, +837,838,839, +840,841,842, +843,844,845, +846,847,848, +849,850,851, +852,853,854, +855,856,857, +858,859,860, +861,862,863, +864,865,866, +867,868,869, +870,871,872, +873,874,875, +876,877,878, +879,880,881, +882,883,884, +885,886,887, +888,889,890, +891,892,893, +894,895,896, +897,898,899, +900,901,902, +903,904,905, +906,907,908, +909,910,911, +912,913,914, +915,916,917, +918,919,920, +921,922,923, +924,925,926, +927,928,929, +930,931,932, +933,934,935, +936,937,938, +939,940,941, +942,943,944, +945,946,947, +948,949,950, +951,952,953, +954,955,956, +957,958,959, +960,961,962, +963,964,965, +966,967,968, +969,970,971, +972,973,974, +975,976,977, +978,979,980, +981,982,983, +984,985,986, +987,988,989, +990,991,992, +993,994,995, +996,997,998, +999,1000,1001, +1002,1003,1004, +1005,1006,1007, +1008,1009,1010, +1011,1012,1013, +1014,1015,1016, +1017,1018,1019, +1020,1021,1022, +1023,1024,1025, +1026,1027,1028, +1029,1030,1031, +1032,1033,1034, +1035,1036,1037, +1038,1039,1040, +1041,1042,1043, +1044,1045,1046, +1047,1048,1049, +1050,1051,1052, +1053,1054,1055, +1056,1057,1058, +1059,1060,1061, +1062,1063,1064, +1065,1066,1067, +1068,1069,1070, +1071,1072,1073, +1074,1075,1076, +1077,1078,1079, +1080,1081,1082, +1083,1084,1085, +1086,1087,1088, +1089,1090,1091, +1092,1093,1094, +1095,1096,1097, +1098,1099,1100, +1101,1102,1103, +1104,1105,1106, +1107,1108,1109, +1110,1111,1112, +1113,1114,1115, +1116,1117,1118, +1119,1120,1121, +1122,1123,1124, +1125,1126,1127, +1128,1129,1130, +1131,1132,1133, +1134,1135,1136, +1137,1138,1139, +1140,1141,1142, +1143,1144,1145, +1146,1147,1148, +1149,1150,1151, +1152,1153,1154, +1155,1156,1157, +1158,1159,1160, +1161,1162,1163, +1164,1165,1166, +1167,1168,1169, +1170,1171,1172, +1173,1174,1175, +1176,1177,1178, +1179,1180,1181, +1182,1183,1184, +1185,1186,1187, +1188,1189,1190, +1191,1192,1193, +1194,1195,1196, +1197,1198,1199, +1200,1201,1202, +1203,1204,1205, +1206,1207,1208, +1209,1210,1211, +1212,1213,1214, +1215,1216,1217, +1218,1219,1220, +1221,1222,1223, +1224,1225,1226, +1227,1228,1229, +1230,1231,1232, +1233,1234,1235, +1236,1237,1238, +1239,1240,1241, +1242,1243,1244, +1245,1246,1247, +1248,1249,1250, +1251,1252,1253, +1254,1255,1256, +1257,1258,1259, +1260,1261,1262, +1263,1264,1265, +1266,1267,1268, +1269,1270,1271, +1272,1273,1274, +1275,1276,1277, +1278,1279,1280, +1281,1282,1283, +1284,1285,1286, +1287,1288,1289, +1290,1291,1292, +1293,1294,1295, +1296,1297,1298, +1299,1300,1301, +1302,1303,1304, +1305,1306,1307, +1308,1309,1310, +1311,1312,1313, +1314,1315,1316, +1317,1318,1319, +1320,1321,1322, +1323,1324,1325, +1326,1327,1328, +1329,1330,1331, +1332,1333,1334, +1335,1336,1337, +1338,1339,1340, +1341,1342,1343, +1344,1345,1346, +1347,1348,1349, +1350,1351,1352, +1353,1354,1355, +1356,1357,1358, +1359,1360,1361, +1362,1363,1364, +1365,1366,1367, +1368,1369,1370, +1371,1372,1373, +1374,1375,1376, +1377,1378,1379, +1380,1381,1382, +1383,1384,1385, +1386,1387,1388, +1389,1390,1391, +1392,1393,1394, +1395,1396,1397, +1398,1399,1400, +1401,1402,1403, +1404,1405,1406, +1407,1408,1409, +1410,1411,1412, +1413,1414,1415, +1416,1417,1418, +1419,1420,1421, +1422,1423,1424, +1425,1426,1427, +1428,1429,1430, +1431,1432,1433, +1434,1435,1436, +1437,1438,1439, +1440,1441,1442, +1443,1444,1445, +1446,1447,1448, +1449,1450,1451, +1452,1453,1454, +1455,1456,1457, +1458,1459,1460, +1461,1462,1463, +1464,1465,1466, +1467,1468,1469, +1470,1471,1472, +1473,1474,1475, +1476,1477,1478, +1479,1480,1481, +1482,1483,1484, +1485,1486,1487, +1488,1489,1490, +1491,1492,1493, +1494,1495,1496, +1497,1498,1499, +1500,1501,1502, +1503,1504,1505, +1506,1507,1508, +1509,1510,1511, +1512,1513,1514, +1515,1516,1517, +1518,1519,1520, +1521,1522,1523, +1524,1525,1526, +1527,1528,1529, +1530,1531,1532, +1533,1534,1535, +1536,1537,1538, +1539,1540,1541, +1542,1543,1544, +1545,1546,1547, +1548,1549,1550, +1551,1552,1553, +1554,1555,1556, +1557,1558,1559, +1560,1561,1562, +1563,1564,1565, +1566,1567,1568, +1569,1570,1571, +1572,1573,1574, +1575,1576,1577, +1578,1579,1580, +1581,1582,1583, +1584,1585,1586, +1587,1588,1589, +1590,1591,1592, +1593,1594,1595, +1596,1597,1598, +1599,1600,1601, +1602,1603,1604, +1605,1606,1607, +1608,1609,1610, +1611,1612,1613, +1614,1615,1616, +1617,1618,1619, +1620,1621,1622, +1623,1624,1625, +1626,1627,1628, +1629,1630,1631, +1632,1633,1634, +1635,1636,1637, +1638,1639,1640, +1641,1642,1643, +1644,1645,1646, +1647,1648,1649, +1650,1651,1652, +1653,1654,1655, +1656,1657,1658, +1659,1660,1661, +1662,1663,1664, +1665,1666,1667, +1668,1669,1670, +1671,1672,1673, +1674,1675,1676, +1677,1678,1679, +1680,1681,1682, +1683,1684,1685, +1686,1687,1688, +1689,1690,1691, +1692,1693,1694, +1695,1696,1697, +1698,1699,1700, +1701,1702,1703, +1704,1705,1706, +1707,1708,1709, +1710,1711,1712, +1713,1714,1715, +1716,1717,1718, +1719,1720,1721, +1722,1723,1724, +1725,1726,1727, +1728,1729,1730, +1731,1732,1733, +1734,1735,1736, +1737,1738,1739, +1740,1741,1742, +1743,1744,1745, +1746,1747,1748, +1749,1750,1751, +1752,1753,1754, +1755,1756,1757, +1758,1759,1760, +1761,1762,1763, +1764,1765,1766, +1767,1768,1769, +1770,1771,1772, +1773,1774,1775, +1776,1777,1778, +1779,1780,1781, +1782,1783,1784, +1785,1786,1787, +1788,1789,1790, +1791,1792,1793, +1794,1795,1796, +1797,1798,1799, +1800,1801,1802, +1803,1804,1805, +1806,1807,1808, +1809,1810,1811, +1812,1813,1814, +1815,1816,1817, +1818,1819,1820, +1821,1822,1823, +1824,1825,1826, +1827,1828,1829, +1830,1831,1832, +1833,1834,1835, +1836,1837,1838, +1839,1840,1841, +1842,1843,1844, +1845,1846,1847, +1848,1849,1850, +1851,1852,1853, +1854,1855,1856, +1857,1858,1859, +1860,1861,1862, +1863,1864,1865, +1866,1867,1868, +1869,1870,1871, +1872,1873,1874, +1875,1876,1877, +1878,1879,1880, +1881,1882,1883, +1884,1885,1886, +1887,1888,1889, +1890,1891,1892, +1893,1894,1895, +1896,1897,1898, +1899,1900,1901, +1902,1903,1904, +1905,1906,1907, +1908,1909,1910, +1911,1912,1913, +1914,1915,1916, +1917,1918,1919, +1920,1921,1922, +1923,1924,1925, +1926,1927,1928, +1929,1930,1931, +1932,1933,1934, +1935,1936,1937, +1938,1939,1940, +1941,1942,1943, +1944,1945,1946, +1947,1948,1949, +1950,1951,1952, +1953,1954,1955, +1956,1957,1958, +1959,1960,1961, +1962,1963,1964, +1965,1966,1967, +1968,1969,1970, +1971,1972,1973, +1974,1975,1976, +1977,1978,1979, +1980,1981,1982, +1983,1984,1985, +1986,1987,1988, +1989,1990,1991, +1992,1993,1994, +1995,1996,1997, +1998,1999,2000, +2001,2002,2003, +2004,2005,2006, +2007,2008,2009, +2010,2011,2012, +2013,2014,2015, +2016,2017,2018, +2019,2020,2021, +2022,2023,2024, +2025,2026,2027, +2028,2029,2030, +2031,2032,2033, +2034,2035,2036, +2037,2038,2039, +2040,2041,2042, +2043,2044,2045, +2046,2047,2048, +2049,2050,2051, +2052,2053,2054, +2055,2056,2057, +2058,2059,2060, +2061,2062,2063, +2064,2065,2066, +2067,2068,2069, +2070,2071,2072, +2073,2074,2075, +2076,2077,2078, +2079,2080,2081, +2082,2083,2084, +2085,2086,2087, +2088,2089,2090, +2091,2092,2093, +2094,2095,2096, +2097,2098,2099, +2100,2101,2102, +2103,2104,2105, +2106,2107,2108, +2109,2110,2111, +2112,2113,2114, +2115,2116,2117, +2118,2119,2120, +2121,2122,2123, +2124,2125,2126, +2127,2128,2129, +2130,2131,2132, +2133,2134,2135, +2136,2137,2138, +2139,2140,2141, +2142,2143,2144, +2145,2146,2147, +2148,2149,2150, +2151,2152,2153, +2154,2155,2156, +2157,2158,2159, +2160,2161,2162, +2163,2164,2165, +2166,2167,2168, +2169,2170,2171, +2172,2173,2174, +2175,2176,2177, +2178,2179,2180, +2181,2182,2183, +2184,2185,2186, +2187,2188,2189, +2190,2191,2192, +2193,2194,2195, +2196,2197,2198, +2199,2200,2201, +2202,2203,2204, +2205,2206,2207, +2208,2209,2210, +2211,2212,2213, +2214,2215,2216, +2217,2218,2219, +2220,2221,2222, +2223,2224,2225, +2226,2227,2228, +2229,2230,2231, +2232,2233,2234, +2235,2236,2237, +2238,2239,2240, +2241,2242,2243, +2244,2245,2246, +2247,2248,2249, +2250,2251,2252, +2253,2254,2255, +2256,2257,2258, +2259,2260,2261, +2262,2263,2264, +2265,2266,2267, +2268,2269,2270, +2271,2272,2273, +2274,2275,2276, +2277,2278,2279, +2280,2281,2282, +2283,2284,2285, +2286,2287,2288, +2289,2290,2291, +2292,2293,2294, +2295,2296,2297, +2298,2299,2300, +2301,2302,2303, +2304,2305,2306, +2307,2308,2309, +2310,2311,2312, +2313,2314,2315, +2316,2317,2318, +2319,2320,2321, +2322,2323,2324, +2325,2326,2327, +2328,2329,2330, +2331,2332,2333, +2334,2335,2336, +2337,2338,2339, +2340,2341,2342, +2343,2344,2345, +2346,2347,2348, +2349,2350,2351, +2352,2353,2354, +2355,2356,2357, +2358,2359,2360, +2361,2362,2363, +2364,2365,2366, +2367,2368,2369, +2370,2371,2372, +2373,2374,2375, +2376,2377,2378, +2379,2380,2381, +2382,2383,2384, +2385,2386,2387, +2388,2389,2390, +2391,2392,2393, +2394,2395,2396, +2397,2398,2399, +2400,2401,2402, +2403,2404,2405, +2406,2407,2408, +2409,2410,2411, +2412,2413,2414, +2415,2416,2417, +2418,2419,2420, +2421,2422,2423, +2424,2425,2426, +2427,2428,2429, +2430,2431,2432, +2433,2434,2435, +2436,2437,2438, +2439,2440,2441, +2442,2443,2444, +2445,2446,2447, +2448,2449,2450, +2451,2452,2453, +2454,2455,2456, +2457,2458,2459, +2460,2461,2462, +2463,2464,2465, +2466,2467,2468, +2469,2470,2471, +2472,2473,2474, +2475,2476,2477, +2478,2479,2480, +2481,2482,2483, +2484,2485,2486, +2487,2488,2489, +2490,2491,2492, +2493,2494,2495, +2496,2497,2498, +2499,2500,2501, +2502,2503,2504, +2505,2506,2507, +2508,2509,2510, +2511,2512,2513, +2514,2515,2516, +2517,2518,2519, +2520,2521,2522, +2523,2524,2525, +2526,2527,2528, +2529,2530,2531, +2532,2533,2534, +2535,2536,2537, +2538,2539,2540, +2541,2542,2543, +2544,2545,2546, +2547,2548,2549, +2550,2551,2552, +2553,2554,2555, +2556,2557,2558, +2559,2560,2561, +2562,2563,2564, +2565,2566,2567, +2568,2569,2570, +2571,2572,2573, +2574,2575,2576, +2577,2578,2579, +2580,2581,2582, +2583,2584,2585, +2586,2587,2588, +2589,2590,2591, +2592,2593,2594, +2595,2596,2597, +2598,2599,2600, +2601,2602,2603, +2604,2605,2606, +2607,2608,2609, +2610,2611,2612, +2613,2614,2615, +2616,2617,2618, +2619,2620,2621, +2622,2623,2624, +2625,2626,2627, +2628,2629,2630, +2631,2632,2633, +2634,2635,2636, +2637,2638,2639, +2640,2641,2642, +2643,2644,2645, +2646,2647,2648, +2649,2650,2651, +2652,2653,2654, +2655,2656,2657, +2658,2659,2660, +2661,2662,2663, +2664,2665,2666, +2667,2668,2669, +2670,2671,2672, +2673,2674,2675, +2676,2677,2678, +2679,2680,2681, +2682,2683,2684, +2685,2686,2687, +2688,2689,2690, +2691,2692,2693, +2694,2695,2696, +2697,2698,2699, +2700,2701,2702, +2703,2704,2705, +2706,2707,2708, +2709,2710,2711, +2712,2713,2714, +2715,2716,2717, +2718,2719,2720, +2721,2722,2723, +2724,2725,2726, +2727,2728,2729, +2730,2731,2732, +2733,2734,2735, +2736,2737,2738, +2739,2740,2741, +2742,2743,2744, +2745,2746,2747, +2748,2749,2750, +2751,2752,2753, +2754,2755,2756, +2757,2758,2759, +2760,2761,2762, +2763,2764,2765, +2766,2767,2768, +2769,2770,2771, +2772,2773,2774, +2775,2776,2777, +2778,2779,2780, +2781,2782,2783, +2784,2785,2786, +2787,2788,2789, +2790,2791,2792, +2793,2794,2795, +2796,2797,2798, +2799,2800,2801, +2802,2803,2804, +2805,2806,2807, +2808,2809,2810, +2811,2812,2813, +2814,2815,2816, +2817,2818,2819, +2820,2821,2822, +2823,2824,2825, +2826,2827,2828, +2829,2830,2831, +2832,2833,2834, +2835,2836,2837, +2838,2839,2840, +2841,2842,2843, +2844,2845,2846, +2847,2848,2849, +2850,2851,2852, +2853,2854,2855, +2856,2857,2858, +2859,2860,2861, +2862,2863,2864, +2865,2866,2867, +2868,2869,2870, +2871,2872,2873, +2874,2875,2876, +2877,2878,2879, +2880,2881,2882, +2883,2884,2885, +2886,2887,2888, +2889,2890,2891, +2892,2893,2894, +2895,2896,2897, +2898,2899,2900, +2901,2902,2903, +2904,2905,2906, +2907,2908,2909, +2910,2911,2912, +2913,2914,2915, +2916,2917,2918, +2919,2920,2921, +2922,2923,2924, +2925,2926,2927, +2928,2929,2930, +2931,2932,2933, +2934,2935,2936, +2937,2938,2939, +2940,2941,2942, +2943,2944,2945, +2946,2947,2948, +2949,2950,2951, +2952,2953,2954, +2955,2956,2957, +2958,2959,2960, +2961,2962,2963, +2964,2965,2966, +2967,2968,2969, +2970,2971,2972, +2973,2974,2975, +2976,2977,2978, +2979,2980,2981, +2982,2983,2984, +2985,2986,2987, +2988,2989,2990, +2991,2992,2993, +2994,2995,2996, +2997,2998,2999, +3000,3001,3002, +3003,3004,3005, +3006,3007,3008, +3009,3010,3011, +3012,3013,3014, +3015,3016,3017, +3018,3019,3020, +3021,3022,3023, +3024,3025,3026, +3027,3028,3029, +3030,3031,3032, +3033,3034,3035, +3036,3037,3038, +3039,3040,3041, +3042,3043,3044, +3045,3046,3047, +3048,3049,3050, +3051,3052,3053, +3054,3055,3056, +3057,3058,3059, +3060,3061,3062, +3063,3064,3065, +3066,3067,3068, +3069,3070,3071, +3072,3073,3074, +3075,3076,3077, +3078,3079,3080, +3081,3082,3083, +3084,3085,3086, +3087,3088,3089, +3090,3091,3092, +3093,3094,3095, +3096,3097,3098, +3099,3100,3101, +3102,3103,3104, +3105,3106,3107, +3108,3109,3110, +3111,3112,3113, +3114,3115,3116, +3117,3118,3119, +3120,3121,3122, +3123,3124,3125, +3126,3127,3128, +3129,3130,3131, +3132,3133,3134, +3135,3136,3137, +3138,3139,3140, +3141,3142,3143, +3144,3145,3146, +3147,3148,3149, +3150,3151,3152, +3153,3154,3155, +3156,3157,3158, +3159,3160,3161, +3162,3163,3164, +3165,3166,3167, +3168,3169,3170, +3171,3172,3173, +3174,3175,3176, +3177,3178,3179, +3180,3181,3182, +3183,3184,3185, +3186,3187,3188, +3189,3190,3191, +3192,3193,3194, +3195,3196,3197, +3198,3199,3200, +3201,3202,3203, +3204,3205,3206, +3207,3208,3209, +3210,3211,3212, +3213,3214,3215, +3216,3217,3218, +3219,3220,3221, +3222,3223,3224, +3225,3226,3227, +3228,3229,3230, +3231,3232,3233, +3234,3235,3236, +3237,3238,3239, +3240,3241,3242, +3243,3244,3245, +3246,3247,3248, +3249,3250,3251, +3252,3253,3254, +3255,3256,3257, +3258,3259,3260, +3261,3262,3263, +3264,3265,3266, +3267,3268,3269, +3270,3271,3272, +3273,3274,3275, +3276,3277,3278, +3279,3280,3281, +3282,3283,3284, +3285,3286,3287, +3288,3289,3290, +3291,3292,3293, +3294,3295,3296, +3297,3298,3299, +3300,3301,3302, +3303,3304,3305, +3306,3307,3308, +3309,3310,3311, +3312,3313,3314, +3315,3316,3317, +3318,3319,3320, +3321,3322,3323, +3324,3325,3326, +3327,3328,3329, +3330,3331,3332, +3333,3334,3335, +3336,3337,3338, +3339,3340,3341, +3342,3343,3344, +3345,3346,3347, +3348,3349,3350, +3351,3352,3353, +3354,3355,3356, +3357,3358,3359, +3360,3361,3362, +3363,3364,3365, +3366,3367,3368, +3369,3370,3371, +3372,3373,3374, +3375,3376,3377, +3378,3379,3380, +3381,3382,3383, +3384,3385,3386, +3387,3388,3389, +3390,3391,3392, +3393,3394,3395, +3396,3397,3398, +3399,3400,3401, +3402,3403,3404, +3405,3406,3407, +3408,3409,3410, +3411,3412,3413, +3414,3415,3416, +3417,3418,3419, +3420,3421,3422, +3423,3424,3425, +3426,3427,3428, +3429,3430,3431, +3432,3433,3434, +3435,3436,3437, +3438,3439,3440, +3441,3442,3443, +3444,3445,3446, +3447,3448,3449, +3450,3451,3452, +3453,3454,3455, +3456,3457,3458, +3459,3460,3461, +3462,3463,3464, +3465,3466,3467, +3468,3469,3470, +3471,3472,3473, +3474,3475,3476, +3477,3478,3479, +3480,3481,3482, +3483,3484,3485, +3486,3487,3488, +3489,3490,3491, +3492,3493,3494, +3495,3496,3497, +3498,3499,3500, +3501,3502,3503, +3504,3505,3506, +3507,3508,3509, +3510,3511,3512, +3513,3514,3515, +3516,3517,3518, +3519,3520,3521, +3522,3523,3524, +3525,3526,3527, +3528,3529,3530, +3531,3532,3533, +3534,3535,3536, +3537,3538,3539, +3540,3541,3542, +3543,3544,3545, +3546,3547,3548, +3549,3550,3551, +3552,3553,3554, +3555,3556,3557, +3558,3559,3560, +3561,3562,3563, +3564,3565,3566, +3567,3568,3569, +3570,3571,3572, +3573,3574,3575, +3576,3577,3578, +3579,3580,3581, +3582,3583,3584, +3585,3586,3587, +3588,3589,3590, +3591,3592,3593, +3594,3595,3596, +3597,3598,3599, +3600,3601,3602, +3603,3604,3605, +3606,3607,3608, +3609,3610,3611, +3612,3613,3614, +3615,3616,3617, +3618,3619,3620, +3621,3622,3623, +3624,3625,3626, +3627,3628,3629, +3630,3631,3632, +3633,3634,3635, +3636,3637,3638, +3639,3640,3641, +3642,3643,3644, +3645,3646,3647, +3648,3649,3650, +3651,3652,3653, +3654,3655,3656, +3657,3658,3659, +3660,3661,3662, +3663,3664,3665, +3666,3667,3668, +3669,3670,3671, +3672,3673,3674, +3675,3676,3677, +3678,3679,3680, +3681,3682,3683, +3684,3685,3686, +3687,3688,3689, +3690,3691,3692, +3693,3694,3695, +3696,3697,3698, +3699,3700,3701, +3702,3703,3704, +3705,3706,3707, +3708,3709,3710, +3711,3712,3713, +3714,3715,3716, +3717,3718,3719, +3720,3721,3722, +3723,3724,3725, +3726,3727,3728, +3729,3730,3731, +3732,3733,3734, +3735,3736,3737, +3738,3739,3740, +3741,3742,3743, +3744,3745,3746, +3747,3748,3749, +3750,3751,3752, +3753,3754,3755, +3756,3757,3758, +3759,3760,3761, +3762,3763,3764, +3765,3766,3767, +3768,3769,3770, +3771,3772,3773, +3774,3775,3776, +3777,3778,3779, +3780,3781,3782, +3783,3784,3785, +3786,3787,3788, +3789,3790,3791, +3792,3793,3794, +3795,3796,3797, +3798,3799,3800, +3801,3802,3803, +3804,3805,3806, +3807,3808,3809, +3810,3811,3812, +3813,3814,3815, +3816,3817,3818, +3819,3820,3821, +3822,3823,3824, +3825,3826,3827, +3828,3829,3830, +3831,3832,3833, +3834,3835,3836, +3837,3838,3839, +3840,3841,3842, +3843,3844,3845, +3846,3847,3848, +3849,3850,3851, +3852,3853,3854, +3855,3856,3857, +3858,3859,3860, +3861,3862,3863, +3864,3865,3866, +3867,3868,3869, +3870,3871,3872, +3873,3874,3875, +3876,3877,3878, +3879,3880,3881, +3882,3883,3884, +3885,3886,3887, +3888,3889,3890, +3891,3892,3893, +3894,3895,3896, +3897,3898,3899, +3900,3901,3902, +3903,3904,3905, +3906,3907,3908, +3909,3910,3911, +3912,3913,3914, +3915,3916,3917, +3918,3919,3920, +3921,3922,3923, +3924,3925,3926, +3927,3928,3929, +3930,3931,3932, +3933,3934,3935, +3936,3937,3938, +3939,3940,3941, +3942,3943,3944, +3945,3946,3947, +3948,3949,3950, +3951,3952,3953, +3954,3955,3956, +3957,3958,3959, +3960,3961,3962, +3963,3964,3965, +3966,3967,3968, +3969,3970,3971, +3972,3973,3974, +3975,3976,3977, +3978,3979,3980, +3981,3982,3983, +3984,3985,3986, +3987,3988,3989, +3990,3991,3992, +3993,3994,3995, +3996,3997,3998, +3999,4000,4001, +4002,4003,4004, +4005,4006,4007, +4008,4009,4010, +4011,4012,4013, +4014,4015,4016, +4017,4018,4019, +4020,4021,4022, +4023,4024,4025, +4026,4027,4028, +4029,4030,4031, +4032,4033,4034, +4035,4036,4037, +4038,4039,4040, +4041,4042,4043, +4044,4045,4046, +4047,4048,4049, +4050,4051,4052, +4053,4054,4055, +4056,4057,4058, +4059,4060,4061, +4062,4063,4064, +4065,4066,4067, +4068,4069,4070, +4071,4072,4073, +4074,4075,4076, +4077,4078,4079, +4080,4081,4082, +4083,4084,4085, +4086,4087,4088, +4089,4090,4091, +4092,4093,4094, +4095,4096,4097, +4098,4099,4100, +4101,4102,4103, +4104,4105,4106, +4107,4108,4109, +4110,4111,4112, +4113,4114,4115, +4116,4117,4118, +4119,4120,4121, +4122,4123,4124, +4125,4126,4127, +4128,4129,4130, +4131,4132,4133, +4134,4135,4136, +4137,4138,4139, +4140,4141,4142, +4143,4144,4145, +4146,4147,4148, +4149,4150,4151, +4152,4153,4154, +4155,4156,4157, +4158,4159,4160, +4161,4162,4163, +4164,4165,4166, +4167,4168,4169, +4170,4171,4172, +4173,4174,4175, +4176,4177,4178, +4179,4180,4181, +4182,4183,4184, +4185,4186,4187, +4188,4189,4190, +4191,4192,4193, +4194,4195,4196, +4197,4198,4199, +4200,4201,4202, +4203,4204,4205, +4206,4207,4208, +4209,4210,4211, +4212,4213,4214, +4215,4216,4217, +4218,4219,4220, +4221,4222,4223, +4224,4225,4226, +4227,4228,4229, +4230,4231,4232, +4233,4234,4235, +4236,4237,4238, +4239,4240,4241, +4242,4243,4244, +4245,4246,4247, +4248,4249,4250, +4251,4252,4253, +4254,4255,4256, +4257,4258,4259, +4260,4261,4262, +4263,4264,4265, +4266,4267,4268, +4269,4270,4271, +4272,4273,4274, +4275,4276,4277, +4278,4279,4280, +4281,4282,4283, +4284,4285,4286, +4287,4288,4289, +4290,4291,4292, +4293,4294,4295, +4296,4297,4298, +4299,4300,4301, +4302,4303,4304, +4305,4306,4307, +4308,4309,4310, +4311,4312,4313, +4314,4315,4316, +4317,4318,4319, +4320,4321,4322, +4323,4324,4325, +4326,4327,4328, +4329,4330,4331, +4332,4333,4334, +4335,4336,4337, +4338,4339,4340, +4341,4342,4343, +4344,4345,4346, +4347,4348,4349, +4350,4351,4352, +4353,4354,4355, +4356,4357,4358, +4359,4360,4361, +4362,4363,4364, +4365,4366,4367, +4368,4369,4370, +4371,4372,4373, +4374,4375,4376, +4377,4378,4379, +4380,4381,4382, +4383,4384,4385, +4386,4387,4388, +4389,4390,4391, +4392,4393,4394, +4395,4396,4397, +4398,4399,4400, +4401,4402,4403, +4404,4405,4406, +4407,4408,4409, +4410,4411,4412, +4413,4414,4415, +4416,4417,4418, +4419,4420,4421, +4422,4423,4424, +4425,4426,4427, +4428,4429,4430, +4431,4432,4433, +4434,4435,4436, +4437,4438,4439, +4440,4441,4442, +4443,4444,4445, +4446,4447,4448, +4449,4450,4451, +4452,4453,4454, +4455,4456,4457, +4458,4459,4460, +4461,4462,4463, +4464,4465,4466, +4467,4468,4469, +4470,4471,4472, +4473,4474,4475, +4476,4477,4478, +4479,4480,4481, +4482,4483,4484, +4485,4486,4487, +4488,4489,4490, +4491,4492,4493, +4494,4495,4496, +4497,4498,4499, +4500,4501,4502, +4503,4504,4505, +4506,4507,4508, +4509,4510,4511, +4512,4513,4514, +4515,4516,4517, +4518,4519,4520, +4521,4522,4523, +4524,4525,4526, +4527,4528,4529, +4530,4531,4532, +4533,4534,4535, +4536,4537,4538, +4539,4540,4541, +4542,4543,4544, +4545,4546,4547, +4548,4549,4550, +4551,4552,4553, +4554,4555,4556, +4557,4558,4559, +4560,4561,4562, +4563,4564,4565, +4566,4567,4568, +4569,4570,4571, +4572,4573,4574, +4575,4576,4577, +4578,4579,4580, +4581,4582,4583, +4584,4585,4586, +4587,4588,4589, +4590,4591,4592, +4593,4594,4595, +4596,4597,4598, +4599,4600,4601, +4602,4603,4604, +4605,4606,4607, +4608,4609,4610, +4611,4612,4613, +4614,4615,4616, +4617,4618,4619, +4620,4621,4622, +4623,4624,4625, +4626,4627,4628, +4629,4630,4631, +4632,4633,4634, +4635,4636,4637, +4638,4639,4640, +4641,4642,4643, +4644,4645,4646, +4647,4648,4649, +4650,4651,4652, +4653,4654,4655, +4656,4657,4658, +4659,4660,4661, +4662,4663,4664, +4665,4666,4667, +4668,4669,4670, +4671,4672,4673, +4674,4675,4676, +4677,4678,4679, +4680,4681,4682, +4683,4684,4685, +4686,4687,4688, +4689,4690,4691, +4692,4693,4694, +4695,4696,4697, +4698,4699,4700, +4701,4702,4703, +4704,4705,4706, +4707,4708,4709, +4710,4711,4712, +4713,4714,4715, +4716,4717,4718, +4719,4720,4721, +4722,4723,4724, +4725,4726,4727, +4728,4729,4730, +4731,4732,4733, +4734,4735,4736, +4737,4738,4739, +4740,4741,4742, +4743,4744,4745, +4746,4747,4748, +4749,4750,4751, +4752,4753,4754, +4755,4756,4757, +4758,4759,4760, +4761,4762,4763, +4764,4765,4766, +4767,4768,4769, +4770,4771,4772, +4773,4774,4775, +4776,4777,4778, +4779,4780,4781, +4782,4783,4784, +4785,4786,4787, +4788,4789,4790, +4791,4792,4793, +4794,4795,4796, +4797,4798,4799, +4800,4801,4802, +4803,4804,4805, +4806,4807,4808, +4809,4810,4811, +4812,4813,4814, +4815,4816,4817, +4818,4819,4820, +4821,4822,4823, +4824,4825,4826, +4827,4828,4829, +4830,4831,4832, +4833,4834,4835, +4836,4837,4838, +4839,4840,4841, +4842,4843,4844, +4845,4846,4847, +4848,4849,4850, +4851,4852,4853, +4854,4855,4856, +4857,4858,4859, +4860,4861,4862, +4863,4864,4865, +4866,4867,4868, +4869,4870,4871, +4872,4873,4874, +4875,4876,4877, +4878,4879,4880, +4881,4882,4883, +4884,4885,4886, +4887,4888,4889, +4890,4891,4892, +4893,4894,4895, +4896,4897,4898, +4899,4900,4901, +4902,4903,4904, +4905,4906,4907, +4908,4909,4910, +4911,4912,4913, +4914,4915,4916, +4917,4918,4919, +4920,4921,4922, +4923,4924,4925, +4926,4927,4928, +4929,4930,4931, +4932,4933,4934, +4935,4936,4937, +4938,4939,4940, +4941,4942,4943, +4944,4945,4946, +4947,4948,4949, +4950,4951,4952, +4953,4954,4955, +4956,4957,4958, +4959,4960,4961, +4962,4963,4964, +4965,4966,4967, +4968,4969,4970, +4971,4972,4973, +4974,4975,4976, +4977,4978,4979, +4980,4981,4982, +4983,4984,4985, +4986,4987,4988, +4989,4990,4991, +4992,4993,4994, +4995,4996,4997, +4998,4999,5000, +5001,5002,5003, +5004,5005,5006, +5007,5008,5009, +5010,5011,5012, +5013,5014,5015, +5016,5017,5018, +5019,5020,5021, +5022,5023,5024, +5025,5026,5027, +5028,5029,5030, +5031,5032,5033, +5034,5035,5036, +5037,5038,5039, +5040,5041,5042, +5043,5044,5045, +5046,5047,5048, +5049,5050,5051, +5052,5053,5054, +5055,5056,5057, +5058,5059,5060, +5061,5062,5063, +5064,5065,5066, +5067,5068,5069, +5070,5071,5072, +5073,5074,5075, +5076,5077,5078, +5079,5080,5081, +5082,5083,5084, +5085,5086,5087, +5088,5089,5090, +5091,5092,5093, +5094,5095,5096, +5097,5098,5099, +5100,5101,5102, +5103,5104,5105, +5106,5107,5108, +5109,5110,5111, +5112,5113,5114, +5115,5116,5117, +5118,5119,5120, +5121,5122,5123, +5124,5125,5126, +5127,5128,5129, +5130,5131,5132, +5133,5134,5135, +5136,5137,5138, +5139,5140,5141, +5142,5143,5144, +5145,5146,5147, +5148,5149,5150, +5151,5152,5153, +5154,5155,5156, +5157,5158,5159, +5160,5161,5162, +5163,5164,5165, +5166,5167,5168, +5169,5170,5171, +5172,5173,5174, +5175,5176,5177, +5178,5179,5180, +5181,5182,5183, +5184,5185,5186, +5187,5188,5189, +5190,5191,5192, +5193,5194,5195, +5196,5197,5198, +5199,5200,5201, +5202,5203,5204, +5205,5206,5207, +5208,5209,5210, +5211,5212,5213, +5214,5215,5216, +5217,5218,5219, +5220,5221,5222, +5223,5224,5225, +5226,5227,5228, +5229,5230,5231, +5232,5233,5234, +5235,5236,5237, +5238,5239,5240, +5241,5242,5243, +5244,5245,5246, +5247,5248,5249, +5250,5251,5252, +5253,5254,5255, +5256,5257,5258, +5259,5260,5261, +5262,5263,5264, +5265,5266,5267, +5268,5269,5270, +5271,5272,5273, +5274,5275,5276, +5277,5278,5279, +5280,5281,5282, +5283,5284,5285, +5286,5287,5288, +5289,5290,5291, +5292,5293,5294, +5295,5296,5297, +5298,5299,5300, +5301,5302,5303, +5304,5305,5306, +5307,5308,5309, +5310,5311,5312, +5313,5314,5315, +5316,5317,5318, +5319,5320,5321, +5322,5323,5324, +5325,5326,5327, +5328,5329,5330, +5331,5332,5333, +5334,5335,5336, +5337,5338,5339, +5340,5341,5342, +5343,5344,5345, +5346,5347,5348, +5349,5350,5351, +5352,5353,5354, +5355,5356,5357, +5358,5359,5360, +5361,5362,5363, +5364,5365,5366, +5367,5368,5369, +5370,5371,5372, +5373,5374,5375, +}; + #endif //SHAPE_DATA_H diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 5c235125f..f75e2c5e7 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -160,6 +160,16 @@ b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClie return 0; } +void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command->m_type == CMD_LOAD_MJCF); + if (command->m_type == CMD_LOAD_MJCF) + { + command->m_mjcfArguments.m_flags = flags; + command->m_updateFlags |= URDF_ARGS_HAS_CUSTOM_URDF_FLAGS; + } +} b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient) { diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 021bcf493..382e144d8 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -237,7 +237,7 @@ int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int fla b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName); b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName); b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClient, const char* fileName); - +void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags); ///compute the forces to achieve an acceleration, given a state q and qdot using inverse dynamics diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index bd18e3cf7..6e98ad191 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -5693,7 +5693,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm b3Printf("Processed CMD_LOAD_MJCF:%s", mjcfArgs.m_mjcfFileName); } bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? (mjcfArgs.m_useMultiBody!=0) : true; - int flags = CUF_USE_MJCF;//CUF_USE_URDF_INERTIA + int flags = CUF_USE_MJCF; + if (clientCmd.m_updateFlags&URDF_ARGS_HAS_CUSTOM_URDF_FLAGS) + { + flags |= clientCmd.m_mjcfArguments.m_flags; + } + bool completedOk = loadMjcf(mjcfArgs.m_mjcfFileName,bufferServerToClient, bufferSizeInBytes, useMultiBody, flags); if (completedOk) { diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index e1a494fb8..df9dbc14e 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -93,10 +93,13 @@ struct UrdfArgs int m_urdfFlags; }; + + struct MjcfArgs { char m_mjcfFileName[MAX_URDF_FILENAME_LENGTH]; int m_useMultiBody; + int m_flags; }; struct BulletDataStreamArgs diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 9a373b115..eccda8cfc 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -509,6 +509,8 @@ enum eURDF_Flags { URDF_USE_INERTIA_FROM_FILE=2,//sync with URDF2Bullet.h 'ConvertURDFFlags' URDF_USE_SELF_COLLISION=8,//see CUF_USE_SELF_COLLISION + URDF_USE_SELF_COLLISION_EXCLUDE_PARENT=16, + URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS=32, }; #endif//SHARED_MEMORY_PUBLIC_H diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 37134093c..5a74d2ad8 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -12,6 +12,7 @@ #include "../OpenGLWindow/ShapeData.h" #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btVector3.h" +#include "Bullet3Common/b3Logging.h" struct DepthShader : public IShader { @@ -72,6 +73,8 @@ struct Shader : public IShader { Matrix& m_lightModelView; Vec4f m_colorRGBA; Matrix& m_viewportMat; + Matrix m_projectionModelViewMat; + Matrix m_projectionLightViewMat; float m_ambient_coefficient; float m_diffuse_coefficient; float m_specular_coefficient; @@ -87,6 +90,7 @@ struct Shader : public IShader { mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS mat<4,3,float> varying_tri_light_view; mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS + mat<4,3,float> world_tri; // model triangle coordinates in the world space used for backface culling, written by VS Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Matrix& viewportMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray* shadowBuffer, float ambient_coefficient=0.6, float diffuse_coefficient=0.35, float specular_coefficient=0.05) :m_model(model), @@ -109,8 +113,11 @@ struct Shader : public IShader { { m_invModelMat = m_modelMat.invert_transpose(); + m_projectionModelViewMat = m_projectionMat*m_modelView1; + m_projectionLightViewMat = m_projectionMat*m_lightModelView; } virtual Vec4f vertex(int iface, int nthvert) { + B3_PROFILE("vertex"); Vec2f uv = m_model->uv(iface, nthvert); varying_uv.set_col(nthvert, uv); varying_nrm.set_col(nthvert, proj<3>(m_invModelMat*embed<4>(m_model->normal(iface, nthvert), 0.f))); @@ -118,14 +125,17 @@ struct Shader : public IShader { Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0], unScaledVert[1]*m_localScaling[1], unScaledVert[2]*m_localScaling[2]); - Vec4f gl_Vertex = m_projectionMat*m_modelView1*embed<4>(scaledVert); + Vec4f gl_Vertex = m_projectionModelViewMat*embed<4>(scaledVert); varying_tri.set_col(nthvert, gl_Vertex); - Vec4f gl_VertexLightView = m_projectionMat*m_lightModelView*embed<4>(scaledVert); + Vec4f world_Vertex = m_modelMat*embed<4>(scaledVert); + world_tri.set_col(nthvert, world_Vertex); + Vec4f gl_VertexLightView = m_projectionLightViewMat*embed<4>(scaledVert); varying_tri_light_view.set_col(nthvert, gl_VertexLightView); return gl_Vertex; } virtual bool fragment(Vec3f bar, TGAColor &color) { + B3_PROFILE("fragment"); Vec4f p = m_viewportMat*(varying_tri_light_view*bar); float depth = p[2]; p = p/p[3]; @@ -492,14 +502,25 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); + Matrix viewMatrixInv = renderData.m_viewMatrix.invert(); + btVector3 P(viewMatrixInv[0][3], viewMatrixInv[1][3], viewMatrixInv[2][3]); Shader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowBufferPtr, renderData.m_lightAmbientCoeff, renderData.m_lightDiffuseCoeff, renderData.m_lightSpecularCoeff); for (int i=0; infaces(); i++) { + B3_PROFILE("face"); for (int j=0; j<3; j++) { shader.vertex(i, j); } + + // backface culling + btVector3 v0(shader.world_tri.col(0)[0], shader.world_tri.col(0)[1], shader.world_tri.col(0)[2]); + btVector3 v1(shader.world_tri.col(1)[0], shader.world_tri.col(1)[1], shader.world_tri.col(1)[2]); + btVector3 v2(shader.world_tri.col(2)[0], shader.world_tri.col(2)[1], shader.world_tri.col(2)[2]); + btVector3 N = (v1-v0).cross(v2-v0); + if ((v0-P).dot(N) >= 0) + continue; mat<4,3,float> stackTris[3]; diff --git a/examples/pybullet/examples/dumpVrLog.py b/examples/pybullet/examples/dumpVrLog.py new file mode 100644 index 000000000..0fe87cdf0 --- /dev/null +++ b/examples/pybullet/examples/dumpVrLog.py @@ -0,0 +1,108 @@ +import time +import math +from datetime import datetime +import struct +import sys +import os, fnmatch +import argparse +from time import sleep + +def readLogFile(filename, verbose = True): + f = open(filename, 'rb') + + print('Opened'), + print(filename) + + keys = f.readline().decode('utf8').rstrip('\n').split(',') + fmt = f.readline().decode('utf8').rstrip('\n') + + # The byte number of one record + sz = struct.calcsize(fmt) + # The type number of one record + ncols = len(fmt) + + if verbose: + print('Keys:'), + print(keys) + print('Format:'), + print(fmt) + print('Size:'), + print(sz) + print('Columns:'), + print(ncols) + + # Read data + wholeFile = f.read() + # split by alignment word + chunks = wholeFile.split(b'\xaa\xbb') + log = list() + if verbose: + print("num chunks:") + print(len(chunks)) + chunkIndex = 0 + for chunk in chunks: + print("len(chunk)=",len(chunk)," sz = ", sz) + if len(chunk) == sz: + print("chunk #",chunkIndex) + chunkIndex=chunkIndex+1 + values = struct.unpack(fmt, chunk) + record = list() + for i in range(ncols): + record.append(values[i]) + if verbose: + print(" ",keys[i],"=",values[i]) + + log.append(record) + + return log + + +numArgs = len(sys.argv) + +print ('Number of arguments:', numArgs, 'arguments.') +print ('Argument List:', str(sys.argv)) +fileName = "data/example_log_vr.bin" + +if (numArgs>1): + fileName = sys.argv[1] + +print("filename=") +print(fileName) + +verbose = True + +log = readLogFile(fileName,verbose) + +# the index of the first integer in the vr log file for packed buttons +firstPackedButtonIndex = 13 +# the number of packed buttons in one integer +numGroupedButtons = 10 +# the number of integers for packed buttons +numPackedButtons = 7 +# the mask to get the button state +buttonMask = 7 + +for record in log: + # indices of buttons that are down + buttonDownIndices = [] + # indices of buttons that are triggered + buttonTriggeredIndices = [] + # indices of buttons that are released + buttonReleasedIndices = [] + buttonIndex = 0 + for packedButtonIndex in range(firstPackedButtonIndex, firstPackedButtonIndex+numPackedButtons): + for packButtonShift in range(numGroupedButtons): + buttonEvent = buttonMask & record[packedButtonIndex] + if buttonEvent & 1: + buttonDownIndices.append(buttonIndex) + elif buttonEvent & 2: + buttonTriggeredIndices.append(buttonIndex) + elif buttonEvent & 4: + buttonReleasedIndices.append(buttonIndex) + record[packedButtonIndex] = record[packedButtonIndex] >> 3 + buttonIndex += 1 + if len(buttonDownIndices) or len(buttonTriggeredIndices) or len(buttonReleasedIndices): + print ('timestamp: ', record[1]) + print ('button is down: ', buttonDownIndices) + print ('button is triggered: ', buttonTriggeredIndices) + print ('button is released: ', buttonReleasedIndices) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 726abebac..372b281a2 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -563,8 +563,10 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key int bodyIndicesOut[MAX_SDF_BODIES]; PyObject* pylist = 0; int physicsClientId = 0; - static char* kwlist[] = {"mjcfFileName", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &mjcfFileName, &physicsClientId)) + int flags = -1; + + static char* kwlist[] = {"mjcfFileName", "flags", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|ii", kwlist, &mjcfFileName, &flags, &physicsClientId)) { return NULL; } @@ -576,6 +578,10 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key } command = b3LoadMJCFCommandInit(sm, mjcfFileName); + if (flags>=0) + { + b3LoadMJCFCommandSetFlags(command,flags); + } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); if (statusType != CMD_MJCF_LOADING_COMPLETED) @@ -3206,8 +3212,8 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb static PyObject* pybullet_submitProfileTiming(PyObject* self, PyObject* args, PyObject* keywds) { - b3SharedMemoryStatusHandle statusHandle; - int statusType; +// b3SharedMemoryStatusHandle statusHandle; +// int statusType; char* eventName = 0; int duractionInMicroSeconds=-1; @@ -6208,6 +6214,8 @@ initpybullet(void) PyModule_AddIntConstant(m, "URDF_USE_INERTIA_FROM_FILE", URDF_USE_INERTIA_FROM_FILE); PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION", URDF_USE_SELF_COLLISION); + PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_PARENT", URDF_USE_SELF_COLLISION_EXCLUDE_PARENT); + PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS", URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS); PyModule_AddIntConstant(m, "MAX_RAY_INTERSECTION_BATCH_SIZE", MAX_RAY_INTERSECTION_BATCH_SIZE); diff --git a/examples/pybullet/tensorflow/humanoid_running.py b/examples/pybullet/tensorflow/humanoid_running.py new file mode 100644 index 000000000..d54d08d44 --- /dev/null +++ b/examples/pybullet/tensorflow/humanoid_running.py @@ -0,0 +1,648 @@ +import tensorflow as tf +import sys +import numpy as np + +import pybullet as p +import time +p.connect(p.GUI) #GUI is slower, but shows the running gait +p.setGravity(0,0,-9.8) +p.setPhysicsEngineParameter(fixedTimeStep=1.0/60., numSolverIterations=5, numSubSteps=2) +#this mp4 recording requires ffmpeg installed +#mp4log = p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4,"humanoid.mp4") + + +plane, human1 = p.loadMJCF("mjcf/humanoid_symmetric.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS) +p.removeBody(plane) +print (human1) +p.resetBasePositionAndOrientation(human1,[0,1,1.5],[0,0,0,1]) + +plane, human2 = p.loadMJCF("mjcf/humanoid_symmetric.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS) +p.resetBasePositionAndOrientation(human2,[0,2,1.5],[0,0,0,1]) +p.removeBody(plane) + +plane, human = p.loadMJCF("mjcf/humanoid_symmetric.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS) + +ordered_joints = [] + +jdict = {} +for j in range( p.getNumJoints(human) ): + info = p.getJointInfo(human, j) + link_name = info[12].decode("ascii") + if link_name=="left_foot": left_foot = j + if link_name=="right_foot": right_foot = j + if info[2] != p.JOINT_REVOLUTE: continue + jname = info[1].decode("ascii") + jdict[jname] = j + lower, upper = (info[8], info[9]) + ordered_joints.append( (j, lower, upper) ) + p.setJointMotorControl2(human, j, controlMode=p.VELOCITY_CONTROL, force=0) + p.setJointMotorControl2(human1, j, controlMode=p.VELOCITY_CONTROL, force=0) + p.setJointMotorControl2(human2, j, controlMode=p.VELOCITY_CONTROL, force=0) + + + +motor_names = ["abdomen_z", "abdomen_y", "abdomen_x"] +motor_power = [100, 100, 100] +motor_names += ["right_hip_x", "right_hip_z", "right_hip_y", "right_knee"] +motor_power += [100, 100, 300, 200] +motor_names += ["left_hip_x", "left_hip_z", "left_hip_y", "left_knee"] +motor_power += [100, 100, 300, 200] +motor_names += ["right_shoulder1", "right_shoulder2", "right_elbow"] +motor_power += [75, 75, 75] +motor_names += ["left_shoulder1", "left_shoulder2", "left_elbow"] +motor_power += [75, 75, 75] +motors = [jdict[n] for n in motor_names] + +class Dummy: + pass +dummy = Dummy() +dummy.initial_z = None + +def current_relative_position(human, j, lower, upper): + #print("j") + #print(j) + pos, vel, *other = p.getJointState(human, j) + #print("pos") + #print(pos) + #print("vel") + #print(vel) + pos_mid = 0.5 * (lower + upper); + return ( + 2 * (pos - pos_mid) / (upper - lower), + 0.1 * vel + ) + +def collect_observations(human): + j = np.array([current_relative_position(human, *jtuple) for jtuple in ordered_joints]).flatten() + #print("j") + #print(j) + body_xyz, (qx, qy, qz, qw) = p.getBasePositionAndOrientation(human) + #print("body_xyz") + #print(body_xyz, qx,qy,qz,qw) + z = body_xyz[2] + dummy.distance = body_xyz[0] + if dummy.initial_z==None: + dummy.initial_z = z + (vx, vy, vz), _ = p.getBaseVelocity(human) + more = np.array([z-dummy.initial_z, 0.1*vx, 0.1*vy, 0.1*vz, qx, qy, qz, qw]) + rcont = p.getContactPoints(human, -1, right_foot, -1) + #print("rcont") + #print(rcont) + lcont = p.getContactPoints(human, -1, left_foot, -1) + #print("lcont") + #print(lcont) + feet_contact = np.array([len(rcont)>0, len(lcont)>0]) + return np.clip( np.concatenate([more] + [j] + [feet_contact]), -5, +5) + +class SmallReactivePolicy(object): + def __init__(self, name, ob_space, ac_space): + self.name = name + with tf.variable_scope(name): + batch_of_observations = [None] + list(ob_space.shape) + self.ob = tf.placeholder(dtype=tf.float32, shape=batch_of_observations, name="ob") + x = self.ob + + width = 256 + self.dense1_w = tf.get_variable("dense1_w", [x.get_shape()[1], width]) + self.dense1_b = tf.get_variable("dense1_b", [width]) + x = tf.nn.relu(tf.matmul(x, self.dense1_w) + self.dense1_b) + + width = 128 + self.dense2_w = tf.get_variable("dense2_w", [x.get_shape()[1], width]) + self.dense2_b = tf.get_variable("dense2_b", [width]) + x = tf.nn.relu(tf.matmul(x, self.dense2_w) + self.dense2_b) + + assert(len(ac_space.shape)==1) + width = ac_space.shape[0] + self.final_w = tf.get_variable("final_w", [x.get_shape()[1], width]) + self.final_b = tf.get_variable("final_b", [width]) + x = tf.matmul(x, self.final_w) + self.final_b + self.action_node = x + + self.all_variables = tf.get_collection(tf.GraphKeys.TRAINABLE_VARIABLES, tf.get_variable_scope().name) + + def act(self, ob): + a = tf.get_default_session().run(self.action_node, feed_dict={ self.ob: ob[None] }) + return a[0] + + def load_weights(self): + assigns = [ + (self.dense1_w, weights_dense1_w), + (self.dense1_b, weights_dense1_b), + (self.dense2_w, weights_dense2_w), + (self.dense2_b, weights_dense2_b), + (self.final_w, weights_final_w), + (self.final_b, weights_final_b)] + to_run = [] + feed_dict = {} + for var, w in assigns: + ph = tf.placeholder(tf.float32, w.shape) + to_run.append( tf.assign(var, ph) ) + feed_dict[ph] = w + tf.get_default_session().run(to_run, feed_dict=feed_dict) + +def demo_run(): + sess = tf.InteractiveSession(config=tf.ConfigProto(inter_op_parallelism_threads=1, intra_op_parallelism_threads=1, device_count={ "GPU": 0 })) + pi = SmallReactivePolicy("pi", np.zeros((44,)), np.zeros((17,))) + pi.load_weights() + t1 = time.time() + timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "humanoidTimings.json") + + frame = 0 + while 1: + obs = collect_observations(human) + obs1 = collect_observations(human1) + obs2 = collect_observations(human2) + + actions = pi.act(obs) + actions1 = pi.act(obs1) + actions2 = pi.act(obs2) + + #print(" ".join(["%+0.2f"%x for x in obs])) + #print("Motors") + #print(motors) + + #for m in range(len(motors)): + #print("motor_power") + #print(motor_power[m]) + #print("actions[m]") + #print(actions[m]) + #p.setJointMotorControl2(human, motors[m], controlMode=p.TORQUE_CONTROL, force=motor_power[m]*actions[m]*0.082) + #p.setJointMotorControl2(human1, motors[m], controlMode=p.TORQUE_CONTROL, force=motor_power[m]*actions[m]*0.082) + + forces = [0.] * len(motors) + for m in range(len(motors)): + forces[m] = motor_power[m]*actions[m]*0.082 + p.setJointMotorControlArray(human, motors,controlMode=p.TORQUE_CONTROL, forces=forces) + for m in range(len(motors)): + forces[m] = motor_power[m]*actions1[m]*0.082 + p.setJointMotorControlArray(human1, motors,controlMode=p.TORQUE_CONTROL, forces=forces) + for m in range(len(motors)): + forces[m] = motor_power[m]*actions2[m]*0.082 + p.setJointMotorControlArray(human2, motors,controlMode=p.TORQUE_CONTROL, forces=forces) + + p.stepSimulation() + #time.sleep(0.01) + distance=5 + yaw = 0 + humanPos, humanOrn = p.getBasePositionAndOrientation(human) + p.resetDebugVisualizerCamera(distance,yaw,20,humanPos); + frame += 1 + + if frame==1000: break + t2 = time.time() + print("############################### distance = %0.2f meters" % dummy.distance) + print("############################### FPS = ", 1000/ (t2-t1)) + #print("Starting benchmark") + #logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS,"pybullet_humanoid_timings.json") + #p.stopStateLogging(logId) + print("ended benchmark") + print(frame) + p.stopStateLogging(timinglog) + + +weights_dense1_w = np.array([ +[ -0.3857, -0.7450, +0.1473, +0.1996, +0.0570, +0.4522, +0.1172, +0.7558, -0.2530, -0.7948, +0.3120, +0.6216, +0.1044, -0.4347, +0.0921, +0.0187, +0.2030, +0.2042, -0.2928, +0.2717, +0.5117, +0.1115, -0.0278, -0.0675, -0.2967, +0.3128, -0.1434, -0.0476, +0.0561, -0.1874, +0.1675, -0.1028, +0.0712, +0.8653, -0.5565, -0.1207, +0.0982, -0.2875, -0.0755, -0.3057, -0.0841, +0.5336, +0.2068, -0.0132, -0.2131, -0.5910, +0.1329, +0.2789, +0.0036, +0.0048, +0.2655, +0.3585, +0.2861, -0.2288, -0.0646, +0.0569, -0.4701, -0.0116, +0.4616, +0.0947, -0.1013, -0.0256, +0.2854, +0.3382, +0.0822, +0.1160, -0.4913, +0.3991, +0.0121, -0.3392, +0.2515, +0.7188, +0.3412, +0.1247, +0.1422, +0.0420, +0.1401, +0.5830, +0.0226, +0.6080, +0.3019, -0.7696, -0.0580, +0.2104, +0.3786, +0.2968, -0.3726, +0.2792, +0.3572, -0.4362, +0.5368, +0.0068, +0.4366, -0.4799, +0.2688, +0.1115, +0.0251, +0.4107, -0.0358, +0.0198, +0.2563, +0.0315, -0.1143, +0.6191, +0.1694, +0.4175, +0.1873, +0.0678, +0.1324, +0.3038, +0.0610, +0.2491, -0.2730, +0.2933, +0.1704, +0.1746, +0.1444, -0.2578, +0.3743, +0.3837, +0.3294, +0.0433, +0.5242, -0.3465, +0.1618, -0.5255, -0.1703, +0.0420, +0.5505, +0.4046, +0.1596, +0.3973, -0.5158, -0.2922, +0.3183, -0.0244, +0.3496, +0.4069, -0.1961, +0.2705, -0.1008, -0.4008, -0.1443, -0.2113, +0.2064, -0.3466, +0.2565, +0.0279, +0.5785, -0.2918, +0.7262, +0.0285, -0.1779, +0.2811, -0.2066, +0.5471, -0.7668, +0.1909, -0.5684, -0.0002, +0.2291, -0.0631, +0.0823, +0.5520, -0.3267, +0.0143, +0.4295, +0.2594, +0.3523, -0.1266, +0.4412, -0.2685, +0.0863, +0.1779, +0.1280, +0.5087, +0.0809, +0.1118, -0.5754, -0.3300, -0.0032, +0.7060, -0.5172, -0.6553, -0.0951, -0.0129, +0.1382, -0.0504, -0.2634, +0.2659, -0.1932, -0.3762, +0.3072, +0.1612, +0.2942, -0.1438, -0.0850, +0.1877, +0.4726, +0.2751, -0.0787, +0.3128, -0.1351, +0.2552, -0.4833, -0.0322, +0.3641, +0.3715, -0.1938, +0.5040, -0.0598, +0.0341, +0.6252, -0.2977, +0.2694, +0.0525, +0.6295, -0.1007, -0.0406, +0.1028, +0.5181, +0.2201, +0.2269, +0.3724, -0.1985, -0.1614, +0.0093, +0.2851, +0.0191, +0.0620, +0.1989, +0.5905, +0.5589, +0.1896, +0.3859, +0.1207, -0.0323, +0.3912, +0.2950, +0.3255, +0.2765, -0.3384, +0.4286, +0.2692, +0.2889, +0.5955, +0.0918, -0.3228, +0.3828, -0.0196, -0.0484, +0.3256, -0.1361, +0.5124, -0.1782, +0.2984], +[ -0.3305, -0.5427, +0.1033, -0.8093, -0.6948, +1.0265, +0.2688, -0.4297, -0.3887, -0.0335, -0.4224, +0.0902, -0.0416, -0.3621, +0.4824, -0.5138, -0.6160, +0.0404, -1.0360, +0.2734, +0.3415, -0.7259, -0.3395, -0.2803, +0.6166, +0.3448, +0.3657, +0.0495, +0.8924, +0.1673, +0.2726, +1.2509, -0.0482, +0.2982, -0.0817, -0.6190, -0.7550, -0.6310, +0.1912, +0.2475, -0.4001, +0.2715, -1.3571, -1.2735, +0.4491, +0.0965, +0.3893, -0.1449, +0.5919, -0.7355, -0.2579, -0.6447, -0.8400, -1.0339, -0.7232, +0.2704, -0.2094, -0.9082, +0.0719, -0.9922, +0.7732, -0.1924, -0.7696, -0.3170, -0.3350, -0.3462, +0.3686, +0.7608, -0.3624, +0.0222, +0.0152, +0.0056, -0.6305, +0.3649, +0.4987, -0.2182, -0.6930, -0.0010, -0.2901, -0.1365, -0.4998, +0.2176, +0.4334, -0.2511, +0.5084, -0.4405, +0.8559, -0.4784, +0.0126, -0.1106, +0.8800, -0.7713, +0.2210, +0.1882, +0.0233, -0.0679, +0.0100, -0.6957, +0.4229, +0.4257, +0.1985, +0.9668, -1.0394, +0.1009, -1.1962, -0.6810, -0.8522, -0.9797, -0.4765, +0.6148, -0.1001, +0.1577, -0.5535, -0.6540, -0.0717, -1.4224, -0.4940, +0.3266, -0.3978, +0.2954, +0.2281, -0.5369, +0.2422, -0.2924, +0.2163, +0.7444, +0.4338, -0.5244, +0.2214, +0.5298, -0.1770, -0.3549, +0.0541, -0.1783, -0.1656, +0.9927, -0.9395, +0.6691, -0.2921, -1.1986, -0.2086, +0.1251, +0.3633, -0.1052, -0.4214, +0.1419, +0.7749, -0.0831, -0.8905, +0.5360, +0.0565, -2.0616, -1.4039, -0.7739, +0.2181, +0.3649, +0.2573, -0.1620, -0.2045, -0.4774, +0.4206, +0.4216, +0.0844, -0.3038, +0.2918, -1.4121, -1.0846, -0.5310, +0.2190, +0.3286, -0.1058, -0.8251, -0.0417, -0.3994, -0.0012, +0.4315, +0.1682, -1.1433, +0.2849, -0.5689, -0.3473, +0.6981, -0.1699, -0.1203, -1.3225, -0.2436, -0.2331, +0.2366, +0.0377, -0.4367, -0.0645, -1.3493, -0.3995, -0.4136, +0.4007, -0.4532, +0.1397, -0.4860, +0.7116, -1.0520, -0.7300, +0.9354, +0.2490, -0.0118, -0.6467, +1.0208, -0.0185, -0.1010, +0.0259, -0.4621, -0.5824, -0.5307, -0.3225, +0.1271, -0.0694, -0.0902, +0.4922, +0.2764, -0.1927, -0.2009, -0.8424, +0.0237, -0.0958, +0.3260, -1.3182, -0.7006, +0.2267, -0.9277, +0.1478, +0.1729, +0.3861, -0.6517, -0.3447, +0.4089, +0.1253, -0.3610, +0.7556, -0.5048, -0.8110, +0.1085, -0.9362, -0.8233, +0.4134, -0.0085, -1.5413, -0.4102, +0.7793, -1.2224, -0.7392, -0.3367, -0.0849, +0.0131, +0.8377, +0.4575, +0.8130, -2.0800], +[ -0.5030, +0.4311, -1.1143, -0.2571, +0.0500, +0.6580, +0.1807, +0.3972, +1.0069, -1.9235, -0.4153, +1.2305, -0.0986, +1.6550, -2.0094, -0.5650, +0.1596, +2.2019, +0.1256, +1.7433, -1.8320, +1.2385, +0.2217, +1.9671, -0.0651, -1.5623, +0.6551, -1.0514, -0.2327, -0.7264, +1.1247, +0.7084, -3.1100, +2.5875, -0.6701, +0.5488, +0.2897, +0.3663, +0.0783, -0.2380, -0.9809, -1.4906, -0.0467, -0.3069, -1.3131, -1.1489, +0.4462, -0.0183, -0.7812, -1.0135, -0.8092, -0.3989, -0.0717, -2.4097, -0.4086, -1.3601, +0.4654, -1.2662, +0.9914, -1.6910, -0.4650, -1.1016, +0.0476, +0.4011, +0.1599, -0.2772, +0.1293, -0.1329, +2.4128, +0.3290, -0.0782, -1.8737, -2.1851, -0.2125, +1.0481, -2.0785, -0.7290, -0.7160, -0.0253, -0.7524, +0.2129, -0.2267, -0.8073, +0.1843, +0.7838, +1.0147, +0.1327, -0.0788, +0.3903, +2.0292, +2.5541, +1.6453, -0.1778, -2.1681, -0.1496, -0.3376, +0.4545, +0.2194, -1.5197, -1.2230, +3.2199, +1.0545, +0.1571, +0.8699, -4.2024, +0.9999, +1.8670, +0.3410, +2.0595, -0.1076, +1.5986, -0.3768, -0.7450, -1.0840, -0.0150, -3.7617, +1.4254, +0.8361, +0.2078, -0.8808, -0.2463, -3.4380, +1.4160, -1.9439, -1.0356, +2.8675, +0.9860, -3.6350, -0.8313, +0.2089, +1.3341, -2.8791, +0.4524, +0.4555, -0.9851, +0.6086, +0.7343, +1.3275, +1.0979, -2.4916, +0.0722, -0.7323, +0.9880, +1.5356, +0.5431, -0.3248, -0.9631, +0.7564, +0.7160, -0.0709, -1.5644, +1.2694, +2.5064, -2.5448, -1.7748, -1.1803, -1.1250, -0.2383, -1.1826, -1.1312, +1.7279, -0.3852, +0.0540, -0.9594, -0.7022, -2.7155, +1.2207, -0.4283, +0.2370, -1.1960, +1.0917, -0.3953, -0.5567, -2.5472, -2.0418, -0.6104, +3.4862, -0.4001, +0.9669, -0.7622, +0.1008, -1.7957, +1.0803, -0.3787, -0.5001, -0.8955, +0.8044, +2.5939, +1.5200, +0.9680, +0.4177, -0.2482, +2.2624, -1.1416, -1.5353, +2.2794, -1.8803, +0.2573, -0.3707, +2.0442, +2.7544, +1.6080, -0.6924, -0.8825, +2.8865, -0.7160, -1.4308, -0.0376, +0.3018, +1.8101, +0.3378, -0.3874, -0.3636, -0.5764, -1.0234, +2.6209, +1.1319, +1.4093, +0.6829, -1.3812, +1.8284, +0.1921, -0.0356, -2.3225, -0.8761, +1.8518, -1.0584, -0.8935, -0.6575, +0.3690, -0.9779, +0.2513, +0.4220, +1.2618, +2.0158, +0.1686, +1.9862, +0.6183, -1.2881, -1.7737, +0.0968, -0.8762, -0.9781, -1.3425, -2.6438, +0.8928, +0.3356, +0.1711, +1.9928, +0.5683, +2.1339, -0.5671, -0.2999, +0.2771, +1.8581, -0.7244], +[ -0.8237, -2.4723, -0.0093, -1.0811, +0.5365, +0.6595, -0.5366, +1.1555, -0.8875, -1.3330, +1.4121, -0.0944, -0.0463, -0.9496, -2.8476, -0.7136, +0.6020, -0.0054, -1.4527, +0.9208, +0.3012, -0.1480, -0.8642, +0.1982, +0.1088, +1.2782, -0.7724, -1.3168, -0.9594, -1.1935, -0.3237, -0.6884, -0.1389, +0.7907, -2.4444, -0.4292, -0.1315, -1.2616, -0.0916, -1.7440, -1.5036, +0.1978, +1.2539, +0.7862, +0.0931, -1.4788, +0.1313, -0.0527, -1.4072, +0.4968, -0.2224, +0.3658, +1.6503, -0.2057, -0.6812, -0.2703, -1.6274, +1.0684, +1.2275, +0.1127, -2.2420, -0.1408, -0.2346, -0.1119, +0.1498, -0.0589, -1.4065, -0.1043, +1.4940, -0.2420, -0.2223, -0.0973, +0.5512, -1.6769, +0.3286, +0.5443, -0.1542, +0.9522, -0.8605, +1.4236, +1.6691, -1.5443, -1.4476, -0.2985, +0.5213, -0.6793, -1.4328, -0.4417, -0.0097, -0.3373, -0.0559, -0.3530, +0.5015, -2.2177, -0.8512, -1.4107, -0.2278, +1.0842, -0.6454, -0.6701, +0.2807, -2.3556, +0.6937, -0.1830, +0.2528, +1.4582, +0.9585, +0.7474, -0.2290, -0.3547, -0.0505, +0.8672, -1.3728, +0.3593, -1.5079, +1.2051, +0.1671, +0.1287, -0.1089, +0.9447, +0.2902, -0.0274, +2.6386, -0.4357, -1.0866, -0.7725, -0.7474, -0.2920, -0.7512, +0.2729, -0.2291, +0.4386, -0.2122, -1.0203, +0.5233, -0.3802, -0.1169, +0.1006, -0.5432, -0.2080, +0.6461, -1.4341, +0.0192, -1.2795, +0.8708, -0.3168, -0.4657, +0.5388, +0.8268, -0.9466, -0.4054, +1.5877, +0.1454, +0.5291, -0.8998, +1.3563, -1.8375, -1.0953, -1.6413, +0.2750, +1.0708, -0.9597, -0.3052, -0.0953, -2.2925, -0.0300, +1.2808, +1.3430, -0.0976, -0.7264, +1.1371, -0.7336, +0.1982, -0.6328, -0.0308, +0.8406, -0.1227, -0.1331, -2.1831, -0.5677, +0.4565, -0.1594, -1.8026, -0.1020, +1.3437, -0.2881, +1.0612, -0.9352, -0.2676, +0.2737, +0.6647, -0.4582, -0.3532, -0.2741, -0.5150, -0.2847, +0.3100, +1.0055, +0.6360, +1.2014, -1.0370, +0.3126, +0.2799, +1.4690, +0.2299, -0.9563, +0.1604, +1.0580, -0.0236, +0.5362, -1.1913, -1.6834, -0.5451, -0.2479, +0.5986, +0.9416, +0.8835, -0.8778, -1.5741, +0.2702, +0.9200, -1.2569, -0.0010, +0.7474, +1.0404, +0.0567, +0.7431, -0.5104, +0.2774, -0.3255, +0.0748, +0.5445, +2.7912, +0.1370, +0.0845, -0.2513, -0.2607, +0.5337, -0.9225, +1.1601, +0.3889, -1.9067, +0.0405, +0.8032, +0.3716, +1.0054, -0.1264, -1.2699, +1.0490, -0.4518, -0.4633, +0.2149, -0.0493, +0.4784, -0.4567, -1.1741], +[ -0.0944, +0.0480, +1.3354, +0.4432, +0.4545, +0.3836, +0.7112, -1.3257, -0.6328, -0.0922, +0.1074, +0.9008, +0.8560, -0.7031, +0.6321, -0.5160, -0.0619, -2.3403, +0.1938, -1.3679, -0.0181, -0.1057, -0.2195, -1.2982, +0.9032, +0.4164, -0.7188, -0.5110, +0.6287, +1.9699, -1.0438, -0.3658, +0.3573, -1.1268, +0.8508, -0.2637, +0.4056, +0.0488, -0.1575, -0.0724, +1.3003, +0.7745, -1.0815, -0.1154, +0.3653, +0.4608, -0.6923, +0.1087, +0.1252, +1.0462, -0.8961, +0.3603, -0.5450, +1.1358, -0.2845, +0.3265, -0.8838, +1.1137, -0.6003, -0.6661, +0.6010, +0.3586, +0.8275, +0.7424, +0.8698, +0.4970, +0.5513, +1.1435, -0.3027, -0.6154, -0.1741, +1.3238, +0.2132, -0.2333, -0.1694, +0.7055, -0.8932, -0.0664, +0.3277, -0.5222, -0.3499, -0.3942, -0.4391, +0.0751, -0.7457, -1.1832, -0.4438, -0.3663, -1.0466, +0.1051, -1.1153, +0.4985, -0.2054, -0.0507, +0.3941, -0.1353, -0.4284, +0.2639, +0.4999, +0.8301, -0.7917, -0.3978, -0.0342, +0.1796, +0.3845, -1.4847, -0.4932, -0.1793, -0.9531, +0.5409, -0.7341, +0.7626, +0.3836, +0.5465, +0.1335, -0.2535, -0.4195, -0.7734, -0.0282, +0.0965, +0.0656, +0.9656, -0.8877, +0.8172, -0.1439, -1.4527, -0.0562, +1.5419, +0.0539, -0.5125, +0.5689, +0.1007, -1.2620, +0.3370, -0.1986, -0.2692, -1.2472, -0.7832, -0.6892, +0.6072, +0.0229, +0.4541, -0.4522, +0.0858, -0.8327, -0.0613, +0.3183, -0.3064, -1.0261, +0.5405, +1.0349, -0.2815, -0.6725, +0.4688, +1.6724, -0.0363, -0.0079, -0.0928, +0.3130, -0.2153, -0.5456, -0.0559, -0.2529, +0.3921, +0.3518, +0.2280, -0.1720, +1.0129, +0.7512, +0.6854, -0.4686, -0.1534, +0.8615, +0.8109, +0.7310, +0.3680, -1.4893, -0.7378, -0.4477, +0.0875, -0.4890, +1.8208, -0.0533, -0.3616, +0.4427, +0.3344, -1.6178, -0.3798, -1.3912, -0.4389, -0.6612, +0.0819, -1.6541, +0.8210, +0.3600, -0.7912, +0.8786, -0.6454, -0.3264, -1.2999, -1.7624, +0.1224, -0.1934, +0.5783, -1.7141, +0.8077, +1.2373, -0.6583, -0.5147, -0.3372, +0.4648, +0.9727, +0.6322, -1.1757, +0.0907, -0.7186, -0.0748, +0.5319, -0.7838, +0.7031, -1.4109, -0.2312, +0.0961, +1.0103, -0.3424, -0.2508, +0.4101, +0.7785, +0.6908, +0.1522, +0.8434, -0.3437, -0.1315, -0.5243, +0.1131, -0.0426, -0.4195, +0.5145, +0.4746, -0.1487, +0.3564, +0.6381, +0.7912, -0.5876, +0.4997, -0.0617, -0.3899, +0.5708, -1.2090, +0.4058, -0.7794, +0.3661, +0.4308, -0.3041, -0.0436, -0.7230], +[ -0.1693, +0.2109, +0.3784, -0.0080, +0.5547, +0.4148, +0.3266, -1.0521, +0.3823, -0.1225, -0.8964, -0.1654, -1.3043, +0.2666, -0.0568, -0.1568, -0.0791, -0.4838, -0.8760, +0.4993, +0.6268, -0.7398, -0.6804, -0.2253, +1.2625, -0.2067, +0.0057, +0.9870, +0.8815, +1.1994, +0.3070, +1.1701, -0.3489, -0.0767, +0.2292, -0.4519, -2.2981, -1.1613, -0.1678, -0.6078, +0.2043, -0.5179, -0.5619, -0.2558, -0.9022, +1.1423, +0.1024, +0.6167, +0.3965, -0.8278, -0.2011, -0.8241, -1.6596, +0.0758, -0.0408, +0.2526, +0.1655, -1.0185, +0.4132, -0.4839, +1.2156, -1.1229, -1.2566, +0.7611, +0.5421, -1.0482, +0.8612, +0.9921, -1.1233, +1.7774, -0.1655, -0.2706, -1.0794, +0.9931, -0.1433, -0.3584, +0.0190, -0.3132, +0.0309, +0.1503, -0.3054, +0.9918, +0.3700, -0.7727, +0.1072, -1.0991, +0.4594, -0.7141, +0.6146, -0.0139, +0.8529, +0.5119, +0.7132, +0.4453, +0.5105, +0.0267, -0.4190, -0.7954, +0.8213, +0.6556, +0.5070, +0.6732, -0.2794, +0.9429, -0.3095, -0.5547, -0.4120, -1.4048, +0.2273, +0.4487, +0.3343, +0.7247, +0.3450, -0.6724, +0.6049, -0.3514, +0.3779, -0.6072, -1.0495, +0.5256, +1.0763, -0.2961, +0.1332, -0.5312, +0.1100, +0.3449, +1.6291, +0.2253, +0.2368, +0.0290, -0.2767, -1.1455, -0.2682, +0.1284, -1.4564, +0.6327, -0.1539, +1.2590, -0.3506, -0.9105, -0.1498, +0.1575, +0.6813, -0.2192, -0.2872, +0.1151, +0.8868, +0.1692, -0.6037, +0.4819, +0.3007, -1.5199, -0.8464, -1.0408, +0.4265, +0.7844, +0.8532, -0.0920, +0.1953, -0.5603, -0.4884, +0.5512, -1.2749, -0.2217, +0.3123, -0.9690, -1.2862, +0.7008, +0.7091, +0.3228, -0.4245, -0.4376, +0.6493, -0.2635, -1.2255, -0.1248, -0.1569, +0.9362, +1.1395, -0.2800, +0.0824, +1.1488, +1.2098, -0.4093, -0.9025, +0.0509, +0.0269, +0.1081, +0.3318, +0.3225, +0.1275, -0.0008, -1.0040, -1.1738, +0.7737, -0.3590, -0.2654, -0.4784, +1.0984, -1.1707, -0.6749, +0.8187, -1.0614, -0.1445, -0.4563, +0.0654, +0.2446, -0.5677, +1.0999, -0.1202, -0.8633, -0.2968, +0.2704, -1.0857, +0.1737, -0.5571, +1.1680, +0.8176, +0.7732, -0.8523, +0.1559, +1.4784, -0.9508, +0.2607, -0.4858, -0.4288, +0.3398, -0.2658, +0.4940, -0.1560, -0.4237, -1.1838, -0.5357, +0.7169, +0.2918, +0.4518, +0.1140, -0.7701, +0.4624, -1.1948, +0.0489, -0.2978, +0.4910, -0.1722, -1.0723, -1.0176, +1.2704, +0.5973, -0.0866, -0.1371, +0.0481, -0.3902, +0.0107, +0.3683, +0.4267, -1.4834], +[ +0.5232, -0.8558, +0.5185, -0.1749, +0.1769, -0.5573, -0.0458, -0.4127, +1.3763, +2.5431, -0.5299, +0.3071, -0.5284, -0.4808, +0.2318, -0.0218, -0.1686, -0.1167, -0.0031, -0.3821, +0.9205, +0.0218, +0.7872, -0.5842, +0.0058, +0.2999, -0.2260, -0.1462, +1.3377, +0.5496, -0.3178, -0.8289, +1.1450, +1.0358, -0.7660, -0.5572, +0.3902, -1.2106, -0.1539, +0.2933, +0.6901, -1.1992, +0.5752, +0.0957, -0.2819, -0.5681, +0.2146, +0.0067, -0.9133, +0.9878, -0.1733, -0.3514, -0.8065, +0.9410, +0.2219, +0.3498, -0.5299, +0.3124, -0.8900, +0.6115, +0.2797, +0.9970, +0.3009, -0.0738, -0.3954, -0.4603, +0.7079, +0.2928, -0.5789, -1.0670, +0.7549, -0.7836, +0.4045, +0.3377, -0.4876, +1.7466, +1.9039, -0.5488, -0.4373, -0.2601, -0.3506, -0.0796, +1.1116, +0.0505, -0.1337, -0.2355, -1.6805, +0.1413, -0.3198, -1.0743, +0.5475, -0.8052, +0.8536, +1.1319, -0.0467, -0.6715, +0.2528, -0.3115, -0.5555, +0.4093, -0.1936, -0.3740, +0.2118, +0.0130, +0.1481, +0.8102, +0.8727, -0.4478, -0.1795, -1.2396, +0.5329, +0.7156, -0.1103, +0.9139, +0.2145, +0.7780, -0.1246, -0.9007, +0.5015, -1.2858, +0.5447, +1.3758, -0.5856, +0.4267, -0.1301, -0.9774, -0.6882, -0.1422, +0.6529, -0.5675, -0.5422, +0.9215, -0.2504, +0.3921, +0.9338, +0.0692, +0.4588, +0.0834, -0.4489, +0.0373, +0.3061, +0.0813, -1.3657, -0.2746, -0.3013, -1.1962, +0.1209, +0.9623, +0.0926, +0.0567, +0.0956, -0.2540, -0.0818, +0.0936, +1.1011, -0.6436, -0.8282, -0.5360, -0.2208, +0.5188, -0.3779, +0.3434, -0.0911, +0.6764, +0.2386, +0.0013, -0.9257, +0.6741, -0.1466, +0.2445, +0.1111, +0.3185, +1.1240, +0.8707, +0.0378, -0.9029, -0.9465, -0.6231, -1.4129, +0.3802, -1.5123, +1.3141, +0.1999, +0.4264, -1.0309, -0.0267, -0.5697, +0.4476, -2.1773, -0.5022, -0.5318, -0.1031, -0.4144, +0.2167, +1.0164, -1.5997, -0.1081, -0.3293, -0.2674, -0.7626, -1.0667, -0.8751, +0.0664, +0.4146, -1.3921, +0.5493, -0.7975, +0.0980, -0.5029, -0.1264, -0.7898, +0.2919, +0.0012, -0.2293, +1.3743, -0.1972, -1.3811, -0.0774, -1.0635, -0.3949, +1.1958, +0.3768, -0.2495, +0.8773, -0.3418, -0.6583, +1.2778, -1.6794, +0.1734, -0.0181, +0.2225, +0.6471, +0.2625, -0.6214, -0.3865, +1.0985, -0.8866, +0.4487, +0.1762, +1.0691, +0.7759, +0.5970, +0.2840, -0.7712, +0.1730, +0.0925, -0.1487, +0.0576, +0.0686, -0.1030, +0.6999, -0.3605, -0.6520, -0.1534, +0.5036, -0.0735], +[ -0.2289, -0.5922, -0.3208, -0.1333, -0.0326, -0.0578, +0.0332, +0.0471, -0.1084, -0.4932, -0.0932, -0.0906, -0.0260, -0.2126, -0.4305, -0.0188, +0.1235, -0.2268, +0.0852, -0.2105, +0.0018, -0.0488, +0.1105, +0.0611, -0.3910, -0.0054, +0.1663, +0.0056, +0.0980, -0.0026, +0.1730, -0.0223, -0.1192, +0.0819, -0.0443, +0.1055, +0.2771, +0.1749, -0.4834, +0.0447, -0.4144, +0.1763, +0.2071, +0.1313, -0.1478, -0.3675, -0.4603, -0.0393, -0.1476, -0.4405, +0.2786, +0.0533, -0.0090, -0.1548, -0.3037, -0.0474, -0.2303, +0.1435, -0.4198, -0.2340, -0.3181, +0.0761, -0.1041, -0.0830, +0.0821, +0.0260, -0.3217, +0.0803, +0.1699, -0.4164, -0.1374, -0.1893, +0.0264, -0.2450, +0.1259, -0.6180, -0.1789, +0.1294, -0.2350, -0.1580, +0.2364, +0.0720, -0.1429, -0.0719, -0.3570, -0.0641, -0.2126, +0.1802, -0.1192, +0.0961, -0.0488, -0.3722, -0.1681, -0.1850, -0.1174, -0.0995, -0.0689, -0.1762, +0.2204, -0.4273, -0.3115, +0.0453, -0.1812, +0.0243, -0.1017, -0.0409, -0.0154, -0.0384, +0.0726, +0.5732, -0.1037, -0.2238, -0.0214, -0.0157, -0.0765, -0.1075, -0.0497, -0.0572, +0.3680, -0.2548, -0.1833, -0.1734, -0.0024, -0.0409, -0.2650, -0.3656, -0.2709, -0.4396, +0.0812, +0.0568, -0.3316, -0.1572, -0.2154, -0.1327, -0.1297, -0.3840, -0.4213, -0.3873, +0.3184, -0.1843, -0.5567, -0.2090, -0.2135, +0.0507, -0.0770, -0.4947, -0.3724, +0.0858, +0.0379, -0.2661, +0.0211, -0.1906, +0.2820, +0.1454, +0.0023, -0.2778, -0.2379, -0.0416, -0.2564, +0.1671, -0.2432, -0.1838, -0.1781, -0.3161, -0.3932, +0.1783, +0.1303, +0.1332, +0.0891, -0.1433, +0.0342, +0.0357, -0.1301, -0.0396, +0.0971, +0.0341, +0.0115, -0.3819, +0.2581, -0.4620, +0.3078, -0.0279, -0.2815, +0.0667, -0.1623, -0.1194, -0.0260, -0.2250, +0.1046, -0.3312, -0.2797, +0.0327, -0.0621, -0.2257, -0.0914, +0.1443, +0.0216, +0.2057, -0.1393, +0.4458, +0.2710, +0.3774, -0.1885, +0.0797, -0.0635, -0.3876, +0.1444, -0.0729, -0.2443, -0.1203, +0.4256, -0.0877, +0.0331, -0.3111, -0.1889, -0.0357, +0.1845, -0.1711, +0.0514, -0.1889, +0.0969, -0.0028, -0.1255, -0.1160, -0.0326, -0.1921, -0.4856, +0.4974, -0.2119, -0.1067, +0.2061, -0.0208, -0.3160, -0.1110, -0.2838, -0.2922, +0.1144, +0.0072, -0.0288, +0.1297, -0.0054, +0.2679, -0.3201, -0.2886, +0.0570, +0.1230, +0.0826, -0.1899, -0.0796, -0.1337, +0.0620, -0.4111, -0.4262, +0.1163, -0.0294, -0.0575], +[ -0.0622, +0.1620, +0.1952, -0.1080, +0.4558, +0.2408, -0.3618, -0.4013, +0.7836, +1.3814, -0.2123, -0.3030, +0.1139, +0.1433, +0.2230, -0.0583, -0.1621, +0.4591, -0.4137, +0.4395, -0.3145, +0.1856, -0.4073, +0.2994, +0.1968, +0.5244, +0.3641, -0.0631, +0.6546, +0.1779, +0.1935, -0.1469, +0.9319, -0.0075, +0.0064, +0.1900, +0.5569, +0.0826, +0.0453, -0.0783, +0.4028, +0.0221, -0.0692, +0.4296, -0.2226, +0.3554, -0.0285, -0.4677, -0.1184, +0.3233, +0.1011, +0.1190, +0.5385, +0.1720, -0.5215, -0.2803, +0.2099, -0.0718, -0.1586, +0.1376, +0.0903, +0.1490, +0.4136, +0.2823, +0.5320, +0.1268, -0.3858, +0.6468, -0.0144, +0.4940, -0.1289, +0.1769, +0.1861, +0.0321, -0.0865, +0.4818, +0.3785, +0.0222, -0.0553, -0.3994, -0.2557, +0.2507, -0.0072, +0.0473, -0.4798, +0.0217, +0.5227, +0.2150, +0.0384, -0.2661, +0.2132, -0.1044, +0.5976, -0.2044, +0.1120, -0.0102, -0.2942, -0.3944, +0.4103, -0.1596, -0.1556, +0.0462, -1.0610, +0.5723, +0.4564, -0.2365, +0.3736, +0.1133, +0.1969, -0.2941, +0.5913, -0.0584, +0.3066, +0.0832, -0.3040, +0.4964, -0.1276, +0.0732, +0.0802, -0.7690, +0.2472, -0.1118, -0.4396, +0.4151, -0.1141, -0.2248, +0.2854, +0.3040, +0.3152, +0.6751, -0.2495, -0.1024, +1.0877, +0.2063, +0.1743, -0.2615, +0.6156, +0.0471, -0.5015, +0.6820, -0.1908, +0.3957, -0.0110, -0.2385, -0.5311, +0.4914, +0.0466, +0.2728, +0.1332, +0.0846, +0.2048, -0.2136, -0.2074, +0.2046, +0.0061, +0.2663, +0.0967, +0.0476, +0.0986, +0.3985, +0.5587, -0.5540, +0.0154, +0.4506, -0.0422, +0.0927, +0.2275, +0.3403, +0.5497, +0.0195, -0.2267, -0.0105, -0.0707, +0.4026, +0.0864, +0.3935, +0.3245, +0.6428, -0.3807, -0.0543, +0.5879, +0.0241, +0.6732, -0.2620, +0.1640, -0.0437, -0.1938, +0.5656, -0.3021, +0.8425, -0.0940, +0.8219, -0.0001, +0.2326, +0.1968, -0.0967, +0.1712, -0.1926, +0.0581, -0.4711, -0.1671, +0.2421, +0.3986, +0.1873, -0.6380, +0.1934, +0.1938, -0.4676, +0.3012, +0.0563, -0.1293, -0.3734, -0.2708, -0.2509, -0.3866, +0.3017, -0.5500, +0.6813, -0.0220, +0.4279, -0.0009, +0.7408, +0.1708, -0.1965, +0.4782, -0.0380, -0.5077, +0.0028, +0.5409, +0.4656, -0.0188, +0.2003, -0.1777, -0.1324, +0.5119, +0.5334, -0.0911, -0.0135, -0.3527, +0.3077, -0.1689, -0.6573, -0.2195, -0.3638, +0.0081, +0.1452, +0.3054, -0.6117, -0.5621, +0.3031, +0.0552, +0.3948, +0.5129, -0.2373, +0.0839, +0.5478], +[ -0.2677, -0.3924, -0.1111, -0.0630, +0.0402, +0.8159, -0.7826, -0.3290, +0.4201, -0.3960, -1.1485, +0.5117, +0.2460, -1.0035, +0.1106, -0.6896, +0.9486, -0.3650, -1.0935, -0.3699, +0.3832, -0.5691, -0.6172, +0.7244, -0.1093, +0.4114, +0.5099, -0.6623, +0.6719, +0.3053, +0.8786, -0.3956, -0.6784, -0.2966, -0.1117, -0.3018, +0.2616, -0.4997, +0.2619, +0.5151, +0.4021, +1.0451, -0.1027, -1.5431, -0.0887, +0.0385, +0.2563, +0.8701, +0.0441, -0.2206, -1.3057, -0.4979, +0.9920, +0.4251, -0.5946, -0.6684, -0.0290, -0.8045, -0.1703, +0.3256, -0.2287, -0.1461, +0.0372, -0.0408, +1.7013, -0.7573, -0.4167, +0.8182, -0.1155, -0.2996, -1.2980, +0.4730, -0.5008, +0.6145, -0.2813, -0.0028, -0.1076, +0.0624, +0.5987, -0.4668, +0.3587, -0.1747, +0.1252, +1.1977, -0.2709, +0.2823, -0.1866, +0.3410, -0.5528, +0.2268, +0.5243, -0.4282, -0.5827, -0.4805, -0.5156, -0.0079, -0.1744, -0.7665, -0.0406, -0.5617, -0.0789, +0.2851, -0.8815, -0.0942, -0.0398, -0.5599, +0.8206, -0.4598, +0.1249, +0.0113, +0.3342, +0.4045, +1.0031, +0.0616, -0.7941, -0.5623, -0.5799, -0.3538, +1.4136, -0.0132, +0.0433, +0.0970, +0.4327, -0.6650, -0.3680, +0.0627, +0.6853, +0.0673, +0.4382, -0.0087, -0.1974, -0.4244, -0.7625, +0.6924, -0.1693, -1.1118, -0.2853, -0.2515, -0.1511, -0.0270, -0.1421, -0.4663, +0.3691, -0.4666, -0.7505, +0.6488, -0.4772, -0.0213, +1.2589, -0.2793, +1.1358, -0.5494, +0.0434, +0.5151, +0.0317, -0.4004, -0.2366, +0.6840, +0.1423, +0.2131, -0.8648, +0.2816, +0.0387, -0.4625, -0.1181, -0.2421, -0.8358, +0.0494, +0.7998, -0.1886, -0.8349, +0.5409, +0.0161, +0.8034, +1.4518, +0.3666, +0.7202, +0.4448, -0.5884, -0.3133, +0.7557, +0.0059, +0.8145, -0.2922, +0.2949, +0.7668, +0.9744, -0.1347, -0.2402, +0.9782, +0.3939, -0.1655, -0.1001, -0.3705, -0.0666, -0.1012, +0.8532, -0.2305, -0.4295, -0.2271, +0.0515, +0.2608, -0.6333, +0.8459, -0.1468, +0.9393, +0.3433, +0.3040, +0.0816, -1.2577, -0.0702, -1.1087, -0.0060, -0.7152, -1.0524, +0.6505, -0.7323, +0.3990, -0.5519, +0.6579, +0.1630, +0.9545, -0.2553, -0.6284, +0.3982, -0.2823, +0.5572, +0.5401, -0.2477, +0.2319, -0.5750, +0.7342, +0.0408, +0.5492, -0.2967, +1.4490, +0.3361, -0.2268, -0.7317, +0.6182, -0.1477, -0.4826, +0.0556, -0.3748, +0.6668, -0.0177, -0.5986, -0.7161, -0.6142, -0.2449, -1.2808, +0.8982, -0.7086, -0.7748, -0.5544, +0.5172], +[ +0.3264, -0.3646, -0.2821, +0.2518, -0.2395, +0.4445, +0.1520, -0.6761, +0.0477, -0.0257, -0.1895, +0.3927, -0.2809, -0.9354, +0.2936, -0.3648, -0.3078, +0.1713, -1.5407, -0.1606, +0.0767, -0.1158, -0.8929, -0.2041, -0.1796, -0.1950, +0.0282, +0.1191, -0.4838, +0.1555, +0.8111, +0.6948, -0.2704, +0.2824, +0.3988, +0.2703, +0.0469, -0.2392, +0.0474, -0.1288, +0.4766, +0.4855, -0.4078, -0.5256, +0.1170, +0.0866, +0.4342, -0.0211, -0.0795, -0.0084, -0.2736, +0.2599, -0.0845, -0.2772, +0.5235, -0.2618, -0.2152, -0.0467, +0.1013, -0.5947, +0.5272, +0.0357, +0.4374, +0.1216, -0.3292, -0.9619, -0.2307, +0.4286, -0.3531, -0.2730, -0.1754, +0.2060, +0.4299, +0.0241, -0.0986, -0.0976, -0.5591, -1.1694, -0.3214, +0.5812, -0.3629, -0.3911, +0.6738, -0.7340, +0.3937, +0.0766, +0.2025, -1.3811, +0.3293, +0.1468, +0.2015, -0.0419, -0.4160, +0.2073, +0.0666, -0.2161, -0.6732, -0.2642, +0.1835, +0.3544, +0.3416, +0.0349, -0.4627, -0.1447, -0.9931, -0.0727, -0.2949, -0.2648, +0.2203, -0.6087, +0.3623, +0.3079, -1.2249, +0.7935, +0.0456, -0.3232, -0.7579, -0.3691, -0.3644, -0.3231, -0.5396, -0.4050, -0.0730, -0.4963, -0.0114, +0.2249, -0.3597, +0.7511, +0.2707, +0.5135, -0.1835, -0.5691, +0.2467, -0.6838, +0.1932, +0.5926, -0.9298, -0.1595, +0.0481, +0.4326, -0.0335, -0.3318, +0.2815, -0.0922, -0.2933, -0.0080, +0.5774, -0.0885, -0.4674, -0.2266, +0.0717, -0.6698, -0.4830, +0.1746, +0.1206, +0.0057, +0.4676, +0.8745, +0.1639, -0.4449, +0.1793, -0.3137, +0.6698, +0.9404, -0.1441, +0.0394, -0.6488, -0.3911, -0.5945, +0.3869, -0.5025, -1.2525, -1.1017, +0.6362, +0.4449, +0.2157, -0.1160, -1.1086, +0.7340, -0.0693, -0.5617, +0.4067, +0.0116, +0.4172, -0.3053, +0.0775, -0.0651, +0.2388, -0.1879, -0.4723, -0.1241, -0.4346, +0.0472, -0.0284, -0.1501, -0.2792, -0.3968, -0.7242, -0.4812, -0.5336, +0.2079, -0.3344, -0.3619, -0.5222, -0.3702, -0.0723, -0.0517, -0.4299, -0.0198, -0.1965, -0.6650, -0.1824, -0.2982, +0.1540, -0.1657, -0.1400, +0.1720, -0.2381, -0.7029, -0.0878, +0.0376, +0.0026, +0.3682, +0.5348, -0.4287, -0.1807, -0.1908, -0.4586, -0.0709, +0.2970, -0.0811, +0.0257, -0.2661, -0.6801, +0.5421, -0.3208, +0.3125, +0.1977, -0.1810, -0.3915, -0.5920, +0.3147, +0.7049, +0.9834, +0.3962, -0.8117, -0.2904, -0.7984, +0.4009, -0.5159, -0.1035, +0.1518, +0.0063, -0.3525, +0.0744, -0.1268], +[ +0.0625, +0.2454, -0.1680, -1.0803, -0.9500, +0.2996, +0.3217, +0.0085, -0.0059, -0.3208, +0.5185, +0.1062, +0.3422, -0.3999, +0.5857, -0.0080, -0.8149, -0.0158, -0.3960, +0.4506, +0.3388, -0.3658, -0.2523, +0.6703, +0.5079, +0.1302, -0.4467, -0.5027, -0.0643, +0.0363, +0.2143, +0.0472, +0.2093, +0.4312, -0.1742, +0.4757, +0.0191, +0.4348, +0.1218, +0.3021, +0.3486, +0.2348, -0.1680, +0.7838, +0.2344, -0.4433, -0.3828, -0.0978, -0.1935, +0.4506, +0.2706, -0.8820, -0.1456, -0.0464, +1.2349, +0.3701, -0.0550, -0.0462, +0.0159, -0.1349, +0.5415, -0.2748, +0.7589, -0.7571, -0.2683, -0.2130, -0.2549, -0.0779, +0.1291, -0.0558, -0.4440, +0.2060, -0.3370, +0.0437, +0.0959, -0.3270, -0.3595, +0.4739, -0.6070, +0.3405, -0.6890, -0.3997, +0.9429, -0.2491, -0.4467, -0.1436, +0.1208, +0.0807, +0.8200, -0.5003, +0.1874, -0.4556, -0.1118, +0.1554, -0.1637, -0.6165, +0.0985, -0.6718, +0.1694, +0.0411, +0.4699, -0.6709, -1.1974, -0.4875, -0.1075, -0.3117, +0.6738, -0.0284, +0.4542, -0.9254, +0.3416, +0.5329, -1.0175, +0.4751, -0.0045, -0.3945, -0.4542, +0.1306, +0.1225, +0.2302, -0.5529, -1.3256, -0.0214, -0.2178, +0.8287, -0.0749, -0.2770, -0.0777, -0.3252, +0.1128, -0.3628, +0.7585, -0.0378, -0.2960, +0.6577, +0.3493, -0.0804, -0.1532, -0.5900, -0.0800, +0.6437, -0.6141, +0.6726, -0.7391, +0.2646, +0.0756, +0.6011, -0.0260, -0.8565, -0.1149, +0.2192, +0.4871, +0.0104, +0.2024, -0.5196, -0.7092, +0.4307, -0.3232, +0.1580, +0.0137, -0.0342, -0.2374, +1.0388, +0.7055, +0.4224, +0.0823, +0.8568, +0.4611, +0.1539, +0.6464, +0.2207, -0.1220, -0.6761, +0.3361, +0.5564, +0.6674, -0.3938, -0.2722, +0.3716, -0.3942, -0.2741, -0.0643, +0.0216, +0.0490, -0.4106, +0.8186, +0.1605, -0.0186, +0.0375, -0.6412, -0.0754, -0.9746, +0.6032, +0.2447, -0.3215, +0.8977, -0.0854, +0.5343, -0.4140, -0.2407, -0.1262, -0.4800, +0.4799, -0.4230, -0.2194, +0.2363, -0.4803, -0.2196, +0.0986, -0.7099, -0.3558, -1.0284, -0.9217, -0.3823, +0.5392, -0.0932, -0.1111, -0.0598, -0.7438, +0.2199, +0.6413, -0.2135, +0.3571, +0.3792, -0.4850, -0.2320, -0.6774, -0.0164, +0.4418, +0.2769, +0.3637, +0.0232, +0.8487, -0.9506, -0.1698, -0.5427, -0.2042, -0.5941, +0.2801, -0.4724, -1.5630, -0.5589, +0.7907, +1.0127, -0.6128, +0.3578, -0.5873, -0.3068, -0.0814, -0.0631, -0.0210, +0.9920, +0.3312, -0.4430, +0.6246, +0.6557], +[ +0.1172, -0.2783, -0.7095, -0.1262, +0.1530, -0.4792, +0.4528, +0.4891, -0.0607, -0.0569, -0.6220, +0.0542, -0.6498, -0.2800, +0.6819, +0.3944, +0.5009, -0.9332, -0.2285, -0.7853, -0.6265, +0.1337, +1.1938, -0.1144, -0.3300, -0.0133, +0.5468, -0.2664, -0.0629, +0.0819, -0.2319, -0.4802, +0.2619, -0.7073, +0.1089, -0.0294, +0.1425, -0.2403, -0.0213, +0.8602, +0.0572, +0.1639, +0.3086, -0.6500, +0.1558, +0.1301, +0.2429, -0.2941, -0.1814, -0.3338, -0.6974, +0.3184, -0.5866, -0.1422, +0.2782, +0.0576, +0.2659, -0.2389, -0.5860, +1.3488, -0.1118, -0.4311, -0.1720, -0.2200, +0.1286, -0.1911, -1.0148, -0.0483, -0.3248, +0.3650, -0.0782, -0.1176, +0.3009, -0.1670, -1.2346, -0.4646, +0.1518, -0.8071, -0.3581, +0.4864, -0.3260, -0.3035, -0.2051, -0.6271, +0.4720, -0.5316, -0.8055, +0.6693, +0.5715, -0.7599, -0.2398, +0.1251, +1.0183, +0.2211, -0.9324, +1.5669, -0.3032, -0.0371, -0.0379, -0.2408, +0.5500, -0.4923, -0.1783, -0.5724, +0.1722, +0.2496, -0.0764, +0.5859, -0.1657, +0.2223, -0.2168, -0.0718, +0.0140, -0.5691, +0.1387, +0.7260, -0.1042, +0.0874, +0.5520, -0.6215, +0.5677, -0.1417, +0.1505, -0.1036, -0.6195, -0.5452, -0.0128, +0.2492, -1.2844, +0.2443, +0.1171, +0.6839, +0.8262, +0.6484, -0.0565, +1.0374, +0.3303, -0.5101, -0.2423, -0.4095, +0.1344, +0.6334, +0.2040, +0.5704, +0.0024, -0.0590, +0.2815, +0.4398, -0.0049, +0.0402, +0.1377, +0.1521, -0.2131, +0.0969, +0.0767, +0.3693, -0.0257, +0.2920, -0.0683, -0.1724, +0.5336, -0.2084, +0.2234, -0.5008, +0.4164, +0.7633, -0.0421, -0.1122, +0.4551, +0.3941, +0.0674, +0.9635, -0.0118, +0.3610, -0.2044, -0.0694, -0.6825, +0.3749, +0.1638, +0.5919, +1.0967, +0.1926, +0.2287, -0.0137, -0.2464, +0.1192, +0.4823, -0.7307, -0.1790, +0.7419, -0.4121, -0.7841, -0.5308, -0.1830, -0.7204, +0.0274, +0.3211, +0.4353, -0.5871, -0.4515, +0.7361, +0.3886, -0.2943, +0.1441, -0.0550, +0.4522, -0.0730, +0.1857, -0.0623, -0.0710, +0.8215, +0.6196, +1.3767, +0.2375, +0.3282, -0.7874, +0.3915, +0.3988, -0.5452, -0.0948, -0.8480, -0.6538, +0.6593, +0.1014, +0.0919, -0.6544, -0.1404, +0.7558, +0.0326, -0.2532, +0.2364, -0.3909, +0.4244, +0.0179, +0.1291, +0.7988, -0.1690, -1.0113, +0.1032, +0.2351, -0.5359, +0.2737, +0.4163, +0.1660, -0.3177, -0.8316, +0.4132, -0.6683, -0.0579, -0.5545, +0.1057, -0.0281, -0.0024, -0.4894, +0.2741, +0.3701], +[ -0.0647, +0.6531, -0.1032, -0.4992, +0.5037, -0.5282, -0.2488, -0.1359, -0.2810, -0.1751, -0.7607, +0.1065, -0.9882, +1.0841, +0.3367, -0.4327, -0.3151, -0.4300, +0.8063, -0.7392, -0.4708, +0.2053, -0.0891, -0.1977, -0.3533, +0.6672, +1.0239, +0.2179, -0.0560, -0.1074, -0.6713, +0.2259, -0.4024, -0.7552, +0.0620, -0.2045, -0.1162, -0.1587, -0.0859, +0.1280, -0.0673, +0.1809, +0.7352, -0.0873, -0.3025, -0.0806, +0.4108, -0.1462, +0.8900, +0.0117, -0.9559, +0.2582, +0.3579, -0.1051, +0.1183, +0.1419, +0.0427, -0.4753, -0.1908, +0.1446, -0.7479, -0.6421, -1.1942, -0.3313, +0.6718, -0.2275, -0.0107, -0.6022, -0.5933, +1.5015, -0.3277, -0.8475, -0.3529, -0.1143, -1.2357, -0.0210, -0.8484, -0.4511, -0.4182, +0.0266, +0.8972, -1.0084, +0.2561, +0.2466, +0.9909, -0.2399, -0.3424, +1.0800, -0.0557, -1.0021, -0.2742, -0.7683, -0.3469, -0.8045, +0.3725, +0.8353, +0.6543, +0.3471, +0.1389, -0.2780, +0.8554, +0.0150, +0.3343, +0.1361, +0.5095, +0.4998, +0.3005, +0.0996, +0.0335, -0.3677, -1.0182, -0.2247, -0.6468, -1.1545, +0.7807, -0.9215, -0.3781, +0.4275, -0.6639, -0.4142, +0.8174, +0.0859, +0.1202, -0.1684, -0.2050, +0.2585, +0.3646, -0.8418, -1.2981, +0.2840, +0.1240, +0.4204, +0.5400, +0.3127, -0.2068, +0.2112, +0.4278, +0.0198, -0.5277, -0.7125, -0.1634, -0.6394, +0.6822, +0.1249, -0.5505, -0.1739, -0.1031, -0.2829, +0.2146, +0.3009, +0.5936, -0.0538, -0.5024, -0.3015, +0.0261, -0.1504, +0.4943, +0.5050, +0.4151, -0.1256, -0.6758, -0.6859, +0.8435, -0.8839, +0.0378, -0.6141, +0.3176, -0.2099, +0.4002, +0.8110, +0.0505, +0.3271, -0.6036, +0.3374, +0.0504, -0.3805, -0.6931, -0.1313, +0.0039, -0.3990, -0.6584, -0.5678, -0.4761, -0.3674, -0.5052, +1.3493, +0.9539, +0.3604, -0.5794, +0.6608, -0.4635, -1.5371, -0.6674, +0.2887, -0.7866, -0.6152, -0.0875, -0.2175, -0.3096, -0.1594, -0.2646, -0.2216, -0.4797, +0.9517, -0.3274, +0.0285, +0.6995, -0.2708, -0.5643, +1.2240, +0.0139, +0.7940, +0.1366, +1.1820, -0.2451, -0.0172, -0.1148, +0.4907, -0.2293, -0.5941, +0.1354, +0.6113, -0.0891, +0.2567, +0.2524, -0.5225, -0.0711, +0.3287, +0.7458, -0.5293, -0.2398, -0.2208, +1.0366, +0.6547, +0.5174, -0.0728, +0.1773, -0.6946, +0.0987, +0.0746, +0.4341, +0.8016, +0.6499, +0.2621, -0.4212, -0.2207, +0.8608, -0.0083, +0.2800, +0.2154, +0.0722, +0.5301, +0.3713, -0.0081, +0.2663, +0.1345], +[ +0.3130, -0.0585, -0.1601, -0.1024, -0.3747, -0.4581, -0.2575, +0.1997, +0.5295, +0.0490, -0.2800, -1.0577, -0.0588, -0.0160, -0.1494, +0.0341, +0.0715, -0.0382, +0.1771, +0.1815, -0.0765, +0.2010, -0.1023, +0.5555, -0.4700, +0.0106, +0.1853, +0.4241, +0.5859, -0.2705, +0.3113, -0.3753, -0.3432, -0.2268, -0.2882, +0.0709, -0.0510, -0.1118, +0.1877, +0.3823, +0.1815, +0.3125, +0.2013, -0.1324, -0.8493, -1.1203, +0.0683, +0.1163, -0.1035, +0.1080, -0.5283, -0.4333, +0.1647, -0.5032, +0.0462, -0.2156, +0.4899, -0.3746, -0.2878, -0.1702, +0.2101, -0.2306, -0.2466, +0.0105, +0.2818, -0.2101, -0.4292, -0.0190, -0.2841, -0.0979, +0.0887, +0.6823, -0.5044, +0.1998, -0.4433, +0.1215, +0.1917, -0.2307, -0.1198, -0.0065, -0.3293, -0.4149, -0.1700, -0.2872, +0.3405, -0.0418, +0.0654, +0.1995, +0.8670, -0.2927, +0.1775, +0.0614, +0.3018, -0.2374, +0.0618, -0.3852, +0.0395, +0.2544, +0.0949, -0.2742, -0.3114, -0.0646, +0.0232, -0.0231, -1.5945, -0.2847, -0.1796, +0.3372, +0.2968, -0.1711, +0.0107, -0.3552, +0.1396, +0.2219, -0.4459, -0.5304, +0.0420, +0.2320, -0.2626, -0.2587, +0.1755, +0.1605, +0.3022, +0.1686, +0.2614, -0.1657, +0.0606, +0.3014, -0.1068, -0.2048, -0.6107, -0.1257, -0.1822, +0.3166, +0.2270, -0.0117, -0.7933, +0.1176, -0.0666, -0.1363, -0.0265, +0.1240, -0.6695, +0.0981, +0.1127, +0.3905, +0.2705, -0.4131, -0.4401, +0.2276, +0.3034, -0.0891, -0.4392, +0.0877, -0.0618, +0.3465, +0.0433, -0.0895, -0.2266, -0.1432, -0.2860, -0.3363, -0.2260, -0.0956, -0.2604, -0.2610, +0.1076, -0.1004, +0.0107, +0.0907, -0.1411, -0.5052, +0.0195, +0.5423, +0.2808, -0.6256, +0.3389, +0.0530, +0.0222, -0.0686, +0.5507, +0.0523, -0.4677, -0.2825, +0.3375, -0.5367, +0.4671, +0.5011, -0.0104, +0.0006, +0.4560, -0.1539, -0.1961, -0.0134, -0.3079, -0.0018, -0.1379, -0.3216, +0.1171, +0.4003, -0.8743, -0.4253, -0.1950, +0.2639, +0.2655, +0.3551, +0.1033, +0.1134, -1.0368, +0.0362, +0.0625, +0.0248, -0.1044, -0.5546, -0.3031, +0.2400, -0.0652, -0.0214, +0.0618, -0.0641, -0.2360, -0.0096, +0.0669, +0.1070, +0.4031, +0.1504, -0.0330, +0.4363, +0.0873, +0.2462, -0.0825, +0.2503, +0.0775, -0.0813, -0.4761, -0.5802, +0.0291, -0.2824, -0.7243, -0.0158, +0.0532, -0.5854, -0.1676, +0.0203, -0.7103, +0.3987, +0.3179, -0.0535, +0.1871, -0.4414, -0.3198, -0.1166, -0.2955, +0.2740, +0.2244, +0.3489], +[ -1.5291, +0.7509, -0.0074, -0.7377, -1.1521, -0.0855, -0.0966, -1.1100, -0.0266, +0.4928, -1.3361, -0.7886, +0.1070, +0.4873, -0.7260, +1.1879, -0.2253, +0.2718, -0.1084, -0.0427, -1.2677, -0.6730, -0.3085, +0.5077, -0.2227, -1.7757, +0.3039, +0.5841, +0.1047, +0.0855, +1.0019, -0.6676, +0.0868, -0.5888, -0.4921, -1.9100, +0.2842, +0.8124, +0.3632, -0.6278, +0.2443, +0.3960, +0.6543, -0.5543, +0.1428, -1.4196, +0.3199, +0.3195, +0.9092, +0.2958, +0.7929, +0.3910, -1.2143, +0.9585, +0.0838, +0.2479, +0.6162, -1.7836, -0.5629, +0.7295, +0.0387, +0.0682, +0.1486, -0.4095, +0.5116, +0.5360, +0.3109, -0.7139, +1.7474, +0.3068, -0.1707, -0.2102, -0.4153, +0.1328, -0.4242, +0.8287, +0.4251, -0.1067, -0.0917, -0.4040, -0.0577, -1.4141, -0.4519, +1.0870, +0.3584, -0.2708, -0.5739, +0.1603, +0.4197, -0.1262, -1.2906, +1.2730, -0.4890, +0.1423, -0.3007, -0.1097, +0.0113, +1.2365, +0.0550, -0.3075, +0.0122, +0.4935, -0.5145, -0.2649, +0.1376, +0.4116, +0.2533, +0.1799, -0.3758, -1.1299, +0.0371, -1.0792, +0.5395, -0.2699, +0.1940, +0.4513, +0.4543, -0.0455, -1.3227, +0.6893, -1.0421, -0.0902, +0.0099, -0.5710, +0.0049, +0.1784, -0.2424, +1.0698, -0.4470, -1.6596, +1.3418, +0.7313, -0.0859, -0.0128, -0.0812, +0.0355, -0.6078, +0.3808, -1.0758, +0.1621, +0.3418, +0.3347, -1.1316, +0.2234, -0.6019, +0.5632, -0.4485, +0.4843, -0.5448, +0.4000, +0.8122, -0.1500, -0.7165, +0.1042, -0.3117, +1.0720, +0.7967, -0.7584, +0.8979, -0.1655, -1.1808, -0.3785, -0.2499, +0.1837, +0.2004, -0.9096, -0.2102, -0.2760, -1.5241, -0.1974, +0.1111, +0.3633, -0.1225, -0.2235, -0.4475, -0.5283, -0.2199, +1.0813, -0.3643, -0.8134, +0.2379, -0.5054, -0.3266, +0.6273, -0.0715, -0.1116, +0.4867, -0.2660, -0.0761, -0.0847, +0.4224, -0.7916, +0.3691, +0.0447, -0.1773, -1.0054, -0.5019, +0.5543, -1.3049, +0.3457, -1.0282, +0.0240, -0.6582, -1.2401, -0.4293, -0.3723, +0.3960, -0.0613, -0.0244, -1.3904, +1.2358, +0.7765, -0.4009, -0.0309, -0.7966, -0.2476, -0.6584, +0.6055, -0.2617, -1.0294, -1.8422, -1.2904, +0.2408, +0.0069, -0.5984, -0.1944, -0.6952, -0.0202, -0.2899, +0.4219, -0.4417, -0.5361, +0.6666, -0.9856, -0.7815, -1.3829, -0.3073, -0.2199, -1.1877, +0.8324, -1.7394, -0.7193, -0.2104, -0.7743, -0.8404, +0.6159, +0.6948, -0.4127, -0.3222, -0.9054, -0.9808, -0.1008, -0.1919, -0.1492, -0.2286, -0.4747], +[ -0.2811, +0.1011, -0.0610, +0.1050, +0.0698, +0.3638, -0.6212, -0.7514, +0.6360, +0.3330, +0.1242, +0.0861, +0.1506, -0.1573, -0.1668, -0.1629, +0.0568, -0.0068, -0.1079, -0.2086, -0.0798, +0.3590, -0.0907, +0.2449, +0.0255, -0.8407, +0.1177, -0.4512, -0.0412, -0.3018, -0.4712, -0.4733, -0.5295, -0.0837, -0.2969, +0.5147, -0.6457, +0.2246, +0.4988, +0.2238, +0.1222, +0.3123, -0.2500, -0.5234, -0.1785, -0.0682, +0.5842, -0.8358, +0.5900, -0.4114, -0.7249, -0.2819, +0.0768, +0.1637, -0.3317, -0.0877, +0.4097, +0.5530, +0.3368, +0.2629, -0.5228, -0.3268, +0.0520, -0.5589, +0.3444, -0.2139, -0.7170, -0.4311, +0.5924, -0.1573, -0.2035, -1.1198, -0.8246, +0.0195, -0.5881, -0.0686, -0.0860, -0.2957, -0.2666, +0.0974, -0.5724, -0.8344, +0.3288, -0.1264, +0.0128, -0.0728, +0.2257, +0.2318, +0.0079, -0.4364, -0.2328, +0.2227, -0.4731, +0.2063, -0.4602, +0.3852, +0.1137, +0.4837, -0.0091, +0.4234, +0.6562, -0.0626, -0.6597, -0.0398, -0.0536, +0.3562, -0.5488, -0.6842, +0.0974, +0.0361, +0.4993, +0.1175, +0.3602, +0.1439, -0.6109, -0.4640, +0.1863, -0.7654, -0.2980, +0.2690, -0.2946, -0.1190, -0.4721, -0.2476, +0.1443, -0.0955, +0.1548, -0.1863, -0.0491, -0.2371, +0.0805, +0.3213, -0.0869, -0.4615, -0.4175, -0.4486, +0.3961, -0.1400, -0.5382, +0.0238, +0.1956, +0.0548, -0.3000, +0.0894, -0.1157, -0.2935, -0.0645, -0.4242, +0.0501, -0.4838, -0.1142, +0.4003, -0.5963, +0.1655, +0.4490, +0.1399, -0.4131, +0.7218, +0.0651, -0.1533, +0.3304, -0.1523, -0.3286, +0.5715, -0.1760, -0.5536, +0.9708, -0.0695, -0.1759, +0.2954, -0.0463, +0.4200, -0.6787, +0.1121, -0.0979, +0.7546, +0.0308, -0.4884, -0.0656, -0.5207, -0.4658, -0.1859, +0.5848, +0.1012, -0.6946, +0.2289, -0.3811, -0.2526, +0.3721, -0.1001, +0.0271, -0.3716, +0.6291, -0.0850, +0.6132, +0.0041, +0.3856, -0.0917, +0.5693, -0.1875, -0.1611, +0.2646, -0.1155, -0.0618, +0.2702, -0.1550, +0.3912, -0.2428, +0.5281, -0.5046, -0.1638, -0.0070, +0.2807, +0.2511, +0.9921, +0.3561, -0.5066, -0.2131, +0.0024, +0.7692, -0.0259, -0.1815, -1.1148, -0.2950, -0.0485, -0.5774, +0.1976, +0.2171, -0.1562, -0.0544, -0.5389, -0.5517, -0.2927, -0.4904, +0.4556, +0.2309, -0.8640, -0.7473, -0.2229, +0.7439, +0.2569, +0.1446, +0.2150, -0.0239, +0.3427, +0.1103, -0.2397, -0.3290, -0.2605, +0.6977, -0.0860, -0.7998, -0.2629, -0.0009, +0.5513, -0.1890], +[ -0.6315, -0.9363, +0.5395, +0.5106, +0.3953, +0.2615, -0.4221, -0.4210, +0.4084, -0.3708, -0.8895, -0.7031, -0.2397, -0.0047, -0.0392, -0.9907, -0.0518, -0.2610, -0.1791, +0.3649, -0.4118, +0.5682, -0.4480, +0.6911, -0.8780, +0.2294, +0.4313, -0.6176, +0.1673, +0.3952, -0.5156, -0.2230, -0.1931, +0.4439, +0.1103, +0.3786, -0.2360, +0.2698, +1.0768, -0.2860, +0.3186, -0.3953, -0.0972, +0.0864, -1.4468, -1.0603, +0.0658, -1.2611, +1.3845, +1.1612, +0.0940, -0.0551, +0.7263, +0.6747, +0.0263, -0.3770, -0.5943, +0.1021, +0.4164, +0.5683, -0.3671, -0.2409, +0.3109, +1.0640, -1.0311, +0.5001, -0.1592, -0.1081, -0.2889, +0.6021, -0.3917, -0.3445, -0.2361, +0.4034, -0.4031, -0.5691, -0.3715, -0.4639, -0.7814, -0.9862, -0.4163, +0.1789, +0.3550, -0.0066, -0.1438, -0.1465, -0.6079, +0.7529, -1.2862, +0.5823, +0.0574, -0.5088, -0.5231, +0.0124, -0.1859, +0.4937, -0.7876, -0.6860, -0.4469, -0.3876, +0.3195, -0.3171, -0.9781, -0.6090, -0.1717, +0.2865, -0.6920, -0.1219, +0.1502, +0.5604, -0.3207, +0.0759, +0.1306, -0.3244, +0.1978, +0.3598, +0.2209, +0.5365, +0.5977, +0.6504, -0.7021, +0.2033, -0.1353, -0.2584, -0.5924, -0.3167, -0.0117, +0.6623, +0.0350, +0.5381, +0.1891, +0.6693, +0.7502, -0.4372, +0.5079, -0.0811, +1.2352, -0.4580, -0.5438, +0.4481, -0.4331, +0.7399, +0.2847, -0.1288, -0.1061, +0.3820, +0.0009, -0.7364, -0.0127, -0.5112, -0.2881, -0.4204, -0.3917, +0.5281, +0.0792, +0.1718, -0.8185, +0.5843, +0.0028, +0.8819, +0.4506, +0.5220, +0.8724, +0.9187, +0.0321, +0.5469, -0.2751, +1.0228, -1.2236, +0.1936, -0.9670, -0.1699, +0.1720, +0.0485, +0.2123, +0.8600, -0.2548, -0.4831, -0.0137, +0.6477, +0.9001, -0.3948, -0.2098, +0.6062, -0.8639, -0.2834, -0.2457, -0.1975, +0.2417, -1.0677, +0.0405, +0.1193, +0.6034, -0.2025, +0.1993, -0.4663, +0.4749, -0.4462, +0.9196, -0.1786, +0.2205, +0.4837, +0.0870, +0.7167, +0.2900, +0.1003, +0.2930, +0.4127, -0.1221, -0.1679, +0.0162, +0.2090, +0.0474, +0.6412, +0.7725, +0.0576, -0.0105, -0.1292, +0.2671, +0.6288, +0.0149, +0.1800, -0.2455, -0.0688, +0.3809, -1.0889, -0.2251, -0.1113, +0.4618, +0.2450, -0.6848, -0.8293, +0.3566, -0.0628, +0.0873, -0.4762, -0.8713, -0.9663, -0.4618, +0.8200, +0.4479, -0.1278, +0.4284, +1.0482, -0.1372, +0.3498, +0.0962, +0.1740, +0.7217, +0.2614, +1.2404, +0.2340, +0.1609, -0.3998, -0.2072, +1.2226], +[ +0.3659, -0.3277, +0.2886, -0.6295, +0.2202, +0.1956, +0.2046, -1.0997, -0.3790, -0.2504, -0.2179, +0.4310, -0.0257, -0.5886, -0.2192, +0.5606, +0.5691, +0.3139, -0.3161, +0.1774, +0.4663, -0.4175, +0.1008, +0.1057, -0.1205, +0.2663, -0.8731, +0.5174, -0.0934, -0.2885, -0.4381, -0.5083, -0.2518, -0.1219, -0.6879, -0.0831, +0.3837, -1.2419, -0.5405, -0.2546, +0.7046, +0.3395, +0.5555, -0.3908, +0.1154, -0.0987, +0.2476, +0.3723, +0.0672, -0.5928, +0.0105, +0.1161, -0.2884, -0.0896, -0.4600, +0.0441, -0.6273, -0.1487, +0.2347, +0.1172, +0.2784, -1.1121, +0.0912, -0.0353, +0.0231, -0.3515, +0.2365, -0.4356, -0.0845, +0.2015, -0.1389, +0.2026, -0.6346, +0.2443, +0.4571, -0.1172, -0.3613, -0.4059, -0.7775, -0.7386, -0.1742, -0.4192, +0.1514, -0.1638, +0.0724, +0.0156, -0.3456, +0.1126, -0.1153, -0.2124, +0.7085, +0.4719, +0.3253, +0.3380, +0.9501, +0.4256, +0.1533, -0.6508, +0.7624, +0.0468, -0.1102, -0.3088, +0.0204, -0.4028, +0.4368, -0.4793, -0.0175, +0.0985, -0.9569, -0.0340, -0.1244, +0.3770, -0.2597, +0.2212, +0.2798, +0.4668, -0.4196, +0.0917, -0.2541, -0.2862, +0.5804, -0.3658, -0.5237, -0.7544, +0.5569, -0.4648, -0.5293, +0.7809, +0.7766, -0.5682, +0.1964, -0.8185, -0.1124, -0.2674, +0.0967, -0.1906, +0.2630, +0.1404, -0.1758, +0.1631, +0.1065, -0.3872, +0.0061, -0.9510, -0.1729, -0.4610, +0.2472, +0.1792, +0.0699, +0.3596, -0.1982, +0.2670, +0.2600, -0.4795, -0.2844, -0.2111, -0.0606, -0.8002, -0.4567, -0.1884, -0.0098, -0.2961, +0.2176, -0.0458, -0.0488, -0.6393, -0.5504, -0.2651, +0.0190, -0.2114, -0.0548, -0.6148, +0.9049, -0.1097, -0.9733, +0.0583, -0.4493, -0.0165, -0.0770, +0.0710, -0.4033, -0.4281, -0.4991, -0.3947, -0.4954, -0.9631, +0.0378, -0.4770, +0.1315, -0.3187, -0.7582, +0.3062, -0.5525, +0.7319, -0.2604, +0.0441, -0.1059, +0.2834, +0.3660, -0.8329, +0.3057, -0.4196, +0.4101, -0.1431, -0.0602, +0.0972, -0.4246, +0.0750, -0.2165, -0.0929, -0.5216, -0.0272, +0.2421, -0.1263, +0.3659, -0.6390, +0.4958, -0.0563, +0.1865, +0.4631, -0.7523, -0.1715, +0.5228, +0.0712, +0.0542, +0.0209, -0.1205, +0.0727, +0.2380, +0.2908, -0.3024, -0.6805, +0.0372, -0.2433, -0.0941, -0.2936, -0.4086, -0.2987, +0.0643, -0.2925, -0.1958, -0.1803, +0.5245, +0.3150, +0.0475, -0.7125, -0.0838, -0.0100, +0.1168, +0.0011, -0.1571, +0.1697, +0.4557, -0.0282, -0.8599, +0.3087], +[ +0.5293, +0.5316, -0.0075, +0.2349, -0.1925, -0.3699, +0.7133, -0.4346, -0.3532, -0.5599, +0.6772, +1.0476, +0.1895, -0.1390, +0.4312, +0.2892, +0.3951, +0.0404, +0.4593, -0.3496, +0.0116, -0.6154, -0.0422, +0.3318, -0.3554, -0.1510, -0.1144, +0.3037, +0.2126, -0.2470, -0.3374, -0.5273, -0.4472, -0.1286, +0.2244, -0.3495, +0.3391, -0.1282, +0.0407, -0.0645, +0.2085, +0.2341, +0.0162, -0.0732, -0.8081, +0.4448, +0.4809, +0.1450, -0.0442, -0.0492, -0.5167, +0.5533, +0.1572, -0.1957, +0.1203, +0.5138, -0.0965, +0.8614, -0.3152, +0.0709, +0.4340, -0.5613, +0.1492, +0.1472, +0.1821, +0.1713, +0.1056, -0.6941, +0.4367, +0.2689, +0.1627, +0.0061, -0.4394, +0.0959, +0.0825, -0.5954, -0.0809, -0.5548, +0.4909, -0.2199, -0.1998, -0.2514, +0.0983, -0.0957, -0.0226, +0.2085, -0.2957, -0.0954, +0.1584, -0.3026, +0.1529, +0.2377, +0.4984, -0.1790, +0.3467, -0.4972, -0.1265, +0.1861, +0.5680, -0.4604, +0.2749, +0.0564, +0.1688, -0.1455, +0.1582, -0.7147, -0.1668, +0.7087, -0.6417, +0.2222, +0.2567, -0.3951, +0.0252, -0.5056, -0.5749, -0.0059, +0.0058, -0.1503, -0.0303, -0.1436, -0.1979, +0.0134, -0.1827, -0.5967, +0.1955, -0.3377, -0.4552, +0.2332, +0.4630, -0.4029, +0.1100, -0.3156, +0.3175, +0.1121, +0.6988, -0.1980, +0.2492, -0.1373, -0.0736, +0.0154, +0.1906, +0.3765, -0.5100, -0.2742, -0.2842, -0.2733, +0.4817, +0.6092, +0.1535, -0.0521, +0.6241, +0.6618, +0.0321, -0.5597, -0.6581, +0.2474, +0.4140, -0.1778, -0.7715, -0.3870, +0.3461, +0.2471, -0.0063, +0.0640, +0.0977, -0.5769, +1.1693, +0.3004, +0.0837, +0.3198, +0.8379, -0.5325, -0.3676, +0.0443, -0.5164, -0.5141, -0.3037, +0.4722, +0.0488, +0.8697, -0.1157, -0.2020, -0.1556, -0.3323, +0.0794, -0.4998, -0.3284, +0.1285, +0.2727, +0.6930, -0.1084, +0.4371, -0.1270, +1.1286, -0.5242, +0.2965, +0.6526, +0.3987, +0.1444, -0.4337, -0.1283, -0.0356, +0.0632, -0.0329, +0.0984, +0.3490, -0.0315, -0.4110, -0.3036, -0.3578, -0.0063, +0.4834, +0.2061, +0.2501, +0.0401, -0.6852, -0.3525, -0.4835, +0.1745, +0.3534, +0.0782, -0.1772, +0.5503, +0.2279, +0.0390, -0.4885, +0.3623, +0.0601, -0.3582, +0.1909, +0.1955, -0.9959, +0.1046, -0.7885, -0.1006, +0.4565, -0.2528, -0.5783, -0.0917, -0.0401, +1.0514, +0.2831, +0.3431, +0.3726, -0.2791, +0.5676, -0.3964, +0.2246, +0.1321, -0.0372, +0.4953, +0.1855, -0.2201, +0.4205, -0.2678, +0.3705], +[ -0.4383, +0.3767, -0.1398, -1.2589, -0.0351, +0.8848, -0.3821, +0.7381, -0.1629, -0.2208, -0.0231, -0.1089, +0.2688, -0.1913, -0.1701, -0.8031, -0.7192, +0.2047, +0.3901, +0.6492, -0.6799, +0.2456, +0.0256, +0.1402, -0.8989, -0.3148, -0.3743, +0.1524, -0.5692, +0.0725, +0.2199, +0.2573, +0.2630, -0.0155, -0.8638, -0.3227, -0.0941, +0.0170, +0.4481, -0.0033, -0.3460, -0.4853, -0.2198, +0.3081, -0.5793, +0.2964, -0.4996, +0.3581, -0.4945, -1.0241, +0.3134, +0.0406, -0.3108, -0.0937, -0.6398, -0.4360, -0.3965, -0.1980, +0.2188, +0.1330, -0.1319, -0.2892, +0.1846, -0.2287, -0.3640, +1.3056, -0.7990, +0.0514, -0.1256, -0.0869, -0.5219, -0.4011, -0.0828, -1.3749, +0.4000, +0.0481, +0.0219, -0.1074, +0.2081, -0.0452, +0.4307, -0.8420, -0.9887, +0.6651, -0.3451, -0.4989, -0.2157, +0.1838, -0.2326, -0.5271, -1.0106, +0.0422, +0.1659, -0.6790, -0.4370, +0.0993, -0.4219, +0.2926, -1.4655, +0.3299, -0.4630, -0.4127, +0.0650, -0.0907, -0.5557, +0.5449, +0.2549, -0.8462, -0.4960, -0.2910, -0.1676, +0.3139, -0.3498, -0.1617, +0.1417, -0.0890, +0.4634, -0.3460, -0.1623, +0.3784, +0.2638, -0.0517, +0.0446, +1.2269, -0.2161, +0.0567, +0.1503, -0.5337, -0.1629, +0.5830, +0.0807, -0.1728, -0.0075, +0.5278, -0.7841, +0.4637, -0.2269, +0.1374, -0.3859, -0.9908, -0.1801, +0.0038, +0.2798, +0.3467, -0.3097, -0.3130, +0.1028, +0.0310, +0.0803, -0.3599, -0.1481, -0.4712, -0.1677, -0.8620, +0.1360, -0.3232, -0.6546, -0.3307, -0.1443, +0.4429, +0.0644, -1.0791, -0.3051, -0.1541, -0.4603, +0.1506, -0.0511, +0.1952, -0.0245, -0.0150, +0.2477, -0.0090, -0.1937, -0.4797, +1.0447, +0.0411, -0.2671, -0.0387, -0.8022, +0.2201, -0.3823, -0.3047, +0.1043, -0.4240, -0.0245, +0.3587, -0.2156, -0.1411, -0.3159, -0.0002, +0.0291, +0.0051, +0.5761, -0.4807, +0.6089, -0.2353, +0.0092, -0.6888, +0.2516, +0.8081, +0.1554, +0.7692, +0.3867, -0.2633, -0.2482, -0.3817, +0.2199, +0.5334, +0.3730, +0.1608, +1.2073, -0.7426, +0.1119, -0.6921, -0.4162, +0.0102, -0.1226, +0.2965, -0.6047, -0.4760, +0.2470, -0.1461, -0.2106, -0.1756, -0.4781, -0.8994, -0.2296, -0.0045, -0.1405, +0.1110, +0.1516, +0.4299, +0.1353, +0.3075, -0.1090, -0.3561, -0.4872, +0.1200, +0.1690, +0.0664, +0.0576, -0.6695, -0.2393, -0.1848, -0.5203, +0.0431, +0.0627, +0.1742, +0.2262, +0.3209, +0.3629, -0.2562, +0.1898, -0.1370, +1.1583, +0.2679], +[ +0.3879, -0.2526, +0.5881, +0.3189, +0.2070, +0.6931, -0.3306, +0.0660, +0.1093, -0.4855, -0.0718, -0.3554, +0.3417, +0.2194, -0.0519, -0.8023, -0.6628, +0.0588, -0.4819, +0.3613, -0.3590, +0.1909, +0.1917, +0.2438, +1.0631, -0.6014, +0.0911, -0.5642, -0.4269, +0.0198, +0.5636, +0.2587, +0.1228, +0.1936, +0.0986, -0.2277, +0.0956, -0.0331, -0.2739, +0.9812, -0.7628, -0.6546, -0.0186, +0.4016, -0.5244, +0.6846, +0.2533, -0.1366, -0.1932, +0.3941, -0.2001, -0.6538, -0.1762, +0.1094, +0.0883, -0.1340, -0.6598, +0.1996, +0.3834, +0.5194, -0.2248, -0.2921, -0.0777, +0.2306, +0.0241, +0.1826, +0.0310, +0.4689, +0.1437, +0.0393, -0.1703, -0.4118, +0.2480, -0.2397, +0.3582, -0.2542, -0.6081, -0.0572, +1.3444, +0.0118, +0.2765, -0.6030, -0.2835, -0.0242, -0.1264, -0.2328, +0.3599, +0.2655, +0.3077, -0.0469, +0.4283, -0.4493, -0.0542, -0.0127, -0.2526, +0.5933, -0.4638, +0.3775, -0.7117, -0.6042, -0.2770, -0.1601, +0.0737, +0.0611, +0.5926, +0.6737, +0.0839, -0.3346, -0.1312, -0.0318, -0.1617, -0.0336, -0.9100, -0.2009, +0.2274, +0.0688, -0.7166, +0.1150, -0.8140, +0.1184, -0.5295, +0.0943, +0.4650, +0.8789, -0.0656, +0.1492, -0.4394, +0.0036, -0.3073, +0.2290, -0.5697, +0.4223, +0.2011, +0.2196, -0.1706, +0.4915, -0.8992, +0.0736, +0.3837, -0.4251, -0.2159, +0.3671, -0.1270, +0.0207, +0.2042, -0.1387, -0.0351, -0.1776, -0.1136, +0.0430, -0.0738, +0.0864, -0.5124, -0.5529, +0.6100, +0.4673, -0.0771, -0.2835, +0.3972, +0.0485, +1.1983, -0.1951, -0.6381, -0.0974, -0.4182, -0.3271, -0.2248, +0.3219, +0.3027, -0.0334, +0.0823, -0.1266, -0.1004, -0.3568, +0.4390, +0.6042, -0.4685, +0.9686, -0.1652, +0.4926, -0.2821, +0.3147, +0.7419, -0.7130, +0.8363, +0.1439, -0.2505, -0.8304, -0.0077, +0.0359, -0.3370, +0.0313, +0.3718, -1.3662, +0.3167, -0.4004, -0.8605, -0.1397, -0.0067, +0.0608, +0.0011, +0.5468, +0.7826, -0.7418, -0.5643, -0.3295, -0.3556, +0.9552, +0.0878, -0.7521, -0.0417, -0.0411, +0.5019, +0.4218, +0.1044, +0.2018, +0.7178, +0.0425, -0.5157, -0.4186, +0.1644, +0.0227, +0.1145, +0.0584, -0.6852, -1.0077, +0.4781, +0.0082, -0.2462, +0.2854, +0.7114, -0.4493, +0.6272, +0.4718, -0.7225, +0.4412, +0.2769, +0.0257, +0.4356, -0.1177, -0.2400, -0.5487, +0.0604, +0.4203, -1.2504, -0.5002, -0.1294, -0.1064, +0.4515, -0.0592, +0.4579, -0.5153, +0.1722, +0.0011, -0.2838, -0.0426], +[ -0.5000, +0.0939, +0.2115, +0.1138, -0.2612, -0.2688, +0.1126, -0.1978, +0.0107, -0.0291, -0.6198, -0.3804, +0.3689, -0.5019, -0.2919, +0.2962, -0.0346, +0.2433, +0.0477, -0.2796, +0.2503, +0.2574, +0.1043, -0.1736, +0.0486, -0.2836, -0.1299, -0.4129, +0.3905, -0.0475, +0.1315, +0.0154, +0.0612, +0.0488, +0.1056, -0.3194, +0.0503, +0.0915, +0.1376, -0.0937, +0.2009, +0.1034, +0.2468, +0.0418, -0.6219, -0.0482, -0.2431, -0.2583, +0.3053, +0.6434, +0.5343, -0.1449, -0.3486, -0.3343, +0.4435, +0.3061, +0.5672, -0.0846, +0.3410, -0.2485, +0.2576, +0.0540, -0.4661, -0.3009, -0.1271, +0.1216, -0.2006, -0.2457, -0.4119, -0.5092, +0.1415, +0.0494, -0.0872, -0.0839, +0.0892, +0.3253, +0.5367, +0.1022, +0.1056, +0.0895, -0.1332, -0.3175, -0.4450, +0.1273, -0.3015, +0.3787, -0.0738, +0.1450, -0.0459, -0.1222, +0.0501, -0.4743, -0.0633, -0.1730, -0.0526, +0.1144, +0.1252, +0.0175, +0.2888, +0.2878, -0.0642, -0.4326, -0.0421, +0.5604, -0.1325, +0.1343, +0.4688, +0.3642, -0.3168, -0.3097, +0.1854, -0.1056, -0.0041, -0.1558, -0.4009, -0.0136, -0.0572, -1.4377, -0.1642, -0.0893, -0.1262, +0.5482, -0.1530, -0.1314, -0.1865, +0.1544, +0.2510, -0.2994, +0.2177, +0.1859, +0.3517, -0.3309, -0.1467, -0.2601, -0.0053, +0.2824, -0.0076, -0.1656, +0.5284, -0.2198, -0.5152, -0.4911, -0.0592, -0.3420, +0.0482, +0.0769, -0.2824, +0.1832, +0.3256, +0.2028, -0.1730, +0.0780, +0.1358, +0.1322, -0.2479, +0.0363, -0.1282, +0.3515, +0.2663, -0.2877, +0.2531, +0.0901, +0.4157, +0.2200, -0.0936, -0.4784, +0.1988, -0.1421, +0.0299, +0.3992, -0.5075, +0.1705, -0.4994, -0.4354, -0.2757, -0.3260, +0.1986, -0.0314, -0.2276, -0.0841, +0.1922, +0.0777, -0.3740, -0.8162, -0.3210, +0.2908, -0.0066, +0.3830, -0.0275, -0.0054, -0.5686, -0.3304, +0.2550, -0.1482, -0.1277, +0.1528, +0.0152, +0.3266, -0.1639, -0.2498, +0.1536, -0.1135, -0.1109, -0.0162, -0.1373, -0.3185, -0.1413, -0.4320, +0.0198, +0.0807, -0.3152, -0.1504, +0.3467, -0.0254, +0.1652, -0.0769, -0.2225, +0.2389, +0.1408, +0.5036, -0.1342, +0.3223, +0.5522, -0.5153, +0.1950, -0.5411, +0.1289, -1.3593, -0.1572, +0.1246, +0.2857, -0.5160, -0.0212, +0.1755, +0.2012, -0.1534, +0.0277, +0.0755, -0.4493, +0.1839, +0.2857, -0.2879, -0.0920, -0.0917, +0.2131, +0.5900, -0.4697, +0.2854, -0.7325, -0.0251, -0.5607, -0.5852, +0.0302, -0.5642, -0.7150, +0.0296], +[ -0.5366, -0.0531, +0.1124, -0.2017, -0.1809, -0.4269, +0.6671, -1.3134, +0.0068, -0.3639, +0.6549, +0.0154, -0.0122, +0.7394, -0.1614, +0.4954, -0.7794, +0.8172, -0.7611, -0.0067, +0.1521, +0.1350, +0.3450, -0.1466, -0.0309, +0.7165, +0.4891, -0.1217, -0.4430, +0.1883, -0.1012, -0.0586, +0.9688, -0.5793, -0.7512, -0.7491, +0.3468, +0.2876, +0.3349, +0.1740, +0.4537, +0.4894, +0.1092, +0.0501, +0.0156, +0.5487, +1.0158, -0.3966, -0.2654, -0.0724, +0.5067, -1.0364, +0.3480, -1.2098, +0.1811, +0.1189, -0.1088, -0.4454, +0.2028, -1.8978, +0.5481, +0.6970, -1.6196, -1.6491, -0.3147, +1.4683, -0.9395, +0.1823, -0.3368, -0.0161, +0.3138, +0.5338, -1.0571, -0.6651, +0.8359, +0.6429, -1.0306, +0.1145, -0.1924, -0.8384, -0.5674, +0.2337, +0.2191, -0.0808, +0.4547, +0.2254, +0.7611, +0.2956, +0.4412, +0.2042, -0.3485, -0.8579, -0.0360, +0.4043, +0.2869, +0.2893, -0.6088, -0.0838, -0.0675, +0.6638, -1.3170, -0.6425, +0.1490, +1.0714, +1.4623, +0.1846, +0.8732, +0.1235, +0.0416, -0.6125, -0.4323, -0.4897, +0.1530, -0.8170, +0.1582, +1.4972, +0.5751, -0.9646, -0.3476, -0.8966, +0.0913, -0.2005, -0.0103, -0.3659, +0.1734, +0.7632, -1.1119, -0.0537, +0.0060, -1.3084, -0.4407, -0.0468, -0.4416, +1.1417, +0.4995, +0.2502, -0.3735, -0.2458, +1.3448, -0.8585, +0.0501, -0.0543, +0.2666, -0.8573, +1.4857, +0.7025, -0.0231, -1.3243, -0.4544, -0.2274, +0.4979, +0.3006, +0.6793, -0.1725, -0.0746, +0.3645, +0.1898, -0.5180, +0.5533, -0.5042, +0.2358, +0.4967, -0.2988, +0.1609, -0.0783, -1.1282, -0.2522, -0.6260, -0.2272, +0.0970, -0.3885, -0.1422, -0.4530, -0.9385, +0.0407, -0.7700, -0.2531, +0.5047, -0.3739, +0.6096, +0.0805, -0.3859, -0.0817, +0.8843, -0.3196, -0.8929, -0.2564, +0.2006, +0.2478, +0.3182, +0.7476, -0.7697, +0.9693, +0.2046, +0.3687, +0.1164, +0.4698, -1.7755, -1.1123, +0.2230, -0.7335, -0.0206, -0.2223, +0.3990, +0.5648, -0.9936, -0.8622, -0.1690, -1.1837, +0.6950, -0.6163, +0.7241, -0.2630, +0.4631, +0.3327, +0.4036, -0.7987, +0.4207, +0.4984, +0.2982, -1.2386, +0.4749, +0.4591, -0.7422, +1.0875, +0.5354, -0.6738, +0.0386, +0.7613, +0.0585, +0.1570, -0.7002, -0.5231, +0.4646, +0.3237, +0.6031, +0.2195, +0.8915, -0.4667, +0.3789, +0.2301, +0.2010, -0.5623, +0.4832, +0.1143, +0.7928, -0.3460, -0.0472, -0.2626, +0.6499, -0.8235, -0.2990, -1.1168, -0.1905, -0.7103, +0.5388], +[ +0.3133, -0.6316, +0.2023, +0.6097, -0.5400, +0.1520, +0.0771, +0.1700, +0.5944, -0.1067, +0.0666, -0.0254, -0.4327, +0.2285, +0.4536, -0.5574, +0.0504, +0.7510, +0.0809, +0.3838, -0.8439, -0.1147, -0.1345, +0.0099, +0.1836, +0.3595, -0.2420, -0.0407, -0.1447, +0.2181, -0.7152, +0.1702, +0.7404, +0.2821, +0.0276, -0.9614, -0.4581, -0.5366, -0.2125, +0.0668, -0.0150, -0.2005, -0.3165, +0.3662, -0.1285, -0.3924, -0.6074, -1.2115, -0.0836, +0.3740, +0.0347, -0.5316, -0.4051, +0.4834, +0.4039, +0.5063, -0.6241, -0.8050, +0.2015, -0.4484, -0.2013, -0.6292, -1.1865, -0.8314, -0.0588, -0.3668, +0.2977, +0.3386, -0.1837, +0.0628, +0.3704, +0.5527, +0.3007, +0.2247, +0.0288, +0.4336, -0.4317, +0.1014, -0.0536, -0.1351, -0.0964, -0.5354, -0.2087, +0.1205, -0.0931, +1.2910, -0.4756, +0.5848, -0.3123, +0.4850, -0.7045, +0.2975, +0.4772, -0.5417, -0.6282, +0.2288, +0.3505, -0.4983, -0.3921, -0.8337, +0.6614, -0.8303, -0.0417, -0.0454, +0.3398, +0.5071, -0.2283, +0.8284, +0.8516, +0.1268, -0.1436, -0.7265, -0.0281, -0.4421, -0.6513, +0.3358, -0.0248, +0.3102, -0.0737, +0.1734, -0.0482, -0.3296, +0.1719, -0.0633, -0.1005, -0.2895, +0.3284, +0.5012, +0.4542, +0.4629, -0.2717, -1.0846, +0.4166, +0.5448, +0.0183, -0.2270, +0.3915, +0.3580, -0.2457, -0.2945, +0.1370, -0.0692, -0.0832, +0.7713, -0.5414, +0.7029, -0.0502, -0.2691, -0.2321, -0.0533, -0.1938, -0.1868, -0.0738, +0.6259, -0.9198, +0.7292, -0.8877, -0.2662, -0.1584, -0.4681, -0.1216, +0.0493, -0.5111, +0.2386, +0.3455, -0.4765, -0.9506, -0.5355, -0.4193, -0.1604, -0.2862, +0.6543, +0.0157, +0.2146, -0.1735, -0.3411, +0.2515, +0.0945, +0.2771, -0.8631, +0.8575, -0.1875, +0.1667, -0.1624, -0.2783, -0.1305, +0.4377, -0.0527, +0.1919, +0.2666, -0.5505, +0.2840, -0.3974, +0.1018, +0.2978, -0.3643, +0.1362, +0.0297, +0.3011, +0.1747, -0.0179, -0.4801, +0.8440, -0.6682, +0.4672, +0.6367, -0.1213, +0.3026, +0.4612, -0.1369, -0.3340, +0.0787, -0.2030, -0.4573, +0.3517, +0.4259, -0.0845, +0.1546, -0.2297, -0.2969, -0.0824, +0.1241, -0.4702, +0.0363, +0.0921, +0.3557, -0.8600, -0.3158, +0.3729, +0.0638, -1.1007, -0.2081, -0.2055, +0.1172, +0.0916, -0.0058, +0.1816, +0.0123, +0.1429, -0.5018, -0.3023, -0.4876, -0.0388, -0.1106, -0.3108, -0.8963, -0.6240, +0.6068, -0.1200, -0.3523, -0.5510, +0.2055, +1.1523, +0.5612, -0.4251, -0.4462], +[ -0.2078, +0.2159, -0.6899, +1.1732, -0.5647, -0.0560, -0.0740, +0.1268, -0.0523, +0.3479, +1.4624, -0.4836, +0.7700, -0.5258, +0.7166, -0.1354, -0.3892, +0.3247, +0.3710, -0.4606, -0.5177, -0.0647, -0.1316, +0.0905, +0.1431, +0.7916, -0.0960, +0.7971, -0.0478, -0.0183, -0.1254, +0.3246, +0.3927, +0.7055, -0.1469, -0.0563, -0.5129, -1.2095, -0.4517, -0.3763, -0.2522, -0.6434, -0.0896, +0.0748, +0.1881, +0.2351, -0.2307, -0.3198, +0.2472, -0.6252, +1.0733, -0.9754, +0.9886, +1.6223, -0.0218, -0.0685, -0.6506, -0.6508, +0.6577, +0.1807, -0.3100, -0.0847, +0.5665, +0.1520, -0.4894, +0.1449, +1.0282, +0.3099, +0.3025, +0.0711, +0.5635, +0.1188, +0.4385, +0.3915, -0.1982, +0.3720, -0.0862, -0.3462, -0.3721, -0.1543, +0.1193, +0.5861, -0.0313, -0.1667, +1.1074, +0.7065, -0.5241, +0.5442, +0.2790, -0.1370, +0.1128, -0.5967, +0.0350, +0.0144, -0.6178, +0.2484, +0.2531, -0.6824, +0.0965, +0.2046, +0.4401, -0.1291, +0.6294, -0.2014, -0.2637, +0.1229, -0.9164, +0.0964, +0.9267, +0.1048, +0.8069, -0.8321, -0.5052, -0.0693, +0.4893, -0.0462, +0.0229, -1.0707, +0.1171, +0.5665, -0.8612, -0.0277, -0.2675, -0.2062, -0.3403, -0.2790, +0.1097, -0.1200, +0.0495, +0.4543, -1.1329, +0.0464, -0.7925, -0.7417, +0.7223, -0.0427, -0.0673, -0.0399, -0.9868, +0.1529, +0.5369, +0.3171, -0.3458, +0.5491, -0.0901, +0.5131, +0.0404, -0.2901, -1.0743, -0.4129, -0.7517, +0.2465, -0.4845, +0.1737, -0.6957, +0.4938, -0.3270, +0.2558, +0.7118, -0.6806, -0.4913, +0.3811, +0.5939, -0.0987, +0.4408, -0.6064, +0.4788, -0.3907, +0.7597, +0.5543, +0.4437, +0.0443, -0.1223, -0.0524, -0.1103, +0.7907, +0.3542, +0.8101, +0.4851, +0.4546, +0.0818, -0.4959, +0.7695, -0.2585, -1.6009, +0.1457, +0.3954, +0.8016, -0.2011, -0.8105, +0.7025, -0.7162, +0.4712, +0.4286, +0.6986, -0.6297, +0.2641, +0.9476, +0.2917, +0.0902, -0.4511, -0.4805, +0.4719, -0.5469, +0.5991, +0.3369, -0.9000, +0.7184, -0.3536, -0.1188, -0.1574, -0.2844, +0.2864, +0.6465, +0.4639, +0.7739, +0.0324, -0.0467, -0.0402, -0.0269, +0.4416, -0.0577, -0.5605, +0.2913, -0.3087, -0.2643, -0.9488, +0.0121, -0.5815, -0.6524, -0.1886, +0.9885, -0.3186, -0.0408, +0.7183, -0.0352, -0.2070, -1.0671, +0.1828, +0.0276, -0.2088, -0.0692, +0.1481, +0.4491, -0.2706, -0.5036, +0.3425, +0.3358, -0.3577, -0.1041, -0.5428, +0.5906, -0.8141, +0.4981, +0.4530, -0.0505], +[ +0.0883, +0.5745, +0.1241, +0.0386, -1.3220, +0.1391, -0.7444, +0.1266, -0.4752, -0.0622, -0.0086, +0.4961, -0.9183, +0.2870, -0.0505, -0.0834, -0.4600, -1.2942, +0.4397, -0.9405, -0.2526, +0.0333, -0.5344, +0.0062, -0.3627, -0.0152, +0.1844, +0.4362, -0.3528, -0.6949, -0.7837, +0.4124, -0.4609, +0.3771, -0.0652, +0.1978, -1.2737, +0.0702, -0.9126, +0.4987, -0.3259, +0.3806, -1.2165, +0.1094, -0.1793, +0.2912, +0.5028, -0.3525, +0.3053, -0.1895, -0.3082, -0.4153, -1.0049, -0.2444, -0.0007, -0.6810, -0.4850, -0.5223, -0.2507, +0.1435, -0.3542, +0.2929, -0.5005, -0.3632, +0.2116, +0.6687, +0.0826, -0.0506, -0.2402, -0.4810, -0.3074, -0.1164, +0.2267, -0.1956, -0.0909, -0.0020, +0.0059, +0.7786, +0.1430, -0.0885, +0.0162, +0.1277, +0.4625, +0.3426, +0.3616, -0.5267, +0.2048, +0.4234, -0.0988, -0.4840, +0.8986, +0.3059, +0.1044, -0.0221, +0.1213, +0.2799, +0.2168, -0.3360, +0.0820, -0.2899, +0.5913, +0.0276, +0.6040, -0.7100, +0.1102, -0.7610, -0.9273, +0.2782, -0.4118, -0.5615, +0.3015, -0.3658, +0.0120, -0.4225, -0.9050, -0.5561, -0.1952, -0.2364, -0.2842, -0.4078, +0.4831, -0.3532, +0.2448, -0.1562, -0.2250, +0.1278, -0.3951, -0.3186, -0.3552, +0.2271, -0.6228, +0.1711, +0.1144, +0.5876, -0.0525, +0.1323, -0.1743, +0.4941, +0.2175, +0.1452, -0.6939, -0.3579, -0.2105, +0.0473, +0.1207, -0.2609, +0.7277, -0.6756, -0.9064, +0.3227, -0.2519, +0.3097, +0.2882, +0.0695, -0.1104, -0.0890, +0.2658, -0.1416, +0.0912, +0.3849, +0.0381, +0.1393, +0.2570, -0.1948, -0.0091, -0.3471, +0.4512, -0.9123, +0.3797, -0.2508, +0.3012, +0.5242, +0.1647, -0.0376, -0.1543, +0.1072, +0.3013, +0.3925, -0.5150, +0.3293, -0.4495, -0.5439, +0.1226, -0.0503, +0.3166, +0.0229, -0.1003, +0.0704, -0.7325, -0.4725, -0.1982, -0.0686, +0.2250, -0.5051, -0.1548, +0.7555, -0.1745, -0.4507, +0.0182, +0.0478, -0.1299, -0.0160, +0.2467, -0.1570, -0.0555, +0.4546, -0.0208, +0.6012, -0.5317, -0.3977, +0.1079, +0.2253, -0.4173, -0.0367, +0.0345, -0.5867, +0.3191, -0.0608, -0.2514, +0.3111, +0.5135, +0.8052, -0.4308, -0.1522, -0.8264, +0.1884, +0.0839, +0.2944, -0.2407, +0.6267, -0.1679, +0.7118, -0.3055, -0.0245, +0.4895, +0.0072, +0.8225, -0.1348, +0.0345, -0.3597, +0.1860, +0.0213, +0.8171, +0.4510, -0.1827, -0.2858, -1.2174, -0.3189, +0.0268, +0.6681, +0.4480, +0.3994, -0.1562, -0.9024, -0.2326, +0.1346], +[ +0.3084, +0.3326, +0.1054, +0.5372, -0.4462, +0.3715, -0.4384, +0.4350, +0.4069, -0.1899, -0.2812, +0.3302, -0.5307, -0.0522, +0.4385, -0.5310, -0.8525, -0.3197, +0.0000, -0.1851, +0.2713, -0.1222, -0.0797, +0.1402, +0.1150, -0.3401, -0.5592, -0.0257, -0.3595, -0.2370, +0.6668, +0.3255, -0.3060, +1.0412, -0.3289, -0.0084, -0.7253, +0.5238, -0.2928, -0.0062, -0.4224, +0.4303, -0.2587, +0.3176, -0.5448, +0.4752, +0.7116, -0.1239, +0.4182, -0.5606, -0.0119, -0.4950, -0.1067, +0.5279, -0.0342, -0.8565, -0.4620, -0.1194, -0.0360, +0.5641, +0.1143, +0.5987, -0.3046, +0.3763, +0.3809, +0.0488, +0.2096, +0.3724, -0.1403, -0.1926, -0.5922, +0.1727, +0.4608, -0.5037, +0.0887, +0.0214, +0.2735, +0.5127, +0.1420, +0.8844, -0.3324, +0.2358, +0.7508, +0.1167, +0.0459, -0.4334, -0.0198, +0.5772, +0.4406, -0.1656, +0.2223, +0.2519, -0.3324, +0.4001, -0.3142, -0.1051, +0.3291, -0.0687, +0.0978, +0.0169, +0.2624, -0.0020, -0.0262, -0.6117, +0.2776, -0.2481, -0.7874, +0.0241, +0.4585, -0.3711, +0.3154, -0.4785, +0.7140, +0.3236, -0.8819, +0.0408, -0.3777, -0.4275, -0.1939, -0.5276, +0.1249, -0.6084, +0.0583, -0.0348, +0.7692, -0.1150, -0.0375, -0.0562, -0.1039, +0.0838, -0.5024, +0.5375, +0.0474, +0.3641, +0.6234, +0.2684, +0.4376, -0.0756, +0.1711, -0.1052, -0.6423, -0.0710, +0.0612, -0.3986, +0.2754, -0.2364, +0.6701, -0.1358, -0.1000, +0.7136, -0.1151, -0.5315, -0.2194, +0.6152, +0.4980, +0.2460, -0.3362, -0.2858, -0.3295, -0.2964, +0.1795, +0.0117, +0.3812, +0.3558, +0.3506, -0.2463, +0.3887, -0.3427, +0.3082, +0.1121, -0.1937, +0.3812, -0.1235, +0.3321, +0.1251, -0.0890, +0.4140, +0.5447, +0.3223, +0.1721, +0.4238, -0.0615, +0.6814, +0.2036, -0.3634, +0.6447, -0.3903, +0.4421, -0.6876, +0.4155, -0.1082, +0.3378, +0.2087, -0.6629, -0.5236, +0.9171, -0.5905, -0.2467, -0.1317, +0.1906, -0.0160, +0.0688, +0.0536, -0.3821, -0.0679, +0.2156, +0.3244, +0.3768, -0.2809, -0.0848, -0.0698, +0.0940, -0.8873, +0.4357, +0.0218, +0.4299, +0.3018, +0.1461, -0.4344, +0.2483, +0.4554, -0.0151, +0.4039, +0.3796, -0.3374, -0.1993, -0.1437, -0.2406, +0.1328, +0.6773, -0.4468, +0.4858, -0.7805, -0.0731, +0.4331, +0.4372, +0.3843, -0.1971, +0.5076, +0.3756, +0.9754, +0.1496, +0.5236, +0.2684, -0.1820, -0.5176, -0.3597, +0.1541, +0.1695, +0.6111, -0.1462, -0.4114, +0.0234, +0.0209, +0.5436, +0.5810], +[ -0.2500, +0.3077, +0.1558, +0.3010, +0.6922, +0.4368, +1.2611, +0.4390, -0.2915, -0.0442, -0.0027, +0.3695, -0.1254, -0.5003, -0.8550, -0.0819, +0.6677, +0.7455, -0.0776, -1.2166, +0.0246, -0.8068, +0.1458, +0.1168, +0.3775, -0.0366, -0.4019, -1.0362, +0.0472, -0.9426, -0.0675, -0.6501, +0.2171, -0.2521, +0.2897, +0.0093, +0.7755, -0.1403, -0.0516, +0.2505, +0.2692, -0.1350, +0.2832, -0.1298, -0.3193, +0.3324, +0.1854, -0.0759, -0.7190, -0.2470, +0.1966, -0.4939, -0.1859, -0.2846, -0.9652, +0.5937, -0.3156, +0.1543, +0.3539, -0.7877, -0.4272, +0.3107, +0.0315, +0.5174, -0.0162, -0.0552, +0.1052, -1.0040, -0.2154, +0.8140, +0.8001, -0.1447, +0.2047, +0.5197, -0.0189, +0.2863, -0.3463, -0.2873, +0.1687, -0.3446, +0.2374, -0.1005, +0.0379, +0.3568, +0.1127, +0.6150, +0.2781, +0.1287, -0.3984, -0.0689, +0.1423, -0.4591, -0.1348, -0.8668, +1.0449, +0.1205, -0.7809, -0.4016, +0.0480, -1.3975, -0.3335, +0.1350, -0.1440, +0.4579, +0.2722, +0.2101, +0.2482, -0.0158, +0.0860, -0.4599, -0.5761, -0.1191, +0.0220, -0.6415, +0.1869, +0.1274, +0.2244, -0.6932, +0.3727, +0.1536, +0.3592, +0.1398, +0.0148, +0.4021, -0.1487, +0.1267, -0.0019, +0.5425, +0.3965, +0.2555, +0.1843, +0.4653, -0.8533, -0.0198, +0.0784, -0.6288, +0.1757, -0.0479, -0.3504, -0.2092, +1.4140, -0.0574, -0.3833, -0.6488, -0.8540, -0.2835, -0.9608, +0.5502, +0.6005, -1.5338, -0.1230, -0.9029, -1.3107, -0.1371, -1.2359, +0.1221, +0.0265, +0.1265, -1.0465, +0.0593, -0.6191, -0.2046, +0.3733, -0.0338, -0.6591, +0.1019, -0.0270, -0.2339, -0.0395, -0.6103, -0.2356, +0.0017, +0.4525, +0.5458, +0.0776, -0.2577, -0.0378, +0.2578, -0.4619, +0.3851, +0.0819, +0.0461, -0.4399, -0.1668, -0.3137, -0.0088, -0.5462, -0.5962, +0.6968, +0.2002, +0.3099, -0.3296, -0.0797, -0.1906, +0.3054, -0.4745, +0.6503, +0.0542, +0.2144, -0.5482, -0.7552, -0.4890, -0.2945, -0.2794, -1.2685, -0.0533, -0.8263, -0.7473, +0.5711, -0.1414, +0.0348, -0.2394, +0.7934, +0.3019, +0.0283, -0.2052, -0.2160, -1.2565, +0.1837, -0.5952, +0.2728, -0.4365, -0.0053, +0.3223, +0.0588, -0.4739, +0.2493, +0.5917, -0.3267, -1.0887, +0.4630, +0.2037, +0.4404, -0.3157, -0.3922, -0.2117, +0.0694, -0.3869, +0.1015, +0.0267, +0.0393, -0.2944, -0.5654, +0.0621, -0.1336, +0.1256, +0.1415, -0.5144, -0.8333, -0.5362, -0.2697, +0.1414, -0.4653, +1.0042, +0.0541, -0.2995], +[ -0.3617, +0.6119, +0.1803, -0.7268, +0.1873, +0.1849, +0.3978, -0.2046, -0.4021, -0.0068, -0.4464, +0.1547, -0.1373, -0.0781, -0.7765, -0.3411, +0.4319, -0.0365, -0.2461, +0.0698, -0.1267, -0.8131, +0.1605, +1.1406, -0.0785, -0.1109, +0.0651, -0.1175, +0.2334, +0.0754, -0.1100, -0.2610, +0.1067, -0.4293, +0.6595, +0.0901, +0.4231, +0.0030, +0.4254, -0.3673, -0.1324, -0.0250, +0.4087, -0.2628, -0.5321, -0.7347, +0.7819, -0.0667, -0.3807, +0.2666, -0.1121, +0.3202, -0.3344, +0.5674, -0.0790, +0.3794, -0.2026, +0.5088, +0.4095, -0.0543, -0.1254, +0.0291, +0.8022, +0.9585, +0.2550, -0.9030, -0.1392, -0.2231, +0.2384, +0.3346, +0.4932, +0.5478, -0.4844, +0.5016, +0.0050, -0.3516, -0.1467, -0.3614, -0.3191, +0.0918, -0.6497, -0.8179, -0.1203, +0.2838, -0.8380, -0.2386, +0.2764, +0.2012, +0.2537, -0.2596, -0.1523, -0.2144, -0.4428, -0.2279, +0.3967, -0.0666, +0.4540, +0.1012, -0.1424, -0.2584, -0.4035, +0.3236, +0.0341, -0.1242, +0.3707, -0.0029, -0.0806, -0.4114, +0.6835, -0.2080, -0.3752, +0.4889, -0.7170, +0.4745, -0.4807, -0.6897, -0.8512, +0.1095, -0.5387, +0.2555, -0.3730, -0.2401, +0.3897, +0.1526, +0.4394, -0.0330, -0.0074, -0.2117, +0.0445, +0.5541, -0.4439, +0.6947, +0.5867, +0.0232, -0.3013, -0.4952, -0.0544, +0.5246, -0.4008, -0.8797, +0.7381, -0.7058, +0.2255, -0.0161, -0.7893, -0.1669, -0.3674, +0.2584, +0.0972, -0.6752, -0.0116, -0.4167, -0.1269, -0.5116, -0.3789, +0.1586, +0.3960, +0.2958, -0.6671, -0.2630, -0.6302, +0.3825, +0.0924, -0.4380, -0.4249, -0.5170, +0.3245, +0.4881, -0.7935, -0.5931, +0.2993, -0.5733, -0.7339, +0.1648, +0.3424, +0.4922, +0.3099, +0.1607, -0.1968, -0.0296, -0.1659, -0.2224, -0.8748, +0.6691, +0.2408, -0.4505, -0.2609, +0.5525, +0.5123, +0.1637, +0.9391, -0.2949, +0.5058, -0.0878, +0.7430, -0.5601, +0.1722, -0.1415, +0.2439, -0.2886, -1.1566, +0.2533, -0.4539, -0.2170, -0.0570, +0.3258, +0.0173, -0.3232, +0.1866, -0.8982, -0.4922, -0.4564, -0.3910, +0.1259, -0.2820, -0.3271, -0.0819, -0.4024, -0.3912, -0.1096, -0.0386, -0.1337, +0.4817, +0.5591, +0.3636, +0.1442, +0.2077, +0.2385, +0.0564, -0.8489, +0.4890, -0.5965, +0.4944, +0.7034, +0.2359, +0.9821, -0.2933, +0.4627, -1.0236, +0.1961, -0.0180, +0.0697, -0.1304, -0.0903, -0.2365, -0.4505, -0.5489, -0.4525, +0.3125, -0.7338, -0.6284, +0.9569, -0.1139, +0.1486, -0.3127, -0.4513], +[ +0.1374, -0.5428, -0.8100, -1.0265, -0.2423, +0.1350, -0.1682, +0.0583, -0.2582, +0.1550, +0.0280, -0.2915, +0.3467, +0.3599, +0.0055, +0.1305, -0.1833, -0.1642, +0.1030, -0.2892, +0.0507, -0.3570, +0.2098, -0.1168, +0.0693, +0.1814, +0.0658, -0.0190, -0.4673, +0.0659, -0.4218, +0.0543, -0.4458, -0.2527, +0.4815, -0.0955, +0.0052, -0.0228, -0.3353, -0.3469, -0.6349, -0.1985, +0.1107, -0.1253, +0.2029, -0.3126, -0.1510, -0.1179, -0.1855, -0.1230, -0.3620, -0.0249, +0.1285, -0.2405, +0.3999, -0.1774, -0.0395, +0.5645, -0.2328, +0.0150, -0.3253, -0.0695, -0.6269, -0.3334, +0.0779, -0.0437, +0.1131, -0.1575, +0.3053, -0.1468, +0.0352, -0.3982, +0.1718, -0.2638, -0.0177, +0.2462, -0.1478, -0.2315, +0.0713, -0.1853, -0.0738, +0.0536, +0.2119, +0.2691, +0.0546, -0.5131, +0.4333, -0.4216, -0.3035, -0.1188, -0.4189, -0.2094, -0.1047, +0.1408, +0.0974, -0.2719, -0.1249, +0.1946, -0.0849, -0.1044, -0.0510, +0.1056, +0.0175, +0.0413, +0.1502, -0.0845, -0.4606, +0.0749, +0.5350, +0.0060, +0.0318, -0.3788, +0.1055, -0.3184, -0.2421, -0.1276, -0.1251, +0.2900, +0.2509, -0.3171, -0.6557, -0.2008, -0.5711, -0.1254, +0.0869, +0.3087, -0.1056, -0.1393, -0.2747, -0.0783, -0.4774, -0.4621, +0.1936, +0.0284, +0.5479, -0.5869, -0.2269, -0.0711, -0.2774, +0.0409, +0.1552, +0.1656, +0.2633, +0.1758, +0.0518, -0.3006, -0.0855, -0.0324, +0.1547, +0.3259, -0.1615, -0.0038, +0.0764, -0.2870, +0.1677, -0.1411, -0.6105, -0.2463, -0.2647, +0.2542, +0.1947, +0.0514, -0.3308, -0.3148, +0.1937, +0.0342, -0.2227, +0.0185, -0.0816, -0.0406, -0.2300, -0.1025, -0.3797, -0.3689, +0.0250, -0.1930, +0.1759, -0.0086, -0.2773, -0.1413, -0.2596, -0.1380, -0.0023, -0.0578, -0.1519, +0.2800, -0.0472, +0.1733, +0.0858, -0.4109, -0.1821, -0.2069, -0.0812, -0.0292, -0.1067, -0.1145, -0.7581, +0.0988, -0.1573, -0.0543, -0.0192, +0.1357, +0.1829, -0.3401, +0.1644, +0.0492, -0.5190, +0.0267, -0.3055, +0.1544, -0.0713, +0.1133, -0.4940, -0.2757, -0.2218, -0.4367, -0.0063, +0.0133, -0.1323, -0.0167, -0.1582, -0.0865, -0.3382, +0.5587, +0.0266, +0.0899, -0.4496, -0.4377, -0.3201, +0.0885, -0.1241, -0.2890, +0.1006, +0.0440, +0.0513, -0.5927, -0.2212, -0.1547, -0.3500, +0.3094, -0.4577, +0.0900, +0.2294, +0.2151, +0.1440, -0.2790, -0.1258, -0.3533, -0.1199, +0.5167, -0.0921, -0.0455, -0.1775, +0.2137, -0.2639, +0.1466], +[ -0.5276, -1.3438, +0.3831, -0.9253, +0.8576, +0.0124, -0.2658, -0.2487, -0.1611, +0.3085, -0.5858, +0.5871, -0.9179, +0.5947, +0.7145, +0.6081, -0.7345, -0.4929, -0.1306, +0.6165, +1.1511, -1.1945, -0.7667, -0.3825, -0.0375, +0.1871, +0.7079, -0.0321, -0.0640, -0.4706, +1.0184, +0.6239, +0.2742, -0.5054, +0.2348, +0.4013, +0.5829, +1.2272, -0.0240, +0.1746, -0.1047, +0.8335, -0.0198, -0.0762, -0.5627, -0.1122, +0.3310, +0.1170, +0.2169, -0.0871, +0.0091, -0.3329, +0.5467, -0.5080, +0.5069, +0.5804, -0.8041, +0.9737, -0.3245, +0.1729, -1.0782, -0.3868, +0.2157, -1.2449, -0.7842, +0.0555, -1.1963, -0.5074, +0.0428, +0.6962, -0.1599, +0.4788, -0.2649, +0.8472, +0.4923, +0.3957, +0.2921, +0.8468, +1.2065, +1.0259, +0.3230, -0.3249, +0.1635, -0.0607, -0.4183, +0.3428, +1.2379, +0.6218, -0.0018, -0.6459, -0.0654, +0.6206, +1.1501, +0.5924, +0.0803, -0.4396, +0.1987, +0.7395, +0.0809, +0.3726, +0.7010, +0.4642, +0.0059, -0.8903, +0.4905, +0.7753, +0.2928, +0.1696, +1.1438, -0.6232, -0.8458, -0.5917, +0.8345, -1.1192, +0.4379, -0.0981, -0.6179, +1.0763, -0.1587, -0.0143, -0.3366, +0.3584, +0.6000, -1.7890, +1.5939, +0.5541, -0.8919, -0.3719, +0.1024, +0.0394, -0.2871, +0.1840, +0.4360, +0.3877, +0.7105, -0.5494, -0.2323, -0.8096, -1.4210, -0.0810, -0.4973, +0.8591, +0.3779, +0.4127, -0.1358, -1.2560, +0.0892, +0.0455, -0.2307, +1.3972, +1.4152, -1.0996, -0.0079, +0.1609, +0.1529, +1.2245, -0.7034, -0.0371, +1.0239, -0.1093, -1.2783, -0.1734, -0.1558, -1.2371, +1.1509, +0.2892, +0.3994, +1.4772, +0.2275, -0.1904, +0.1494, -0.6271, -0.2104, -0.6753, +1.2702, -0.6296, -0.3667, +0.1936, -0.5729, +0.0596, -0.9871, -1.0458, +0.1219, +0.0623, -1.0077, +0.3999, +0.2206, -0.6258, -0.7348, -1.5555, -0.3696, +0.3870, +0.0152, +0.1681, -1.2091, -0.3437, -0.8404, +0.9248, -0.1502, +0.4254, -0.5557, -0.3428, +0.3771, -0.3366, +0.1037, +0.3911, -1.4632, +0.1639, -0.8553, +0.3079, -0.0169, +2.2567, -1.9198, +0.3675, -0.4832, +0.4359, +0.6070, -0.7928, -0.0742, -0.5579, -0.1285, +0.1660, -1.0886, +1.1281, -0.2143, +0.9417, +0.3212, -0.0355, +1.6218, -0.5859, -0.1306, -0.6681, +1.0604, -0.5643, -0.5695, -0.8043, -0.8766, -0.4868, +0.9869, +0.9962, +0.3336, -1.1848, -0.3094, -0.3334, +0.2218, -0.4546, -0.5356, -0.8120, -0.6476, -0.6687, -0.5322, +0.1139, +1.3689, -0.0917, -0.0398, +0.9746], +[ +0.4746, +0.6490, -0.0563, +0.6347, -0.1950, -0.1855, -0.0127, -0.1160, +1.1050, +0.0292, -0.1313, +0.7417, +0.0635, +0.5027, -0.4095, +0.5781, +0.3729, +0.1721, +0.3567, +1.1599, -0.5712, -0.6483, -0.4589, -0.5270, +0.1732, -1.2591, +0.4863, -0.9328, +0.0039, +0.2550, +1.4603, -0.7980, -0.3856, +0.0379, -0.2163, +0.6541, -0.4396, +0.5536, -0.0282, -0.4969, +0.2063, -0.8435, +0.3136, -0.6127, -0.1036, +1.1152, +0.5326, -0.6026, +0.2343, -0.3199, -0.3462, -0.2891, +0.3153, -0.4382, +0.2658, +0.5144, -0.1004, +0.5722, +0.6198, -0.1634, +0.6600, -0.3581, -0.5464, -0.2069, +0.2790, -0.0548, -0.2250, +0.5619, -0.3516, +0.5768, +0.0918, -0.0851, -0.1171, -0.4577, +0.2275, -0.0844, +0.9257, -0.0400, -0.1302, -0.2833, -0.2913, +0.3435, -0.6581, -0.5410, -0.1167, +0.1244, +0.9532, +0.3339, -0.1696, -1.0204, -0.8628, +0.4471, +0.6016, -0.0928, -0.5537, +0.9510, +0.2470, -0.0080, -0.1268, +0.7720, -0.0184, -0.3384, +0.2185, -0.8863, -0.0140, +0.0291, -0.3500, +0.1724, +0.7346, -0.5315, +0.5823, +0.2847, +0.1213, +0.5961, -0.5800, -0.4652, -0.7573, +0.1346, +0.0915, -0.5366, +0.1836, +0.8365, -0.5010, +0.0161, -0.4858, +0.2502, +0.8965, -0.2293, -0.1035, -1.1650, +1.1383, +0.0969, -1.4010, -0.0933, +0.4967, +0.4204, -0.6597, +0.1957, +0.5147, +0.3877, -1.0364, +1.7310, -0.7283, -0.5552, -0.9958, +0.1301, -0.2359, -0.6026, +0.8743, -0.0038, -0.8864, -0.6011, -0.9583, -1.2237, -0.5029, -0.0788, +0.6273, -0.1550, +0.0569, +1.0592, -1.0994, -1.3958, +0.7132, -0.3483, +0.0321, +0.2592, +0.6079, +0.1530, +0.8406, +0.3430, -0.0344, -0.1821, +1.5350, -0.2418, -0.5004, -0.1613, -1.2243, +0.3113, +0.5512, -0.1078, +0.2478, -1.0035, -0.4421, +0.2409, +0.2840, +0.0553, +0.5921, +0.5255, +0.7057, -0.1598, +0.9546, +0.0526, +0.3708, +0.2987, -0.2607, -0.3898, +0.6809, -0.3427, -0.6318, -0.2139, -1.0395, +0.5142, +0.3191, -0.5015, +0.3427, -0.8764, +0.2258, -0.6226, -0.3563, -0.0095, +0.1180, -0.0894, -0.0828, +0.4943, -0.9282, -0.6606, -0.4134, +0.1086, -0.0555, -1.1844, +0.6912, +0.4039, -0.1119, +0.0709, -0.0453, -0.7530, +0.0188, -0.2012, +1.1507, -0.4265, -0.1570, -0.5780, +0.5714, +0.7797, +0.1656, -0.4177, -0.2286, +0.3263, +0.3342, -1.0660, +0.9417, +0.0318, +0.4741, +0.0620, -0.3524, -0.3416, -0.5109, -0.0235, +0.4831, +0.0348, +0.3290, +0.8699, -0.1673, -0.3973, +0.4861, -0.4140], +[ +0.9079, +0.7905, -0.8778, -0.6168, -0.6697, -0.0622, +0.7345, -0.0286, +0.8464, -0.5082, -0.0811, +0.6639, +1.0680, +0.1035, -0.2131, +1.1516, -0.2689, -0.6938, +0.8596, +0.0857, -0.8148, +0.3525, -0.6048, -0.9561, -0.4924, -0.0850, +0.1967, -0.7057, -1.1881, +0.8330, +0.2124, -0.7318, -0.1144, +0.2397, +0.3227, +0.9644, -0.4401, -1.3300, +0.3038, +0.2791, +0.3383, +0.5044, +0.6904, -0.6599, -0.6532, -0.6436, +0.6976, +1.3793, -0.3978, +0.7100, -0.2195, -0.3812, +0.3690, -0.1254, -1.0735, +1.2677, -0.2901, +0.0035, +1.6962, -0.6103, +0.6258, -0.9371, -0.7765, +0.0440, +1.6579, +0.1763, +0.5664, +0.5588, +1.0481, +0.6091, -0.0223, -0.9908, -0.4076, -0.2800, -0.0961, +0.1303, +0.0567, +0.2445, +0.0284, +0.5881, +0.5713, +0.5311, -1.2043, +0.3325, +0.7527, +0.2728, +0.7195, +1.2142, -1.3905, -1.0492, -0.4155, -0.5728, +1.0382, -0.3996, -0.1396, +0.5156, -0.2043, -0.6742, -0.5733, +0.2610, +0.4607, -1.3460, +0.1924, +0.3357, +0.5231, +1.0669, -0.5209, -1.6138, -0.0863, +0.7761, -0.9102, +0.1233, -0.9402, +1.2671, +0.4664, -1.2182, +0.2402, -0.7552, +1.8687, +0.0714, +0.9773, +0.8177, -0.3350, -0.0919, -0.5721, -0.8396, +1.1060, -0.1265, +0.0583, +0.4129, +0.5108, +0.2976, -0.6591, -1.6417, +0.7939, +0.5756, -0.7724, -0.5524, +0.5851, -0.5469, +0.1929, +1.2866, -1.1102, -0.6085, -0.2798, +0.3116, -0.3718, -1.3797, +1.5620, -0.1876, +0.6959, -1.3734, +0.3470, -0.6543, -0.1204, +0.8051, +1.1058, -0.2433, +1.0471, +1.3998, -0.6581, -1.3997, -0.1491, -1.2863, -0.5144, -0.0742, -0.9420, -0.5590, -0.8803, -0.3925, +0.3924, +1.0412, -0.6053, +1.0904, -0.7781, +0.2669, -1.2796, -0.3787, +1.4656, +1.0314, -0.2491, -0.8925, -0.0463, +0.6171, +0.8608, -0.3372, +0.5386, -0.9977, +0.4165, +0.2014, +0.8115, +0.0647, -0.2797, +0.2055, +0.3337, +0.8143, -0.1816, -0.2726, -0.7037, -0.0720, +0.0258, -0.5450, -0.6288, +0.8187, -0.3132, -0.3859, -0.8743, -0.2493, -1.5649, +1.1263, +0.2945, +0.3289, -0.4554, -0.1755, -0.4170, -0.8453, -0.1841, +0.7881, +0.6946, +0.2777, +0.1883, +0.2721, -1.1722, -0.4219, -1.4592, +0.6907, -0.6756, -0.2404, +1.1636, -0.0088, -0.4367, +0.1144, +0.6787, +0.4052, +0.4296, -0.1470, -1.3242, +0.0790, -0.3254, -0.5657, +0.5947, -1.4787, -0.0701, +0.9545, +0.6431, -0.6002, -1.3457, +0.8740, +1.3852, +0.1384, -0.8537, +0.2547, +0.7683, +0.2669, +0.5810, +0.2507], +[ +0.7794, -0.3995, +1.0293, +0.2487, -0.1426, -0.0694, -0.4230, +0.5372, -0.8684, -0.2010, +0.6707, -0.0952, -0.3988, +0.3726, -0.4713, +0.8838, +0.1794, +0.0997, +0.4971, -0.0439, +0.5980, -1.1781, +0.7389, +0.2720, +0.6640, +0.9361, +0.5272, -0.9933, +0.5313, +0.6200, -0.5337, -0.3758, +0.7092, +0.3955, -0.5755, +0.4248, +0.1049, -0.1665, -1.3629, -0.8256, +0.1741, -0.4460, -0.0687, +0.2652, +0.0616, -0.3573, -0.3689, +0.2120, -0.3601, +0.0945, -0.3972, +0.6231, -0.9564, +0.0331, -0.0692, +0.8024, +0.8491, -0.4224, +0.2185, -1.0869, +1.0811, -0.4962, +0.2517, +0.6918, -0.9458, -0.8809, -0.0807, +0.8267, -0.8325, -0.6024, -0.6169, -0.4712, -0.5702, +0.5511, +0.6871, -0.2050, +0.3387, +0.5156, +0.0601, -0.5919, -0.0874, -0.2232, -0.5864, +0.5779, -0.9416, -0.1933, -0.1205, -0.3783, -0.1681, +0.7948, +0.5512, -0.8296, -1.2560, -0.5598, -0.7089, +0.5243, -1.2546, +0.0505, +0.0337, -0.0770, +0.5568, +0.8405, -0.3165, +0.1296, +0.0145, +0.1948, +0.3414, -1.0293, -0.3926, +0.3601, +0.5924, -0.0225, +0.2293, +0.5509, -0.4721, +1.0890, +0.0656, -0.8053, -0.4318, -0.2686, -0.3589, +0.3525, -1.6364, +0.1975, -1.2318, -0.0322, -0.0529, -0.1288, -0.5292, +0.8793, -0.3240, +0.4082, +0.8765, -0.1184, -0.2652, +0.4349, -0.1954, -0.9002, -0.1542, +0.1900, -0.3657, +0.6107, -1.3319, +0.3832, -0.7073, -1.0964, +0.0979, -0.0593, +0.2025, -0.7053, +0.8264, -0.5835, +1.0835, -0.2843, -0.0467, -0.2718, -0.8686, -0.9170, +0.2143, -0.2596, -0.3218, +0.2698, -1.1382, -0.3152, +1.2738, +0.4709, -0.4124, -0.0938, -0.1260, +0.1779, -0.1146, +0.5035, +0.1219, -0.5944, -0.7660, -0.0158, -0.6721, -0.4598, +0.3024, -0.6472, +0.2719, -0.3481, +0.1938, +0.5082, -0.1786, +0.6289, -0.1406, -0.4831, +0.0925, +1.3774, +0.2169, +0.6540, +0.5974, -0.2561, -0.3918, +0.2433, +0.4119, -0.4269, +0.6912, +0.1498, -0.2791, +0.2986, -0.7919, +0.4985, +0.1458, +1.0800, -0.0015, -0.1555, -1.0081, +0.1507, -0.8582, -0.0885, +0.1456, +0.2427, -0.3740, +0.2295, -0.6934, -0.6045, -0.3527, +0.7148, +0.3243, -0.5983, -1.0345, +0.2636, -0.5150, +0.2554, +0.7108, -0.3012, -0.5825, +0.9396, -0.3506, +0.6580, +0.3133, -1.0601, +0.0265, +1.2558, -0.8227, -0.6875, +0.5125, +0.3614, +0.3186, +0.3714, +0.1321, +0.2640, -0.3857, +0.2002, -0.0581, -0.1428, -0.3079, -0.1789, -0.2079, -0.4076, -0.3201, +0.6586, +0.1977, +0.3799], +[ +1.0152, -0.4272, +1.5968, +0.6085, +0.0382, -0.0320, -0.1601, +0.2294, -0.5811, +0.3067, +0.3063, +0.5515, -0.1223, -0.7526, +0.2072, -0.4560, +0.1842, +0.0665, +0.0936, -0.3308, +0.1486, +0.1245, -0.2952, -0.3373, +0.5287, +0.2801, -0.3682, -0.2865, +0.1819, +0.0894, +0.2098, -0.1739, +0.9808, -0.0154, +0.8304, -0.1405, +0.2339, -0.4588, -0.1539, +0.2594, -0.4761, +0.4449, -0.6506, -0.9120, +0.9332, +0.3959, +0.5257, -0.2585, -0.0116, -0.0331, -0.5957, -0.3119, -0.1755, -0.3625, -0.0883, +0.1531, +0.5778, +0.2146, +0.9642, +1.1435, +0.5163, -0.1991, -0.8677, +0.8288, -0.2488, +0.6972, +0.2705, -0.1435, +0.0735, +0.8515, -0.5041, +0.1183, +0.8504, +0.2412, +0.5877, -0.1952, -0.8772, +0.5466, -0.3558, -0.9457, +1.2632, -0.7621, -0.0547, -0.1342, +0.0964, -0.5433, -0.4726, +0.0467, -0.2131, -0.2369, -0.2428, -0.9630, -0.4432, -0.0143, -0.2546, -0.0641, +0.5841, -0.7195, +0.0329, -0.3998, +0.1326, -0.1076, -0.0649, +0.1647, -0.0183, +0.4472, -0.2438, -0.7648, -0.4508, -0.4282, +1.1088, +0.4030, +0.0970, -0.3259, -1.3072, +0.0813, -1.1233, +0.6596, +1.3132, -0.0910, -1.4535, +0.1034, -0.6101, -0.5647, -0.1968, -0.1917, -0.3228, +0.4269, -0.0175, +0.1723, +0.7586, +0.2725, +0.2984, +0.0471, +0.3097, +0.5126, -0.0390, -0.2827, +0.1326, -0.5409, +0.2052, +0.1947, -1.2951, -0.1683, +0.0238, +0.0519, +0.2857, +0.3279, -0.0465, -0.2380, +0.6940, +0.0863, +0.7705, +0.0415, -0.1736, -0.0368, +0.0479, -0.4177, +0.6509, -0.7612, -0.4984, -0.2082, -0.0499, -0.4223, +0.1914, -0.9028, -1.0545, +0.5095, -0.1387, -0.3916, -1.0241, -0.2819, +0.6037, +0.5648, -0.0705, +0.0947, +0.6769, +0.0673, +0.2948, -1.3944, -0.6531, -0.4202, -0.1783, +0.0268, +0.0839, +0.1930, +1.2632, -0.1694, +0.1956, +0.0704, +0.1328, +1.1654, -0.0036, -0.2800, -0.1723, +0.1906, +0.6107, -0.7420, -0.1529, -0.0184, +0.3008, -0.3166, -0.4631, +0.8368, +0.0610, +0.5651, +0.3451, +0.1413, +0.4791, +0.7318, -0.4487, +0.5503, -0.1893, -0.9050, -0.0371, +1.0320, -0.2752, -0.2402, +0.1983, +0.1691, -0.1743, +0.0262, -0.3012, -0.2686, -0.5917, +0.4833, +0.2275, -1.0397, -0.7766, +0.1059, +0.9856, -0.7496, +0.0454, -0.1811, -0.5061, -0.2086, +0.4762, -0.0301, +0.3655, -0.8493, -0.3589, +0.2206, -0.1718, +0.4509, -0.6658, -0.1114, +0.4450, +0.1507, -0.7038, +0.1654, +0.1350, -0.1161, -0.6521, +0.4614, -0.2002, +0.7790], +[ +0.2031, +0.3577, +0.0810, +0.3648, -0.4617, +0.3751, -0.1235, -0.1538, +0.2726, +0.1242, -0.1705, +0.1270, +0.2021, -0.2672, +0.0658, -0.1336, +0.1313, +0.3237, +0.4461, +0.1122, +0.1621, -0.1401, +0.2924, +0.5848, +0.0638, -0.3302, +0.1234, +0.2454, -0.1130, +0.1128, +0.1852, +0.0273, -0.1360, +0.1931, +0.0309, -0.0501, +0.0395, +0.2461, +0.0056, +0.8994, +0.2007, +0.0656, +0.1160, -0.5716, -0.3491, -0.3657, +0.3145, -0.1593, -0.1912, -0.0888, +0.4174, +0.1221, +0.3682, +0.0124, +0.4657, +0.2084, +0.1841, +0.1167, -0.0739, -0.2235, -0.1317, -0.1059, +0.0005, -0.3553, +0.0478, -0.2670, -0.3048, -0.0239, -0.3234, +0.2460, -0.1938, +0.0174, -0.1066, +0.0227, -0.0453, -0.2925, +0.2515, -0.0553, +0.6641, +0.1934, -0.0582, -0.0747, +0.1598, -0.0864, +0.6230, -0.2330, +0.1452, +0.0687, +0.3855, -0.0319, +0.0463, +0.3423, -0.1462, -0.5494, -0.2447, +0.2213, +0.2288, -0.0392, +0.1759, +0.1252, +0.2653, -0.2289, +0.2565, -0.2434, -0.3535, -0.1131, -0.3191, +0.0205, -0.0284, +0.0183, +0.0784, -0.2673, +0.1299, -0.0790, -0.1518, -0.0730, +0.1813, +0.3683, -0.1695, +0.1237, +0.3745, +0.3690, -0.6881, -0.1880, +0.0629, -0.0592, -0.0248, -0.0414, +0.4730, +0.1303, -0.0482, +0.0112, -0.1361, +0.1190, -0.0087, +0.1654, +0.0218, +0.3632, +0.4050, +0.0237, -0.1225, -0.0510, +0.2677, +0.1058, -0.4330, -0.2446, +0.0680, +0.0084, -0.1428, -0.0318, -0.3880, -0.0480, +0.1241, -0.2249, -0.0057, +0.3902, +0.0009, +0.4903, -0.0056, +0.0552, +0.0670, +0.2352, -0.3515, +0.2444, +0.1034, +0.1594, +0.1691, +0.1958, -0.0890, +0.4285, -0.4465, +0.2052, +0.1434, +0.0566, -0.1894, -0.1330, +0.3394, -0.0723, -0.2799, +0.5040, +0.3874, +0.2093, +0.1213, +0.4494, +0.0671, +0.2415, -0.0311, +0.1968, +0.1401, +0.2103, -0.2451, +0.0012, +0.3245, -0.1060, +0.5344, -0.0518, +0.0953, +0.1246, -0.0098, +0.0767, +0.1818, -0.2596, +0.0499, -0.1394, +0.2061, +0.0765, -0.3988, -0.1717, -0.1285, +0.3542, -0.0598, +0.0791, +0.2980, -0.1230, -0.0267, -0.1042, +0.0878, +0.0063, -0.0769, -0.6503, +0.3040, +0.5716, +0.0099, +0.4971, -0.1512, -0.1700, +0.0815, +0.3126, +0.1712, +0.2337, -0.0923, +0.3189, +0.0818, +0.1253, +0.3160, -0.0565, +0.1453, +0.1487, +0.1412, -0.0413, +0.1806, +0.3415, -0.2231, +0.1603, -0.0205, +0.0133, -0.1991, -0.0934, -0.2162, +0.1570, +0.5228, +0.0982, +0.1629, -0.0007, +0.0671, +0.6305], +[ -0.2587, +1.4717, -1.2581, +1.1689, -0.8211, +0.7375, -0.5318, +0.7533, +0.9086, +0.5498, +0.4367, +0.4467, +0.7623, -0.5282, +0.1765, +0.3681, +0.5341, -0.1767, +0.1712, +0.0251, +1.2736, +0.3875, +0.4250, +1.0980, -0.9987, -0.7445, +1.4084, -0.1555, -0.0065, +0.7734, -0.0383, -0.7819, -0.5530, +1.3777, +0.1985, -0.1046, +0.7596, -0.5529, -0.7634, +1.6740, +0.6101, +0.9633, -0.5998, -0.5364, -0.5572, +0.4762, +0.6979, -0.3609, +0.1236, +1.5710, +0.1581, +0.2865, -0.6993, +0.0855, +0.3278, +0.3518, -0.0146, -0.6892, -1.5353, -0.0312, +0.1722, -1.0445, -0.1581, -1.0708, +0.3866, +0.7016, -0.6134, -0.6641, +1.1412, +1.3183, -1.6420, -0.2347, -1.0429, +0.7793, +1.1163, +0.3310, +1.1847, +0.1195, -0.4370, +2.6725, +1.7559, -0.0730, +0.1806, +0.8852, +0.4111, -0.0167, -1.1111, -0.2998, +0.6224, +0.8074, -0.6231, -1.3434, -0.1981, -0.3998, +0.5584, +2.2487, +0.8766, +0.3173, +0.1901, +0.4814, -0.2815, +0.2213, +0.1415, -0.1233, -0.8500, +0.5884, +0.7851, +0.3084, -1.3487, +0.5780, +0.2632, +0.0860, +0.6677, +0.4589, +0.5602, +1.3973, +0.1368, -0.5945, +0.3506, +0.4958, +0.1421, -0.0624, -1.9660, -0.1511, +0.0767, +0.1952, -0.7139, -0.1675, -0.2837, +0.3031, -0.8060, +0.4746, +0.9971, +0.9237, -0.6620, -0.4858, -0.0629, +1.3183, +0.0561, -0.6683, -0.0898, +0.8873, -0.4117, +1.0612, +0.3377, +0.6326, -0.0532, -1.0591, +1.4041, +0.7255, +0.2089, -0.3014, +0.4921, +0.0062, +0.3732, -0.8475, +0.6848, +0.0985, +0.3710, -0.2956, -0.4557, -0.1119, -0.3930, -1.0178, -0.8864, -1.1830, +0.0800, -1.2098, +0.0087, +1.1755, +0.1675, +0.9011, +0.2116, -0.6979, +0.3733, -0.4422, +0.4411, -0.2016, +0.0778, +0.5067, +0.7934, -0.6171, -0.3097, +1.4559, -0.1367, -0.2373, +1.1098, -0.6761, +0.6733, +0.3182, -1.1651, -0.8602, -0.0873, -0.1958, +1.1926, -0.2270, +0.7515, -0.0983, -0.8228, +0.4345, +1.0731, +0.5583, +0.7641, -0.9911, -0.9689, +0.9484, -1.5987, -0.7247, +1.2311, -0.0236, +0.3943, -0.1350, +0.3385, -1.1370, +0.0704, -1.0800, +2.6736, -0.3049, +0.3406, +0.3617, +0.2617, -0.4761, -0.2080, -0.7092, -1.1429, -1.1093, +0.6757, -0.7916, -1.6909, +0.1712, -1.2448, -0.0885, -1.1596, -0.9892, +1.1010, -0.1438, -1.1564, -1.1641, +0.8402, +0.4540, +0.3659, +0.5764, -0.6388, +1.3488, -0.1266, -0.1939, +0.7784, -0.8709, -1.7219, +0.5963, +0.2587, +0.7790, +0.8252, +0.2516, -0.6644, +1.2204], +[ +0.3592, -0.5473, -0.3097, -0.1018, -0.2525, +0.2532, +0.1852, -0.0088, +0.0655, -0.1855, +0.5385, -0.3589, +0.1838, +0.0969, -0.2628, +0.5441, -0.5624, +0.5361, -0.0491, -0.7181, +0.1281, +0.8338, -0.5089, +0.1088, +0.2301, +0.7786, +0.2525, -0.1566, +0.1209, -0.0165, -0.5423, -0.0324, -0.4267, +0.1346, +0.5207, +0.3439, +0.2450, -0.3079, +0.3215, -0.2746, -0.0576, +0.3982, +0.2115, +0.5541, +0.0766, -0.4200, +0.3545, -0.6151, +0.3697, -0.4220, -0.9963, -0.0358, +0.4634, -0.5239, +0.4562, +0.6207, -0.3370, +0.2265, +0.3755, +0.3904, -0.2075, -0.2598, -0.0633, -0.4194, +0.5470, +0.5681, +0.1983, -0.0904, +0.5055, -0.6471, -0.0167, -0.0303, +0.2334, -0.0423, +0.2169, +0.6253, -0.6199, +0.2927, +0.5569, +0.5446, -0.5548, -0.4428, -0.1779, -0.6061, +0.3867, -0.0211, +0.4600, +0.3529, +0.1077, -0.4499, +0.0824, +0.7483, -0.0086, -0.4067, +0.9282, -0.1023, -0.1676, +0.1965, +0.3254, -0.1279, -0.1506, +0.1424, +0.1603, +0.8137, -0.3727, -0.4988, +0.1526, -0.2360, +0.3461, -0.0394, +0.4962, +0.0610, +0.1735, -0.0205, +0.7807, +0.1340, +0.5147, +0.0883, +0.3427, -0.2549, +0.0896, -0.1998, +0.3312, +0.2516, -0.0669, +0.4445, +0.1057, +0.2584, +0.0754, +0.9614, -0.2724, +0.0970, +0.3488, -0.2546, -0.1988, -0.2053, +0.2207, -0.6095, +0.1199, -0.1256, -0.7693, +0.0747, +0.0203, +0.1841, +0.3277, -0.0653, +0.5064, -0.0817, +0.0032, +0.0842, -0.0084, +0.1438, +0.4430, +0.0838, +0.4066, -0.5317, -0.4929, -0.7820, +0.6759, -0.0047, +0.0779, +0.1832, +0.7314, -0.1949, -0.2592, -0.1778, +0.2129, -0.1953, +0.2811, -0.3692, -0.8135, -0.1123, -0.3494, +0.3097, -0.0034, -0.0640, +0.3743, -0.1830, +0.3457, -0.2519, +0.1464, +0.2380, +0.9953, +0.1149, +0.2285, +0.3024, +0.1707, +0.4957, -0.0838, +0.2673, -0.1883, +0.5624, -0.3179, +0.1476, -0.3644, -0.1482, -0.3382, +0.5344, +0.3742, -0.2313, +0.0031, +0.3530, +0.6537, -0.6092, -0.2391, -0.1602, -0.0471, -0.4469, -0.2055, +0.0156, +0.4789, -0.1673, -0.4586, +0.0224, +0.6343, -0.5151, +0.5684, -0.2783, -0.4272, +0.0596, +0.3467, -0.5315, -0.3208, +0.7246, -0.2494, -0.5467, +0.5609, +0.6399, -0.0605, -0.4482, -0.3522, -0.2714, +0.0103, +0.1283, -0.3618, +0.4830, +0.2682, -0.3372, -0.9003, +0.3099, +0.5265, -0.1855, +0.3999, +0.2228, +0.2785, +0.2410, +0.3890, +0.1071, +0.4037, +0.0730, -0.1131, -0.5232, -0.0883, +0.4060, +0.5556, +0.8502], +[ -0.1343, -0.2508, +0.4466, +0.1928, -1.3764, +0.5608, +0.5246, +0.1057, -0.5098, -0.2481, +0.3235, +0.5815, +0.6031, -1.3475, +0.3300, -0.4184, -0.6097, +0.1800, -0.2128, +0.8702, -0.3855, +0.8850, -1.2823, +1.7465, +0.1154, +0.3326, +1.5720, +0.3796, +0.6865, +0.3970, -0.4212, -0.6553, +1.1901, +0.1061, +0.4295, -0.2777, +0.7180, -0.3106, -0.1774, -0.1792, -0.7945, +0.5230, +0.3777, -1.5737, +0.5463, -1.1414, -0.3024, -0.2935, +1.6658, +0.1355, -0.3055, +0.1280, +1.0071, +0.6983, -0.1000, +0.8603, -0.4452, -0.0920, -0.0800, +0.4033, -1.3896, +0.3404, +0.3678, -0.8422, +0.9925, +0.6851, -0.1356, -0.8242, +1.6621, -0.2808, -0.1091, +0.4584, +0.2921, -0.7004, +0.8090, +0.1422, -0.8455, -1.1053, +0.0825, +1.1285, -1.2245, -1.0105, -0.3434, -1.6341, -0.5537, -0.8407, -0.2705, -0.1580, +1.3811, +0.7322, -0.2809, +0.6630, +0.0622, -0.9919, -0.2476, -0.5338, -1.0355, -0.4306, +1.2108, -0.7038, -0.8522, -0.4159, -0.4341, -0.9691, -0.4149, +0.2669, +0.1698, +0.6613, -0.5911, -0.0239, +0.2033, -0.0434, -0.1534, +0.0713, -0.2211, -0.6775, -0.5210, -0.7939, -0.9760, -0.3736, +0.4148, -0.0374, -0.5101, +0.2733, +0.1276, +1.1739, +1.0531, +0.1120, -0.2605, -0.3248, -1.3695, +0.5495, -0.3836, -1.2904, +0.0924, +0.1732, +0.7190, -1.8944, +0.5771, -0.7028, -1.3076, +0.3683, +1.0602, +0.9195, +0.5505, +2.1586, -0.1119, +0.2749, +0.0851, +0.1625, -0.5860, +0.7156, +1.0821, +0.6278, +0.6332, +1.0299, +0.7335, -0.6378, -1.1269, -1.3456, -0.3317, +0.2087, +0.2395, -1.2800, +1.3199, +0.8713, -0.1688, +0.7461, +2.3621, -1.8532, -1.1558, -0.8474, -0.8858, +1.1107, -0.6988, +0.5648, +0.5592, +0.0090, +0.9274, +0.0033, -0.2176, -0.2460, -0.4024, -0.5599, +0.1274, +0.0351, +1.7716, -1.3724, +0.2129, -0.5534, -0.2584, -0.2184, +0.1280, +0.2762, -0.8356, -0.1989, +0.6781, +0.7678, -0.0635, -0.8494, -0.5063, +1.4836, +0.9417, -0.8640, -0.9373, -0.0647, -0.4305, +0.3043, -1.3472, -0.6325, +1.0122, -0.9094, -0.3081, +0.2821, +1.9533, -0.4383, -0.0838, -0.4351, -0.2311, +0.6239, +1.3051, +0.9572, -1.2479, +0.5177, +0.9639, +0.3607, +1.8729, +1.3819, +0.5825, -0.5135, -1.0385, -0.9116, -0.0064, +1.0256, -2.7996, -0.2395, +0.7472, -1.3705, +0.2986, -0.6054, +0.6847, +0.0719, -0.8614, +0.2998, +0.1512, -0.6667, +0.2468, +0.6496, -1.2415, +0.8087, +0.6789, -0.2141, +1.5373, +0.1668, +0.4588, +0.7919], +[ +0.4301, -0.0051, -0.0875, +0.3149, +0.1445, -0.2641, -0.1754, +0.5335, -0.0157, -0.2217, -0.0377, +0.1612, -0.0294, +0.3743, -0.2604, +0.1637, -0.1160, +0.0079, -0.0766, +0.0414, -0.0153, +0.2402, +0.3822, -0.3192, -0.6855, -0.4405, -0.4147, +1.1371, +0.3184, -0.1308, +0.0473, +0.4313, -0.0454, +0.1781, +0.4002, -0.8131, -0.3910, +0.2740, -0.0340, +0.7894, -0.0778, +0.1756, -0.0962, -0.1095, +0.3778, -0.1233, +0.3710, -0.0951, +0.1384, -0.1220, -0.0544, -0.9435, +0.2298, -0.2771, -0.3243, +0.0912, -0.1642, -0.0708, +0.0869, -0.1744, +0.4446, -0.0291, +0.7510, +0.8012, -0.3125, +0.5270, +0.2996, +0.4207, +0.6451, +0.4491, +0.4604, -0.3475, -0.6101, +0.1729, -0.4379, -0.1075, +0.1705, -0.3692, +0.8727, -0.0143, -0.3038, -0.0700, +0.3822, +0.6457, -0.0217, +0.5809, +0.2763, -0.2581, +0.2419, -0.4404, +0.1733, +0.0276, +0.6988, +0.8704, +0.1141, -0.3121, +0.3798, +0.2060, -0.1407, +0.1235, -0.3681, -0.2431, +0.6762, +0.5232, -0.5515, +0.5500, -0.3355, -0.4603, +0.4862, -0.1196, +0.0621, +0.5295, +0.6918, +0.2692, +0.1853, -0.0964, +1.0014, +0.3324, +0.3988, +0.5131, +0.2976, -0.2324, +0.5504, -0.0915, +0.2536, +0.0679, +0.2896, +0.3822, +0.2914, -0.0889, -0.2608, -0.2823, +0.2455, -0.1054, -0.2823, -0.0489, +0.7225, -0.5020, -0.1037, +0.4323, -0.0741, -0.3735, -0.2149, +0.1601, -0.7872, -0.9418, -0.5975, +0.5669, -0.1317, -0.1543, -0.1119, +0.7635, -0.2892, +0.2267, -0.2927, +0.6342, -0.7640, +0.1373, +0.2916, -0.2643, +0.2569, -0.3059, -0.0311, -0.3020, -0.6296, +0.0174, +0.0450, +1.0147, +0.4829, +0.5843, -0.3074, +0.4011, -0.0653, +0.1264, +0.4231, -0.5560, +0.1051, +0.1399, +0.2078, +0.3617, +0.3190, +0.1993, -0.2986, -0.3466, -0.4155, -0.0597, +0.3793, +0.4466, +0.3959, -0.3023, +0.0040, -0.2326, -0.4952, +0.0890, -0.0792, +0.0179, -0.4617, -0.3461, -0.0826, -0.1708, +0.2706, +0.5588, +0.4019, +0.3551, -0.4609, +0.3649, -0.1232, -0.1674, -0.1038, +0.1348, -0.0660, +0.0727, +0.7005, +0.0865, -0.1129, +0.3601, -0.0603, -0.1414, -0.0705, -0.0303, +0.6423, +0.1803, +0.4151, +0.0681, +0.5287, +0.5347, -0.0853, +0.9422, +1.1476, -0.0179, +0.2478, +0.0933, +0.2639, +0.2103, +0.4472, -0.1852, -0.4093, -0.3714, -0.3393, -0.0699, +0.7782, -0.4494, +0.5415, +0.7094, +0.1251, +0.5135, -0.4087, -0.2527, +0.4463, -0.0505, -0.2852, -0.8556, +0.3942, +0.0987, -0.0077, +0.5979], +[ +0.2845, +1.0812, -0.7494, +0.7928, +0.1685, +0.1597, +0.1420, +0.0782, +0.0160, -0.1429, -0.3610, -0.6243, -0.1857, -0.3799, -0.1864, -0.7237, +0.1977, -0.0277, +0.2529, -0.6009, +0.1861, +1.2845, +0.0113, -0.1965, -0.4988, +0.9524, -1.1362, +0.0979, +0.0978, +0.5577, -0.5694, +0.1245, -0.0096, +0.2110, +0.9419, -0.9761, -0.1216, +0.1184, +0.6906, +0.0689, -0.2717, -0.1839, +0.4812, +0.8658, -0.3780, -0.9149, -0.1993, +0.4785, -0.4723, -1.1146, -0.4531, -0.8288, +0.8131, +0.3287, -0.3474, +0.0937, -0.7731, -0.3929, -0.2429, +0.2462, +0.4287, -0.2803, -0.8852, +0.5022, +0.1806, +0.0863, -0.1661, -0.9738, +0.7656, +0.4123, +0.0462, -0.6986, -0.6324, +0.2546, -0.1041, -0.3495, +0.3546, -0.2854, -0.0838, +0.1096, +0.1486, +0.4535, +0.5963, +0.5115, -1.1775, -0.0183, +0.3368, -1.0411, -0.1538, -0.1992, -0.0637, -0.4965, +1.3624, +0.0774, -0.1885, -0.1917, -0.1281, -1.5518, +0.0393, +0.3687, -0.2982, +0.0824, +0.6070, +0.4407, +0.4273, +0.3254, -0.0359, +0.0932, +0.0982, -0.1779, -0.4939, +0.4630, -0.0588, -0.0963, -0.0445, +0.0383, -0.9067, -0.4780, -0.8662, +0.6478, +0.1210, -0.0671, -0.0488, -0.4615, +0.5291, +0.0794, -0.3347, +0.7754, -0.1222, +0.4951, +0.1517, +0.1694, -0.6412, -0.0738, -0.2780, -0.2456, +0.2203, +0.0484, +0.0835, +0.6804, -0.4793, -0.8170, -0.0797, -0.3415, -0.3049, +0.1274, -0.6019, +1.2989, -0.2131, -0.0808, -0.4516, +0.4898, -0.2154, -0.0225, +0.0655, +0.3478, +0.0185, -0.3479, +0.4347, +0.0999, +0.0793, -0.9525, -0.0407, -0.0925, +0.6913, +1.4525, -0.4044, +0.0837, -0.2553, +0.4982, -0.4324, -0.1525, -0.1488, -0.6428, +0.1974, -0.5170, +0.2185, -1.3480, -0.0615, -1.3151, +0.3056, -0.1194, +0.2072, -0.6148, -0.5407, -0.5680, +0.2053, -0.2356, -0.1255, +0.6072, +0.2077, +0.1942, -0.3421, -0.0024, -0.0669, -0.1494, +0.3493, -1.0341, +0.0665, +0.3289, +0.2825, +0.0613, -0.0985, +0.1094, +0.3992, +0.0906, -0.2558, -0.0444, -0.2922, -0.2714, +0.0269, +0.2303, -0.8004, -0.2422, -0.1758, +0.1609, -0.1121, +0.0069, -0.2658, -0.0016, +0.4041, -0.4815, -0.1375, -0.3767, +0.0661, +0.6412, -0.0630, +0.7240, +0.0774, +0.4729, +0.4779, -0.6123, -0.4901, +0.0965, +0.2687, +0.6720, -0.7838, -0.8790, -0.5969, +0.1599, -0.0727, +0.3581, +0.2928, -0.4210, +0.1209, +0.5134, +0.8239, -0.2588, +0.5264, +1.4808, +0.2310, -1.1862, +1.1727, -0.0640, +0.1582, +0.3120], +[ +0.0172, -1.1238, -0.5016, -1.1918, +0.3910, +0.1795, +0.0503, -0.4863, +0.1703, +0.1462, -0.1386, +0.3944, -0.6998, +0.2394, +0.3020, +0.0680, +0.0091, -0.3455, -0.7739, -0.5416, -0.1543, +0.0340, -0.5541, -0.4612, +0.0488, -0.1452, -0.3268, -0.0772, -0.1545, -0.3110, -0.0585, +0.0679, +0.0346, +0.0893, +0.0122, -0.6993, +0.0531, +0.1817, +0.0834, -0.1794, -0.0571, -0.4912, +0.0552, -0.3705, -0.1491, -0.5484, +0.3888, +0.0526, -0.1392, -0.3859, -0.3149, +0.1368, +0.0454, -0.2472, +0.0746, -0.2081, -0.3802, -0.2701, -0.7529, +0.5921, -0.1139, +0.5151, +0.4211, +0.2626, -0.1105, -0.5061, -0.4920, +0.2586, -0.0108, -0.1262, -0.0240, +0.3779, -0.7462, +0.3654, -0.3487, -0.2882, +0.2652, +0.4255, +0.1863, +0.5477, -0.5843, -0.3706, +0.1130, -0.3929, -0.1854, -0.3030, +0.2220, -0.0894, -0.7535, -0.7834, -0.0204, -0.5167, -0.2607, +0.3052, +0.0319, -0.2919, -0.1374, -0.1339, +0.2415, +0.1194, +0.1944, +0.0716, +0.6676, -0.8269, -0.0466, +0.1289, +0.1831, +0.3119, +0.3629, -0.5299, -0.0872, +0.3453, +0.2217, -0.4897, -0.2563, -0.1342, -0.0896, +0.2592, -0.4204, -0.0450, -0.6944, +0.0078, +0.0787, +0.0199, +0.4863, +0.1886, +0.3215, -0.2611, -0.1486, +0.2414, -0.1718, +0.4281, -0.6486, -0.4176, -0.3029, +0.4823, +0.8132, +0.1277, +0.0055, +0.3228, -0.1253, -0.3521, -0.5403, -0.1949, -0.2421, -0.2463, +0.1556, -0.3001, +0.1514, +0.0274, -0.7368, +0.0907, +0.1133, -0.1469, +0.1039, +0.1180, +0.2917, +0.2558, +0.0316, -0.3933, -0.4351, +0.4973, -0.2582, -0.2405, +0.3755, -0.1156, -0.2276, +0.2097, -1.0808, -0.8002, +0.0366, -0.0562, -0.4894, -0.0145, -0.6245, +0.4986, +0.5006, +0.2602, -0.0508, -0.3204, +0.1924, -0.0899, +0.3825, +0.5341, +0.7027, +0.1131, +0.1199, +0.0252, +0.0072, +0.6830, +0.1546, +0.2466, +0.1135, +0.0015, -0.0177, -0.4254, -0.0954, +0.0434, -0.0305, -0.1784, +0.2699, +0.2957, -0.2150, -0.0487, -0.2437, -0.2200, +0.0523, -0.2779, -0.6089, +0.1060, -0.2136, -0.2251, -0.3129, -0.0839, -0.2522, +0.1036, -0.2146, -0.0584, +0.5832, -0.3026, -0.5945, +0.2099, +0.1080, +0.4115, -0.0818, +0.2817, +0.0098, -0.3738, -0.0005, -0.2097, -0.7590, -0.0630, +0.2055, +0.2783, -1.5297, -0.3210, -0.3086, -0.1355, +0.0386, -0.3155, +0.1009, +0.1150, -0.3786, -0.4136, +0.4385, -0.2626, +0.0942, +0.0446, +0.1205, -0.1513, -0.2796, +0.1553, -0.0969, +0.0511, -0.1249, -0.2802], +[ -0.1034, +0.2357, -0.4203, +0.1591, +0.3585, +0.1246, -0.0421, +0.1255, -0.2100, +0.0055, -0.0512, +0.6803, -0.6657, +0.0623, -0.0359, -0.2987, -0.6500, +0.0916, +0.1569, +0.5246, -0.2630, +0.2165, -0.5772, +0.1229, +0.0293, -0.6651, -0.4447, +0.1485, +0.2914, +0.3376, -0.3570, +0.1639, +0.1711, +0.2401, -0.3681, -0.6154, -0.2828, -0.9889, +0.4287, +0.4902, -1.0063, -0.0716, -0.2519, +0.2374, +0.0735, -0.0310, -0.0960, -0.3189, -0.0257, -0.3756, -0.1699, -0.6484, -0.2126, -0.0991, +0.2516, +0.2817, -0.2249, -0.5916, +0.0468, +0.1980, +0.2723, -0.2368, -0.1617, -0.4406, -0.0696, -0.2598, -0.2409, -0.4176, -0.8485, +0.2568, -0.1216, +0.2768, -0.3487, +0.0511, -0.1213, -0.5023, -0.3206, -0.2718, -0.0845, -0.5767, +0.2253, +0.4208, -0.3365, -0.1327, -0.3217, -0.6869, +0.0320, -0.2220, -0.1256, +0.0224, +0.5940, +0.0939, +0.1967, -0.2259, -0.0278, -0.5220, -0.6105, +0.0110, +0.0768, -0.2414, -0.0436, +0.1692, +0.1113, -0.9959, -0.0885, -0.0330, +0.0898, -0.2107, -0.3087, -0.0716, -0.7209, -0.5470, +0.1603, +0.0911, -0.3636, +0.2226, +0.5098, +0.0130, -1.0301, -0.2137, -0.5319, +0.1819, +0.0335, +0.4514, -0.2537, -0.1274, -0.2860, -0.2903, +0.1763, -0.7967, +0.1072, +0.0330, -0.0080, -0.0305, +0.1275, -0.0920, +0.1267, -0.9726, -0.5605, -1.0906, +0.0436, -0.1351, +0.2924, -0.0994, +0.1213, -0.0452, -0.1222, +0.0212, -0.3013, +0.2962, +0.2039, +0.7498, +0.2355, -0.4564, +0.0400, +0.4825, -0.2935, +0.4372, +0.6510, -0.2114, +0.4234, +0.0511, -0.0598, -0.1777, -0.5762, -1.0183, +0.1683, -0.9535, +0.0247, +0.0302, -0.1133, +0.2441, -0.2464, +0.3237, +0.0242, +0.5588, -0.4974, +0.0399, -0.0217, -0.0068, +0.0193, +0.0620, +0.6197, -0.9937, -0.0499, -0.1407, -0.1001, -1.1461, -0.3159, -0.6738, +0.1658, +0.1644, -0.5083, -0.0085, +0.1327, +0.1629, +0.4424, +0.0172, -0.3822, -0.0851, -0.2080, +0.3361, -0.1089, +0.1334, +0.1965, +0.2532, -0.7738, +0.1240, +0.1797, +0.1834, -0.7705, -0.0152, -0.7457, +0.6776, -0.2594, +0.0591, -0.0137, +0.6278, +0.0465, -0.3670, +0.0655, -0.8144, -0.5686, +0.0183, +0.0477, -0.0919, +0.0162, -1.1542, +0.4707, +0.2479, -0.2166, -0.1802, +0.3401, -0.6682, -0.3063, -0.1307, +0.1714, -2.4957, -0.1072, -0.3282, -0.7105, -0.8619, +0.3392, -0.3000, -0.1363, -0.0181, -0.1055, +0.2948, +0.3553, +0.2409, +0.4209, +0.3848, -0.7700, -0.5748, +0.0001, +0.3585] +]) + +weights_dense1_b = np.array([ -0.0562, -0.1282, -0.3753, -0.1119, -0.0136, -0.2313, -0.0345, +0.0894, -0.0010, -0.0601, -0.0762, -0.1205, -0.1190, +0.0179, -0.0906, -0.0572, +0.0797, -0.2050, -0.0318, -0.2306, -0.0182, -0.0847, +0.0607, -0.1987, -0.1262, -0.1896, -0.0226, -0.0034, -0.0809, +0.0404, +0.0756, -0.1168, -0.0733, -0.0739, +0.0161, -0.0528, +0.0067, +0.0332, -0.2382, -0.0745, -0.0184, -0.0287, +0.1160, -0.0248, -0.1523, -0.0589, -0.3165, -0.0986, -0.0604, -0.0633, +0.0549, -0.0209, -0.0474, -0.2358, -0.0890, -0.1201, -0.0595, +0.1562, -0.1967, -0.0995, -0.1231, +0.0500, +0.0962, -0.1140, +0.0393, -0.1390, -0.1273, -0.0866, +0.0868, -0.0849, -0.1148, -0.2904, +0.0706, -0.1821, -0.1143, -0.2196, -0.0112, -0.0375, -0.1567, -0.0589, +0.1257, +0.1125, -0.1020, +0.0818, -0.2838, -0.1653, -0.1676, -0.0244, -0.0784, -0.0181, -0.0429, -0.0966, +0.0494, +0.0093, -0.0858, -0.0919, -0.1196, -0.2181, +0.0292, -0.2283, -0.2595, -0.0925, -0.0134, -0.0093, +0.0310, +0.0078, -0.0172, -0.0803, -0.0386, +0.1367, -0.1948, -0.0290, +0.0785, -0.0464, +0.0371, -0.0128, -0.0377, -0.0724, +0.1637, -0.1972, -0.1093, -0.1634, -0.0691, -0.0834, -0.2310, -0.2676, -0.0683, -0.0024, -0.1401, -0.0378, -0.1633, -0.1665, -0.1098, -0.0746, -0.0684, -0.1914, -0.1284, -0.0998, +0.0577, -0.0638, -0.0885, -0.0445, -0.0384, -0.1012, +0.0067, -0.2128, -0.1312, +0.0526, +0.1238, +0.0742, +0.0261, +0.0444, +0.0614, +0.1223, +0.1232, -0.1827, -0.1289, -0.0469, -0.1420, +0.0705, -0.2220, -0.2401, -0.1121, -0.1697, -0.1621, +0.0688, +0.0688, -0.0040, -0.0048, -0.0416, -0.1265, +0.0311, +0.0280, +0.0287, -0.1893, -0.0966, -0.0876, -0.1778, +0.0000, +0.0074, -0.0978, -0.1932, -0.0790, +0.0037, -0.1398, -0.1006, -0.0532, -0.1227, +0.1148, -0.1254, -0.1134, +0.1205, -0.1588, +0.1093, -0.2470, -0.0915, -0.1715, -0.0036, -0.2943, +0.1375, +0.1075, -0.0339, -0.0491, +0.0060, +0.0145, -0.1867, +0.0646, -0.1327, -0.0529, -0.0830, +0.1433, -0.1924, -0.0285, -0.2420, -0.2244, -0.1451, -0.1009, -0.1149, +0.0846, +0.0473, +0.1568, -0.0062, -0.1289, -0.2085, +0.0600, -0.1314, -0.1569, +0.2043, -0.0302, -0.1666, +0.0473, -0.0075, -0.2825, -0.0696, -0.2223, -0.2911, -0.0567, -0.0510, +0.0184, -0.2132, -0.0371, +0.1715, -0.1301, -0.0310, +0.1523, -0.0142, +0.0185, -0.0030, -0.0725, -0.1011, -0.0923, -0.1991, -0.1686, -0.1198, -0.2226, -0.1094]) + +weights_dense2_w = np.array([ +[ +0.0445, +0.3258, -0.3897, -0.9250, -0.1552, +0.0457, -0.1724, -0.0763, -1.4100, +0.1473, -0.1446, -0.3841, +0.1477, -0.0290, +0.1949, +0.3805, -0.0565, +0.0721, +0.4733, -0.8596, +0.1278, -0.7788, +0.2252, +0.5076, +0.3259, -0.4569, +0.0218, -1.1651, -0.6023, +0.5247, -0.0698, -0.5287, -0.4980, -0.3742, -0.3540, +0.2404, -0.2737, -0.0001, -0.2909, -0.6940, +0.1236, -0.4878, -0.2978, -0.0255, -0.2776, -0.0096, -0.0926, +0.3629, +0.1967, -1.4511, +0.0184, -0.0039, -0.0859, -0.3284, +0.1288, -0.2185, -0.4335, -0.0137, -0.4161, -0.1739, +0.1742, +0.1686, -0.7623, -0.4584, +0.0873, -0.1496, -0.2064, -0.2601, -0.0554, +0.1165, -0.1830, +0.3370, -0.3273, -0.0035, -0.5173, -0.4919, -0.5520, +0.4621, -0.3296, +0.2683, -0.2363, +0.2684, +0.5559, -0.0760, -0.3864, -0.5297, -1.1667, -0.1952, +0.1237, -0.0796, -0.2315, -0.1927, +0.0855, +0.1945, +0.2481, +0.3408, +0.5076, +0.2756, +0.2805, +0.2590, +0.0864, +0.1665, +0.7472, +0.0074, +0.1091, -0.7141, -0.1676, +0.0718, -0.2115, -0.1887, -0.4651, +0.3149, +0.1988, -0.4582, -0.0331, -0.0648, +0.1369, -0.3698, +0.3056, +0.6038, -0.4791, -0.8684, -0.3822, -0.4373, -0.3103, +0.1921, -1.2456, -0.1832], +[ -0.1644, +0.0559, -1.1163, +0.4768, +0.0837, +0.1339, -0.7792, -0.9042, +0.3480, -0.7278, -0.1942, -0.3883, +0.2595, +0.4492, -0.2603, +0.2858, -0.5011, -0.4032, -0.5475, +0.4062, +0.3066, +0.2421, +0.3979, -0.0046, -1.0351, -0.6019, +0.3501, +0.3352, +0.4175, -0.5266, -0.6269, -0.5685, -0.3698, +0.5508, -0.4117, -1.1622, -0.9162, +0.2534, +0.0436, -0.8803, +0.3523, +0.0850, +0.3050, +0.8887, -0.3365, -0.3370, +0.1841, -0.4630, -1.1252, +0.1474, -0.3641, -0.2109, -0.6057, +0.1948, +0.2263, -0.0045, -0.0550, +0.6555, -0.3998, -0.4963, -0.5501, -0.2589, -0.4759, -0.9856, -0.4430, -0.9262, +0.1264, -0.4759, -0.5656, +0.7274, +0.6485, +0.7692, +0.5744, -0.1457, +0.1298, +0.1832, +0.3575, -0.5757, -0.1918, +0.4286, -1.0246, -0.6236, +0.2141, -0.1002, -0.3561, -0.3934, +0.7368, -0.2440, +0.1372, +0.1610, -1.0551, -0.8087, -0.3633, -0.2956, -0.1642, -0.9371, -0.3696, -0.5521, +0.0405, +0.0178, -0.5200, -1.3731, -1.1641, -0.9716, -0.9021, -0.5449, -0.8470, +0.3427, -0.5285, +0.4033, +0.3367, -0.9577, -0.3523, -0.2851, +0.7887, -0.2403, +0.0766, +0.6234, -0.4794, +1.1367, +0.1354, -0.5252, +0.2428, -0.3933, +0.2007, +0.0248, +0.3071, +0.0446], +[ +0.0672, -1.0581, +0.3253, +0.3608, +0.4397, +0.4099, -0.1706, -1.4956, +0.1242, -0.0741, -0.0724, -0.8454, +0.1054, -0.3769, +0.0595, -0.8427, +0.1487, +0.1021, +0.0235, +0.2057, -0.3067, +0.0910, -0.0292, -0.4893, +0.0259, +0.1918, -0.4798, -0.1641, +0.2843, +0.6346, -0.1970, +0.4576, +0.1711, -0.7762, -0.9540, -0.1866, -0.0695, -0.2133, -0.4258, -0.1893, -0.3393, -0.2800, -0.4166, -0.4609, -0.1899, -0.0236, +0.1991, -0.2867, -0.3952, +0.1985, -1.1685, -0.4137, -0.3359, -0.5354, -0.2031, +0.4196, -0.6850, -0.1369, -0.2796, -0.5954, -0.1591, +0.0054, -0.0236, -0.0944, +0.2996, -0.3397, +0.3878, -0.3327, -0.5361, +0.3334, -0.5441, +0.0895, -0.6604, -0.1568, -0.4287, -0.6188, -0.4958, -0.8847, -0.2318, +0.0979, -0.1458, +0.6555, -0.2316, -0.8410, -0.1204, -0.5653, -0.7725, -1.4690, -0.0659, -0.6189, -0.8568, +0.1092, -0.3853, -0.1022, -0.4768, +0.0461, -1.2451, +0.4257, -0.3797, -0.8929, +0.0062, -0.1235, +0.7245, +0.3688, -0.4415, -0.3380, -2.0255, -0.4822, -0.6014, -0.4930, +0.4081, -0.1571, +0.3983, +0.1135, -0.3538, -1.1742, +0.4119, -0.2515, +0.2638, -0.9096, -0.7660, -0.5376, +0.4075, -0.8097, +0.0791, +0.2727, -0.1079, -0.9154], +[ +0.3015, -0.0740, +0.4066, -0.5555, +0.5124, +0.3837, +0.2981, -0.9054, +0.1914, -0.5646, +0.8334, -0.3740, -0.0627, +0.1642, -0.6534, +0.6830, -0.2664, -0.8940, -0.0617, -0.0839, -0.6640, -0.2262, +0.1927, +0.2503, -1.0157, +0.3276, +0.0375, +0.8604, +0.0385, -0.0106, -0.1545, +0.6813, +0.5188, +0.0947, +0.0471, +0.9269, +0.8989, -0.2302, -1.3604, -0.2539, +0.5975, -0.2451, +0.3136, -0.6545, -0.5904, +0.6794, -0.7342, -0.2178, -1.0867, +0.3340, -1.2048, -0.2076, -0.0349, +0.1764, -0.1004, -0.1311, -0.2428, +0.4325, +0.1302, +0.0019, -0.0881, +0.3566, +0.0503, -0.0759, +0.0366, -1.0691, +0.1273, -0.2615, -0.0779, +0.6359, -0.6128, -0.4660, -0.3794, +0.1681, -0.3744, +0.0897, +0.3767, +0.3950, +0.6027, +0.6578, -0.2572, -0.3049, -0.5333, -0.4376, -1.8317, -0.9671, -0.4943, -0.3099, +0.2941, +0.1555, +0.3129, -0.3870, -1.6067, +0.1901, +0.3682, -0.2147, -0.4661, +0.3253, +0.0028, -0.9932, -0.7515, +0.3019, -0.3932, -0.1185, -0.1441, +0.5607, -1.2272, -0.1169, +0.1525, -0.4974, +0.4858, -0.1839, -0.3725, -0.1979, +0.2342, -0.0696, -0.0034, +0.1385, +0.9345, +0.6038, -0.5267, +0.1343, +0.2124, +0.3444, +0.0326, +0.3010, +0.1535, +0.8926], +[ -0.6132, -0.0626, +0.1836, -0.0017, +0.3117, -1.2901, +0.2260, -0.3219, +0.0400, -0.2747, +0.2144, -0.3827, +0.3195, +0.2954, -0.3256, -0.3032, +0.6317, +0.4147, -0.2002, -0.1467, -0.9987, -0.5831, -0.6824, +0.0135, +0.0619, +0.0365, -1.1740, -0.5402, +0.1055, -0.4065, +0.2682, -0.7483, -0.0056, -1.5943, -0.6814, -0.1541, -0.1458, -2.2840, +0.6172, -0.5811, -0.0055, -0.6315, +0.3828, -0.2704, +0.5921, -0.1200, -0.1509, -0.2821, +0.1405, -1.3506, -0.2311, +0.0215, -0.0361, +0.0953, +0.3615, +0.3187, -0.3967, -0.0055, -0.1907, -0.0275, +0.0199, -0.5271, +0.0952, -0.2753, -0.1653, +0.1166, +0.0769, -0.1883, -0.6950, +0.1223, +0.5596, +0.1561, -0.3390, +0.2991, -2.3407, +0.0940, -1.1829, +0.1751, +0.0089, +0.2114, -0.1418, -0.0711, -0.0123, -0.9252, +0.5315, -0.5255, -0.1498, +0.6514, +0.0192, -0.7630, -0.2391, -0.5887, -0.2899, -0.3057, +0.4777, -0.0072, -1.2469, -0.3501, +0.1416, -0.3820, -0.0205, -0.5110, +0.0706, -1.0889, -0.3870, +0.1781, -1.2873, +0.1878, -0.0433, -0.7868, -0.4801, -0.0985, -0.4878, +0.0957, +0.1303, +0.2984, +0.1435, +0.4211, +0.5997, -0.5081, -0.3256, -0.4320, -0.9251, -0.4870, -0.7026, +0.0313, +0.1807, +0.3195], +[ -0.4618, -0.1217, -1.4947, +0.6432, -0.0286, -0.0113, -0.1610, +0.3059, +0.1557, -0.3754, -0.2707, +0.1685, +0.0389, -0.3181, +0.5652, -0.1861, -0.1956, +0.4189, +0.1113, +0.1597, -0.0383, +0.3372, +0.2067, +0.0350, +0.3312, -0.2489, -0.4308, -0.4614, -0.4210, +0.1451, -0.1855, -0.4838, +0.4251, +0.2819, +0.0486, +0.2659, -0.0646, +0.3865, +0.2074, +0.0339, +0.4180, -0.0953, +0.0472, +0.0316, -0.2890, +0.4763, +0.5133, +0.2853, -0.4433, +0.2192, +0.3042, -0.1120, +0.0379, -0.6806, +0.0723, +0.0475, +0.0077, -0.0484, -0.5169, +0.3545, -0.2064, +0.0259, +0.2864, +0.0194, +0.1699, -0.0441, -0.1463, +0.1760, +0.3086, -0.4820, -0.2502, -0.4887, +0.0559, +0.4278, +0.1996, +0.1614, +0.2339, +0.0800, -0.6270, -0.2786, -0.4181, -0.1674, -0.2827, -0.4783, +0.1192, -0.0594, -0.6800, -0.0548, -0.1755, -0.1158, +0.3345, +0.2706, -0.3446, +0.0566, -0.6105, +0.1354, -0.3801, -0.0385, -0.2697, -0.0631, -0.1239, -0.1411, +0.0484, -0.6900, -0.2176, -0.1499, +0.0073, -0.3549, -0.4897, -0.0909, -0.0063, +0.1598, +0.2158, -0.9459, -0.2283, +0.3218, +0.1076, +0.0235, +0.4750, -0.1916, -0.0259, -0.3111, +0.1156, +0.0414, +0.0901, -0.2362, +0.2898, +0.3987], +[ +0.1194, +0.2215, -0.7395, -0.6066, -0.2603, -0.6324, +0.0280, -0.0233, +0.2191, -0.0356, +0.1409, -0.0238, -0.3462, +0.5912, +0.0531, -0.2901, +0.0148, +0.2699, -0.1726, -0.1041, +0.1550, +0.3988, -0.1391, +0.0865, -0.1727, -0.0615, -0.3390, -0.2071, +0.5588, -0.1679, -0.6875, +0.1969, -0.0317, +0.0969, +0.4025, +0.2154, -1.1675, +0.3348, +0.3878, -0.1976, +0.4689, +0.1378, +0.2840, +0.3174, +0.3507, +0.0292, +0.4537, +0.1683, +0.3744, +0.0121, -0.0917, +0.0866, +0.3034, -0.5841, +0.2858, -0.6695, -0.4560, +0.6588, +0.4572, +0.0193, +0.3867, -0.6039, -0.0019, +0.2913, +0.0934, +0.4742, +0.0944, -0.3412, +0.3524, +0.0335, -0.6695, +0.7083, +0.5825, -0.1013, -0.0832, +0.6263, +0.5189, -0.3299, -0.0619, +0.2237, +0.0813, -0.0122, +0.2237, +0.9135, +0.3399, +0.1430, -0.0912, -0.0395, +0.3444, -0.6128, -0.0136, +0.0827, +0.2395, -0.5342, +0.0654, +0.0967, -0.1721, -0.1917, +0.1808, -0.1465, -0.1908, +0.2995, -0.1450, +0.3075, +0.5168, +0.7156, -0.0292, -0.2514, -0.1955, -0.4305, +0.2834, -1.6873, +0.3317, -0.2397, -0.5233, -0.1526, -0.2658, +0.1916, -0.0949, +0.2834, -0.1353, +0.2761, +0.3861, -0.1116, -0.7916, -0.0785, +0.1260, -0.0051], +[ -0.4166, -0.6567, +0.2667, +0.1786, +0.3510, -0.0422, +0.7925, -0.0154, -0.1518, -0.0187, +0.0379, -0.1076, +0.3849, -0.2907, +0.0690, +0.3741, +0.5237, +0.2914, -0.4741, +0.5339, +0.2658, +0.3419, +0.6672, -0.0275, +0.1312, +0.2843, +0.5785, -0.5382, -0.9244, +0.3275, +0.1660, +0.0649, -0.0301, -0.7872, +0.3756, +0.3165, -1.1756, -0.3764, +0.3109, -0.2525, -0.1304, +0.1871, -0.3203, +0.7052, -0.1682, -0.2009, +0.1683, +0.3273, +1.6270, +0.2042, +0.1354, -0.2825, +0.1715, -1.6118, +0.1005, -0.0738, -0.1032, +0.3228, +0.2159, -0.3190, -0.5356, +0.3108, +0.0485, +0.4706, +0.3739, -1.1787, +0.3236, -0.6023, +0.1504, +0.1740, +0.2444, -0.3717, -1.2288, -0.2562, -0.0348, -0.0171, -0.5948, -0.9390, +0.0392, -0.7069, -0.2203, +0.3624, -0.2812, -0.2286, -0.0412, +0.0528, -0.3069, -0.0803, -1.6197, +0.8269, +0.1908, +0.8159, +0.3059, +0.1064, -0.5850, +0.4684, +0.2937, -0.0045, -0.1077, -0.7226, -0.0540, -1.5225, -0.2574, +0.8567, +0.1914, +0.6329, -0.5773, +0.0707, -0.4777, +0.0377, -0.0070, -0.1626, -0.5968, -0.2404, -1.2759, -0.2537, +0.1132, -0.1214, -0.9898, -0.2443, -0.6741, -0.6288, +0.1556, -0.3358, +0.1861, -0.5565, +0.7699, -0.1238], +[ -0.9355, +0.9826, +0.1094, +0.6101, +0.5008, -0.0418, +0.3574, -0.4915, -1.0313, -0.2750, +0.4640, +0.1685, +0.1614, -0.5493, -0.0395, +0.0826, -0.4272, -0.2077, +0.7788, -0.4189, +0.0903, -0.4165, -0.1848, +0.0345, -0.3355, +0.0290, -0.2494, +0.2498, +0.2195, -0.3544, +0.3827, +0.5353, +0.3030, -0.3058, +0.1684, +0.0712, +0.1870, +0.0772, -0.6504, +0.1901, +0.1617, -0.0998, -0.1492, -0.5738, +0.2446, +0.0092, -0.5506, -0.2370, +0.1765, -0.1482, +0.5713, +0.0210, +0.0355, +0.1140, -0.7140, -0.0040, +0.4767, +0.2202, -0.3633, +0.1525, -0.1511, +0.5307, +0.5185, +0.3934, -0.1424, +0.4631, -0.3201, -1.2858, -0.0077, -0.1245, -0.0614, -0.4914, -0.4229, +0.3751, +0.0951, -0.4626, +0.0338, +0.0951, -0.1898, -0.0954, -0.0744, -0.5868, +0.3834, -0.8412, +0.3414, -0.4893, +0.2224, -0.6829, -0.2101, -0.4551, +0.6793, +0.1760, -0.4434, +0.3216, +0.1542, +0.0045, +0.4077, -0.4215, -0.2623, +0.0514, +0.0329, -0.1839, -0.4462, -0.2559, -0.1739, -0.0286, +0.0429, -0.7608, -0.4764, -0.1833, +0.2059, -0.9402, -0.3059, -0.0848, -0.3453, -0.3135, +0.1000, -0.0187, +0.7457, -0.8470, +0.1928, +0.4921, -0.1373, +0.4402, +0.4008, -0.3943, -0.1944, +0.1398], +[ +0.1872, +0.9816, +0.0851, +0.1390, -0.8130, -0.1898, -0.3910, +0.3106, -0.2167, +0.6273, +0.5541, -0.0014, +0.2877, -0.1589, -0.2232, -0.1208, -0.2884, -0.9505, +0.4753, -1.7450, -0.3683, -0.7012, +0.1969, -0.5218, -0.1690, +0.4793, -0.4462, +0.0265, -0.2971, -0.0282, +0.3979, -0.7204, +0.0335, -0.6340, -0.4683, +0.4272, -0.7263, -0.4165, +0.1131, -0.1232, -0.0161, -0.5044, -0.3839, +0.0541, +0.5817, -0.2580, -1.3879, -0.1213, +0.3584, +0.0509, -1.0074, -0.0474, -0.3855, +0.2602, -0.3497, -0.5726, +0.5644, -0.1663, +0.3701, -0.5592, -1.5091, -0.3567, +0.4544, +0.6069, -0.8949, +0.6127, -0.7491, +0.7633, -0.4563, -0.8731, -0.4802, +0.1802, -0.8905, +0.1056, -0.2027, +0.1881, -0.3565, -0.2124, -0.3840, +0.0482, +0.3754, -0.6157, -0.1367, -0.1701, -0.2833, -0.5350, -0.4995, +0.2334, -0.7944, -0.9158, +0.0448, -2.6868, -0.0335, -0.0847, +0.4522, -0.4106, +0.1345, -0.5642, -0.8447, +0.4460, +0.4215, -0.1796, -0.0094, -0.6337, +0.4704, -0.6282, -0.1135, +0.8338, +0.2184, -0.1924, -0.0502, -0.1903, +0.2182, -0.1559, -0.5885, -0.4098, -0.0150, -0.6609, +0.5288, -0.6010, -1.1834, +0.5740, -0.5148, +0.7980, +0.5594, -0.0867, -1.3654, +0.6106], +[ -0.4394, +0.2310, -0.3018, -0.3480, -0.9776, -0.2720, +0.1813, +0.3134, +0.1339, -0.0724, -0.8018, +0.1788, -1.0079, -1.1364, -0.8186, -0.1026, +0.2480, +0.0618, -0.0769, -0.2584, +0.4019, -0.3211, -0.1836, -0.1351, -0.4099, -0.2835, -0.5408, -0.7063, -0.2228, +0.0479, +0.2686, -0.3299, -0.7873, +0.0996, -2.0968, +0.4859, +0.1783, -0.5059, -0.5944, +0.1206, +0.1465, -0.1475, -1.4468, -1.1564, -1.9459, -0.0934, +0.5490, -0.1651, +0.3982, -0.2141, -0.4545, -0.1564, -0.1334, +0.2570, +0.0896, -0.1352, -0.5934, +0.3121, -0.6738, +0.0189, -0.1665, -0.8223, -0.0091, -0.4308, +0.3138, -0.5113, -0.0708, -0.2009, -0.6023, -0.4238, -0.1099, +0.3639, -0.0279, +0.1326, -0.1242, +0.0337, +0.2367, +0.0850, -0.0917, -1.2237, -0.6782, +0.5698, +0.1095, -0.1615, -0.8337, +0.2228, -0.5700, +0.0232, -0.0210, -0.3978, +0.4321, -0.0272, -0.1537, -1.2350, -0.5124, -0.3720, -0.2994, +0.2628, +0.4213, -0.7631, -0.2937, -0.0566, -0.3422, +0.2419, +0.0051, -0.4876, +0.2640, +0.0167, -0.4600, +0.4592, -1.0462, -0.2274, +0.0501, -1.3160, -0.6923, +0.2786, -0.3156, -0.4447, -0.3842, +0.7620, -0.6217, +0.1690, -1.3204, -0.2791, -0.5546, -0.0060, -0.0596, -0.1868], +[ -0.5495, +0.3365, -0.7584, -0.2572, -0.2659, +0.4092, +0.1424, -0.2120, +0.3421, +0.0521, -1.4783, -0.1153, +0.3200, +0.9175, +0.5001, -0.2805, +0.2878, +0.3383, +0.0098, -0.7964, -0.0732, +0.0894, +0.4826, +0.5428, +0.0961, +0.0482, -0.4127, -0.4349, +0.1313, +0.5661, -0.5111, +0.3665, -0.3487, -0.2787, -0.8896, +0.0938, -0.5667, +0.1014, -0.1201, -1.3133, -0.5152, +0.1094, -0.2116, -0.3066, +0.3762, +0.7020, +0.9420, +0.5691, +0.0542, -0.7900, -0.6320, -0.1268, +0.0348, +0.6443, -0.3499, -0.1280, +0.4221, +0.0023, -0.8830, -0.9870, +0.5297, -0.0939, +0.4132, -0.0311, +0.5731, -0.2274, -0.6287, -1.1691, -0.2294, +0.4159, +0.2609, -0.1928, +0.1094, +0.1801, -0.0305, +0.1778, -1.4363, -0.5287, -0.2018, +0.7580, -0.4102, +0.2158, -0.0664, +0.1027, -0.0060, +0.5857, +0.1354, -0.0279, +0.2287, -0.3410, +0.1904, -1.1251, +0.3415, -0.2569, -0.6138, -1.1146, +0.0824, +0.1870, -0.6945, -0.7618, +0.3157, +0.3979, +0.1496, +0.2627, +0.0947, -1.2781, +0.0487, +0.3630, -0.2052, -0.7007, -0.0074, +0.3732, +0.4000, +0.0503, -0.3131, +0.4917, -0.3112, -0.2290, -0.1998, +0.1941, -0.7223, +0.2580, -0.3792, -0.1586, -0.4023, -0.6316, +0.0302, +0.3170], +[ -0.2819, -0.1824, +0.5367, -0.5343, -0.6550, +0.3470, +0.3113, +0.3216, +0.0234, +0.2092, +0.5161, +0.4814, -0.6742, +0.1774, -0.4262, -0.1184, -0.3862, +0.3776, -0.0454, +0.3588, +0.2280, +0.0591, -0.5632, -0.1272, -0.5212, -0.1646, -1.0133, -0.6814, +0.3322, +0.2075, +0.6023, -0.6443, -0.5341, -0.2680, -0.0889, -0.2357, -0.3847, -0.0124, -0.1986, +0.2168, +0.2596, -1.5922, +0.0155, -0.4838, -1.1318, +0.0587, -1.1597, -0.3127, +0.0851, -0.0218, -0.1821, +0.1180, +0.0146, -0.6130, -0.2081, -0.2196, -0.7754, -0.0791, +0.4528, +0.0908, +0.3110, +0.2869, +0.4468, +0.1967, +0.2325, -0.2844, +0.1799, +0.1444, +0.5616, -0.7208, +0.4001, +0.3364, +0.3572, +0.3306, -0.1394, +0.0448, +0.0176, -0.1806, +0.0376, -0.5749, -1.4323, -0.1710, -0.1247, -1.1199, -0.0686, +0.3875, +0.0285, -0.1925, -0.6119, -0.3564, -0.2852, +0.5464, -0.8385, -0.3253, -0.8248, -0.3679, -0.2737, +0.4797, -0.5317, -0.0144, +0.1526, -0.1459, -0.3113, -0.1446, -0.0265, -0.8188, +0.3409, +0.4165, -1.6213, +0.3362, -0.1435, +0.0679, -0.3296, -1.2932, -0.1976, +0.0025, -0.3460, -0.2282, +0.0328, +0.0128, -0.6903, -0.2594, +0.1898, -0.3305, +0.0718, -0.1354, +0.3221, -0.2091], +[ +0.7015, -0.0079, +0.0603, -0.1224, -0.0905, -0.0360, +0.1416, +0.0313, -1.2110, -0.2915, -0.9822, +0.1289, -0.5388, -0.5899, -0.3639, +0.1049, +0.2668, -0.6067, -0.0946, +0.2901, -0.6062, +0.1575, -0.3185, +0.1406, -0.0531, +0.0853, +0.1109, +0.2724, -0.9222, +0.0355, +0.4736, -0.4827, -0.7927, +0.0591, -0.3695, -0.8606, -0.3656, -0.4858, +0.0656, -0.1895, -0.5924, -0.1785, -0.0872, +0.0163, -0.3657, -0.1144, -0.7264, -0.0708, +0.3746, -0.4169, +0.0849, +0.2061, +0.5279, +0.4709, -0.0896, -0.5886, -0.1939, +0.1890, -0.1501, +0.2609, +0.2305, -0.2359, -0.4166, -1.3491, +0.2312, +0.0627, -0.3370, -0.2057, -0.2985, +0.2800, -0.0274, -0.4590, +0.2526, -0.3559, +0.1709, +0.2335, +0.3815, -0.6601, +0.2350, -0.5104, -0.1831, +0.2343, +0.1400, -0.5159, -0.0107, -1.0395, -0.1054, -0.5677, +0.1986, -0.5501, -0.7590, +0.2544, +0.2979, -0.2088, +0.0723, +0.2322, +0.3433, -0.5151, -0.1836, -0.2278, -0.3615, -0.0833, -0.4835, +0.5434, -0.1283, +0.0631, -0.3564, +0.1727, +0.0701, -0.1985, +0.4197, +0.8758, +0.1505, -0.7602, -0.1722, -0.3172, -0.1665, -0.0129, +0.1756, +0.1746, -0.6835, -0.2638, -0.3309, -0.2754, +0.2760, -0.3245, -0.4501, +0.1531], +[ -0.5910, +0.4678, -0.8342, +0.0698, -0.3237, -0.1614, +0.3568, +0.3391, -0.1352, -0.9422, +0.1731, +0.0649, +0.0359, +0.0780, -0.0588, +0.1787, -0.2640, +0.1125, +0.1091, -0.9467, -0.1841, -0.5780, +0.2515, -0.2598, +0.0299, +0.3900, -1.1704, -0.2194, -0.5359, -0.0265, -0.0861, +0.4115, -1.0049, -0.0218, -0.2298, +0.0651, +0.3290, +0.3422, -0.1790, -0.2639, +0.2790, -0.0778, -0.0189, +0.5084, -0.5000, +0.1139, +0.3918, -0.6133, +0.0850, -0.5195, +0.6430, +0.2377, +0.4246, -0.1079, +0.0031, -0.4855, +0.1163, +0.1400, -0.8990, +0.0836, -0.1079, -0.1238, -0.8169, -0.7508, +0.2860, -0.1766, -0.4766, -1.9178, -0.0434, -0.1472, -0.1214, -0.4738, -0.4151, +0.1791, +0.4102, -0.3687, -0.4524, +0.2226, -0.1458, +0.1435, -0.0020, +0.4678, +0.4075, -1.0137, -0.3772, +0.0394, -0.2466, -0.7199, -0.0438, -1.0581, +0.2332, -0.7536, -0.1882, -0.8108, -0.2119, -0.3047, -0.4887, +0.2553, -0.2199, -0.7156, +0.1906, -0.0012, +0.0211, +0.1094, -0.2721, -0.4634, -0.2296, -0.5068, +0.1374, +0.2166, +0.4215, -0.1778, -0.0065, +0.6533, +0.0195, -0.2174, -0.8611, -0.0556, +0.3126, -0.1544, -1.2263, +0.0302, -0.9812, +0.2193, +0.1708, -0.1093, -0.2972, +0.1680], +[ +0.3990, +0.0859, -0.1240, -0.8370, -0.4172, +0.2365, -0.0056, +0.0501, -0.1428, -0.0168, +0.0601, -0.2195, -0.3317, -0.2262, +0.1396, +0.1408, -0.3450, -0.3909, -0.2250, -0.5431, -0.9326, -0.5343, -0.3074, -0.1953, -0.1808, +0.2521, -0.0151, +0.0151, +0.3445, -0.0578, -0.2371, -0.1088, -0.0111, +0.0672, -0.1129, -0.4050, -0.0916, +0.1445, -0.0713, -0.2679, +0.1176, -0.4107, -0.1053, -0.2070, +0.7283, +0.0182, +0.0785, -0.3302, +0.4245, +0.6522, -0.5767, -0.0863, -1.0398, -0.1261, +0.2347, -0.5232, +0.2685, -0.1588, -0.4723, -0.3260, -0.4737, -0.7348, -0.4172, +0.4803, -0.4773, -0.4487, +0.7380, -0.6768, -1.1271, -0.3248, +0.2887, -0.0650, +0.8312, +0.4609, +0.2830, +0.0250, -0.1387, -0.1422, +0.2407, -0.1626, -0.4312, -1.1603, +0.4189, +0.0939, -0.3531, -0.2178, +0.2811, +0.1014, +0.3626, -0.0389, +0.3537, -0.0242, +0.9483, +0.3594, -0.0648, -0.3060, +0.1765, -0.7881, -0.1364, -0.4580, -0.0794, -0.2943, -0.5105, -0.1794, +0.1520, -0.1179, -0.9498, +0.0333, +0.1983, -1.0507, +0.3775, +0.1208, +0.1412, +0.2968, +0.2580, -0.1786, +0.3944, +0.0681, -0.8295, +0.5816, -0.1301, -0.0029, -0.4506, +0.2168, -0.1471, +0.3748, -0.1863, -0.0625], +[ +0.1393, -0.3440, -0.1916, -0.6145, -1.0682, -0.0085, +0.0467, -0.0013, -0.0962, -0.3870, -0.0871, -0.3778, +0.2254, +0.1940, +0.1934, -0.7901, -0.4800, +0.2300, -0.6122, -0.5443, -0.2042, +0.0812, +0.2239, +0.1593, +0.1071, -0.7654, +0.3019, -0.0838, +0.4722, -0.2109, +0.2228, -0.2398, +0.1788, -0.0798, -0.3246, +0.0000, -0.7649, +0.0329, +0.3764, -0.2840, -0.1474, -0.0116, +0.3365, +0.5115, +0.5601, -0.7000, -0.2180, -0.0863, +0.2020, -0.1458, -0.9690, -0.2748, -0.3088, -0.0826, +0.2325, +0.2183, -0.1520, -0.1366, -0.3107, +0.2733, +0.4968, -0.0895, -0.1239, +0.2910, -0.2267, -0.1839, -0.0321, -0.4823, +0.3016, +0.3723, +0.3944, +0.1201, +0.3839, -0.0409, -0.2140, -0.0261, -0.2642, +0.3141, +0.6421, +0.6582, +0.2082, -0.6195, +0.2912, +0.0357, -0.5369, +0.0784, -0.1916, -0.1177, -0.1315, -0.3553, -0.0516, +0.8580, -0.0791, -0.8106, -0.1678, -0.1375, -0.2407, -0.3142, -0.1501, -1.1768, -0.0442, -0.2097, -0.7157, -0.3549, +0.0532, -0.2223, -0.4742, +0.0961, -0.3822, -0.7533, +0.0197, -0.3242, -0.7685, -0.4098, +0.4850, +0.1301, -0.5146, -0.2493, +0.0855, +0.0385, +0.4716, +0.4514, +0.1462, -0.0489, -0.5990, +0.2224, -0.3817, -0.0842], +[ -0.3052, -0.1947, -0.2996, -0.0040, -0.1721, +0.2344, -0.3913, +0.1915, -0.0813, +0.1120, +0.4848, +0.7501, -0.1336, +0.1784, +0.2548, +0.0553, -0.2648, +0.5434, +0.1071, -0.7360, +0.4868, -1.9705, +0.3370, -0.4066, -0.1121, +0.2190, -0.2057, -0.1045, -0.3884, -0.1164, -0.3860, +0.3627, +0.0852, -0.0559, -0.0288, +0.4844, -1.2247, -0.6384, -0.3676, -0.2889, +0.1286, -0.1623, -0.4514, -0.9095, +0.3574, -0.8860, -0.1597, -0.0322, +0.3061, -0.0241, -0.3640, +0.1712, +0.4706, -0.4074, -0.0463, +0.4842, -0.2766, -0.1878, +0.2203, -0.0552, -0.5473, +0.3471, -0.4691, -0.0022, +0.0363, +0.6001, +0.3843, +0.1338, +0.5381, +0.2268, -0.3754, +0.2853, +0.1396, -0.2906, -0.5988, +0.6063, +0.3165, +0.3628, +0.5851, -0.8569, -0.1414, -0.2864, -0.3541, +0.5733, +0.1381, -0.7078, +0.4508, +0.0572, -0.6422, -0.2782, +0.4011, +0.8227, +0.1561, -0.3120, -0.1448, -0.3317, +0.3289, -0.2140, +0.0195, +0.6493, +0.0570, -0.4285, -0.4959, +0.4498, -0.2399, -0.8054, -0.9527, +0.1554, -0.2333, -0.7512, -0.3255, +0.0679, +1.1837, +0.4886, +0.0729, -0.6745, -0.2946, +0.4916, +0.0207, +0.3546, -0.4189, -0.4255, -0.6069, -0.6768, +0.1386, -0.6672, -0.6658, -0.8829], +[ +0.0797, -0.5054, +0.0136, +0.1980, -0.1277, +0.0739, +0.2982, +0.1720, +0.2600, -0.4211, -0.2309, -0.4136, +0.0334, +0.0354, +0.5589, -0.1356, -0.1200, -1.5159, -0.3698, +0.4210, -0.7663, -0.3039, -0.2075, +0.0265, +0.2961, -0.3017, +0.5159, -0.1434, +0.2200, +0.1586, +0.2846, -0.0269, -0.0215, +0.3860, +0.2604, -0.5857, +0.2478, -0.0333, -0.4322, -0.7724, -1.0079, +0.0702, +0.0804, -0.2026, +0.2561, +0.1934, +0.0800, +0.6753, -0.5215, +0.0715, -0.1621, +0.0212, -0.6631, -0.3874, -0.5760, -0.0029, -0.0078, +0.1267, +0.2254, -0.3903, +0.0217, +0.6639, -0.0116, -0.3764, -0.1426, -0.6670, +0.1575, +0.1441, +0.3506, -0.3192, +0.4579, +0.2575, -0.3044, +0.1800, -0.7823, -0.2821, +0.0089, +0.1812, +0.2162, +0.2755, -0.0168, -0.0375, -0.0799, +0.4972, -0.0946, -0.4242, -0.5448, -0.4950, -1.1926, +0.1192, -0.1251, -0.3178, -0.2847, -0.2470, -0.1367, -0.4373, -0.4606, -0.2024, +0.0416, -0.6683, +0.3778, -0.5890, +0.0598, +0.6347, -0.4389, -0.1130, +0.8578, -0.4276, +0.4702, +0.2074, +0.2512, -0.1159, -0.3021, +0.4248, -0.4255, -0.1036, +0.5195, -0.3745, -0.2933, +0.5167, -0.6131, +0.5847, +0.2629, -0.5066, -0.0528, -0.5667, +0.5172, +0.4329], +[ -0.0319, -0.0812, +0.1893, -0.0076, +0.0408, +0.9861, +0.1532, +0.5791, +0.4635, -0.5317, +0.0360, +0.1377, +0.4940, -0.3670, +0.0597, -0.2673, +0.4268, +0.5371, +0.9459, +0.6026, +0.3581, +0.5822, -0.3556, -0.2087, +0.2368, -0.6264, -0.6553, -0.3130, -0.0068, +0.0108, +0.6198, -0.1246, +0.4941, +0.0035, +1.1518, -0.0484, -0.3501, -0.1881, -0.5316, +0.6341, -0.0666, -0.3592, -0.8007, +0.0054, +0.4806, +0.3872, -0.1414, -0.1555, +0.1436, -0.9244, -0.3463, +0.3656, +0.4359, +0.3659, +0.1684, -0.0401, -0.2197, -0.1504, +0.4222, +0.1781, -0.1574, +0.2468, +0.2445, -1.2630, -0.2287, +0.2540, -0.0357, -0.4610, -0.3447, +0.0243, +0.4182, -0.1686, -0.1656, +0.0064, -0.1063, +0.0522, -0.2769, +0.4825, +0.0400, -1.8240, -1.3218, -0.3842, -0.2491, +1.1058, +0.3958, +0.0994, +0.0235, +0.4443, -0.3370, +0.4494, -0.2813, +0.1513, -0.7493, -0.1674, -0.8722, +0.6108, -0.2310, -0.4216, -0.6610, +0.0855, -0.3479, -0.1705, -0.0974, +0.0694, -0.2493, -0.0780, -0.7308, -0.0663, +0.5153, -0.0797, +0.1073, -0.5629, +0.0242, +0.1148, -0.2580, +0.0235, -0.1664, -0.4889, +0.1834, -0.4821, -0.4944, -0.3256, +0.0020, -1.0169, -0.7666, +0.0411, -0.4586, +0.1203], +[ -0.5432, -0.8020, +0.0918, -0.1605, -0.3804, -0.2535, -0.4118, +0.3286, -0.6496, +0.3496, -0.0343, -0.3351, +0.1318, +0.3702, +0.4219, -0.1902, +0.3082, +0.0794, -0.8055, -0.1940, -0.7841, +0.2015, +0.4231, -0.2529, -0.1225, +0.0647, +0.1334, -0.0605, -0.0080, +0.4599, -0.0993, +0.2709, -0.5362, +0.2351, -0.0537, -0.3275, -0.9580, +0.1666, +0.0469, -0.1855, +0.3882, +0.2301, -0.0206, +0.1937, -0.3547, -0.0842, +0.0262, -0.1558, -0.2253, -0.4692, -0.0289, -0.1977, -0.3126, +0.1086, -0.3525, +0.0515, -0.7167, -0.1288, +0.0262, -0.0331, +0.1438, -0.2140, -0.2829, +0.0953, +0.0114, -0.5833, +0.0937, +0.3545, -0.0935, -0.2859, +0.0646, +0.2267, -0.3251, +0.3041, +0.0245, -0.0780, -0.4906, -0.8082, -0.0172, +0.0940, +0.1477, +0.1898, -0.0042, +0.2624, +0.2332, +0.2750, -0.2046, +0.0405, +0.2157, +0.2673, -0.8699, +0.0976, +0.0859, -0.1087, -1.5906, -0.7188, +0.1202, -0.0439, +0.1963, +0.1605, +0.0621, +0.0184, -0.0679, -0.6141, +0.3824, -0.0532, -0.1961, +0.0858, +0.1383, -0.7507, -0.2177, +0.4552, -0.1719, +0.1524, +0.0328, +0.2659, +0.1018, +0.1842, +0.0123, -0.5312, -0.0575, -1.0402, +0.2488, -0.0787, +0.2566, +0.2899, -0.3392, -0.1630], +[ -0.1194, +0.3467, -0.2206, +0.1329, +0.0768, +0.6891, +0.0714, -0.4637, -0.5310, -0.0903, +0.4664, +0.3078, -1.2855, +0.1329, +0.0155, +0.0817, -0.3605, -0.8722, +0.0441, +0.5491, -0.1563, -0.8174, +0.3046, +0.1270, +0.3098, -0.0151, -0.0045, -0.9193, -0.1783, +0.1567, +0.5533, +0.0915, -0.6435, -0.3851, -0.4275, -0.2248, +0.7145, +0.0099, -0.0457, -0.4532, +0.1251, -0.3843, -0.1030, -0.0806, -0.5033, +0.2596, +0.3066, -0.5329, -0.4325, +0.1346, +0.1403, -0.5028, -0.0000, +0.0686, -0.3853, +0.1682, -0.1527, -0.0705, +0.4857, +0.3771, +0.0472, +0.2039, -0.1899, +0.3069, -0.3187, +0.3162, +0.2182, -0.2863, -0.5433, -0.6458, +0.3378, +0.3192, +0.1345, +0.0484, -0.0181, -0.1583, -0.9560, -0.3627, -0.3025, -0.2251, -0.4278, -0.3376, +0.0789, -1.0522, +0.0469, -0.6978, +0.1622, -1.1855, +0.1655, +0.0138, -0.8016, -0.1230, +0.5485, +0.3558, +0.3172, +0.0599, +0.1526, -0.1669, -1.0670, -0.3345, -0.3429, -0.8567, +0.5445, +0.5922, +0.2734, -0.0315, -0.6848, -0.3854, -0.1927, -1.1359, -0.4998, +0.1007, -0.3175, -0.5658, +0.4406, -0.0551, +0.4072, +0.1219, -0.5193, -0.2507, -0.8700, +0.2308, +0.4804, -0.7289, +0.1062, +0.4289, +0.4740, +0.5733], +[ +0.4704, +0.0984, +0.5533, -0.1550, -0.7135, +0.3362, -0.1627, +0.3920, -0.3064, -0.9689, -0.5753, -0.5526, -0.0743, +0.3165, -1.3096, -0.0676, -0.1110, -0.0326, -0.7468, -0.0229, -0.2737, -0.0090, -0.3595, -0.5636, -0.0341, -0.4081, +0.2472, -0.3242, -0.1158, -0.6365, +0.1962, +0.2294, +0.1400, +0.5869, +0.1713, +0.0023, +0.0232, -1.2354, +0.1584, -0.1950, -0.2557, -0.0327, +0.1266, +0.2868, +0.2143, -0.1170, +0.3738, +0.2260, +0.1861, +0.1461, -0.4707, +0.3385, -0.5547, -0.5667, +0.1489, +0.1197, +0.1865, +0.1954, +0.3249, -0.0711, +0.1393, -0.1540, +0.1666, -0.0516, +0.4031, +0.3465, +0.0516, +0.3941, -0.7685, -0.3348, -0.2972, +0.2939, +0.3497, -0.6229, +0.0615, -0.2449, +0.3241, -0.0620, +0.1183, +0.2582, +0.0633, -0.3186, -0.0816, +0.0410, -0.4114, -0.0251, -0.1757, +0.2182, +0.0251, +0.7628, -0.0240, -0.0525, +0.4578, +0.0557, +0.2615, +0.2159, +0.2395, +0.1016, +0.0726, -0.4254, -0.0181, -0.6271, -0.6427, +0.0284, +0.4687, +0.2167, -0.8132, +0.3172, +0.4417, -0.1187, -0.5183, -0.1523, -0.1811, -0.8048, +0.4459, +0.4368, +0.4110, -0.3081, -0.3863, +0.3325, +0.0145, +0.0293, -0.0961, -0.6588, -0.6577, -0.3175, +0.0458, +0.1852], +[ -0.3244, +0.3453, +0.4659, +0.1278, +0.0263, +0.3692, -0.1322, +0.5408, +0.0223, -0.4064, -0.0329, +0.0427, +0.0518, +0.1526, -0.6745, -0.6814, -0.2794, +0.0076, +0.4716, +0.0989, +0.2801, +0.4726, +0.8755, -0.0468, -0.1572, +0.0386, -0.0018, +0.0436, -0.7961, +0.5156, -0.0432, +0.3131, +0.1239, +0.4978, +0.0452, -0.0287, -0.5577, +0.0747, +0.1409, +0.2401, +0.2333, +0.2038, +0.0243, -1.4126, -0.0031, -0.5302, +0.1366, +0.4580, -0.9463, +0.2064, -0.1316, -0.4320, -0.2185, +0.0589, +0.0850, -0.0792, +0.1943, -0.2924, -0.1323, -0.2118, -0.4611, +0.4587, +0.0022, +0.1149, -0.3412, +0.5380, +0.1929, +0.1675, -0.0647, -0.0765, -0.4030, -0.8584, -0.1539, -0.0367, -0.5127, +0.1979, +0.0682, -0.4566, -0.0323, -0.1059, -0.0351, -0.2856, -0.0800, -1.1048, +0.1813, -1.0385, -0.2560, -0.5610, -0.8361, +0.7297, +0.3240, +0.2591, -0.0883, +0.3069, -0.7018, -0.4564, -0.0893, -0.0577, -0.3922, -0.2135, -0.0295, -0.2734, +0.2407, -0.5047, -0.1526, -0.2218, +0.1511, -0.4272, -0.0752, +0.0014, +0.1558, -0.0979, +0.2299, -0.4949, +0.0825, +0.2803, +0.2763, +0.3299, -1.4277, -0.1536, +0.6685, -0.6775, -0.4354, -0.0490, +0.1724, +0.4184, -0.9353, +0.0334], +[ -0.0237, +0.1151, +0.3952, +0.0888, +0.2637, +0.0448, +0.0319, -0.0838, +0.2934, +0.6864, -0.3903, +0.1003, -0.1447, -0.2490, -0.1426, +0.3537, +0.0199, -0.1132, -0.2192, -0.2704, +0.0392, +0.3247, -0.2443, +0.2803, -0.0727, +0.0282, -0.6015, +0.3304, -0.1920, +0.1517, -0.0807, -0.3249, +0.2810, -0.1769, +0.1114, -0.2788, +0.1025, +0.1887, +0.3154, -0.1968, +0.2691, -0.5229, +0.2975, +0.2208, -0.6344, +0.1650, -1.2574, -0.6373, -0.5196, +0.0786, -0.2593, +0.0290, -0.0111, -0.2176, -0.4665, +0.3046, +0.1656, +0.0257, -1.1199, -0.3922, -0.8051, +0.5381, +0.3533, -0.8867, +0.3014, +0.0465, -0.4772, +0.7044, +0.0911, +0.4027, -0.6977, +0.6835, -0.1308, +0.2430, +0.0300, +0.6958, -0.3284, +0.0979, -0.2630, +0.3343, -0.0862, +0.1222, -0.0311, +0.1402, -0.0087, -1.2493, +0.0120, +0.4401, -0.2778, -0.1811, -0.4879, -0.0948, +0.4839, -0.0848, -1.0303, -0.0772, -1.1900, -0.2582, -1.0577, -0.0152, -0.5970, +0.2376, +0.3681, -0.2117, -0.3704, -0.3580, -0.1064, +0.0134, +0.1705, +0.3112, -0.2077, +0.2380, +0.3597, -0.2131, -0.1586, -0.0093, -1.0376, -0.1940, -0.0034, -0.0930, +0.0630, -0.6793, -0.2775, -0.1766, -1.0874, -0.0242, +0.1328, -0.1924], +[ -1.1468, -0.5489, +0.6413, -0.2795, +0.2465, -0.4405, -0.4913, -0.5075, -0.4153, +0.3906, -0.6549, +0.2271, -0.6259, -0.2240, -0.4772, -0.1406, -0.4188, -0.8288, +0.0420, -0.2326, -0.0934, -0.2890, -0.4452, +0.0712, -0.1635, -0.1321, -0.1832, -1.8540, -0.1445, +0.5685, -0.3540, +0.3484, -0.2176, -0.5167, -0.3536, +0.1132, +0.3618, -0.0910, +0.4795, -0.9537, -0.3972, -0.5818, +0.0083, -0.0556, -0.4010, +0.0754, +0.1722, -0.7388, -0.2646, -0.2676, -0.2518, -0.1411, +0.1569, -0.6923, +0.6213, +0.4417, -0.4442, -0.3801, +0.1185, -0.2595, -0.2257, -0.6323, +0.5424, -0.6875, +0.0820, -0.0442, +0.0114, -0.5173, -0.7365, +0.3089, -0.4189, +0.1188, -0.8139, +0.4656, +0.3616, -0.2981, -0.8207, -0.1880, -0.1042, -1.0588, -1.5954, -0.1536, +0.0503, -0.9106, -0.9322, +0.2419, -0.1794, -0.0604, +0.0307, +0.0501, -0.4008, +0.1348, -0.6489, -0.5990, +0.1142, +0.6489, +0.0001, -0.0647, -0.2143, -0.3874, +0.1357, -0.5418, +0.5746, +0.1351, -0.0070, -0.6785, -0.3209, +0.5239, -0.1253, +0.1702, -0.5094, +0.0634, +0.2103, +0.7014, -0.2335, +0.3936, -0.2217, -0.0133, -1.0560, +0.5696, +0.2297, -0.1418, +0.0136, -0.3143, -0.5973, +0.6279, -0.3356, -0.9309], +[ -0.5827, -0.0787, +0.3842, +0.6057, -0.3744, -0.1667, +0.2557, +0.5199, +0.3724, -1.0853, -0.0962, +0.1177, +0.3746, -0.3622, -0.6888, -0.1403, -0.3840, -0.4151, +0.3217, +0.3957, -0.1144, +0.0298, -0.0959, +0.1055, -0.0409, +0.3927, -0.2206, +0.0536, -2.3865, -0.2262, +0.3847, -0.1112, -0.3791, +0.2793, -0.0349, -0.3009, +0.0038, -0.3509, +0.5816, +0.2646, -0.0839, -0.9176, -0.2282, -0.5341, -0.3662, -0.9341, -1.9107, -0.0757, -0.8490, -0.4928, +0.3568, -0.0798, +0.5515, -0.2662, +0.1106, +0.1013, +0.0582, +0.3810, +0.0315, -0.0477, +0.2104, -0.3271, -0.2738, -0.8973, +0.2263, -0.5105, +0.0182, -0.4493, +0.2752, +0.4808, +0.2276, -1.3286, -0.0032, -0.4071, +0.5225, -0.0665, +0.2638, -0.4450, +0.0857, +0.3098, +0.1059, +0.1158, +0.2210, -0.0440, -0.1754, -0.9768, -0.1933, -1.1677, -0.1349, +0.1467, -0.3771, +0.3430, +0.1020, +0.0143, -0.0550, -0.9697, -0.1434, -0.3386, -0.9714, -0.0249, +0.0532, +0.0235, -0.0579, +0.2284, +0.4151, -0.2941, -0.4709, -0.0016, -0.0338, +0.4262, +0.4149, +0.5157, +0.3371, -0.1495, +0.4588, -0.3911, -0.4941, +0.2330, -0.5315, +0.0509, -0.5540, +0.1312, -0.2170, +0.0867, +0.4329, -0.0276, +0.5138, +0.3968], +[ +0.1998, -0.6684, +0.2405, -0.2226, +0.0870, +0.1251, -0.4833, -0.4312, -1.0778, -0.4821, +0.4113, +0.0560, +0.6275, +0.0820, -0.0387, +0.0599, +0.4298, -0.1943, -0.1843, -0.0708, +0.0096, -0.7072, +0.3246, +0.6720, -0.7070, +0.2634, +0.2187, +0.3547, +0.0874, +0.0002, -0.6501, -0.6871, -0.2653, +0.0179, -0.0689, +0.0401, -0.2196, +0.1604, -0.3960, -0.1868, -0.1688, -0.0027, -0.1126, -0.2441, -0.4034, -0.1133, -0.3361, -0.3621, +0.3158, -0.7948, -0.0176, -0.1477, +0.3512, +0.3682, +0.4621, +0.0704, +0.3446, +0.0440, -0.4264, +0.3301, -0.3714, -0.5986, -0.6574, +0.4734, -0.0074, +0.2797, -0.4191, -0.2061, +0.5278, -0.2210, -0.0518, +0.5543, -0.0311, +0.2562, -0.1211, -0.4534, -0.9899, +0.4539, -0.1718, +0.2690, -0.7115, +0.1055, -0.0716, +0.1627, -0.1308, +0.1347, +0.7711, -0.6220, -0.7527, -0.5695, +0.0804, -0.7078, +0.0921, -0.3860, +0.4700, -0.1721, -1.0485, +0.0481, -0.0229, +0.0861, +0.4104, +0.2938, -0.5985, +0.6484, -0.0059, -0.4095, +0.2968, +0.1489, +0.0121, -0.7843, -0.5046, -0.3111, -0.1684, +0.0097, +0.5670, -0.0855, +0.3821, -0.0115, +0.2500, -0.1258, -0.5862, -0.0663, -0.2129, +0.2693, +0.2945, -0.2954, +0.2243, +0.0915], +[ +0.1491, -0.4850, +0.0809, -0.2971, +1.0399, +0.3669, -0.0123, -0.1522, +0.1059, +0.2378, +0.2477, -0.2592, +0.3836, -0.0857, -0.3333, -0.6129, +0.0457, -0.0590, -0.0397, +0.1242, -0.5554, +0.0273, -0.4591, +0.5780, -0.2889, +0.3091, +0.2659, +0.4226, +0.4354, +0.2692, +0.4760, +0.3523, +0.0599, -0.2643, +0.1443, -0.1300, +0.0442, +0.1209, +0.1833, -0.4734, +0.1125, -0.2706, -0.1989, +0.2754, +0.1445, +0.0215, -0.4975, -0.2346, -0.2444, -0.5111, -0.5242, -0.4954, +0.5329, +0.0265, +0.1177, +0.2493, -0.4953, +0.0555, +0.0568, +0.2252, -0.1676, -0.1292, +0.1785, +0.1137, -0.0854, +0.7888, -0.0573, +0.5062, -0.0035, +0.5743, +0.4510, +0.3742, -0.4986, +0.1980, -0.1241, -0.0968, -0.8677, -1.0860, -0.1191, +0.2507, +0.0636, +0.3880, -0.2442, -0.1665, +0.3182, -0.3076, -0.1607, +0.6608, -0.2604, +0.0612, -0.1349, -0.3337, -0.8032, -0.3801, +0.1673, -0.0237, -0.0209, +0.0583, -0.1621, -0.0147, +0.2593, +0.0167, +0.1946, -0.6068, +0.2827, -0.5656, +0.2463, -0.0721, +0.1951, -1.2302, -0.0800, -0.5759, -0.5164, -0.2900, -0.2080, +0.0350, +0.0602, -0.1280, -0.0347, -0.1066, +0.2023, +0.4489, +0.6241, +0.3711, +0.5918, +0.2161, -0.4956, +0.1668], +[ -0.1357, -0.1698, -0.7316, +0.3652, +0.0674, -1.2720, -0.0912, -0.5569, +0.0930, -0.0845, +0.1653, +0.0734, -0.3262, +0.0146, -0.4687, +0.1030, +0.1811, +0.1278, +0.2951, -0.4805, +0.1283, -0.3634, -0.1027, +0.0652, -0.3734, +0.0178, +0.0866, -0.5421, -0.2491, -0.0326, +0.1385, -0.8705, +0.2461, -0.0332, +0.4078, +0.1592, +0.0401, -0.7436, +0.3928, +0.1498, +0.5691, -0.3048, +0.0986, +0.2868, -0.5354, +0.1134, +0.4664, +0.0562, +0.2706, -0.1634, +0.3235, +0.3488, -0.0153, -0.2665, -0.0167, -0.4450, -0.4409, +0.2170, -0.1988, -0.2794, -0.0368, -0.2582, -0.1815, +0.0439, -0.3384, +0.4003, -0.0865, -0.5755, -0.0364, +0.1403, +0.0383, -0.1997, -0.1938, +0.0637, +0.2091, +0.3471, +0.0495, -0.1602, +0.2309, +0.0595, -0.2814, -0.2176, +0.4826, -0.7634, -0.0873, -0.1180, -0.1384, +0.1120, -0.2059, -0.2466, +0.1173, -0.3572, -0.3572, -0.2505, -0.6559, +0.1643, +0.1230, +0.2162, -0.6531, -0.8617, +0.4565, -0.1033, +0.5384, -0.8266, -0.3981, +0.4561, +0.2701, +0.2100, -0.1536, +0.5401, -0.2075, -0.4098, -0.4645, +0.1560, -0.2259, -0.3549, +0.4475, -0.1320, +0.2875, -0.7113, -0.2840, +0.1135, -0.0461, -0.5452, -0.1279, -0.1301, +0.2210, +0.1697], +[ +0.6435, -0.5374, +0.7059, -1.2844, +0.3331, +0.1965, -0.0462, -0.3113, -0.5450, +0.1836, -0.8688, +0.1490, +0.1404, +0.2400, +0.5905, +0.6755, -0.4403, -0.3344, +0.6835, -0.2276, +0.4156, -0.0392, +0.0920, -0.4069, +0.3981, +0.4558, -0.0543, +0.1275, +0.6342, +0.2539, -0.0430, +0.3649, +0.5104, -1.1261, -0.0370, +0.3103, +0.3421, -0.1283, +0.4646, +0.2611, +0.3789, +0.1872, -0.7172, -0.7900, -0.1028, -0.3773, -0.3112, +0.3605, -0.0117, +0.4345, +0.7488, +0.1943, +0.0338, -0.3219, -0.4089, -1.0467, +0.3920, -0.0685, -0.0742, -0.6270, +0.4976, +0.4420, +0.2313, -0.0729, -0.0655, -0.0379, +0.0229, +0.2117, +0.2947, -0.5324, +0.3692, -0.4863, +0.6824, -0.3295, -0.1910, -0.1978, +0.5208, +0.4267, +0.0503, -0.2036, +0.2884, +0.2474, -0.0536, +0.1046, -0.0932, -0.1035, +0.0076, +0.2182, +0.0644, -0.0851, -0.2564, +0.1322, +0.2937, +0.1040, -0.3049, +1.0216, -0.9281, +0.0380, -0.1511, +0.4697, -0.1954, -0.3933, -0.2124, -0.3136, +0.6186, +0.4962, +0.5756, -0.1871, -0.2659, +0.1281, +0.4317, +0.7874, -0.0278, +0.2312, -0.3561, +0.1679, -0.4217, +0.2351, +0.2232, +0.5258, -0.0928, +0.6838, -0.7248, +0.4629, +0.2531, +0.1841, -0.1334, -0.0406], +[ -0.3188, -0.0379, -0.7361, +0.3839, +0.4312, +0.1416, -0.6620, -0.1834, +0.6492, +0.2045, +0.0918, +0.2239, -0.3887, -0.4778, -0.2293, +0.2039, +0.6022, -0.3230, -0.0367, -0.0062, +0.5820, -0.1047, -0.0389, -0.2042, +0.1448, +0.5953, +0.2238, -0.2452, +0.0376, +0.4239, -0.0790, -0.1298, -0.4279, +0.1278, +0.2601, +0.6771, +0.0499, +0.9155, -0.3233, +0.1631, +0.2057, -0.2145, +0.3982, -0.0398, -0.7616, +0.2762, -0.0642, -1.2607, -0.4831, +0.2535, +0.3595, +0.8134, -0.6300, -0.7384, -0.5111, +0.5001, +0.0594, +0.0364, -0.1260, -0.0926, -0.0640, -0.1960, -0.1721, -0.5651, +0.4040, +0.2053, -0.5327, +0.1512, +0.2509, -0.1374, -0.0726, +0.3524, -0.3582, -0.2351, -0.2557, -0.0285, -0.1707, +0.6744, +0.2174, -0.4556, +0.2178, +0.3446, -0.3666, +0.1903, -0.2920, +0.3549, +0.2236, -0.0646, +0.5224, -0.1073, +0.1408, -0.1009, +0.1210, -0.1780, +0.2569, +0.5953, +0.1192, -0.0251, +0.4589, +0.3212, +0.0774, -0.2077, +0.1941, -0.0578, -0.0650, +0.4753, -0.4224, +0.4952, +0.1230, -0.2847, +0.1758, -0.5142, +0.4695, -0.3469, -0.3873, +0.5217, +0.0902, +0.7590, +0.0308, -0.2582, -0.5947, +0.0503, +0.3442, -0.3170, +0.0445, -0.2957, +0.5019, +0.2107], +[ +0.1048, -0.0561, -0.0525, -0.7182, +0.0354, +0.3660, -1.1555, -1.1208, -0.5165, -0.0398, +0.0327, -0.3179, +0.0262, -0.3808, +0.0158, +0.0145, +0.4033, +0.3654, +0.5534, +0.4138, +0.0817, -0.1434, -0.0530, -1.4958, +0.4055, +0.2290, +0.1861, +0.3552, +0.1662, -0.3241, +0.0854, +0.1171, +0.0808, -0.1947, -0.2937, -0.7268, -0.7695, +0.3824, +0.5217, +0.1133, -0.4979, -0.2852, -0.4815, -0.4886, +0.3429, -0.2525, +0.5806, -0.2051, +0.3463, -0.5691, -0.5052, -0.4976, +0.2206, -0.7014, -0.0586, -0.2747, -0.8545, -0.0350, -0.3665, -1.5639, +0.0383, -0.4149, +0.1876, -0.8109, -0.4667, +0.2656, -0.0170, -0.3138, -1.2522, +0.4170, +0.0891, -0.1986, -0.7625, -0.6820, -0.3524, +0.3081, -0.1074, -0.5283, +0.3158, +0.0359, +0.4437, +0.1540, -0.4941, +0.1000, -0.1309, -0.2385, -0.9683, +0.5341, -0.0965, -0.1651, -0.1631, +0.1685, +0.1192, -0.0842, +0.5338, +0.4437, +0.0736, +0.8859, -0.5837, -1.0810, +0.5466, -0.6217, +0.2345, -0.2710, +0.0490, -0.3720, -0.1459, -0.1457, -0.2499, -0.9045, +0.1468, -0.4773, +0.4526, -0.1049, +0.4992, -0.8887, +0.5294, +0.0333, +0.3291, -0.5449, -0.8528, -0.1049, -0.1040, -2.6816, +0.3526, +0.2408, -0.9251, +0.0610], +[ -0.2964, -0.2083, +0.0424, +0.0505, +0.1074, +0.3514, -0.0107, -0.5381, -0.3241, -0.3222, +0.0024, +0.6921, -0.4159, -0.4654, +0.2284, -0.7048, -0.6569, +0.0266, -0.1426, +0.0671, -0.0949, +0.0700, +0.5167, +0.2447, +0.2482, +0.1973, -0.1360, +0.3100, +0.2290, +0.4399, +0.1359, +0.0125, -0.1705, -0.6492, +0.0810, +0.2847, +0.1981, -0.2366, -1.4675, -0.1468, +0.4505, +0.2943, -0.5034, -0.5678, -0.0262, +0.2682, +0.4964, -0.6642, -1.1591, +0.4420, +0.2433, -0.0938, +0.2768, -0.8135, -0.9967, +0.0143, -0.2953, +0.1051, -0.5533, +0.0041, -0.6914, -0.1544, +0.3746, +0.3854, +0.2449, -0.2513, -0.4268, -0.3551, -0.0974, -0.5500, +0.0167, +0.2236, +0.3164, -0.1721, +0.1192, +0.3897, -0.4358, -0.6739, -0.4272, -0.1869, -0.3346, -0.1730, -0.5168, -0.1763, -0.5286, -0.0470, -0.0356, +0.0258, -1.1001, +0.0107, -0.1562, +0.2231, -1.0873, -0.3293, -0.5195, +0.5809, +0.1942, -0.1022, -0.2603, -0.1272, +0.1439, -0.2179, +0.2000, +0.0747, -0.4566, +0.4470, +0.3608, -0.6655, +0.1031, -0.4562, +0.2097, -0.0302, +0.3557, -0.9670, -0.4443, +0.2522, +0.3013, -0.2915, +0.0225, -0.1372, -0.4500, -0.2117, -0.1959, -0.0600, +0.5294, -0.1705, -0.1156, -0.0542], +[ -0.0208, +0.7405, -0.4383, +0.5303, +0.2675, +0.0568, -0.4659, -0.3365, +0.4135, +0.3779, +0.1938, -0.7019, -0.2156, -0.5470, -0.7469, +0.1874, +0.0905, -0.5753, -0.7818, -0.1834, +0.4375, -0.2027, -0.1311, -0.1083, -0.3591, +0.3264, +0.0091, -0.6734, +0.3241, +0.2321, -0.1777, -0.0185, +0.2118, +0.0124, +0.1134, +0.0124, -0.4860, -0.0174, +0.3886, -0.7700, +0.1497, +0.1214, +0.2275, +0.0411, +0.1275, -0.4150, +0.0006, +0.7057, -0.9674, -0.3909, +0.1516, -0.4077, -0.0694, +0.3073, -0.0010, -0.1849, +0.7372, +0.0443, -0.1081, -0.0876, -0.3725, -0.2869, -0.4462, -0.4792, +0.3107, -0.3265, -0.1656, -0.3827, -0.1651, +0.3184, -0.2078, +0.0350, +0.1123, +0.0150, +0.0277, +0.2372, -0.4666, +0.1226, -0.1048, +0.2568, -0.2841, -1.0603, +0.1028, +0.3149, +0.5520, -1.8827, -0.3189, -0.2473, +0.2472, +0.0820, -0.4540, +0.5905, +0.3832, -0.6837, +0.2165, +0.0537, -0.2796, -0.0364, -1.2825, -0.3029, +0.3441, -0.2498, -0.2441, -0.2514, -0.4793, +0.2179, +0.5167, +0.6067, -0.3378, -0.1064, +0.1996, -0.5619, -0.4490, -0.1642, -0.1905, +0.0808, +0.2745, -0.2686, +0.1887, -0.0947, -0.5427, +0.1202, +0.4490, -0.6860, -0.7833, +0.0671, +0.2752, -0.7211], +[ -0.2267, -0.4105, +0.0993, -0.8289, -0.0224, +0.0670, -0.0504, -0.1812, -0.7614, +0.3466, -0.7155, +0.1835, -0.1513, +0.1975, +0.0964, +0.0733, -0.1324, -0.1731, +0.5462, +0.0405, +0.4601, +0.0706, +0.1772, -0.1179, +0.2340, +0.0641, +0.1571, -0.6174, -1.5172, -0.0205, -0.3400, -0.1019, +0.1146, +0.2761, -0.7689, -0.4238, -0.3081, +0.1397, -0.4290, -0.0428, +0.1390, -0.1651, +0.0185, -0.4418, -0.0883, +0.4287, -0.5795, +0.0443, +0.0215, +0.0641, +0.2475, +0.0211, -1.1612, -1.4932, -0.8886, +0.0467, +0.1714, -0.2832, -0.3644, -0.0116, -0.3516, -0.5362, -0.2998, -0.1456, -0.0855, +0.0317, +0.0449, +0.1793, +0.4453, -0.0510, -0.3119, -0.4332, +0.1258, -0.2377, -0.0082, +0.0491, +0.7216, +0.0419, +0.0119, +0.1955, +0.2907, -0.4195, +0.2496, +0.1890, +0.0793, -0.3036, -0.2109, -1.3736, -0.3541, +0.1394, -0.9612, -0.4894, -0.7474, +0.2959, -0.4060, +0.5467, -0.3859, -0.5294, +0.2514, +0.1297, -0.4952, +0.0727, +0.5270, +0.0924, -0.4186, +0.4920, -0.6645, +0.2551, -0.2143, -0.1432, -0.1560, +0.6847, -0.0212, -0.8119, -0.1084, +0.0864, -0.4569, +0.1187, -0.1744, -0.2312, -0.2499, -0.2763, -0.9371, +0.6095, +0.0696, -0.2863, -0.3708, -0.5223], +[ -0.0993, +0.1409, -0.1793, -0.2212, +0.4238, -0.0122, +0.6906, +0.1833, -2.0175, +0.3794, +0.4159, +0.5124, +0.7251, +0.7544, -0.4348, +0.1692, -0.3089, +0.7574, -0.0629, -1.1735, +0.2699, -2.2604, -0.2160, -0.0578, -0.8138, +0.0195, +0.3376, -1.2619, +0.3395, -0.1720, -0.6129, +0.0844, +0.3609, -0.1273, +0.2086, +0.3600, -0.1894, -3.0401, +0.3955, -0.4007, -0.0204, -0.6748, +0.0073, -0.8910, +0.2773, +0.1150, +0.8242, +0.7532, +0.1008, -0.0217, -0.0444, +0.1562, +0.6075, -0.1385, +0.8037, -1.2225, -1.0055, -0.3115, -1.3787, -0.6643, +0.3021, +0.1386, +0.2093, -0.3072, +0.0422, +0.1009, +0.3473, +0.2925, +0.3533, +0.4157, +0.4200, +0.2637, +0.0863, +0.4686, -1.2533, +0.3166, +0.9838, -0.6280, +0.1329, -1.0853, -0.5044, -0.1253, +0.1313, -1.1326, +0.1254, -0.1927, -0.1857, +0.1723, +0.0076, -1.2293, -0.2048, +0.4640, -0.2034, -0.6014, -0.3775, -0.3859, +0.3363, -0.2945, +0.0382, +0.5226, -0.1826, +0.6612, -0.3325, +0.1265, +0.3302, +0.1980, -0.2690, +0.0844, -0.2510, -0.4544, -1.5446, +0.1948, -0.1010, -0.0159, -0.1156, -0.3827, -0.1778, +0.0800, -0.8696, +0.6485, -1.0103, -0.4169, -0.7944, +0.0499, -0.6260, -0.5471, -0.4483, -0.5094], +[ +0.5392, +0.1172, +0.0275, +0.1544, +1.1570, -0.3080, -0.5902, -0.2057, -0.0664, -0.4454, +0.2383, +0.0378, +0.5122, -0.3850, +0.3855, -1.8852, +0.1903, -0.2271, +0.1657, -0.0089, -0.7770, -0.3977, +0.1360, -0.7773, -0.2348, +0.0727, +0.2212, -0.3639, +0.6679, +0.2904, +0.1359, -0.2630, +0.1017, +0.3486, +0.0137, -0.6607, +0.0223, -0.2305, +0.8595, -0.3969, -0.4659, -0.5061, +0.0212, -0.1709, +0.0391, -0.2071, +0.4317, +0.4371, -0.2553, +0.5389, +0.8191, +0.5738, -0.6220, -0.2034, -1.1353, -0.3365, +0.4038, -0.3686, +0.2349, -0.6040, -0.4666, -1.0111, +0.2354, -0.2390, -0.2813, +0.0137, -0.3303, +0.4529, -0.3076, -0.0214, -0.3884, -0.1122, +0.7831, -1.2856, +0.2155, -0.5377, +0.2776, -0.1138, -0.2114, +0.1813, +0.1368, -1.0741, +0.0916, +0.5912, -0.2229, -1.0282, -0.1046, +0.4429, -0.4369, +0.2257, -0.1841, -0.1243, -0.5969, +0.6227, +0.1674, -0.5557, +0.4748, -0.2929, -0.7047, -0.2068, -0.1569, -0.6345, -0.1933, +0.1590, -0.2230, -0.1560, +0.4469, -0.3296, -0.0643, -0.1517, -0.6115, -0.4458, -0.8033, -0.7308, +0.3220, -0.2440, -0.3975, +0.9195, +0.0928, +0.1867, +0.1243, -0.1109, -0.5436, -0.7016, +0.1229, -0.2620, +0.0747, +0.0395], +[ -0.0930, -0.3029, -0.8064, +0.0595, -0.0668, +0.1339, -0.0232, +0.1940, -0.0714, -0.2307, +0.1003, +0.3736, -0.0819, -0.2503, -0.2354, -0.0711, +0.1693, +0.0067, -0.4982, +0.3025, +0.0624, -0.0853, -0.6454, +0.1086, +0.2843, -0.1772, -0.4409, -1.4024, +0.3635, -0.0416, +0.0553, +0.4314, -0.6700, +0.1636, -0.3898, +0.0493, +0.3268, -0.0700, +0.0769, -0.0717, +0.2101, -0.0093, +0.2108, -1.5399, +0.2003, -0.4194, -0.8017, +0.1748, -0.8769, -0.0063, +0.1513, +0.0150, -0.6772, +0.1734, +0.2375, +0.0514, -0.1617, +0.3689, -0.5984, +0.1162, -0.1536, -0.0563, +0.2035, -0.0057, -0.6710, +0.0289, +0.4487, +0.2953, -1.2650, -0.0297, -0.5534, -0.6967, +0.0130, -0.1984, -0.7579, +0.5317, -0.0111, +0.0940, -0.5060, -0.1077, -0.1284, +0.0490, -0.1276, -1.8656, +0.3652, +0.0840, -0.1318, -0.1325, -0.3580, -0.2401, +0.0261, +0.2243, +0.0091, +0.1637, +0.0901, +0.0508, -0.0459, -0.1134, -0.8943, -0.1263, +0.3323, -0.0566, -0.3716, +0.2921, +0.0915, -0.1310, -0.3878, -0.4224, -0.7798, -0.2240, -0.2051, -0.7585, -0.5029, -0.0167, -0.1496, -0.0068, -0.1469, +0.3943, +0.3463, -0.7880, +0.0019, +0.4755, -0.2236, -0.3436, +0.1817, -0.2543, -0.2750, -0.6216], +[ +0.2941, +0.5212, -0.5303, +0.2481, -0.1247, +0.2795, -1.5880, -0.7743, +0.3191, -0.3844, +0.3387, -0.5577, -0.6174, +0.3974, -0.4779, -0.7220, -0.0463, -0.0913, -1.3168, +0.0135, +0.1484, -0.0498, +0.2259, +0.4178, -0.0876, -0.2693, +0.1369, +0.2502, -0.0656, -0.5450, +0.2394, +0.7425, -0.1176, -0.6768, +0.3786, +0.4059, -0.6969, -0.0171, +0.0904, -0.5270, -0.0360, -0.3437, +0.4420, +0.2451, -0.6108, +0.2447, -0.9276, -0.1345, -0.4143, +0.1865, +0.1812, +0.0931, -0.1564, -0.5130, -0.7225, -0.0157, +0.1752, -0.4479, +0.0675, +0.5620, -0.4499, +0.3246, +0.0693, +0.2682, +0.3500, -0.2140, -0.6988, -0.0295, -0.1263, -0.0159, -0.2053, -0.4079, +0.4124, -0.0439, -0.4604, +0.1539, -0.0377, +0.5189, -0.5679, +0.2178, -0.4457, -0.4877, +0.3757, +0.4720, -0.9661, -0.1367, -0.0157, +0.4836, -0.1011, +0.1128, -0.4998, +0.4024, +0.7681, +0.1909, -0.1169, -0.5119, -0.2230, +0.2154, -0.1260, +0.2651, -0.7235, -0.3367, +0.0055, -0.4508, +0.4804, -0.2347, -0.5094, -0.1651, +0.2996, -0.0992, +0.2322, +0.2990, -0.3644, -0.6489, +0.3211, +0.3138, +0.0483, +0.0671, +0.5185, -0.1174, +0.1915, -0.0306, -0.5184, +0.2785, -0.4954, +0.1726, +0.6179, -0.0235], +[ +0.2760, +0.3725, -0.0371, -0.5838, +0.2662, +0.1452, +0.3655, +0.2378, -0.1644, -0.9611, +0.5298, -0.4268, -0.3355, +0.3852, +0.4199, -0.3979, -0.3181, +0.3396, +0.3900, -0.5893, -0.2061, -0.1745, +0.3943, +0.6097, -0.2366, +0.0709, -0.6992, +0.3411, +0.4275, +0.0919, -0.0053, -0.3365, +0.4480, -0.1550, -0.8431, +0.5171, -0.4993, +0.1273, -0.2844, -0.3381, +0.5470, -0.2013, +0.2882, -0.9610, +0.1412, -0.0964, +0.0044, +0.0038, +0.2124, -0.5394, -0.2606, -0.1058, +0.0822, -0.4766, -0.4265, -0.4760, -0.0880, +0.0038, -0.3442, +0.0923, +0.0758, +0.2901, +0.0425, +0.5120, +0.0898, +0.5336, -0.1097, -1.1518, +0.3573, +0.0061, +0.1088, -0.5034, +0.4174, +0.2556, +0.1247, -0.1178, +0.1635, -0.0455, +0.3008, +0.1288, -0.1310, -0.1485, +0.2552, -0.6359, -0.0076, -0.1008, -0.3596, -0.2426, -0.2802, -0.3335, +0.0636, +0.0919, -0.6020, -0.1037, +0.2003, -0.2811, +0.7944, +0.4460, +0.6442, -0.0287, -0.3200, +0.4558, +0.2535, -0.2042, -0.1385, +0.0802, -0.8761, +0.2059, +0.1495, -0.0019, -0.5408, +0.2027, -0.4553, -0.4089, +0.0049, -0.5366, +0.1640, +0.3857, +0.3282, -0.2697, -0.0992, +0.4844, -0.1067, -0.0197, -0.2498, +0.3069, -0.0976, -0.7914], +[ +0.0142, -0.0026, -0.5157, -0.4681, +0.0490, +0.1227, -0.2058, -0.8495, +0.1658, -0.2885, +0.1190, +0.1598, +0.5551, -0.3939, -0.6779, -0.1901, -0.6929, -0.4041, -0.0699, -0.0882, -0.0221, +0.1317, +0.3063, +0.2556, +0.1287, -0.0917, -0.0125, -0.3015, -0.3198, -0.1379, -0.2990, +0.3797, +0.1721, +0.5024, +0.2430, +0.0677, +0.1688, +0.0327, -0.1941, -0.0533, -0.3133, +0.1973, -0.2886, -0.3350, -0.0477, +0.2165, +0.3585, -0.1051, -0.1397, -0.1625, -0.7361, -0.2345, +0.3849, -0.1586, -0.3379, +0.2672, -0.0470, -0.1875, +0.2920, +0.2989, -0.2291, +0.6091, +0.0558, +0.1342, -0.8134, -0.2803, -1.0841, -0.2406, -0.1681, -0.5506, -0.2986, +0.2645, -0.0933, +0.1797, +0.0895, -0.2683, +0.4570, -0.0242, +0.1440, -0.1492, -0.0114, -0.0047, +0.2500, +0.1609, -0.0815, +0.5155, -0.8726, -0.3475, +0.2900, +0.2171, +0.8899, +0.0279, -0.0639, -0.7957, -0.6067, -0.2539, +0.2562, -0.1503, +0.2246, -0.4192, +0.2636, +0.3823, -0.0439, -0.1201, +0.7856, -0.4672, -0.4431, -0.2572, -0.3309, +0.1956, +0.1299, -1.4765, -0.5911, +0.2877, -0.1105, +0.0746, -0.4482, +0.5192, +0.0021, +0.1777, -0.9104, -0.4471, -0.3169, +0.0379, +0.2301, -0.0664, -0.3687, -0.3786], +[ +0.1452, +0.4198, +0.0029, -0.0653, +0.1279, -0.6948, -0.1948, -0.1250, -0.1105, -0.2747, +0.4042, +0.1690, -0.2262, +0.7211, -0.4752, -0.4305, -0.4072, -0.2737, -0.5282, -0.8213, +0.4226, -0.2642, -0.7944, +0.1969, -0.6681, -0.4189, +0.1181, -0.4910, -0.2916, +0.0997, +0.0117, -0.0747, +0.1751, -0.3160, +0.2432, +0.5472, -0.0317, -2.7381, +0.0325, +0.2137, -0.1013, +0.1664, -0.0917, -0.9620, +0.5616, -0.2506, +0.2052, +0.2765, +0.2510, +0.0808, -0.6145, -0.1196, -0.0933, +0.3694, +0.4940, -0.2804, -0.2966, -0.0262, -0.8431, -0.1175, +0.0853, -0.0399, -0.0043, +0.3427, -0.2527, +0.0856, +0.3868, +0.3824, -0.0973, +0.2683, -0.4012, +0.2811, +0.1426, -0.0987, -0.1868, -0.1632, -0.6806, +0.0187, -0.0480, -0.4748, +0.0284, -0.9966, +0.1995, +0.3622, +0.4135, -0.4110, +0.1553, +0.1887, +0.1804, +0.0739, -0.1146, +0.5380, -0.3272, -0.0136, -0.1157, +0.3098, +0.3483, -0.4912, +0.2376, +0.3166, -0.1080, -0.2667, +0.3626, -0.0983, +0.2281, +0.0979, +0.1868, +0.0387, +0.3307, -0.4710, -0.3623, +0.0682, -0.0451, +0.1160, +0.8219, -0.7232, -0.0459, -0.0459, -0.3669, -0.5020, +0.1200, +0.1164, -0.4330, -0.1329, +0.1223, +0.1938, -0.3021, -0.0096], +[ +0.0307, -0.1074, -0.5054, +0.1841, +0.3880, -0.4125, -0.0031, -0.8579, +0.1511, -0.4849, +0.3685, -0.0198, -0.1758, -0.1953, -0.0517, -0.6631, -0.2308, -1.0682, +0.0739, -0.6081, -0.0497, +0.2496, +0.0853, +0.6000, +0.2825, +0.4384, +0.0759, -0.4724, +0.4003, -0.3203, -0.2263, +0.3586, -0.1000, -0.6729, +0.3914, +0.4385, -0.2797, -0.2717, -0.3915, +0.2754, -0.6234, +0.1709, -0.5713, +0.0729, +0.0171, +0.3864, +0.1788, +0.7924, +0.4496, +0.5952, -0.4405, +0.5408, -0.6600, -1.1460, -0.2819, -0.1166, -0.4777, -0.2295, +0.5355, -1.2873, +0.1339, -0.2345, +0.0593, -0.0066, +0.0373, -0.0773, +0.9912, +0.1974, -0.3827, -0.4358, +0.2365, +0.2508, -0.2249, +0.0185, +0.0868, +0.0450, -0.0914, -0.3509, -0.1456, +0.0433, -0.5912, -0.6836, -0.9345, +0.1830, +0.4085, -0.5123, +0.0836, +0.2667, -0.4867, +0.1397, +0.8275, -0.0913, -0.1340, +0.4561, +0.0949, +0.7140, -0.1231, -1.1192, -0.7728, +0.0636, -0.8626, -0.3440, -0.0248, -0.3980, +0.2891, +0.3982, -0.2360, +0.5865, +0.5816, -0.8450, +0.0182, -0.8395, -0.4600, -0.0709, -0.6221, +0.3712, -0.1913, +0.3792, +0.0326, +0.2845, +1.4206, -0.4405, +0.5666, -0.1124, -0.6945, -0.1388, -0.4277, -0.0777], +[ +0.1843, -0.1371, -1.4576, -0.0320, -0.2398, -0.3147, -0.8235, -0.9139, -0.0446, +0.4619, -0.7615, -0.2812, +0.1924, -0.1018, +0.1940, +0.3424, +0.0566, +0.2892, -0.4231, -0.6184, +0.2544, -0.0587, +0.1673, -0.8947, -0.1791, +0.2497, -1.3585, +0.3457, +0.1367, -0.0162, -0.2054, -0.2865, -1.2269, -0.0584, +0.2565, +0.1843, -0.5112, +0.0977, +0.1516, -0.3964, -0.0925, -0.0725, -0.6325, -0.0460, -0.9747, -0.2661, -0.6230, +0.4624, -0.1699, +0.7612, -0.4710, -0.1355, -0.5187, +0.4608, -0.8770, +0.7354, -0.3921, +0.6296, +0.5976, -0.6807, -0.4973, -0.0747, +0.2010, -0.8008, +0.3282, -0.0850, +0.1498, -0.7899, -0.5724, +0.0551, +0.0326, +0.8411, +0.1285, -0.2207, -0.0472, +0.1642, +0.0442, -0.3305, +0.1524, -0.9644, -0.2065, +0.2000, +0.1004, +0.2642, -0.5985, -0.2113, -0.2952, -0.0788, -0.1846, -0.6372, +0.4044, -0.8786, -0.0542, +0.5890, +0.0451, -0.0903, -0.7676, +0.1204, +0.3354, -0.4390, -0.3610, -0.3031, +0.2680, +0.0857, +0.6542, +0.2660, -0.1265, +0.3335, -0.5802, +0.2781, -0.3541, +0.4898, +0.1315, +0.7118, +0.0035, -0.0266, -0.3570, +0.3671, +0.0647, -0.5382, -0.9323, -0.0421, -0.3779, -0.7472, +0.3330, -0.0476, -0.3754, +0.0899], +[ -0.2042, -0.0323, +0.3879, +0.5487, -1.6125, +0.4439, -0.1583, -0.1561, +0.0041, -0.0937, +0.1418, +0.4048, -0.6339, -0.2292, -0.4615, +0.1910, +1.1010, +0.2793, -0.1490, -0.1520, -0.4352, -0.2968, +0.0764, -0.0107, +0.5407, +0.3415, -0.8503, -0.1676, +0.1517, +0.2076, -0.3898, +0.0414, -0.3089, -0.4528, -0.1311, -1.8980, +0.3833, -0.4061, +0.3816, -0.0483, +0.6989, +0.2631, +0.0906, -0.3159, +0.4436, -0.4232, -0.1941, +0.0117, -0.5852, -0.5719, +0.0158, +0.0229, -0.4120, -0.5200, -0.6199, +0.3683, -0.0060, -0.2108, -1.0807, -0.6747, -0.1258, -0.5363, -0.1420, -0.3519, -0.3312, +0.2380, -0.3571, -0.4272, -0.6733, -0.4430, -0.0839, -0.2624, -0.9297, +0.4757, -1.1690, +0.5474, +0.3513, +0.5209, +0.1999, -0.0798, -0.2623, +0.2463, -0.1697, -0.0553, -0.8494, -0.0646, -0.7830, -0.1119, -0.6601, -0.0337, +0.0791, -0.7605, -0.1590, -0.2137, +0.5531, -0.1455, -0.6184, +0.0261, -0.2470, -0.1335, -0.0515, -1.1777, +0.5676, -0.3388, -0.9833, -0.6877, -0.3134, +0.1848, +0.1014, +0.6343, -0.4910, +0.1301, +0.1852, +0.5893, -0.1147, -0.1877, -0.3991, -2.2994, +0.3953, +0.9315, -1.2463, -0.0389, -1.9675, +0.2797, -1.1813, -0.0691, +0.0999, +0.2255], +[ +0.0639, +0.2611, +0.0838, +0.0412, -0.7483, +0.2393, +0.0790, -0.0965, -0.1130, +0.1024, -0.2223, -0.4675, +0.1104, -0.3107, -0.0431, +0.4740, +0.2066, -0.2226, +0.1068, -0.1576, -0.2934, +0.4886, -0.2895, +0.2457, -0.2344, -0.4610, -0.0189, -0.0641, -0.6700, -0.3323, -0.3526, -0.0608, -0.2804, -0.2360, +0.2766, -0.1703, -1.0815, -0.3406, -0.2445, -1.2578, -0.9418, +0.1628, -0.2049, -2.1585, +0.3158, -0.4128, -0.0737, -0.3591, -0.1621, +0.1021, -0.0658, -0.0335, -0.1421, +0.1696, -0.0457, +0.0978, -0.1947, -0.5236, -0.2415, +0.5390, +0.0559, -0.4258, +0.0044, +0.4105, -1.5538, -0.1270, -0.2763, +0.4124, +0.2169, -0.6059, +0.1375, -0.5144, -0.4451, -0.5532, -0.5400, -0.6416, -0.6827, -1.2415, -0.3844, +0.2479, -0.2285, +0.0698, -0.4980, -0.4911, -0.2677, -0.4542, -0.4367, +0.1047, +0.4759, -0.0804, -0.3458, +0.1239, -0.9496, +0.1120, -0.3820, -0.6315, -0.9806, +0.1917, +0.0162, +0.2255, -0.3382, -0.2956, -0.3159, +0.1116, -0.3715, +0.2648, -1.3455, -0.1177, -0.3607, +0.2901, -0.0607, +0.2687, +0.2823, -0.0854, +0.1242, -0.5903, +0.3702, -0.2985, -0.8958, -0.0392, +0.3378, -2.1146, +0.1999, -0.7328, -0.0326, +0.0213, -0.4903, -0.6084], +[ +0.4005, -0.3539, +0.0011, -1.1321, -0.0929, -0.1841, -0.0538, -0.2418, -0.1983, +0.5027, -0.2828, -0.3017, +0.2616, -0.0047, -0.4966, +0.5684, -0.3078, -0.0194, -0.0970, -0.5903, +0.0153, -0.0594, +0.3514, +0.0435, -0.0569, -0.0351, -0.3814, -0.4379, -0.0480, +0.2862, -0.3512, -0.3203, +0.1903, -0.0512, +0.2500, -0.0621, -0.1596, +0.0077, -0.0288, +0.4258, +0.1465, +0.0066, +0.3781, +0.2365, -0.2162, +0.1226, -0.2619, +0.3739, +0.4088, +0.5015, +0.2144, -0.1472, -0.1681, +0.7557, +0.4556, -0.8190, -0.7596, +0.0147, -0.9587, +0.3054, +0.3807, -0.2091, -0.0612, -0.0192, -0.3241, -0.3563, +0.1805, -0.1966, +0.2087, -0.0979, -0.2870, +0.0936, +0.4373, +0.2061, -0.8870, -0.3513, -0.3158, -0.4968, -0.0804, +0.1094, -0.0568, -0.2142, +0.2822, +0.4175, +0.1747, -0.4602, +0.0505, -0.0977, +0.0062, -0.5924, -1.1038, +0.0881, -0.2514, +0.3786, -0.6522, -0.0987, +0.3761, -0.4479, -0.2430, +0.3430, +0.0108, -0.2528, -0.2237, -0.3578, -0.4940, -0.5558, +0.1648, -0.0010, +0.5309, +0.4639, -0.1798, +0.7006, -0.0603, -1.2906, -0.4044, +0.2199, +0.1772, +0.3966, -0.0497, +0.3213, +0.4042, +0.1926, +0.0290, -0.2981, -0.3246, -0.4370, -1.1463, -0.4444], +[ +0.3363, +0.0507, -0.2536, +0.0100, -0.0414, -0.0509, +0.0414, -0.0734, -0.4132, -0.6428, +0.0566, -0.0504, +0.5851, +0.0472, -0.2488, -0.9736, +0.4157, -0.4703, -0.4616, +0.1847, -0.2878, -0.2250, -0.3208, +0.1068, -0.1276, -0.0589, -0.1503, -0.0336, +0.1374, -0.2608, -0.3196, -0.3170, +0.3374, -0.1441, -0.2669, -0.5909, +0.8994, +0.3808, -0.0591, +0.4503, -0.0050, +0.2127, -0.0422, -0.5771, -0.0980, +0.0769, -0.3279, +0.1233, -1.0878, +0.2904, +0.0990, -0.1093, +0.1928, -0.4382, +0.1245, -0.3089, +0.1358, -0.0282, +0.2054, +0.2020, -0.0041, +0.5111, -0.1810, -0.0360, -0.0613, +0.1710, -0.3795, +0.1224, +0.2107, +0.2086, -0.4034, +0.3966, +0.2989, -0.2028, +0.0624, -0.4257, -0.0667, -0.1747, +0.2471, -0.1497, +0.1393, -0.1737, +0.3902, -0.2525, +0.2768, +0.3510, +0.7304, +0.0294, -1.1805, -0.3225, -0.6172, -0.7072, -0.9334, -0.0625, -0.2341, -0.1015, -0.0004, +0.5904, -0.2985, -0.4275, +0.2492, -0.3768, +0.4914, +0.5226, -0.3087, -0.2044, +0.6708, -0.3427, -0.3538, +0.1439, -0.1679, -0.1714, -0.0742, +0.2308, +0.2786, +0.3741, +0.1912, -0.2934, -0.4440, -0.3034, -0.2523, +0.4034, +0.1184, +0.0691, +0.2607, -0.2009, +0.2144, +0.0359], +[ -1.0791, -0.6872, +0.6891, -0.8215, -0.0272, +0.1619, +0.1327, -0.5389, -0.5439, +0.1500, +0.4166, -0.0599, +0.1693, +0.6353, -0.5305, +0.3496, -0.1893, +0.1512, +0.2821, +0.5251, -0.2433, +0.6280, -0.3474, -0.0719, -0.6998, -0.2908, -0.0741, -0.4300, +0.0312, +0.0731, +0.1560, +0.2255, -0.0360, +0.3246, -0.5899, +0.2137, -0.5356, -0.1725, +0.0803, +0.6945, -0.0740, +0.2914, +0.1562, -0.1953, -0.0664, -0.1649, -0.1471, +0.2800, -0.7210, -0.0192, -0.0773, +0.1419, -0.5461, -1.0192, +0.4102, -0.4465, -0.5506, -0.0394, +0.2234, -0.1967, +0.3527, -0.3041, +0.4800, +0.1482, -0.3358, -0.8865, +0.4729, +0.3006, -1.5214, +0.3571, -0.1637, -0.3210, -0.3610, -0.0140, +0.1028, +0.2118, -0.8997, +0.3469, +0.6706, +0.8076, -0.3839, +0.0217, +0.4903, +0.0804, -0.4094, -0.4560, -0.3604, -0.6021, -0.5543, -0.2088, -1.1652, -0.5443, -0.2383, +0.1295, -0.0840, -1.3197, -0.1383, -0.1171, -1.2788, +0.6796, +0.2560, +0.3741, +0.4607, +0.2502, -0.9861, +0.1005, -0.0201, -0.1667, -0.7721, +0.1416, -0.1328, -0.3513, -0.5112, +0.5501, -0.5608, -0.0224, -0.6817, +0.3626, -0.7071, -0.0967, -1.1760, -0.3415, -0.1030, -0.2168, -0.3978, +0.3884, +0.0936, +0.4108], +[ -0.2277, -0.0980, -0.0279, -0.0435, -0.6397, +0.4329, +0.0239, +0.2381, +0.2800, -0.6969, +0.2404, +0.1888, -0.5496, -0.6255, -0.1656, +0.0180, -1.1028, +0.2257, -0.2512, +0.2772, +0.2770, -0.6592, +0.1774, +0.6097, -0.1839, -0.1900, -0.0550, +0.5695, -0.1559, -0.4451, -0.2801, -0.0049, +0.2866, +0.3268, -0.5438, +0.6265, -0.9367, -0.1937, -0.2782, -0.3756, +0.0420, -0.0782, +0.0943, +0.5940, +0.2726, -0.0824, +0.4456, +0.3934, -0.4720, -0.1995, +0.4892, -0.1421, +0.0174, -0.5084, -0.1167, -0.3024, -0.0922, -0.3118, -0.0335, -0.0703, +0.2440, -0.9311, -0.0924, -0.2168, -0.0706, -0.3731, +0.6529, -1.0958, -0.3929, -1.1930, -0.4035, +0.4336, +0.1214, +0.5382, +0.7261, +0.1610, +0.2551, +0.7774, +0.1628, -0.2756, -0.0601, +0.1143, -0.3179, +0.4815, -0.1348, -0.1413, +0.1628, -0.1243, -0.0586, +0.3029, -0.5346, +0.2212, -0.2135, +0.2941, +0.1778, +0.3688, -0.2048, -0.1424, -1.0428, +0.5779, +0.3448, -0.8665, +0.1875, +0.1918, -0.4207, +0.3115, -0.5152, -0.6870, +0.8070, -1.1151, +0.1282, +0.6629, +0.4506, -0.1955, -0.0138, -0.2898, +0.0707, +0.3210, -0.8534, -0.1408, -0.8929, -0.5922, -0.3174, +0.6164, +0.2929, -0.2424, +0.0949, +0.3436], +[ +0.3176, -0.3924, +0.0108, +0.0073, +0.0709, -0.7655, +0.5798, -0.0885, -0.7087, +0.4234, +0.2339, -0.1536, -0.5395, +0.3095, -1.2875, +0.0223, -0.0518, +0.1281, -0.1305, +0.2955, -0.4969, +0.3210, +0.6567, -0.0472, +0.4891, +0.5844, +0.0608, +0.0588, -0.0866, -0.3339, -0.0446, -0.1444, -0.0394, -0.5734, -1.1200, +0.3550, +0.1063, -0.3921, +0.6259, +0.5534, -0.1268, +0.0167, -0.2933, -0.0775, +0.3208, +0.3137, +0.1161, -0.5944, -0.4033, -0.9224, -1.6031, -0.2286, +0.1156, -0.5235, +0.0071, -0.0999, +0.2603, +0.2959, -0.3796, -0.1974, +0.6005, -0.1037, -0.5495, -0.5030, -0.4202, -0.5696, +0.1623, +0.0398, -0.1173, +0.3304, -0.1637, -0.2347, +0.6994, -0.5227, -0.9144, -0.2601, -0.4145, +0.4540, +0.4762, -0.0762, +0.9777, +0.0984, -0.0808, -1.7371, -0.0866, +0.2376, +0.1593, -0.2857, -0.0105, -0.8542, -0.3489, +0.5299, +0.2855, +0.1606, -0.2741, -0.3969, +0.0376, -0.1196, -0.3073, -0.5830, -0.2857, -0.0687, -0.3538, +0.0535, -0.1520, -0.6600, +0.3730, -0.0237, +0.1413, -0.4994, -0.2943, +0.4360, +0.0716, +0.0569, +0.0699, -0.0384, +0.1156, -0.1784, -0.2375, -1.0747, +0.0669, +0.1220, -0.5153, +0.1585, -0.3345, +0.3933, +0.4297, +0.1745], +[ +0.0451, +0.1192, +0.1513, -0.4122, -0.4990, -0.3285, +0.0121, +0.0996, -1.2994, +0.3913, -0.9270, +0.5467, -0.4719, +0.0201, +0.5704, +0.5264, -0.0165, +0.0239, -0.0100, -1.1232, +0.0243, +0.9827, -1.8897, -0.0513, -0.4016, -0.4913, -0.5011, -1.0531, -0.7585, -0.8680, -0.3483, +0.6168, -0.6506, -0.1178, -0.2269, -0.0077, +0.5145, -0.0643, +0.1179, +0.5522, +0.1897, -0.9912, -0.3042, -1.2749, -0.0666, -0.8707, +0.1314, +0.0776, -0.3644, -1.6311, +0.4315, +0.0053, -0.3322, -0.4387, +0.0335, +0.1827, +0.4689, +0.1040, -1.2393, -0.4263, +0.0712, -1.5940, -0.0110, +0.5220, -0.2696, +0.0326, +0.2011, -1.3511, +0.0776, +0.1381, -0.9384, -0.2791, -0.7470, +0.3198, -0.0343, -0.3858, +0.7762, -0.0530, +0.4048, -0.1381, +0.0476, +0.1951, +0.2237, -1.6044, +0.2551, -0.4974, -1.8483, -0.7537, -1.6731, -1.0536, -0.1171, +0.2709, -0.6349, +0.2810, +0.1560, +0.2926, -0.1911, +0.2209, -0.7197, -0.0883, -0.0261, -0.3919, -0.2963, -0.2439, -0.6637, -0.2337, -0.1216, -1.7968, -0.1052, -0.1832, -0.8489, -0.6524, -0.2081, -0.1841, +0.2611, -0.4390, +0.7014, +0.1897, -0.4626, +0.1440, +0.1534, +0.4789, +0.9003, +0.5775, +0.1325, -0.4038, -1.6225, +0.5905], +[ -0.3205, -0.4752, -0.4912, -0.4865, -0.0093, -0.8625, -0.7111, +0.6141, +0.3583, -1.1199, -0.3957, +0.0922, -1.3333, +0.1549, -0.0332, -0.1690, +0.0349, +0.0664, +0.1576, -0.9784, -0.0826, +0.0687, -0.1124, -0.8914, -0.2932, -0.0694, -0.2219, +0.0341, -0.1199, -0.3127, -0.2212, -0.1968, -0.1055, -0.1935, +0.1470, -0.1760, -1.2864, -1.3588, -0.5615, +0.0230, +0.3473, -0.0310, -0.0407, -0.9018, +0.3128, -0.2546, +0.1682, +0.1034, -0.9478, -0.3190, -0.1191, -0.2102, -0.0530, -0.6558, +0.0063, -0.4495, -0.0597, -0.1611, -0.5632, -0.0701, +0.3635, -0.2415, -0.1355, -0.0856, -0.3443, +0.0222, +0.3314, -0.6737, -0.3053, -0.2678, -0.4764, -0.1435, -0.6503, +0.1988, -0.9723, -0.0095, +0.4556, +0.3001, -0.2753, +0.0375, -0.2730, -0.1158, -0.0386, -0.9331, -0.2312, +0.0767, -0.0451, +0.4903, -0.9659, -0.5555, +0.3733, -0.9485, -0.1633, +0.6562, +0.0532, +0.0032, -1.4373, +0.0468, +0.1665, -0.8583, -0.1737, -0.8077, +0.0736, -0.2435, -0.0940, +0.4364, +0.3262, -0.6249, +0.1925, -0.1501, +0.5031, -0.2871, -0.0328, -1.5283, -1.2084, -0.6116, +0.1620, -0.6313, +0.0055, -0.9072, +0.2416, -0.0478, -0.3839, -0.3438, +0.5106, -0.6303, -0.0786, -0.1824], +[ -1.0061, -0.1415, +0.5614, +0.1471, +0.2804, -0.2520, +0.2453, +0.0006, -0.7605, +0.6590, -0.3647, +0.1825, +0.1384, -0.2187, +0.6017, +0.3445, -0.2924, -0.0996, -0.4517, +0.0997, +0.2598, -0.3217, -0.1636, -0.1402, -0.0688, +0.5085, +0.0841, +0.1102, +0.2540, +0.0796, +0.2593, +0.1400, -0.7217, +0.2879, -0.2045, +0.1075, +0.0661, -0.0931, -0.0124, -0.3172, -0.0032, -0.1647, -0.2619, +0.0710, -0.0976, -0.0399, -0.4316, -0.4230, -0.3267, -0.5921, +0.3123, +0.4273, -0.4458, -1.3337, -0.1572, -1.1379, -0.4392, +0.2743, -0.4505, -0.2160, -0.5103, +0.3051, +0.3146, -0.2750, +0.0965, -0.2486, +0.2757, -0.4422, -1.3708, +0.1642, +0.4191, -0.2572, +0.1958, -0.0087, +0.3229, -0.5492, +0.0851, +0.5151, -0.1987, -0.1567, -0.0296, +0.1179, +0.3395, +0.0261, +0.0881, -1.2141, -0.6468, -1.9418, +0.3738, +0.1240, -0.1291, +0.2193, +0.4126, +0.6854, +0.2690, -0.4613, +0.1831, +0.3535, -0.0399, +0.0945, -0.0578, +0.5635, +0.0836, +0.0286, +0.0747, +0.4220, -0.1242, -0.2479, -0.4533, +0.2856, -0.2348, -0.0885, +0.4039, -0.6302, -0.2092, +0.1364, -0.7537, -0.1654, -0.0220, -0.5586, -2.3927, +0.1004, -0.0423, -0.0261, -0.3384, +0.0462, -0.7971, -0.9127], +[ +0.0750, +0.2176, -0.4996, +0.1824, -0.0707, +0.1966, +0.0236, -0.0692, -0.4960, +0.1383, +0.0373, -0.2026, -0.2008, +0.3046, +0.3803, -0.0825, +0.1184, +0.4917, +0.2306, +0.0326, -0.3638, -0.0580, -0.6834, +0.0438, -0.1417, -0.3357, -0.2336, -0.6334, +0.3518, +0.1087, +0.3293, +0.0706, -0.1184, -0.2735, +0.2591, -0.2327, -0.9828, -0.0540, -0.1303, -0.4909, +0.2748, +0.0293, +0.0903, +0.1555, +0.5734, +0.0854, -0.7190, +0.3496, +0.0953, -0.4672, -0.3598, -0.1305, +0.4157, -1.2690, -0.1589, -0.9937, -0.0994, +0.2282, -0.4250, +0.1519, -0.1842, -0.2414, -0.0604, -0.1126, -0.0335, +0.0520, +0.0182, -0.2505, +0.2693, -0.0057, +0.5708, +0.1181, +0.3936, -0.1274, +0.1240, +0.3345, -0.5654, -0.2478, -0.3554, -0.2807, +0.7255, -0.0021, -0.0572, +0.0135, -0.0282, -0.2176, -0.0646, -0.8797, +0.0480, -0.5962, -0.3936, -0.0989, -0.0082, -0.1741, -0.4116, -0.3323, +0.4336, +0.0306, -0.3786, -0.3817, +0.2412, +0.3054, +0.3641, -0.2448, +0.1098, +0.0840, -0.2574, +0.0844, +0.1103, -0.7323, +0.1966, -0.3377, -0.0849, -0.0206, -0.4983, +0.3827, +0.0164, -0.3648, -0.0900, -0.7235, -0.2408, -0.2687, +0.1033, +0.3813, -0.2013, +0.0816, +0.0228, +0.2278], +[ +0.4075, -0.4337, -0.1178, -0.2645, -0.3989, +0.3753, -0.4020, +0.5258, -0.2696, +0.1506, +0.3436, +0.4036, +0.2138, +0.3263, -0.5074, +0.0975, -0.6906, +0.2567, -0.3453, +0.1801, -0.2124, -0.1523, +0.6583, +0.4003, +0.3154, +0.4761, +0.3418, +0.2095, +0.5004, -0.1168, +0.5128, +0.2726, +0.4005, +0.5720, +0.4916, -0.1016, +0.4738, +0.1282, +0.0060, +0.8116, +0.1077, -0.4063, -0.2667, +0.0857, +0.1045, -0.5171, -0.5304, -0.2763, +0.2491, -0.6936, +0.1619, +0.3061, -0.1143, -0.1346, -0.1540, +0.3273, -0.1911, +0.3598, -0.2261, -0.0589, -0.0330, +0.7586, +0.0538, -0.1769, -0.4478, +0.7072, +0.1733, +0.2620, +0.7263, +0.0611, -0.5258, -0.2466, +0.2799, +0.2616, -0.0277, -0.1707, -0.3391, -0.3818, +0.3912, +0.1183, +0.2835, -0.2168, +0.4314, +0.1513, -0.5520, -1.1234, +0.6860, +0.5702, -0.1339, +0.0741, -0.5413, -0.0858, -0.2133, +0.2737, -0.0825, -0.1390, -0.0584, -0.1054, +0.0083, +0.3280, -0.2467, -0.3385, -0.3302, +0.1709, -0.0679, -0.1004, -0.6046, -0.0236, +0.4449, +0.0112, -0.1172, +0.0051, +0.1691, +0.3826, +0.2565, -0.0092, +0.2152, +0.7632, +0.3072, -0.5973, -0.1711, +0.2336, +0.3417, -0.1362, -0.2016, +0.3892, -0.2284, -0.7264], +[ -0.5619, -0.6588, +0.2222, -0.7032, +0.3192, -0.7468, +0.0840, -0.0085, -1.0928, +0.7917, -0.8584, -0.1583, +0.3086, +0.4438, -0.6609, -0.4945, +0.0735, +0.2988, +0.0502, +0.1138, -0.4697, -0.9869, -0.8634, -0.0310, +0.5568, -0.6586, +0.2718, -0.4758, -0.2878, -0.2967, -0.3541, -0.2828, +0.1682, -0.3047, -0.6659, -0.3369, -0.8593, -0.3854, +0.3200, +0.2052, +0.5943, +0.5155, +0.1806, -0.3103, +0.1668, +0.4870, +0.1900, -0.2799, +0.1105, +0.1297, -0.1050, -0.1574, -0.6901, +0.2987, -0.2892, -0.1965, -0.2233, -0.1386, -0.3617, -0.2200, +0.2744, -0.1720, -0.0025, -0.3192, +0.6888, -0.9526, +0.3419, +0.4704, -0.5047, +0.3867, -0.2252, +0.4470, +0.1633, +0.3513, +0.3425, +0.0219, -0.4380, -0.4013, -0.0750, -1.2795, +0.2330, +0.1879, +0.1886, -0.4729, +0.0993, -0.3209, +0.1687, +0.0220, +0.3353, +0.4888, +0.7272, -0.4622, +0.4032, +0.0962, +0.2044, +0.2351, -0.2522, +0.6231, -0.1771, +0.2073, +0.1115, -0.0105, -0.4885, -0.1947, +0.0805, -0.7077, +0.6541, -0.2168, -0.3990, +0.4405, -0.5269, +0.4340, -0.0695, -0.6759, -0.2265, +0.2120, -0.9304, -0.1006, -0.4760, -0.8165, -0.8547, -0.4625, +0.4114, +0.5815, +0.1176, -0.1204, -0.0489, +0.0484], +[ +0.3307, +0.4011, -0.1160, -0.2264, +0.1470, -0.2919, -0.7451, -0.1501, -0.2051, -0.1858, -0.2368, -0.0166, +0.2410, -0.0673, +0.2497, +0.3609, +0.0376, +0.3896, +0.5163, -0.2009, -0.0213, -0.0858, -0.3649, -0.5694, +0.2950, -0.3715, -0.4091, +0.1047, -0.2480, +0.2524, +0.0759, +0.3455, +0.1984, -0.2355, -0.0878, -0.1322, -1.3433, -1.0194, -0.5226, -0.3194, -0.4891, +0.2655, -0.2550, -0.1050, +0.1669, +0.0303, -0.0818, +0.0851, +0.0980, +0.0502, -1.3712, -0.3609, +0.1263, -0.0160, -0.7327, +0.1758, -1.4315, -0.3756, -0.4343, -0.7862, -0.1735, +0.6499, +0.3025, -0.3268, +0.0232, -0.3298, +0.5586, -0.1262, -0.2705, -0.2214, -0.4371, +0.0723, +0.8103, -0.3228, +0.0355, +0.3893, -1.1094, -0.1664, +0.4552, -0.2732, +0.4157, +0.2128, -0.1776, -0.1176, -0.3515, -0.0519, -1.4214, +0.3016, +0.0068, -0.2785, -0.0741, +0.0472, -0.2149, -0.5563, -0.5599, +0.3389, -0.1509, +0.2100, -0.6473, -0.0704, +0.0156, -1.0333, +0.1829, +0.1841, -0.0582, +0.1230, -0.8259, +0.0747, -0.3466, -0.9991, +0.4214, -0.8522, +0.6740, +0.0441, -0.3886, -0.0458, +0.0325, +0.3056, -0.3655, +0.2377, -0.0662, -0.3979, +0.5509, -0.4970, +0.2473, +0.4498, -0.0303, -0.1357], +[ -0.1411, +0.3419, -0.5398, -0.5728, -0.2083, -0.7746, -1.6018, +0.0830, -0.1589, +0.1139, -0.9158, -0.1886, -0.3481, -0.2742, -0.6108, -0.4646, -0.1986, -0.2215, -0.0440, -0.2837, -0.6019, +0.8197, -0.2571, -0.3325, +0.0778, +0.1455, -0.2286, -0.3149, -0.1893, +0.1037, -0.0041, +0.1791, -0.0783, -0.9331, +0.3056, +0.2097, +0.2735, -0.6685, +0.1896, -0.3313, +0.0086, +0.0904, -0.3519, -0.1869, -0.2648, +0.4288, +0.5785, -0.1345, -0.4295, +0.3263, -1.2706, -0.1486, -0.2965, +0.5303, +0.5528, +0.1091, +0.5738, -0.3166, -0.4828, -1.0198, +0.1566, +0.0928, +0.3758, -0.0311, -0.3368, +0.0728, -0.5817, -0.5760, +0.2071, +0.0976, -0.1485, -0.5637, +0.0350, +0.0808, -1.4359, -1.0612, +0.8414, -0.0146, -0.2197, +0.3973, +0.1252, -0.6162, -0.2415, +0.8750, -0.0968, -0.1306, -0.9543, -0.1862, -1.5782, +0.3982, +0.4383, -0.6786, -0.6033, +0.5087, -0.7869, +0.4946, +0.0823, +0.1406, +0.9046, -0.3147, +0.3026, -0.5016, -0.0749, +0.0197, -0.0467, +0.0819, -0.8144, -0.1670, -0.3128, +0.7011, -0.0116, +0.2329, -0.0852, -0.9855, -0.2289, -0.4368, +0.1742, -0.4543, -0.1306, -1.3917, -0.0987, -0.4074, -1.3360, +0.4082, +0.0751, +0.2841, -0.3836, -0.0619], +[ +0.5599, -0.1414, -0.4146, +0.3829, +0.1853, +0.4371, +0.1098, -0.3408, -0.3087, +0.5215, +0.3125, -0.0436, -0.3835, +0.1165, -0.0211, +0.7342, +0.3444, -0.2147, +0.0706, +0.1791, -0.2517, +0.2504, +0.2694, +0.6347, +0.0294, +0.0789, -0.0674, -0.3697, +0.4269, +0.4728, +0.2009, +0.4281, +0.3512, +0.1221, -0.6764, +0.4082, -0.0088, +0.5336, +0.0043, -0.4289, +0.5984, -0.0283, -0.3683, -0.0025, -0.2357, +0.3666, -0.6498, -0.0941, +0.5055, -0.2962, -0.2996, +0.6271, +0.2199, -0.2913, -0.2883, +0.1686, +0.0509, +0.3784, -0.2252, -0.2628, +0.1992, -0.2538, -0.7235, -0.2512, -0.6292, +0.3317, -0.2750, -0.1492, -0.1254, -0.5303, +0.4742, +0.2374, -0.0799, +0.3206, -0.1635, +0.2186, -1.5885, -0.2624, -0.2078, +0.0618, +0.1017, -0.4087, +0.4021, -0.5257, +0.1620, +0.0994, +0.1038, +0.3908, +0.7491, -0.2611, +0.4643, -0.3850, -0.6188, +0.2157, +0.0873, -0.0726, -0.1172, +0.3000, +0.1168, -0.7371, -0.0892, +0.5591, -0.1833, -0.1558, -0.1696, -0.3287, +0.1759, +0.1962, +0.1898, -0.8243, -0.0589, -0.2871, -0.1862, +0.3834, -0.4924, -0.9987, +0.4994, +0.1364, +0.2384, -0.2542, -0.2244, +0.2779, +0.1243, -0.3323, -0.1065, +0.9858, -0.1509, -0.3793], +[ +0.1211, -0.3892, -0.2579, -0.0539, +0.3488, -0.4385, -0.0953, -0.1475, -0.0085, -0.0146, -0.0385, -0.0863, +0.3296, +0.1033, -0.7796, -1.0686, -0.4646, -0.9428, +0.1191, +0.5546, -0.2665, -0.3790, -0.2799, -0.4635, +0.2681, +0.5384, +0.4331, +0.5839, -0.1674, +0.1048, +0.2617, +0.2412, +0.2817, +0.3190, +0.0717, +0.1469, -0.8842, -0.2001, -0.1666, +0.7128, -0.0140, +0.0970, +0.4524, +0.1373, -0.1271, -1.0031, +0.4634, -0.9270, -0.6111, +0.2023, +0.1047, -0.1319, -0.8178, +0.2046, -0.3841, -0.0014, +0.0221, -0.3722, +0.3840, -0.2176, -0.7972, -0.9204, +0.1808, +0.4128, -0.2148, +0.3167, -0.4500, -0.3328, +0.0039, -0.4873, -0.3715, +0.1700, -0.8838, -0.2712, -0.0198, +0.2058, +0.0441, -1.1947, -0.1763, -0.1705, +0.2709, +0.0692, +0.1217, +0.2196, +0.7444, -0.5537, +0.5183, -1.1049, -0.7976, +0.4688, -1.2243, -0.1406, -0.3925, +0.0298, +0.0430, +0.1307, +0.2235, -0.8780, -0.4595, +0.6274, -0.8746, +0.1502, +0.1100, -0.3349, -0.3247, +0.5027, -0.5859, +0.0378, +0.2973, -0.3859, -0.3021, +0.4116, -0.0703, +0.8823, +0.0924, +0.0365, -0.5382, +0.1939, -0.6474, -0.2411, +0.2754, -0.9982, +0.0524, -0.4023, +0.1290, +0.2443, -0.4641, +0.1065], +[ -0.8622, +0.1746, +0.0478, +0.2293, -0.5433, +0.7395, +0.0786, -0.2146, +0.2212, +0.4695, +0.9859, -0.0263, +0.3056, -0.0288, +0.6469, -0.7688, +0.1167, -0.1867, -0.7654, +0.0038, +0.5478, -1.0341, +0.0961, -0.2939, +0.1562, -0.1333, -0.7247, +0.2685, +0.5300, +0.1041, +0.2512, +0.2629, -0.1732, +0.5918, -0.3586, -0.1235, +0.8831, +0.0805, +0.4253, -0.0225, +0.4928, -0.1960, +0.0558, +0.7018, -0.5662, -0.3790, +0.2023, -0.1019, +0.0291, -1.4159, +0.6631, -0.4778, -0.1910, +0.1474, -0.1357, +0.8589, +0.6851, -0.2610, -0.7132, -0.2426, -0.3355, -0.6891, +0.4665, +0.1988, -0.0993, -0.2685, +0.1827, -0.4094, +1.2800, +0.3095, +0.0993, -0.0654, -0.2385, -0.1326, -0.8041, +0.1193, -0.7565, -0.0409, -0.1184, -1.1444, +0.1374, +0.4981, +0.0891, -1.0196, +0.2107, +0.5862, +0.4555, +0.2593, -0.4296, +0.1686, -0.0552, -0.6144, -0.1157, -0.7372, -0.1982, -0.2709, -0.6923, -0.9942, +0.1412, +0.2982, -0.0820, -0.4159, -0.8002, -1.0354, -1.1311, -0.7153, +0.6903, -0.1778, +0.2467, +0.0600, -0.7793, -0.1700, -0.5409, -0.0309, -0.5901, +0.1537, -0.5494, -0.1176, -1.7891, -1.0237, -0.6773, -0.7804, +0.4489, -0.3772, -0.3757, -0.1479, -0.4148, +0.0759], +[ -0.2130, -1.1645, +0.3232, +0.3900, -0.5796, -0.4883, -0.0754, -0.5800, -0.3135, -0.7695, +0.0458, -0.3120, -0.3763, +0.1087, +0.6053, +0.7496, +0.2697, -0.4492, -0.4960, +0.0117, +0.0613, +0.0936, -0.0581, +0.2946, +0.0277, +0.1042, -0.1424, -0.2893, +0.6856, -0.0385, -0.0054, +0.2713, +0.3466, -1.0460, -0.6893, -0.2328, +0.2178, -1.0084, -0.4262, -1.5063, -0.3900, -0.3777, -0.4588, -0.7957, -0.1770, -0.2022, -0.3452, -0.0698, +1.0757, +0.4649, +0.1002, +0.0709, -0.5472, -0.3277, -0.5591, +0.0326, -0.6309, -0.7932, +0.3326, -1.0855, -1.2924, -0.9289, -0.0786, -0.4831, -0.0025, -0.4642, -0.2356, -0.1564, -0.0782, -0.6758, -0.5957, -0.2548, -0.5085, +0.4147, -0.4589, -0.7869, -0.2252, -0.5512, -0.5648, +0.2208, +0.1798, +0.8284, -1.0848, +0.4015, -0.1890, +0.2518, -2.7915, +0.2166, +0.0735, -0.2205, -0.1941, -0.9020, -1.9251, -0.0926, +0.2323, -0.7674, -1.3656, -0.3813, -0.0141, -0.0956, -0.5309, +0.0864, +0.3387, -0.0847, -1.7727, +0.3071, -1.7860, -0.5097, -0.1783, -0.6700, -0.0269, -1.2584, +0.0446, +0.0107, -1.2882, -0.7400, +0.0471, -1.3375, -0.3332, +0.4684, -0.1211, -1.3073, +0.1311, -0.8196, +0.1702, -0.0472, +0.1488, -0.3162], +[ -0.4822, +0.1781, -0.5486, -0.3511, -0.6247, +0.0431, -0.6801, -0.1866, +0.2514, -0.3799, +0.0273, +0.2231, +0.2796, -0.2793, +0.1092, +0.0941, -0.2017, +0.3812, -0.0306, -0.6378, -0.0158, +0.1661, +0.2605, +0.1764, -0.8942, -0.2745, +0.3173, +0.5745, -1.2489, -0.1893, -0.6678, -0.7470, +0.1252, +0.1814, +0.2449, -0.0477, -0.4136, -0.0115, -0.1523, +0.4298, -0.2459, +0.0294, -0.4592, +0.2257, -0.1062, -0.3744, -0.0735, +0.6844, -0.2403, +0.1384, -0.1363, -0.1945, -0.2138, -0.1837, +0.0862, +0.3144, +0.1178, -0.2623, +0.1173, -0.4966, +0.0534, -0.0307, +0.4077, -0.0290, -0.4554, -0.2460, -0.5608, +0.1067, +0.6111, -0.2582, -0.2110, +0.0142, +0.0669, -0.3146, +0.0614, +0.2457, +0.5555, -0.4073, +0.1069, +0.1074, -0.5879, -0.6752, +0.4640, -0.6362, -0.8860, -0.2178, -0.1162, +0.0746, -0.1270, -0.2287, -0.0852, -0.0441, -0.2772, -0.3746, -0.7997, -0.5596, -0.3286, -0.1993, -1.1352, +0.3078, +0.2114, +0.4098, -0.2233, -0.5876, -0.5737, -0.1624, -0.1678, -0.8670, -0.8843, +0.0697, +0.4886, -0.2260, -0.0436, -0.6764, -0.2266, +0.2289, -0.2964, +0.1925, -0.2377, -0.1030, -0.4171, +0.3580, +0.1054, +0.4303, -0.0084, -0.6212, -0.2186, -0.1943], +[ -0.2368, -0.3281, -0.2468, +0.6167, -0.8063, -0.0141, +0.4634, +0.7047, +0.2760, -1.6134, -0.2726, -0.0294, +0.0873, -0.9213, +0.0207, +0.5808, +0.4838, -0.4079, +0.1755, +0.2668, -0.4591, +0.3907, +0.0266, -0.1942, +0.3317, -0.1848, -0.1486, -0.2302, -0.2769, +0.6142, +0.0375, -0.1520, -0.5497, +0.2973, +0.3097, -1.1093, +0.2989, -0.1326, -0.4286, -1.2209, -0.4974, -0.1208, -0.9010, -0.6289, +0.3409, -0.1231, +0.8650, -0.2671, +0.6767, +0.7254, +0.1158, -0.3425, +0.3165, -0.6184, +0.1867, -0.0042, -0.4986, -0.4531, +0.4788, +0.3050, +0.0496, +0.4402, +0.3147, -1.1178, +0.4522, -0.1048, -0.1525, +0.2907, +0.4481, -1.0584, -0.0087, +0.3321, -0.4124, +0.3314, -0.2549, -0.5649, -0.0939, +0.3508, -0.4372, +0.2062, -1.0781, +0.1715, -0.1390, -0.4017, -2.0066, -1.1449, -0.1206, -0.3169, -0.9551, +0.0547, +0.3231, +0.2871, -0.0780, +0.4857, +0.4933, +0.2082, -0.2030, +0.6173, -0.5404, -0.0371, -0.4683, -0.2967, -0.0608, -0.3361, -0.5735, +0.2297, -0.2957, -0.4493, +0.2015, +0.8652, -0.4828, -0.7838, +0.1694, -0.3324, -0.2470, +0.2109, +0.4299, -0.3284, +0.4948, +0.1671, -0.6183, -0.1987, +0.4212, +0.5936, +0.2322, -0.4222, +0.1624, +0.8517], +[ +0.1104, -0.4921, +0.0474, -0.7762, -1.1535, -0.2700, +0.3253, -0.8367, +0.2960, +0.1246, -0.0578, +0.0235, -0.6222, -0.0553, -0.8389, +0.2631, -0.6444, +0.0190, +0.0188, +0.1844, +0.3793, +0.3827, +0.4708, +0.3743, -0.2069, +0.1266, -0.4388, +0.0426, -0.3448, +0.2629, -0.0213, +0.6795, -0.0563, -0.3251, +0.3396, +0.1987, +0.0749, +0.3789, -0.9001, -0.4680, -0.1956, +0.0772, -0.7066, +0.2571, -0.6362, -0.0667, +0.0589, -1.0207, +0.2653, +0.2805, -0.4010, -0.1658, -0.1780, +0.0457, -0.8765, +0.1537, -0.7626, +0.2182, +0.0918, -0.0017, -0.2147, -0.6848, -0.1827, -0.2736, +0.4772, +0.1851, +0.0148, -0.1144, +0.2520, -0.5352, -0.0693, +0.6540, -0.0091, -0.2929, -0.6751, +0.3532, -0.2106, +0.1118, +0.1222, -0.9654, -0.0066, +0.1840, +0.0129, -0.3222, +0.3205, -0.0201, -0.3000, +0.1861, -0.3392, +0.0374, +0.1404, -0.1935, -0.0747, -0.1133, -0.3540, -0.1466, -0.4392, +0.6757, +0.2981, +0.2639, -0.1507, -0.1990, +0.1983, +0.5770, +0.4329, +0.3249, +0.2107, -0.1458, +0.2654, -0.1229, +0.5379, -0.0903, +0.1080, -0.2282, +0.1653, -0.2343, +0.4844, -0.8038, -0.6899, +0.0414, -0.4948, -0.0860, -0.1432, -0.5109, +0.0398, -0.3908, +0.2015, +0.4452], +[ +0.4464, -0.1016, -0.2108, +0.6285, +0.7605, -0.0959, +0.6057, +0.0765, -0.3599, -0.4701, -0.5980, +0.0008, +0.4155, +0.0650, +0.1021, +0.2823, +0.3559, -0.2473, +0.3277, -0.1048, +0.1826, -0.4503, +0.6390, +0.2877, -0.2585, +0.0565, -0.7396, -0.4097, -1.1459, +0.5500, +0.4349, -0.3829, +0.5239, -0.3815, -0.8615, -0.0339, +0.2943, -0.3213, -0.2750, -0.1061, -0.1573, -0.3898, -0.0822, -0.2937, -0.1468, +0.1442, +0.1370, -0.8253, -0.5933, -0.3806, +0.6324, -0.0170, +0.0879, -0.0069, +0.1753, -0.2524, +0.2062, -0.4372, -0.0059, +0.1578, +0.2900, -0.3776, +0.2091, +0.1612, +0.3661, +0.2404, -0.1718, -0.4438, -0.4260, -0.7568, +0.4362, +0.0811, -0.7770, +0.2216, +0.0564, +0.4907, +0.3224, +0.0886, -0.1049, -0.5407, -0.1025, -0.1982, -0.2967, -0.7103, +0.2048, +0.0722, +0.5329, +0.0530, +0.2883, -0.1321, +0.3782, -0.0988, +0.2376, -0.7593, +0.2411, -0.2622, -0.5329, +0.5309, -0.2957, -0.9082, +0.2224, -0.4173, +0.0038, +0.1562, -0.5012, +0.5892, -0.2013, -0.5368, +0.0320, +0.3389, -0.8605, -0.8244, -0.4792, -0.0523, -0.0195, +0.0430, +0.1482, +0.0215, +0.4290, -0.2574, -0.2047, -0.0628, -1.7579, -0.0751, +0.7376, -0.5738, -0.1425, +0.4466], +[ -0.2047, -0.2955, +0.4383, -0.2099, -0.3229, +0.0324, +0.1413, +0.4679, +0.0618, -0.1480, -0.0718, +0.1261, -0.4324, -0.1585, -0.5738, -0.8086, -1.2257, +0.1531, -1.1906, +0.0960, +0.0034, -1.0042, -0.4898, -0.0569, -0.2377, -0.6157, -0.3313, -0.6325, +0.5634, -0.2944, -0.5246, +0.1536, +0.2806, +0.0689, +0.0035, -0.2231, +0.0330, -0.2128, +0.3271, -1.4344, -0.4247, -0.7055, -0.3834, +0.0650, +0.3693, -0.2910, -0.1479, +0.2697, -0.3216, +0.8833, -0.1711, -1.1387, +0.2106, -0.1236, -0.2836, -0.4468, +0.0387, -0.1254, -1.8480, +0.1198, +0.3021, +0.2219, +0.7346, -0.2258, +0.8582, -0.4501, +0.0066, -0.0058, +0.2466, +0.3448, -0.0955, +0.1150, +0.1171, -0.0305, -0.7754, +0.2977, -0.3415, +0.1446, +1.0973, -1.1663, -0.1010, -0.2815, +0.3744, -0.3839, -0.2079, -1.8889, -0.5745, +0.0064, +0.1967, +0.0068, +0.0453, +0.4830, +0.1987, +0.6962, -0.3831, +0.4901, -0.4959, +0.4123, -0.4468, -0.0611, -0.1656, -0.4883, +0.6344, -0.1394, -0.0989, -1.1268, +0.5392, -0.9870, -0.4727, +0.0362, -0.5664, -0.8200, -0.1482, -0.4791, -0.2926, -0.5099, +0.6774, -0.1072, -0.0655, +0.2952, -0.8458, -0.2151, -0.5641, +0.0376, +0.2182, +0.1099, +0.2379, +0.1908], +[ -0.1225, -0.1321, +0.7308, -1.1087, -0.5171, +0.0304, -0.8022, -0.2931, +0.1665, -0.1050, -0.6631, -0.5912, +0.1576, +0.3605, -0.1145, +0.5829, +0.3607, +0.3474, -0.2511, -0.7079, -0.2942, +0.3808, +0.5294, -0.5013, +0.0238, +0.4688, -0.3788, +0.0730, +0.0283, +0.6128, -0.3222, -0.4536, -0.9039, -0.6244, -0.5269, -0.8876, +0.1430, +0.4378, -0.1609, -0.8150, -0.4497, +0.2789, -0.2679, +0.7530, +0.3137, -0.8434, +0.4280, +0.1761, -0.8674, -0.5673, +0.2236, -0.3403, -0.7646, -0.6555, +0.9779, +0.0927, -0.4200, +0.0056, -0.8580, +0.1268, -0.1355, -0.4540, -0.2248, +0.9954, +0.0536, +0.0595, +0.3436, -1.0771, +0.3269, +0.6748, -0.2971, +0.3235, -0.1241, -0.0185, +0.2466, +0.3684, -0.9468, -0.0591, -0.7956, -0.2100, -0.1989, +0.3475, -0.2810, -0.3435, -0.3471, +0.0183, -0.8959, -0.6866, -0.4349, -0.1154, -0.3443, -0.0657, +0.4922, +0.2964, +0.2669, +0.1446, -0.0485, -0.6028, -0.9521, -0.0438, +0.4984, +0.3148, -0.7061, -0.0147, -0.4091, -0.4603, -0.0370, -0.2918, -0.1455, -0.8047, +0.4455, +0.9899, -0.1563, +0.1182, +0.2497, -0.9639, +0.4513, -0.1153, -0.2384, -0.1501, +0.2620, -0.9036, -0.2327, -1.3314, +0.4013, -0.4306, +0.2883, -1.2667], +[ +0.2644, -0.1494, -0.4453, +0.1137, +0.0802, +0.1931, -0.1430, -0.0241, +0.5387, +0.1517, +0.0854, -0.0698, -0.1889, +0.4570, -0.1975, +0.3453, -0.2398, -0.4224, +0.1325, +0.2208, -0.0402, +0.1095, -0.5577, +0.2867, -0.1122, +0.1830, +0.0217, -0.0430, -0.0696, -0.1120, +0.0500, +0.0370, -0.4425, +0.1814, -0.1573, +0.0998, -0.1730, -0.3537, -0.8194, +0.1510, -0.2713, -0.2499, +0.0226, +0.1604, +0.3219, -0.2855, +0.0610, +0.3411, -0.0813, +0.0378, -0.6988, -0.0412, +0.0657, -0.0841, +0.4532, +0.0441, +0.1345, +0.1558, +0.2114, +0.3063, -0.1986, -0.0880, -0.0281, +0.5160, +0.2705, -0.0413, +0.0352, +0.0696, -0.0719, -0.2414, -0.3859, +0.4521, -0.1886, +0.2422, -0.1094, +0.2950, +0.0909, -0.4692, -0.0058, +0.0013, +0.4307, +0.4305, +0.0478, +0.3528, +0.5099, +0.2312, +0.3044, -1.1194, +0.0669, -0.3181, -0.2290, +0.4461, +0.1198, -0.0438, +0.2953, +0.0438, -0.0518, -0.5190, +0.2083, +0.4686, -0.1845, -0.2299, -0.3921, +0.4322, +0.2297, +0.2758, -0.3691, +0.4775, +0.3972, -0.9253, +0.4109, -1.1842, +0.3989, -0.4237, -0.6019, -0.2239, +0.0047, -0.0416, -0.6338, -0.0119, +0.3457, +0.1080, +0.4905, +0.1786, -0.0777, +0.1234, -0.2929, +0.3286], +[ -0.1358, -0.5763, -0.9117, -0.5821, -0.1674, +0.4194, +0.3464, -1.3516, +0.5387, -0.0086, -0.4016, +0.4349, +0.1220, -0.6551, -0.6775, -0.4614, -0.5133, +0.3374, +0.2617, +0.0825, +0.1601, +0.6206, +0.1189, +0.2517, -0.0462, +0.0175, -0.0761, +0.2331, +0.3815, +0.2835, -0.2826, +0.5036, +0.0863, +0.1331, -0.2766, -0.3673, +0.3852, -0.0354, +0.1149, +0.8184, -0.8265, -0.0190, -0.4810, +0.0216, +0.0128, -0.0960, +0.2823, -0.8916, +0.4520, -0.6486, -2.2243, -0.3405, +0.3947, +0.2003, +0.4490, +0.0508, -0.3408, +0.2818, +0.0271, +0.2548, -0.8521, -0.2771, -0.3072, +0.3251, -0.2674, -0.1178, +0.2249, -1.5805, -1.8331, -1.0409, -0.1002, +0.1934, -0.0360, -0.2364, -0.0350, +0.0151, +0.2383, -0.0633, +0.2490, -0.0642, -0.2854, +0.7608, -1.0875, +0.0126, +0.1063, +0.4831, +0.1556, +0.3813, +0.1668, -0.2929, -0.6254, +0.5186, -0.0166, -0.4155, -0.6734, +0.1663, -0.3398, -0.1092, +0.1818, +0.2933, +0.1602, +0.5191, -0.2649, +0.2901, -0.1126, +0.0552, -0.4307, -0.4647, -0.0786, -0.9300, +0.1249, +0.6485, +0.0501, -0.5488, +0.6199, +0.2848, -0.2970, +0.1893, +0.7779, -0.2323, +0.1798, -0.0726, +0.1871, -0.9195, -0.3217, +0.3426, -0.3773, +0.2996], +[ +0.1591, +0.5102, +0.2424, -0.3209, -0.5437, -0.6565, +0.3967, -0.2887, +0.3699, +0.3665, +0.2700, -0.0879, +0.2999, -0.0883, +0.2035, +0.2699, -0.1585, -0.4209, +0.3688, -0.1251, +0.0093, -0.1950, +0.1031, +0.1462, +0.0963, -0.0132, +0.2962, +0.2199, +0.0907, -0.1868, +0.0138, +0.0799, +0.4006, -0.8396, -1.5625, +0.0963, -0.8820, -0.8120, -0.2451, +0.0646, +0.1316, -0.0886, -0.6373, -0.4917, +0.4230, -0.4656, -0.0706, -0.1486, +0.3288, -0.0991, -0.1230, -0.0042, -0.0949, -0.8593, +0.8234, -0.1525, -0.6916, -0.2377, +0.6268, -0.7994, -0.4317, -0.9239, +0.1686, -0.0160, +0.4368, -0.2227, +1.2948, -0.2040, +0.2399, +0.4261, -0.6343, -0.4238, -0.0279, -0.3740, -0.0494, -0.2556, -1.0388, -0.8581, -0.1656, -0.0359, +0.7224, -0.3739, -1.2194, +0.6395, -0.1583, -0.3026, -0.1850, -0.1700, -1.8707, +0.2407, -0.4709, -0.6156, +0.5196, -0.2519, -1.1860, -0.4825, +0.1446, +0.0457, +0.5660, -0.9857, +0.2271, -0.6855, +0.2044, +0.3245, -0.7669, +0.2010, +0.8049, +0.5283, +0.0931, -0.5368, +0.1922, -0.2671, +0.0585, +0.0481, -0.1221, -0.2978, -0.2395, -1.3760, -0.3491, -0.9191, +0.2586, -0.1832, -0.0098, -1.1076, +0.0029, -0.7639, -0.3380, +0.3705], +[ +0.0289, -0.4805, -0.1357, +0.1879, -0.5422, +0.2763, -0.0112, -0.1107, +0.4688, +0.2981, -0.1360, -0.4712, -0.2914, -0.0272, -0.6401, -0.0511, -0.1172, +0.0755, -0.5573, -0.2963, -0.0006, +0.2621, +0.1875, +0.1875, -0.0846, +0.2546, -0.5560, -0.3267, -0.1187, +0.3248, +0.3340, +0.0702, -0.0139, -0.1771, -0.0638, -0.0986, -0.0267, +0.2829, +0.0948, -1.1968, +0.1601, -0.4763, -0.4689, -0.1215, +0.1932, -0.9174, -0.0659, +0.4321, -0.1908, -0.7125, -0.3206, -0.0359, -0.3748, +0.2235, +0.6466, -0.2252, -0.2070, +0.3157, -1.2327, -0.0452, -0.2814, -0.6249, +0.0581, +0.2075, -0.0165, -0.1580, +0.4082, -0.5096, -0.0861, +0.1971, +0.0945, -0.0999, -0.5605, +0.2850, +0.2503, -0.2752, -1.1420, +0.1810, +0.2212, -0.0055, +0.0991, +0.2571, +0.2492, -0.3627, -0.1796, -0.6484, -0.5700, +0.0658, +0.4221, -0.4974, -1.0723, -0.0637, +0.0172, -0.3979, +0.5588, -0.3942, +0.5263, -0.3237, -1.2946, -0.7221, -0.4368, -0.1285, -0.4849, -0.0860, +0.2354, -0.8339, +0.2524, +0.0469, -0.3501, -0.0119, +0.1499, +0.0355, +0.0300, -0.1779, -0.2451, +0.0619, -0.0764, -0.1715, -0.1163, -0.3817, -0.3149, -0.0202, +0.1961, -0.2986, -0.2575, +0.0752, -0.8310, -0.1580], +[ -0.3187, -0.6681, -0.1421, -0.4481, +0.1419, +0.3267, +0.0442, +0.5460, +0.1549, +0.5221, +0.3236, +0.0272, -0.2433, -0.0965, -0.0190, +0.2937, +0.1597, +0.1054, +0.3486, +0.4370, +0.3442, +0.3670, -0.0690, -0.2773, +0.4176, +0.0272, -0.3902, -0.3398, +0.3189, +0.3319, -0.0357, +0.3368, +0.3673, +0.1598, -0.7883, +0.2557, -0.1954, -0.2160, +0.1178, +0.2254, +0.1501, -0.1296, -0.4042, -0.3844, +0.2403, +0.3404, +0.4625, -0.4329, +0.2005, +0.5049, -0.4352, -0.0119, -0.8480, -0.0911, -0.2687, +0.0486, -0.3807, +0.0633, -0.3636, +0.1809, +0.1578, +0.0463, -0.4087, +0.0168, +0.0967, -0.1952, +0.0402, +0.2730, -1.0654, -0.2688, -0.1371, +0.0163, -0.0675, +0.2259, +0.0828, +0.5484, +0.3267, -0.5555, +0.1474, -0.2014, -0.7283, -0.2138, +0.1367, +0.2919, -0.2362, -0.1456, -0.4480, -0.2033, -0.0546, -0.0005, +0.5427, +0.2188, -0.0197, -0.0850, -1.0038, -0.2540, +0.2578, +0.4207, -0.1029, +0.2920, +0.1735, +0.4866, -0.1391, -0.0216, -1.0560, -0.4210, +0.4035, -0.1627, +0.2446, +0.3247, -0.6063, +0.2979, +0.5203, +0.6016, +0.1982, +0.2929, -0.1622, -0.2267, -0.1046, +0.6733, -0.6183, -1.0064, +0.4085, -0.2986, +0.0815, -0.0446, -0.0211, -0.1044], +[ -0.0967, -0.4198, +0.0837, -0.6985, +0.6727, +0.2239, -0.2881, +0.2889, -0.4438, +0.0474, +0.1777, -0.5039, +0.0721, +0.2901, -0.1435, +0.2687, -1.2548, -0.1118, +0.4789, -0.2731, -0.0257, -0.2657, +0.0613, -0.7471, +0.1597, +0.6435, -0.1961, +0.0205, -0.3476, -0.1768, +0.1272, -0.3248, -0.1725, -0.0518, -0.1520, -0.8646, -0.4568, -0.2900, +0.0804, +0.2874, -0.1601, -0.1218, -0.0916, -0.3936, +0.0563, -0.5226, +0.7649, +0.2661, +0.1315, +0.1456, -0.1783, -0.4065, +0.2313, +0.3206, -0.1751, +0.0491, +0.6178, -0.4157, +0.5004, +0.4791, -0.8273, +0.3121, +0.5197, -0.7075, +0.2732, +0.5617, -1.7903, -0.9306, -0.4015, -0.1448, +0.1041, +0.0514, -0.5475, -0.3665, +0.0613, +0.3292, +0.5653, -0.1457, +0.2908, -0.2775, +0.2372, +0.0219, -0.5245, -0.1014, -0.7805, -0.2367, +0.0397, +0.3511, -0.4261, -0.0955, +0.0628, +0.0939, +0.3141, +0.4996, +0.0211, -0.7560, +0.3572, +0.0311, +0.4276, -0.6596, +0.2172, +0.0416, +0.3343, +0.1415, -0.3582, -0.2764, -0.5064, -0.6150, +0.2117, -2.0168, -0.0036, -0.4181, -0.0952, +0.3186, -0.4855, -0.5311, +0.2385, +0.4523, -0.0403, -0.9055, +0.4183, +0.3096, -0.5405, +0.0984, +0.2680, -0.2033, -0.5637, +0.3754], +[ +0.0815, -0.4868, -0.3229, -0.1918, -0.7094, -0.4347, -0.4141, +0.3582, -0.0272, -0.1804, +0.2254, -0.2479, +0.1649, -0.3197, +0.2285, -0.0620, -0.4405, -0.1798, -0.7993, +0.2816, -0.3819, -0.1264, +0.1136, +0.2591, -0.0338, +0.2426, +0.3092, +0.2532, -0.1220, -0.5627, +0.4531, -0.5025, -0.0519, -0.0247, +0.0790, +0.0817, +0.1633, -0.0444, -0.4636, -0.1700, +0.0939, -0.1771, -0.0334, -0.9386, +0.3456, -0.2429, +0.0718, -0.0228, -1.7157, -0.3157, -0.2158, -0.0453, -0.9205, -0.3201, +0.0152, +0.0439, -0.0100, +0.0594, -0.0715, -0.8998, -0.6740, -0.0128, +0.2614, +0.0946, +0.0080, +0.0540, -0.8912, -0.1545, -0.4753, -0.1118, -0.8795, +0.1528, -0.9679, +0.5510, -0.4913, +0.0155, -0.7465, -0.2269, -0.1916, -0.7147, -0.1364, -0.1825, -0.3343, -0.5667, +0.3604, -0.3926, -0.1481, -0.0674, -1.1057, +0.2662, -0.4133, +0.0483, -0.1386, +0.3793, -0.4958, -0.6745, -0.0975, -1.0668, -0.6878, -0.8876, +0.0577, -0.1947, -0.8066, -0.1917, +0.0802, +0.0349, -0.1140, -1.5906, +0.5666, -0.9585, +0.5123, -0.4561, +0.1220, -1.2760, -0.2994, +0.5025, +0.1188, +0.0047, -0.7984, -0.1449, -0.0897, +0.1967, -0.2902, +0.9205, +0.3216, +0.1896, +0.0031, +0.0811], +[ +0.1508, -1.1152, -0.4444, -0.1015, +0.2495, +0.3801, -0.1659, +0.3051, -0.0344, +0.0685, +0.1417, -0.2961, +0.2852, -0.7454, +0.2276, -0.6416, -0.6397, +0.0890, +0.2244, +0.0755, +0.2155, +0.2553, +0.0755, -1.2678, +0.0580, +0.0448, +0.3109, -0.2716, -0.2427, +0.0622, -0.1986, -0.0201, +0.1963, +0.1069, -0.0677, -0.3124, -0.2603, -0.0496, +0.1603, +0.0779, -0.0491, +0.1279, -0.1761, -0.1035, -0.0013, -0.2889, -0.0354, -0.2291, +0.1568, +0.2295, -0.4736, +0.2320, -0.0130, -0.6341, +0.2555, +0.2521, -0.8990, -0.0297, -0.4157, -0.8187, +0.3604, +0.3897, +0.2412, -0.1096, -0.2729, -0.5034, -0.3382, +0.3082, +0.0280, -0.7055, -0.1825, +0.0428, -0.2388, -0.5499, +0.6341, -0.1584, +0.3710, -0.7945, +0.1762, +0.2580, -0.4087, -0.6248, -0.1134, -0.1217, -0.0592, -0.6103, +0.5790, +0.0986, -0.4863, +0.3986, -1.6397, +0.2345, -0.4191, -0.3749, -0.8363, -0.5947, -0.1273, -0.0475, -0.7957, +0.2344, -0.2187, +0.0841, +0.1320, -0.0680, -0.8809, +0.0584, -0.6072, -0.6798, +0.2180, -1.3019, -0.3872, +0.4067, +0.3076, +0.7941, +0.8064, -0.4320, -0.4769, +0.0634, -1.0734, -0.0873, -0.2996, -1.0084, -0.0319, -0.1943, -0.0330, -0.1190, -0.3231, -0.2432], +[ +0.8061, +0.0414, -0.5187, -1.8237, -0.1573, +0.3550, -0.0713, +0.0761, +0.2378, +0.1792, -0.1353, -0.1836, +0.3602, +0.4975, -0.3694, -0.9753, -0.8763, -0.6916, -0.6294, +0.3999, +0.5712, -0.3162, -0.4714, -0.2927, +0.1412, +0.2313, +0.2226, +0.2106, -0.2885, -0.0488, +0.2140, -0.4388, -0.6004, +0.2552, -0.5705, -0.1103, -0.3916, -0.3245, +0.0148, +0.3116, -0.7406, -0.3943, +0.3876, -0.2876, -0.6687, +0.1455, +0.2159, +0.3626, +0.1751, +0.4169, +0.2423, +0.1283, +0.4872, +0.0035, +0.0388, +0.2582, +0.4407, -0.8525, -0.4614, -0.4708, -0.0271, +0.3957, +0.2106, -0.6293, -0.3893, -0.3817, -0.5386, -0.3784, -0.0756, -0.5606, -0.2913, -0.2612, -0.7377, +0.2709, +0.0092, -0.2244, +0.7055, -0.2901, +0.0308, +0.4058, -1.6255, -0.1924, -0.1218, -0.4762, -0.1004, +0.5754, -0.2167, -0.9728, +0.1414, +0.0720, -0.4261, +0.2407, +0.1644, -0.3591, -0.8870, -0.6904, -0.5330, +0.3033, -0.1471, -0.3799, +0.0609, -0.0158, -0.1149, +0.0969, +0.3944, -0.6251, +0.3801, -0.3275, -0.5975, -0.1105, -0.8845, +0.4784, +0.6250, -0.5131, -0.1038, +0.7839, +0.0422, +0.0789, +0.3880, +0.3156, -1.7372, -1.0678, +0.4849, -0.2369, +0.1520, -0.2966, +0.0060, -0.3120], +[ -0.2918, -0.2262, -0.3504, -0.0837, -0.4429, -0.8962, -0.4601, +0.0141, -0.0975, -0.1129, +0.5787, +0.4863, -0.1125, -0.2147, +0.4314, -0.1362, +0.2811, +0.8989, -0.9412, +0.3465, +0.4242, -0.2377, +0.2412, +0.3327, +0.1597, +0.0798, +0.2373, -0.1421, +0.0364, -0.9199, +0.0272, +0.0701, -0.2294, -0.3992, +0.0251, -1.9692, -0.0399, -0.1494, +0.1042, +0.1043, +0.4137, -0.1997, -0.3013, -0.5738, +0.2823, +0.3191, -0.2606, +0.1708, -0.9317, -0.0394, +0.4235, +0.1541, -0.4125, -1.0192, -2.3828, -0.2181, -0.2494, -0.3435, +0.3089, -0.9115, -0.1843, -2.0460, -0.1583, +0.5973, -0.0500, -0.8085, -0.3261, -0.4273, -0.1561, -0.5951, -0.2680, +0.3162, +0.2059, -0.6817, +0.1199, -0.2442, -0.0533, +0.3222, -0.4804, -0.6010, -0.4073, +0.8277, +0.0078, -0.2969, -0.4418, +0.3121, -0.0361, -0.5091, +0.4132, +0.3545, +0.4635, -0.4379, +0.6498, +0.2989, -2.3967, -0.1776, +0.1242, -1.1995, +0.4168, -1.4933, -0.0583, -1.2506, -0.3718, +0.3099, +0.1641, +0.4878, -0.2551, +0.5048, -0.4897, -0.3886, +0.0833, +0.1213, +0.0227, -0.8806, -0.6782, +0.5467, -0.1304, +0.3051, +0.4033, +0.1663, -0.8800, -0.6483, +0.2446, +0.0204, +0.2517, -1.2316, -0.0747, +0.5904], +[ +0.2094, +0.4037, -0.8266, -0.2985, -0.9099, +0.0830, -0.6207, +0.4955, +0.6387, -0.8040, +0.4625, -0.2901, -0.6773, +0.3770, +0.7285, +0.3740, +0.0346, -0.0444, -0.0635, -0.1103, +0.2181, +0.5463, +0.3262, -0.1519, +0.3058, +0.1327, -0.3031, -0.7194, -0.5021, +0.0379, -0.0157, -0.0427, +0.1579, -0.1737, -0.2882, +0.1571, +0.2838, +0.2221, -0.0288, -0.0749, -0.0014, -0.2073, -0.5759, +0.5900, -0.3818, +0.1474, +0.4674, -0.0011, -0.1010, -0.3498, +0.6558, -0.0812, -0.3489, +0.0398, -0.1400, -0.2533, -0.6793, -0.0488, +0.2128, +0.0621, -0.0049, +0.9653, -1.1831, -0.3126, +0.0806, -0.4907, +0.4353, +0.3233, +0.0632, -0.6646, -0.4535, -0.0299, +0.6531, +0.0920, -0.2882, -0.2987, +0.4691, -0.0792, +0.1770, -0.4178, -0.0450, +0.1346, +0.1328, +0.1063, -0.5334, +0.0142, -1.1001, -0.5854, -0.0311, +0.5967, -1.1213, +0.3408, +0.1359, +0.3228, -0.4258, -0.2816, +0.4218, -0.4707, -1.0189, -0.2999, +0.1977, -0.3483, -0.0017, -0.2277, -0.0898, -0.2637, -0.3317, -0.1012, -0.1405, -0.4500, -0.6260, +0.6423, +0.2137, +0.5864, +0.0911, +0.2422, -0.5717, -0.5104, -0.5501, +0.4084, -0.6578, -0.2792, -0.0373, +0.1023, -0.4588, -0.2065, +0.4159, +0.0291], +[ -0.0633, +0.1900, -0.0316, -0.6121, +0.0363, +0.0089, -0.1875, -1.7498, +0.0125, -0.1088, +0.2785, +0.1229, +0.0286, +0.2072, +0.0906, -0.1487, +0.0048, -0.6439, -0.8480, -0.1054, -0.3508, +0.4092, +0.3682, +0.3626, -0.1944, +0.1335, +0.4123, -0.3110, -0.7782, -0.0082, +0.5426, -0.9679, +0.3419, +0.2434, -0.4558, +0.1008, +0.1001, +0.3073, -0.3161, -0.7719, -0.3348, +0.1857, +0.6334, -1.0666, +0.1509, -0.0705, +0.3096, -0.6401, -0.0345, +0.1606, -0.7597, +0.0135, -0.0459, -1.0242, -0.2522, +0.1098, -0.7466, +0.2503, -0.7443, -1.0207, -0.5589, -0.4333, -0.3767, -0.9047, +0.3236, -0.2105, +0.0718, -0.3654, +0.3875, +0.0695, +0.3379, +0.5472, -0.0609, -0.0038, -0.5566, +0.4001, +0.0368, +0.3434, +0.1840, -0.2020, -0.1040, -0.1571, +0.0542, +0.2845, +0.3815, -0.6025, -0.0693, -1.2639, -0.9612, +0.2361, -1.5898, -0.6602, -0.3257, -0.0902, -0.0034, -0.2451, -0.2921, -1.2953, -0.3734, +0.2509, -0.3979, -0.5262, -0.8265, -0.6400, +0.0767, +0.3744, -0.2818, -0.6876, +0.5142, +0.2778, -0.3917, -0.4421, -0.4253, +0.7273, -0.4951, +0.3048, +0.3287, +0.1589, -0.3765, +0.2310, +0.1045, +0.0334, -0.0645, -0.0329, +0.2335, +0.1058, -0.4252, +0.2281], +[ -0.4140, -0.4391, -0.5113, +0.0978, +0.1550, -0.1891, -0.1878, -0.7209, +0.6270, -0.6307, -0.0813, -0.3831, +0.2939, -0.4056, -0.0919, -1.0405, -0.4539, -0.5300, -0.8153, +0.1230, -0.2606, -1.0893, +0.5740, -0.0727, -0.4035, +0.3717, +0.0811, +0.0787, +0.0551, +0.0799, +0.0022, -0.0810, -0.1550, -0.0919, +0.0184, +0.1899, +0.3246, +0.3190, -0.4321, -0.8694, +0.2681, -0.1237, +0.0163, -0.4255, -0.6452, -0.5593, -0.4473, +0.2048, -0.4597, +0.1990, +0.7002, +0.0012, -0.3186, +0.0787, -1.0031, +0.3690, +0.3852, +0.2772, +0.2252, -0.1840, -0.6804, -0.6328, +0.2052, -0.2431, -0.0694, -0.5177, -0.0266, -0.4128, -0.1556, +0.0945, -0.1813, +0.1167, -0.3094, +0.3329, +0.2081, -0.6154, -0.3685, +0.3549, -0.4292, +0.1615, +0.3999, +0.0454, +0.2819, +0.3528, +0.3521, +0.0139, -0.7987, -0.4235, +0.2299, +0.0016, +0.5296, +0.3507, +0.0363, -0.0489, +0.6135, -0.1952, +0.3045, -0.0518, +0.0352, +0.0725, -1.1994, +0.2048, -0.2690, -0.0496, +0.4500, -0.0757, +0.4166, +0.2138, -0.0075, -0.0621, +0.8098, -0.3943, +0.1628, -0.8582, +0.2362, +0.3902, +0.3173, -0.1347, -0.4285, -0.2000, +0.4943, -0.2492, -0.1656, +0.2132, -0.0433, +0.2884, -0.2845, -0.4936], +[ -0.4738, -0.0158, -0.2765, +0.1722, +0.3621, +0.5771, +0.1723, -0.8243, +0.0913, -0.3469, +0.5777, -0.2210, -0.1961, -0.8988, +0.5442, +0.2901, -0.2991, +0.6127, -0.2821, +0.3159, -0.8808, -0.0491, -0.1903, +0.1704, +0.2932, -0.0118, +0.2040, -0.2998, +0.4355, +0.1396, +0.0578, +0.2586, +0.2063, +0.1804, +0.0332, +0.1979, +0.1810, -0.3074, -0.4613, -0.3067, +0.1214, -0.0493, -0.0024, +0.4824, +0.2318, -0.0506, +0.3857, +0.3477, -0.8468, +0.3712, -0.4446, -0.1276, -0.0269, +0.3221, -0.2202, +0.2256, +0.0683, -0.2882, +0.2667, -0.3171, -0.1336, -0.0404, -0.0441, +0.1958, +0.1474, -0.2557, -0.8337, +0.0171, +0.1839, -0.5242, +0.1376, +0.7396, -0.2130, -0.0796, -0.3462, -0.1404, +0.0744, -0.1832, +0.5701, +0.0777, +0.2206, +0.2120, +0.2066, -0.2115, -0.2945, +0.2164, -0.3908, +0.2701, +0.2148, -0.0048, -0.1246, +0.0619, -0.4415, +0.0907, -1.4013, -0.1996, +0.1082, +0.0862, +0.1056, +0.6264, -0.0440, -0.7101, -0.7725, -0.8352, +0.1243, -0.2385, -0.0286, -0.1492, -0.0639, +0.2705, +0.1741, -0.3408, +0.3609, +0.7159, +0.3274, -0.3942, +0.2419, +0.3255, -0.0995, -0.0738, -0.2326, -0.8728, -0.0007, -0.0530, +0.4491, +0.4334, +0.2235, -0.5149], +[ +0.3999, +0.4161, -0.5792, -0.1638, -0.0401, +0.2404, +0.2323, +0.0217, -0.0647, -0.8051, -0.9147, +0.0337, -0.2957, +0.1351, +0.0574, +0.1644, -0.3406, -0.1560, +0.3007, -0.2773, -0.2168, +0.3504, -0.0845, -0.2320, +0.1636, -0.3549, -1.1003, +0.3613, -0.8127, +0.1260, -0.1164, +0.2141, -0.9710, +0.8408, +0.3108, +0.0717, -0.1734, -0.0426, +0.1837, +0.2777, +0.4342, +0.0072, -0.7050, -0.2702, -0.7281, -0.1669, -1.3528, -0.8867, +0.2906, +0.0970, -0.0789, +0.2028, -0.0715, -0.1935, -0.0710, -0.3757, +0.7201, +0.0652, +0.1590, +0.5348, -0.0384, +0.3781, +0.1935, +0.4964, -0.2404, -0.5474, +0.1082, +0.0798, -0.7492, -0.3952, -0.4727, -0.4758, +0.1355, +0.1009, +0.1819, -0.3007, -0.0196, +0.2785, -0.0800, +0.6883, +0.1986, +0.3387, -0.0251, +0.4226, -0.0952, -0.7956, -1.0131, -0.8996, -0.0791, -0.1689, -0.6311, +0.0509, +0.4836, -0.0825, -0.2963, -0.5650, +0.1117, -0.3100, +0.1132, -0.8710, +0.2885, -0.2328, +0.5853, +0.1142, +0.1174, +0.3191, +0.2894, +0.0455, -0.8276, -0.0121, -0.1303, -0.1764, +0.3464, +0.5618, -0.0948, +0.3641, -0.6222, +0.0030, -0.2741, -0.5782, -0.3197, +0.5524, -1.0324, +0.3513, -0.5829, -0.1195, +0.0778, -0.4998], +[ -0.3566, +0.0670, +0.3577, +0.5295, -0.2605, +0.4155, -0.0461, +0.0135, +0.4739, -0.3473, +0.8062, -0.0381, -0.5666, -0.3236, -0.6585, -0.2073, -0.7391, +0.1240, +0.0095, -0.0581, -0.1210, -0.0318, -0.3297, -0.1456, -1.0478, -0.3795, -0.9441, +0.5343, +0.0613, -0.1349, -0.3619, -0.2339, -0.6799, +0.7598, -0.4541, +0.0684, -0.1045, -0.0131, -0.8898, -0.0297, +0.3299, -0.0869, -0.0549, -1.5833, +0.3829, -0.0927, +0.1164, -0.2028, +0.6262, -0.2578, -0.2788, +0.4153, +0.3932, -0.1627, +0.2694, +0.2254, +0.0485, -0.1574, +0.0571, +0.3084, -0.1627, -0.0165, +0.5349, +0.0071, +0.2080, +0.2899, +0.1979, +0.3030, +0.5253, +0.1890, +0.1115, +0.0426, +0.3508, +0.3014, -0.1113, +0.4422, +0.5590, +0.2923, +0.2363, -0.3012, -0.1984, -0.0192, -0.0310, -1.1952, -0.3245, -0.0701, -0.0854, -0.8582, -0.2550, -0.3040, -0.1221, +0.2037, -0.5178, -0.2820, +0.0618, +0.6848, -0.2248, -0.1200, +0.4649, +0.0764, +0.2552, -0.2030, -0.3596, +0.1910, -0.3935, +0.4110, -0.2730, +0.3675, -0.5421, -0.0933, +0.2148, +0.0517, +0.3015, -0.1655, +0.1093, -0.2327, +0.0471, +0.0495, -0.3547, +0.1874, -0.4726, -0.4709, -0.3212, +0.0643, +0.4104, -0.2445, -0.2715, +0.3497], +[ -0.3460, -0.0247, -0.3679, +0.2280, +0.5255, +0.1160, -0.2873, +0.0290, +0.0658, -0.6741, +0.0203, -0.3913, -0.5221, -0.6916, -0.1703, -0.8972, -0.3779, -0.1352, -0.1635, -0.1056, -0.1549, +0.1882, -0.2525, +0.0203, -0.3930, +0.0924, +0.1071, -0.6681, +0.3224, +0.0302, -0.5123, -0.3224, +0.2410, +0.2783, +0.3554, +0.1055, +0.2246, +0.4666, -0.0120, -0.0394, -0.4212, -1.6024, -0.3518, +0.0282, -0.1718, +0.2194, -0.4077, +0.4651, +0.0556, +0.5885, +0.2617, +0.0363, -1.5114, +0.0687, -0.5579, -0.2032, +0.8185, -0.3873, -0.2995, -0.4347, +0.4054, +0.3423, -0.2112, -0.5053, +0.1885, -0.1289, +0.0005, +0.2305, +0.1113, +0.1777, +0.4680, +0.3591, +0.1185, +0.1904, +0.0793, -0.0519, +0.6681, -0.1187, +0.0313, +0.3139, +0.4099, -0.3367, +0.0264, +0.7315, -0.4034, -0.2053, -0.0312, -0.4737, -0.4315, +0.1450, +0.2905, +0.0513, +0.1233, +0.3458, -1.0577, -0.4384, +0.2307, -0.2988, -0.1299, +0.0850, -0.6017, -0.3036, -0.8614, -0.1928, -0.9890, -0.4472, +0.0402, -1.5595, -0.4688, +0.1330, -0.8697, -0.8565, +0.1233, -0.6775, +0.0021, -0.0146, -0.0389, +0.6895, +0.6748, -0.5974, +0.0158, +0.0060, +0.3573, +0.0680, -0.0926, -0.2050, -0.4197, -0.1597], +[ +0.1891, +0.1122, -0.5610, -0.8994, -0.5449, +0.5029, -0.3364, -1.2799, -0.9692, -0.5666, -0.2846, +0.1047, +0.4240, -0.4109, -0.4119, +0.0980, -0.6415, +0.1580, +0.5822, +0.1547, -0.3187, -0.0076, -0.5339, -0.1303, +0.3331, -0.3424, +0.0772, +0.1627, -0.9344, +0.0275, -0.3101, -0.3224, +0.3266, -0.5172, -0.3805, +0.9751, -0.9742, -0.8692, -0.0544, -0.3695, -0.1767, +0.2266, +0.3360, -0.3269, +0.1319, -0.1249, +0.3600, +0.7534, -1.9579, +0.0168, -0.4798, +0.3251, +0.2135, -0.3825, -0.1489, -0.3484, +0.0174, -0.6041, -0.0943, +0.4646, +0.1946, -0.3953, +0.0745, -1.0481, -0.0381, -0.0483, -0.6462, +0.2311, +0.0149, -0.2660, +0.3559, -0.3173, +0.3713, +0.0860, +0.5249, -0.4836, -0.1196, +0.4732, -0.0573, +0.0751, -0.3692, -0.0531, -0.5510, -0.8530, -0.0153, +0.1275, -0.3970, +0.2427, +0.3064, +0.2559, +0.2124, +0.3455, +0.3750, -0.3621, -0.3717, -0.3938, +0.2608, -0.3003, +0.3163, +0.8138, -0.3208, +0.4267, +0.1622, +0.0802, -0.2647, +0.2078, -0.1138, -0.8264, -0.1568, -0.6197, +0.3754, -1.2493, -0.0603, -1.7287, +0.6661, -0.2143, +0.2809, -0.7342, -0.2961, +0.1394, +0.2656, +0.1807, +0.5828, -0.5450, +0.3207, +0.0057, +0.0039, +0.3181], +[ -0.0280, +0.4064, +0.7043, -1.0389, +0.1923, -0.0091, -0.6891, -0.1993, +0.0138, +0.1689, +0.2214, -0.2040, +0.1393, +0.2917, -0.1474, -0.0371, +0.0503, -0.4136, +0.7585, +0.0595, +0.3568, -0.6041, +0.2441, -0.5409, +0.1036, +0.2503, +0.2190, +1.0548, -0.4079, -0.1604, +0.3204, +0.8233, +0.1581, -0.2578, +0.8894, -0.3164, -0.2615, +0.0106, -0.1043, -1.6156, +0.1678, -0.4879, -0.5066, -0.9457, -0.0135, +0.0765, +0.3967, -0.2431, +0.2703, +0.3481, +0.1127, -0.2120, +0.2531, -0.0420, +0.2590, -0.2827, +0.0810, +0.1260, -0.5727, -0.2298, -0.9872, +0.2354, -0.0038, +0.1316, -0.2633, +0.3596, -0.4560, +0.0477, +0.3235, -0.2541, +0.7789, -0.1461, -0.5637, -0.2323, -0.5482, +0.1176, -0.1410, -0.6329, -0.5649, +0.3793, -0.0715, -0.3250, -0.5338, -0.7280, -0.4626, -0.2513, -0.3433, -0.0288, -0.0091, +0.6689, -0.1540, -0.7026, +0.3719, -0.2011, +0.0463, -0.5744, -0.5172, +0.0868, +0.1896, +0.1622, -0.0330, -0.4509, +0.8395, -0.1213, +0.2093, -0.2008, -0.7906, +0.4472, -0.3448, +0.4654, +0.2722, -0.1167, +0.3253, +0.3181, +0.1789, +0.3003, +0.1138, +0.2300, -0.7714, +0.1366, -0.2502, +0.1757, -0.5757, +0.4775, -0.0934, -0.1466, -0.2202, -0.0247], +[ -0.2769, -0.4844, -0.3218, -0.3712, -0.7460, -0.1288, -0.0567, -0.1479, -0.1536, +0.3630, +0.3212, +0.1854, -0.5243, -0.5611, -0.6008, -0.5943, -0.3658, -0.4895, +0.1720, +0.4116, +0.0328, -0.0545, +0.1886, -0.3732, -0.1733, +0.2179, -0.5173, +0.2468, -0.2607, -0.0678, -0.0360, +0.4942, +0.0898, +0.6431, -0.2604, -0.4927, -0.1629, +0.2905, -0.0363, -0.5312, +0.1221, -0.0275, -0.6900, +0.0902, +0.2585, +0.0698, -0.4510, -1.0082, +0.0656, +0.1257, -0.0968, +0.0258, -0.1017, -0.1600, -1.1350, -0.1891, -0.1417, +0.0675, +0.1163, -0.0818, -0.0141, -0.4789, -0.8681, -1.1096, -0.3683, -0.4197, +0.0667, +0.4919, +0.0937, +0.4707, -0.4875, -0.1434, -0.1309, -0.1494, +0.4293, +0.5837, +0.4335, -0.3542, +0.2858, -0.4738, -0.2478, +0.2231, +0.0185, +0.1273, +0.4333, +0.4926, -0.5192, +0.1540, -0.6322, +0.3050, -0.0561, +0.4242, -0.6576, -0.1632, -1.3002, +0.2911, -0.8649, +0.2074, +0.4507, -0.5161, +0.1431, +0.0479, +0.1763, -0.2115, -0.1463, +0.7066, -0.1477, -0.2690, -0.2031, +0.2401, -0.5833, +0.4310, +0.2519, +0.0066, +0.5099, +0.2787, -0.5172, +0.1471, +0.4772, +0.2075, -0.7542, -0.3488, +0.1534, -1.9077, +0.0053, +0.2767, +0.2842, +0.3068], +[ +0.1627, +0.0932, -0.0692, +0.0333, +0.3671, +0.0617, +0.1825, +0.2126, -0.1105, -0.3398, -0.2716, -0.4564, +0.0132, +0.0497, +0.5738, -0.8727, +0.1385, -0.3337, -0.1708, -0.1856, -0.1948, +0.6282, +0.6461, +0.5056, -0.0936, +0.3556, -0.7145, +0.2956, -0.1190, +0.4536, -0.2825, +0.3600, -0.1794, +0.8380, +0.3844, -0.3455, -0.3925, +0.2874, -0.4389, +0.2259, +0.0381, -0.4052, -0.0864, +0.3228, +0.2352, +0.2540, +0.4140, -0.1725, +0.3446, +0.0663, +0.1490, -0.7661, +0.4594, +0.3423, +0.0742, +0.2266, +0.2925, +0.0026, -0.4927, +0.2868, +0.0799, +0.6575, -0.6153, +0.2773, -0.1182, +0.0802, -0.7272, +0.1809, -0.1299, +0.0545, +0.0146, -0.1938, +0.4941, +0.3754, -0.1482, +0.4977, +0.0251, -0.4961, -0.3299, -0.1679, +0.3145, +0.4671, -0.2297, -0.1446, +0.1179, -0.1848, +0.5299, +0.6279, +0.7981, -0.0374, -0.4267, -0.1548, +0.0680, -0.1861, +0.1613, +0.0075, -0.6424, -0.3829, +0.2955, -0.2015, -0.8048, +0.4824, +0.1460, -0.2246, +0.5881, -0.2222, +0.1126, +0.3343, +0.8536, -0.6848, +0.5377, -0.0368, +0.1391, -0.1359, -0.3442, -0.3034, -0.4391, +0.1235, -0.0406, +0.0089, +1.2666, +0.0973, -0.6750, +0.1518, +0.3950, +0.1489, -0.0426, -0.3698], +[ -0.1249, -0.2586, +0.5466, +0.5176, +0.3041, -1.0447, -0.1893, -0.3644, -0.0254, +0.3762, +0.1505, +0.3849, +0.5096, -0.4326, +0.0874, +0.3525, +0.0466, +0.3403, +0.0881, -0.4224, +0.3217, +0.3785, -0.2631, +0.4593, -0.2674, -0.1998, -0.1385, +0.2314, -0.4872, -0.2581, -0.4222, -0.3113, -0.1859, -0.0358, -0.1046, -0.7881, +0.0959, +0.1361, -0.5511, -0.1600, -0.1596, +0.4817, -0.4353, +0.0208, -0.5273, -0.1125, +0.4736, -1.0330, -0.1043, +0.4457, -0.3403, -0.5466, -0.6678, +0.3428, +0.1688, -0.0121, +0.2024, -0.0831, -0.6305, -0.1766, +0.4599, -0.4830, -0.6242, -0.2924, +0.4737, -0.1717, -0.4773, -0.3370, +0.8250, +0.2123, +0.3336, -0.5152, -0.1952, +0.0197, -0.1985, +0.0554, -0.7055, +0.6239, -0.2258, -0.6815, -0.4525, -0.2257, +0.0849, +0.6123, +0.3497, +0.2228, -0.0817, -1.1429, +0.3994, -0.3225, +0.3986, -0.0081, +0.2777, -0.2004, -0.7202, -0.4120, +0.3846, -0.2532, -0.8475, -0.8692, -0.0659, -0.6207, +0.2605, +0.0058, -1.5390, -0.2211, -0.2353, +1.4223, +0.4847, +0.0080, +0.2586, +0.0283, -0.3735, -1.1436, +0.3844, +0.7311, -0.5703, -0.1188, +0.0333, -0.3770, -0.4160, -0.5079, -0.5831, -0.2401, -0.5277, +0.2274, +0.0551, -0.0440], +[ -0.2948, -0.2675, -0.3498, +0.0672, -0.6153, -0.3831, +0.2727, -0.4699, -0.4750, +0.4319, +0.3771, +0.0785, +0.0081, -0.2131, -0.3405, +0.0619, +0.4527, +0.1726, -0.1512, +0.1530, -0.2053, -0.3135, -0.0249, +0.3128, -0.4377, +0.2800, +0.3620, -0.8843, -0.6940, +0.2616, +0.2476, -1.4521, +0.1270, +0.2371, +0.1431, -0.0657, +0.4752, -0.3677, -1.3756, -0.3213, +0.1166, -0.2154, -0.5762, +0.0691, +0.4376, +0.1365, +0.4809, +0.0093, +0.0810, -0.1205, +0.2233, -0.0932, -0.2922, +0.0394, -0.1762, +0.2118, +0.2160, +0.1256, +0.0622, +0.6482, -0.1080, +1.0528, +0.4798, +0.2713, +0.0338, -0.0506, -0.7699, -0.4552, +0.3653, +0.3004, +0.3685, +0.2309, +0.0852, +0.3183, -1.8090, -0.1127, -0.3724, +0.2288, -0.0874, +0.6633, +0.5991, -0.9262, +0.2167, +0.2694, -0.0009, -0.3100, +0.1314, -0.6853, -0.6782, -0.1331, -0.5942, -0.3491, +0.4602, +0.3154, +0.5430, -0.6382, +0.4787, -0.0395, -0.4122, +0.0822, +0.1106, -0.2653, -0.1207, +0.2503, +0.0988, -0.1648, +0.3514, +0.2168, -0.4024, -0.0270, +0.0449, -1.0198, +0.0083, -0.1998, +0.2589, -0.8012, +0.6724, -0.8470, -0.8099, -0.5403, -0.3611, -0.1546, -0.0373, +0.0279, -0.1776, -0.1399, -0.2660, +0.2166], +[ +0.1468, +0.1605, -0.7206, -0.1315, +0.1711, -0.0937, +0.1821, -0.2529, +0.3596, +0.5021, +0.2899, -0.1337, -0.0562, -0.3750, -0.0213, -0.3416, +0.1163, -0.3959, -0.1453, -0.0226, -0.2151, -0.1230, -0.1099, +0.0746, -0.1753, +0.3563, -0.0813, +0.1116, +0.0483, -0.0490, +0.1264, -0.4237, -0.3931, -0.0208, -0.4030, -0.0314, -0.3142, +0.4447, -0.6161, -0.4919, -0.0185, +0.4071, +0.1044, -0.8308, -0.2317, +0.1504, -0.5274, -0.3391, +0.1318, -0.0589, -0.0422, +0.1590, -0.4159, +0.4971, -0.8429, +0.1896, +0.4471, +0.5414, +0.2074, -0.1459, +0.1880, +0.3062, -0.2648, +0.3391, -0.1389, +0.3524, -0.4327, -0.6014, +0.1049, -0.1632, -0.2835, +0.4386, -0.1937, +0.4618, +0.0392, -0.0116, +0.0426, +0.5406, -0.3774, +0.1741, +0.7146, -0.1920, +0.2511, -0.4769, +0.4593, -0.7666, +0.2325, -0.4224, -0.1658, +0.0027, -0.0929, -0.4411, +0.0945, +0.5415, +0.5139, +0.0461, +0.0246, +0.2496, -0.0086, -0.0972, -0.1127, +0.5594, -0.3779, +0.3021, +0.7424, -0.7742, +0.4401, +0.3576, +0.2463, +0.2575, +0.0405, +0.2020, +0.0751, -0.8001, -0.0496, +0.0415, +0.9000, +0.1513, -1.0452, -0.5526, +0.0345, +0.4193, -0.0346, -0.4692, +0.3855, +0.3223, -0.0605, +0.2719], +[ -0.3304, -0.5461, +0.1105, -0.4784, +0.8587, +0.2012, +0.2441, +0.3844, -0.0353, +0.2197, -0.4514, -0.1174, -0.3371, +0.6193, +0.5215, +0.0668, +0.2793, +0.0772, -0.3565, -0.7580, +0.0638, -0.0688, -0.5527, +0.5006, +0.2147, +0.3336, -0.1883, -1.2293, -0.3735, +0.2956, -0.8615, -0.1399, -0.5002, +0.2953, -0.4261, +0.0643, -0.4822, +0.5314, +0.2076, -0.1544, -0.3966, -0.0563, -0.2849, -0.1433, -0.1702, +0.3132, -0.2281, -0.4330, +0.4116, +0.5219, -0.1308, -0.7934, +0.2316, +0.3169, +0.0822, -0.0786, -0.2983, -0.2409, -0.4243, +0.0411, +0.3327, +0.0553, -0.1777, +0.4661, -0.0095, -0.7174, +0.2346, +0.1966, +0.1853, +0.1936, -0.1538, +0.0861, +0.1072, +0.4284, -0.4048, +0.2446, +0.0831, -0.3847, +0.1770, +0.3220, +0.3967, +0.0473, +0.0293, +0.7619, +0.6648, -0.0809, +0.2496, -0.5963, +0.6097, -0.0942, -0.8157, +0.0398, +0.1286, -0.3510, -0.0276, -0.4275, +0.2023, +0.1366, +0.7164, +0.2144, -0.4248, +0.3646, +0.2128, -0.2796, +0.4273, -0.5062, +0.4408, +0.1130, -0.3957, -0.1383, +0.0493, +0.0144, +0.2001, +0.1299, -0.1198, +0.2288, -0.3851, +0.2022, -0.8794, +0.6381, -0.2271, +0.0757, +0.6264, +0.1603, +0.1398, -0.5992, -0.5076, +0.4124], +[ -0.4653, +0.2013, -0.6020, +0.2698, -0.1746, -0.0599, -0.8512, +0.4460, -0.1568, -0.4250, +0.2001, -0.3419, +0.2083, +0.2165, -0.5031, -0.0974, +0.3348, +0.1919, +0.1043, -0.4256, +0.1499, +0.4606, -0.4713, +0.0558, -0.1333, -0.1562, +0.2721, -0.0773, -0.2043, -0.3741, +0.0581, +0.4342, +0.2091, -0.0077, +0.0282, +0.2841, -1.2537, -1.8891, +0.4342, -0.0602, -0.1319, +0.1746, +0.2591, +0.1119, +0.3353, -0.0305, -0.3655, +0.1949, -0.1574, +0.2060, -1.2330, +0.1509, -0.1390, -0.3126, -0.2878, +0.2268, +0.0015, -1.0281, +0.2765, -1.6093, +0.1884, -0.1080, +0.2171, +0.1133, -0.3212, +0.0263, +0.4069, -0.3031, +0.2118, +0.2243, -0.2194, -0.4348, +0.5289, +0.2021, +0.2662, -0.4296, +0.5655, -0.0506, +0.0327, +0.4667, -0.6388, -0.3863, +0.0791, -1.9748, -0.7543, +0.1312, +0.3268, +0.0462, -0.3009, +0.1676, +0.6889, -0.7325, +0.0110, +0.1539, +0.3882, -0.3300, -0.0346, -0.1716, -0.1278, -0.3229, -0.2927, -0.5614, -0.2496, +0.1966, +0.2029, -0.0382, -1.7907, +0.1786, +0.1333, +0.4529, +0.4298, +0.0186, +0.1384, -0.1147, +0.1967, -0.7488, +0.2887, -0.5002, -0.7509, +0.0944, -0.2133, +0.0350, +0.0661, -0.4390, -0.3448, +0.0407, +0.4323, -0.2928], +[ -0.0147, +0.4875, +0.8101, -0.4856, -0.0523, -0.3526, -0.6560, +0.7529, +0.3859, -0.4544, +0.2600, -0.4286, +0.2637, +0.2107, -0.1284, -0.1439, -0.1315, -0.8336, -0.1653, -0.3187, -0.2810, +0.2348, -0.2626, -0.0338, -0.3902, -0.1839, -0.2207, +0.4949, +0.3045, +0.1014, -0.0807, +0.2200, -0.2967, -0.9202, +0.1546, -0.4144, -2.4271, -0.0263, +0.4327, -1.0839, -0.1580, +0.1715, -0.0484, -0.3445, +0.0727, -0.0436, +0.2518, +0.1517, -0.3360, -0.4268, +0.6681, -0.1279, -0.4185, +0.2538, -0.5804, -0.3471, -1.3149, +0.2916, -0.2334, -0.3507, -0.2264, +0.2349, -0.0306, -0.3034, +0.2636, +0.0868, -0.0179, -0.4565, -0.5344, -0.0175, +0.4892, +0.3090, -0.0237, +0.0411, +0.4259, -0.0677, -2.6061, +0.2379, +0.2025, -0.1072, +0.1846, -0.0507, -0.2904, +0.1787, -0.3208, +0.3360, -0.4238, +0.0671, +0.2267, -0.5225, -0.0235, +0.5066, +0.1909, +0.0754, -0.2492, -0.1392, +0.1230, -0.5220, -0.1610, +0.4429, -0.4891, +0.1724, -0.4112, -0.1275, +0.1159, -0.4529, +0.3007, +0.1971, +0.3724, +0.7879, +0.0329, +0.5699, -0.0586, -0.5128, +0.0962, +0.8331, +0.2197, +0.1847, -0.9229, +0.4521, -0.6595, -0.0474, +0.4472, -0.4547, +0.2102, -0.4422, +0.1127, -0.0290], +[ -0.2493, -0.1717, +0.8604, -0.7542, -0.4952, -0.4122, +0.3039, -0.4902, -0.2674, -0.0523, -0.2816, +0.0923, +0.1304, -0.1094, -1.1880, +0.2816, -0.6017, +0.0202, -0.0796, +0.0304, -0.3512, +0.6504, -0.2099, -0.2257, +0.2124, +0.7719, -0.0650, -0.0281, -1.1338, -0.5571, +0.1130, -0.1291, -0.7798, -0.2749, -0.5566, -0.5531, -0.0331, +0.0040, +0.2884, +0.6961, -0.4286, +0.2904, -0.7414, -0.6173, +0.2576, -0.0848, -0.2355, -0.4300, -0.0720, -0.4600, -0.2441, -0.7780, +0.1823, +0.1500, +0.4750, -1.0978, +0.2718, +0.0556, +0.2923, -0.6138, +0.3705, +0.4232, -0.2120, +0.7972, -0.1092, -0.3228, +0.0125, +0.0879, -0.3939, -0.4144, -0.3686, -0.6152, -0.3841, +0.0532, +0.0814, -1.0093, +0.1254, -0.0881, +0.1689, +0.2619, -0.4825, +0.3082, -0.1236, -0.1613, -0.0734, +0.2569, +0.5777, -0.5805, -0.2631, +0.2626, -0.4563, +0.2758, +0.5379, +0.4217, +0.3193, -0.2149, +0.2140, -0.0421, -0.4922, +0.2960, +0.3118, +0.2100, -0.2256, +0.2403, +0.5520, -0.4115, +0.1593, -0.9762, -0.2154, -0.1241, -0.1680, -0.1556, -0.1731, +0.1911, -0.1973, -0.4498, -0.3598, -0.5564, -0.5785, -0.0956, +0.0273, -0.1774, -0.9415, +0.2808, -0.0721, +0.4881, -0.1166, +0.6181], +[ -0.0386, +0.1265, +0.0809, +0.3067, +0.2942, +0.6539, +0.3153, +0.2100, -0.8135, -1.1951, -0.5475, -0.2480, +0.3113, -0.0350, -0.1093, -0.0782, -0.0263, -0.0035, +0.5323, -0.0407, -0.1539, -0.1074, +0.0438, +0.6214, -0.4991, +0.4022, +0.1268, +0.1501, +0.5942, -0.0779, -0.0857, +0.0398, -0.2412, -0.2143, -0.5008, +0.0085, -0.1958, +0.6470, +0.6039, -0.3274, -0.3645, +0.0357, +0.0763, -0.0920, -0.1759, +0.1859, +0.5215, -0.1242, +0.0176, -0.0861, -0.3552, +0.3534, +0.2396, -0.0521, +0.1086, +0.1892, -0.3544, +0.1131, +0.2045, -0.1855, -0.0832, -1.3791, -0.3627, +0.0419, -0.6307, -0.2916, +0.1963, -0.1953, -0.2043, +0.2270, +0.2018, +0.0349, +0.0691, +0.4119, +0.0290, -0.3374, +0.0907, -0.7810, -0.2323, +0.1644, +0.0718, +0.0805, +0.2973, +0.3208, -0.1966, +0.1936, +0.1871, +0.3255, +0.1103, -0.0079, -0.3683, +0.1853, +0.3867, -0.4835, -0.4310, -0.7948, +0.1171, +0.1882, +0.4107, -0.2627, -0.0889, +0.1034, +0.2893, +0.0155, +0.0468, -0.1663, +0.0111, +0.5293, +0.3996, -0.0184, +0.4669, -0.8742, +0.0247, -0.1326, +0.2207, +0.2451, +0.1919, -0.2266, -0.3340, +0.3490, -0.1676, +0.0994, -0.7257, +0.3689, -0.1808, +0.0645, -0.1275, -0.5453], +[ -0.4692, -0.1094, +0.0659, -0.0332, -0.6763, -0.1042, +0.2339, +0.7994, -0.0650, -0.2682, -0.3786, -0.0333, +0.1062, +0.4097, +0.2444, +0.0130, +0.0209, -0.1417, -0.1984, -0.2713, -0.0615, -1.2190, +0.6678, +0.1132, -0.1875, -0.0167, -0.4101, -0.2796, -0.0204, -0.1975, +0.5072, -0.0493, -0.0868, -0.1605, -0.1213, +0.1540, +0.2977, +0.0866, -0.5916, -0.6326, +0.2374, +0.1011, +0.4999, -0.2778, -0.3732, -0.2621, -0.0390, -0.8054, +0.2065, +0.4601, +0.2876, +0.6231, -0.5389, -0.0494, -0.4927, -0.0118, +0.3478, -0.0583, +0.4044, -0.6412, -0.0135, -0.2810, +0.3404, -0.6886, +0.1874, +0.1197, -0.6534, -1.3675, +0.0585, -0.9163, -0.0759, +0.1681, -0.2062, +0.1995, +0.3509, +0.1485, -0.1827, -0.0109, -0.0520, -0.6026, -0.0309, +0.1481, +0.0998, -0.2491, -0.1177, -0.0872, +0.3857, -0.0211, +0.1284, -0.1741, -0.2777, -0.3062, -0.3271, +0.4802, +0.1352, -0.4759, -0.2406, +0.6412, +0.5612, -0.1696, +0.2148, +0.1793, +0.0844, -0.0520, -0.0351, -0.4822, +0.5715, +0.0096, -0.2875, -0.1981, -0.2082, -0.1329, -0.3028, -0.3576, -0.7867, -0.0568, +0.4579, -0.2249, -0.1251, -0.5290, -0.4751, +0.2220, -0.7200, +0.4872, +0.2924, +0.0189, +0.2746, -0.4167], +[ -0.2192, +0.0070, +0.6801, +0.0934, -0.7869, -0.0606, +0.2998, +0.3192, -0.6894, +0.1938, -0.5750, -0.3213, +0.2864, -0.3018, +0.5830, -0.0907, -0.6795, -0.1959, +0.0498, +0.0393, +0.0955, +0.1378, -0.1448, -0.3244, +0.1325, -0.4948, -0.1462, +0.2279, -0.1034, +0.5426, +0.2497, -0.4908, -0.7263, -0.6941, -0.2128, +0.1560, +0.3640, +0.5246, -0.0872, -1.1948, +0.4199, -0.3246, +0.5204, -0.2219, +0.5650, +0.1194, -0.7113, -0.7679, +0.0195, -0.0896, +0.1393, +0.2413, -0.2315, -0.1455, -1.3670, +0.3861, +0.4419, +0.0639, -0.4954, -0.1562, -0.0227, +0.5195, +0.0172, +0.2498, -0.2056, +0.1355, -0.4583, -0.3596, +0.3332, +0.4399, -0.5906, -0.0869, +0.3909, +0.2269, -0.1635, -0.5459, -1.0745, +0.2837, -0.3212, +0.4923, +0.1431, +0.4467, +0.0149, +0.2936, -0.2570, +0.3208, -0.3007, +0.3253, -1.0951, -0.2871, +0.2600, +0.1508, -0.0872, +0.0481, -0.2920, +0.5201, -0.5000, -0.0068, +0.0013, -0.9657, +0.1424, -0.0475, +0.1101, +0.5505, -0.5671, +0.3893, -0.3366, +0.3850, -0.1474, +0.0822, +0.7856, -0.3526, -0.0134, -0.2321, +0.0435, -0.8470, -0.2428, +0.4091, -0.3198, -0.1435, -0.5942, +0.1096, -0.6466, -0.1988, -0.0292, +0.2447, +0.0265, +0.0018], +[ -0.0352, -0.2346, +0.0859, +0.1758, -0.3347, +0.1836, +0.0254, +0.2248, +0.2209, +0.4463, +0.2712, -0.3749, +0.2835, -0.2375, -0.3635, +0.2696, +0.1382, -0.3179, -0.1828, -0.0968, -0.2109, +0.3391, +0.1696, -0.3930, +0.2445, +0.3224, +0.0135, +0.0054, -0.1534, +0.3513, -0.0069, -0.3339, +0.0513, -0.0552, -0.3873, -0.7594, -0.5288, +0.2727, +0.5225, -0.5971, -0.0917, -0.0256, +0.1634, +0.1411, +0.0724, -0.0886, -0.2640, -0.4610, -0.2578, -0.1688, +0.4008, -0.1871, +0.1569, +0.5000, -0.0814, +0.1857, +0.3914, +0.2859, -0.6269, -0.0063, -0.3616, -0.4331, -0.2693, +0.0870, +0.0893, -0.2255, +0.2131, +0.4674, +0.5417, +0.4653, -0.0902, +0.2695, -0.5260, -0.1611, -0.3307, +0.1241, -0.1217, -0.1343, +0.3153, +0.0153, +0.1986, -0.0012, +0.1353, +0.0304, +0.1240, -1.3306, -0.3043, -0.1730, +0.2383, +0.1076, -0.4895, -0.0328, +0.0427, -0.0550, +0.4644, +0.2662, +0.3317, -0.0916, -0.2966, -0.8270, -0.0122, -0.1229, -0.1763, -0.2821, +0.1425, -0.5055, +0.1814, -0.4447, -0.0676, -0.0509, -0.3788, -0.2959, +0.3250, -1.3882, +0.0385, +0.2324, -0.0204, -0.1502, +0.4036, +0.1506, +0.5967, -0.8639, +0.0580, -0.8099, +0.3450, -0.1774, +0.0239, -0.1997], +[ +0.5684, -0.0216, -0.5538, +0.2260, -0.2572, +0.4158, +0.0583, -0.2957, -0.3397, +0.2123, -0.4795, -0.6243, -0.0550, -0.1616, -0.2777, +0.4278, +0.1357, -0.5469, -0.8075, -0.0971, +0.5367, +0.4817, +0.0394, +0.5311, -0.9895, -0.6751, +0.4951, +0.2023, +0.3504, -0.1906, -0.0098, -0.3285, -0.3039, -0.0281, -0.1405, -0.3270, +0.6313, -0.0546, -0.5070, -0.4210, -0.6010, +0.0226, -1.0871, -0.3306, -0.0799, -0.2131, +0.1067, -0.1444, +0.5036, +0.0780, -0.2379, +0.1027, +0.0106, +0.0445, +0.4597, -0.1717, +0.0732, -0.1699, +0.0170, +0.3763, +0.1521, -0.1140, -0.0989, +0.3150, -0.2521, -0.2231, +0.2822, +0.4532, -0.2959, +0.0680, +0.0628, +0.5487, -0.4580, -0.2850, -0.8598, +0.2140, +0.0685, -0.0025, -0.0184, -0.6549, -0.4093, -0.1550, +0.1699, -0.2195, -0.3559, -0.0794, -0.2342, -0.8754, -0.0657, +0.1804, -0.7524, -0.0975, +0.3923, -0.0837, -0.2477, +0.3972, -0.1719, -0.1009, +0.4203, +0.1686, -0.0107, +0.0231, -0.4684, +0.8655, +0.3072, -0.6401, -0.0229, +0.1848, +0.3838, +0.1357, -0.3682, -0.0991, -0.0411, -0.3113, +0.0033, +0.5014, +0.6548, -0.5687, -0.8568, +0.3984, -0.2581, -0.7770, +0.2297, -0.1984, -0.2011, -0.1527, +0.2363, +0.5539], +[ -0.1108, +0.0564, +0.4279, -0.2463, -0.0422, +0.0309, +0.4093, -0.2905, +0.1476, +0.8005, -0.0774, +0.1371, -0.0529, -0.1442, -0.0326, +0.5159, -0.1651, +0.1366, +0.1476, +0.2852, -0.4420, -0.3403, -1.1074, +0.2820, -0.4842, -0.2464, -0.9850, +0.2316, -0.7857, +0.5891, -0.1194, -0.3680, -0.6987, +0.4992, +0.5802, -0.2089, -2.3145, -0.8983, +0.2000, +0.2328, +0.1504, -0.9694, -0.0397, +0.5221, +0.2330, -0.5433, -0.5676, -1.0922, +0.3621, -0.4841, +0.2218, -0.1468, -0.2117, -0.1497, -0.0331, -0.4497, -0.3092, -0.4888, +0.4701, -0.6076, +0.2927, +0.2463, +0.0962, +0.4161, +0.2268, -0.1202, +0.7343, +0.3379, +0.3461, -0.0830, +0.0510, -0.1624, -0.2082, +0.5592, -0.1132, -0.0248, -0.3746, +0.2488, -0.2618, -0.7138, -0.8501, -0.6333, +0.1322, -0.7100, +0.1321, -0.7706, +0.2088, +0.0503, -0.0784, +0.2525, -1.4688, +0.1988, -0.1214, -0.7245, +0.0321, +0.0732, -0.0386, +0.0683, +0.3169, +0.1711, +0.1284, -0.3320, +0.0664, -0.2360, +0.2742, +0.0370, +0.1123, +0.3008, +0.0063, -0.9690, -0.1391, -1.2992, +0.2320, -0.8184, -0.0203, -1.3783, +0.1210, -0.0003, -0.5927, +0.1050, -1.0701, -0.0294, +0.4847, -0.3004, +0.3503, -0.3461, -0.0561, +0.2380], +[ +0.3711, -0.5122, +0.3078, +0.0482, +0.6545, -0.8755, +0.6540, +0.0361, -0.1457, +1.1641, +0.0596, -0.1890, +0.3317, +0.1001, -0.2053, -0.4404, -1.2854, -1.4911, +0.2391, -1.8613, -0.0210, +0.3602, -1.2691, -0.5337, -0.3914, +0.1565, -0.1174, -0.0831, -0.4771, -0.0826, -0.0608, -0.3441, -0.1007, -0.8418, -0.5199, -0.1941, -2.3056, +0.0221, +0.4960, -0.5980, -1.6187, -0.4539, -0.0842, -1.0271, +0.5722, +0.1285, +0.0500, +0.3821, +0.2063, +0.1320, -0.0600, -0.1402, -2.6885, +0.1343, +0.3053, -0.8118, +0.2949, -0.2179, +0.0871, -0.2730, +0.5062, -1.1280, +0.0665, -1.2273, -0.5753, -0.4810, +0.1590, +0.6403, -0.8059, +0.4987, -1.2487, +0.1267, -0.1181, -1.5417, -0.2113, +0.0210, +0.4132, -1.4785, -0.5953, +0.2741, +0.6321, +0.4405, -0.3417, +0.1373, -0.2862, -0.5855, +1.0328, +0.2625, -0.2791, -0.8597, -0.3383, +1.1336, -0.7141, +0.0972, -1.1505, -0.1554, +0.4601, -0.3757, -0.1693, -0.5801, -0.1438, -1.8935, -0.0646, -0.5465, -0.4190, -0.0872, +0.1621, -1.1848, -0.4613, -1.3268, +0.1992, -0.3329, +0.3877, +0.4914, -0.2977, +0.0102, -0.0888, -1.0388, -0.3733, -1.0903, -0.2616, +0.4798, -0.0164, -1.3258, -0.2859, -0.7703, -0.0513, +0.1921], +[ -0.4288, +0.4251, -0.8418, +0.2533, -0.2653, -0.3997, -1.4284, +0.1745, -0.1872, -0.2045, +0.1453, +0.0717, -0.1374, +0.3480, -0.1474, -0.0239, +0.3027, +0.1502, -0.0728, +0.1668, -0.1015, -0.2752, -0.8042, -0.9138, +0.2101, -0.4770, +0.2333, -0.7844, +0.1624, -0.2283, +0.4549, -0.1719, -0.6743, -0.2464, -0.0733, +0.1715, -0.3638, -2.5636, +0.0812, -0.1348, +0.2581, +0.1219, -0.0507, -0.4468, +0.7635, -0.3612, +0.3942, +0.2470, +0.2363, +0.2047, -0.4177, +0.2005, -0.3347, -0.3090, -0.0926, -0.1653, +0.1673, -0.7612, +0.5780, +0.0328, -0.2601, -0.0094, +0.2529, +0.3364, -0.2499, +0.1589, +0.3585, -0.0452, -0.3698, +0.2585, -0.5148, -0.0327, -0.3892, -0.6538, +0.0538, +0.0272, -0.0580, +0.0795, -0.0597, -0.5941, +0.0464, -0.1051, -0.2354, -0.4521, -0.2243, -0.2938, +0.0795, +0.0080, -0.2831, +0.0473, +0.2404, +0.3361, +0.0059, +0.5983, +0.2747, +0.7289, +0.2341, -0.4635, -0.4206, +0.4859, +0.0844, -0.9279, +0.4085, +0.2349, -0.0769, +0.1156, -1.2277, +0.1506, -0.5583, +0.2217, -0.0559, +0.6840, +0.1522, -0.2177, -0.2074, -1.2565, +0.4764, -0.2736, -0.8419, +0.4239, -0.8196, -0.1434, +0.1341, -1.6368, -0.1080, -0.1508, +0.3498, +0.0597], +[ -0.3368, +0.2092, +0.5426, +0.2464, +0.4091, +0.1462, -0.2139, -0.0042, +0.2487, -0.3703, +0.6684, +0.2895, -0.2406, -0.0249, +0.1861, +0.8212, -0.3994, +0.2464, +0.3857, -0.2585, +0.5531, -0.4998, -0.3836, +0.2367, +0.3707, +0.1389, -0.5142, +0.1372, +0.4955, -0.4030, -0.2420, +0.0510, +0.0492, +0.1571, +0.0938, +0.3084, -0.8010, -1.0584, +0.4347, -0.2451, -0.2941, -0.6722, +0.1788, -0.1841, +0.1940, -0.1804, +0.1675, +0.4239, -0.0414, -0.1289, +0.1509, -0.0777, +0.1962, +0.0061, +0.5778, -0.5213, -1.1370, -0.3478, +0.7225, -0.5497, +0.1487, +0.5139, -0.1376, -0.4082, -0.6474, +0.2995, +0.2718, -1.0549, -0.5648, +0.2498, -0.0656, -0.6016, -0.0853, -0.0022, -0.9858, +0.5829, -0.2664, -1.0040, -0.1400, -0.9499, -0.3189, -0.9519, +0.2420, -0.4990, -0.1585, -0.2386, -0.3771, -0.4614, +0.3374, +0.9149, -0.1293, +0.1826, +0.1705, -0.5659, +0.0785, -0.2180, +0.3528, -0.4823, +0.4564, +0.4903, -0.4538, +0.4069, -0.1866, +0.0438, +0.0104, +0.0877, -0.0139, +0.0428, +0.7354, -0.0088, -0.1079, -0.3406, +0.0882, -0.2470, -0.3901, +0.0013, +0.3204, +0.0920, +0.0433, -0.0745, -1.8448, +0.1017, -0.2950, -0.3807, -0.4693, -0.1578, -0.0062, -0.9509], +[ +0.0735, +0.1321, +0.3943, -0.1060, -0.2087, +0.0374, +0.2031, +0.3275, -0.2623, -0.4766, -0.5651, -0.3270, +0.5977, -0.3862, -1.0126, +0.8957, -0.4264, -0.2896, +0.3246, -0.1566, +0.2141, -1.0416, +0.0665, +0.3242, -0.6463, +0.2869, -0.2468, +0.5867, -0.3243, -0.6057, +0.1175, -0.3758, -0.8298, +0.2636, -0.3871, +0.1890, +0.0788, -0.0283, -0.2311, -0.8094, -0.1637, -0.0869, -0.6365, -0.0403, -0.0636, +0.4252, +0.0832, -0.4041, +0.2266, +0.5261, -0.2208, +0.1190, +0.3236, -0.3321, +0.6679, +0.1548, -0.2739, -0.2599, +0.8133, -0.5076, -0.2133, +0.3947, +0.2446, +0.1589, -1.2893, -0.3493, +0.5011, -0.3098, -0.0777, -0.1097, +0.1047, -0.5573, +0.4166, -0.0184, +0.0405, -0.1612, -0.0876, +0.5153, +0.2051, +0.4426, +0.0784, +0.1342, +0.3865, -0.2819, +0.2431, -1.7776, -0.0231, -0.2412, -0.1342, -0.4856, +0.2141, +0.7703, +0.2504, +0.1393, -0.0915, +0.1368, -0.0667, +0.0242, +0.3334, +0.0918, -0.2404, +0.3281, -0.4851, +0.2643, +0.1716, +0.2915, -0.6321, -1.5506, +0.4295, +0.1463, +0.9801, -0.1069, +0.4641, -0.1582, +0.0235, -0.0070, -0.3506, -0.1147, -0.1624, +0.3232, -0.2713, +0.0645, -0.0997, +0.1111, -0.0303, -0.0156, -0.3195, +0.1981], +[ -0.3898, +0.4090, -0.2097, +0.1600, +0.9530, -0.0467, -0.5210, -0.6534, +0.2393, -0.5750, +0.0579, +0.0129, +0.0012, -0.3364, -0.6190, +0.4100, +0.4866, -0.1644, +0.3908, -0.2042, +0.6471, +0.3077, -0.4285, -0.1191, -0.3428, +0.3255, +0.1868, +0.3541, -0.3422, +0.0310, +0.0242, +0.3750, -0.6444, -0.1468, +0.5030, +0.3276, +0.3054, -0.0126, -0.5548, +0.3717, +0.1292, +0.1356, +0.0733, -1.4465, -0.2176, -0.1912, -0.4031, -0.1692, -0.8686, +0.2757, -0.1966, +0.3493, -0.6788, -0.3001, -0.7071, +0.1474, +0.1610, -0.5100, +0.1408, +0.0447, -1.2487, -1.2027, +0.5734, -0.8365, +0.8718, -0.0544, +0.3266, -1.3697, +0.1424, +0.2102, -0.4280, +0.2247, -0.2800, +0.4358, +0.2002, +0.3223, +0.0825, +0.2227, +0.2776, -0.7352, +0.0881, +0.1030, +0.1458, -0.9093, -0.4533, +0.3908, +0.2786, +0.0234, +0.0198, +0.1295, +0.1039, -0.1075, -0.7748, +0.2882, -0.7246, +0.6064, +0.4672, -0.3293, -0.8341, +0.4853, +0.1837, -0.0405, -0.2606, +0.8020, +0.5313, +0.0470, -0.1615, +0.3864, -0.5154, +0.3749, -0.2012, -0.2818, +0.4120, -0.3524, -0.3061, -0.0957, -0.2543, +0.1877, -0.9297, -0.3793, -0.4868, +0.0211, -0.2999, +0.4195, +0.3744, -0.4142, -0.1698, +0.4015], +[ -0.0032, -0.1157, -0.7626, -0.0068, -0.1563, -0.2504, +0.2543, +0.2672, -0.6115, -0.1193, -0.0808, +0.1192, -0.2597, +0.1511, +0.3637, -0.3866, +0.5929, +0.4882, -0.2581, +0.1825, -0.4854, -0.0445, +0.2782, +0.1469, -0.1412, -0.3135, -0.6042, -0.1404, -0.0105, +0.0360, +0.3121, -0.8642, +0.6442, +0.7403, -0.1205, -0.5401, +0.0028, -0.0572, +0.2258, -0.0124, +0.0772, +0.0219, +0.3767, +0.4778, +0.2339, -0.0446, -0.1991, +0.4794, +0.1058, -0.2104, -0.4589, +0.0639, +0.5277, -0.6294, -0.3231, +0.3277, -0.0388, +0.1474, -0.5446, +0.3626, +0.7244, -0.2283, -1.0641, -0.1651, +0.3294, -0.3860, +0.3972, +0.5262, +0.2624, +0.8364, +0.0352, -0.0869, +0.0968, -0.2432, +0.3734, +0.2818, +0.1536, -0.0855, +0.7703, -0.2547, -0.0042, +0.4066, +0.3864, -0.0546, -0.1226, +0.4063, +0.0661, -0.0131, -0.9015, -0.3502, -0.3724, +0.2265, -0.3302, -0.4852, +0.0126, +0.4551, -0.9050, +0.4911, -0.2053, -0.0778, +0.1277, -0.5993, -0.0439, -0.0805, -0.2957, +0.0837, -0.2367, -0.2302, -0.3742, +0.2723, -0.4829, -0.6283, -0.0074, -0.1597, +0.7585, -0.1683, +0.1012, -0.5039, +0.1081, +0.4095, -0.0830, +0.2724, -0.1499, +0.1271, -0.1143, +0.4757, +0.7004, -0.0638], +[ +0.5604, +0.1489, +0.7939, +0.0495, -1.6573, -0.0948, +0.0507, -0.2181, -0.8301, +0.2946, -0.8348, +0.0103, -0.0534, -1.9317, +0.3094, +0.4461, -0.5899, +0.0193, +0.8027, +0.2224, +0.3142, -0.0909, +0.1901, +0.3415, -0.7243, +0.1823, +0.1726, +0.4332, -0.1833, +0.0276, +0.4527, -0.4807, -0.2075, +0.1518, +0.4846, +0.0998, +0.0544, -0.0686, -0.2238, -0.6958, -0.3039, -0.0180, -0.8097, -0.0506, -0.0706, +0.0831, +0.1330, -0.4893, +0.3243, +0.3210, +0.1427, -0.1627, +0.1470, -0.4862, -0.2567, +0.3008, +0.0347, -0.1611, -0.7610, -0.2009, +0.1149, +0.2351, +0.4647, -0.5399, -0.3643, +0.2018, -0.0247, +0.0455, +0.0261, +0.2084, +0.2071, -0.0061, +0.5638, +0.4168, +0.1248, -0.0494, -0.5499, +0.1191, -0.3897, -0.8652, -0.0281, -0.0855, -0.0485, -0.0882, -0.3547, -0.2732, +0.5744, +0.3363, +0.2781, +0.1670, +0.2282, +0.1124, -0.0644, +0.2288, -0.0276, -0.4266, +0.1707, -0.0295, +0.0060, -0.0297, +0.0298, -0.0614, +0.0064, -0.0780, -0.1962, -0.3330, +0.1126, -0.1496, -1.5588, -0.1446, +1.0634, +0.0322, +0.0421, +0.2496, +0.0028, -0.3989, +0.2559, -1.1919, +0.4706, +0.1022, +0.6683, -0.5075, +0.3810, +0.0101, -0.0736, +0.3099, -0.1884, -0.0315], +[ -0.1955, -0.5094, +0.1636, -0.1839, -0.8500, +0.0869, -0.3795, -0.0824, +0.1572, +0.5188, +0.1795, -0.1984, +0.1677, +0.3621, +0.1295, -0.3444, +0.6014, +0.1478, -0.0711, -0.2961, +0.0910, +0.1848, +0.2503, -0.2125, -0.3327, +0.2299, -0.5543, -0.7245, -0.2514, +0.3123, +0.2954, +0.0990, +0.2281, -0.0702, +0.2690, -0.2279, -0.3561, -0.2342, -0.2415, +0.2229, +0.4394, -0.1579, +0.2719, -0.1974, -0.0336, +0.2625, -0.5710, -0.0972, -0.3365, +0.0324, +0.3265, +0.1474, -0.3497, +0.1704, -0.0507, -0.0087, -0.8585, -0.0940, -0.6150, +0.2710, +0.6073, -0.6070, -0.2289, -0.5282, +0.3340, -0.3444, -0.0644, -0.8340, -0.3540, -0.1502, +0.2084, -0.3327, -0.0523, +0.1642, -0.7461, -0.1801, -1.0584, -0.4991, -0.3224, +0.1219, -1.1949, -0.5131, -0.0919, -0.5761, +0.0495, -0.2821, +0.1686, +0.0202, +0.2129, +0.2013, -0.9683, -0.1908, -0.1073, +0.3261, +0.1326, -0.1326, -0.5122, -0.1264, +0.0474, +0.0922, -0.2146, +0.1663, +0.1091, +0.0349, +0.1768, +0.1695, -0.1796, +0.3195, -0.3877, -0.2224, -0.2449, +0.3745, +0.1159, -1.2097, -0.0515, -0.3228, +0.2604, +0.2458, -0.5800, -0.3306, -0.6286, -0.3607, -0.4681, -0.8831, -0.2818, -0.2989, -0.3671, -1.1921], +[ +0.1324, -0.4846, +0.3543, -0.4279, +0.0218, +0.2834, +0.1271, -0.2439, -0.5697, +1.1672, +0.1293, -0.1005, +0.3387, -0.7602, -0.4949, -0.1251, +0.2813, -0.1402, +0.0073, +0.4846, -2.0272, -0.0837, -0.1081, -0.1338, -0.0291, -0.0520, +0.1935, +0.1562, -0.4019, -0.2690, +0.1373, -0.2031, +0.1697, -0.0621, +0.1849, -0.8227, +0.3108, +0.0454, +0.2020, -0.3821, -0.2381, -0.1363, +0.0512, -0.5040, +0.1104, -0.3400, -0.5262, +0.5317, -0.4527, -0.8015, -0.0089, +0.0263, +0.1689, +0.0380, -0.1424, +0.3908, -0.0995, -0.1746, +0.4555, +0.2764, +0.2897, -0.1100, -0.4770, -1.0901, +0.3817, +0.3746, -0.6783, +0.2379, +0.9173, -0.1580, +0.1852, +0.6157, -0.1961, +0.1422, -0.9707, -0.4440, -0.0112, -0.3850, -0.2027, -0.0332, -0.7040, -0.4630, +0.6232, -0.4129, -0.3921, +0.2035, -0.0832, +0.5634, +0.0469, +0.0092, -0.1565, -0.0481, -0.2951, -0.0111, -1.7074, +0.1362, +0.1502, +0.2415, +0.0590, -0.0583, +0.3007, +0.2916, -1.0366, -0.1694, -0.5418, -1.1429, +0.1295, +0.1362, +0.0207, +0.0179, -0.5855, -0.1739, -1.1501, -0.1732, +0.6585, +0.3460, -0.4667, +0.0654, -0.3989, -0.0483, -0.3596, -0.4865, -0.1731, +0.3521, +0.3019, -1.1546, +0.1897, -0.0856], +[ +0.0735, -0.0567, -0.8032, -0.4114, -0.6058, -0.2193, +0.6009, +0.6099, +0.1714, +0.1384, +0.1317, +0.5786, +0.1662, -0.1301, +0.6285, +0.2156, +0.0117, -0.5567, +0.0561, -1.0620, -0.1751, +0.1477, +0.3508, +0.0661, -0.0849, +0.2782, -0.0713, -0.0370, -0.3821, +0.1062, -0.0948, +0.0361, +0.3888, +0.4089, -0.4191, -1.8165, -0.2541, -0.0063, -0.5197, +0.4507, +0.7076, +0.2521, -0.1259, -0.1574, +0.0586, +0.3146, +0.1439, -0.4246, +0.4805, -0.1064, +0.3108, -0.1860, -0.0510, -1.1670, +0.3645, +0.0356, -0.2300, +0.2261, -0.4346, +0.3613, -0.8356, -0.4161, +0.0780, +0.1070, +0.1950, -0.8652, -0.1801, -0.2838, -0.5130, -0.7402, -0.4372, -0.3082, -0.1407, +0.0451, +0.4333, +0.5375, -1.4056, -0.1902, -0.0910, -0.1582, -0.1891, -0.2806, -0.6402, -0.4763, +0.2221, -0.2245, -0.5862, +0.2639, +0.3936, -0.3819, +0.3230, -0.8123, -0.5992, -0.1648, +0.8798, +0.2127, -0.5322, -1.0589, -1.3485, -0.6906, -0.0448, -1.2024, +0.1072, +0.2755, -0.5748, +0.0877, +0.2745, +0.0640, +0.2661, -0.3139, +0.2355, +0.4331, +0.3440, +0.4860, -0.3379, +0.5891, +0.2155, -0.3365, +0.3805, +0.2537, -0.6251, -0.0326, +0.1532, -0.0125, +0.1749, -0.3645, -0.9793, +0.0434], +[ -1.1930, +0.5646, -0.9985, -0.2640, -0.1287, -1.0951, +0.0648, +0.2532, -0.4144, -0.4100, -0.0835, +0.2912, -1.2506, +0.1132, -1.2571, -0.0902, +0.6812, -0.3145, +0.0854, -0.5571, +0.0128, +0.2900, -0.5539, +0.0010, -0.4862, +0.2361, -1.2377, -0.6221, +0.1594, +0.1456, -0.0369, -0.6333, +0.1119, -0.1009, -0.0694, +0.1564, +0.5584, -0.0073, -0.3532, +0.1511, -0.2448, +0.3191, +0.0510, -0.7811, +0.0116, -1.3001, +0.0963, -0.2932, +0.2152, +0.6290, -0.3466, -0.2318, -0.4833, -0.9795, +0.1221, -0.1789, -0.4434, +0.3625, +0.1297, -0.2875, +0.1629, +0.2148, +0.3416, +0.3896, +0.4758, -0.2505, +0.0288, +0.5394, +0.1399, -0.0757, +0.1861, -0.4772, -0.2275, -0.4032, +0.2681, -0.2982, +1.1032, -0.2331, -0.1047, +0.3253, -0.1822, -0.1980, +0.0089, +0.3273, +0.0098, -1.1442, +0.0552, -0.8381, -0.4844, -1.0339, -0.0695, +0.3731, +0.3991, -0.7210, -0.7972, +0.0382, -0.1339, -0.0447, +0.0631, -0.0759, +0.3365, +0.2942, -0.5237, +0.1108, +0.2281, +0.4007, -0.1869, -0.0529, -1.0671, -0.0356, -0.7960, +0.0457, +0.2884, -1.2189, -0.0712, +0.6715, -0.1247, -0.5548, +0.0852, +0.2519, +0.1606, +0.1365, +0.4946, -0.6133, +0.0761, -1.3449, +0.5933, -1.1779], +[ -0.2804, -0.5471, +0.0551, -0.9886, -0.3381, +0.0967, -0.1828, +0.3549, +0.8853, -0.4441, -0.3885, -0.3878, -0.1378, -1.2579, -0.5911, -0.0165, +0.4075, -0.2342, +0.1255, -0.4637, -1.2356, +0.0905, +0.5726, -1.2384, +0.3039, -0.1166, +0.9449, -0.1286, -0.1615, -0.6373, -0.6342, -0.7324, -0.4217, -0.2331, -0.1038, -1.9344, +0.2348, -0.1012, +0.1137, -0.0832, -0.7858, -0.3082, -0.1527, +0.0916, +0.0603, -0.5602, -0.3892, +0.4406, +0.0072, +0.5934, -0.2114, -0.5871, +0.7619, +0.4133, -0.8720, -0.3605, +0.0495, -0.0443, +0.0407, +0.0590, +0.0571, -0.9888, +0.5016, +0.0917, -1.0617, -0.1703, +0.3349, -0.3760, -0.4340, +0.6685, +0.3912, +0.2040, -0.1057, -0.1511, +0.2123, +0.4670, +0.1919, -0.3246, -0.4883, -0.0083, -0.8998, -0.7696, +0.5723, +0.2926, +0.2666, -0.2535, +0.2142, +0.2284, +0.8592, +0.1695, +0.1796, +0.3706, +0.5187, +1.1045, -0.3000, +0.3547, -0.7726, +0.2280, -1.3668, +1.2893, -0.2239, -0.2915, -0.9778, -0.0967, -0.2130, +0.3331, +0.1535, +0.3457, -0.6926, +0.8179, -0.4072, +1.5560, +0.2476, -0.0502, +0.5784, +0.6010, +0.2252, -1.1767, +0.0105, -0.9442, -0.8745, +0.1999, -1.4982, +0.2176, -0.0420, -0.7675, +0.0954, +0.8451], +[ -0.4607, +0.9224, -0.0666, +0.2874, +0.0829, -0.2010, -0.0345, -0.9402, +0.4678, -0.1414, -0.6691, -0.3298, -0.8264, -0.1855, +0.1957, +0.0315, +0.3370, -0.0251, +0.2687, +0.2016, -0.8409, +0.4957, -0.0033, -0.3533, -0.0471, +0.1057, +0.4238, -0.7189, +0.2092, -0.5275, -0.1519, +0.8259, +0.1368, -0.0003, +0.6165, +0.0160, +0.3227, -0.0074, -0.4793, -0.4458, -0.6210, +0.1793, +0.0263, +0.6392, +0.0782, +0.1148, +0.1563, +0.6285, -0.0923, -0.1974, -0.1243, -0.0663, -1.0275, +0.1073, -1.0154, -0.3729, -0.0186, +0.1367, +0.3499, -0.1006, +0.3770, -0.4031, -0.6277, -0.2577, -0.5225, -0.4877, +0.0720, -0.5231, -0.5414, +0.0301, +0.1047, -0.2830, +0.5737, -0.2476, -0.5488, -0.5124, -0.1490, +0.1823, +0.2839, -0.1406, -0.5689, -0.3808, -0.1889, -0.4013, -0.4741, -0.3185, -0.1529, -0.7650, -0.2723, -0.5697, +0.4438, -0.1550, +0.3837, +0.1311, -0.5736, +0.1836, -0.1597, +0.1093, -0.4329, -0.6388, -0.4136, -0.0996, -0.5276, +0.1312, -0.1520, +0.0417, -0.1222, +0.1583, -0.2679, -0.7778, -1.3841, +0.0280, -0.4868, -0.3024, -0.0940, +0.2621, +0.1358, +0.3894, +0.1022, -0.8691, -0.2127, +0.3902, -0.8880, +0.2733, -0.3573, -0.1029, -0.2447, +0.1657], +[ +0.1771, -1.0649, +0.1922, -0.4930, +0.2546, -1.6105, -0.1822, +0.4909, -1.8516, -1.1523, -0.4807, +0.1944, -0.5609, -0.5628, +0.0320, -0.8651, +0.5125, -0.1112, -0.7384, +0.4523, +0.0384, +0.2800, +0.1029, -0.3131, +0.2663, +0.0665, +0.3445, +0.3239, -2.2262, -0.7737, -0.4730, +0.1132, -0.2555, -0.4740, -0.8098, -0.5930, +0.1079, -0.0022, -0.0244, +0.0345, -0.4886, -0.1646, -0.7892, +0.2974, -0.0426, -0.3042, -0.9469, -0.8653, -0.2788, -0.3556, -0.5344, +0.1168, -0.8683, +0.1483, +0.5287, +0.1890, +0.0854, +0.0945, -1.1579, -0.1664, -0.0890, +0.1049, -0.7604, -0.3063, +0.7497, -0.9224, +0.0295, -1.3473, -0.8716, +0.4510, -0.4206, -0.0661, -0.6026, -0.0489, +0.1988, -0.9539, -0.0979, +0.1267, +0.1407, -2.0032, +0.2541, +0.4513, +0.2627, -0.4517, -0.1051, -0.5941, -0.5248, +0.0565, -0.0243, -0.9744, +0.5845, +0.0379, +0.4668, -0.3622, +0.3820, +0.4215, -0.6691, +0.0417, -1.6526, -0.4631, -0.4563, -0.2545, -0.2057, -0.0443, +0.4281, -0.9920, -0.5481, -0.8264, +0.6692, +0.0857, -1.2917, +0.1586, +0.0600, -1.4808, -0.1486, -0.1216, -1.2193, +0.4264, -0.8464, -0.6857, -0.0517, +0.0287, -0.1867, -0.6775, -0.3675, +0.5128, -1.5418, +0.2499], +[ -0.1612, -0.4239, -0.3609, -0.4407, -1.8796, +0.1811, +0.1288, -0.0542, -0.9194, +0.3582, +0.1502, +0.1751, -0.0533, -0.0531, -0.0382, -1.2325, -1.2668, +0.6905, -0.0798, +0.1129, -0.3606, -0.5942, +0.2636, -0.1080, -0.2369, -0.0980, -0.3586, +0.0497, -0.6267, -0.2695, +0.7429, -0.0488, +0.5714, -0.6892, -0.8693, +0.1249, -0.7356, -0.1495, +0.1155, +0.4590, +0.5223, -0.5127, +0.1505, +0.2809, +0.2153, +0.7752, -0.1908, -0.6606, +0.2257, +0.0174, +0.0978, -0.5091, -0.6323, +0.1803, -0.3168, -0.3116, +0.0962, -0.0341, -0.0762, +0.6551, -0.3391, +0.4467, +0.3393, -0.4190, +0.5773, -0.4536, -0.6370, +0.0585, +0.0999, -0.1559, +0.5472, -1.2403, -0.1902, -0.0791, -0.3356, -0.0231, -0.3575, -0.0715, +0.3344, +0.1620, -0.4599, -1.0161, -0.0755, +0.3601, -0.6676, +0.2324, -0.4592, -0.2415, -0.4137, +0.0879, -0.0214, -0.6427, -0.7533, -0.3647, -1.3776, -0.3563, +0.1488, +0.5039, -0.7781, -0.0703, -0.6032, +0.0771, -0.1891, -0.5058, +0.1018, +0.4503, -0.7568, -0.2828, -0.4956, +0.4676, -1.1091, +0.5466, -0.5813, -0.6780, +0.3361, -0.6156, +0.2207, +0.3111, +0.0996, -0.6625, +0.3951, -0.6766, +0.1181, +0.9436, +0.0373, -0.3188, -0.2978, -0.5654], +[ +0.0668, -0.3408, -0.1976, +0.4520, -0.7920, -0.0620, -0.5180, +0.3705, +0.3587, -0.0448, -0.0541, -0.4324, -0.2409, +0.2633, -0.1210, -0.5174, -0.0161, -0.2320, -0.5553, -0.0265, -0.0198, +0.0403, -0.1374, -0.2721, -0.4634, -0.1764, -0.4010, -0.8389, +0.0032, -0.2553, -0.0130, -0.3559, -0.3330, +0.4345, +0.0551, -0.4100, +0.2560, +0.1938, -0.1803, -0.6254, +0.4951, -0.6375, -0.0450, +0.2914, +0.2987, -0.4416, -0.6367, -0.0493, -0.2898, -0.2539, -0.5301, -0.2232, -0.4586, -0.2803, +0.3026, +0.2851, -0.3451, +0.3517, -0.6863, -0.1376, -0.6062, -0.7945, -0.0853, -0.1367, +0.3939, +0.0591, +0.1730, +0.6343, +0.5698, +0.1005, -0.3372, +0.3566, +0.2433, -0.4498, +0.1536, -0.3045, -0.4275, +0.1514, +0.1296, -1.0830, -0.2265, +0.7224, -0.0265, -0.0444, -0.4194, -1.2595, +0.0165, +0.3162, -0.3852, -0.3603, -0.3801, +0.0952, -0.0012, +0.0985, -0.5196, +0.0584, +0.2641, -0.0625, +0.1562, -0.6879, -0.5486, -0.6414, -0.3643, +0.0262, +0.0134, -0.5337, -0.3427, -0.6458, -0.4454, +0.2579, -0.3257, -0.6284, +0.2397, -0.2731, -0.0075, +0.1768, +0.5291, -0.1539, +0.1083, +0.1832, -1.1263, +0.0974, +0.3043, -1.4778, -0.1009, +0.0417, -0.5630, +0.4801], +[ -0.6454, -0.7756, -0.4977, -0.8220, -1.1194, +0.0238, -0.4573, -0.0432, +0.6942, -0.1904, -0.0429, -0.5213, -0.3837, -0.1483, +0.1033, +0.3135, +0.4299, -0.1421, -0.6400, -0.0736, -0.4123, +0.0786, -0.0591, +0.0877, -0.2312, +0.4058, +0.0759, -0.5178, -0.7740, -0.4119, -0.2352, -0.6448, -0.2426, +0.6444, -0.0683, -0.9792, -1.3938, -1.5029, -0.7095, -0.2758, +0.0554, +0.1728, -0.1377, -0.2068, -0.3909, -0.4126, +0.5882, -0.2119, -0.2786, +0.3562, -1.0845, -0.5862, +0.0659, -1.8884, -0.0195, -0.0630, -0.0171, +0.3654, +0.2821, -1.0086, +0.3942, -0.0654, +0.1168, +0.4569, +0.3138, -0.1170, +0.3250, -0.5120, -0.6833, -0.9898, -0.2593, -0.2547, -0.4772, -0.4333, +0.0239, -0.1653, +0.2902, -0.1610, +0.1376, +0.1103, -0.3598, -1.0606, -0.3341, -0.1726, +0.2773, +0.5422, -0.1895, -0.4480, -0.2850, -0.3535, -0.6584, +0.2745, +0.0285, -0.2066, +0.4448, -0.9888, -0.1846, -0.1153, -0.1576, -0.1381, +0.3401, -0.7143, -0.3209, -0.0279, -0.3679, +0.2760, -0.4931, -0.3817, +0.7612, +0.2598, -0.0127, -0.0994, +0.4239, -0.8268, -0.5012, +0.2769, -0.6953, +0.1870, +0.2750, -0.8051, +0.2195, +0.6554, -0.9753, -2.0387, -0.1231, -0.4834, -0.4421, +0.5339], +[ +0.4335, +0.1656, -0.9974, -0.1176, -0.3960, -0.0638, +0.2079, +0.1231, -0.0854, -0.0827, +0.2503, -0.2978, -0.3204, +0.4953, +0.1134, +0.5835, +0.3386, -0.1330, +0.2271, -0.2615, -0.2089, -0.0507, -0.2240, +0.1935, +0.3242, -0.1012, -0.1488, -0.0782, -1.1263, +0.1241, +0.3369, -0.3031, +0.1686, -0.3965, -0.3629, +0.3934, +0.2049, -0.2970, +0.2818, -0.1164, -0.0679, -0.4821, -0.1474, +0.3424, -0.5797, +0.1040, -0.3827, +0.0046, +0.3052, -0.3735, +0.0795, +0.1228, -0.1774, -0.5957, -0.1294, +0.3470, +0.2718, +0.0017, +0.2303, +0.1612, +0.2331, +0.1641, -0.1593, -0.0877, -0.5581, +0.2669, -0.6158, +0.3496, +0.2728, -0.0912, -0.5599, -0.1258, -0.0708, +0.0594, +0.1851, -0.1625, -0.1608, +0.3045, +0.0633, -0.8487, +0.5131, +0.1964, +0.0798, -0.1822, -0.1556, -0.2373, -0.0818, -0.1272, -0.7765, +0.0968, -1.2447, -0.3894, +0.2402, +0.2558, -0.0405, -0.3095, +0.2425, +0.0121, +0.2948, -0.7793, +0.2155, +0.3195, +0.0075, -0.6360, -0.2475, +0.1176, +0.2035, -0.5655, -0.3994, -0.6486, -0.3726, -0.4562, -0.7920, +0.9645, -0.3052, +0.5184, +0.2414, -0.7075, -0.0663, +0.1578, +0.8090, +0.1994, +0.2978, +0.1654, +0.0228, +0.1505, +0.1746, -0.3233], +[ +0.3193, +0.0939, -0.2118, +0.6163, -0.0063, -1.3777, +0.0669, -0.1254, +0.4310, +0.0861, -0.1759, +0.2185, -0.1819, -0.3422, +0.1034, +0.2122, +0.1399, +0.1688, -0.4949, +0.0118, +0.6199, +0.0669, +0.1229, +0.3465, +0.1135, -0.1835, +0.0139, +0.0407, +0.3231, +0.2393, -0.0652, +0.6749, +0.0268, +0.1387, -0.2595, +0.2993, -0.0990, -0.4262, -0.2514, +0.3848, -0.2463, -0.1556, +0.1515, +0.1848, -0.4442, -0.2183, -1.3425, -0.2220, +0.4470, +0.0889, -0.1207, -0.0777, +0.5244, -0.2950, -0.1844, -0.0176, -0.0992, +0.0521, +0.3979, -0.9022, -0.0738, +0.5636, +0.2176, +0.0760, +0.2633, -0.0544, +0.1360, -0.0387, -0.1706, -0.3108, -0.8670, -0.3537, -0.3533, -0.6687, -0.2000, -0.3473, +0.1711, +0.4867, +0.1795, -0.3960, +0.1990, -0.1117, -0.2524, +0.4683, +0.7174, +0.1119, +0.5589, -1.3097, +0.8495, +0.1438, -0.4314, -0.3728, -0.6224, -0.3955, +0.7276, +0.7996, -0.4632, -0.5398, +0.3639, +0.3985, -0.0895, -0.3919, -0.2611, +0.1941, -0.0824, +0.0592, +0.8058, -0.4699, -0.3778, -0.2650, +0.2874, -0.3255, -0.2280, -0.1563, +0.4553, -0.1038, +0.7102, +0.2857, -0.6250, -0.5684, +0.1135, -0.0182, +0.0845, -0.0283, -0.3868, -0.5412, -0.2434, -0.1659], +[ -0.0464, +0.5243, -0.4781, +0.2690, +0.1849, -0.3429, +0.3832, -0.3084, -0.1094, -0.0967, +0.1260, -0.1243, -0.1423, -0.1049, -0.2899, -0.3276, +0.6179, -0.1143, +0.2727, +0.4459, -0.0010, +0.1593, +0.1067, -0.7444, +0.1892, -0.3649, +0.3654, +0.1727, -0.3584, -0.4054, -0.0355, +0.0589, +0.3136, -0.6080, -0.4424, -1.1500, -0.2929, -0.1218, +0.0851, +0.1286, -0.1481, -0.0944, +0.0483, +0.3923, -0.6804, -0.2047, -0.1822, -0.3020, +0.4498, -0.1132, +0.1351, -0.2379, +0.3005, -0.2661, -0.0353, -0.3425, +0.1234, -0.3196, +0.3445, -0.6262, +0.2050, -0.4626, +0.2234, +0.0922, +0.4025, +0.2875, -0.4980, +0.2534, +0.4041, -0.5816, -0.3658, -0.3838, -0.2730, -0.8847, -0.5349, +0.4322, -0.2092, +0.2194, -0.5464, -0.0687, -0.7599, -0.0938, -0.5080, -1.0531, +0.5433, -0.4617, +0.3173, +0.4012, -0.0094, +0.3008, -0.1310, +0.2291, -0.3119, -0.0245, -0.1378, -0.5103, +0.0308, -0.5093, -0.0109, -0.8061, -0.5017, -0.3643, +0.5121, -0.8432, -0.7076, +0.5774, +0.6549, -0.7813, -0.0083, -0.2012, +0.1741, -0.3110, -0.2896, +0.2991, -0.6618, -0.0971, +0.1034, +0.1374, +0.8942, +0.0567, -0.1838, +0.7772, -0.0397, -0.0103, -0.4255, -0.1541, +0.3253, +0.1915], +[ -0.2430, -0.4043, +0.1766, +0.0398, +0.0914, -0.3983, +0.1439, +0.1795, +0.2706, +0.3679, +0.1778, -0.2966, +0.0740, -0.1158, -0.1662, -1.3763, +0.0125, +0.1487, -0.3066, -0.2777, +0.0985, +0.1373, +0.2813, +0.1631, +0.0871, -0.0837, -0.0411, -0.4317, +0.5459, -0.2093, -0.5389, +0.1417, -0.4010, +0.0224, +0.1920, +0.2597, -1.4467, +0.4732, -0.0835, -0.3698, +0.1804, +0.3861, -0.8786, +0.0130, +0.0713, +0.1911, +0.0763, +0.1476, -0.3351, +0.3152, +0.1109, +0.3021, +0.0581, +0.4585, -0.1141, +0.0913, -0.3624, +0.2428, -0.1251, +0.0972, +0.1378, +0.1701, -0.3600, -0.3366, +0.0519, +0.2137, -0.0586, -0.2494, -0.2853, +0.4357, +0.0171, -0.2218, -0.7087, +0.2661, -0.3040, -0.1467, -0.4746, -0.3447, -0.8009, +0.0269, -0.1932, -0.0666, -0.1277, -0.0639, +0.4825, -0.8051, -0.0217, +0.1795, +0.0144, -0.4030, -0.2109, -0.1861, +0.1756, +0.4672, -0.1331, +0.2954, +0.0176, +0.2001, +0.0948, +0.4184, -0.9002, +0.3168, -0.3742, +0.2870, -0.1890, -0.2389, +0.6784, -0.4299, -0.5234, -0.2825, +0.0168, -0.3289, +0.5472, +0.0703, +0.2210, +0.3631, +0.4255, +0.2899, -0.3018, -0.1029, +0.2479, +0.1401, -0.3799, -0.1869, +0.2482, -0.0682, -0.3796, -0.0130], +[ -0.4788, +0.2948, -0.0242, +0.0233, +0.2287, +0.0991, -0.4801, +0.7143, +0.7220, -0.4549, +0.3487, -0.0855, -0.0851, -0.6122, -1.1795, -0.0827, -0.0839, -0.6036, -0.9077, +0.0458, +0.2859, +0.0758, -0.2018, -0.0300, +0.0544, +0.4906, +0.3798, -0.4791, -0.1694, -0.0224, -0.4815, -0.1661, -0.5559, +0.3484, -0.0509, +0.1270, +0.4359, -0.0170, +0.3239, +0.1996, -0.0626, -0.5734, +0.0043, -0.0116, +0.2306, -0.2151, -0.8066, -0.6628, -0.2044, -0.1113, +0.2094, +0.2780, -1.2293, +0.1742, -0.6659, +0.2707, +0.2288, +0.5875, +0.0937, -0.0826, +0.1510, -0.0347, -0.2975, -0.9115, +0.0580, +0.2950, +0.1988, +0.1708, +0.1293, +0.1360, -0.2675, -0.3640, -0.0489, -0.3411, -0.0149, +0.0747, +0.4562, -0.0167, -0.2461, +0.5418, +0.0244, -0.5008, +0.3172, +0.3555, -0.0258, -1.2760, +0.0538, -0.5143, -0.1031, +0.2422, -0.0139, +0.2600, +0.3610, +0.3186, +0.1357, -0.5968, +0.0320, +0.0657, -0.1833, -0.0577, -0.0921, +0.1382, -0.0592, +0.0876, -0.0436, -0.2665, -0.1702, -0.0775, -0.1017, -0.1287, +0.4811, -0.1845, +0.3371, -0.7259, -0.0593, +0.2927, -0.1583, +0.1932, +0.1477, +0.0772, -0.9719, -0.1581, +0.2555, -0.0088, +0.2792, -0.2661, +0.0771, -0.0628], +[ -0.1205, +0.0738, +0.5668, +0.3952, +0.2991, -0.2343, -0.2425, +0.3841, +0.1064, -0.7505, +0.1889, +0.2206, +0.4329, -0.0102, +0.5949, +0.1324, +0.1983, +0.5530, -0.0399, +0.0467, +0.3105, +0.0241, +0.0438, -0.1896, -0.5775, +0.2109, +0.2776, -0.3537, -0.6479, +0.2617, +0.5693, -0.0925, +0.3954, -0.1472, +0.4712, +0.1076, +0.1822, +0.5363, -0.2732, -0.0041, +0.0766, +0.2539, +0.2578, -0.0138, +0.2948, -0.0362, -0.0785, -0.2411, +0.2752, -0.9657, +0.0666, +0.2308, -0.2310, +0.0951, -0.4527, -0.0697, +0.0239, -0.0487, -0.4776, +0.3036, -0.0820, -0.4492, +0.3268, -0.6473, -0.1562, -0.1372, -0.4948, -1.4579, +0.1958, +0.0605, +0.2382, +0.0434, -0.3164, +0.0126, -0.1310, +0.1430, +0.1571, -0.7431, +0.1440, -0.1454, -0.2756, +0.1328, -0.3722, -0.5365, +0.1636, +0.4522, +0.6084, +0.2015, -0.7049, -0.8863, -0.8337, -0.0482, +0.1404, -0.0012, -0.5127, -0.3220, -0.7337, -0.4108, -0.0388, -0.7985, +0.3413, -0.8897, -0.0404, -0.3497, -0.1888, -0.0018, -0.3787, -0.5566, -0.6240, +0.0503, +0.2438, -0.4712, -0.3124, -1.2848, -0.2774, -0.3625, -0.0763, +0.0441, +0.5113, -1.0048, +0.1605, +0.0592, -0.0083, +0.2849, -0.0818, -0.4153, +0.4741, +0.0249], +[ -0.3259, -0.0924, +0.2141, -0.6682, +0.0653, -0.3126, +0.2141, -0.5372, +0.0619, +0.4928, +0.6802, -0.0303, -0.1073, -0.0185, -0.1252, +0.4509, +0.0839, -0.1281, -0.3127, +0.2805, +0.2024, -0.5651, +0.0838, +0.3462, -0.2815, -0.2832, -0.2357, -0.1275, +0.6727, -0.1054, -0.2455, +0.1086, -0.2943, -0.2398, -0.4691, +0.0847, +0.1380, -0.1887, +0.4670, -0.9059, +0.4327, -0.4259, -0.2343, +0.2994, -0.0059, -0.3699, -0.4257, -0.2617, -0.0120, -0.3947, +0.1851, -0.3750, -0.1081, -0.6665, +0.3328, -0.0758, -0.5060, +0.2679, +0.3259, -0.4441, +0.0263, -0.9864, -0.3219, +0.2595, -0.6472, +0.8043, -0.3170, -0.8339, -0.3836, -0.0252, -0.0801, -0.1906, +0.2606, +0.8412, -0.1107, +0.0706, -0.0642, -0.1641, +0.2282, -0.1386, -0.5176, +0.3356, +0.3406, -0.4221, +0.0099, -0.3131, -0.1490, -0.2464, +0.9962, -0.4005, -0.2326, -0.0511, +0.2822, -0.3473, -0.3058, -0.8731, +0.7910, +0.1322, -0.8155, -0.0386, +0.2808, -0.1292, -0.3470, -0.5239, +1.1692, -0.5421, -0.0557, -0.7708, -0.4259, +0.0206, -0.0570, -0.4799, -0.1320, +0.5666, -0.0914, -0.3411, -0.2026, +0.0413, -0.3290, +0.1876, -0.1087, -0.4253, -1.4439, -0.1898, -0.2367, +0.5706, -0.0462, -0.2875], +[ -0.5263, -0.5064, -0.4516, +0.2607, +0.0497, +0.4931, +0.2818, +0.1744, -0.4092, -0.1174, +0.5896, +0.1405, -0.3963, +0.1237, +0.2961, +0.2657, -0.0256, +0.3371, +0.0303, -0.4256, -0.3957, -1.3833, +0.2552, +0.5481, -0.0588, -0.1626, -1.3412, +0.2287, -0.0006, +0.3928, -0.4100, +0.2736, +0.4837, +0.2450, -0.6648, +0.3226, -0.4540, +0.1576, +0.0255, +0.4007, +0.1668, -0.5768, -0.5063, -0.7843, -0.2192, -0.1426, +0.0226, +0.0908, +0.3442, -0.5859, -0.0460, -0.1415, +0.1459, +0.2539, +0.0692, +0.1603, -0.9199, +0.1091, -0.5698, +0.3860, -0.2066, -0.2292, -0.0759, +0.4949, +0.1564, +0.1298, +0.1323, -0.4606, +0.4239, -0.0202, +0.4525, +0.0676, -0.0940, +0.7246, +0.1034, +0.4973, -0.0566, +0.2889, +0.1821, -0.8860, -0.2605, +0.1120, +0.1359, -1.6559, -0.0994, +0.1441, -0.2562, -0.0352, +0.2069, -0.2465, +0.7558, +0.5875, -0.2769, -0.4353, -0.8551, +0.0189, -0.3636, +0.5614, -0.1159, +0.6795, +0.2753, +0.1151, -0.0356, -0.3354, -0.8142, +0.3002, -0.0226, -0.1470, -0.3682, -0.5422, -0.3524, -0.0762, +0.3675, -0.1527, -0.0612, +0.2292, +0.5106, -0.1995, +0.2385, -0.0520, +0.7068, -0.4076, -0.3832, +0.0323, +0.5738, -0.1864, -0.4493, +0.1467], +[ -0.4268, -0.5872, +0.1827, -0.0295, -0.5556, -0.7391, +0.7044, +0.0806, +0.2893, -0.4276, +0.2567, -0.8649, +0.3852, +0.0466, +0.4104, -0.3009, -0.2069, -0.4436, +0.3243, +0.4523, +0.1035, -0.0934, +0.1396, -0.2971, +0.2776, +0.0283, -0.1412, -0.5667, -0.7793, +0.3937, -0.0179, +0.2908, -0.6341, -0.4567, +0.2814, -0.3609, -1.2294, -0.3265, -0.0420, +0.2264, +0.0654, -0.5900, +0.1255, +0.0563, +0.2543, -0.1010, +0.3539, -0.0393, +0.1338, -0.3963, +0.0427, -0.3492, -0.3314, -0.3047, -0.1329, +0.1481, +0.1273, +0.1482, -0.1715, -0.4490, -0.6341, -0.1411, -0.1587, -0.0418, +0.3699, -0.1815, +0.0967, -0.2825, -0.2781, +0.0213, +0.0603, +0.1463, -0.1261, +0.0788, -0.2587, -0.0294, +0.1550, +0.1917, -0.1985, +0.2772, -2.3317, -0.4041, -1.1275, +0.1741, -0.3849, +0.1296, -0.0309, +0.1997, -0.4544, +0.0789, +0.4179, +0.3871, +0.1782, +0.2553, -0.9304, -0.1356, -0.7131, -0.3142, +0.3308, -0.2094, -0.1491, +0.6618, +0.1643, +0.3704, -0.1532, +0.3060, -0.6095, +0.1046, -0.6198, -0.8268, -0.0314, +0.4699, -0.0570, +0.0696, -0.2731, -0.6359, -0.3539, -0.0665, -1.4877, -0.0778, -0.5318, -0.2568, -0.2785, +0.4667, -0.3807, +0.1290, +0.4132, -0.2281], +[ +0.4144, -0.2453, -0.6352, +0.0797, +0.4837, +0.1756, -0.1689, -0.0407, -0.1641, +0.3902, +0.1434, -0.0858, -0.3018, -0.3788, -0.4070, -0.4580, +0.5782, +0.1014, +0.0483, -0.4649, -0.8623, -0.2727, -0.0816, -0.0794, +0.3690, +0.2358, +0.1840, -0.5061, +0.4956, -0.0459, +0.1033, +0.1466, +0.4621, -0.2750, -0.5645, -0.7397, +0.5092, -0.2278, -0.3908, -0.8516, +0.0498, -0.1350, +0.0435, -0.7773, -0.0719, -0.3933, +0.3576, -1.1889, -0.1261, -0.3057, -1.5315, -0.0822, -1.0068, -0.1458, +0.1108, +0.1728, +0.6613, -0.0482, +0.1267, -1.9655, +0.2621, +0.6660, +0.1185, -0.2526, -0.8080, -0.2140, -0.1064, -0.8375, +0.0504, -0.3653, -0.4404, +0.1181, +0.4609, -0.3721, -0.6912, +0.4146, +0.6302, +0.0670, +0.3416, -0.0533, +0.2287, -0.1202, -0.0853, -0.4180, +0.6715, +0.0844, -0.2472, -0.6553, +0.0278, -0.1189, -0.5933, -0.8400, -0.7732, -0.4495, -0.1789, +0.4419, +0.3583, +0.2423, -0.3636, -0.5046, +0.0133, +0.1114, -0.2747, +0.4451, -0.2000, -0.3484, -0.2960, +0.3360, -0.5738, +0.0549, +0.0452, -0.0862, +0.0327, +0.9143, -0.0679, -0.5630, -0.3637, -0.5268, -0.2273, +0.3010, -0.2710, -0.2692, +0.1983, -1.2048, -0.1386, +0.0690, -0.0446, -0.4564], +[ +0.1738, +0.1187, -0.3066, +0.4367, +0.1442, -0.3168, -0.5278, +0.4796, -0.5142, +0.4568, -0.2377, -2.1440, +0.2173, -0.0282, -1.2387, -0.2722, -0.2450, -0.9980, -0.1381, +0.3996, -0.3626, -0.2866, -0.7293, +0.1695, -0.0305, -0.3145, +0.2440, -0.0217, +0.2407, +0.1341, +0.4644, +0.0791, -0.0324, +0.8154, +0.2003, -0.8524, -0.7770, -1.6000, -0.1595, -0.2486, +0.2989, +0.3587, +0.1625, -0.0403, +0.4665, -1.1816, -0.7108, -0.1961, -0.3279, +0.2137, -0.2674, -0.4244, -0.1972, +0.0484, -0.5213, +0.0114, -0.5583, -1.1815, -0.2730, -2.4739, +0.0351, -0.9367, +0.4868, -1.1313, -0.2428, -0.1098, +0.1168, +0.0097, -0.0091, -0.0988, +0.6567, +0.2903, -1.1361, -0.0712, +0.5666, +0.5488, +0.0187, +0.4147, -0.4554, -0.0554, -0.1015, -0.3783, -0.2677, +0.2319, -0.0162, -0.3072, -0.0450, -1.5145, -0.3145, +0.2317, +0.0531, +0.0717, -0.4312, -0.0905, +0.2989, +0.2484, +0.5011, -0.5255, +0.2265, -1.6048, +0.0203, -0.3383, +0.2683, +0.3878, -1.3090, +0.0639, +0.6891, -0.1080, -0.3280, -0.0528, -0.4217, +0.0452, -0.4198, -0.1554, -0.0454, -1.4473, +0.6277, -0.1168, -1.7838, +0.5812, -0.5257, -0.3076, -1.3098, -0.3146, +0.6357, +0.2521, +0.3271, -0.3130], +[ +0.0589, -0.6008, +0.6131, -0.0561, +0.1542, +0.2693, -0.6580, -0.4314, +0.3777, +0.6637, +0.0180, -0.2727, -0.2689, -0.0286, -0.1122, -1.1123, +0.4082, -0.6998, +0.3442, -0.5004, +0.7137, -0.0825, +0.1974, +0.0429, +0.0050, -0.9253, +0.1016, +0.4778, -0.1797, +0.1576, -0.4610, +0.1361, -0.2568, -0.3893, -0.5261, -0.2596, -0.3747, -0.9947, +0.9117, +0.0450, -0.0129, -0.0390, -0.2002, -0.6058, +0.4297, +0.8271, -0.3855, -0.3747, -0.1476, +0.2770, +0.1003, +0.1974, +0.4767, -0.1774, -0.1524, -0.4341, +0.3936, +0.3613, -0.1879, -0.5588, +0.1126, +0.0162, -0.0249, -0.2132, +0.1565, +0.2099, +0.2711, +0.6800, +0.3956, +0.1056, -0.1320, +0.3389, +0.6546, -0.2477, -0.7566, -0.6385, -0.8820, -0.7212, +0.0082, -0.0972, -0.5484, -0.6205, +0.2054, -0.6334, -0.1074, -0.4796, -0.2095, -0.3918, -0.0249, +0.0496, +0.6946, -0.8485, -0.7488, +0.1659, +0.1668, -0.6838, +0.4973, +0.0243, +0.3332, -0.6033, -0.0636, -0.2762, +0.3183, +0.0333, +0.0461, -0.5229, +0.1616, +0.2639, -0.7256, +0.3384, +0.4716, -0.1737, +0.2796, -1.0387, +0.5968, -0.3691, -0.2509, +0.1983, -0.5982, -0.2095, -0.3888, -0.0593, -0.4660, +0.2009, -0.2723, -0.3105, -0.0894, +0.0340], +[ +0.0328, -0.4288, -0.4086, -0.0870, +0.0050, +0.2962, -0.5815, -1.1317, +0.2684, -0.3838, +0.3732, -0.0419, +0.1006, -0.0332, -0.4590, -0.0034, -0.1430, -0.0152, -0.4190, -0.2460, -0.1689, +0.2852, -0.3491, -0.1469, +0.5112, -0.2610, +0.5671, +0.3549, -0.1863, +0.1151, +0.0004, +0.1777, +0.0849, -0.0509, -0.0241, -0.2225, +0.5380, -0.1528, +0.1736, -0.5529, -0.3402, -0.4931, +0.1928, +0.2212, -0.1292, -0.1949, -0.6881, +0.2509, -0.4402, -0.1828, +0.4146, +0.0894, +0.2925, -0.3445, -0.3955, +0.2638, -0.4357, -0.4719, +0.3477, +0.2992, -0.1546, -0.5620, +0.0869, +0.3226, +0.1604, +0.7277, -0.9342, -0.3394, -0.1522, -0.8674, +0.1367, -0.1647, -0.2419, -0.9182, -0.0594, -0.7259, +0.3389, +0.2066, +0.4865, +0.2865, -0.3317, -0.3533, +0.1510, -0.0408, -0.2310, -0.1214, -0.7874, +0.0594, +0.0637, +0.1704, -0.0509, +0.4279, +0.1456, +0.0183, +0.0084, -0.3207, +0.3121, -0.4553, +0.3080, -0.0612, +0.2902, -0.4538, -0.2972, -0.4140, +0.3137, -0.1422, -0.8175, -0.1954, +0.5369, -0.7929, +0.2202, -1.4705, -0.1834, -0.1199, -0.1593, +0.2240, -0.3757, -0.3017, -0.0894, -0.1868, +0.6420, -0.0309, +0.1543, -0.5357, -0.2081, -0.1984, +0.0857, +0.3100], +[ -0.2785, +0.1105, +0.4149, -1.5879, +0.0800, +0.2271, +0.2915, -0.3843, -0.4893, -0.7819, +0.0453, +0.0527, -0.0760, -0.2994, -0.2641, +0.3183, -0.6400, -0.1805, +0.4145, +0.2248, +0.0725, +0.1895, -0.0617, -0.2392, -0.0425, -0.0769, -0.0557, +0.2105, +0.0059, +0.0436, +0.0629, +0.1110, +0.1154, +0.0762, +0.4204, +0.1830, +0.0864, -0.4372, -0.3877, +0.0984, +0.2884, -0.1137, -0.2281, +0.4976, +0.0322, -0.3907, +0.1984, +0.4247, +0.4307, +0.2986, +0.1207, -0.1555, +0.5228, -0.0764, -0.7537, -0.4695, +0.1507, -0.2460, +0.6236, +0.0654, -0.3903, -0.1480, -0.2316, -0.1298, -0.0985, -0.6067, +0.0898, -0.9388, -0.0253, -0.6018, -0.1985, +0.3939, +0.0958, +0.4344, +0.0901, -0.1734, +0.0954, -0.5844, -0.5133, +0.0663, +0.1024, +0.1432, +0.1262, +0.5046, -0.8934, -0.0737, -0.2976, -0.0891, -0.1219, -0.4012, +0.4510, -0.4059, -0.0357, +0.3248, -0.6301, -0.1376, +0.3172, -0.0587, +0.8964, -0.1738, +0.1822, +0.4807, -0.3443, -0.2458, -0.2195, +0.1496, +0.6157, -1.0314, +0.1581, +0.5302, +0.0455, +0.3477, +0.0962, +0.5732, -0.0013, -0.4262, -0.1007, -0.5615, -0.9545, +0.1694, -0.4215, +0.2925, -0.3688, +0.3731, -0.0066, +0.6691, -0.4870, -0.3537], +[ +0.4068, +0.5845, -0.8742, -0.0664, -0.3680, +0.4151, -0.7328, +0.0857, -0.2333, +0.0135, -0.0799, +0.1949, -0.1770, -0.3081, +0.3287, +0.2236, +0.1515, +0.1368, +0.2567, -0.0252, +0.0880, -0.2675, -0.2043, -0.6968, +0.0936, -0.4986, +0.7414, +0.3489, +0.6269, -0.0687, +0.1289, +0.2688, -0.4887, -0.3381, -0.4586, -0.0715, -0.4161, -0.4189, +0.1545, +0.2416, +0.4395, -0.1713, +0.2378, +0.1061, -0.0685, +0.2889, -0.2323, -0.4748, +0.0775, -0.0366, -0.2849, +0.3293, +0.3429, -0.0311, -0.0716, -0.1996, +0.2068, -0.0579, +0.0055, -0.4996, +0.5267, -0.2290, -0.0476, +0.0717, -0.1189, +0.5376, -1.0262, +0.0645, -0.0771, -0.1288, +0.1105, -0.1917, -0.1174, -0.9960, -0.0879, -0.2593, +0.1000, -1.1075, -0.3571, -0.0944, +0.0719, -0.1795, +0.0898, +0.1515, -0.1497, -0.0154, +0.6563, -0.3794, +0.5367, -0.0372, +0.2813, -0.1864, +0.1888, +0.3343, +0.1813, +0.1186, -0.3605, -0.3599, +0.0245, -0.1951, -0.2185, -0.3295, +0.4275, +0.5862, -0.3230, +0.2030, -0.2806, +0.2977, -0.2020, -0.2393, +0.7133, +0.5259, -0.2807, -0.0618, -0.2883, -0.7191, -0.0670, +0.2811, -0.5409, -0.3810, -0.6504, +0.3010, -0.0262, -0.4714, -0.6627, +0.2988, -0.0401, -0.4720], +[ -0.2626, -1.0124, +0.5541, -0.4718, -0.4002, +1.0249, +0.7575, -0.9172, +0.3645, +0.4410, -1.9788, -0.3823, -0.4584, -0.1375, +0.1245, -1.9877, -0.0296, -0.7269, -0.3599, -0.1202, -0.1364, -0.2387, -0.2567, -0.0231, -0.1633, -0.7615, -0.0839, +0.1308, +0.3210, -0.0354, +0.1021, -0.5398, -1.2572, -0.3326, -1.0425, -1.1440, -1.5605, +0.3467, -0.0568, +0.3251, +0.2199, -0.1133, -1.1209, -0.7836, -0.1683, +0.1539, -0.6069, +0.1850, +0.3215, +0.0858, -0.3703, -0.1263, -0.1525, -0.4650, -0.2361, -0.0552, +0.0358, -0.1606, +0.3956, -0.6136, -0.3105, +1.1259, +0.2709, -0.4181, +0.3087, -0.0557, +0.3173, -1.1064, +0.0733, +0.9819, -0.6309, +0.0837, -0.1080, -1.0399, -0.5285, -0.1462, -0.5661, -0.5493, -0.2285, +0.2912, -0.1998, +0.2417, +0.2161, -0.2585, -0.2857, +0.6020, +0.2718, -0.8665, -0.0585, +0.0802, -0.4464, -0.7278, -0.3143, -0.4762, +0.6787, +0.1115, +0.3620, -1.2068, -0.0188, -1.3203, +0.1745, -0.5332, +0.3937, -0.0463, -1.4745, -0.0737, +0.5788, -0.1706, -0.2145, +0.3874, -0.1163, +0.4487, -0.0749, -1.4194, -0.0450, -0.4730, +0.2539, -0.4686, -0.3258, -0.2435, -0.0529, +0.0138, -0.3011, -1.7579, -0.0738, -0.5660, -0.2687, -0.1031], +[ -0.1890, +0.1846, +0.1528, +0.1868, -1.0463, +0.1361, -0.6526, +0.3472, +0.9501, +0.1137, -0.1338, -0.3032, -0.1089, -0.3156, +0.4740, -0.1239, +0.0710, -0.3375, -0.3874, -0.0470, -0.0551, +0.5221, +0.5352, +0.0590, +0.0157, -0.1133, +0.2564, +0.0972, -0.1763, -0.0172, +0.2382, +0.3805, +0.3693, -0.1347, -0.4978, -0.4696, +0.1159, +0.5663, +0.0888, +0.0899, -0.1063, -0.4584, +0.3321, +0.4006, +0.1525, -0.2469, -0.2116, -0.4201, +0.1384, +0.6111, +0.1410, -0.1235, +0.1201, -0.1482, +0.1087, +0.4535, -0.0998, -0.0626, -0.3032, +0.4636, -0.6396, +0.3708, -0.0050, +0.4596, +0.5721, +0.2259, +0.2125, +0.0627, +0.3765, -0.7187, -0.7086, +0.2721, -0.0764, -0.0565, +0.0235, -0.3755, -0.2753, +0.4597, +0.6486, +0.2965, +0.5531, -0.3629, +0.0782, -0.1587, +0.0848, -0.1989, -0.3563, -1.4503, +0.2558, -0.2762, +0.5357, +0.0858, +0.1913, -0.2766, +0.1420, -0.4243, -0.1676, -0.3365, +0.0941, +0.0516, -1.1257, -0.4089, -0.8515, -0.2830, +0.4711, +0.3335, -0.1440, -0.0064, +0.4255, -0.2008, +0.4499, -0.5755, +0.1673, +0.2069, -0.2422, -0.0123, -0.2220, +0.1374, -0.0896, +0.0227, +0.3576, -0.5969, +0.4685, +0.0131, +0.2259, +0.3857, +0.2969, +0.5092], +[ +0.2385, -0.0237, -0.2371, -0.9950, -0.7939, +0.1525, -0.6166, -0.0463, +0.0723, +0.2182, +0.3742, +0.1939, -0.3690, -0.5012, -1.2359, +0.2250, -0.2047, -0.7313, -0.3548, +0.0486, +0.3503, +0.3015, +0.2342, +0.5576, +0.0184, -0.5800, +0.0429, +0.2196, +0.2226, -0.1715, -0.1384, +0.3288, -0.1334, +0.3295, +0.6067, -0.0384, +0.0176, +0.0138, -0.1203, +0.0863, -0.0909, -0.3321, -0.0272, -0.0426, -0.1637, +0.1722, -0.6915, +0.0731, +0.2473, +0.0653, -0.1243, -0.3751, -0.6515, +0.0765, +0.3489, +0.0208, +0.3015, +0.0442, +0.1349, +0.1498, +0.6269, +0.8148, -0.4758, +0.2989, -0.7103, -0.2501, -0.5741, -0.0260, -0.4906, -0.2687, +0.5507, -1.0255, +0.1971, -0.4078, -0.1656, +0.7028, +0.3517, -0.8417, +0.2221, -0.1728, -0.0505, -1.1888, +0.3255, +0.0383, -0.8892, +0.0544, +0.3391, -0.1401, -0.9512, -0.0529, +0.2119, -0.3345, -0.2999, -0.4352, -0.1427, -0.0157, -0.2630, +0.1494, +0.3705, +0.4497, -0.4527, -0.1771, -0.3700, -0.2584, -0.5270, +0.3196, -0.5018, -0.0420, +0.4243, +0.0048, -0.3724, -0.1658, -0.0970, -0.5838, +0.2219, -0.2543, -0.3992, -0.0216, +0.5249, +0.1735, +0.5442, -0.0929, +0.1333, +0.1425, -0.1071, -0.1370, +0.1609, -0.3632], +[ -0.6062, -0.0107, -0.5037, +0.0280, -0.7645, -0.3818, +0.0495, -0.6663, -0.1796, +0.0424, -0.7120, -0.2048, +0.1505, +1.1172, +0.1182, +0.7021, +0.0447, +0.2636, -0.0117, -0.6400, +0.1739, -2.0563, +0.2643, +0.2216, -0.6307, -0.3034, -1.6683, +0.2710, +0.5509, +0.0906, +0.1050, -0.6639, -0.1404, +0.0301, +0.8906, +0.1874, +0.4052, -0.0841, -0.5191, -1.3543, +0.3044, +0.6129, -0.1700, +0.0759, -1.0354, -0.7217, +0.2234, +0.8004, -0.4027, -0.1250, +0.2738, -0.9314, -0.0443, -0.1532, -0.4836, +0.5214, -1.4886, +0.0576, -0.3373, -0.5356, -0.2243, -0.1056, +0.5262, +0.5279, -0.9975, -1.0158, -0.0009, -2.1319, -0.6019, -0.5193, +0.8604, +0.5502, -0.1540, +0.2157, +0.2840, -0.1492, +0.0043, +0.1732, -0.0667, +0.7070, +0.1044, +0.0107, +0.4892, -1.3223, -0.1142, -1.0157, -0.0481, +0.5053, +0.2333, -0.1292, +0.2140, +0.1220, -0.3557, -1.2828, -0.1046, -0.1504, -0.0380, -0.0526, -0.7740, +0.1770, +0.4862, -0.7069, -0.6501, -0.2251, +0.6397, +0.5812, -0.0295, -0.3300, -0.1545, -0.2888, -0.0862, -0.2176, -0.1580, -0.9327, -0.3072, -0.2631, +0.3495, -0.8641, +0.4137, +0.3080, +0.4942, -0.7215, -0.4081, -0.4022, +0.0381, +0.6014, -0.9209, -0.0248], +[ -0.0358, -0.2476, +0.0637, -0.2123, -0.9081, -0.0865, +0.3561, -0.5554, +0.1656, +0.1798, -0.0769, -0.3535, -0.2186, +0.2111, -0.2864, -0.1337, -0.4597, +0.3778, -0.2488, -0.0923, -0.1262, -0.0262, +0.2277, -0.3163, -0.0397, +0.0646, -0.4947, -0.2864, -0.5216, -0.7771, -0.5574, +0.1186, -0.0542, +0.0515, -0.2259, +0.4735, -0.1975, -0.0630, +0.0789, -0.1683, +0.5125, -0.4719, +0.6143, +0.0867, +0.6118, -0.0284, -0.2530, +0.3255, +0.2878, -0.3443, -0.7612, +0.1266, +0.1155, -0.0903, +0.3597, -0.3959, +0.0233, +0.0967, -0.7554, +0.2049, -0.4178, -0.1526, -0.0914, +0.2557, +0.3241, +0.3012, +0.1893, +0.2647, +0.2142, -0.1623, -1.2681, +0.4970, -0.2651, +0.2166, -0.1153, +0.0663, -0.7682, +0.4426, +0.3446, +0.3132, +0.6882, +0.7522, -0.1070, -0.3160, +0.1417, -0.4353, -0.3498, -0.2256, -0.1062, -0.4434, -0.3921, -0.5221, +0.3964, -0.4258, +0.1572, +0.1609, -0.3845, -0.5640, -0.3708, +0.4984, -1.0621, -0.2547, -0.1994, -0.0205, +0.3775, -0.4878, +0.0006, -0.0061, +0.0959, +0.0843, -0.1139, -0.2873, +0.3424, -0.1215, -0.8438, -0.6846, -0.0152, +0.2998, +0.4343, -0.8696, +0.2929, +0.1009, -0.8495, -0.7728, -0.0976, +0.0524, -0.2486, +0.0719], +[ -0.3571, -0.4067, +0.5145, -0.6866, -1.0174, +0.0091, +0.1718, -0.1745, -0.2513, +0.0362, +0.1269, +0.2780, -0.4117, +0.4818, +0.3668, -0.1561, +0.1516, -0.8762, +0.1162, -0.0460, +0.6237, -0.0380, -0.0423, +0.1929, +0.0457, -0.8398, -0.2828, +0.3374, -0.4903, +0.1736, +0.5767, -1.4534, +0.3863, -0.9543, +0.2292, -0.2237, +0.4655, -0.0044, +0.0677, -0.0377, +0.2746, -0.5696, -0.0749, +0.3972, +0.1447, +0.1636, -0.0700, -0.2671, +0.2902, +0.0804, +0.3041, -0.2553, -0.7488, -0.7124, +0.7484, -0.7365, +0.3321, +0.4087, -0.4259, -0.2603, +0.5249, +0.2184, +0.3844, -0.0441, +0.1161, +0.1279, -0.2196, -0.1223, -0.0356, -0.0484, -0.3438, -0.1186, -0.3836, +0.0660, +0.3879, +0.2712, -0.2012, +0.1470, +0.3385, -0.1620, -0.3034, -0.5461, -0.0432, +0.2796, -0.8137, -1.3743, +0.4925, +0.2108, -0.1027, -0.2138, -0.7378, -0.1209, -0.4294, -0.0851, -0.2624, -0.3597, -0.8611, +0.4464, +0.0393, -0.9927, -0.0209, +0.1669, -0.1943, -0.0069, +0.2535, -0.2320, +0.0523, -0.0387, +0.0736, +0.6659, +0.0430, -0.8271, -0.5452, -1.2268, -0.2558, +0.1095, +0.1778, -0.0051, +0.3514, +0.5244, +0.0645, +0.4827, -1.0049, -0.2551, -0.3863, +0.4874, +0.5816, +0.1889], +[ -1.1268, -0.0477, +0.6551, -0.2983, -0.7391, +0.0787, -0.0184, -0.7897, -0.0595, +0.5084, +0.2580, +0.0430, -0.7676, -0.5418, +0.3700, -0.8769, -0.2995, +0.1440, -0.0261, -0.4732, +0.0802, -0.6458, -0.3006, +0.0732, +0.5992, +0.3819, -0.5000, -0.1366, -1.0918, +0.0226, +0.1488, -0.0729, +0.1031, +0.1314, +0.2606, -0.3808, -0.6380, -0.5858, -0.4060, +0.2601, +0.0668, -0.1249, +0.1666, -0.5117, -0.4081, +0.2744, +0.2560, -0.8061, -0.9125, -0.1472, +0.2233, +0.0335, -0.3542, -1.0575, -0.2591, -0.0555, -0.3672, -0.0313, -0.1326, -0.4782, +0.0546, -0.0755, +0.1963, -0.2694, +0.0272, -0.2004, -0.7292, -0.2204, +0.4913, -0.0399, -0.6559, -0.0752, -0.2607, -0.0702, +0.2666, +0.2539, -1.0182, +0.1792, +0.1817, -1.1582, -1.8026, +0.2342, -0.7006, -0.4952, +0.1345, +0.2998, -0.2620, +0.1336, -0.0174, -0.4578, -0.1101, -1.5142, -0.4791, -0.2391, -0.9607, +0.3614, +0.2139, +0.3459, +0.7567, -0.1753, +0.1528, -1.0601, +0.2125, +0.2843, -0.0785, +0.5537, -0.2362, -0.2993, +0.1568, -0.7571, +0.2312, -0.8912, +0.2062, -0.3023, -0.2358, +0.5970, -0.5798, -0.5901, -0.1895, -1.0248, -0.0076, +0.0373, -0.4598, -0.3706, -1.0179, -0.1707, +0.4706, -0.4109], +[ +0.5548, +0.0762, -0.9732, +0.4974, +0.0721, +0.0603, +0.0403, -0.4016, -0.1278, -0.4030, +0.0751, -0.4352, +0.2306, -0.3200, +0.2516, -0.4887, +0.0665, -0.2368, -0.2360, +0.4221, +0.1742, -0.2811, -0.2135, -0.4115, -0.2981, +0.3318, +0.0242, +0.2272, -0.3173, -0.1427, +0.2518, -0.3534, -0.4959, -0.2551, -0.0797, -0.1724, -0.4159, -0.2069, -0.2414, -0.8762, -0.3802, -0.3595, -0.1394, -0.0372, +0.0818, -0.1363, -0.8352, -0.4604, -0.1355, +0.0200, -0.2153, +0.1949, +0.0538, -0.4498, -0.2186, -0.2281, +0.0772, +0.0655, -0.5071, +0.1983, -0.8508, +0.0344, -0.0185, +0.2695, +0.5237, +0.3735, -0.0424, +0.0236, +0.1312, +0.5737, -0.2471, -0.2865, -0.0292, -0.5521, -0.0439, +0.0889, -0.5819, +0.4158, +0.2471, -0.4975, -0.3082, +0.1817, -0.2181, +0.1859, -0.3464, +0.1266, -0.1987, +0.0891, -0.8471, +0.2534, +0.0612, +0.0998, +0.5045, +0.2724, +0.2775, +0.0461, -0.1714, +0.3437, -0.0115, -0.6069, +0.3813, -0.3904, +0.2130, +0.5443, +0.5034, +0.2294, -0.2291, +0.2235, -0.1319, -0.0598, -0.1721, +0.2250, +0.1713, -0.0901, +0.7149, +0.0539, +0.0448, -0.5711, +0.1461, +0.4580, -0.1875, +0.0457, -0.1837, -0.4180, +0.0479, -0.1208, +0.1840, +0.4426], +[ -0.2842, +0.2116, +0.0117, -0.6003, +0.0043, -0.2358, +0.4554, +0.7943, +0.2894, -0.1744, -0.7563, +0.4605, -0.2773, -0.3848, -0.5594, -0.3504, -0.2448, -0.0372, -0.3179, +0.1210, +0.1392, -0.5565, +0.2361, -0.5027, +0.7456, -0.1703, -0.0240, +0.1292, +0.2535, -0.3699, -0.3059, -0.5017, -0.2633, +0.1405, +0.0046, -0.3354, -0.2708, -0.1274, +0.0338, +0.1981, -0.0836, +0.6965, +0.0527, +0.0872, -0.1278, -0.4493, +0.4030, -1.5423, +0.5086, +0.1008, -0.3396, +0.0430, -0.4026, -0.1746, -1.0235, +0.2083, -0.2529, +0.4123, +0.2179, +0.1214, +0.6086, -0.0055, -0.5584, -0.6812, -0.1916, -0.3864, +0.0741, +0.1077, +0.4114, +0.0345, -0.1636, -2.1677, +0.6062, -0.1717, +0.0664, +0.1639, +0.4483, -0.6986, -0.0163, -0.2069, +0.2554, -0.3096, -0.0139, +0.3088, +0.0131, -0.3570, -0.1024, -0.1159, +0.2009, +0.2716, -0.1614, +0.3146, +0.0674, +0.2829, -0.0565, +0.2379, +0.0764, +0.0750, +0.0191, +0.0233, -0.1372, +0.2373, +0.2386, +0.0077, -0.2598, +0.2932, -0.2208, -0.1869, +0.4116, +0.2577, -0.3386, +0.3720, -0.0159, +0.3788, +0.3233, +0.2683, -0.4094, -0.2736, -0.2217, -0.1135, +0.1307, +0.2497, -0.5941, +0.0363, -0.0517, +0.1772, -0.1428, -0.1171], +[ -0.0162, -0.0627, +0.1236, +0.4031, -0.2465, +0.1629, +0.0719, +0.4211, +0.1920, -0.1312, +0.0193, +0.2175, -0.1819, -0.6242, -1.0284, +0.2454, +0.0434, -0.1952, +0.1975, -0.1499, +0.0737, -0.3134, -0.4515, +0.1174, -0.1765, -0.1006, -0.0569, -0.9097, -0.7455, -0.4741, +0.2333, -0.3261, +0.3061, +0.1993, -0.2329, +0.2430, +0.1176, +0.2400, +0.2129, +0.4918, -0.2546, -1.1784, -0.6182, -0.1537, +0.1395, +0.5393, -0.7461, -0.2201, +0.1386, -0.2714, -0.2729, -0.1344, -0.2892, -0.7805, +0.1870, -0.4685, -0.1468, +0.3957, +0.0906, -0.0169, -0.1142, -1.1525, +0.4167, -0.5574, +0.0122, -0.1523, +0.2502, -0.0223, -0.0227, +0.2885, +0.0504, -1.7032, +0.0428, +0.3443, -0.4039, +0.2699, -0.0908, -0.3298, -0.2390, -1.0043, -1.0324, +0.0237, +0.1503, +0.5633, -0.4685, -0.3616, -0.8335, -1.0535, -0.6771, -0.0776, -0.3784, +0.4398, -0.6072, -0.5504, -0.5404, -0.3614, -0.3855, +0.0132, +0.1216, -0.3302, +0.3921, +0.1087, -0.2751, +0.3683, -0.8535, -0.0739, -0.0324, -0.8358, +0.2640, +0.0494, +0.3263, -0.3085, -0.0733, -1.1149, +0.2494, -0.1388, -0.3078, +0.1479, +0.6488, +0.5278, -0.6395, -0.0259, -1.1560, -0.0320, +0.0748, -0.3467, +0.5657, +0.5099], +[ -0.1044, -0.6576, -0.0207, -0.2102, -0.2144, +0.0663, +0.3874, +0.2177, -0.1430, -0.3068, -1.4322, +0.4873, +0.1080, -0.1987, -0.1861, -0.0218, -0.0747, -0.0191, +0.6192, -0.2742, -0.1812, +0.2117, +0.6730, +0.3359, +0.5871, +0.1320, +0.0645, +0.3662, -0.9857, +0.0502, -0.0964, -0.0680, -0.2814, -0.4225, -0.6175, +0.3815, +0.1500, +0.2513, +0.1783, -0.0825, +0.0526, +0.2218, +0.2001, +0.1161, -0.1507, +0.2265, +0.1415, -0.6507, +0.2255, -0.0120, +0.3568, +0.0921, +0.3392, +0.0370, -0.1990, -0.2535, +0.1636, +0.3225, -0.4935, +0.2109, -0.0501, +0.0897, -1.0855, +0.1237, +0.0788, +0.5188, -0.4567, +0.0116, -0.5196, -0.1994, -0.2475, -0.6040, +0.0321, -0.1177, +0.0018, -0.4671, -0.5711, +0.0513, -0.5653, +0.2688, -0.2311, +0.2756, -0.0531, +0.7042, -0.3073, +0.3589, +0.3590, -0.1418, +0.5496, -0.4660, +0.5389, -0.1360, +0.2775, +0.2597, -0.1089, -0.1900, +0.4253, +0.3885, +0.4209, -0.3493, +0.0138, +0.5685, +0.1056, -0.1521, -0.5811, -0.1916, -0.0096, +0.0435, +0.1461, +0.0400, +0.2125, -0.3966, +0.4368, +0.0176, +0.2729, +0.0513, -0.4901, +0.0455, -0.0224, -0.3494, +0.0116, +0.3173, -0.9230, +0.2972, +0.1613, +0.4970, -0.2340, +0.0639], +[ -0.1437, -0.7074, -0.0227, -0.1429, +0.5628, -0.1444, -0.4686, -0.4664, +0.2558, +0.1615, +0.1201, -0.0562, -1.6423, +0.4704, -0.6496, -0.7396, +0.1954, -0.1594, -0.5794, -2.0340, -0.0471, +0.1209, +0.0230, -0.1971, -0.3795, +0.3395, -0.2557, -1.0066, +0.1323, +0.3637, +0.1311, -0.2849, +0.0459, -0.0762, -0.0104, +0.6315, -0.3362, -0.1927, +0.4068, +0.0825, +0.4061, +0.0420, -0.1391, +0.0454, +0.0701, +0.2792, +0.2601, +0.1755, +0.4302, +0.0462, -1.3625, +0.1624, +0.0497, -0.0207, +0.2457, +0.2754, -0.4668, +0.1269, -0.0177, -0.0970, +0.0154, -0.5404, -0.0584, +0.4238, +0.1016, +0.1083, -0.4236, +0.3165, +0.0311, -0.1969, -0.1508, +0.1011, -0.4269, -0.0473, -1.4787, -0.0548, -2.0101, +0.3298, -0.4169, -0.1667, -0.2075, -0.5669, +0.2357, -0.1768, +0.2307, -0.0191, +0.6791, -0.0978, -0.4987, -0.2691, +0.0821, -0.5149, +0.1673, -0.1167, -0.0717, +0.5303, +0.6750, +0.1378, -0.1502, -0.4372, -0.0052, -0.0900, +0.0762, -0.4988, -0.2373, -0.4635, -0.6370, +0.5504, +0.1706, -1.2182, -0.3613, -0.4645, -0.1783, -0.8491, -0.1739, -0.3553, +0.2115, -0.1156, -1.3149, -0.2067, +0.3576, -0.2588, -0.5707, -1.1997, +0.3510, -0.5910, -0.0631, -0.0799], +[ -0.7265, +0.8917, -0.0751, -1.3913, +0.3771, -0.1059, -0.0873, +0.3571, -0.8270, -0.1692, +0.1868, -0.3708, +0.0788, +0.4810, +0.7026, +0.3153, -0.2533, +0.0807, -0.4520, -0.6554, +0.2868, -0.4496, +0.0535, -0.1686, -0.2701, -0.2813, -0.7436, +0.3309, -0.2931, -0.4216, +0.3644, -0.1687, +0.5863, +0.8018, +0.6494, +0.4601, -0.3677, -1.0434, +0.2167, +0.5227, +0.1440, -0.4096, +0.1883, +0.5111, +0.5387, -0.1108, +0.3406, -0.1422, +0.1151, -0.1370, -0.7487, -0.0985, -0.4278, -0.2114, +0.2810, -0.0622, +0.2291, -0.3401, -0.4664, -0.1857, +0.4196, +0.0946, +0.4732, -0.0479, -0.1954, -0.6938, +0.1261, +0.0103, -0.3667, -0.0102, +0.1229, -0.2663, +0.2842, +0.2170, +0.0748, +0.3038, +0.6471, +0.1502, +0.4311, +0.3652, -0.3753, -0.1012, +0.4648, -0.2373, -0.5606, +0.1091, +0.3855, -0.1598, -0.4532, +0.0894, +0.0529, +0.2738, +0.1630, +0.6182, -0.2206, -0.2195, -0.7492, -0.2194, -0.3159, +0.7241, +0.0582, -0.5792, -0.6760, +0.0261, +0.3155, +0.1989, +0.3230, +0.2225, -0.2388, -0.1559, -0.1574, +0.1876, -0.2981, -0.0996, +0.0628, +0.1548, -0.1244, -0.9343, +0.0628, +0.2718, +0.1845, -0.0582, -0.4112, +0.3589, -0.1315, -0.2060, +0.1827, -0.1181], +[ +0.3130, +0.1275, -0.4132, -0.4863, +0.2244, +0.2695, +0.4271, +0.2023, -0.0472, +0.4431, -0.1568, +0.6265, +0.2728, +0.2451, -0.2830, -0.0059, +0.2365, +0.3480, +0.2522, -0.7088, +0.0403, -0.0386, +0.1891, -0.3917, +0.0114, +0.4899, +0.0924, +0.3148, -0.5466, +0.1659, -0.1183, -0.1935, -0.1756, -0.1477, +0.1472, -0.1724, +0.2143, +0.7332, +0.0079, +0.2761, -0.3160, +0.5058, -0.0931, -0.1448, -0.0298, +0.7194, +0.1387, -0.6623, +0.0052, +0.2097, -0.5607, +0.5945, -0.2575, +0.2782, -0.5959, +0.1211, -0.0791, -0.2460, -0.7347, -0.2956, +0.1763, +0.6106, -0.4464, +0.2316, -0.2995, +0.4528, -0.8791, -0.7911, -0.1451, -0.2947, +0.2296, -0.1733, +0.2242, -0.0035, -0.4821, -0.6993, +0.3675, +0.2964, +0.3193, +0.2363, +0.0551, -0.0624, +0.3850, +0.1241, -0.1481, +0.2376, +0.0553, -0.3350, -0.1162, -0.2798, -0.1833, +0.0958, -0.1838, -0.0980, -0.1692, -0.3936, +0.3211, -0.0617, -0.0247, +0.0837, +0.7681, +0.3259, +0.0790, -0.0632, -0.4515, -0.5924, +0.3167, -0.4388, +0.5271, +0.0197, -0.0969, -0.2817, -0.0572, -0.0888, +0.2329, +0.2268, +0.2331, +0.1691, -0.4536, -0.2887, -0.2485, +0.2667, +0.0362, +0.1168, +0.2150, -0.2858, -0.0200, +0.4715], +[ +0.1219, -0.0217, -0.5837, -0.3836, +0.4210, -0.5505, +0.1642, -0.1091, -0.8230, -0.6983, +0.3176, -0.1022, +0.0676, +0.2756, +0.4560, +0.2047, +0.1622, +0.1974, +0.3630, +0.2332, -0.2842, +0.0591, -0.1309, +0.2992, +0.5811, +0.4116, -0.6022, -0.4205, +0.2960, +0.0698, -0.4935, -0.8271, +0.3858, -0.0605, -0.1359, -0.2071, +0.5370, -0.6949, +0.4987, -0.2968, -0.0380, -0.4235, +0.1417, -0.5961, +0.3926, -0.1673, -0.4168, +0.7737, +0.0137, -1.2432, +0.2691, +0.1803, +0.7565, +0.2014, +0.0604, -0.3547, +0.0504, -0.1369, -0.7881, -0.2128, +0.0610, -0.0196, -0.1566, +0.0030, -0.8292, -0.0454, +0.0377, -0.0885, +0.0579, -0.2501, +0.0370, -0.9455, -0.0527, -0.2292, -0.5440, -0.0517, -0.0122, -0.2071, -0.0758, +0.0947, +0.0308, +0.1070, +0.1017, -0.3191, +0.1329, -0.3563, -0.1016, -0.8970, +0.4906, -0.2456, -0.3833, -0.3038, -0.0509, -0.1365, +0.2201, -0.5577, +0.1567, -0.1963, -0.4634, -0.0231, +0.1323, +0.4220, -0.4158, -0.6117, -0.1371, -1.3515, -0.4502, -0.7084, +0.4100, +0.0979, -0.1893, -0.6622, -0.2095, +0.1093, +0.3789, -0.3222, -0.4348, +0.3956, -0.1112, -0.1735, +0.2460, +0.0870, -0.4405, +0.1579, -0.0126, +0.3663, -0.1206, -0.4883], +[ +0.4090, +0.3428, +0.2512, -1.5906, +0.6582, -0.8021, +0.1520, -0.0569, -0.4027, +0.2248, +0.2477, -0.4910, -0.9947, -0.4317, +0.2517, -0.3626, -1.3942, +0.2331, +0.5284, -0.4955, -0.1959, +0.0347, -0.2575, -0.1463, -0.1766, +0.1963, -0.8659, +0.0555, +0.4978, -0.9231, -0.4148, +0.5886, -0.3435, +0.3906, -0.2323, -0.3572, -0.0199, -0.4587, -0.4683, -0.4979, -0.2390, +0.0564, -0.6407, +0.2675, -0.7272, -0.2480, +0.4758, -0.7479, +0.1223, +0.0275, +0.1572, +0.0790, +0.4834, -0.3260, +0.0827, -0.3243, -0.4053, -0.2065, +0.8476, -0.4793, +0.7518, +0.0727, -0.2254, -0.8287, -0.7180, -0.1953, +0.2458, -0.5847, -0.3380, -0.1605, +0.0760, +0.8777, -0.0750, -0.2355, -0.3456, -0.5562, +0.0233, +0.0654, -0.2250, -0.1257, +0.0755, +0.1061, +0.0183, -0.6314, -0.0276, -0.5709, +0.1427, -0.9943, -0.2089, -0.1618, +0.1928, +0.0366, -0.4056, +0.1872, +0.3670, +0.5268, -0.2949, +0.4297, -0.6547, +0.0743, -0.7467, +0.4479, -0.7236, +0.4257, +0.0888, -1.5198, +0.0594, -0.8880, -0.6984, -0.3094, -0.5483, -0.9416, -0.1274, -0.4495, +0.5366, -0.4214, +0.2500, +0.3083, -0.6264, +0.4781, -0.3504, -0.2692, -0.4077, +0.0213, -0.9375, +0.1823, -0.7678, -0.6795], +[ +0.4683, +0.4362, +0.3526, -0.0894, -0.2294, -1.1023, -0.3028, +0.1758, -0.1920, +0.3107, -0.0442, +0.1234, -0.4052, -0.7556, -1.4301, -0.0456, +0.2569, -1.0682, -0.1381, -0.1230, +0.1955, -0.3330, +0.1838, -0.3458, -0.5642, +0.1428, +0.2405, +0.6010, -0.1470, -0.3523, -0.0542, +0.1510, -0.3189, -0.5421, +0.3879, -0.2164, -0.2662, +0.1630, -0.0339, -0.3344, -1.4772, +0.1192, -0.6321, -0.0340, -0.0587, +0.3702, -0.8599, -2.0794, +0.4569, -0.1700, +0.1769, +0.3511, -0.0855, +0.2822, +0.2336, +0.1616, +0.5258, -0.1024, +0.4351, +0.1208, -0.2025, -0.6205, -0.4838, -0.1901, -0.7711, -1.0001, +0.3786, +0.3819, -0.2563, +0.1972, +0.4146, +0.0413, +0.6957, -0.4456, +0.3663, +0.7249, -0.5925, -1.0268, +0.4177, -0.0087, +0.4056, -0.0701, +0.0594, +0.1083, +0.2143, -0.4115, -0.0350, -0.0193, +0.3083, -0.7987, +0.1743, -0.3390, +0.9210, -0.1339, -0.5012, -0.5543, +0.4410, +0.0627, +0.3689, +0.2465, +0.1989, -0.0166, +0.3254, +0.3029, -0.3015, +0.0947, -0.2871, +0.0143, -0.0860, +0.5374, -0.5375, -0.0836, +0.5282, +0.0927, +0.3490, -0.4070, -0.4771, -0.1295, -0.4146, +0.2507, -0.7222, -0.3260, +0.1335, +0.0136, -0.1393, +0.1429, -0.2269, -0.2930], +[ -0.0437, -0.2157, +0.4923, -0.6321, +0.0022, -0.0296, -0.9576, -0.5569, +0.3181, +0.2091, +0.3334, +0.1503, +0.1709, -1.6208, -0.4494, -0.8162, -0.7325, -0.9672, -0.3088, +0.3997, -0.1793, -0.5785, -0.1168, -0.4739, -0.0540, +0.4712, -0.0863, +0.1757, +0.0740, -0.1534, +0.0955, +0.0096, -0.1520, -0.3343, +0.3403, -0.2325, -0.3957, -0.2039, -0.1898, +0.4041, +0.0474, +0.5879, -0.1018, -0.3031, -0.1018, -0.1546, +0.3044, +0.0565, -0.3444, -0.0236, +0.1412, +0.2696, -0.1557, -0.8822, -0.1266, +0.2104, -1.0103, +0.1355, +0.6538, +0.3990, -0.8994, -0.2313, +0.4144, -0.2434, -0.2434, -0.5452, -0.3693, -1.0065, -0.2526, +0.1606, +0.1587, -0.0940, -0.7770, +0.2070, +0.5299, +0.1534, +0.0182, -0.5653, -0.2528, -0.2816, +0.3887, +0.3633, -0.0236, +0.0537, -0.3035, +0.0553, -0.3131, +0.2767, -0.6836, +0.2380, -0.3762, +0.1924, +0.2998, -0.1018, -0.5629, +0.1175, -0.0172, -0.2261, -0.1764, +0.2219, +0.0248, +0.0758, +0.4091, +0.5297, -0.1721, +0.2416, -0.0586, -0.0440, +0.1363, -0.9104, -0.1781, +0.1013, -0.6489, -0.0025, +0.4615, -0.0297, +0.0765, +0.2838, -0.4600, -0.1713, -1.6520, -0.4385, +0.0017, -0.9159, +0.2006, -0.2593, -0.2150, +0.1949], +[ +0.0339, -0.0568, -0.5621, -0.0932, +0.0583, -0.9944, +0.0075, +0.3368, -0.6028, +0.2755, +0.1404, +0.3316, +0.3873, +0.0802, -1.0236, -0.0446, +0.4943, -0.2195, +0.2907, +0.2503, -0.7739, -0.3247, +0.2905, +0.3955, +0.1023, +0.5193, +0.0899, -0.2487, -0.4851, +0.0584, +0.0920, -0.6081, +0.1348, -0.1767, +0.0742, -0.5411, -0.3979, -0.1991, +0.5524, +0.0053, +0.4063, +0.1606, +0.2620, -0.1135, -0.5295, +0.2818, -0.3286, -0.4359, -0.3249, -0.2776, +0.5612, +0.0728, -0.5318, +0.2386, -0.8625, +0.0792, +0.3288, +0.3633, +0.3718, -0.2269, +0.7100, -0.3257, +0.3669, -0.3163, +0.0914, +0.1124, -0.7857, +0.0114, +0.0858, +0.0580, +0.0056, -0.7910, -0.3239, -0.0388, +0.2442, -0.1195, +0.3433, -0.1431, -0.1119, +0.0972, +0.1949, -0.3508, +0.0935, -0.5958, +0.7940, -0.7228, +0.6034, -0.4416, -0.0069, -0.0365, -0.0326, -0.0376, +0.3765, +0.4202, -0.1681, -0.6389, +0.0301, +0.3833, -0.0720, -0.6577, +0.3238, +0.5271, +0.6202, -0.1260, -0.6644, -0.1715, +0.4823, +0.1443, -0.0962, +0.1568, -0.3111, +0.2790, -0.7418, +0.2376, +0.2314, +0.8497, +0.0939, -0.1574, -0.3043, -0.7649, +0.0571, +0.3874, -0.3846, -0.0944, +0.5540, -0.4897, +0.0387, +0.5230], +[ +0.4302, -0.2172, -0.6644, +0.5350, -0.6361, -0.1944, -0.8780, -0.2447, +0.2381, -0.5389, -0.2404, +0.2404, -0.4202, -0.1248, -0.3898, +0.3124, +0.1769, +0.3764, +0.3986, -0.5957, +0.3145, +0.2409, -0.3809, +0.1314, -0.0018, -0.6858, +0.3517, +0.0978, -1.3349, +0.0992, +0.1196, -0.2485, +0.2190, -0.5817, +0.1557, -0.1075, -0.2156, +0.3588, -0.8234, +0.5031, +0.0244, +0.0619, -0.3212, -1.0465, -0.0554, -0.0448, -0.6694, +0.1508, -0.9232, -0.1322, -0.1564, -0.3022, -0.1517, -0.1223, -0.2044, +0.2124, -1.0978, -0.1057, +0.0144, +0.1217, -0.3823, -0.0009, +0.1590, +0.0353, -0.1922, +0.2753, -0.3672, -0.3458, -0.0228, -0.4366, -0.5541, +0.1015, -0.4054, -0.0574, -0.7021, -0.3660, +0.4662, +0.1551, +0.0294, -0.2665, -0.1404, -0.5847, -0.6307, -0.3790, -0.2180, +0.1872, -0.6189, +0.1271, +0.0037, -0.3821, -0.5943, -0.0343, -0.2771, +0.0432, -0.7665, +0.3099, -0.2629, -0.0641, +0.0618, +0.6157, +0.2150, -0.1869, -0.8548, +0.0362, -0.3927, +0.4267, +0.0765, -0.3128, +0.1172, -0.0424, +0.3030, -0.4808, -0.0301, +0.5784, +0.2766, +0.1312, +0.1552, -0.5810, +0.1366, +0.3775, -1.1347, -1.1573, +0.1438, +0.0798, +0.0821, +0.0965, +0.2632, -0.1688], +[ +0.0486, +0.4445, +0.8387, +0.2568, -1.1572, +0.4689, +0.1263, +0.2519, -0.6219, -0.0639, -0.0465, -0.3888, +0.1773, -0.0798, -0.3921, +0.1864, -0.2427, -0.6167, -0.2716, +0.3918, +0.1758, -0.1026, -0.3277, -0.0350, -0.4220, +0.2290, -0.3666, +0.0481, +0.1537, -0.1635, +0.2875, -0.1457, +0.3795, -0.1145, -0.3384, +0.2957, -0.1083, +0.3636, +0.4398, -0.4989, +0.3521, +0.6306, +0.3257, +0.8925, +0.0012, -0.3577, -0.4091, -0.2389, +0.3009, +0.2426, -0.1863, -0.4598, -0.5801, +0.4239, +0.7071, -0.6306, -0.0318, +0.7025, -0.6715, +0.1279, -0.1172, -0.4279, -0.3312, +0.3969, +0.3163, +0.0021, +0.2250, -1.1076, +0.3326, -0.0329, -0.7956, -0.2683, +0.3947, +0.1141, +0.3432, -0.3208, +0.4752, -0.3115, -0.2513, +0.4078, +0.3549, -0.3452, +0.4530, +0.5450, +0.3026, -0.2971, -0.3374, -0.7781, +0.1321, -0.4501, -1.0434, -0.2007, +0.1588, +0.3823, -0.2005, -1.5922, -0.4523, -0.5334, -0.4728, -0.7466, -0.1689, +0.3333, +0.9141, -0.2566, +0.1104, -0.1154, +0.0838, -0.1758, +0.1811, +0.6251, +0.3063, +0.1442, -0.3461, -0.0870, -0.3754, -0.2758, -0.5202, +0.3635, -0.8359, -0.1352, -0.4679, +0.5761, -0.9381, +0.1186, -0.6600, -0.4856, -0.1229, -1.3795], +[ -0.4596, -0.4665, -0.7232, +0.4427, -0.5278, +0.2214, +0.1276, -0.7940, -0.8310, +0.2893, +0.1474, -0.0802, +0.4358, -0.3326, +0.4273, -0.2247, -0.0812, +0.1327, -0.4622, +0.5568, -0.1326, -0.2577, -0.6547, -0.0465, +0.3134, +0.1999, -0.1509, -0.0916, -0.7934, -0.5564, +0.2215, +0.1797, +0.4205, +0.0757, +0.0866, +0.0747, -0.6790, +0.1504, -0.0331, -0.6397, +0.4036, -0.1117, +0.7006, -0.8588, -0.1314, -0.2884, -0.6283, -1.0481, -0.9171, -0.2741, +0.7294, +0.1341, -0.5690, -0.2267, -0.1509, -0.1553, +0.4570, -0.0115, +0.1082, -0.0045, -0.0435, -0.0790, +0.1057, +0.1385, +0.5353, -0.1467, +0.3976, -0.1944, +0.1313, +0.0635, -0.0690, -0.0125, +0.3091, +0.1871, +0.2987, -0.1033, +0.0188, +0.2802, +0.0149, -0.5585, +0.3224, +0.2919, +0.3109, -0.0414, +0.1248, -0.4365, +0.3245, -0.0306, -0.0583, -0.2472, +0.0395, -0.6055, +0.0278, +0.1616, +0.5013, -0.2901, -0.0443, -0.0004, -0.4235, -0.6453, -0.2101, -0.2178, -0.1750, -0.2190, +0.0142, +0.1256, -0.3123, +0.4291, -0.3367, +0.1954, +0.3119, +0.1210, -0.5771, +0.0519, +0.1849, -0.1615, -0.0733, +0.3759, -0.1807, -0.3813, -0.5297, -0.1774, -0.0199, +0.2418, +0.3511, -0.0563, -0.1167, -0.4282], +[ +0.0952, +0.2561, -0.2844, -0.2665, -0.0839, +0.7566, -0.1682, +0.2183, -0.2247, -0.4824, -0.0646, -0.3158, -1.2641, -0.3514, -1.0803, +0.5559, +0.4353, -0.4389, +0.2619, -0.3615, +0.2897, -0.7813, -0.3570, -0.0004, +0.3873, +0.3192, +0.0727, -1.0953, +0.0653, +0.1268, -0.0092, -0.1782, +0.0052, +0.2457, -0.8414, +0.1563, +0.0886, +0.0362, +0.3103, -0.1490, -0.2650, -0.5943, -0.2877, -0.0656, -0.5241, +0.2399, -0.7845, -0.2950, -0.3548, -0.5025, +0.5442, -0.1611, -0.1232, -0.0572, +0.2483, -0.0855, -0.3825, +0.0387, -0.2524, +0.2587, +0.6535, -0.0393, +0.0975, -0.3105, +0.2879, +0.3140, -0.1188, -0.0446, +0.2561, -0.1164, +0.3638, +0.0178, -0.3148, +0.3328, +0.5837, +0.0712, +0.1361, +0.2261, -0.4964, +1.0193, -1.0342, +0.3773, +0.1262, -0.1145, -0.4670, -1.0224, +0.0325, -0.4796, -0.1071, -0.0128, +0.2066, +0.2780, -0.5035, -0.3934, -0.0626, +0.2125, +0.5664, +0.3072, +0.4962, -0.7859, +0.4584, -0.1682, -0.4819, +0.0270, -0.0845, -1.3404, +0.7211, +0.0027, +0.2755, -0.1331, -0.2127, -0.3678, +0.0117, +0.2418, -0.2516, -0.2810, -0.4912, +0.0286, +0.1692, +0.0112, -0.5188, -0.2282, -0.8814, -0.5661, +0.2812, +0.5454, -0.4854, +0.3009], +[ +0.1870, +0.3014, -0.5271, -0.1075, +0.0156, -0.3080, +0.1362, -0.9902, -0.3459, -0.6937, -0.4316, +0.0986, +0.2262, +0.0075, +0.6713, +0.5430, +0.0630, -0.3519, -0.1376, +0.0561, -0.0776, +0.2371, +0.1225, -0.0702, -0.4031, -0.0734, +0.0244, -0.5890, -0.6585, +0.0734, -0.1912, -0.2719, +0.4767, +0.2162, +0.0277, +0.0434, +0.4320, -0.1501, +0.0798, +0.0340, +0.1550, +0.3855, +0.0754, -0.0348, -0.1188, +0.1943, -0.0932, +0.4244, +0.2955, +0.4376, -0.0588, -0.3101, +0.6338, -0.8185, -1.4382, +0.0284, +0.1375, -0.2207, +0.3143, -0.3735, +0.4699, -0.2343, +0.3439, +0.2575, +0.0560, -0.5537, +0.1837, -0.3537, +0.4204, -0.2469, +0.4694, -0.4818, -0.0800, +0.1547, +0.1375, -0.3788, +0.1500, +0.7913, -0.1740, +0.5279, +0.4443, -0.3273, +0.1345, -0.1566, +0.1651, -1.1800, +0.4721, -1.2701, +0.1045, +0.0280, -0.9942, -0.4377, -0.8253, +0.4465, -1.0180, -0.8197, -0.1882, -0.5531, +0.1068, +0.5739, -1.6526, -0.4122, -0.4316, -0.6513, -0.7149, +0.2063, -0.8572, -1.2181, -0.0730, +0.1810, +0.0309, +0.1499, -0.7045, -0.2607, -0.7460, -0.3004, -0.4975, +0.1208, -0.0947, -0.0603, +0.2271, -1.2883, -0.1305, +0.1314, +0.0737, +0.0324, -0.1463, -0.3041], +[ +0.0458, -0.0894, -0.2151, -0.6742, -0.2983, -0.6282, +0.1355, -0.1223, +0.6234, +0.5262, -0.6218, +0.3284, +0.0273, +0.0397, -0.7536, -0.2314, -0.1161, +0.4722, -0.5954, +0.0380, -0.0210, +0.0786, -0.3814, -0.7529, +0.2928, -0.0075, -0.6387, -0.7448, -0.8791, +0.2035, +0.2726, -0.3057, -0.3138, -1.4312, +0.3530, -0.1899, -0.9923, -0.5255, +0.4026, -0.6432, -0.0311, +1.1196, +0.5319, +0.0608, -0.4065, -0.3264, -0.0691, -0.4776, -0.0131, -0.1747, -0.0769, -0.3585, -0.1498, +0.0016, -0.5073, +0.7675, -0.6077, -0.5249, -0.3288, -0.7887, +0.0849, +0.2405, -0.2989, -0.0863, +0.4390, +0.0930, -0.2713, +0.0888, -0.3606, -0.7837, -0.7676, -0.2362, -0.4155, -0.2206, +0.7188, -0.5565, -0.2318, -0.9128, -0.5840, -0.2630, -0.9346, +0.1868, -0.2590, -0.9223, +0.2309, -0.0921, -0.0357, -0.3798, -0.0737, -0.7020, +0.0108, +0.4331, -0.5297, -0.1514, +0.1932, +0.1644, -0.3387, +0.1624, -0.0290, +0.3106, -0.1923, -0.5176, -0.1456, -0.9456, -0.0735, -0.1717, -0.5372, -0.3042, -0.5604, -0.0275, -0.1044, -0.2694, +0.1343, +0.2035, +0.0755, +0.2408, -0.3585, +0.3206, +0.0377, -0.6399, -0.6233, -0.7337, -0.8767, +0.1049, -0.8633, -0.2215, +0.1198, +0.0252], +[ -0.3981, -0.9485, +0.1615, -0.1278, +0.3925, -0.1676, +0.1565, -0.2447, -0.4455, +0.0189, -0.2803, +0.0478, -0.0118, -0.0795, -1.2917, -1.3892, -0.7834, -0.2114, -0.5573, +0.2180, -0.0635, +0.4844, +0.1714, -0.1521, +0.1799, +0.1737, +0.0494, +0.6905, +0.0204, -0.1172, +0.0560, -0.1334, -0.5119, +0.0524, -0.3917, -0.1034, +0.3487, -0.1477, +0.3384, +0.3475, -0.1820, -0.3406, +0.1093, -0.1681, +0.6878, -0.2988, +0.6641, -1.0641, -0.1253, -0.3916, -0.2225, +0.1199, -0.0494, -0.0510, -0.7834, +0.1818, -0.3580, +0.1913, +0.2561, +0.1417, +0.1223, -0.8103, -1.1695, +0.2879, +0.2757, +0.2811, +0.3511, -0.1775, -0.7569, +0.2796, +0.0768, +0.1223, -0.1397, -0.1127, +0.2790, +0.2812, +0.0628, -0.6584, +0.2361, -0.0339, +0.2359, +0.0154, +0.3348, +0.2586, +0.3898, -0.1157, +0.1350, -1.0472, -0.3809, +0.0340, +0.1931, -0.3670, +0.0556, -0.0287, +0.0381, -0.2873, +0.1255, +0.2827, -0.4592, -0.1651, +0.0170, +0.0656, +0.4979, +0.0304, -0.5095, -0.3564, -0.1532, -0.2341, +0.1253, +0.0679, +0.3635, -0.5372, +0.5080, -1.3852, +0.2097, +0.1693, -0.4685, +0.0981, -0.3357, -0.8061, +0.3398, +0.0947, -0.5268, -0.1303, +0.2309, +0.0951, +0.3498, +0.2407], +[ +0.2665, -0.0532, -0.0694, +0.0253, -0.3748, +0.0328, -0.4113, +0.0673, -0.2931, -0.0414, +0.1795, -0.0323, -0.3450, -0.1150, +0.2287, -0.2842, -0.7729, -0.3042, -0.2463, -0.0702, -0.2516, -0.0768, -0.1726, +0.5449, +0.0152, -0.0060, -0.2021, +0.0711, -0.2867, +0.0975, -0.3351, -0.0997, +0.0162, +0.1531, +0.3364, -0.0450, -0.0111, +0.1189, -0.1334, -0.6545, -0.4830, +0.0474, +0.3154, +0.4580, -0.1064, +0.2929, +0.4214, -0.2082, -0.6345, +0.0035, +0.6610, -0.1338, +0.1163, +0.4461, -0.2158, -0.8791, -0.3630, +0.0719, +0.1888, +0.5635, +0.0478, -0.1271, -0.0503, -0.5142, -0.3326, -0.3739, -0.4792, -2.6695, +0.0054, -0.5449, +0.4130, +0.1073, +0.1240, +0.6417, +0.0663, +0.3216, -0.7660, -0.0552, -0.3331, +0.2927, +0.3266, +0.0314, -0.1650, +0.4794, -0.0994, +0.6366, -0.1988, -0.2426, -0.4117, +0.0769, +0.0283, -0.6750, -0.8874, -0.3598, -0.7254, +0.0542, -0.0244, -0.2915, +0.2490, -0.5648, -0.1576, -0.8881, +0.1953, +0.4120, -0.7454, +0.0790, +0.7552, -0.2105, +0.2571, -0.0879, +0.0528, -0.7195, -0.2049, +0.2198, -0.8199, -0.2095, -0.1536, -0.2254, -0.3881, -0.0710, -0.0862, -0.0728, -0.4765, +0.0377, -0.2601, +0.5323, -0.4757, +0.0056], +[ -0.5613, -0.0316, +0.5095, -0.3853, -0.1999, -0.2166, +0.2410, -0.1814, -1.0522, +0.0969, +0.9236, +0.2533, +0.0451, -0.0508, +0.0811, +0.3947, -0.3305, -0.2005, +0.0055, +0.4741, -0.6295, -1.6430, +0.3491, +0.0489, +0.2295, +0.0272, -1.0309, +0.3897, +0.0007, +0.2152, -0.6022, -0.1800, -0.9179, +0.0791, +0.0380, -0.1480, +0.1407, -0.1113, +0.1436, -0.0275, -0.0495, -0.1882, -0.0968, -0.5008, -0.5220, -0.0886, +0.3981, -0.1246, +0.0909, +0.1886, +0.3237, -0.5167, +0.2581, +0.3119, -0.0412, +0.0391, -0.2006, +0.1589, -0.0481, +0.0569, -0.3648, +0.6140, +0.0046, +0.4178, -0.4773, +0.1720, +0.1110, -0.4165, -0.3226, -0.2994, -0.1289, +0.0845, +0.3111, +0.2951, +0.4875, -0.6199, +0.1223, +0.4922, -0.3103, -0.1180, +0.1047, +0.6244, -0.4275, -0.2973, +0.1429, -0.6453, +0.1289, -0.7252, +0.1454, +0.6175, +0.3022, +0.2301, -0.5072, -0.1339, +0.2775, -0.1535, -0.2081, +0.2216, +0.1102, -0.1702, -0.1977, +0.2827, -0.0540, -0.0717, -1.2428, -0.4476, -0.7154, -0.5406, -0.3560, -0.2525, -0.3185, -0.1646, +0.0909, +0.6647, -0.1795, -0.1505, -0.1118, -0.3078, -0.0913, -1.1243, +0.2496, +0.1140, -2.2075, -0.4422, +0.6752, +0.3675, -0.5279, -0.3644], +[ +0.4551, -0.0319, -0.1932, +0.2266, -0.1468, -0.3072, -0.1329, +0.1246, -0.2067, -0.2614, +0.3834, -0.4731, -0.0135, +0.0497, -0.6278, -0.1505, +0.3569, +0.1982, +0.5036, -0.6404, +0.4569, -0.3846, -0.0121, +0.3326, -0.2668, +0.2187, +0.0431, +0.0004, -0.1539, +0.2131, +0.1308, -0.0228, -0.7287, -0.5572, +0.6008, +0.1236, +0.2499, +0.1608, +0.4676, -0.5957, -0.1967, -0.4873, +0.2819, -0.0164, -0.1783, -0.0527, -0.1868, -0.1273, -0.2112, +0.0099, -0.0311, +0.4071, +0.4450, -0.5066, +0.1030, +0.2545, +0.6692, +0.3454, -0.5475, -0.7075, +0.2926, -0.0085, -0.2729, -1.2123, -0.4895, +0.7207, -0.4900, -0.1653, +0.2227, +0.2817, +0.0906, -0.3284, -0.5089, +0.2956, +0.5533, -0.1981, +0.0924, -0.2792, +0.3144, +0.2213, -0.6193, +0.2680, +0.1391, +0.3618, +0.0205, -0.1751, +0.5281, -0.4151, +0.0489, -0.0676, -0.1298, -0.1577, +0.2879, -0.0986, -0.5174, -0.1008, +0.2711, +0.1748, +0.2306, -0.9342, +0.1570, +0.3747, +0.2685, +0.0691, +0.1287, -0.0570, +0.2586, +0.4351, -0.1724, +0.0868, +0.2339, +0.0590, +0.3207, -1.0457, +0.1448, -0.4016, -0.3144, -0.3675, -0.1135, +0.5790, -0.9001, +0.0850, -0.6078, -0.1776, -0.4906, +0.5657, +0.3524, +0.4872], +[ -0.7267, -0.3766, -0.7996, -0.8690, -0.1338, -0.5856, -0.9790, -0.6182, -0.4302, -0.5680, +0.2210, +0.6662, -0.0394, +0.0189, +0.0192, -0.0539, +0.5934, +0.7768, -0.1917, +0.5445, -0.4624, +0.0003, -0.5339, -0.3818, -0.7532, +0.6063, -0.0766, -0.1849, +0.1387, -0.1513, -0.2904, -0.4841, -0.8696, -0.6494, +0.3400, -0.4493, +0.7742, -0.5473, +0.3086, -0.7270, -0.3335, +0.0908, +0.0757, -0.4248, -1.3225, -1.2498, -0.5104, -0.1792, -0.0900, -0.1979, -1.1543, -0.6224, +0.3853, -0.4153, -0.1675, +0.3672, +0.0385, -0.2739, +0.3483, +0.1304, -0.2027, -1.0781, +0.0487, +0.9165, +0.3448, +0.1050, +0.6307, -0.0179, -0.2644, -0.6719, +0.8630, +0.2447, -0.7928, -0.7747, -0.4640, +0.3419, -0.3761, +0.4682, -0.3551, -0.7790, -0.1836, -1.2261, +0.0014, -0.0157, +0.7793, +0.0543, -0.0427, -1.2934, +0.4384, +0.6282, -0.4136, -0.7120, -0.0312, -0.1617, +0.3792, +0.3923, +0.4131, -0.0939, +0.0765, -0.0514, -0.6875, -0.6300, +0.0322, -0.1902, +0.0416, -0.0501, -0.3586, -0.0728, +0.1699, +0.6857, -0.2486, +0.4669, -0.8803, -0.7892, -0.0981, +0.1722, -0.9295, +0.4021, -0.8335, -0.7050, +0.0081, -0.6816, +0.3777, +0.2073, -0.2389, -0.5322, +0.1118, -0.0305], +[ +0.1518, +0.5124, +0.2856, +0.3206, -1.0614, -0.7988, +0.6489, -0.3330, +0.0626, -0.7497, -0.3054, -0.3453, +0.3817, -0.3338, -0.5490, -0.6551, -0.2633, +0.8902, +1.0987, -0.1853, -0.5848, +0.1062, +0.4732, -0.8558, +0.2518, -0.6830, +0.0990, +0.0484, +0.6778, -0.6857, -0.2717, -0.0487, +0.2458, +0.0854, -0.5820, -0.2739, +0.2974, -0.0806, +0.0331, -0.1789, +0.3143, -0.2483, +0.3278, -0.8205, +0.2240, +0.2381, +0.4927, +0.5869, -0.0209, +0.2602, +0.0947, -0.5313, +0.1366, +0.7339, +0.1222, -0.1071, +0.3209, -0.6647, +0.3956, -1.1462, +0.1540, -0.6027, -0.6462, -0.0196, -0.0257, +0.2174, +0.0618, -0.4277, -0.2348, -0.1575, +0.0113, -0.1159, -0.2370, -0.7871, +0.6167, -0.5572, +0.3090, -0.8006, -0.1515, -0.3669, +0.7213, -0.8533, -0.3268, +0.3503, -0.3551, +0.2349, +0.5376, +0.2798, -0.2976, +0.0167, -1.5816, +0.0884, -0.3257, -0.0122, +0.0005, +0.5181, +0.4005, +0.2125, +0.0817, -0.1632, -1.3130, -1.2145, +0.1358, +0.5636, -0.3694, -0.3336, -0.6762, +0.3142, +0.6745, -1.0468, +0.3761, -0.0945, -0.0999, +0.1924, -0.0761, +0.4415, -1.3590, +0.4247, -0.8823, -1.2536, -0.6982, -0.6742, -1.6875, +0.2924, -0.2236, -0.2251, -0.0849, +0.1060], +[ -0.2809, -0.5262, -0.2225, -0.2377, +0.4993, -0.6156, -0.4075, -0.0431, -0.0557, +0.1105, -0.6226, +0.2642, +0.0313, -0.1356, +0.2995, -0.1605, -0.2844, +0.0588, -0.7481, +0.3667, +0.3974, -0.5936, -0.8852, +0.3301, +0.0846, -0.2080, +0.6778, -0.4275, +0.5747, +0.1188, -0.1728, -0.6314, +0.1443, -0.5844, +0.4162, -0.5322, -0.4064, -0.8819, +0.0508, +0.2179, +0.1001, +0.7090, +0.4653, -0.9416, +0.0668, -0.2436, -0.2129, +0.3427, -0.5489, -0.9096, -0.0917, +0.0727, -0.3989, +0.5349, +0.1648, -1.0449, -0.4291, -0.1728, -0.2757, -0.1645, -0.0187, -0.4139, +0.4843, -0.2568, -0.0983, -0.2277, +0.0900, -1.8861, -0.5909, +0.2268, +0.0799, -0.2358, -0.3471, -0.0441, -0.3774, +0.0699, -1.4087, -0.0041, -0.0716, -0.4921, -0.4239, +0.3420, -0.0662, +0.9081, +0.1914, -0.1240, -0.3794, +0.5857, +0.0536, -0.0472, -0.3365, -0.2709, -0.0922, +0.1280, +0.1297, +0.2072, -0.3271, -0.0874, -1.2091, +0.2147, -0.1462, +0.0871, -0.8567, -0.2144, -0.6922, -0.5972, -0.2472, -0.0717, -0.0147, +0.2899, +0.1847, -0.1391, -0.5344, -0.6827, +0.4351, +0.0889, -0.9915, +0.4124, +0.0220, -0.2009, -0.9442, +0.0113, -0.9631, -0.0650, -0.4303, +0.3435, -1.2977, -0.2697], +[ -0.9292, +0.2608, +0.1856, -0.2181, +0.2864, +0.4665, +0.1183, -0.8772, +0.0637, -0.6156, +0.2125, +0.0861, +0.3298, +0.0282, +0.1922, +0.1052, +0.2205, +0.0923, +0.0565, -0.5392, -0.2462, +0.4160, +0.3582, -0.2283, -0.7549, +0.2029, +0.4387, +0.1588, -0.3804, +0.3135, +0.0810, -0.5952, -0.7394, +0.1698, +0.4097, -0.7306, -0.0494, +0.0300, +0.0150, -0.1442, +0.1094, -0.3293, +0.3067, +0.3319, -0.0988, +0.3934, +0.1500, -0.5475, -0.1318, -0.2197, -0.5067, -0.1792, +0.0558, +0.2852, -0.3734, +0.8150, -0.1424, +0.0324, -0.6778, -0.8345, -1.0479, -0.0120, +0.1208, -0.2252, -0.1481, -0.3718, +0.1413, -0.3404, -0.9226, +0.4955, +0.3686, -0.8111, -0.1841, +0.0163, -1.0335, +0.6153, -0.2061, +0.0014, -0.1898, +0.2517, -0.7933, -0.5624, +0.0223, -0.1111, -0.7173, -0.5490, -0.0761, -0.2222, -0.0284, +0.1807, -0.4117, -0.0473, -0.2069, -0.7928, -1.1569, -1.3606, +0.0030, +0.0516, +0.0198, +0.6680, +0.2385, -0.2643, +0.5895, -0.7420, +0.4909, +0.2861, -0.0732, +0.6386, -0.2367, -0.1159, +0.0837, -0.7266, -0.4135, +0.0526, -0.3135, +0.1495, -0.0127, -2.0576, -0.0804, +0.0785, -0.4744, +0.2081, -1.2179, +0.7396, -0.3955, +0.2333, -0.0346, +0.2791], +[ -0.2268, +0.2013, -0.5402, +0.2770, -0.0082, +0.4595, -0.1749, -0.2543, -0.1718, +0.0961, +0.0349, +0.3766, +0.0737, +0.1959, -0.3471, -0.1843, -0.0979, +0.1185, +0.3418, +0.1544, -0.1183, -1.2213, -0.6225, +0.0391, -0.5351, +0.3344, -0.5902, -0.1954, -0.0066, -0.4488, -0.0837, -0.2661, -0.6075, -0.4927, +0.0208, +0.1308, +0.2957, -0.1448, -0.3114, -0.6437, -0.1392, +0.2135, +0.5756, -0.4650, -0.0871, -0.0378, +0.0438, -0.7491, +0.1258, +0.2093, +0.3463, +0.3314, -0.1335, -0.2222, -0.1071, +0.4345, -0.2314, -0.4647, -0.6163, -0.7831, -0.2002, +0.3730, -0.2890, +0.2425, -0.6488, +0.1770, -0.1440, -0.2539, -0.2734, +0.4355, +0.6381, -0.3941, +0.1792, -0.2053, -0.5537, -0.1537, -0.5183, +0.2566, -0.1217, +0.2459, +0.6899, -0.0281, +0.2930, -0.5520, +0.2116, -0.1514, -0.2412, +0.2833, -0.1344, +0.1574, +0.0028, -0.5203, -0.2195, -0.0272, +0.5438, -0.0241, -0.5652, +0.0420, +0.2021, -0.0554, +0.1088, -0.4577, -0.4282, +0.0337, +0.3764, -0.4121, -1.2664, +0.3727, -0.0548, -0.2052, +0.4138, -1.0687, +0.1104, +0.3876, -0.0396, -0.2886, +0.2004, -0.1510, +0.0247, -0.3260, -0.6714, +0.0787, -1.5699, +0.3883, -0.1314, +0.5150, -0.3001, -0.2822], +[ +0.1684, -0.1801, -0.3803, +0.3242, -1.3898, -0.0164, +0.3353, -0.0684, -0.1274, -0.5869, -0.4406, -0.0327, -0.0911, -0.1410, -0.0482, -0.4738, -1.2314, +0.2128, -0.0070, +0.1838, +0.0874, +0.0349, +0.2578, +0.2648, +0.5699, -0.4537, -0.2206, +0.3551, +0.3482, -0.3540, -0.1552, +0.1978, -0.9056, -0.3204, -0.2323, -0.6219, -0.4323, -0.1937, -0.0836, +0.1794, -0.0247, +0.1785, +0.1420, +0.0799, +0.2649, +0.3340, -0.0749, -0.3701, +0.3743, +0.3156, -0.1766, -0.1078, +0.5056, +0.4657, +0.4107, +0.2601, +0.6687, -0.0331, -0.2322, +0.2948, -0.1161, -0.0473, -0.7238, -0.1265, -0.3066, -0.3860, +0.2964, -0.2473, -0.0809, -0.3711, -0.7312, +0.0084, +0.3872, -0.0947, -0.6261, -0.0878, +0.1778, -0.0130, +0.1784, -0.9601, +0.2736, +0.0141, -0.1347, -0.7251, -0.2413, +0.3626, -0.1804, -1.2693, +0.1459, -0.6756, -0.2493, +0.0932, +0.3681, -0.5659, -0.0836, +0.0400, +0.2949, -0.3150, +0.2663, +0.1656, -0.6306, -0.0984, -1.2519, +0.6206, +0.0805, +0.1215, +0.3839, -0.1390, +0.7582, +0.2061, -0.1455, -1.3268, +0.3533, -1.6798, -0.5648, -0.4298, -0.8972, +0.3650, -0.6773, -0.0183, +0.0872, +0.4950, -0.9771, +0.2133, +0.1443, -0.0497, +0.4870, -0.2217], +[ +0.6267, +0.1301, -0.3306, -1.0258, +0.2057, +0.4931, -0.2351, -0.2018, -0.2368, -0.5251, +0.3094, -0.2823, +0.4636, -0.1351, -0.1550, +0.1763, -0.8259, -0.6003, -0.3396, +0.1493, +0.4048, +0.1490, +0.2579, -0.1343, -0.0206, -0.6311, +0.3482, -0.0913, -0.8055, +0.0169, +0.7410, -0.1831, +0.2173, -0.1678, -0.0208, +0.5627, -1.4239, -0.0164, -0.0073, -0.2144, -0.4044, +0.1796, +0.2598, +0.2679, +0.4010, -0.2579, -0.3336, -0.0400, -1.3157, -0.0357, -0.4101, -0.0237, -0.1238, +0.5636, -0.3515, +0.4706, -0.2472, -0.7447, +0.1059, -0.2435, +0.4814, +0.5299, +0.4779, -0.7503, -0.1554, -0.6424, -1.2135, -0.6341, +0.2854, +0.5496, +0.8835, -0.1009, -0.4304, +0.2574, +0.2398, -0.1378, +0.1702, -0.8172, +0.4276, +0.2123, -0.0892, -0.2800, +0.2954, -0.8317, +0.2422, -0.0725, -0.0830, +0.3638, +0.0008, +0.1038, -0.3386, -0.2826, +0.6363, +0.1712, -0.3421, -0.0179, +0.3188, -0.2417, +0.0737, +0.4939, +0.1590, -0.4242, -0.2644, -0.2834, +0.1430, -0.0259, -1.2540, +0.1671, +0.1528, +0.4099, +0.1172, -0.2910, +0.2072, -1.3059, -0.9609, -0.5290, +0.0630, -0.0445, -0.9980, -0.1157, -1.6957, +0.2090, +0.3895, -0.3709, +0.1529, +0.0459, -0.2081, +0.5258], +[ +0.4619, -0.5045, +0.0551, -0.9881, -0.8347, +0.2548, +0.1978, -0.7792, -0.4077, +0.4406, +0.6625, -0.3996, +0.2176, -0.4900, +0.2775, -0.5605, +0.0858, +0.0350, +0.0021, -1.0448, -0.4682, +0.0814, +0.0182, -0.1981, +0.3167, -0.0874, -0.4012, -0.4910, -0.9434, -0.7696, -0.1997, -0.2376, +0.1798, -0.6100, -0.9803, -0.5586, -0.2755, +0.2490, -0.0105, -0.0703, -0.1876, -0.5880, -0.6362, -0.0205, -0.3295, +0.1129, -0.5366, -0.1106, +0.4670, +0.5399, -0.7514, +0.2281, +0.5209, -0.9634, -0.2351, +0.3960, +0.0656, -0.2068, +0.0328, -0.3803, +0.4883, +0.7068, -0.0755, +0.3051, -0.1799, +0.3548, +0.0245, -0.8406, +0.5388, -0.3920, -0.0589, +0.2305, -0.0688, +0.3521, -0.1127, -0.5709, +0.7565, +0.2302, +0.1326, +0.0851, +0.2450, -0.0791, -0.4171, +0.0232, -0.2033, +0.0597, -0.1151, -0.0953, -1.1862, +0.1883, -1.5003, -0.7315, -0.4973, +0.0377, -0.3782, -0.9304, -0.5009, -0.1716, -0.3631, +1.0673, -0.1637, +0.0956, +0.1959, -0.1385, -0.3929, +0.6728, -0.8928, -0.6624, +0.2334, -0.1005, -0.6072, +0.5098, +0.2577, -0.8387, -0.0504, +0.0006, -0.4881, -0.2785, -0.6791, +0.2444, -1.6745, +0.7535, +0.1534, -0.6352, -0.1115, -0.8862, +0.4983, -0.3777], +[ +0.0039, -0.2421, -0.6910, -0.3335, -0.0837, -0.2838, +0.2400, -1.2017, -0.1120, -0.0139, -0.5140, -0.1658, +0.5439, +0.0746, +0.0851, -0.1371, -0.7936, +0.1147, +0.5279, -0.0356, -0.2768, -0.0167, +0.1016, -0.2588, -0.3150, +0.2725, -0.0054, +0.2662, +0.0579, -0.1121, -0.0991, +0.2667, +0.7342, -0.7297, +0.4873, -0.1084, -1.1444, +0.0317, -0.1765, -0.0591, -0.0372, +0.3193, +0.0158, +0.3735, -0.1446, +0.2017, -0.1544, +0.4685, +0.0265, -0.6809, -0.4011, -0.0152, +0.4425, -0.2115, -0.2186, -0.1628, +0.1875, -0.0227, -0.3668, +0.1109, +0.2440, +0.0213, -0.2574, -0.0887, -0.1618, +0.0969, -0.0538, -0.1107, +0.5406, +0.0602, -0.2506, -0.5262, -0.4628, +0.0089, +0.2437, +0.1938, +0.2170, -0.3531, -0.7044, +0.1436, +0.2583, +0.3916, -0.2783, -0.2629, +0.0761, +0.0875, -0.9802, +0.0204, +0.1054, +0.2970, +0.7322, -0.5680, -0.0099, -0.3184, -0.1267, -0.3843, -0.0616, -0.8026, -0.2121, +0.2040, -0.3985, -0.0946, +0.1960, +0.1519, +0.4106, -0.0654, +0.5344, -0.3274, -0.3358, -0.2711, +0.6550, +0.4539, -0.7734, +0.1422, -0.2948, +0.1008, -0.0853, -0.2603, +0.7007, -0.6726, +0.0125, +0.1267, -0.6258, +0.1602, -0.2965, -0.1978, -0.6674, -0.4518], +[ -0.9500, +0.5158, -1.1744, +0.0740, +0.0436, +0.0438, -0.4280, -0.2762, +0.2074, -0.1028, +0.0739, -0.0115, -0.1277, -0.2505, -0.4827, -0.2839, +0.1152, +0.1610, +0.3091, +0.6768, -0.2460, -0.0686, -0.4819, -0.3605, +0.1447, +0.4809, -0.4239, -0.4925, +0.5307, +0.0843, +0.1355, -0.0367, +0.2052, -0.3004, +0.1302, +0.4693, +0.3006, -0.4246, +0.4669, +0.1178, +0.1144, -1.1948, -0.1282, +0.4038, -0.4283, +0.1599, -0.4491, +0.2429, -1.0034, +0.0174, +0.5517, +0.4962, -0.2714, -0.3836, -0.2347, -0.4319, -0.1098, -0.6308, +0.9688, -0.2591, -0.8816, -0.7226, +0.4885, -0.1887, +0.5752, +0.2882, +0.1037, -0.0317, +0.3730, -0.1366, -0.4621, -0.2760, +0.0279, +0.5956, -0.9843, -0.4147, +0.0957, +0.5332, -0.2361, -0.2058, -0.0305, -0.2593, -0.1523, -0.5416, +0.2070, -0.0619, -0.0003, +0.1300, -0.4867, +0.6031, -0.6785, +0.1582, -0.1877, +0.0956, +0.2111, -0.6048, +0.4825, -0.1882, +0.0376, +0.2428, -0.1485, +0.1739, -0.3589, -0.4452, -0.3057, -0.4095, -0.2261, -0.8174, -0.6000, +0.4134, -0.3563, +0.3176, -0.0916, -0.0814, +0.5660, +0.0409, -0.7521, +0.6180, +0.2267, -0.5896, -0.1423, +0.0642, -0.2697, -0.2845, +0.0757, +0.2297, -0.2817, +0.6343], +[ +0.3890, +0.0535, +0.3087, +0.2975, -0.7018, -0.0931, +0.4065, +0.4104, -0.1657, +0.2489, +0.0326, +0.3264, +0.2226, -0.2367, +0.5259, -0.3036, -0.9529, +0.4010, +0.1735, -0.0055, +0.1524, -0.6000, +0.5753, +0.1844, -0.1587, -0.3337, -1.9309, -0.1105, -0.4555, +0.4847, +0.0744, +0.0622, +0.2596, +0.5020, +0.2214, +0.1037, +0.5817, +0.1068, -0.1771, +0.0581, +0.3138, -0.0515, +0.3535, -0.8904, -0.5829, +0.2976, +0.2191, -0.0195, -0.8137, -0.6905, +0.2786, -0.1527, -0.4237, +0.1000, +0.2552, +0.0808, +1.0988, -0.1274, +0.2045, +0.4628, +0.1749, -0.3866, +0.6104, -0.3980, -0.0178, -0.3929, -0.1803, -0.8545, -0.0878, -0.4427, +0.3839, -0.5144, -0.3475, -0.0654, -0.1235, +0.2331, -1.4457, -0.4737, -0.6052, +0.5628, -0.2034, +0.3515, -0.2301, -0.0919, +0.3140, -0.3579, -0.6903, +0.3909, -0.9177, +0.2810, +0.0279, -0.3726, +0.4125, +0.2434, +0.0410, +0.0660, -1.0987, -0.0353, +0.2336, +0.1051, -0.4656, -0.4937, +0.0350, -0.2236, -0.0849, +0.5482, -0.6291, -0.2668, -0.7553, +0.4446, -0.1521, +0.2322, -0.0618, -0.7684, -0.0211, -0.7521, -0.4413, -0.2209, +0.1516, -0.3465, -0.2536, -0.3436, -1.3926, -0.0055, -0.0946, -0.2139, +0.4978, +0.1550], +[ +0.1824, +0.0143, -0.1206, +0.3375, -0.3361, +0.3083, -0.0700, +0.8453, +0.2253, +0.2099, -0.1996, -0.3395, +0.3576, -1.3679, -0.0428, -0.7877, +0.3538, +0.4466, -0.0145, +0.5967, +0.1201, +0.2372, -0.3292, -0.3154, -0.1127, +0.1202, -0.1974, +0.6890, +0.3200, -0.0740, +0.1855, +0.0077, -0.0945, +0.2474, -0.1007, +0.0700, -0.4022, +0.1296, +0.4136, +0.5564, -0.1594, -0.2018, -1.2523, -1.2306, -0.1650, -0.0376, +0.0669, +0.0331, -0.0342, -0.2498, -0.3276, +0.4391, +1.0456, +0.0483, -0.2005, +0.2550, -0.6899, -0.0965, +0.4833, +0.3001, -0.6011, -0.0260, -0.2868, -0.7893, -1.0207, -0.0175, -0.0952, -0.2876, -0.7890, +0.2103, +0.4201, -0.4367, +0.4146, -0.3874, -0.2699, -0.2160, +0.1711, -0.8880, -0.1532, -0.2323, -0.4310, -0.2285, -0.1300, -0.0841, -0.6891, +0.2807, -0.0937, -0.3057, +0.6814, +0.2866, +0.5278, +0.8035, -0.5203, -0.1778, -1.0515, +0.6584, +0.1471, -1.0273, -0.2658, -0.5072, +0.0127, -0.0615, -0.2851, +0.0409, -0.3019, +0.2049, -0.0702, -0.3491, +0.0534, +0.7843, +0.3878, -0.5921, +0.5680, +0.2656, +0.5469, -0.1330, -0.0072, +0.1807, -0.4021, +0.0038, +0.2884, -0.4720, +0.1204, +0.4983, -0.1370, -0.0990, +0.7926, -0.3488], +[ +0.2300, +0.6087, -0.0082, -1.2226, +0.1576, -0.4915, -0.3726, -1.0621, -0.6511, +0.2293, -1.1797, +0.5666, -0.7113, +0.0993, -0.2472, -0.4969, -0.9459, -0.0998, +0.1155, -0.3605, -0.3714, -0.0703, -0.9070, -0.8149, +0.4075, +0.3847, +0.3870, -0.6099, +0.3129, -0.5348, +0.2247, -1.0771, +0.5544, +0.3654, -0.5315, -1.0543, -0.4763, -0.4465, -0.6050, -0.2096, -0.1478, +0.3596, -0.3324, +0.3449, +0.2356, +0.0944, -0.2123, -0.2224, +0.2490, -1.4370, -0.0835, -0.2723, +0.1200, -0.3455, +0.1009, -0.3616, -0.3534, -1.7871, -0.3896, -0.2862, -0.2670, -0.3593, -0.5910, +0.5745, -0.2602, +0.0340, +0.1708, -0.4089, +0.3851, -1.6957, -0.2035, -0.6983, +0.0559, -0.5295, +0.4757, +0.2245, -1.7969, -0.2094, +0.1555, +0.4289, -1.2022, +0.0317, -0.1430, -0.2117, +0.4984, -0.4803, +0.7204, -0.3257, -0.6799, +0.0338, +0.3276, +0.3263, -0.3260, -0.9453, -0.0989, +0.3106, -0.5899, +0.0706, -0.0357, -0.1701, -0.4282, -0.4814, -0.8425, -1.0043, -0.2107, +0.0957, -0.8044, -1.7443, +0.2266, +0.0735, +0.1612, -0.1467, +0.0684, -0.8959, -0.7182, -1.7431, +0.0837, +0.2855, +0.2861, -0.3948, -1.2593, -0.1133, +0.1008, +0.3739, -0.0448, -0.2614, -1.0801, -0.0383], +[ -0.0219, +0.4673, +0.0720, +0.1025, -0.1718, +0.4312, +0.3162, +0.1224, -0.0772, -0.2335, +0.3989, +0.5195, +0.0886, +0.0311, -0.9016, +0.4079, +0.3557, +0.0124, +0.2610, -0.0354, +1.1624, +0.1489, +0.2329, +0.0525, -0.7647, +0.1217, -0.2150, -0.1314, +0.1197, +0.2997, +0.0565, +0.6098, -0.0841, -0.0375, +0.6587, -0.0039, -0.2714, +0.7896, -0.3866, -0.7326, +0.3856, +0.7797, -0.0919, -0.1280, -0.2440, +0.5504, +0.2908, -0.2026, +0.1612, +0.1853, -0.2838, +0.5732, -0.0413, -1.3385, -0.7872, -0.4109, +0.6555, +1.0085, -0.6796, +0.1276, -0.0543, -0.6212, -0.4915, -0.5643, +0.1743, +0.0960, +0.1293, +0.0850, +0.5357, +0.5093, +0.4603, +0.2881, -0.1999, -0.4185, +0.1500, +0.4510, -0.4934, -0.4103, -0.1194, -0.0130, +0.2831, -0.0871, +0.5230, +0.1946, -0.4303, +0.7498, +0.4965, +0.0346, -0.3671, -0.7613, -0.2100, -0.3338, -0.1799, -0.1297, -0.2704, +0.5702, -0.3001, +0.2092, -0.4677, +0.0012, +0.4288, -0.2035, +0.1332, +1.0783, +0.0607, +0.4426, +0.5940, +0.6015, -0.8767, +0.3162, +0.3726, -0.2623, +0.1870, -0.0285, +0.1607, -0.0021, +0.0700, +0.2217, +0.3027, +0.2830, -1.4722, -0.0339, +0.3761, -0.3429, -0.2930, -0.0237, +0.1299, -0.4305], +[ +0.1671, -0.2823, +0.1159, -0.7041, -0.5511, -0.4782, -0.4659, -1.1058, +0.1460, -1.3718, +0.2498, +0.1930, -0.2512, -0.1289, -0.2683, -0.5802, -0.0859, +0.0886, -0.0273, -0.0261, -0.4940, +0.0258, -0.0169, +0.1049, +0.2472, +0.1351, +0.7329, -0.1584, +0.1520, -0.3350, -0.6529, +0.1952, -0.9995, +0.0622, -0.4440, +0.2660, -0.8487, +0.1427, +0.7882, +0.2495, +0.2777, +0.1706, +0.0289, +0.6014, -0.7555, -0.3365, +0.3145, -0.5503, -1.6347, -0.6634, +0.4050, -0.5163, -0.6031, +0.4128, -0.9969, -0.3725, -0.1041, -0.7641, -0.1003, -0.3806, +0.2152, +0.0487, -0.0878, -0.0076, +0.1628, -0.6543, +0.0234, -0.2593, -0.2289, +0.1173, +0.1792, -1.0842, -0.9257, -0.4630, -0.3395, -0.6874, -0.0962, -1.0616, -0.5033, +0.5055, -0.5397, -0.8901, +0.0775, -0.3459, -0.3129, -0.0488, +0.3182, -0.2662, -0.7964, -0.1391, -0.2649, +0.2875, +0.4105, -0.7456, -0.3695, +0.2845, -0.0605, -0.0508, -0.2737, +0.1793, -0.5491, +0.4235, -0.0912, +0.3686, -0.7618, -0.1382, -0.5352, -0.2718, +0.4649, +0.5763, +0.4316, -0.3403, -0.0679, -0.4345, +0.2904, -0.3905, -0.9981, -0.2377, +0.2218, -0.3052, -1.3612, -0.4851, +0.5302, +0.1600, -0.2865, -0.2246, -0.4073, +0.3381], +[ +0.0889, +0.0775, -0.6289, -0.1875, +0.4177, -0.2482, -1.6165, -0.7609, -0.1220, +0.1504, +0.4350, +0.4812, +0.0481, -1.1510, +0.2691, +0.3924, -0.5124, +0.2843, +0.0126, -0.1909, +0.2830, +0.3845, -0.5436, +0.1834, -0.3164, +0.1342, +0.6956, +0.5842, -0.2587, -0.6035, +0.4699, -0.4336, +0.0916, -0.7320, +0.1821, -0.2561, +0.4985, +0.1053, -0.6610, +0.7626, -0.6151, -0.0714, +0.4482, -1.2292, -0.1627, -0.2995, -0.7809, +0.2100, -0.5498, -0.0004, -0.4434, -0.0608, +0.2343, -0.0094, +0.5446, +0.2986, -1.0180, -0.0752, -0.3189, +0.1246, -0.8013, -0.5674, -0.1408, +0.4468, +0.3148, -0.2493, +0.3091, -1.9250, -0.7569, +0.3410, -1.9147, -0.2626, +0.1818, -0.2512, -0.2214, -0.3516, -0.0064, -0.2877, +0.0865, +0.5975, -0.2466, +0.1317, +0.0568, -0.6254, -0.0446, +0.3834, -0.4067, +0.3229, -0.5899, +0.4960, -0.4747, +0.5292, -0.7871, +0.3493, -0.6473, +0.5501, -0.0895, -0.3299, +0.4775, -0.1642, +0.0202, +0.1572, -0.3672, -0.3397, -0.8822, +0.0939, -0.2822, +0.1689, -0.1651, +0.0127, +0.4674, +0.3544, -0.5526, -0.0664, +0.1906, +0.7608, -0.4556, -0.4964, -0.3022, +0.2400, -0.6743, +0.1732, +0.3559, -0.0506, +0.1518, -0.1480, +0.2606, +0.0297], +[ +0.1881, -0.1553, -1.5724, -0.3950, -0.0466, -0.2909, -0.0651, -0.1796, +0.0579, +0.6609, -0.0485, +0.0586, -0.3038, -0.0271, -0.4263, +0.4364, +0.0581, -0.1549, +0.0078, +0.0661, -0.7348, -0.2544, +0.1467, +0.3350, -0.5166, -0.0372, -0.2058, +0.5173, -0.1624, +0.5320, +0.3230, -0.6647, -0.3546, -0.3545, -0.3915, -0.0860, -0.5308, +0.1087, +0.1293, -0.4919, -0.0958, -0.8816, +0.5965, +0.3580, -1.1357, -0.1426, -0.0060, -0.3153, +0.3681, -0.0367, +0.6846, +0.2793, +0.6284, -0.2864, -0.5706, +0.3115, -0.0177, +0.2115, +0.3319, +0.0076, -0.0807, +0.1127, +0.0774, +0.3027, +0.3027, +0.9219, -0.3770, +0.0644, -0.3406, +0.0139, +0.0360, -0.1875, +0.1214, -0.0015, -0.2289, -0.1416, -0.3921, -0.1148, -0.3307, -1.1176, -0.4131, -0.0516, +0.3109, -0.6787, +0.3690, +0.0135, -0.1024, -0.0886, +0.0624, +0.1677, +0.8001, -0.0035, -0.1321, -0.0525, +0.1772, +0.0420, -0.6397, -0.4285, +0.4524, -0.5925, -0.1888, +0.3598, -0.0754, -0.3101, -0.3709, +0.1504, -0.2078, -0.8417, -0.5245, -0.1972, -0.5917, -0.5529, -0.2298, -0.3431, +0.3858, +0.3420, -0.3509, +0.7314, +0.6297, -0.0504, +0.0196, +0.1993, +0.3695, -0.6020, +0.1692, -0.3026, -0.0274, +0.0532], +[ -0.0535, -0.0434, +0.3107, -0.0591, -0.4013, +0.0417, +0.5899, +0.0130, +0.5355, -0.5781, +0.3742, -0.1657, -0.0823, +0.1356, +0.2386, -0.1355, -0.4844, -0.4785, -0.1089, +0.2514, +0.1284, +0.6192, -0.5746, -0.0572, -0.3031, -0.0263, +0.3194, -1.4349, -0.7038, -0.0708, +0.0176, +0.1220, +0.1893, +0.3585, -0.0543, -0.0984, +0.0147, +0.5180, -0.9553, -0.3607, -0.6300, -0.2242, -0.3692, -0.3634, -1.2479, +0.6050, +0.4687, +0.1761, -0.1653, +0.4686, +0.5265, -0.1602, -0.0254, +0.2749, -0.0829, -0.6103, -0.2437, -0.3340, +1.1699, +0.2183, +0.0314, -0.3264, -0.6732, -0.1501, -0.3775, +0.1754, -0.6461, +0.0506, +0.4287, -0.1066, +0.8648, -0.3817, -0.1776, +0.2415, +0.4775, +0.2610, -0.3349, -0.1050, -0.4431, +0.2219, +0.7191, -0.2294, +0.3001, +0.8845, +0.1041, -0.2900, -0.2438, -0.3065, +0.3172, +0.4716, +0.6355, +0.3926, +0.0178, -0.9722, +0.7055, -0.1003, -0.0791, +0.0472, -1.5021, -0.7299, +0.0327, +0.3117, -0.7694, -0.2055, -0.3508, -0.4653, -0.1949, -0.9672, -0.1199, -0.0421, +0.0697, -0.5390, +0.1305, -0.8102, -0.1820, +0.3357, -0.3483, -0.7162, +0.5876, -0.3791, -0.3721, -0.9082, -0.7910, +0.5692, +0.4901, -0.6508, -0.1578, +0.2336], +[ -0.0991, -1.9675, -1.1434, -0.0578, -0.4255, -0.0507, -0.3146, -0.7487, -0.4001, +0.1678, +0.7082, -0.1235, -0.0231, -0.3190, -0.0053, -1.8510, -0.7238, -0.5839, -0.2875, +0.2034, -0.0091, +0.0977, -1.2770, -0.2555, -0.3162, -0.1805, +0.1029, +0.0722, -0.1223, +0.2691, -0.4410, +0.3330, -0.1966, +0.3145, +0.2016, -0.1409, -0.4752, -0.0351, -1.0175, -0.0973, +0.2214, +0.0240, +0.5960, -0.3388, +0.1563, +0.3184, -0.6502, -0.9855, -0.9964, -0.1694, +0.4374, -0.0568, +0.2252, +0.0092, -0.4467, +0.0417, -0.5258, -0.0546, -0.6569, -0.3540, -1.2910, -0.7955, +0.1682, -0.1409, +0.1721, -0.4994, -0.0251, -1.7718, -0.6462, -0.4405, -0.7201, +0.3206, -0.0858, -0.0252, +0.1274, +0.2316, -0.5193, +0.1882, +0.2965, +0.4450, -0.3046, -0.5045, +0.5530, -0.2995, +0.4155, -0.2074, -1.0422, -0.9297, -0.6145, -0.2277, +0.4566, +0.1720, +0.0193, -0.3610, -0.0938, -0.6841, -0.3188, -1.2707, -0.0435, -1.0730, -0.3487, -0.0927, -0.0735, +0.0962, -0.2547, -0.0440, -0.6346, +0.1233, +0.0456, +0.5358, +0.0747, -0.1466, -0.4682, -0.2771, +0.1966, -0.2784, -0.4773, -0.4910, -0.2745, +0.4193, -0.2568, -1.9416, -0.5763, -0.3306, -0.1720, -0.0927, -0.8908, +0.1176], +[ +0.2536, -0.5662, -1.4522, -0.5358, -0.2006, +0.0220, -0.0610, +0.0789, -1.8121, +0.1627, -0.3495, -0.6294, +0.4751, +0.1971, -0.4895, +0.0809, -0.6595, -0.5438, +0.7782, +0.6407, -0.0433, +0.1764, -0.2216, -0.0686, +0.0906, -0.6181, -0.3142, -0.4193, -0.5353, +0.2141, -0.2462, -0.4703, -0.5101, -0.5080, -0.3058, -0.0421, -0.3943, -0.1619, +0.3189, +0.7229, -0.5070, +0.4745, -0.5701, -0.2622, -0.0397, -0.5832, +0.8179, +0.3112, +0.4857, +0.5036, +0.5898, -1.3488, -0.5989, +0.0316, -0.0931, -1.2044, -1.3549, -0.4709, +0.2934, -0.5466, -0.1476, +0.3979, -0.4231, +0.1120, -0.3600, -0.7282, +0.3255, +0.1035, -0.6146, +0.1888, -0.0499, +0.1143, +0.3409, -0.0101, +0.1368, -0.0465, -0.5839, -0.3748, +0.2394, +0.9458, -0.0254, -0.4362, +0.1776, -0.0580, +0.3576, -1.2487, -0.5310, -0.1680, +0.5085, -0.0916, +0.0656, +0.4350, -0.1020, +0.8172, +0.1495, -1.1081, -0.7834, -0.3577, -1.9330, -0.3652, -1.1755, +0.0698, -0.3965, -0.2653, +0.1445, -0.0767, -0.5884, -0.2787, -0.0916, -0.0178, -0.9965, +0.0826, +0.0155, +0.2869, +0.2088, +0.5580, -1.0579, -0.1831, -0.5635, -0.1048, -1.1000, +0.3504, +0.0230, -0.4332, -0.3865, +0.0846, -0.3690, -0.4813], +[ -0.4787, +0.2002, +0.2028, -0.0158, -0.2770, +0.1566, +0.1161, -0.0419, +0.2129, -0.2984, -0.1568, -0.0816, -0.0431, -0.2907, +0.0723, -0.1756, -0.0761, +0.0398, -0.3367, +0.2629, +0.3230, +0.0630, +0.1386, +0.0527, +0.2323, +0.0386, +0.1846, -0.0896, -0.1129, -0.1477, +0.0972, +0.1004, -0.1855, -0.3664, +0.3041, +0.2854, +0.2017, +0.1173, +0.4246, +0.2498, +0.3192, -0.3189, +0.4909, +0.2758, -0.5229, -0.1006, +0.2822, +0.1657, -0.6560, -0.3957, +0.4602, +0.1682, -0.5488, +0.1815, +0.1368, +0.0183, +0.2881, -0.1455, +0.2657, -0.8587, -0.1013, +0.4186, +0.3135, -0.8613, +0.2746, +0.5370, -0.2433, -0.2217, +0.3542, +0.2261, +0.1301, -1.1449, -0.9689, -0.7366, +0.1102, -0.0582, -0.2559, -0.1644, +0.0449, +0.1363, -0.1750, +0.2502, -0.1844, -0.1620, -0.2977, +0.5287, -0.4214, +0.6418, -0.2855, -0.0037, -0.4145, -0.3059, +0.0475, -0.0043, -0.8526, -0.5528, +0.3328, +0.2346, +0.1871, -0.5865, +0.6419, -0.1642, +0.3508, -0.0835, +0.2359, +0.0595, -0.1623, +0.1377, -0.1352, -0.3811, +0.4506, +0.2045, +0.0203, -0.0315, -0.0122, -0.3571, -0.1826, +0.5790, -0.3454, -0.4992, -0.9696, -0.5495, -0.3217, +0.1935, -0.6748, +0.0319, +0.1601, +0.0082], +[ +0.1543, +0.2776, +0.2125, -0.1371, +0.4160, +0.3294, -1.0957, +0.2656, +0.2960, -0.4023, +0.2340, -0.1207, -0.3459, +0.1713, +0.6184, +0.5171, -0.2404, +0.1536, -0.2846, -0.5125, +0.3653, -0.5599, +0.0234, -0.3938, +0.0080, +0.4929, -0.9391, -0.0329, +0.1044, +0.0408, +0.2737, +0.9848, -0.6877, -0.5425, +0.0472, +0.2561, +0.2861, +0.2821, -0.2904, -0.5215, -0.3803, -0.6176, -0.9423, +0.1615, -0.1899, +0.3273, +0.0132, +0.4926, -0.3626, -0.4278, -0.1285, +0.0150, +0.1360, -0.3941, -0.0030, -0.1985, -1.1165, +0.1333, -0.2363, +0.3486, +0.1008, +0.2353, -0.2938, -0.4431, -0.2364, -0.2566, +0.1370, -0.9465, +0.1358, +0.3459, +0.2047, +0.2755, -0.3602, -0.1038, -0.4590, -0.3507, -0.9952, +0.0772, -0.0768, -0.2582, -0.5881, -0.2763, +0.4777, +0.0767, -1.0746, +0.4439, -0.8703, -0.5357, -0.0913, +0.2446, -0.5459, +0.2101, +0.0278, -0.1329, +0.0798, +0.3622, +0.0351, -0.4444, -0.2385, +0.1734, -0.1854, +0.1911, +0.0680, -0.1799, +0.0571, -0.4096, +0.3666, +0.0189, -0.8021, +0.0096, +0.2552, -0.1276, -0.0449, -0.0363, +0.4031, -0.5259, +0.2744, +0.1172, +0.2298, +0.5545, +0.4626, +0.5044, -0.0241, -0.4306, -0.1280, +0.3301, +0.1978, -0.3536], +[ +0.1044, -0.7254, +0.2392, -0.2555, +0.5187, -0.1259, -0.0267, -0.0483, -1.1547, -0.4744, +0.4596, -0.2068, +0.2914, -0.1488, -0.5269, +0.5604, -0.9596, -0.6791, -0.1505, +0.4476, -0.6482, -0.4336, +0.2112, +0.1545, -1.2010, -0.2492, -0.1578, +0.0995, -1.7680, -0.0496, -0.2035, +0.7748, +0.3368, -0.1282, +0.8091, +0.1360, -0.2153, +0.5392, -0.3572, -1.0836, -0.4843, -0.0050, -0.1601, +0.2288, +0.0453, -0.3114, -0.1580, -0.3662, +0.3852, -0.3149, +0.3257, +0.0765, +0.3093, +0.1396, +0.1867, +0.5917, +0.3227, +0.0719, +0.0757, +0.3152, +0.0477, +0.8263, +0.4331, -0.3088, -0.3377, -0.1028, +0.0539, +0.0915, -0.6793, -0.4235, +0.3025, +0.3221, -0.3192, -0.0481, -0.0763, +0.2885, -1.1171, +0.6361, +0.7532, -0.7269, +0.0376, -0.2484, -0.1291, +0.3408, +0.3876, -0.3870, +0.7317, +0.3827, -0.2842, -0.5059, +0.4893, +0.0877, +0.1553, +0.9659, -0.0103, -0.3438, +0.9302, +0.1913, +0.3300, +0.1906, -0.5161, -0.5922, -0.2896, +0.2806, -0.1469, -0.7416, -0.3286, -0.1041, +0.3214, -0.8853, -0.3089, +0.3274, +0.2492, -0.8162, -0.3591, -0.2656, -0.4484, +0.0786, -0.7396, -0.2242, +0.4194, -0.0522, +0.2031, +0.5960, +0.5511, -0.2235, -0.3685, +0.1638], +[ -0.3699, -0.3807, +0.0028, +0.3853, -0.3473, +0.3783, -0.3137, +0.4999, -0.4700, +0.1855, +0.0250, +0.1907, +0.0717, -0.0765, +0.2081, -1.0673, -0.0229, +0.8743, +0.1154, -0.2901, -0.0200, +0.5757, -1.0128, -0.6901, -0.3488, -0.5791, -0.6534, -1.1944, +0.6867, -0.5736, -0.1345, +0.4021, +0.5175, +0.4459, +0.1793, -0.1494, +0.4040, +0.4946, +0.0618, +0.1245, +0.1907, -0.9389, -0.0765, -0.6841, +0.0778, -0.3652, -0.0633, +0.1939, -0.1546, +0.1572, -0.3063, -0.1174, +0.2252, -0.0803, -0.1216, -0.9586, -0.0063, +0.5818, -0.3919, +0.4517, -0.3592, +0.0098, +0.0147, -0.1723, +0.2093, +0.4135, +0.8197, +0.2438, +0.0600, +0.4231, -0.1608, +0.1411, +0.3974, -0.4794, -0.2719, -0.2291, -0.1298, -0.1203, -0.3707, +0.1493, +0.1233, -0.0575, +0.2616, +0.0770, -0.3670, -1.1465, -0.4462, +0.1386, +0.1485, -0.2544, -0.5235, +0.0563, +0.0058, +0.1420, -0.3137, -0.2150, -0.8871, +0.0340, -0.1614, +0.6602, -0.2263, -0.4392, +0.0526, +0.2306, +0.5134, -0.3948, -0.1330, -0.0663, -0.7350, +0.0353, +0.0651, -0.1853, +0.4299, -1.3736, +0.2536, +0.1521, -0.0121, +0.6278, +0.3257, -0.1518, -0.2645, +0.4809, +0.5553, -0.0840, -0.1191, +0.1542, +0.1102, -0.2089], +[ -0.0419, +0.2234, -1.4385, -0.1830, +1.3311, +0.6173, -0.2102, +0.0031, -0.4902, +0.0924, +0.1009, +0.0748, -1.5489, -0.1538, -0.2732, -0.0818, -0.6964, +0.2878, +0.2451, -0.4405, +0.1007, -0.0500, +0.3956, -0.2394, -0.4406, +0.1492, +0.1290, -0.3666, -0.3905, +0.1184, +0.4340, -0.5971, +0.0667, -0.1793, -0.5301, +0.5881, -0.7302, -0.5281, -0.2048, +0.0339, -0.6472, -0.9960, -0.6116, +1.3143, +0.5008, -0.5765, -0.1432, -0.1568, -0.2412, -1.2500, -0.4832, +0.0049, +0.1551, +0.6098, -0.0762, +0.0962, +0.1702, -0.4485, -0.9531, -0.2700, +0.2681, +0.1645, -0.9228, -0.2238, +0.0731, +0.1705, +0.3593, +0.4110, +0.3440, -0.4387, -1.1249, +0.5916, +0.0850, +0.1453, +0.4015, +0.2324, -0.2840, +0.0777, -0.1384, -0.0731, +0.0235, +0.0055, +0.3287, -0.1665, -0.3519, -0.2227, -0.4549, +0.0024, +0.1338, +0.0871, +0.3680, +0.5274, -1.4743, -1.1676, -1.4731, -0.2902, -0.5654, -0.3894, +0.6527, -0.3981, +0.2669, +0.1013, -0.8804, -0.9715, -1.0932, -0.7290, +0.0872, +0.0093, +0.4981, -0.8423, -0.2592, -1.1377, -0.1514, -0.1664, -0.6785, -1.5269, -0.0527, +0.9430, -0.0178, -0.6142, -0.6908, -0.5368, -1.6182, +0.4248, -0.5426, -0.3651, -0.6827, -0.7300], +[ -0.5645, -0.0951, -0.8245, -0.2915, +0.0918, +0.1296, -0.8500, +0.8293, +0.0947, -0.0885, -0.1730, -0.3815, -0.0692, -0.1989, -0.0563, +0.4089, +0.4482, -0.0204, -0.0750, -0.0014, +0.2101, +0.3434, -0.0062, -0.1062, +0.2121, -0.3191, +0.1604, -0.5890, -0.8282, -0.0523, +0.2027, +0.1242, +0.3165, +0.3932, +0.3421, +0.1213, -0.3542, -0.2865, -0.6644, +0.2467, -0.1323, +0.2825, -0.2337, -0.5893, -0.0853, -0.8551, -0.4441, -0.5042, -1.1045, +0.0843, +0.0584, -0.7077, -1.2498, -0.6926, -0.3114, -0.0837, -0.6698, -0.2653, +0.0489, -0.3547, -0.3114, +0.2408, -0.0194, -0.4708, +0.1986, +0.0656, +0.3541, +0.1654, +0.0352, -0.2591, -0.8707, +0.2080, -0.2313, +0.0107, -0.1276, +0.2932, -0.0761, +0.5935, +0.4470, -0.2565, -0.1063, -0.5294, +0.3806, +0.0910, -0.4328, -0.2868, +0.4114, -0.8960, +0.3032, +0.5253, -1.0797, -0.1307, -0.6211, +0.0088, +0.0559, +0.1488, +0.2288, -0.2893, -0.4812, -0.6787, -0.8455, -0.6098, +0.0031, -0.2632, -0.0195, -0.1413, -0.7222, -0.4115, -0.5803, +0.4494, -0.2986, -0.4152, -0.3315, -0.2730, -0.7341, -0.7955, +0.3027, +0.2047, -0.6978, +0.1749, -0.0703, -0.7464, -0.1227, -0.6139, +0.1868, +0.1686, -0.4433, -0.5345], +[ +0.5373, -0.5023, +0.3304, +0.1281, +0.3533, -0.6281, +0.2297, -0.4778, -0.1587, -0.6127, -1.2827, -0.3540, +0.2693, +0.0097, +0.1842, -0.2062, +0.3589, +0.0386, +0.0940, -0.6110, +0.5074, -0.4471, +0.0641, -0.4592, -0.1442, +0.3023, -0.3187, -0.5908, -1.2507, -0.6518, -0.1777, +0.8415, +0.0770, +0.0154, -0.0216, +0.1021, +0.1544, -0.5672, -0.5015, -0.6091, -0.8604, -0.0805, +0.2870, -0.4945, -0.0334, +0.1428, -1.0402, -0.4387, +0.4980, +0.1699, -1.3964, -0.6875, -0.4314, +0.2615, -1.1531, +0.7509, -0.3166, +0.5292, +0.2292, -0.3682, -0.2563, -0.0884, -0.0064, +0.3462, -0.0136, -0.4905, -0.5082, -0.7308, -0.0257, +0.2141, +0.4705, +0.0467, -0.0859, -0.5980, +0.4867, +0.1216, -1.3656, -0.5548, -0.6892, +0.1645, -0.1880, -0.3532, +0.5091, -0.0183, +0.4596, -0.2019, -0.1287, +0.6507, -0.1666, +0.7605, -0.1819, -0.3911, +0.7056, +0.0560, -1.0917, +0.1926, +0.1152, -0.5854, -1.2015, -0.2047, +0.2450, +0.4330, -0.1793, +0.0967, +0.3471, -0.8313, -0.5207, +0.4464, +0.3575, +0.0050, +0.0109, +0.3466, -0.6398, +0.0550, -0.3470, -0.1641, -0.5482, -1.6662, -0.3640, +0.4271, -2.0190, -0.2807, -0.4156, +0.5930, -0.2044, +0.2586, +0.3294, -0.0410], +[ -0.3317, -0.0433, +0.7553, +0.0780, -0.1600, +0.3487, -0.0899, +0.4752, -0.5306, -0.5418, -0.3998, -0.2042, +0.0573, -0.2629, -0.3835, -0.2808, -0.7365, +0.0468, +0.1259, +0.0197, +0.1999, -0.0067, -0.0952, -0.5982, +0.6603, -0.3708, -0.4107, -0.2107, +0.1856, +0.0801, -0.0317, -0.1030, +0.6148, +0.0689, +0.0360, +0.5873, +0.6373, -0.4274, +0.3931, +0.6688, -0.0991, -0.8677, -0.1208, -0.6740, -0.0005, -0.3582, -0.0956, -0.5954, -0.9473, +0.2657, +0.4797, -0.1288, -0.5544, +0.2299, -0.3652, -0.2259, +0.0398, -0.3877, +0.1457, +0.1774, -0.3009, +0.2741, -0.2197, +0.1699, +0.0348, +0.2522, +0.5760, +0.3269, -0.2433, +0.3860, +0.5211, -0.6615, +0.2792, -0.5678, +0.5221, +0.0590, +0.1282, +0.5853, -0.1564, +0.1237, -0.0384, +0.3060, -0.3530, +0.0635, -0.1059, -0.8397, +0.0054, -0.5784, -0.1677, +0.6336, +0.4885, +0.0895, +0.0792, +0.7527, +0.0445, -0.4034, +0.1270, -0.0362, -0.2035, +0.0901, +0.2301, -0.6577, +0.1569, -0.0478, -0.7499, +0.0353, -0.5966, -0.0205, -0.5135, +0.4103, +0.1819, +0.1055, +0.0828, -1.3878, -0.6138, +0.0191, -0.2161, +0.2299, +0.1145, -0.0208, +0.5890, -0.4278, -0.2275, -0.6212, +0.2328, +0.4505, +0.1880, -0.2761], +[ -0.2579, -0.1070, +0.5948, -0.4495, -0.1056, -0.5783, +0.7626, -0.0990, -0.4974, -0.3786, +0.0336, +0.1340, +0.0176, +0.3846, -0.1908, -0.0323, -0.1243, +0.3143, -0.1815, -1.2845, -0.0969, +0.4785, -0.1254, +0.0742, -0.5627, +0.3179, -1.1277, +0.6710, -0.3180, -0.4783, -0.7258, +0.0998, +0.0103, -0.3908, -0.6606, +0.0864, -0.1134, -0.7322, -0.0021, -0.3648, -0.1118, -0.0069, -0.0316, -0.5033, +0.0592, -0.4308, -0.1743, -0.3476, +0.5224, -0.2702, -0.6365, -0.4019, +0.1359, +0.2903, +0.6723, -0.2187, -0.6024, +0.2384, +0.0491, -0.0900, +0.1348, -0.2781, +0.0112, +0.2478, -0.1627, -0.1756, +0.5521, -1.3692, -0.1336, +0.4796, -0.1884, +0.1825, -0.1318, +0.6813, +0.3728, -0.4068, -0.2569, +0.2171, +0.5401, +0.0103, -0.2397, +0.2136, +0.6071, -1.1484, +0.1637, +0.5346, -0.3671, -0.9121, -0.2676, -1.7229, -0.4905, -0.1932, -0.1517, -0.4315, +0.0992, -0.0417, +0.0596, +0.1999, +0.0300, -0.1353, +0.3451, +0.3250, -0.6266, +0.6477, +0.4953, +0.8932, +0.1584, +0.3444, -0.2406, +0.0892, -0.3448, +0.0994, -0.2997, +0.3734, -0.0937, +0.0631, -0.3965, +0.1908, +0.3220, +0.3505, +0.0664, -0.0990, +0.5812, +0.3055, -0.6768, +0.0508, -1.1169, -0.2971], +[ -0.2826, +0.3017, -1.0716, +0.5454, -0.2297, +0.2570, -0.2675, -0.3280, +0.5000, -0.6632, -0.1680, +0.0455, -0.5645, -0.2240, -0.0925, +0.0285, +0.5507, +0.3751, +0.4763, +0.3696, +0.0971, +0.0564, +0.0225, +0.1475, +0.4914, -0.2191, -0.6406, -0.1431, -0.6880, +0.2840, +0.5321, -0.1326, +0.1830, -0.2063, -0.6520, +0.2547, -0.0021, -0.0909, +0.2077, +0.0425, +0.3344, -0.5121, +0.5924, -0.6228, -0.2005, -0.7171, -0.1157, +0.0358, -0.4479, +0.0911, +0.2311, -0.2368, -0.3824, -0.4127, +0.0186, +0.3056, -0.2722, -0.4932, -0.6576, +0.6565, -0.2643, -0.2520, +0.0746, +0.6838, +0.3458, +0.3152, -0.5829, +0.6142, +0.2486, -0.6898, +0.0375, -0.0663, -0.0938, +0.0495, +0.5894, +0.5695, -0.0793, +0.0908, +0.3887, -0.1746, -0.7917, +0.0934, -0.3565, -0.7500, +0.2916, -0.2257, +0.4372, -0.0252, -0.2825, -0.5158, +0.6199, -0.2699, -0.0864, +0.1938, -0.7209, -0.2632, -0.6214, -0.0095, -0.7482, -0.1812, -0.0885, -0.3705, -0.4529, -0.7320, +0.1304, -0.2019, -0.3944, -0.1590, -0.2112, -0.0378, +0.0883, -0.1832, +0.4093, +0.0177, -0.9067, -0.0438, +0.3012, +0.1318, -0.1884, -0.1744, +0.6493, +0.2527, +0.3349, -0.0854, +0.1585, +0.5028, -0.0638, +0.4182], +[ +0.2906, -0.2576, -0.2176, -0.4541, +0.1092, -0.0287, -0.3137, -0.2885, +0.1561, +0.2431, -0.1863, +0.1705, -0.0177, +0.0854, +0.0712, -0.4275, -0.3382, -0.6201, -0.7132, +0.3172, -0.4919, +0.4363, +0.2332, +0.3105, +0.3940, -0.4142, +0.4294, +0.0273, +0.7051, +0.1778, -0.3064, +0.0910, +0.1420, +0.6417, -0.0247, -1.1611, +0.1286, +0.2238, -0.0254, +0.0795, -0.9549, +0.9174, -0.2747, -0.2260, +0.1629, +0.3881, +0.6297, +0.3515, -1.0133, +0.5295, +0.2742, +0.3474, +0.6074, -1.1186, +0.0476, +0.2279, -0.3011, -0.1067, -0.1332, -0.2300, -0.2225, -0.3024, -0.2980, -0.1358, -0.1022, -0.6499, -0.3039, +0.1199, -0.3481, -0.7577, +0.4489, -0.4166, +0.5674, -0.9603, -0.0928, -0.1741, +0.2443, -1.2442, -0.2971, +0.5504, -0.1294, -0.6932, +0.5146, +0.3808, -0.0010, -0.2611, -0.2290, -0.3077, -0.3866, +0.0346, +0.0652, -0.0467, -0.2865, -0.1689, +0.5712, -0.0300, -0.1392, +0.5242, -0.4779, -0.0639, -0.2994, +0.1722, -0.5602, +0.5796, -0.5325, +0.4226, +0.0793, +0.6263, +0.1931, +0.3964, -0.0242, -1.0088, -0.1576, -0.2754, +0.3829, -0.0360, -0.1474, +0.5173, -0.3908, +0.5383, +0.3459, -0.3353, +0.2198, -0.1983, -0.2535, -0.8102, -0.1733, -0.2498], +[ -0.2845, +0.2532, -0.3930, +0.0176, -0.0401, +0.3929, -0.2219, -0.0176, -0.6583, -0.8225, -0.3858, -0.6111, -0.3160, +0.1729, -0.5304, -0.4961, +0.4348, +0.1502, -0.0024, +0.5605, -0.5965, -0.3403, -0.0525, +0.4160, -0.1761, -0.5333, +0.6485, -0.1001, -0.3320, -0.2852, +0.0461, +0.3127, +0.2732, +0.4850, -0.7572, +0.3340, +0.1216, -0.2146, +0.5141, -0.0446, +0.3435, -0.1889, -0.0703, +0.1833, +0.6237, -0.2869, -0.1359, +0.3557, -0.6367, -0.2098, -0.3921, +0.2821, -0.6608, -0.7367, +0.1877, -0.3778, -0.2733, +0.2592, +0.3895, +0.5889, +0.1726, -0.8440, -0.1420, +0.2875, -0.5746, +0.0062, +0.1275, +0.3359, +0.3913, +0.3068, -0.4358, -0.1234, -0.0252, +0.3891, +0.2927, +0.5481, -0.1240, -0.7086, +0.2341, +0.0585, -0.0918, +0.4686, +0.2239, +0.2763, -0.4061, +0.5489, -0.3236, +0.2883, -0.0754, -0.4910, -0.4830, +0.0780, +0.4842, -0.1382, +0.4660, -0.5561, +0.1641, -0.1805, -0.2352, -0.4031, +0.3937, +0.0209, +0.1165, -0.4197, -0.1378, -0.0776, -0.1210, -0.0451, -0.4686, -0.4069, +0.3611, -0.2608, -0.3837, -0.6298, -0.1267, -0.3378, -0.0777, +0.1820, -0.0371, +0.4034, +0.0692, +0.0375, -0.2704, -0.4865, -0.4545, +0.3542, -0.1009, -0.8298], +[ +0.0277, +0.4274, +0.0410, -0.3348, +0.2236, -0.2796, +0.3243, -0.3701, +0.3331, +0.0335, -0.2298, -0.0108, -0.7326, +0.2532, -0.0554, +0.1458, -1.0869, +0.5397, -0.3616, -0.4258, +0.0051, +0.5826, +0.0720, +0.7102, -0.4815, -0.5512, -1.3826, -0.0495, -0.0009, -0.2800, -0.2969, +0.1124, -1.1290, -0.6278, +0.2533, -0.6351, -0.8564, +0.2894, -0.4166, +0.0631, -0.3520, -0.1019, +0.0933, -0.5000, -0.5518, +0.0643, +0.0005, -0.3435, +0.3769, -0.1839, +0.3340, -0.5945, +0.0447, +1.3741, -0.3691, -1.1582, -0.8776, -0.0717, -0.0328, +0.0922, -0.5648, +0.1482, +0.5882, -0.3070, +0.0753, -0.3949, +0.5848, -0.0525, -0.1069, -0.1223, +0.2160, -0.6329, +0.2816, -0.0776, +0.3009, +0.8861, +0.4515, -0.3619, +0.1494, +0.4558, -1.4952, -0.0373, +0.4441, -0.4643, +0.3820, +0.0463, -0.4576, -1.4621, -0.7752, -0.3164, -0.2166, +0.3246, +0.0032, -0.3442, -0.9252, +0.2383, -0.5751, -0.2526, -0.3966, -0.0106, +0.0551, -0.2484, -0.5117, +0.0920, +0.3756, -0.3718, -0.3283, +0.6047, +0.3816, +0.1391, +0.2320, +0.0394, +0.0631, -0.0844, +0.1382, -0.0184, -1.0713, -1.0758, -0.9147, -0.1541, -0.0780, -0.0554, +0.3733, +0.1043, +0.0783, +0.0085, +0.0763, +0.0499], +[ +0.2028, -0.0972, -0.0420, +0.3582, -0.2659, +0.0275, -0.3126, +0.0726, -0.3374, -0.1147, -0.4659, -0.3320, +0.2382, -0.1582, +0.2975, -0.5718, +0.1347, +0.3142, -0.2734, -0.0589, -0.4717, -0.2501, -0.1617, +0.1413, +0.3922, -0.4995, -0.1628, +0.2263, -0.2123, +0.2214, +0.2072, -0.3154, -0.1453, -0.1673, +0.1661, -0.2971, -0.0208, +0.2328, +0.1944, -0.6479, +0.0608, -0.3874, -0.1620, +0.0104, +0.2743, +0.1931, -0.6089, +0.1236, -0.2400, +0.0071, -0.4273, -0.5542, +0.4053, -0.3175, +0.2030, +0.5557, +0.3351, +0.4363, -0.7274, +0.3224, -0.0487, -1.1022, -0.3274, -0.0646, +0.3601, +0.2220, -0.1501, +0.4314, -0.2996, +0.4053, -0.4276, +0.5074, -0.1857, +0.1020, +0.1378, +0.1655, -0.8446, -0.3429, -0.1343, -0.3011, -0.0274, +0.4764, -0.7874, -0.6551, +0.2766, -0.2518, +0.1279, +0.2594, -0.2784, -0.3953, +0.1520, -0.0223, +0.2754, +0.3359, +0.2621, +0.1815, -1.5922, +0.2841, -0.0714, -0.6989, -0.1654, -0.5011, +0.1637, -0.1394, -0.2840, -0.3650, +0.2890, +0.0167, -0.1014, -0.1577, +0.2075, -0.6913, +0.3595, -0.9863, -0.1042, +0.0475, -0.3596, -0.4279, -0.0539, +0.0853, +0.5694, -0.0971, +0.1162, +0.1094, +0.3452, +0.1604, +0.1195, -0.2351], +[ +0.1900, +0.7089, +0.3496, -0.2038, -0.3084, +0.2608, -0.6953, +0.5173, -0.1191, -0.2883, +0.0648, +0.2797, +0.0287, -0.7875, +0.2421, +0.3568, +0.1613, +0.0608, -1.1179, +0.3233, +0.2435, +0.2525, +0.6172, -0.7511, +0.5085, +0.2840, +0.5009, -0.1700, +0.2576, -0.0248, +0.2106, +0.2717, +0.0067, +0.6714, +0.4278, -0.6350, +0.2729, -0.4513, +0.0890, -0.2815, -0.2417, +0.4750, -0.2657, -0.2394, +0.0306, +0.6279, -0.5832, +0.2397, -0.0580, +0.6375, +0.5022, +0.2646, +0.2561, +0.2462, -0.2213, +0.2257, -0.2983, -0.6287, +0.3809, -0.0921, -0.2330, -0.3067, +0.0942, -0.0820, +0.2682, -0.6325, +0.5378, +0.1533, -0.0488, -0.2197, -0.7697, +0.1914, -0.0968, -1.1765, +0.1117, +0.3153, +0.1784, +0.3065, +0.5665, -0.2415, -0.3054, -0.1691, +0.0961, +0.0841, -0.2884, -0.0720, -0.1946, -0.4453, -0.4094, +0.7505, +0.9860, +0.4382, +0.0251, +0.6391, -0.9557, +0.4968, +0.3713, -0.6909, +0.3377, +0.5932, -0.0497, -0.7133, -0.0375, +0.6459, +0.1891, +0.2072, -0.3249, -0.9538, +0.0223, +0.1423, -0.4737, +0.4759, +0.3123, +0.2271, +0.3975, +0.1807, -0.0245, -0.4997, +0.0934, +0.3119, -0.6308, -0.6775, +0.1343, -0.9224, +0.3735, +0.3916, +0.3533, -0.2392], +[ +0.2814, -0.0062, +0.0933, -0.7245, -0.0320, -0.1942, +0.2133, +0.4642, +0.3284, -0.3294, +0.3022, +0.1587, -0.2439, -0.5907, +0.2743, -0.4863, +0.0067, -0.5499, -0.3214, +0.2841, +0.0214, -0.0561, -0.0420, +0.4335, -0.4909, +0.1226, +0.6087, +0.2644, +0.0271, +0.3237, -0.2749, -0.2716, -0.1286, +0.7110, -0.5399, -0.8197, -0.2695, -0.5925, -0.9547, +0.2210, -0.0892, +0.3999, +0.4132, +0.5972, -1.0397, -0.2844, +0.3267, -0.3480, +0.1662, +0.9957, -0.1922, -0.0408, -0.7742, -0.1346, -0.2137, +0.1514, +0.5590, +0.1207, -0.4661, -0.4641, +0.1634, +0.2661, -0.1209, -0.1571, -0.1591, -0.9180, -0.5031, +0.6926, +0.4839, -0.1161, +0.2329, +0.1166, -0.0009, -0.3337, +0.2277, +0.8259, -0.9418, +0.4854, +0.1511, +0.0460, -0.6269, +0.1148, +0.2744, -0.4243, +0.4802, +0.0008, +0.3037, -0.4941, +0.5982, -0.0887, -0.0670, +0.2764, +0.9553, -0.2374, +0.3233, +0.2260, -0.2309, -0.0966, +0.0436, +0.3731, +0.1013, +0.0365, -0.1977, -0.1226, -0.3751, -1.1944, -0.7115, +0.5875, -0.4934, +0.7552, +0.6172, +0.9160, +0.0696, -0.1216, +0.5968, +0.5816, -0.6307, +0.2768, -0.2808, +0.8865, -0.3658, +0.2391, +0.8127, +1.0817, +0.2553, +0.0153, +0.5750, -0.8275], +[ +0.0082, +0.0867, -0.7852, +0.0827, +0.1291, +0.0101, -0.4648, +0.2129, +0.1481, +0.2185, +0.0041, +0.1023, -0.0985, -0.4019, -0.1962, -0.4703, +0.2551, +0.0781, -0.2133, -0.2784, +0.4115, +0.1406, -0.6719, +0.0922, +0.0814, -0.2462, +0.1721, -0.0595, -1.2963, -0.1522, -0.2524, -0.7243, +0.0807, -0.4981, +0.2275, +0.2468, -0.4768, -0.1847, +0.4707, +0.8096, -0.2368, -0.0147, +0.0535, -0.6021, -0.0384, +0.2849, +0.3360, -0.1571, -0.5368, +0.0510, +0.2195, -0.0610, +0.3591, -0.6108, +0.2859, +0.4386, -0.3010, -0.1109, +0.4162, -0.1174, +0.4276, -0.2966, +0.1508, +0.3311, -0.2374, -0.1032, +0.3684, +0.2232, -0.2740, +0.1488, +0.4066, -0.3463, -1.3788, +0.0910, -0.6708, -0.5257, +0.2128, -0.7257, -0.5533, +0.3904, -0.8414, -0.3692, -0.4447, +0.2932, +0.3695, +0.1974, -0.0307, -0.0207, +0.2861, +0.0093, -0.3723, +0.0885, -1.1285, +0.5602, -0.4984, +0.0470, -0.7330, -0.3404, -0.0676, +0.0126, +0.2968, -0.6792, -0.1664, -0.0904, -0.0668, +0.0039, +0.3229, -0.3829, -0.0114, +0.0498, +0.2746, +0.3235, -0.7055, -0.9976, -0.1135, +0.7543, +0.0806, +0.3088, -0.2352, +0.0764, -0.7089, -0.9394, +0.2522, -0.3699, -0.1798, -0.2856, -0.1290, +0.1445], +[ +0.1170, +0.1270, -0.3989, -0.3419, +0.0840, -0.9038, +0.0866, +0.2107, -0.4077, +0.2281, +0.0722, +0.3743, -0.0479, +0.1286, -0.7060, -0.0320, -0.5403, -0.0098, -0.4120, -0.4272, +0.2438, -0.4637, -0.7268, -0.0662, -0.3122, -0.3862, +0.2022, -0.0472, -0.4934, -0.0315, -0.1665, -1.2208, -2.0757, +0.0802, +0.3474, -0.0081, -0.2626, -0.3028, -0.2964, -0.0162, +0.1108, -0.6319, +0.3311, -0.1075, -0.5383, +0.1789, +0.0341, +0.0732, +0.0174, -0.6334, +0.1319, +0.2015, +0.0771, -0.5511, +0.0671, -0.2133, -0.0329, -0.1802, -0.4966, -0.0583, -0.4500, +0.3364, +0.3630, -0.2253, -0.4866, +0.1868, -0.0692, -0.2527, -0.0107, -0.1891, +0.2936, -0.4164, -0.5263, +0.1735, -0.1163, -0.5953, +0.1242, +0.4013, -0.1936, -0.9705, -1.2014, +0.2352, -0.2794, -0.5115, -0.0017, -1.5073, +0.1604, -0.3522, -0.0468, -0.6165, +0.1721, +0.2418, -0.4455, -0.0092, -0.1756, +0.2693, -0.6080, +0.4912, -0.1329, +0.4136, -0.2932, +0.0115, -0.0402, +0.2502, -0.0197, -0.4421, +0.0759, -0.6872, -0.7786, -0.0250, +0.3514, +0.2312, +0.1051, -0.9007, +0.3253, +0.1189, +0.1139, -0.2096, -0.2937, +0.0679, -0.8154, -0.4950, +0.6838, -0.0920, +0.0793, -0.2171, -0.0949, +0.1958], +[ -0.2691, -0.6323, -0.1146, -0.7969, +0.3603, +0.0558, -0.3731, -0.8005, -0.0474, +0.0781, -0.1341, -0.2605, -0.1887, +0.4685, +0.8360, +0.4681, +0.0750, +0.0393, +0.1146, +0.0619, -0.6425, +0.2530, +0.1581, +0.1261, +0.0122, +0.0781, +0.1272, -0.3750, -0.6580, -0.1638, +0.1062, +0.3031, -0.3352, +0.2163, -0.1018, -0.8000, -0.6169, -0.2181, +0.3027, -0.9585, -0.2230, -0.1886, -0.4316, -0.4782, -0.5062, -0.9208, -0.7954, +0.1160, -0.5291, -0.8184, -0.0061, -0.1857, -0.9126, +0.5665, -0.2163, +0.0021, -1.0223, +0.0705, +0.2187, -0.2989, +0.6618, +0.0370, +0.2902, -0.1797, +0.0894, +0.1833, -0.1715, -0.0093, +0.3925, -0.3233, -1.0342, -0.4808, +0.1210, +0.3849, +0.5812, +0.2901, +0.0822, -0.8464, +0.3258, +0.2498, -0.0856, +0.1311, -0.0029, +0.4667, -0.0699, -0.2817, -0.7217, +0.2866, +0.0190, +0.1614, -0.5219, -0.0784, +0.0649, +0.0512, +0.4715, -0.5501, +0.1089, -0.7258, +0.2023, +0.2316, -0.2090, -0.0795, +0.4351, -0.3446, -0.4372, -0.1601, -0.3571, +0.0786, +0.3685, -0.4748, +0.3770, +0.2971, -0.0189, -0.6198, +0.0504, -0.2866, -0.2560, +0.1544, -0.6670, -0.9603, -1.4674, -0.1516, +0.2214, -0.4532, -0.1952, +0.6401, -0.2176, -0.8166], +[ -0.0285, -0.3986, +0.1484, -0.2599, -0.1303, +0.0441, +0.4181, -0.4833, -1.0472, -0.4699, -0.5243, +0.4656, -0.6172, -0.8212, +0.1187, -0.0418, +0.0160, -0.1062, -0.0762, +0.3476, +0.3903, +0.0679, -0.1581, -1.0278, +0.0026, -0.4655, -0.2266, +0.1243, -1.2957, -0.9490, +0.3861, +0.3092, -0.4318, +0.8314, -0.7161, -0.4065, +0.3536, -0.1895, +0.0566, -0.2526, -0.4563, +0.3996, +0.2692, -0.9285, -0.0938, +0.0857, -1.2679, -1.3199, +0.1553, -0.5119, -0.5065, +0.4989, -0.7397, +0.0820, -0.4976, +0.3495, +0.1541, +0.3716, -0.3373, +0.4194, -0.4855, +0.3548, -0.6374, -0.2918, -0.4379, -0.2620, +0.6569, +0.3145, +0.4310, +0.0951, -0.1676, +0.1585, +0.7460, +0.0699, +0.0143, -0.0661, -1.1089, +0.3126, +0.2163, -0.4875, +0.1745, +0.2242, +0.2786, +0.3927, -0.5813, +0.3231, -0.1843, -0.0234, -0.2786, +0.0067, +0.1955, -0.0388, +0.1289, +0.6098, +0.2552, +0.7925, -0.2620, +0.1436, -1.0747, -0.2431, +0.3825, -0.1392, -0.5851, +0.4949, +0.0018, +0.0258, -0.1703, -0.1578, +0.4324, +0.0654, -0.0453, +0.0184, +0.5218, +0.4344, +0.1994, -0.2861, -0.7278, -0.1987, -0.4662, -0.1155, -0.0638, -0.1569, -0.9375, +0.8239, -0.0273, +0.1714, +0.6239, -0.2999], +[ +0.3140, -1.1413, -0.1982, -0.6762, +0.6062, +0.3005, -0.4418, -1.0130, -0.2415, +0.1512, -0.0788, -0.2140, +0.2363, -0.0995, -0.1775, -0.2692, -0.2319, -0.1664, -0.0480, -0.2605, -0.4175, +0.5565, +0.1244, +0.0817, -0.2587, -0.1275, +0.1042, -0.2228, +0.0417, +0.1563, -0.0341, +0.1533, -0.2492, -0.1530, +0.0599, +0.4991, -0.9855, -0.2737, +0.2038, -0.3164, +0.0745, -0.1019, +0.0571, +0.5334, +0.0129, +0.0066, +0.0281, +0.4225, -0.3663, -0.1974, -0.4947, +0.2419, -0.0759, -1.3532, +0.1309, +0.0166, -0.2925, -0.0691, -0.2376, +0.3762, -0.8569, -1.2457, -0.0893, +0.3526, +0.0858, +0.2560, -0.9409, -0.2089, +0.1291, -0.1224, +0.1125, +0.3010, -0.6485, -0.1327, +0.2401, +0.0642, -0.7335, -0.0607, -0.0949, +0.1965, -0.0402, +0.7876, -0.2581, -0.0049, -0.5583, +0.3317, -0.5640, +0.7555, -0.4633, +0.3739, +0.1979, +0.7038, -0.1302, -0.4236, -0.7923, -0.0621, +0.3316, +0.4299, -0.3998, -0.4017, +0.3687, +0.2797, -0.0302, -0.0357, +0.1949, -0.0202, +0.3365, -0.0781, -0.2587, -0.4195, +0.1678, -0.4627, -0.1905, -0.3720, -0.2279, -0.4517, +0.1817, -0.2728, -0.4155, +0.4474, +0.2705, +0.5126, -0.1381, -0.7768, +0.0570, +0.3170, -0.1461, +0.1520], +[ +0.2711, -0.7083, +0.0868, +0.2666, -0.8103, -0.0690, -0.0300, -0.7091, +0.1559, -0.3225, -0.3553, -0.1263, +0.2223, -0.2423, +0.3708, -0.0383, -0.3726, +0.1577, +0.0520, +0.1042, -0.5502, -0.1205, -0.0600, +0.1708, +0.3769, +0.6033, -0.0370, -0.2149, +0.0203, +0.2205, +0.1817, +0.0686, +0.2958, -1.5378, -0.3753, -0.5048, -0.8244, +0.3607, +0.0226, -0.3186, -0.6852, +0.1654, -0.2479, +0.1836, -0.5161, -0.1248, -0.7217, -0.4131, -0.2711, -1.2179, +0.5068, -0.7894, -0.2289, +0.1742, -0.4522, -0.2113, -0.1300, +0.1045, +0.1983, -0.0241, +0.0476, +0.2304, +0.1034, -0.7503, +0.0238, -0.4383, +0.0790, -0.8974, -0.1478, +0.3492, -0.7141, +0.2589, +0.0790, -0.2512, -0.2460, -0.0059, -0.3912, -0.5338, -0.3274, +0.0376, +0.1176, -0.2580, -0.3363, +0.0977, +0.4249, +0.1062, -0.3632, -0.1051, -0.1989, +0.1453, -0.3825, +0.4364, +0.3469, -0.0374, -0.2044, -0.1771, -0.5730, -0.1720, +0.6108, -1.2931, +0.0127, +0.0761, -0.1373, +0.0288, -1.2347, +0.5185, -0.1560, +0.3861, +0.1622, -0.5163, -0.1247, -0.1058, -0.2902, -0.2007, +0.6575, -0.1101, -0.6524, +0.0326, -0.4036, +0.0191, +0.1843, +0.1588, +0.0258, -0.0628, +0.1276, +0.1841, +0.5514, +0.0580], +[ +0.3696, -0.2226, -0.5965, +0.0039, +0.0826, -0.0328, +0.2075, +0.3482, +0.1155, -0.6658, -0.6598, +0.0239, -0.2714, -0.2931, -0.0308, -0.1994, +0.3646, -0.0805, +0.1486, +0.2427, -0.0741, +0.3452, +0.0704, -0.0799, +0.6901, -0.2128, -0.2928, +0.0834, -1.0479, -0.1028, +0.0560, -0.4974, -0.1569, +0.0858, +0.2110, +0.0329, +0.0708, -0.2342, -0.2855, +0.5861, -0.1896, +0.1390, -0.3496, +0.3056, -0.8322, +0.1572, -0.4228, +0.3259, -0.6415, +0.4092, +0.4396, -0.1126, +0.2508, -0.8185, -0.4606, -0.0904, -0.5178, -0.6965, -0.3374, -0.1446, -0.5244, -0.1085, -0.7043, +0.0682, +0.2373, -0.0717, -0.8114, +0.3448, +0.0167, +0.2812, -0.7497, -0.4294, -0.3268, -0.1051, -0.1815, -0.3281, -0.0849, -0.4348, +0.2231, -0.9791, -0.2975, +0.5974, -0.3474, +0.1663, +0.0978, -0.3039, +0.1740, +0.2455, -0.1384, +0.1306, -0.0091, +0.3224, -0.4614, +0.2875, -0.7874, +0.5825, -0.0400, -0.3206, +0.4512, -0.3062, +0.1509, -0.2496, +0.0852, -0.2199, +0.1985, +0.1227, -0.2818, -0.1475, +0.3922, +0.1838, +0.0896, +0.4384, +0.1683, -0.4647, +0.0348, -0.1814, +0.1457, -0.8301, -0.5137, +0.1269, -0.3037, +0.0274, -0.2094, +0.0461, -0.2276, +0.2731, +0.2495, +0.1495], +[ -0.0085, +0.2052, +0.1864, -1.2076, -1.0113, +0.0311, +0.0778, -0.5844, +0.4804, +0.3460, -0.4087, +0.3961, +0.5099, -0.4606, -1.3054, -0.7246, +0.4725, +0.4758, -0.1597, -0.6904, -0.1142, -0.0945, -0.1305, -0.2708, +0.3056, -0.1290, -0.4496, +0.1660, +0.1616, -0.5353, +0.2048, -0.0921, +0.4782, -0.4734, -0.5955, -1.1665, -0.6502, -1.0449, +0.0884, -0.6652, +0.6585, -0.1359, +0.2576, -0.6263, -0.0742, -0.0931, -0.3415, -0.8582, -0.0877, -0.5015, -1.0665, +0.3704, -0.1931, -0.4724, -1.0108, +0.0551, -0.5867, +0.1302, -0.0530, -1.2517, +0.2389, -0.6020, +0.2280, +0.2903, -0.4259, -0.0438, -0.0464, -0.0403, -0.5162, -0.7994, -0.3000, +0.0190, -0.1081, -0.1555, -0.0449, +0.1102, -0.8093, +0.1541, +0.1101, +0.1885, +0.0181, +0.1531, -0.5090, -0.3342, +0.0650, +0.2316, -0.5225, -0.4101, -0.0930, -0.2833, -0.0896, -0.8806, +0.6488, -0.1290, -0.4551, +0.3343, -0.0093, -0.3612, +0.2181, -0.1496, +0.1006, -0.7886, -0.3799, -0.4418, +0.0317, -0.3366, +0.0126, +0.5321, -0.1736, +0.2711, -0.1181, -0.1883, +0.6228, -0.4832, +0.0469, +0.2955, -0.1980, -0.7133, +0.5580, +0.1149, -0.5710, -0.1318, +0.4555, -0.9994, +0.1088, -0.1644, +0.0360, +0.4702], +[ -0.2252, -0.4254, +0.6137, +0.4718, -0.5521, -0.2921, -0.5468, +0.7702, -0.5979, +0.2184, -0.2062, +0.0745, -0.4151, +0.1969, +0.7839, +0.0988, +0.1779, -0.2031, +0.1115, -0.2029, -0.2319, -1.0614, -0.1879, -1.2515, -0.0887, -0.2592, +0.2736, +0.0759, -0.4067, -0.2098, +0.2684, -0.9703, -0.2628, -1.4381, -2.2795, -2.2924, -0.2015, -1.1202, -0.0949, -1.5898, +0.1963, -0.2292, -0.1158, +0.5034, +0.0557, -0.4832, -0.1155, -0.5655, +0.0922, -0.3294, -1.1680, +0.2987, -1.2463, -0.3976, -0.5490, +0.0465, -0.0955, -0.1976, -0.0012, -0.5143, -0.1448, -0.0414, +0.0126, -0.4112, -0.0247, -0.1230, +0.1532, -0.2767, +0.3638, +0.1027, -0.0585, +0.3002, +0.3676, -0.3005, +0.2677, +0.3266, -1.5747, +0.3166, +0.1465, -0.1974, -0.1422, +0.0436, -0.0890, +0.1626, -0.2840, -0.1864, -1.2519, -0.1626, +0.2748, -0.5678, -1.4952, -0.0378, +0.4490, +0.3409, +0.1429, -1.2740, +0.1465, -0.3097, -0.4857, -0.0346, +0.0447, -0.0255, -0.1301, -0.0094, -0.5234, -0.6989, +0.2882, +0.1444, -0.6770, +0.4679, +0.1677, +0.7201, -0.2564, +0.1432, +0.0667, -0.0215, -0.1456, -0.4922, -0.4803, -0.3481, -1.7805, +0.2801, -0.2172, +0.3164, +0.0410, +0.2213, +0.3071, -0.1733], +[ -0.1136, -0.0677, -0.4356, +0.8331, -0.8691, -0.5827, -0.0215, -0.5241, -0.5871, -1.4385, -0.8891, -0.1442, +0.0689, -0.4092, +0.3884, -0.7465, -1.0275, +0.2555, +0.3577, +0.2575, +0.0209, -0.1352, +0.0379, -0.0821, +0.0465, -0.0177, +0.0115, -0.3766, -0.1401, -0.0996, +0.1216, -0.8895, +0.0781, -0.0920, -0.1415, -0.2272, +0.4005, +0.3169, +0.1274, +0.0498, -0.5372, +0.1034, -0.1719, -0.0153, +0.6849, +0.0268, +0.0420, +1.1373, +0.2045, +0.0175, +0.2241, +0.3592, +0.3729, -0.0936, -0.3730, -0.6442, +0.3203, -0.0835, -0.0376, -0.1133, +0.1059, -0.2747, -0.6443, +0.1147, -0.0212, +0.1011, +0.0599, +0.0543, +0.1753, +0.1356, -0.2370, -0.8859, +0.3428, -0.5916, -0.5082, -0.6873, +0.1431, -0.3359, -0.3301, +0.3276, -0.2136, -0.6678, +0.1320, +0.1852, -0.0982, -0.0495, -0.2122, +0.2887, +0.0018, -0.1580, -1.1534, +0.6158, +0.5112, +0.1241, -0.3766, +0.3000, -0.1223, -0.3958, +0.2922, -0.0240, -0.5557, -0.0616, +0.2368, -0.2329, +0.1579, +0.0014, -0.3179, -0.2191, -0.1892, +0.2321, +0.0039, +0.7091, -0.3429, -0.4592, +0.1506, +0.3075, -0.1510, +0.1857, +0.1459, +0.1891, -0.4055, +0.0411, -0.6508, +0.0743, -0.4859, +0.0052, +0.4068, +0.1873], +[ +0.4762, -0.3284, -0.1555, +0.2002, -0.1366, +0.1701, +0.1370, -0.3074, -0.2124, -0.5547, +0.2435, -0.1142, -0.0982, -0.1635, -0.1310, -0.2785, +0.0024, +0.0102, -0.2526, -0.4488, -0.1647, -0.0045, -0.3931, -0.0204, +0.2716, -0.0475, +0.1861, +0.6183, -0.4493, -0.0702, +0.2247, -0.1569, +0.1372, -0.3291, -0.8000, -0.6748, +0.4074, +0.5101, -0.7657, -0.6029, -1.0873, -0.1586, +0.4112, -0.5648, -0.0312, +0.1353, -0.9385, +0.0067, -0.2617, -0.3750, -0.1196, +0.5406, -0.7990, +0.4246, -0.4306, -0.2984, +0.3182, +0.0648, +0.4050, +0.1368, +0.2012, -0.2350, -0.2371, +0.3948, -0.5506, +0.0713, -0.4612, +0.2157, +0.3576, -0.9170, -0.8457, +0.2411, +0.4271, -0.1765, -0.1865, -0.2401, -0.4079, -0.1546, -0.0300, +0.3523, +0.1223, -0.4455, +0.1529, -0.2628, -0.4528, -0.9364, -0.8459, -0.1533, -1.0921, -0.3128, -0.5306, -0.2182, +0.5052, -0.8434, +0.5184, +0.1367, +0.0152, -0.1304, +0.7222, -0.2846, +0.0592, -0.1285, +0.1846, +0.2904, +0.4518, +0.1123, -0.3481, -0.3457, +0.1827, -0.0044, -0.0458, +0.0374, -0.1125, +0.0941, -0.3499, -0.0423, -0.4055, -0.2829, +0.7004, +0.1410, -0.3933, -0.3708, -0.4537, -0.5014, +0.1018, +0.5535, +0.3223, +0.1110], +[ +0.6492, +0.1605, +0.1305, -0.4848, -0.6308, +0.1230, -0.6904, +0.4446, -1.0387, -0.4102, -0.1002, +0.0278, -0.0709, +0.0744, -0.0401, -1.0359, -0.0711, +0.7240, -0.1909, -0.2549, -1.1637, +0.0829, +0.1114, -0.2705, -0.0319, -0.4715, -0.7474, -0.5330, -0.0540, -0.5394, +0.5775, -0.1039, -0.4891, -0.8315, -0.5596, -0.8209, -0.9092, -0.7611, -0.3003, +0.1847, -0.1835, -0.5320, +0.3177, -0.0634, +0.0724, -0.3234, -0.0891, -0.0884, -0.0462, -0.1958, -0.5008, -0.3015, +0.1186, -0.8094, +0.4712, +0.0014, +0.2931, +0.0220, -0.4707, +0.1514, +0.1064, -0.4192, -0.1069, +0.5645, -0.1316, +0.0881, +0.1463, +0.1614, +0.1803, +0.2927, -0.6776, +0.0035, -0.1937, -0.1933, -0.6986, +0.0889, -0.6174, +0.2617, +0.1724, +0.2762, +0.0236, +0.4052, -0.3615, -1.8092, +0.0611, +0.1489, -0.6541, +0.3291, -0.6879, -0.1768, -0.2767, -0.1210, -0.3152, -1.0731, +0.4075, -0.0101, -0.9484, -0.1233, -0.3091, -0.3765, +0.3507, -0.5516, +0.1996, -0.3513, +0.4850, +0.6935, -2.8095, +0.3908, +0.1824, -0.5622, -0.6693, -0.1793, -0.1975, -0.5803, +0.0783, -1.4139, -0.1627, -0.5159, -0.0761, +0.1372, -0.0913, +0.1193, -0.6293, +0.6834, +0.1290, +0.6432, -0.0958, +0.2212], +[ +0.2521, +0.2630, -0.4733, +0.3795, +0.0419, -0.4095, +0.2999, +0.3761, +0.3422, -0.2029, -0.3041, +0.2830, +0.3336, -0.1059, -1.3482, -0.0119, -0.5787, -0.6648, -0.3205, -0.6331, -0.1909, -0.0394, -0.7875, +0.0651, -0.0273, +0.1049, +0.5533, -1.2675, +0.1238, -0.3109, -0.6440, +0.1942, -0.3646, -0.3191, -0.0766, +0.2061, -0.1044, +0.0561, +0.3081, -0.2792, -0.3319, -0.1471, +0.3511, +0.0339, -0.1977, -0.6400, +0.0097, -0.6432, +0.1321, +0.1810, +0.1756, -0.1767, +0.1977, +0.3617, -0.3304, -0.5127, -0.8530, +0.0533, +0.1787, -0.1992, +0.2893, -0.2216, -0.6566, +0.0704, -0.1389, -0.4372, +0.1779, -0.3765, -0.1337, -0.0503, +0.3742, -0.1786, -0.3624, -1.1077, -0.1552, +0.4102, -0.5214, -0.5095, +0.0131, +0.1564, +0.6065, +0.1712, +0.1516, -0.3438, +0.3225, -0.0621, +0.3922, -0.4830, +0.1927, -1.4449, -0.9013, -0.0744, +0.2114, +0.0668, -0.1440, +0.2017, +0.4194, +0.2080, +0.1666, -0.0075, -0.1641, -0.9365, -0.1810, +0.0262, -0.2943, +0.2071, +0.1249, -1.5124, -0.0661, -0.3135, -0.1278, -0.3549, -0.0708, -0.2791, -0.0023, -0.1236, +0.1872, -0.0021, +0.4197, -0.5973, -1.3331, -0.7616, -1.0685, -0.4284, -0.0643, -0.0932, -0.7615, -0.4550], +[ -0.6894, +0.2387, -0.8501, -0.2360, +0.1588, -0.3975, -0.2485, +0.0576, +0.1002, -0.2252, -0.5013, -0.3919, +0.3921, +0.0695, -0.9917, -0.8031, -0.2710, +0.3396, +0.5580, -0.0996, -0.0319, -0.9168, -0.0259, -0.3321, +0.3293, -0.0079, -0.4774, +0.5074, +0.2986, -0.5248, -0.2066, -0.5032, -0.7702, -0.4826, +0.0393, -0.3987, -0.7677, +0.2482, -0.7121, -0.1591, +0.3542, +0.2598, -0.1925, -0.1286, -0.1442, -0.2242, +0.2685, -0.5320, -0.1839, +0.3071, -0.0286, -0.2077, -0.1724, +0.3268, -0.1637, +0.1221, -0.3711, +0.3796, +0.1677, +0.0798, +0.0081, -0.2726, +0.3648, +0.2464, +0.2526, +0.5343, -0.3083, +0.2492, -0.3297, +0.4204, -0.2402, -0.2899, +0.3629, -0.4292, +0.4970, +0.2512, -0.0435, -0.3246, -0.5294, +0.6179, -0.2060, +0.4789, -0.0905, +0.1975, +0.6006, -0.1819, +0.1146, -0.6750, +0.4257, -0.0368, +0.3578, -0.0778, +0.1832, +0.3916, -0.0713, -0.0925, -0.0996, +0.1648, +0.1729, -0.6876, +0.1275, -0.4039, +0.8193, +0.5192, +0.2734, +0.3087, +0.1873, -0.1174, +0.0053, -0.5225, +0.2610, -0.1341, +0.5482, -1.1334, -0.1744, +0.0211, +0.2616, -0.6873, -0.1929, -0.5472, -0.1666, +0.3171, -0.0373, +0.1694, -0.1680, -0.0884, +0.2463, -0.2079], +[ -0.3374, -0.3851, -0.1854, -0.1772, +0.1176, +0.0174, -0.0545, -0.2007, -0.2658, -0.1292, -0.2258, -0.1332, -0.3853, -0.6779, +0.4847, -0.0840, +0.0082, -0.4100, +0.1835, -0.3973, -0.2225, -0.3307, -1.2065, -0.5345, +0.2386, +0.1299, -0.6485, -0.0198, +0.3878, +0.4176, +0.1944, +0.4104, -0.3611, +0.1750, -0.2422, +0.3888, -0.3439, -0.3678, -0.5949, +0.3910, -0.0784, -0.2476, -0.6963, -0.5632, +0.2662, +0.3285, +0.2715, -0.3387, +0.0520, -0.3993, -0.1589, +0.4355, -0.1047, +0.4287, -0.2753, +0.1810, -0.2075, +0.2192, -0.3173, +0.0667, -0.2311, -0.0826, +0.3369, -1.4102, +0.1262, -0.0202, +0.2389, -0.2517, +0.4403, +0.1408, +0.0129, +0.1655, -0.2732, +0.1485, -0.0319, +0.2674, -1.2042, -0.5246, +0.1175, -0.9084, -0.1473, +0.7580, -0.0608, -0.1657, -0.3441, -0.2765, -0.2576, +0.1945, -0.4545, +0.0471, +0.2464, -0.1764, -0.3006, -0.4309, +0.5991, +0.7491, +0.3486, +0.2068, -0.4579, -0.0765, +0.1341, -0.0713, -0.3125, -0.3926, -0.5280, -0.4428, -0.8202, -0.2347, +0.1489, -0.1848, +0.0109, +0.2817, +0.3943, +0.5811, -0.0619, -0.0500, -0.3740, -0.0044, -0.3349, +0.2791, -0.1661, -0.3395, +0.2254, -0.8203, +0.5381, -0.0089, -0.0524, -0.0049], +[ -0.3129, +0.3310, -0.0912, -0.2157, +0.1215, -0.3659, -0.0721, +0.2889, +0.3868, +0.0040, -0.4878, +0.2934, -0.0622, +0.1938, +0.2447, -0.4872, +0.5489, -0.5351, -0.8669, -0.5864, +0.1900, +0.3462, +0.3815, -0.1919, +0.1619, -0.3233, +0.1040, +0.3066, -1.1438, -0.1468, -0.2173, +0.3603, -0.0183, -0.5742, -0.2445, -0.1754, -1.7395, -0.2586, -0.0417, +0.2469, +0.2116, +0.0549, +0.2056, -0.0176, +0.1254, +0.3214, +0.3466, -0.2643, -1.6379, +0.1342, -0.3079, +0.0917, +0.2076, -1.6489, -0.8988, +0.1965, -0.2954, -0.2331, +0.2279, -1.2496, -0.0440, -0.2847, +0.0058, +0.6779, +0.3672, -0.2293, -0.5255, -0.2264, +0.5899, -0.4577, -0.8445, -0.3349, +0.4782, -0.0213, +0.5035, -0.1462, -0.0816, -0.0924, -0.3762, +0.0949, -0.5648, +0.4525, +0.5809, -0.0342, +0.1381, -0.3033, -0.4382, -0.1888, -0.5410, +0.1169, +0.7043, -0.4616, +0.0419, -0.3368, -0.0198, +0.0373, +0.2670, -0.9157, +0.5766, -0.8848, +0.2547, -2.4214, +0.0289, +0.0294, +0.3200, +0.2833, +0.7030, +0.1917, +0.0806, +0.0319, +0.1276, +0.3893, +0.1187, +0.0187, -0.4040, +0.9615, -0.2946, -0.0678, -0.3491, +0.3768, -0.6789, -0.1654, +0.3386, -0.2474, -0.0224, -0.5732, +0.2590, +0.2987], +[ +0.0499, -0.0441, -0.3651, +0.2152, -0.3977, -0.5853, -0.1028, -0.4648, -0.0573, -0.0586, +0.0939, +0.7476, -0.0733, -0.1556, -1.2404, +0.2962, -0.3082, +0.2758, +0.4992, -0.5321, +0.2672, -0.3016, -0.1122, -0.9559, +0.0373, +0.1253, +0.0423, -0.3638, -0.6725, -0.8164, +0.4092, -0.6592, +0.2284, +0.0237, +0.1574, -0.4085, -0.0249, -1.7635, +0.3639, +0.1628, -0.1960, +0.1105, +0.2272, +0.1142, -0.2709, +0.3293, -0.2763, -0.7405, +0.0259, -0.4482, -0.3133, +0.4974, -0.1307, +0.2308, -0.3896, +0.0042, +0.0054, -0.2991, -0.0221, -0.4111, -0.0786, -0.0812, +0.3746, +0.0347, -1.2763, +0.1178, -0.5588, -1.6551, -0.1173, -0.6023, -0.1478, -0.0474, +0.0818, -0.0719, -0.4102, -0.4633, +0.4273, -0.2414, +0.5594, -0.0444, -0.5016, -0.4598, +0.2786, -0.1450, +0.1030, +0.3086, +0.1437, -0.2915, -0.4826, -0.4433, +0.2210, -0.5075, -0.1776, -0.0854, +0.2941, +0.1911, -0.4371, -0.2531, -0.1352, -0.2630, +0.6148, -0.2859, -0.0440, -0.3877, -0.4516, +0.0055, -0.4590, -0.3747, -0.0737, +0.0759, +0.0977, -0.5848, -0.6917, +0.2776, -0.1383, -0.1147, -0.0361, -0.0117, +0.2566, -0.4038, -0.3312, +0.4280, -0.0726, -0.9503, -0.3591, -0.0391, +0.1074, +0.2458], +[ +0.5959, -0.3278, +0.0867, +0.2935, +0.1105, +0.2164, +0.2708, -0.0261, -1.1600, -0.2612, -0.2102, -0.2892, -0.1252, -0.1953, +0.3011, -0.2992, +0.2181, -0.0139, +0.1810, +0.2124, -0.2466, -0.0319, -0.4725, -0.1248, +0.7223, -0.1485, +0.0357, -0.1122, -0.6130, -0.1449, +0.3717, -0.5425, +0.2772, +0.3600, +0.0771, +0.2939, -0.2337, +0.6262, -0.1961, -0.6447, -0.3119, +0.1573, -0.3272, -0.6251, +0.0969, -0.9605, -0.0935, -0.1721, +0.3689, -0.1753, -0.7054, -0.1648, -0.7860, +0.3147, -0.3318, -0.4041, +0.0940, +0.7184, -0.3698, +0.5603, +0.2647, +0.2764, -0.5868, -0.0931, -0.1904, -0.1462, +0.3757, -0.1287, -0.2810, +0.0976, -0.2559, +0.2289, +0.1456, +0.0947, +0.1649, -0.0449, +0.0254, -0.0624, +0.2917, -0.1126, +0.1546, -0.4106, +0.3425, -0.2223, -0.1813, +0.3036, +0.2795, +0.1488, +0.1489, -0.0121, -0.6496, +0.1909, +0.0567, -0.1244, -0.1460, -0.1951, +0.1426, +0.0090, -0.8283, +0.1649, -0.3020, +0.2870, -0.5023, +0.1188, -0.5140, -0.1743, -0.0307, +0.0629, +0.0458, -0.1941, -0.1876, +0.4947, +0.4413, -0.7051, +0.0857, +0.2037, -0.1575, -0.0895, -0.4297, +0.3757, +0.0474, +0.0595, +0.1458, +0.3288, +0.2035, -0.1370, +0.1637, +0.2244], +[ -0.0494, -0.5338, +0.3075, +0.3866, -0.0238, +0.0546, +0.3774, +0.1667, -1.4458, -0.3139, -0.0358, +0.2484, +0.0907, -0.1575, -0.6370, -0.0251, -0.1844, -0.0867, +0.0449, +0.2515, -0.5639, -0.2377, +0.0194, +0.2508, +0.3766, -0.0566, -0.5726, +0.2667, +0.3919, -0.1322, -0.1609, -0.4608, +0.1251, +0.5491, -0.0081, -0.1707, -0.5703, -0.1431, +0.3946, -0.1315, -0.1477, +0.3808, -0.4407, +0.0204, -0.0408, -0.0296, +0.2634, +0.3544, -0.1645, +0.3577, -0.1202, +0.0353, +0.6943, -0.2540, +0.4272, +0.4394, -0.0890, +0.0457, +0.2672, -0.0779, +0.2240, -0.3899, +0.2615, -0.3007, -1.1412, -0.2154, -0.0115, +0.3824, -0.2625, +0.2427, +0.5087, +0.1939, +0.0251, +0.1826, +0.2723, +0.3710, +0.0138, -0.3563, -0.4064, -0.2353, +0.0655, -0.4434, -0.0499, +0.1209, +0.1625, +0.0255, +0.1468, +0.3519, +0.0685, -0.2707, -0.3953, +0.2012, -0.3277, +0.1075, -0.9070, +0.0664, -0.0505, +0.9489, -0.2441, +0.2456, +0.1766, -0.0657, +0.4403, +0.0069, -0.5148, -0.0763, +0.5377, +0.1470, -0.2591, +0.2392, -0.5094, -0.6703, -0.0883, -0.1473, +0.4173, -0.5030, +0.5998, -0.1939, +0.2321, -0.0096, +0.0813, +0.0249, -0.0330, +0.4237, +0.3936, +0.7550, -0.1033, -0.4626], +[ -0.1749, +0.4291, +0.1856, +0.8326, -0.2389, -0.1074, +0.0163, -0.4133, -0.1674, -0.4193, -0.2264, +0.0122, +0.1945, +0.3477, +1.1767, -0.2818, +0.2058, +0.1774, -1.2170, -0.0517, -0.1186, +0.1058, +0.5971, -0.1671, -0.5438, +0.2372, +0.1234, -0.8853, +0.0058, +0.1098, -0.2242, -0.1922, -0.5617, -0.1774, -0.2270, -0.2765, -0.0398, -0.2875, -0.2003, +0.4318, -0.0017, +0.6389, -0.3364, -0.1669, +0.1289, +0.0043, +0.1394, +0.0054, -0.0405, -0.1790, -0.3323, -0.0987, -0.6836, -1.5795, -0.7282, +0.8996, -0.1916, +0.4577, -0.3145, +0.3770, -1.1245, -0.1127, +0.3954, +0.3256, +0.6970, -0.0398, -0.4260, -0.1392, +0.2852, -0.3624, +0.5735, -0.3427, -0.5304, -0.1201, +0.0896, +0.0079, -0.4158, +0.7538, -0.2106, +0.0878, +1.1722, +0.0430, -0.7040, -0.3037, +0.2125, +0.2748, +0.0432, -0.9073, -0.5361, -0.0635, +0.1367, -0.2737, +0.1896, -0.0686, -0.8063, +0.1628, -0.2493, -0.0644, -0.4000, -0.0832, -0.8262, -0.2087, +0.0469, -0.2701, -0.0342, +0.3451, +0.3271, +0.1488, -0.2298, +0.0165, +0.3822, +0.3408, -0.5740, +0.4275, -0.4073, +0.1550, -0.0615, -0.3236, +0.3417, -0.4795, -1.4346, -1.1582, -0.0334, +0.1012, +0.0681, -0.3589, +0.0009, +0.2403], +[ +0.4514, +0.2783, +0.6260, +0.3761, -0.2668, +0.2137, -0.2847, +0.1101, +0.1570, -0.8077, -0.3457, -0.1276, -0.3249, -1.1498, +0.3708, +0.0481, +0.3022, -0.5984, +0.5839, +0.0303, +0.0994, -0.2405, +0.0918, +0.5515, -0.1574, +0.0112, +0.1610, +0.0654, -1.0527, +0.3909, -0.1364, -0.5042, -0.0112, -0.1151, -0.3180, +0.0759, +0.4440, +0.0077, +0.4591, +0.2136, +0.0356, -0.3316, -0.3721, -0.4922, -0.1280, -0.4384, -1.0652, -1.0171, +0.3237, -0.1799, +0.4100, +0.1289, -0.5390, -0.4013, +0.1032, +0.2068, +0.2910, +0.0418, -0.6356, +0.1113, +0.0839, -0.5103, -0.3927, -0.4109, +0.1319, -0.5748, +0.2908, +0.2892, -0.5980, +0.1307, +0.6128, -0.5456, -0.2789, +0.3952, +0.2433, -0.2612, +0.1269, +0.3073, +0.0327, -0.7277, -0.0694, -0.1416, +0.1028, +0.2833, -0.1480, +0.1768, -0.8571, -0.0552, +0.2363, -0.2078, +0.2579, -0.0756, -0.6716, -0.7545, +0.0556, -0.2509, +0.2202, -0.4954, +0.5409, +0.2372, -0.5721, +0.2712, -0.8320, +0.0032, -1.1220, -0.3420, -0.4108, +0.2167, -0.0481, +0.1335, +0.5197, -0.0579, +0.2260, -1.0780, +0.0694, +0.0960, +0.0198, -0.1209, -0.0714, -0.3428, -1.4402, -0.0295, -0.8579, -0.0698, +0.0709, -0.6385, +0.1580, +0.3372], +[ -0.1761, -0.1190, -0.1444, -0.1236, +0.0190, -0.6771, +0.1407, -1.1494, -0.5002, +0.1270, +0.1412, -0.1491, -0.4276, +0.1093, -0.2619, -0.5989, -0.0392, -0.3743, +0.1734, -0.6701, +0.3487, +0.1645, +0.0872, -0.0868, -0.3575, -0.4350, +0.5061, -0.0672, -0.7309, -0.3852, -0.5321, +0.0891, +0.1581, -0.9461, +0.3101, +0.2622, +0.1075, -1.1945, +0.0055, +0.1117, -0.2656, +0.1402, -0.2464, +0.1366, +0.0586, -0.0188, +0.0702, +0.1080, +0.5085, -0.8725, -0.6361, +0.2417, +0.2799, -0.2453, +0.0209, +0.1083, -0.6030, +0.0556, +0.4698, -0.5757, +0.3942, -0.7870, -0.5153, -0.3523, -0.7754, +0.1655, +0.1634, +0.1448, +0.0469, -0.5121, -0.3382, -0.1957, +0.4266, +0.0971, +0.3234, -0.0826, -0.8881, +0.4790, +0.0021, -0.0421, -0.6887, +0.0712, +0.0470, -0.6644, -0.1432, -0.4532, -0.6663, +0.1885, -0.2055, -0.4784, +0.0304, -0.0816, -0.3079, -0.3411, -0.2617, -0.4918, -0.2279, +0.2341, +0.3344, +0.3590, -0.2672, -0.3317, -1.4133, +0.2980, +0.0894, -0.0787, -0.6533, +0.4272, -0.1723, -1.3314, -0.2505, -0.6322, -0.0732, -0.3339, -0.2277, -0.5841, -0.0023, +0.6160, -0.8841, -0.3858, +0.1262, -0.1833, -0.3150, +0.2126, -0.0341, +0.1543, -0.0226, -0.0872], +[ +0.1093, -0.3953, -0.2439, +0.2264, +0.0552, -0.2641, +0.1326, -0.3655, -0.0776, +0.1456, -0.3135, -0.2428, +0.1776, +0.0427, -0.1049, +0.3194, -0.6210, -0.1818, +0.0587, -0.3108, -0.0102, +0.3117, +0.2641, +0.0718, -0.2656, -0.0378, +0.0577, +0.3685, -0.2128, +0.5100, -0.3235, +0.4025, -0.4131, -0.2795, +0.4549, -0.5022, -0.7002, +0.1465, +0.1464, +0.4145, +0.2155, +0.2542, -0.4837, +0.4830, +0.2456, +0.2177, +0.3704, +0.4179, -0.2369, -1.2701, -0.1190, -0.0053, +0.0357, -0.3522, +0.6011, -0.4625, -0.0481, +0.3027, -0.3711, -0.1843, -0.1280, -0.1988, +0.0890, +0.2666, +0.3521, -0.0716, -0.5562, -0.2326, -0.5869, -0.0804, +0.2775, +0.3285, -0.2048, -0.0762, -0.2221, -0.1345, -0.5772, +0.4186, -0.3327, -0.3538, +0.2481, +0.2320, -0.2328, +0.0304, -0.0009, +0.3131, +0.3529, +0.0744, +0.1237, -0.9127, +0.0470, -0.7908, +0.7607, +0.2485, -0.1654, -0.1840, +0.2082, +0.1369, +0.1086, -0.3694, -0.0488, -0.1335, +0.2039, +0.4223, -0.3518, -0.1256, +0.1546, -0.5031, +0.0287, +0.0298, +0.1991, +0.0729, -0.0224, -0.2507, -0.8534, +0.1450, -0.0068, -0.3593, -0.1262, -0.4906, +0.2334, +0.0321, -0.7071, +0.2864, -0.0723, -0.0620, -0.3231, +0.5353], +[ -0.1872, -0.6072, -0.1623, -0.2428, +0.5207, -0.4531, +0.3649, -0.0208, -0.0905, +0.1987, -0.1625, +0.0392, -0.7373, -0.2516, -1.1968, -0.2712, -0.3207, -0.2279, -0.1482, +0.3457, -0.6574, +0.2216, -0.7708, +0.0120, -0.2948, -0.2319, +0.0410, -0.1395, +0.1286, -0.8962, -0.6844, -0.2874, -0.2098, -0.8660, -0.3060, +0.1075, -0.4889, -0.4876, +0.1585, +0.0271, -0.7649, -0.3120, -0.5355, -0.3379, +0.0560, -0.1290, -0.5892, -0.0722, +0.0397, -1.7302, -0.1772, +0.0709, +0.4661, +0.5430, +0.0243, +0.1174, -0.7254, +0.3965, +0.0488, +0.5466, +0.0975, -0.5617, +0.5235, -0.1244, -0.5608, +0.1739, +0.5572, +0.4367, -0.4987, +0.2556, -0.6455, +0.2922, -0.4531, +0.1180, -0.0714, -0.3898, -0.7729, -0.2274, +0.0612, -0.0508, +0.1203, +0.1132, -0.2378, -0.4293, +0.9299, +0.1615, +0.0224, +0.1529, -0.6744, -0.6975, -0.7713, -0.1987, -1.2150, -0.0764, -0.4671, +0.1748, -0.0191, -0.1449, +0.3394, +0.2276, +0.4175, -0.4635, -0.0192, -0.0181, -0.2375, +0.0315, -0.9739, -0.0035, -0.1776, -0.1825, -0.1149, -0.6031, -0.1993, +1.0660, +0.1942, +0.2916, -0.3240, +0.1672, +0.8438, +0.0368, +0.2153, -0.2414, -0.5326, -0.1686, -0.8086, +0.2675, -0.1521, +0.1660], +[ +0.3672, +0.3659, -0.3833, -0.0773, +0.5133, -0.1099, -0.1455, -0.2446, +0.1592, +0.1504, +0.1035, +0.3368, -0.3332, -0.2314, +0.1218, +0.5182, +0.2823, -0.7633, -0.2657, -0.4206, +0.2680, +0.3045, +0.1340, -0.7384, +0.1212, +0.5130, +0.1806, +0.0665, +0.3528, +0.3223, -0.1746, +0.2645, +0.0619, +0.4065, +0.5508, -0.4019, -0.5304, -0.9035, -0.9114, -0.7582, -0.1242, +0.0469, -1.1396, -1.0376, +0.2146, -0.1570, -1.2924, -0.5072, -0.5510, +0.8576, -0.6060, -0.5182, -0.4349, +0.5918, -0.2843, +0.2225, -0.8508, -0.4305, +0.1419, -0.4509, -0.7419, -0.4085, -0.0913, -0.1617, -0.2415, -0.3566, -0.4031, -0.8209, -1.1396, -0.1332, +0.2044, +0.0062, -1.3372, -0.4069, -0.3494, +0.0520, -0.4325, -0.2444, -0.3479, -0.4087, -0.0608, -0.0265, +0.7527, -0.4687, -0.1593, +0.3562, -0.7702, -0.0494, +0.5192, -0.0127, +0.1519, +0.4498, +0.2519, -0.3605, -0.8008, +0.2678, +0.4282, -0.2361, +0.4220, +0.2413, -0.3887, -0.1261, -0.2721, -0.0707, -0.5530, -0.0053, -0.0583, +0.1979, +0.2960, -0.9714, -0.5201, -0.5804, -0.0634, +0.4646, +0.0475, -0.9271, -0.1548, -0.4379, -0.7117, +0.5550, -2.2792, -1.3753, +0.3930, -0.2748, -0.1226, -0.1022, -0.1620, -0.5356], +[ +0.2949, -0.0316, -0.3410, -0.8611, -0.3436, -0.0336, -0.5042, +0.3260, +0.0233, +0.5927, -0.4618, -0.2004, +0.0765, -0.3380, -0.5127, +0.1943, -0.4830, -0.3109, +0.1185, -0.2727, +0.0741, +0.4450, -0.2149, +0.2026, -0.2270, -0.4992, -0.2183, +0.3672, +0.0453, -0.0997, -0.3463, -0.9736, -0.1515, -0.9857, +0.0598, -0.5932, -0.3548, +0.1416, +0.2225, -0.3457, +0.2285, -0.6075, +0.1748, +0.3191, -0.2952, +0.2206, +0.1597, +0.0573, +0.0946, -0.0554, +0.4816, -0.2746, -0.2081, +0.0103, -0.1562, +0.0599, +0.4590, +0.0938, -0.1300, +0.2554, +0.8053, -0.3771, +0.0845, +0.1849, -0.2444, -0.3207, -0.2108, +0.4256, -0.4149, +0.3380, -0.5478, -0.1006, +0.3588, +0.0793, +0.0071, +0.0359, -0.4133, -0.4701, -0.2979, -0.1489, +0.3917, -0.3694, -0.2860, -0.1781, +0.4127, -1.5028, -0.7666, -0.4226, +0.0058, -0.2195, +0.2938, +0.1673, -0.1712, +0.0225, -0.2716, -0.4006, -0.8034, +0.1702, -0.6867, -0.6487, +0.4672, +0.3390, -0.1677, -0.1081, -0.1951, -0.6481, -0.0202, -1.5928, +0.2900, -0.1350, -0.1210, +0.1912, -0.0764, -0.6552, -0.2993, +0.3903, +0.1795, -0.6494, +0.4557, +0.0359, -0.1020, -0.0776, +0.2410, +0.4618, +0.1899, +0.0519, -0.1175, -0.4876], +[ +0.4475, +0.6580, -0.9072, -0.4252, -0.7311, +0.3157, -0.3769, -0.2521, +0.0655, -0.3300, +0.8021, +0.5316, +0.5242, +0.9494, -1.3550, -0.1479, -0.6358, -0.7123, -0.3423, +0.0953, -0.2029, +0.5488, +0.3757, +0.6414, -1.0084, -0.4088, +0.1759, +0.1782, -0.0354, -0.2070, +0.2549, -0.7897, -0.6122, +0.3156, +0.1283, +0.1304, +0.2468, -0.3438, -0.1424, -2.6215, -0.1281, +0.5616, +0.1851, -0.4052, +0.2366, -0.8374, +0.4125, +0.6650, -0.0151, -0.5108, -1.8219, -0.3488, +1.0016, -0.4113, -0.5853, +0.6533, -0.1658, +0.1938, -0.1667, +0.2028, +0.5964, -0.0301, +0.1358, +0.1099, -0.0235, -1.5907, -1.0106, -0.0173, -0.1321, +0.2166, -0.1253, +0.4326, +0.3080, -0.6533, +0.7349, -0.5500, +0.7962, +0.5124, +0.0823, +0.9100, +0.1135, -0.2727, +0.8711, -0.1426, -0.4308, -0.0841, +0.6076, -0.7595, -0.4672, +0.3527, -0.4772, +0.3365, -0.4806, -1.4707, +0.8538, +0.1737, -0.4534, +0.5326, +0.1963, -0.4248, +0.3910, +0.6292, +0.2747, +0.5681, -1.2108, -0.0866, -0.1978, -0.8462, -0.3194, -1.2809, -0.2784, +0.2669, -0.9332, -0.5646, -0.2407, +0.2679, -0.9020, -0.1795, -0.0125, -0.8087, -0.9155, -2.1798, +0.0504, -0.3026, -1.3238, -1.7538, +0.3439, -0.0563], +[ +0.0319, -1.6628, -0.0173, +0.2989, +0.1676, +0.0364, -0.1573, -2.2370, -0.2175, -0.9091, -0.6619, +0.0660, -0.5971, +0.3842, -0.3193, -0.3382, +0.3384, -0.2757, +0.3400, +0.1164, -0.4148, -0.1678, -0.3672, +0.9148, +0.4749, +0.0187, -0.3610, -0.2145, +0.2947, +0.1979, -0.1432, -0.1918, +0.1166, +0.2417, -0.0415, +0.1454, +0.1314, +0.5063, -0.6644, -0.1707, +0.2847, -0.4376, -0.1103, -0.8536, +0.2727, -0.1896, -0.5441, -0.5398, -0.0445, +0.0335, +0.0064, -0.4442, -0.0465, +0.3768, -0.8925, -0.2810, -0.1458, +0.1723, -0.0520, +0.9517, +0.7592, -0.2111, +0.1319, -0.8783, -0.2669, -0.2436, -0.2715, -0.4499, -0.7418, +0.1686, +0.0313, -0.0361, -0.3253, +0.2035, +0.0673, -0.2192, +0.0130, -0.2811, -0.0055, -0.4326, -0.5431, -0.3846, -0.2410, -0.8734, -0.1606, +0.0070, -0.3290, +0.5137, +0.3075, -0.1952, +0.0826, +0.1185, -0.0543, -0.1451, +0.4320, +0.5998, +0.4729, -0.3437, -0.3013, -0.4789, -0.4182, +0.2208, +0.1769, +0.1167, +0.5403, -0.2031, -1.8206, -0.9715, -0.4390, -1.0862, +0.0155, -0.7855, -0.5351, -0.0728, -0.4738, +0.0931, +0.4726, -0.0554, +0.2552, -0.5134, -0.3282, +0.0480, -0.2491, -0.4939, -0.3105, -1.0567, -0.0065, +0.1648], +[ +0.3248, -0.1633, +0.5252, -0.4404, -0.2621, +0.2188, +0.2378, -0.4007, -0.7312, +0.4298, +0.4192, -0.0322, +0.1656, -0.8179, +0.3438, +0.2162, +0.1376, -0.1415, +0.1829, +0.2162, +0.1823, +0.0527, +0.4989, -0.1013, +0.0446, +0.2098, +0.0298, +0.4420, +0.0982, +0.0556, -0.1275, -0.4022, +0.0921, +0.3972, +0.2696, -0.1864, +0.4565, +0.2358, +0.4417, -0.0330, +0.1875, +0.3638, -0.6421, +0.0176, -0.4929, +0.2501, -0.4281, -0.0558, +0.0193, +0.4463, +0.3124, +0.2450, +0.2867, -0.2307, -0.4713, +0.0499, -0.0854, +0.0547, -1.0298, -0.0193, +0.1035, +0.4370, -0.8156, +0.0611, -1.1987, -0.1717, -0.4427, +0.0735, -0.4460, -0.1526, -0.3083, -0.6694, +0.0866, +0.3043, +0.4516, -0.6468, -0.0721, -0.1257, -0.1034, +0.0416, -0.0325, -0.5287, +0.4402, -0.1051, -0.0580, -0.1416, -0.1219, +0.4046, +0.4270, +0.2213, +0.4172, +0.4552, -0.3745, +0.0014, -0.4077, -0.4349, +0.0824, -0.0385, +0.3813, +0.0135, +0.0187, +0.3953, -0.1952, +0.0045, -0.9718, -1.0177, +0.1590, -0.6199, +0.4418, -0.4560, -0.0083, -0.1064, +0.3796, +0.4562, +0.2073, -0.1268, +0.1443, +0.0193, +0.2260, +0.1600, -0.6394, -0.1616, -0.6255, -0.1362, -0.0162, +0.4192, +0.0862, -0.0224], +[ +0.2984, +0.0992, -0.0996, -0.6480, +0.1425, -0.2154, -0.2364, -0.5196, +0.2569, +0.4777, +0.0330, -0.2675, -0.4374, +0.4110, +0.2946, -0.1093, +0.6461, -0.2925, -0.1891, +0.3656, -0.1734, -0.6296, -0.5544, -0.3675, +0.3985, -0.1510, +0.3925, -0.2182, -0.0117, -0.0585, -0.3104, +0.3286, +0.8725, +0.6009, +0.1548, +0.1402, -0.0681, -0.3306, -0.2152, +0.1912, -0.1301, -0.6383, -0.0810, +0.0093, -0.1257, +0.4486, -0.1424, +0.0640, +0.4627, -0.2530, -0.1157, +0.2227, -0.1777, +0.3090, -0.2005, -0.1327, +0.3165, +0.0120, +0.4165, -0.3985, +0.1769, -0.0774, -0.1105, -0.1150, +0.2654, -0.0559, -0.1382, +0.2627, +0.2446, -0.5470, -0.5101, +0.0276, -0.3068, +0.4351, -0.0344, -0.2234, +0.3508, -0.8163, +0.2247, -0.7000, -0.3395, +0.0134, -0.1784, -0.2246, +0.6040, -0.2900, +0.3628, -0.3002, +0.4111, +0.5022, -0.4669, +0.2574, +0.5707, -0.2343, +0.6138, -0.1966, -1.4395, +0.0095, -0.4462, -0.1831, +0.0234, -0.5368, +0.2990, -0.5012, +0.1117, -0.1993, -0.2311, +0.4470, +0.5955, -0.8588, +0.1398, -0.7063, -0.1499, -0.0807, -0.1804, -0.6344, +0.0708, +0.0311, -0.2556, +0.2427, +1.2595, -0.2182, -0.0405, -0.1956, -0.4734, +0.0082, -0.2395, -1.0875], +[ +0.4931, -0.0139, -0.1785, -1.3003, -0.9315, +0.1883, +0.0783, +0.1156, +0.2229, +0.4970, -0.3026, -0.0427, +0.3666, +0.0441, +0.3605, +0.3052, +0.1717, +0.2815, -1.1105, +0.5068, -0.9422, +0.1006, +0.3818, -1.0538, +0.4193, +0.1306, +0.0993, -0.0268, +0.6013, -1.2039, -0.1301, -0.2177, -0.2388, +0.0288, -0.2354, +0.0407, +0.2387, -0.4171, +0.1845, +1.3959, -0.4449, -1.0931, +0.1117, -1.2900, -0.3455, +0.1650, +0.4779, +0.1619, -0.1346, +0.5967, +0.1350, +0.1895, -0.1691, +0.0322, -0.5549, -0.4310, -0.5731, -0.5571, +0.1791, +0.2053, -0.1841, -0.0625, +0.2050, +0.2110, -0.0270, -1.5258, -0.1127, +0.3542, -0.6700, +0.0764, +0.3272, -1.6352, +0.5401, -0.1176, -0.6925, -0.1588, +0.1769, -0.5969, +0.2519, -0.7011, -0.5501, -0.3885, -0.2958, -0.5574, -0.1361, +0.4964, +0.2261, +0.1588, -0.6176, +0.3896, +0.3587, -0.1452, -0.4678, -0.4397, -0.6235, -0.2614, -0.3143, -0.7581, -0.3924, +0.1405, -0.1026, -1.1059, -0.5655, -0.5290, -0.9429, +0.1219, +0.2150, -0.0211, +0.3210, +0.1728, +0.3014, +0.7363, -0.6684, -0.2873, -0.2049, -0.3292, -0.9234, +0.3870, -1.4117, +0.2839, -0.1830, -0.7153, -1.5961, +0.0216, +0.3415, -0.3118, -0.5493, -0.1679], +[ +0.3085, +0.1217, +0.2708, +0.1764, +0.0721, -0.5826, +0.0589, +0.1488, -0.2251, +0.1201, -0.5999, +0.3246, +0.7053, +0.4986, -0.6902, +0.4752, -0.1896, +0.3343, -0.5747, +0.2491, +0.0376, +0.0067, -1.5010, +0.0388, +0.0795, -0.4898, +0.2748, -0.7656, +0.0971, -0.3358, +0.1696, +0.1662, -0.4723, +0.2035, +0.1646, -0.0822, -0.1929, -0.8202, +0.2350, -0.1611, +0.1259, -1.3991, +0.2596, -0.0796, +0.3935, +0.1308, +0.0481, +0.0643, -0.5223, -0.7995, -0.1504, -0.1120, +0.1316, -0.5272, +0.1430, -1.6754, -0.3763, -0.4128, +0.2002, -0.0846, +0.1848, +0.2289, -0.1495, -0.2388, +0.1006, -0.4186, +0.6275, -0.8756, -0.2684, +0.1550, -0.7136, -0.5394, -0.0622, -0.5143, -0.5301, -0.5289, -1.3851, -0.1833, -0.3752, -1.3665, +0.3135, +0.3702, -0.2620, -0.2681, -0.1054, -0.5276, -0.8615, +0.1398, +0.5070, +0.0973, -1.3543, -0.1740, +0.2780, +0.2337, +0.2031, -0.0993, +0.3770, -0.5235, -0.4920, +0.0583, -0.0661, -0.0447, -0.0847, +0.2940, +0.1105, -0.4637, -0.0770, +0.1984, -0.1683, +0.3739, -0.3324, -0.1877, -0.2671, -0.3427, -0.2696, -0.6949, -0.8354, +0.0840, -0.7230, -0.2395, -0.2272, -0.1010, -0.5552, -0.0120, -1.7305, +0.4488, -0.7055, -0.0241], +[ -0.0699, -0.0347, -0.1426, +0.0382, -0.6711, -0.9992, +0.0990, -0.0885, -0.0089, -0.3321, +0.0392, +0.1791, -0.0517, -0.0319, +0.0047, -0.0617, -0.2380, +0.3098, -0.0395, -0.2500, -0.0267, -0.1255, -0.4858, +0.1856, -0.0685, -0.2430, +0.1449, +0.3326, -0.4269, +0.5182, +0.1142, -0.2007, +0.2764, -0.2299, +0.7191, -0.7689, -0.1414, -1.1110, -0.1952, +0.0435, -1.4034, +0.0324, +0.1118, +0.0090, -0.0316, -0.2086, -0.1791, +0.1090, -0.3573, +0.0272, +0.4384, +0.0325, -0.5804, +0.0563, +0.3496, +0.1126, -0.6086, -0.1028, -0.6224, +0.6576, +0.4319, -0.4998, +0.1549, -0.3424, -0.1119, -0.3496, +0.4719, +0.0783, -0.4349, +0.1816, -0.5880, +0.1618, -0.3262, -0.3673, -0.3076, -0.1708, -0.4230, -0.5483, +0.4582, -0.7904, -0.5307, -0.5135, -0.5689, -1.2002, -0.1985, +0.1232, +0.2213, -0.1413, +0.2333, +0.4705, -0.5972, +0.5658, -0.1857, -0.0892, -0.5555, +0.0480, -0.7166, -0.3275, -0.3127, +0.2932, -0.2623, -0.6273, -0.2590, -0.1251, -0.2027, +0.2016, -0.7108, -0.2773, -0.4188, +0.5586, +0.2671, -0.2214, -0.0762, -0.9201, -0.4880, +1.1728, -0.0636, +0.1197, -0.7996, -0.1891, -0.7012, -0.5298, +0.4840, -0.2211, +0.3282, -0.3851, +0.2790, +0.2206], +[ +0.2515, -0.0460, +0.6307, -0.4469, -1.2297, +0.3137, -0.0871, -0.9855, +0.3819, -1.2793, -0.4935, +0.2099, -0.2078, +0.5218, -0.3201, +0.5992, -0.3316, -0.6488, -0.4344, -0.2481, +0.4467, -0.1658, +0.3424, -0.7730, -0.0601, +0.2052, -0.7356, -0.1673, +0.0029, -0.1864, +0.4766, +0.4392, -0.5309, -0.2602, -0.4008, -0.9269, -0.8221, -0.3150, -0.5733, -0.5973, -0.1171, -0.2877, +0.4653, +0.6510, -0.0373, +0.1813, -0.5940, -0.3138, -0.1951, -0.2005, +0.3433, +0.3224, +0.0881, -0.2401, -1.2631, -0.0198, +0.0647, -0.4116, -0.1162, -0.3314, +0.1495, +0.1694, +0.1436, -0.2433, -0.6034, -0.1160, +0.4647, -1.1555, +0.2582, -0.7255, -0.8492, +0.1665, +0.0833, +0.7934, +0.0374, +0.1002, -0.1522, +0.9246, -0.4266, +0.3160, -0.1681, +0.4971, -0.1865, -0.1163, -0.9149, +0.3540, -0.2281, +0.0785, +0.0523, -0.3920, -0.7295, -1.5365, -0.3843, +0.2214, +0.5486, -0.1391, -0.0621, +0.6017, -1.6143, -0.2603, -0.4795, -0.6317, -0.4797, -0.0137, -0.5190, -0.4591, -1.6069, +0.2246, -0.1321, +1.2048, +0.1243, +0.1225, +0.1101, -0.2003, -0.8028, +0.2594, -0.0839, +0.9636, -0.1147, +0.4519, -0.9124, +0.5739, +0.0732, +0.1405, +0.2791, -0.0281, -0.3491, +0.4972], +[ +0.2997, -0.0590, +1.5474, -0.2897, -0.0720, +0.4884, +0.3767, -0.6406, +0.2781, +0.1654, +0.5724, -0.3223, -0.3083, -0.0130, -0.8242, +0.1416, -1.2836, -0.2536, -0.5389, -0.7150, +0.2057, +0.3423, +0.1123, -0.4825, -0.3663, -0.0181, -0.9098, -0.8177, -0.1424, +0.6420, -0.2045, -1.4718, +0.8390, -0.3501, +0.7143, +0.4790, -0.8828, -0.6263, +0.4958, -0.3797, +0.0561, -0.5050, -0.7387, +0.1345, +0.0628, -0.0689, -0.3732, -0.4678, -0.5067, +0.8548, +0.1120, +0.6079, -0.0247, -0.5180, +0.0315, +0.7373, -0.0192, -0.0424, -0.6181, +0.3579, +0.2907, -1.0741, -0.5571, -0.4145, +0.6020, +0.1359, -0.1789, -0.7475, +0.2754, +0.3870, -0.5211, +0.0470, +0.2925, -0.6933, -0.4954, +0.5955, +0.3210, -0.7589, +0.3018, -0.5384, -1.0367, +0.2131, -0.3080, -0.1733, +0.0630, -0.5894, -0.3412, +0.9476, +0.0097, -0.6666, -0.1119, +0.2413, -0.6325, -0.2442, -1.2067, -0.3356, +0.2132, +0.1711, -0.8029, -0.0991, +0.3307, +0.3498, -0.9837, +0.4930, -0.7711, -0.9355, -0.3776, +0.2788, -1.0194, -0.4159, -0.3065, -0.5042, +0.1818, -0.3402, -0.6123, -0.6465, +0.0899, -0.0228, -0.9121, -0.7620, -1.9192, -0.1273, -0.3641, -0.6793, -0.6107, -0.9946, -1.3522, -0.0111], +[ -0.1071, -0.0914, -0.3853, -0.4486, -0.4044, +0.3221, +0.2509, -0.2483, +0.8798, -0.0691, -0.9215, +0.4125, +0.0706, +0.3623, -1.1719, -0.1146, -0.1429, +0.2887, -0.0463, -0.1385, +0.0253, +0.6948, +0.2812, +0.2271, +0.1506, +0.1074, +0.2028, +0.3923, +0.0775, +0.1088, -0.2068, +0.3874, -0.1533, -0.1300, +0.3297, -0.5180, -0.0545, +0.3264, +0.1504, +0.4627, -0.6114, +0.1983, -0.2525, +0.0557, +0.1478, +0.2654, +0.1795, -1.0393, -0.3441, +0.2040, -0.2679, -0.1513, -0.0434, -0.6975, -1.2178, +0.0540, +0.0830, -0.4225, -0.1042, +0.3557, -0.4862, +0.4225, +0.0174, -0.0394, -0.2975, +0.2248, -0.5806, -0.0481, +0.0870, -0.9754, -0.3492, -0.2499, +0.1434, -0.7345, -0.4206, -0.1391, +0.5547, -1.5464, +0.2995, -0.2667, +0.2176, -0.0222, -0.8436, +0.3644, -0.0144, +0.1929, -0.1981, -0.2658, +0.0008, +0.2550, +0.2259, +0.2459, -0.0549, -0.8412, -0.2304, +0.2651, +0.3952, -0.1507, +0.7589, +0.1382, +0.3815, +0.4374, +0.5381, -0.2944, -0.7976, +0.5965, -0.2968, +0.2455, +0.3352, -0.7624, +0.1680, -1.0777, +0.2098, +0.0263, +0.5142, +0.1962, -0.9001, -0.2288, -0.0602, -0.3794, -0.0381, -0.3365, +0.5141, -0.2042, -0.2965, -0.2482, +0.0614, -0.0506], +[ -0.4827, -0.9625, -0.6821, +0.6980, -0.7364, -1.0121, +0.1778, -0.2168, -0.5134, +0.0203, -0.1385, +0.3100, -0.4719, -0.0024, -0.7544, +0.1833, -0.5929, +0.0118, +0.5007, +0.2929, -1.1400, -0.3093, +0.1488, +0.0664, -0.0794, +0.1037, -0.1451, +0.4052, +0.6305, +0.0479, +0.6161, -0.2096, +0.4492, +0.1423, -0.8857, -0.5945, -0.9675, +0.1129, -0.0625, +1.0241, -0.2228, -0.3425, +0.3905, -0.0610, -0.7793, -0.5432, -0.4786, -0.7494, -0.3886, -0.0728, -0.3910, -0.3117, -0.6177, +0.7814, +0.1274, -0.1076, -0.9399, -0.1651, -0.2074, -0.3800, +0.1975, +0.3417, -0.3567, +0.1682, +0.5643, -0.3865, -0.5320, -0.0927, -0.4048, -0.3455, +0.4964, +0.2474, +0.6381, -0.2735, +0.1357, +0.0831, -0.7824, +0.1336, +0.1894, -0.5041, +0.1137, -0.8554, -0.3267, -0.8148, +0.2027, -0.6058, +0.2357, -0.6815, +0.3592, -1.0961, -0.0851, -0.3931, -0.3858, -0.4947, +0.3376, -0.4960, -1.2253, -0.2729, -0.0613, +0.0338, -0.4375, +0.1772, -1.2183, -0.3815, -0.6360, -0.1212, +0.5667, +0.3882, -0.2186, +0.3979, -0.8886, +0.5915, -0.1799, -0.2567, -1.1061, +0.2576, +0.0697, +0.5720, -0.7618, -0.0331, -0.3751, -0.5745, -0.3045, -0.0802, -0.2254, +0.2281, +0.7876, +0.8453], +[ -0.5146, -0.1675, +0.4185, +0.3867, -2.0276, -0.3550, -0.0103, +0.0759, -0.5695, -0.5775, +0.4338, +0.0862, -0.2782, -1.1816, +0.4527, +0.0245, +0.2384, +0.2595, -0.1889, +0.1669, +0.1330, -0.5044, +0.1522, +0.1296, +0.1008, -0.1094, -1.0970, +0.2959, -0.0608, -0.2347, +0.0648, -0.8752, -0.0874, -0.3487, +0.1176, +0.6469, +0.4873, +0.2115, -0.1896, -0.3099, +0.2538, +0.1531, -0.0522, +0.1851, -0.4144, -0.0601, -0.1023, +0.0833, +0.0115, +0.0726, +0.8781, -0.2878, -1.7336, +0.0163, -1.6014, -0.0083, -0.3536, +0.2323, -0.7565, -0.2184, -0.4687, +0.3105, +0.3376, +0.4321, -0.3851, +0.0826, -0.2408, +0.0863, -1.4832, +0.0563, -0.2557, -0.3054, -0.3075, -0.2278, -0.1671, +0.0521, +0.3658, +0.3719, +0.0804, -0.6263, -0.1550, -0.1028, -0.2334, +0.2369, -0.4011, +0.9961, -0.0063, +0.9473, +0.2949, -0.1119, -0.6594, -0.4036, +0.4119, -0.6482, -0.1113, +0.1171, -0.4483, -0.4772, -0.0929, +1.0857, +0.2080, +0.1390, +0.6034, +0.2009, +0.0470, +0.1179, -0.3087, -0.2450, -0.3718, +0.1897, -0.0922, +0.5298, +0.0121, +0.1860, +0.1340, +0.4798, -0.0977, -0.1933, -0.1136, -0.0081, -0.3595, -0.1116, -0.8788, -0.8181, +0.0373, +0.1917, +0.0235, +0.4108], +[ -0.2226, -0.1118, -0.4395, +0.0949, +0.2345, +0.1716, -0.5861, +0.3246, -0.1655, -0.3465, -0.1213, -0.3040, +0.2176, -0.1509, +0.1273, +0.2831, -0.2209, -0.0024, -0.1555, +0.2461, -0.4054, -0.3875, -0.2816, +0.1992, +0.2812, -0.4946, -0.0605, +0.4227, -1.1630, +0.0745, -0.0690, -0.1638, -0.1808, +0.0094, -0.0691, -0.2381, -0.8959, -0.2208, +0.3658, +0.5741, +0.2885, -0.0040, +0.4126, -1.0711, +0.3548, -0.3181, -0.6322, -0.1208, -1.0722, +0.2538, -0.5078, -0.5311, +0.3811, -0.2693, +0.2067, +0.6466, +0.0822, -0.1527, +0.1130, -0.3884, -0.3325, -1.1208, +0.1370, -0.3095, +0.0311, +0.1457, -0.0690, +0.0818, -0.5080, -0.7021, -1.9342, +0.0178, -0.1540, +0.1579, +0.5999, -0.0807, -0.0241, +0.4862, -0.1039, -0.0031, -0.5623, +0.0595, +0.1014, -0.7204, +0.0172, +0.2057, +0.2657, +0.4014, -0.2632, +0.3744, +0.3248, -0.4278, -0.5524, +0.4031, -0.4441, +0.5158, +0.4152, -0.1849, +0.5721, +0.3827, +0.2814, -0.0213, -0.1929, -0.2211, +0.2765, -0.5487, +0.4636, -0.3462, -0.2213, +0.2036, -0.0372, -0.7832, +0.3035, -0.3648, +0.1918, -0.2024, +0.1873, -0.3389, -0.1560, +0.2861, +0.5234, +0.1103, -0.0112, -0.1042, +0.5901, -0.1086, -0.3113, +0.2456], +[ +0.6437, +0.2104, -0.1146, -0.2029, -0.1413, +0.0463, -0.1361, -0.3423, -0.5981, -1.3993, -0.2364, -0.6253, -0.0367, +0.0396, +0.4071, -0.1041, +0.2952, -0.7470, -0.5323, +0.1711, -1.6514, -0.2995, -0.1617, -0.0444, +0.2066, -1.2562, +0.1500, +0.2685, +0.0740, -0.6300, -0.1595, -0.2937, -0.1878, -0.1974, +0.0573, -0.1410, +0.3946, +0.3699, -0.2207, -0.9597, +0.6649, +0.3057, -0.1968, -1.5333, +0.0333, +0.1745, +0.6678, -0.4441, -0.5636, -0.0175, -0.8500, -0.1240, -0.6060, +0.2580, +0.1085, +0.0204, -0.4799, +0.0779, +0.4179, -0.0790, -0.1145, -1.4217, +0.7018, +0.0990, +0.4478, +0.2631, -1.5982, -0.1057, -0.6651, -0.2051, +0.9339, -0.7448, -0.7337, -0.1249, +0.1416, +0.3265, +0.4638, -0.3997, +0.1113, -0.6644, -1.0355, -0.5059, -0.3138, -0.8874, -0.8188, +0.2271, -0.5940, +0.4332, -0.5486, -0.2080, -0.8829, -0.1462, -0.7029, -1.0269, -0.4292, +0.6677, -0.6375, +0.2042, -0.0905, +0.5251, -0.1005, -0.0572, -0.2358, +0.1797, -0.6072, -0.5522, +0.0565, -0.6040, -0.0751, -0.0251, -0.0597, -0.6340, -0.4350, -0.4168, +0.1966, -0.3608, -0.3125, -0.1044, +0.2857, -0.2191, -0.0965, -0.1001, +0.1235, +0.3814, +0.0643, -0.8396, +0.3091, +0.3177], +[ -0.0125, +0.3690, -0.0585, -1.0826, -0.8428, -0.1197, -0.1145, -0.2935, +0.3786, -0.0549, +0.4265, -0.2455, -0.1427, +0.2034, +0.2929, +0.4222, +0.1811, -0.4978, -0.3388, +0.3621, -0.0699, -0.4999, -0.5357, +0.0117, -0.5642, +0.0933, +0.1825, +0.6247, +0.6617, +0.2117, +0.5872, -0.2158, -1.5956, -0.4088, +0.1522, -0.0365, -0.1444, +0.0480, +0.0145, -0.8867, -0.3696, +0.7545, +0.0776, -0.4678, +0.2637, +0.0863, +0.4760, -0.7836, -0.8257, -0.7849, +0.3583, +0.2555, -0.3267, +0.0516, -0.4765, -0.2294, -0.1335, +0.6383, -0.0482, +0.1919, +0.4054, -0.0641, +0.1350, -0.6503, +0.2876, -0.1300, -0.0278, +0.1501, -1.4875, +0.3619, -0.7003, -0.0982, +0.0386, +0.2116, -0.1633, +0.5162, -1.7085, +0.1229, +0.0061, +0.4792, +0.0814, +0.2878, +0.2448, -0.0493, +0.2096, +0.8204, -0.0978, +0.1990, -0.0858, +0.1393, +0.5323, -0.4105, +0.3717, -0.3621, +0.1622, -0.0615, +0.0896, +0.2078, +0.1755, -0.6073, +0.0121, +0.5078, +0.4294, -0.2070, +0.0555, -0.3551, -0.2384, +0.9508, +0.9955, +0.3392, -0.1987, -0.4620, +0.3046, -1.0395, -0.0181, +0.4667, +0.0746, -0.3318, -0.1283, +0.4452, -0.2630, -0.2656, -0.2240, +0.2857, -0.5009, +0.1492, -0.1431, -0.1559], +[ -0.0629, -0.2279, -0.2815, +0.1708, +0.8295, -0.1126, -0.1447, -0.6849, -0.1887, -0.0727, -0.3118, +0.3364, +0.1892, -0.0240, +0.6113, +0.3232, -0.1727, -0.1026, -0.1972, -0.1144, -0.1729, +0.0693, +0.0774, +0.6179, -0.0878, -0.1258, -0.0726, -0.4002, -0.0009, +0.1317, -0.1568, -0.1211, -0.3489, -0.2788, +0.3074, +0.1012, +0.4588, +0.5282, -0.4225, -0.3813, +0.3806, +0.0643, +0.3658, +0.1461, -0.5421, +0.5411, -0.3853, +0.3188, -0.2143, +0.3654, +0.1371, +0.1195, +0.4107, -1.8788, -0.3085, +0.1691, +0.3571, +0.1617, -0.1075, -0.0012, -0.0209, +0.1295, +0.0088, +0.2663, -0.4468, +0.2328, -0.5461, -0.4623, +0.0639, -0.4745, +0.0185, +0.1748, +0.2751, +0.0289, -0.1511, -1.0610, -0.9342, +0.1023, -0.5897, +0.4368, +0.4395, +0.3023, +0.0362, +0.0504, +0.0549, +0.4292, -0.2066, -0.0201, +0.5096, -0.6873, -0.0542, -0.6261, -0.4679, +0.3975, +0.6687, +0.0149, -0.0495, +0.2126, +0.3135, -0.4383, +0.2927, -0.2681, +0.4141, +0.0640, +0.5893, +0.0434, +0.3599, +0.5617, +0.2766, -0.1020, +0.5417, -0.4419, +0.0661, -0.0103, -0.0789, -0.4222, +0.8133, -0.6130, -0.2251, -0.3994, +0.0350, +0.4120, -0.0729, +0.1060, -0.1923, +0.2212, -0.0015, -0.1975], +[ -0.4066, +0.0110, -0.1552, +0.7796, -0.0239, +0.3462, -0.2415, +0.0705, +0.2349, -0.0734, -0.3265, -0.1310, +0.2559, +0.5686, -0.4128, +0.0741, +0.3212, -0.2172, +0.1443, +0.0788, +0.3495, -0.5490, +0.3459, -0.0580, +0.0692, -0.9546, -0.4976, -0.1698, +0.1399, -0.4934, -0.6442, +0.6383, +0.4024, -0.2844, +0.1234, +0.1897, -0.0190, -0.0917, -0.2153, +0.7597, +0.3709, -0.5425, +0.0875, +0.1794, +0.1240, -0.2885, -0.6782, -0.2058, -0.2110, +0.3166, +0.2170, +0.2508, -0.0191, -1.8132, -0.4284, -0.4284, +0.3022, -0.0620, +0.1973, -0.1018, -0.1348, -0.3027, -0.2532, +0.8243, -0.9928, -0.0993, -0.3451, -0.2089, -0.3335, +0.1183, +0.3709, -0.6175, +0.7353, -0.6027, +0.2178, +0.1978, -0.3458, -0.0521, -0.6020, +0.1237, +0.0796, +0.0057, +0.1332, +0.7635, -0.5412, +0.0156, -0.3960, +0.0878, -0.1451, -0.9331, -0.4365, +0.1153, -0.0123, +0.1842, -0.1648, -0.3365, -0.0141, +0.2035, +0.1613, +0.1402, -0.1826, -0.7295, +0.0094, +0.1283, -0.5300, +0.0302, +0.3494, +0.3142, -0.8464, +0.6401, +0.4011, -0.2069, +0.0559, -0.3056, +0.1178, +0.0165, +0.0848, +0.2998, -0.0056, +0.2207, -0.4445, +0.2723, -0.5331, -0.0323, -0.3625, +0.4932, +0.2006, -0.1021], +[ -0.0519, +0.6391, -0.9079, -0.4731, +0.1328, -0.9114, +0.1221, -0.8589, -0.1144, -0.0532, -0.2697, +0.1769, +0.1012, -0.1550, -0.2779, -0.0026, -0.1059, -0.8324, -0.0975, +0.1698, +0.0020, -1.0129, -0.0535, +0.0840, -0.6365, +0.3403, -1.0890, +0.2234, +0.2051, -0.3762, -0.0219, -0.0708, +0.3895, -0.0854, +0.1450, -0.3397, -1.0253, -0.1690, +0.2384, -0.0361, +0.6280, -0.0232, -0.4950, +0.0184, -1.0879, -0.7964, -0.4034, -1.1418, -0.2425, +0.1005, -0.1049, +0.2868, -0.9874, +0.2592, -0.7185, +0.2495, -0.2086, -0.3738, +0.1108, -0.1768, -0.2887, -0.8102, +0.4337, +0.1725, -0.2910, -0.0147, -0.0028, -1.5598, +0.5284, +0.1599, +0.1920, +0.2220, -0.2343, -0.0158, +0.5636, +0.0944, -1.1463, -0.2529, +0.1844, -0.6164, +0.2345, -0.0869, +0.4677, -0.6338, +0.0034, -0.4730, -0.2976, +0.0252, -0.4131, -0.3446, -1.0642, -0.1187, +0.9727, +0.5157, -1.0458, -0.3792, +0.0248, -0.3634, +0.5012, -0.4836, +0.1707, +0.0261, +0.5114, -0.0316, +0.3451, -0.0684, -0.3541, -0.2896, +0.2410, -0.7695, -0.7893, -0.2634, -0.3458, +0.3608, -0.8740, -0.0193, +0.4683, -1.3214, +0.4505, -0.8586, -0.5350, +0.0255, -1.7029, +0.1839, -0.6434, -0.7443, +0.2752, -0.1452], +[ +0.4497, +0.1332, +0.2510, -0.6546, +0.1903, +0.4629, -0.2670, -0.6217, -0.7900, +0.4055, +0.1048, +0.0932, -1.2687, -0.0471, +0.3675, -0.0751, +0.1833, +0.0968, +0.2331, +0.0363, -0.2188, -0.0195, -0.0392, -0.5979, -0.0682, +0.3105, +0.2466, +0.1776, +0.6357, -0.6630, +0.3737, -0.1215, +0.3028, +0.2282, +0.1548, -0.5035, -0.1194, -0.6486, +0.1720, -0.1318, +0.0364, -0.4553, +0.7951, +0.2073, -0.7346, -0.4911, +0.6745, +0.4376, +0.2163, -0.0280, -0.1423, -0.3016, -1.3744, +0.3040, -0.3974, +0.0085, +0.0414, +0.3840, +0.2412, -0.0372, +0.5375, -0.5450, +0.5068, +0.8780, -0.4269, -0.6047, +0.5153, +0.1237, -0.9643, -0.6672, -0.1510, +0.4786, -0.0686, +0.1789, -0.3273, -0.1779, +0.0177, +0.1571, +0.1606, +0.1549, -0.4766, -0.9026, +0.0653, +0.0868, +0.0621, -0.7266, -0.3686, +0.3382, +0.2308, +0.6874, +0.1348, +0.4977, -0.5859, -0.2626, -0.3469, +0.1516, +0.0895, -0.2519, -0.2592, -0.1837, -0.2296, +0.1767, -0.5679, -0.1375, -0.5070, -0.6382, -0.1374, +0.5779, +0.4514, +0.1180, -0.2327, -0.4522, -0.3484, -0.0035, +0.7310, +0.0454, +0.8697, +0.1059, -0.3448, -0.2883, +0.6039, -0.3576, +0.1361, -0.1209, -0.4024, +0.1768, -0.5684, -0.3368], +[ -0.0751, +0.7339, +0.0408, -0.1337, -0.9369, +0.5861, +0.0524, +0.0775, +1.0767, +0.3343, +0.3302, +0.5541, -0.4625, +0.0849, -0.8359, -0.4253, +0.6121, +0.1737, -0.3291, +0.2212, -0.3580, -0.0990, -0.7006, -0.1041, -0.0072, +0.7889, -0.3767, -0.0867, -0.1271, -0.1077, -0.1127, -0.2207, -0.8218, -0.3934, -0.2509, +0.4139, +0.1033, +0.0888, +0.0886, -0.5549, +0.0095, -0.4237, +0.1985, +0.4558, -0.1326, +0.0703, -2.2189, -0.6442, +0.3691, -0.7504, -0.5856, +0.0930, -0.8067, +0.1189, +0.1913, +0.1365, -0.4218, +0.2168, +0.3196, -0.3373, +0.3003, -0.4674, +0.0712, +0.0123, -0.1566, -0.0622, -0.1992, -0.3691, -0.5824, +0.2877, -0.2970, -0.2558, -0.3782, -0.2703, +0.0438, -0.6318, -0.3175, -0.5792, +0.2643, +0.3303, -0.2036, +0.2678, -0.1222, -1.0226, +0.0067, -0.0072, +0.5945, -0.1497, -0.9653, -0.3418, -0.5937, -0.4764, +0.5599, -0.0670, +0.3942, +0.1478, -0.6724, -0.4065, -0.7034, -0.7214, +0.0970, +0.2242, -0.1217, +0.0651, +0.0720, -0.5892, +0.4075, +0.1377, -0.3125, -0.3514, -0.2487, +0.0044, -0.1191, +0.6080, +0.3778, -0.2010, -0.0943, -0.0418, -0.7266, -0.1643, -0.9309, +0.2203, -0.0052, -0.1801, -0.0985, -0.3393, +0.0116, -0.6730], +[ +0.1655, +0.5211, +0.1849, +0.2302, +0.0248, +0.0857, +0.4936, +0.2880, -0.2824, -0.4684, -0.4457, +0.1313, -0.6796, +0.4019, -0.4805, +0.3073, +0.1115, +0.4333, +0.3163, -0.0816, -0.1883, -0.7356, +0.2636, +0.0995, -0.4038, -0.1299, +0.0056, -0.2588, -1.1740, -0.0212, +0.1199, -0.0595, -0.1753, -0.2451, -0.5145, +0.6284, +0.4209, +0.2919, -0.3954, +0.1508, -0.6492, +0.3991, -0.2702, +0.1863, -0.3409, -0.2513, +0.2952, -0.5227, +0.2080, -0.6887, -0.1140, -0.0634, +0.1080, -0.0947, +0.0752, -0.1845, -0.0627, +0.1679, +0.6477, +0.5071, +0.1089, -0.4251, -0.5890, -0.2697, -0.4606, +0.1704, -0.2831, -0.7625, -0.6498, +0.1262, -0.0748, +0.1890, +0.4346, -0.2856, +0.1777, +0.2118, -0.1639, +0.0903, +0.2122, +0.0529, -0.0736, +0.5409, -0.1846, -0.2421, +0.4487, +0.2775, +0.5984, -0.2293, -0.7922, +0.2889, -0.0407, -0.8344, -0.1089, +0.3043, -0.0466, -0.1661, -0.5346, +0.6690, -0.3531, -0.5414, +0.4480, +0.4577, +0.0423, +0.3368, -1.8731, +0.0042, +0.0487, -0.2900, +0.0695, -0.9501, -0.4540, +0.2717, +0.3854, -0.0282, -0.1735, +0.0998, +0.0670, -0.3067, +0.2340, -0.1544, +0.2871, -0.1017, -0.2588, +0.0652, +0.0129, -0.2747, +0.4155, +0.3013], +[ +0.2223, -0.9679, +0.0401, +0.2288, +0.2322, -0.5094, +0.1492, -0.6846, -1.2302, -1.1388, -0.6790, +0.4103, -0.6791, +0.1317, -0.0930, -0.3675, +0.0592, -0.1658, -0.6330, +0.3715, +0.4643, +0.1644, -0.1344, +0.4981, +0.1944, -0.8210, +0.0189, -1.2005, -0.4496, -0.0847, -0.0119, +0.5595, -0.3832, -0.4543, -0.2933, -0.1109, +0.0720, -0.0590, -0.2404, +0.0776, +0.5052, -0.0757, -0.0339, -1.3568, -0.4457, -0.1594, -0.9628, -0.2158, -0.3825, +0.3444, +0.0402, -0.2147, -0.2908, -0.3348, -0.1453, -0.3531, +0.2931, +0.1324, +0.0639, +0.3645, +0.2742, -0.4940, +0.0532, -0.1737, -0.0905, -0.3756, +0.1394, +0.4191, +0.3998, -0.4623, -0.7704, +0.3675, +0.3252, -0.6931, -0.4788, -0.1673, -0.8348, -0.3218, -0.0130, -0.3295, +0.2809, -0.2567, -0.1624, -0.4012, +0.4326, -0.3862, -0.6991, +0.1055, +0.7961, +0.0076, -0.2748, -0.3902, +0.2232, +0.1281, -0.3812, +0.3097, -0.4672, -0.3840, -0.6258, +0.5342, +0.2299, -0.6102, -0.1629, +0.4811, +0.4830, +0.4507, +0.2669, -0.6992, +0.2315, +0.2384, +0.2729, +1.0647, -0.2825, -0.3955, -0.0508, -0.4677, +0.1125, +0.2005, -2.1221, -0.4147, +0.7121, +0.0425, +0.1868, +0.1919, +0.2679, -0.3342, -0.0763, +0.1073], +[ -0.0654, -0.1073, -0.5421, -0.2829, +0.6467, +0.2590, -0.3870, -0.8888, -0.1084, +0.5274, +0.1781, -0.0704, -0.4214, +0.2349, +0.2373, -0.5531, -0.2668, -0.6312, -0.2647, +0.0704, -0.4293, -0.7401, +0.3813, +0.1831, +0.1679, -0.4934, -0.0593, -0.3502, -0.2770, -0.0854, +0.0259, -0.1256, -0.5697, -0.1773, -0.3519, +0.4235, -0.0044, +0.5315, +0.2296, +0.3223, -0.2340, +0.3053, -0.5114, +0.1810, +0.1124, +0.3993, +0.4845, +0.2141, -0.3139, -0.0677, +0.3592, +0.1048, -1.2924, -1.0374, +0.8679, +0.5891, +0.3809, -0.3269, +0.0119, -0.1475, -0.0078, +0.1639, +0.4512, -1.1933, -0.1273, -0.2329, +0.1390, +0.0104, -0.0103, +0.2769, +0.0931, -0.2808, +0.2999, -0.0588, -0.3744, -0.3424, -0.2338, -0.2979, -0.3278, +0.3907, +0.2448, +0.0403, +0.1301, +0.0081, -0.6344, -0.4866, -0.1352, -0.8317, -0.6158, +0.5084, -0.7984, +0.3205, +0.1955, -0.3610, +0.1183, +0.1329, -0.3594, +0.3290, -1.1694, -0.2003, +0.0781, -0.0032, +0.4619, -0.1056, -0.7916, -0.5779, +0.6348, -0.0596, +0.4251, -0.5653, -0.1052, +0.1622, -0.4602, -0.6598, +0.1516, +0.2682, +0.4577, +0.1530, -0.2461, +0.0172, -1.3133, -0.0957, -0.1072, -1.1757, +0.2277, +0.2722, -0.0490, +0.1136], +[ -0.2706, -1.2512, +0.2696, -1.0084, +0.3117, -0.5319, -0.3465, -0.0488, +1.0287, +0.1097, -0.3625, -0.0389, -0.2479, -0.3738, +0.3461, -1.6060, +0.2601, -0.4393, -0.7228, -0.2388, +0.2520, -0.0927, -0.0280, -0.1029, +0.3711, -0.3085, +0.0205, -0.1936, -0.9044, -0.0753, -0.4208, -1.5043, +0.0190, -0.2815, -0.1377, -0.6180, -0.1372, -0.1862, -1.2507, +0.0372, +0.3842, -0.6174, +0.4050, +0.6584, -0.4990, -0.1768, -0.1160, -0.8179, -0.2810, -1.1368, -0.0725, +0.2794, -1.3444, -0.7596, -0.7320, +0.0897, +0.4123, +0.5142, -0.0750, +0.1239, +0.1268, +0.1203, +0.4617, +0.0976, +0.1864, -0.0440, +0.0886, +0.1883, -0.5202, +0.3451, -0.3070, +0.2383, -0.0104, +0.2111, +0.3925, -0.7099, +0.3812, +0.3015, +0.1315, -1.3199, +0.4941, +0.1706, -0.2051, -0.8561, +0.1534, -0.1699, +0.0855, -0.2844, +0.1083, -0.0424, -0.8068, +0.3341, +0.2707, -0.7211, -0.5140, +0.1177, +0.1067, +0.2696, -0.7588, +0.5373, -0.0774, +0.0413, -0.2777, -0.1816, +0.0809, -0.3440, -0.0609, +0.1262, -0.7086, +0.0860, -0.6973, +0.0434, -0.0279, -0.7123, -0.2715, +0.0866, -1.0773, -0.6588, -0.5664, -0.0048, +0.1432, -0.4712, +0.9000, -0.7647, +0.3333, -0.4572, -0.0580, -0.3291], +[ -0.1489, +0.5402, +0.6031, -0.2599, +0.3752, +0.4728, +0.1931, +0.0208, +0.1361, -0.7378, -0.7793, -0.4287, -0.3272, -0.2295, +0.1028, +0.1304, -1.4411, -0.3225, -0.1984, -0.0057, +0.3592, -0.0134, +0.3944, -0.0920, +0.3960, +0.0392, -0.5262, +0.3807, -0.6193, -0.8345, -0.7070, -0.1297, -0.0611, +0.0396, +0.0453, +0.6339, +0.5192, +0.4388, +0.4164, -0.2803, +0.1011, -0.2051, -0.0662, +0.1686, -0.0033, -0.2948, +0.4392, +0.3964, +0.0259, +0.1745, -0.0610, +0.0383, -0.4387, -0.7948, +0.0140, -0.3424, +0.6568, -0.3117, -0.8600, +0.0046, -0.7629, -0.2124, -0.1618, -0.0903, -0.0160, -0.1507, -0.3717, +0.4397, -0.5954, +0.0672, +0.0663, -0.1411, -0.1637, +0.6175, -0.1576, -0.3223, -0.1278, -0.3660, +0.1637, +0.7346, +0.4341, +0.3055, +0.1026, +0.0186, +0.0550, +0.2911, -1.2892, -1.2114, -0.1807, -0.0828, -0.2480, -0.2462, -0.2581, -0.7757, +0.2902, +0.0266, -0.2626, -1.7307, -0.3781, -0.1001, +0.3482, -0.8434, +0.2130, +0.0520, -1.4175, +0.1837, -0.2961, -1.0314, -0.7599, +0.3381, +0.6051, +0.5653, +0.0906, -0.1182, -0.0302, -0.3867, -1.0201, -0.2550, -0.3505, +0.4122, -0.0611, -0.1809, -1.3066, -0.4740, +0.0075, -0.2133, +0.0619, -0.1811], +[ +0.4725, -0.6903, +0.1069, -0.2764, -0.4829, +0.1424, -0.4064, -0.7198, +0.0647, -0.1901, +0.5348, -0.2738, -0.2990, -0.3179, -0.0097, -1.5312, +0.5687, +0.1389, -0.4395, -0.3930, +0.5095, -0.1703, -0.1827, +0.0805, +0.4156, +0.3704, -0.1195, -0.1711, +0.2741, +0.3656, -0.2913, -0.8413, +0.1128, -0.0996, +0.5234, +0.1482, +0.4244, -0.4038, -0.2496, -0.0959, +0.0538, -0.4928, -0.3236, -0.3246, +0.2523, +0.0080, +0.1540, -0.5401, -0.4358, +0.5393, -0.7050, +0.5095, -0.1597, -0.6963, -0.5342, -0.4408, +1.3109, -0.1664, -0.3779, -0.9932, +0.2030, +0.9412, -0.3152, +0.1530, +0.2447, -0.4332, -0.1578, -0.9264, -1.2485, +0.1622, +0.5076, -0.6892, -0.0615, +0.1607, -1.5503, +0.0253, +0.6621, +0.5765, -0.7294, -0.3851, -0.2190, -0.7339, -0.7382, -0.1852, +0.1626, -1.1072, -0.3674, -0.7856, -0.0389, -0.0732, -1.1486, -0.4915, +0.3573, -0.0292, +0.4741, +0.2513, +0.5534, +0.3612, -0.8750, -0.8013, +0.4614, -1.1983, -0.0763, +0.5898, +0.5711, +0.2504, -0.4979, +0.0021, -0.4765, +0.0824, -0.1976, -0.4295, +0.3984, -1.3600, -0.1005, -0.4039, +0.1267, +0.2414, -0.3044, -0.9220, -0.8115, +0.2719, +0.0273, +0.2470, -0.3792, -0.3335, +0.0905, +0.5115], +[ +0.2076, +0.0608, +0.1159, -0.2067, -0.4900, -0.1953, -0.1437, +0.4170, -0.0335, -0.0583, +0.0487, -0.3439, -0.5721, +0.3095, +0.1239, +0.1339, +0.3199, +0.2520, -0.8602, -0.1184, +0.3002, +0.1484, -0.0931, -0.2876, -0.4837, -0.2327, -0.3427, -0.1833, -0.2469, +0.2013, +0.3121, +0.2055, +0.2293, -0.5355, +0.1646, -0.0459, +0.1082, -0.1895, -0.2310, -1.0031, +0.2505, -0.0454, -0.3693, -0.1980, +0.6906, -0.0510, -0.2170, +0.3851, +0.3530, -0.2247, -0.1184, -0.1441, +0.6583, +0.1746, +0.1381, +0.3182, +0.1797, +0.4545, -0.3327, +0.3556, -0.4037, -0.6595, +0.2673, -0.0412, +0.4172, +0.3935, -0.0065, +0.0560, +0.2428, +0.3260, -0.6168, -0.0381, -0.6579, -0.2867, -0.1551, +0.3825, -1.0231, -0.0084, +0.1505, -0.2083, -0.3050, +0.3750, -0.3108, -0.4509, -0.0301, +0.2131, -0.3729, +0.3262, -0.0628, -0.2456, -0.1833, -0.1106, +0.2168, -0.3768, +0.2713, +0.5294, -0.2034, +0.0242, -0.6079, -0.1576, +0.2150, +0.2100, +0.4975, +0.1428, -0.1845, +0.3099, +0.2005, +0.0964, -0.2774, -0.1429, -0.2301, -0.0242, +0.3992, -0.2053, +0.1651, -0.0676, -0.0708, -0.1506, -0.5444, +0.2067, -0.1700, -0.2707, -0.1692, +0.1861, -0.0041, -0.0532, +0.0183, +0.2384], +[ -0.6375, +0.3651, +0.2436, +0.1752, -0.1460, -0.0626, +0.4601, +0.0446, -0.1151, +0.3228, -0.1859, +0.1703, +0.2150, +0.0290, -0.0694, +1.0209, +0.8811, +0.0272, -0.0669, +0.1925, +0.0989, -0.8075, +0.1572, -0.3682, -0.0514, -0.0063, +0.2538, -0.4736, -0.7416, -0.1268, +0.4847, -0.3042, -0.3548, -0.4044, +0.0744, -0.0751, -0.0986, +0.1080, +0.1435, -0.8579, +0.0235, -0.4297, +0.2014, -0.0363, +0.1568, -0.1170, +0.3229, +0.4236, +0.2343, -0.0142, +0.1517, +0.3264, -0.2739, -0.1967, -0.8886, -0.0304, +0.4113, +0.2752, -0.2778, -0.3894, -0.3228, -0.1496, +0.3176, -0.0606, +0.6366, +0.0869, -0.4706, -0.0623, +0.4748, -0.4167, -0.2650, -0.1523, -0.0372, -0.5838, -0.3944, -0.1141, -0.2120, -0.1428, -0.8031, +0.7924, +0.0753, +0.2618, -0.6083, +0.0661, +0.0275, +0.0300, +0.2161, +0.7156, +0.1853, +0.0142, +0.7981, +0.1379, -0.1876, +0.3035, +0.0018, +1.0314, +0.0758, -0.1061, +0.1913, -0.1958, -0.0590, -0.5442, +0.6021, +0.3196, +0.2609, +0.1737, -0.0722, -0.2525, -0.4437, -0.0467, +0.2741, -0.0649, -0.1994, -0.2601, -1.0840, -0.0605, +0.2686, -0.1046, +0.4438, -0.5226, +0.1733, -0.4228, -0.5853, +0.3934, -0.0476, -0.3616, -0.2780, -0.1258], +[ +0.6867, +0.4724, +0.3292, -1.1454, -0.2058, +0.4164, +0.2246, +0.0381, -0.5152, +0.8548, +0.4807, +0.2806, -0.2856, -0.3538, +0.2281, +0.9878, -0.2247, +0.6616, -0.1019, +0.3186, -0.6905, +0.0708, +0.5357, -0.1032, -0.7422, -1.2644, -0.4052, +0.6192, -0.1329, -0.2649, +0.5382, +0.4912, -1.2289, +0.0261, -0.3315, +0.0534, -0.5083, -0.1222, +0.4136, -0.4186, -0.6623, +0.0077, -0.1184, -0.6798, -0.4292, -1.3118, +0.0811, -0.0773, +0.3190, -0.6695, +0.5506, +0.6003, -0.5128, -0.4308, -0.2475, +0.8333, -0.7603, +0.1938, +0.3206, +0.1851, -0.0911, -0.2287, +0.6717, -0.0226, -0.6560, -0.3719, -0.4950, +0.2135, +0.1312, -0.1219, +0.2059, +0.4192, +0.5512, +0.4458, +0.0162, -0.1117, +0.2476, +0.3416, +0.1183, +0.1549, -0.2135, -0.6936, +0.3073, +0.3932, -0.3390, +0.8693, +0.3992, +0.5370, +0.5329, +0.6200, +0.2953, +0.0928, +0.3588, -1.3759, +0.1482, -0.0664, +0.3160, +0.4801, +0.4890, +0.3038, -0.6116, +0.1161, -0.3446, -0.3424, -0.1681, +0.1677, -0.6294, -0.9320, -0.4076, +0.2937, +0.6234, +0.0829, -0.8659, -0.2892, -0.2668, -0.7057, +0.5845, +0.2654, -0.6165, +0.0247, -0.2863, +1.0240, +0.0559, -0.2702, +0.2465, -0.3120, -0.4070, +0.0242] +]) + +weights_dense2_b = np.array([ +0.0589, +0.2417, -0.0986, +0.1092, +0.0381, +0.2114, +0.2297, +0.1468, -0.1559, -0.1759, +0.0344, +0.3008, +0.3244, +0.3597, +0.1691, +0.0277, +0.0064, +0.2372, +0.0961, +0.3293, +0.2077, +0.1230, +0.1195, +0.4294, +0.2816, +0.1169, +0.4083, +0.0309, +0.0433, +0.4852, +0.1903, +0.1055, +0.2894, +0.0468, +0.0669, +0.1655, -0.0712, +0.2791, +0.3653, +0.1661, +0.0730, +0.4481, +0.2336, +0.4547, +0.3048, +0.3674, +0.1072, +0.2519, +0.0875, +0.1864, +0.0793, +0.1467, +0.1665, -0.0635, +0.2464, +0.2529, +0.2301, +0.3551, +0.1974, +0.5505, +0.1776, +0.0702, -0.0460, +0.1697, -0.0007, +0.0430, +0.2190, +0.3566, +0.2163, +0.2470, +0.1928, -0.0373, +0.3103, +0.1705, +0.0386, +0.1008, +0.0483, -0.0530, +0.0899, +0.1354, +0.2905, +0.0686, +0.2512, +0.4373, +0.2106, +0.2685, +0.2320, +0.0750, +0.4447, +0.2390, -0.0136, +0.0224, +0.1565, -0.0579, -0.0142, +0.0710, +0.2252, +0.1527, +0.3315, +0.1419, +0.3483, +0.3999, +0.2818, +0.1021, +0.2659, +0.2742, +0.0814, +0.0849, -0.0068, +0.1339, +0.1216, +0.0148, +0.0219, -0.0728, +0.2957, +0.0854, +0.0055, -0.0289, +0.0866, +0.0203, +0.0353, +0.2069, +0.3297, +0.1171, +0.0607, +0.1667, +0.5721, -0.0218]) + +weights_final_w = np.array([ +[ +0.1312, +0.2606, +0.0873, -0.2167, -0.0211, -0.2425, -0.2365, +0.0256, -0.0525, -0.1167, +0.0605, +0.1389, -0.0801, -0.2973, +0.1066, +0.0129, +0.0549], +[ +0.0107, +0.1381, +0.0126, -0.0227, +0.0100, -0.1605, -0.4347, -0.2622, -0.3952, +0.1417, -0.0394, -0.0345, -0.1321, +0.0973, +0.0614, -0.1857, +0.0101], +[ +0.0489, +0.0031, -0.2181, +0.2105, +0.2968, -0.2446, +0.0639, -0.2621, -0.0567, +0.0232, +0.1381, +0.2903, -0.1861, -0.4347, +0.5889, +0.1608, +0.3169], +[ +0.2935, +0.0971, -0.1493, +0.0123, -0.3232, +0.1984, -0.1904, +0.0674, -0.1251, -0.1421, -0.2297, +0.1642, +0.4883, +0.1015, +0.0046, -0.1664, -0.1933], +[ +0.0655, -0.0136, +0.1110, -0.0768, +0.0236, -0.0335, +0.2260, -0.4519, -0.0795, -0.3457, +0.0667, -0.3201, +0.3744, -0.0273, +0.2743, +0.0971, -0.1144], +[ -0.3984, +0.0525, -0.0927, -0.1104, +0.0242, +0.2294, -0.0730, -0.2585, -0.1027, -0.1138, -0.0855, +0.2366, -0.1895, -0.1304, -0.4098, +0.2590, -0.0564], +[ -0.0326, +0.0244, +0.3413, +0.2870, +0.1252, -0.0921, +0.4718, +0.1316, -0.0767, -0.1213, -0.0975, +0.0160, -0.0676, +0.0719, +0.3433, +0.1957, +0.2411], +[ +0.1805, -0.0909, +0.1841, +0.0092, +0.0334, -0.0274, -0.1892, -0.1136, -0.1936, -0.0776, +0.0088, -0.5994, -0.0894, +0.0054, +0.0222, -0.5486, +0.0794], +[ +0.1231, -0.1501, +0.1568, -0.0432, +0.2135, -0.0308, -0.1665, +0.1327, -0.0055, +0.0054, -0.2374, -0.1399, +0.5330, +0.3818, +0.0111, +0.3729, -0.3116], +[ +0.0443, +0.0425, -0.2333, -0.0758, +0.0445, -0.0364, -0.1385, +0.4477, +0.2164, +0.0454, -0.1320, -0.3380, +0.5406, +0.0488, -0.2379, +0.1216, -0.0559], +[ -0.4501, +0.1921, +0.0992, -0.2644, +0.0216, -0.0723, +0.0213, -0.1043, -0.0775, +0.2790, -0.2341, +0.0725, +0.0472, -0.0021, -0.1217, -0.1285, -0.2625], +[ -0.0878, -0.1506, -0.2460, +0.1033, -0.0043, -0.1535, -0.0529, +0.1674, +0.0078, +0.3391, +0.8355, +0.0874, -0.0233, +0.1923, +0.0359, +0.1081, +0.1508], +[ -0.3796, +0.0832, -0.2270, +0.1005, -0.1703, +0.0832, +0.0064, +0.1643, +0.0637, -0.1930, +0.0365, -0.0470, +0.1059, -0.1114, +0.1208, -0.3628, +0.2056], +[ +0.2360, +0.0879, -0.1799, -0.0360, +0.1466, -0.3555, +0.0957, -0.0095, +0.2665, +0.5403, -0.5690, -0.0800, -0.3047, +0.1044, +0.0053, -0.0098, -0.2020], +[ -0.1021, -0.0576, +0.5277, +0.3862, -0.2923, -0.1565, +0.3422, +0.2636, +0.1655, +0.1700, +0.1921, -0.6448, -0.2882, +0.2176, -0.2975, +0.4688, +0.0548], +[ +0.1350, -0.0520, -0.0243, -0.1268, +0.2160, +0.0838, -0.2554, +0.1928, -0.0042, -0.0117, +0.3009, -0.3786, -0.3108, -0.0581, +0.2374, +0.2102, +0.0998], +[ +0.1258, +0.1091, +0.3406, +0.3366, +0.2269, -0.1391, -0.1218, +0.1913, -0.0044, +0.1850, +0.2097, -0.2372, -0.2832, -0.0987, +0.1170, +0.0516, -0.1875], +[ -0.0902, +0.2603, +0.3307, +0.1615, -0.0565, -0.3079, +0.0315, +0.0874, +0.0755, +0.7551, -0.1873, +0.2390, -0.1559, +0.0447, -0.0154, +0.0343, +0.1431], +[ -0.1310, -0.0000, +0.1157, -0.4601, -0.2381, +0.1276, -0.1355, +0.0909, -0.2596, +0.4611, +0.5581, +0.1119, -0.2449, -0.1039, +0.1356, -0.1378, +0.1854], +[ -0.2234, +0.1488, -0.0868, -0.0221, -0.2624, +0.5707, -0.4488, -0.0552, +0.1251, +0.0740, +0.0574, +0.3261, +0.0011, -0.0559, +0.0850, +0.1478, -0.0575], +[ -0.1547, -0.2551, -0.2269, -0.0155, +0.2671, +0.2239, +0.0401, -0.0152, -0.2506, -0.0510, -0.0408, -0.1499, -0.3132, -0.0916, +0.0558, -0.1317, -0.1131], +[ -0.3986, +0.0452, +0.0059, +0.0143, +0.3271, -0.2273, -0.1940, +0.1802, -0.0765, -0.3095, +0.0365, +0.0157, +0.1850, -0.2821, +0.0505, -0.0141, +0.0334], +[ -0.1405, -0.1715, +0.2472, +0.0586, +0.2633, +0.0251, +0.0151, +0.5158, -0.0045, -0.0354, +0.3007, +0.3528, +0.1331, -0.0457, -0.1532, +0.1718, -0.0002], +[ -0.2526, +0.0306, -0.2338, +0.0557, -0.0416, -0.2174, +0.2027, +0.1293, +0.0471, -0.4165, -0.0245, +0.0312, -0.2050, +0.2281, +0.0194, -0.0756, -0.1017], +[ +0.2395, -0.0035, -0.0206, +0.2011, -0.0853, +0.1665, -0.2279, -0.2057, +0.0230, -0.2693, -0.0173, -0.0095, +0.1317, -0.1597, +0.3547, +0.0186, +0.1017], +[ -0.1807, +0.0229, +0.1314, -0.0384, +0.1618, +0.1776, +0.2824, +0.1815, -0.0702, +0.1897, +0.1154, -0.1015, +0.3698, +0.0610, +0.2967, -0.1962, +0.0017], +[ -0.0074, +0.2953, -0.2820, +0.1022, +0.3167, +0.4200, -0.0643, +0.1692, +0.1454, -0.4422, -0.0188, +0.0325, -0.0591, +0.0319, +0.0870, -0.1527, -0.1347], +[ -0.2557, +0.0643, -0.0250, -0.0358, -0.2493, -0.1554, +0.1479, +0.2026, -0.3371, -0.1351, +0.1498, +0.0373, +0.4199, +0.0188, -0.2702, +0.0521, +0.0950], +[ +0.1081, -0.4271, +0.0690, -0.3374, -0.0935, -0.1386, -0.0240, -0.0407, +0.4000, +0.1332, -0.2086, +0.7726, +0.0442, +0.0718, -0.2187, -0.1867, -0.0762], +[ -0.2350, -0.1500, +0.1550, +0.1218, +0.0389, +0.1064, -0.0495, +0.1717, -0.0759, -0.2376, -0.2130, -0.0091, -0.0250, -0.2824, +0.0911, -0.1364, -0.1061], +[ -0.1212, +0.4204, -0.0501, +0.0208, -0.2520, +0.2076, +0.0444, +0.1458, -0.0982, -0.0022, +0.2173, +0.2447, -0.0222, -0.0018, -0.0566, +0.2430, -0.0905], +[ +0.1643, -0.2400, -0.1019, -0.1235, +0.2953, +0.1080, -0.0416, +0.0763, -0.1258, -0.1884, -0.3330, +0.2187, -0.2763, -0.1867, -0.2056, -0.2271, +0.1966], +[ -0.4632, +0.1782, +0.2223, -0.3054, -0.0924, -0.2057, +0.0089, +0.2455, +0.3828, +0.1087, -0.1154, +0.0237, -0.3203, -0.0789, +0.0756, +0.1260, +0.0117], +[ -0.0527, -0.1818, +0.0755, +0.0768, -0.0594, +0.1384, +0.0534, -0.5923, +0.4133, +0.1154, -0.2839, -0.0294, +0.0174, +0.1350, +0.1564, +0.1622, -0.0221], +[ -0.1845, -0.0040, +0.0629, +0.0127, +0.2480, +0.3868, -0.1440, +0.2099, +0.0125, -0.1419, -0.0316, -0.1121, -0.1147, +0.1579, -0.1398, -0.3699, -0.2407], +[ -0.3024, -0.4112, +0.3517, -0.1744, +0.0442, +0.1175, +0.1120, +0.0313, -0.1000, -0.1217, -0.3270, +0.1557, +0.0458, +0.0634, +0.1686, +0.0292, +0.0342], +[ +0.0055, +0.0122, +0.0775, +0.0206, -0.2969, +0.1358, -0.2017, -0.0757, -0.3607, -0.2885, -0.3357, +0.0148, -0.0613, -0.3099, -0.2110, +0.4725, -0.0229], +[ -0.0870, +0.2184, -0.0565, +0.1654, -0.1285, +1.1648, +0.5389, -0.2226, -0.2618, -0.4095, -0.3999, -0.1014, +0.0956, +0.1682, +0.0492, +0.2601, +0.0474], +[ -0.2767, +0.0553, +0.0306, +0.0024, -0.0094, +0.1389, -0.1430, +0.0036, +0.4679, +0.1425, -0.2145, -0.0646, +0.0081, -0.0832, -0.1137, -0.0659, +0.1728], +[ -0.3456, +0.2478, -0.0933, -0.2658, +0.0159, +0.0989, -0.1268, -0.1793, -0.2511, -0.1328, -0.2603, -0.1707, +0.1464, +0.2335, -0.1048, -0.3861, +0.3799], +[ +0.0906, -0.2603, +0.1179, +0.1688, -0.2237, -0.0822, +0.0288, +0.2402, +0.0442, +0.1249, -0.2379, +0.0698, -0.0972, -0.0560, -0.1527, +0.0879, -0.0982], +[ +0.1656, -0.1126, -0.3280, -0.1454, -0.1580, -0.2798, +0.0980, +0.1962, +0.0373, -0.3712, +0.6412, -0.0309, +0.0066, +0.0889, -0.0277, -0.3184, +0.1719], +[ -0.3050, +0.1695, -0.2984, +0.3151, -0.1415, +0.0532, +0.0595, +0.2024, +0.1260, +0.1307, -0.0846, -0.0340, +0.0356, +0.2450, -0.0064, +0.3211, +0.1223], +[ +0.2064, +0.0314, -0.7182, -0.0014, +0.4533, -0.0736, -0.4364, +0.1237, +0.1503, +0.1236, -0.0738, +0.2819, +0.2560, -0.1169, +0.1758, -0.4164, +0.0911], +[ +0.1323, +0.0817, -0.0994, -0.3297, +0.0779, -0.0238, +0.1504, +0.0698, +0.1012, +0.1071, -0.5144, -0.1897, -0.1890, -0.0724, -0.0617, -0.0274, +0.2011], +[ -0.0281, -0.2267, -0.3032, +0.2410, +0.0516, -0.2491, -0.3050, -0.1812, +0.2029, +0.3053, +0.4205, -0.2745, -0.0210, -0.0765, -0.0071, -0.1102, -0.1442], +[ +0.0010, -0.0779, +0.3468, +0.4334, +0.1432, +0.1585, -0.1131, -0.0239, -0.0272, -0.0349, +0.0364, +0.2644, -0.3331, +0.1804, -0.5429, -0.2642, +0.2148], +[ -0.1210, +0.6697, -0.0792, -0.2096, -0.0938, +0.1053, -0.3676, +0.1888, +0.0033, +0.0138, -0.1001, +0.0124, -0.4953, -0.2625, +0.4315, +0.1741, +0.0748], +[ +0.3386, -0.0625, +0.2074, -0.0791, +0.4092, -0.1314, +0.0619, +0.0787, -0.0088, +0.0886, -0.1326, +0.4888, -0.1590, -0.0694, +0.3429, -0.1274, +0.0160], +[ -0.0111, -0.2156, +0.1449, +0.2451, +0.1138, +0.0158, -0.5589, -0.2248, -0.1329, -0.4511, +0.1869, -0.0745, -0.3610, +0.1168, +0.1185, +0.3343, -0.0786], +[ -0.1221, -0.4784, -0.2020, -0.1611, -0.0048, +0.1330, -0.3143, +0.0581, -0.0509, -0.4198, +0.2756, +0.1595, +0.3195, +0.0522, -0.0918, +0.1170, -0.0423], +[ +0.1040, +0.0353, -0.3103, +0.0942, +0.0581, +0.0454, -0.1175, -0.0464, +0.0016, +0.3844, +0.4261, -0.2159, +0.0670, -0.0158, -0.1561, +0.2365, -0.1176], +[ -0.1606, -0.4301, +0.0624, -0.4848, +0.0412, -0.3168, -0.0772, -0.0698, -0.2040, +0.3138, -0.2606, -0.0569, +0.1970, +0.1635, +0.1485, -0.0893, -0.0093], +[ -0.0691, +0.7319, -0.1740, +0.1397, +0.0422, +0.1841, +0.0551, -0.1779, +0.0263, +0.2575, -0.1547, -0.0804, -0.0104, +0.1240, +0.0396, +0.5363, -0.0852], +[ -0.0874, +0.0740, -0.2354, +0.0765, +0.2228, -0.2960, -0.2207, -0.1744, -0.0959, +0.2325, -0.5918, +0.0846, -0.0356, +0.0450, -0.2203, +0.1262, -0.1228], +[ -0.3480, +0.1078, +0.0365, +0.4309, -0.1477, +0.0616, -0.0769, -0.0193, +0.0070, -0.1749, +0.2338, +0.0302, +0.2317, +0.0679, +0.0253, +0.2287, -0.0449], +[ -0.0917, -0.1148, -0.5216, +0.5428, +0.0322, -0.0604, -0.1308, +0.1717, +0.2328, +0.1074, +0.0431, -0.3477, -0.1743, -0.0226, +0.3206, +0.1525, +0.0347], +[ +0.1605, +0.0369, +0.2022, +0.0722, -0.2906, +0.3964, +0.7451, +0.0630, +0.0663, -0.0819, +0.0415, +0.1646, -0.1499, -0.1255, +0.1425, -0.1912, -0.0421], +[ +0.0196, +0.0653, -0.1871, -0.3252, -0.4638, +0.4087, -0.2621, -0.7069, +0.1975, -0.3065, +0.2014, -0.0236, -0.0719, +0.2058, -0.0210, -0.1895, -0.0760], +[ +0.1401, +0.2856, -0.0084, -0.4474, -0.1189, +0.1954, +0.1608, -0.1745, -0.4177, -0.3583, -0.2078, +0.0498, -0.1714, -0.0160, -0.0649, -0.1105, +0.1325], +[ +0.0479, +0.2704, -0.0470, +0.3404, -0.1584, -0.0478, -0.0354, -0.0816, +0.3430, +0.1074, +0.2332, -0.0058, -0.2567, -0.0425, +0.1168, -0.3646, -0.0250], +[ +0.4094, -0.5041, +0.2346, -0.1907, +0.2669, -0.2752, -0.1550, -0.1642, +0.3191, -0.0082, +0.0502, -0.2870, -0.1683, -0.0697, -0.3527, +0.3189, +0.1332], +[ -0.2716, -0.0033, -0.2637, +0.0069, -0.2129, +0.2672, +0.0694, -0.0430, +0.0637, -0.0555, -0.3187, +0.2670, -0.0308, +0.1458, +0.2477, -0.2574, +0.0914], +[ +0.2928, -0.0535, -0.0691, -0.0436, +0.0613, -0.0920, -0.1360, +0.5571, +0.0624, +0.0410, -0.1896, +0.4296, +0.0266, +0.2580, -0.2728, +0.0482, +0.0613], +[ +0.0488, +0.2622, +0.1998, +0.2080, +0.1624, +0.2532, -0.2194, +0.4212, -0.2253, +0.1078, -0.1612, +0.0316, -0.1959, +0.0955, +0.1069, +0.2729, +0.0990], +[ +0.2588, +0.0617, -0.0078, -0.3274, +0.1988, +0.0345, -0.0577, +0.0777, +0.1154, +0.7071, -0.0287, +0.1041, +0.2812, -0.0966, +0.1488, +0.1547, -0.0200], +[ +0.1464, +0.1786, +0.1756, -0.0633, -0.1991, +0.0583, +0.3696, -0.0610, -0.2088, +0.6352, -0.2822, -0.0619, +0.0712, +0.0683, +0.0591, -0.1966, +0.0573], +[ -0.0289, +0.5961, +0.2250, +0.1727, -0.1021, +0.0805, -0.6852, -0.1022, +0.4412, -0.1102, -0.0573, +0.0108, +0.4795, -0.1854, +0.1619, -0.3180, +0.0826], +[ -0.1803, +0.0848, -0.1195, +0.2291, +0.0999, +0.1137, -0.2016, +0.5933, -0.0431, +0.0807, -0.1362, -0.2669, -0.2680, +0.0616, +0.3381, -0.1365, -0.0133], +[ -0.0019, +0.1816, -0.2680, +0.0490, -0.1431, -0.0349, +0.1846, +0.1512, -0.1755, +0.2003, -0.2616, -0.1497, +0.0726, -0.0063, -0.2029, -0.3561, -0.1127], +[ -0.0543, -0.0786, -0.1657, +0.3412, +0.2236, -0.0256, +0.1423, -0.2476, -0.0579, -0.0400, +0.3387, +0.1397, +0.0693, -0.0978, -0.0721, +0.0494, -0.1215], +[ +0.3175, -0.0093, -0.0200, -0.1039, +0.1993, -0.2639, +0.2093, -0.2860, -0.0647, +0.0382, -0.1736, +0.1920, +0.0989, -0.0879, +0.3887, +0.1490, -0.2475], +[ +0.1223, -0.0573, -0.1927, +0.0222, -0.2032, -0.1156, +0.1203, +0.1252, +0.3434, -0.0309, +0.1683, -0.0745, -0.2512, -0.0162, -0.2847, +0.0018, +0.2597], +[ -0.2100, -0.0401, +0.3119, +0.0271, +0.0367, -0.2558, +0.3757, +0.2703, -0.1604, -0.1646, -0.0853, -0.1255, +0.1305, +0.0554, -0.0657, +0.3253, -0.2175], +[ -0.1669, -0.1024, +0.3036, +0.1949, -0.4268, +0.2212, +0.2057, -0.1204, +0.0223, -0.0924, +0.0152, -0.2183, +0.0476, -0.0045, -0.1289, +0.0776, +0.1919], +[ -0.1015, +0.1058, +0.3162, +0.2942, +0.2410, +0.1193, +0.1045, -0.1116, -0.0550, +0.0776, -0.2475, +0.2624, +0.0536, -0.0720, +0.1367, -0.1158, +0.1027], +[ -0.3849, +0.3457, +0.0135, +0.0063, +0.2045, -0.0144, -0.0950, +0.1271, +0.4600, -0.0311, +0.1044, -0.2487, +0.1230, +0.0327, -0.3978, -0.3512, +0.2497], +[ +0.2812, -0.0669, +0.1645, -0.0291, -0.0164, -0.1144, +0.2963, -0.0595, -0.1484, +0.1771, -0.0079, -0.5441, +0.0339, +0.3036, -0.2279, +0.1066, -0.2468], +[ -0.0718, +0.5449, -0.0494, +0.1283, +0.2544, +0.1221, +0.0988, +0.0028, +0.0135, +0.0904, +0.1348, +0.1037, -0.0058, +0.0007, -0.0455, +0.1696, +0.1674], +[ -0.2138, -0.3133, -0.3800, +0.0846, -0.0372, -0.2185, +0.0951, +0.2048, +0.1555, +0.1266, +0.0414, +0.2256, +0.0326, -0.0332, -0.0807, -0.3547, +0.2416], +[ -0.0868, -0.0794, -0.2556, -0.3129, +0.0309, +0.1684, +0.3753, +0.1522, +0.2974, -0.2167, +0.0158, +0.2495, +0.0596, -0.1184, +0.0521, +0.2815, +0.1270], +[ +0.0900, -0.1678, -0.0648, -0.0243, -0.1684, -0.2439, +0.0659, +0.3151, -0.4868, +0.0200, -0.0563, -0.0812, +0.2157, -0.1118, -0.0546, +0.1121, +0.1330], +[ -0.1735, -0.0359, +0.1421, -0.0054, +0.1613, -0.0438, +0.7337, -0.2124, +0.0604, +0.0033, +0.1450, -0.0176, -0.2187, -0.0204, -0.2695, +0.0197, -0.0461], +[ +0.0981, +0.2768, +0.0884, +0.5310, +0.1594, +0.4027, +0.1326, -0.3091, +0.3588, -0.3596, +0.2099, +0.1202, -0.2811, -0.2679, -0.3697, -0.1143, +0.0364], +[ +0.1433, -0.1962, +0.1004, -0.0014, -0.1924, -0.2953, +0.0410, +0.3597, +0.2484, +0.0705, -0.1239, +0.1030, +0.2636, +0.1599, +0.0982, -0.0888, +0.0597], +[ -0.0233, +0.0115, -0.6757, +0.2189, -0.0165, -0.4398, +0.5602, +0.1727, -0.3657, +0.4095, +0.1018, +0.1222, -0.0591, -0.0114, +0.2174, +0.2068, -0.2059], +[ +0.1465, +0.3763, +0.2525, -0.0040, +0.1222, +0.0591, -0.2716, -0.3108, +0.3361, +0.2440, +0.1371, +0.1249, -0.1091, +0.2130, +0.4761, -0.0394, -0.1550], +[ +0.0480, -0.4882, -0.0725, -0.3144, -0.2882, -0.0517, -0.0909, +0.1522, -0.0457, -0.1458, -0.2927, +0.0594, -0.4833, -0.4030, +0.1000, +0.0829, -0.1583], +[ +0.2517, -0.1086, +0.2060, +0.1727, +0.0902, -0.1455, +0.1913, -0.3011, +0.4524, -0.2250, -0.3558, -0.3009, -0.0365, -0.0636, +0.0852, +0.1678, -0.0045], +[ -0.0800, +0.2266, -0.0954, +0.0206, +0.1473, +0.6583, -0.4648, +0.1038, +0.1741, -0.3025, +0.0773, +0.1044, +0.0888, -0.2105, +0.1827, +0.0543, -0.0055], +[ -0.0999, +0.0095, -0.0853, +0.0084, -0.2591, -0.0105, -0.3086, -0.4188, -0.1658, +0.4141, +0.4294, -0.0325, +0.3242, -0.2091, -0.2607, +0.1492, +0.1504], +[ +0.0317, -0.0307, +0.3815, +0.0595, -0.1011, -0.0057, -0.1609, -0.5363, -0.1927, +0.0689, -0.0432, +0.1582, +0.1995, +0.0791, -0.0799, -0.0426, -0.0398], +[ +0.2850, +0.2052, -0.0389, -0.0705, +0.3961, +0.0547, +0.0385, +0.2505, +0.0714, -0.0159, +0.0321, +0.0161, +0.1245, -0.1221, -0.2063, +0.0359, +0.0904], +[ +0.2388, -0.0879, +0.0303, -0.1298, -0.2066, +0.2349, -0.1669, -0.0393, +0.0557, -0.0419, -0.0636, -0.3270, -0.1898, +0.1185, -0.1003, +0.2182, -0.1358], +[ +0.1651, -0.2028, -0.3384, -0.5319, +0.2690, +0.0798, +0.3677, +0.2660, +0.1497, +0.1026, -0.1128, +0.3130, +0.2733, +0.1554, -0.1325, -0.1619, -0.0860], +[ +0.1536, +0.0465, -0.1248, -0.0063, -0.1992, +0.0119, +0.0328, +0.1646, -0.3838, +0.1776, -0.1014, +0.3482, +0.0298, +0.0296, +0.1838, +0.1373, -0.1523], +[ +0.0442, +0.1129, -0.3831, -0.1119, +0.0817, +0.1744, +0.2670, +0.0339, +0.1102, -0.1592, -0.1006, -0.4853, +0.2444, +0.0459, -0.1019, -0.1361, -0.0604], +[ +0.1310, -0.0497, +0.2974, +0.2772, -0.2771, -0.2194, -0.0129, -0.0623, +0.0006, -0.0298, +0.1518, +0.0271, +0.1619, -0.1267, -0.1727, -0.1988, -0.1210], +[ +0.3556, -0.3053, -0.3899, +0.2106, -0.1380, -0.2564, -0.0534, -0.3945, -0.0198, +0.0277, +0.1276, -0.0327, +0.4129, +0.1444, -0.3541, +0.2025, -0.0395], +[ +0.1271, -0.1985, +0.3796, +0.0934, +0.2144, +0.0129, -0.2250, -0.2218, -0.0024, +0.2304, -0.2798, +0.0901, -0.2428, +0.2513, +0.1104, +0.2521, -0.0836], +[ -0.0790, +0.3823, -0.1396, -0.3351, -0.1272, -0.2597, +0.0591, +0.1499, -0.2298, +0.6025, +0.7618, -0.2407, +0.0333, -0.0403, -0.0925, -0.3186, -0.1176], +[ -0.1944, -0.2272, +0.3309, -0.0803, +0.3230, -0.1632, +0.6171, -0.0997, +0.3684, -0.1963, -0.0740, +0.1319, +0.2760, -0.2500, -0.0141, -0.3381, +0.0988], +[ +0.2057, -0.1338, -0.1396, +0.1905, -0.0804, +0.0064, -0.1375, +0.0256, +0.1821, +0.1315, +0.0442, +0.0899, -0.0152, -0.0606, +0.1378, -0.5944, +0.0902], +[ +0.3549, -0.1397, -0.1932, +0.0118, +0.0244, +0.0824, +0.1821, -0.0512, -0.2780, -0.0666, +0.0240, -0.1947, -0.1455, +0.0940, +0.0609, -0.2599, -0.0573], +[ +0.0848, +0.0130, -0.3703, +0.1482, -0.0567, -0.2191, +0.0100, -0.0555, -0.1383, +0.2142, -0.2411, -0.1008, -0.0247, -0.0685, -0.6440, +0.5464, -0.2950], +[ +0.0558, +0.0309, +0.2263, +0.4103, +0.0554, +0.3598, +0.1403, +0.0423, -0.2540, -0.2593, +0.1508, +0.1841, -0.2731, +0.0649, +0.3406, -0.1161, +0.2166], +[ +0.0934, -0.2574, +0.1155, -0.0240, +0.0258, +0.1470, -0.0135, +0.4334, -0.0167, -0.2294, -0.1428, -0.3680, -0.2007, -0.0010, +0.1405, -0.4045, -0.0752], +[ +0.3774, -0.3684, -0.1185, +0.3444, -0.0005, -0.2114, +0.1939, -0.3012, +0.1912, +0.1980, +0.0747, +0.3322, +0.1122, -0.2042, -0.2741, +0.1889, -0.0508], +[ +0.1951, +0.0460, -0.2167, -0.2370, +0.1496, -0.2761, +0.2644, -0.0282, -0.0858, -0.0368, +0.4173, -0.0596, +0.3189, +0.3252, +0.3012, +0.2653, -0.1094], +[ -0.0618, -0.1060, -0.0063, -0.1816, -0.0928, +0.1112, +0.2248, -0.0704, +0.1565, -0.1376, -0.1280, -0.1405, -0.4444, -0.0081, -0.3809, -0.2760, +0.2826], +[ -0.2150, -0.2761, -0.4387, +0.0652, -0.0250, -0.1408, -0.1410, -0.0401, -0.2530, -0.1720, -0.1383, +0.0815, +0.1345, +0.1094, +0.1165, -0.1125, -0.0680], +[ +0.4100, -0.2501, -0.1091, -0.1421, -0.1276, -0.0343, -0.2467, +0.5050, -0.1084, +0.2873, +0.2955, -0.0441, +0.0624, -0.3208, -0.1248, -0.2148, +0.0624], +[ +0.2167, -0.2099, +0.1943, -0.0190, +0.1348, +0.0457, -0.0756, -0.1493, -0.2804, +0.0296, -0.1222, -0.2076, +0.1460, +0.0056, +0.0618, +0.0620, +0.1078], +[ -0.1699, +0.1200, +0.0562, -0.2747, +0.2608, -0.3566, -0.2460, -0.2062, +0.5545, -0.0188, +0.3313, -0.1312, -0.7428, -0.5009, -0.6418, -0.0003, +0.2460], +[ -0.2792, +0.1021, -0.2467, -0.0577, -0.1567, +0.0156, +0.0434, -0.2623, +0.0924, +0.0685, +0.2042, +0.0532, +0.1473, -0.1451, -0.0592, -0.1645, +0.1258], +[ +0.0919, -0.0480, +0.3094, +0.1917, +0.0822, +0.0892, +0.0365, -0.0325, +0.1961, -0.2383, -0.0073, +0.0189, +0.2700, +0.2116, -0.2724, -0.1682, -0.1288], +[ +0.1483, +0.0807, +0.2281, -0.3101, -0.0014, +0.0484, -0.2612, -0.0005, +0.0087, -0.1544, +0.1201, +0.1475, -0.1714, +0.0190, -0.2971, -0.1113, -0.4718], +[ -0.1700, -0.1545, +0.2127, -0.1944, +0.3472, +0.2332, +0.2231, +0.0469, +0.2023, -0.0298, -0.0297, +0.0597, -0.3039, +0.0959, +0.2502, +0.2281, -0.0078], +[ +0.3397, +0.2010, +0.6118, +0.2780, -0.0135, +0.4304, -0.2720, -0.6300, +0.3764, +0.1227, -0.0925, +0.1188, -0.5911, +0.1235, -0.1578, -0.4889, -0.1543], +[ +0.4581, +0.2872, +0.1375, +0.2818, +0.2036, -0.0369, +0.0807, -0.0667, -0.2801, -0.0582, +0.1936, +0.1047, -0.1245, -0.1259, -0.1373, -0.1140, +0.0582], +[ +0.2535, +0.5913, +0.2155, -0.0587, -0.0918, -0.0362, +0.7135, +0.3591, +0.4240, +0.3692, -0.0313, -0.2431, +0.9143, -0.0241, -0.6210, +0.4646, -0.1512], +[ +0.3188, +0.2507, -0.2129, -0.4617, +0.1874, -0.1286, +0.0632, -0.2470, -0.0572, +0.6183, +0.3531, +0.1321, -0.1687, +0.1307, -0.3712, +0.0199, -0.0776], +[ -0.1779, +0.3660, +0.2386, +0.2297, +0.1792, -0.1369, +0.2320, -0.5867, -0.1306, +0.3471, -0.1127, +0.3352, -0.0214, +0.0801, -0.1368, -0.7262, +0.1757], +[ +0.0183, -0.0485, +0.1199, +0.2513, +0.2022, -0.0472, +0.3076, +0.0656, -0.3302, -0.0587, -0.0200, -0.5474, -0.0863, +0.2087, -0.2581, -0.1750, +0.3391], +[ -0.2339, +0.0639, +0.2085, -0.1872, -0.2686, +0.1490, +0.0436, -0.0841, -0.1054, -0.4899, +0.0193, -0.0250, +0.2212, +0.0972, +0.0329, +0.1328, -0.0545], +[ -0.0874, -0.1087, -0.1577, +0.0936, -0.3083, -0.1450, +0.0365, -0.1924, -0.0536, +0.0475, +0.0348, +0.0772, +0.0348, -0.2800, +0.0864, +0.2640, -0.0215], +[ +0.0745, +0.4503, -0.4064, +0.6300, -0.1275, -0.0463, -0.4074, +0.0031, +0.1408, +0.0531, +0.1400, +0.0308, -0.0220, -0.0014, -0.3056, -0.1551, -0.0096], +[ +0.1479, +0.1186, +0.1323, -0.3466, -0.0654, -0.1084, -0.2509, +0.0944, -0.2135, +0.2020, +0.0602, -0.1239, +0.0741, +0.2037, -0.4462, +0.1065, +0.1710] +]) + +weights_final_b = np.array([ -0.0274, +0.1314, -0.0578, +0.2965, +0.1318, -0.0622, +0.1158, +0.0643, +0.2138, -0.1422, +0.1579, +0.0836, -0.0388, -0.0933, +0.2233, -0.2276, +0.0375]) + +if __name__=="__main__": + demo_run() diff --git a/setup.py b/setup.py index bf36944a9..42ff89b26 100644 --- a/setup.py +++ b/setup.py @@ -417,7 +417,7 @@ else: setup( name = 'pybullet', - version='1.0.1', + version='1.0.2', description='Official Python Interface for the Bullet Physics SDK Robotics Simulator', long_description='pybullet is an easy to use Python module for physics simulation, robotics and machine learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.', url='https://github.com/bulletphysics/bullet3', diff --git a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h index 6488bdd64..f7be7d45b 100644 --- a/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h +++ b/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h @@ -215,10 +215,9 @@ private: */ - - SIMD_FORCE_INLINE unsigned int getHash(unsigned int proxyId1, unsigned int proxyId2) + SIMD_FORCE_INLINE unsigned int getHash(unsigned int proxyId1, unsigned int proxyId2) { - int key = static_cast(((unsigned int)proxyId1) | (((unsigned int)proxyId2) <<16)); + unsigned int key = proxyId1 | (proxyId2 << 16); // Thomas Wang's hash key += ~(key << 15); @@ -227,13 +226,11 @@ private: key ^= (key >> 6); key += ~(key << 11); key ^= (key >> 16); - return static_cast(key); + return key; } - - SIMD_FORCE_INLINE btBroadphasePair* internalFindPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, int hash) { int proxyId1 = proxy0->getUid(); diff --git a/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp b/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp index 93de49998..875d89c53 100644 --- a/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp +++ b/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp @@ -1336,6 +1336,8 @@ const char* btQuantizedBvh::serialize(void* dataBuffer, btSerializer* serializer memPtr->m_escapeIndex = m_contiguousNodes[i].m_escapeIndex; memPtr->m_subPart = m_contiguousNodes[i].m_subPart; memPtr->m_triangleIndex = m_contiguousNodes[i].m_triangleIndex; + // Fill padding with zeros to appease msan. + memset(memPtr->m_pad, 0, sizeof(memPtr->m_pad)); } serializer->finalizeChunk(chunk,"btOptimizedBvhNodeData",BT_ARRAY_CODE,(void*)&m_contiguousNodes[0]); } diff --git a/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp b/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp index fdecac162..b595c56bc 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp @@ -18,9 +18,11 @@ subject to the following restrictions: #include "LinearMath/btSerializer.h" btCollisionObject::btCollisionObject() - : m_anisotropicFriction(1.f,1.f,1.f), - m_hasAnisotropicFriction(false), - m_contactProcessingThreshold(BT_LARGE_FLOAT), + : m_interpolationLinearVelocity(0.f, 0.f, 0.f), + m_interpolationAngularVelocity(0.f, 0.f, 0.f), + m_anisotropicFriction(1.f,1.f,1.f), + m_hasAnisotropicFriction(false), + m_contactProcessingThreshold(BT_LARGE_FLOAT), m_broadphaseHandle(0), m_collisionShape(0), m_extensionPointer(0), @@ -48,6 +50,7 @@ btCollisionObject::btCollisionObject() m_updateRevision(0) { m_worldTransform.setIdentity(); + m_interpolationWorldTransform.setIdentity(); } btCollisionObject::~btCollisionObject() @@ -112,6 +115,9 @@ const char* btCollisionObject::serialize(void* dataBuffer, btSerializer* seriali dataOut->m_ccdMotionThreshold = m_ccdMotionThreshold; dataOut->m_checkCollideWith = m_checkCollideWith; + // Fill padding with zeros to appease msan. + memset(dataOut->m_padding, 0, sizeof(dataOut->m_padding)); + return btCollisionObjectDataName; } diff --git a/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h b/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h index 186964d72..2aaf6201f 100644 --- a/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h +++ b/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h @@ -123,9 +123,9 @@ private: - SIMD_FORCE_INLINE unsigned int getHash(unsigned int indexA, unsigned int indexB) + SIMD_FORCE_INLINE unsigned int getHash(unsigned int indexA, unsigned int indexB) { - int key = static_cast(((unsigned int)indexA) | (((unsigned int)indexB) <<16)); + unsigned int key = indexA | (indexB << 16); // Thomas Wang's hash key += ~(key << 15); @@ -134,7 +134,7 @@ private: key ^= (key >> 6); key += ~(key << 11); key ^= (key >> 16); - return static_cast(key); + return key; } diff --git a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp index 0940da1a4..61f465cb7 100644 --- a/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp +++ b/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp @@ -437,6 +437,9 @@ const char* btBvhTriangleMeshShape::serialize(void* dataBuffer, btSerializer* se trimeshData->m_triangleInfoMap = 0; } + // Fill padding with zeros to appease msan. + memset(trimeshData->m_pad3, 0, sizeof(trimeshData->m_pad3)); + return "btTriangleMeshShapeData"; } diff --git a/src/BulletCollision/CollisionShapes/btCapsuleShape.h b/src/BulletCollision/CollisionShapes/btCapsuleShape.h index aa65d5439..7d64b46ab 100644 --- a/src/BulletCollision/CollisionShapes/btCapsuleShape.h +++ b/src/BulletCollision/CollisionShapes/btCapsuleShape.h @@ -164,11 +164,17 @@ SIMD_FORCE_INLINE int btCapsuleShape::calculateSerializeBufferSize() const SIMD_FORCE_INLINE const char* btCapsuleShape::serialize(void* dataBuffer, btSerializer* serializer) const { btCapsuleShapeData* shapeData = (btCapsuleShapeData*) dataBuffer; - + btConvexInternalShape::serialize(&shapeData->m_convexInternalShapeData,serializer); shapeData->m_upAxis = m_upAxis; - + + // Fill padding with zeros to appease msan. + shapeData->m_padding[0] = 0; + shapeData->m_padding[1] = 0; + shapeData->m_padding[2] = 0; + shapeData->m_padding[3] = 0; + return "btCapsuleShapeData"; } diff --git a/src/BulletCollision/CollisionShapes/btCollisionShape.cpp b/src/BulletCollision/CollisionShapes/btCollisionShape.cpp index 39ee21cad..823e2788f 100644 --- a/src/BulletCollision/CollisionShapes/btCollisionShape.cpp +++ b/src/BulletCollision/CollisionShapes/btCollisionShape.cpp @@ -106,7 +106,10 @@ const char* btCollisionShape::serialize(void* dataBuffer, btSerializer* serializ serializer->serializeName(name); } shapeData->m_shapeType = m_shapeType; - //shapeData->m_padding//?? + + // Fill padding with zeros to appease msan. + memset(shapeData->m_padding, 0, sizeof(shapeData->m_padding)); + return "btCollisionShapeData"; } diff --git a/src/BulletCollision/CollisionShapes/btConeShape.h b/src/BulletCollision/CollisionShapes/btConeShape.h index 46d78d148..3b44e3f27 100644 --- a/src/BulletCollision/CollisionShapes/btConeShape.h +++ b/src/BulletCollision/CollisionShapes/btConeShape.h @@ -168,11 +168,17 @@ SIMD_FORCE_INLINE int btConeShape::calculateSerializeBufferSize() const SIMD_FORCE_INLINE const char* btConeShape::serialize(void* dataBuffer, btSerializer* serializer) const { btConeShapeData* shapeData = (btConeShapeData*) dataBuffer; - + btConvexInternalShape::serialize(&shapeData->m_convexInternalShapeData,serializer); - + shapeData->m_upIndex = m_coneIndices[1]; - + + // Fill padding with zeros to appease msan. + shapeData->m_padding[0] = 0; + shapeData->m_padding[1] = 0; + shapeData->m_padding[2] = 0; + shapeData->m_padding[3] = 0; + return "btConeShapeData"; } diff --git a/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp b/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp index c1aa6ca46..a7a959840 100644 --- a/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp +++ b/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp @@ -211,7 +211,10 @@ const char* btConvexHullShape::serialize(void* dataBuffer, btSerializer* seriali } serializer->finalizeChunk(chunk,btVector3DataName,BT_ARRAY_CODE,(void*)&m_unscaledPoints[0]); } - + + // Fill padding with zeros to appease msan. + memset(shapeData->m_padding3, 0, sizeof(shapeData->m_padding3)); + return "btConvexHullShapeData"; } diff --git a/src/BulletCollision/CollisionShapes/btConvexInternalShape.h b/src/BulletCollision/CollisionShapes/btConvexInternalShape.h index 37e04f5fc..1213b82fb 100644 --- a/src/BulletCollision/CollisionShapes/btConvexInternalShape.h +++ b/src/BulletCollision/CollisionShapes/btConvexInternalShape.h @@ -172,6 +172,9 @@ SIMD_FORCE_INLINE const char* btConvexInternalShape::serialize(void* dataBuffer, m_localScaling.serializeFloat(shapeData->m_localScaling); shapeData->m_collisionMargin = float(m_collisionMargin); + // Fill padding with zeros to appease msan. + shapeData->m_padding = 0; + return "btConvexInternalShapeData"; } diff --git a/src/BulletCollision/CollisionShapes/btCylinderShape.h b/src/BulletCollision/CollisionShapes/btCylinderShape.h index 6f796950e..a214a827c 100644 --- a/src/BulletCollision/CollisionShapes/btCylinderShape.h +++ b/src/BulletCollision/CollisionShapes/btCylinderShape.h @@ -199,11 +199,17 @@ SIMD_FORCE_INLINE int btCylinderShape::calculateSerializeBufferSize() const SIMD_FORCE_INLINE const char* btCylinderShape::serialize(void* dataBuffer, btSerializer* serializer) const { btCylinderShapeData* shapeData = (btCylinderShapeData*) dataBuffer; - + btConvexInternalShape::serialize(&shapeData->m_convexInternalShapeData,serializer); shapeData->m_upAxis = m_upAxis; - + + // Fill padding with zeros to appease msan. + shapeData->m_padding[0] = 0; + shapeData->m_padding[1] = 0; + shapeData->m_padding[2] = 0; + shapeData->m_padding[3] = 0; + return "btCylinderShapeData"; } diff --git a/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp b/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp index 88f6c4dcb..4195fa313 100644 --- a/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp +++ b/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp @@ -175,7 +175,10 @@ const char* btMultiSphereShape::serialize(void* dataBuffer, btSerializer* serial } serializer->finalizeChunk(chunk,"btPositionAndRadius",BT_ARRAY_CODE,(void*)&m_localPositionArray[0]); } - + + // Fill padding with zeros to appease msan. + memset(shapeData->m_padding, 0, sizeof(shapeData->m_padding)); + return "btMultiSphereShapeData"; } diff --git a/src/BulletCollision/CollisionShapes/btStaticPlaneShape.h b/src/BulletCollision/CollisionShapes/btStaticPlaneShape.h index e6e328839..5e9eccc77 100644 --- a/src/BulletCollision/CollisionShapes/btStaticPlaneShape.h +++ b/src/BulletCollision/CollisionShapes/btStaticPlaneShape.h @@ -94,7 +94,13 @@ SIMD_FORCE_INLINE const char* btStaticPlaneShape::serialize(void* dataBuffer, bt m_localScaling.serializeFloat(planeData->m_localScaling); m_planeNormal.serializeFloat(planeData->m_planeNormal); planeData->m_planeConstant = float(m_planeConstant); - + + // Fill padding with zeros to appease msan. + planeData->m_pad[0] = 0; + planeData->m_pad[1] = 0; + planeData->m_pad[2] = 0; + planeData->m_pad[3] = 0; + return "btStaticPlaneShapeData"; } diff --git a/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp b/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp index b3d449676..78ddeb370 100644 --- a/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp +++ b/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp @@ -293,6 +293,9 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s tmpIndices[gfxindex].m_values[0] = tri_indices[0]; tmpIndices[gfxindex].m_values[1] = tri_indices[1]; tmpIndices[gfxindex].m_values[2] = tri_indices[2]; + // Fill padding with zeros to appease msan. + tmpIndices[gfxindex].m_pad[0] = 0; + tmpIndices[gfxindex].m_pad[1] = 0; } serializer->finalizeChunk(chunk,"btShortIntIndexTripletData",BT_ARRAY_CODE,(void*)chunk->m_oldPtr); } @@ -311,6 +314,8 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s tmpIndices[gfxindex].m_values[0] = tri_indices[0]; tmpIndices[gfxindex].m_values[1] = tri_indices[1]; tmpIndices[gfxindex].m_values[2] = tri_indices[2]; + // Fill padding with zeros to appease msan. + tmpIndices[gfxindex].m_pad = 0; } serializer->finalizeChunk(chunk,"btCharIndexTripletData",BT_ARRAY_CODE,(void*)chunk->m_oldPtr); } @@ -375,6 +380,8 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s serializer->finalizeChunk(chunk,"btMeshPartData",BT_ARRAY_CODE,chunk->m_oldPtr); } + // Fill padding with zeros to appease msan. + memset(trimeshData->m_padding, 0, sizeof(trimeshData->m_padding)); m_scaling.serializeFloat(trimeshData->m_scaling); return "btStridingMeshInterfaceData"; diff --git a/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h b/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h index 17deef89d..642758959 100644 --- a/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h +++ b/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h @@ -195,6 +195,13 @@ SIMD_FORCE_INLINE const char* btTriangleInfoMap::serialize(void* dataBuffer, btS serializer->finalizeChunk(chunk,"int",BT_ARRAY_CODE,(void*) &m_keyArray[0]); } + + // Fill padding with zeros to appease msan. + tmapData->m_padding[0] = 0; + tmapData->m_padding[1] = 0; + tmapData->m_padding[2] = 0; + tmapData->m_padding[3] = 0; + return "btTriangleInfoMapData"; } diff --git a/src/BulletDynamics/ConstraintSolver/btGearConstraint.h b/src/BulletDynamics/ConstraintSolver/btGearConstraint.h index f9afcb912..e4613455a 100644 --- a/src/BulletDynamics/ConstraintSolver/btGearConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btGearConstraint.h @@ -141,6 +141,14 @@ SIMD_FORCE_INLINE const char* btGearConstraint::serialize(void* dataBuffer, btSe gear->m_ratio = m_ratio; + // Fill padding with zeros to appease msan. +#ifndef BT_USE_DOUBLE_PRECISION + gear->m_padding[0] = 0; + gear->m_padding[1] = 0; + gear->m_padding[2] = 0; + gear->m_padding[3] = 0; +#endif + return btGearConstraintDataName; } diff --git a/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h b/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h index 57b4e1983..536e5af1b 100644 --- a/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h +++ b/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h @@ -664,6 +664,11 @@ SIMD_FORCE_INLINE const char* btGeneric6DofSpring2Constraint::serialize(void* da dof->m_rotateOrder = m_rotateOrder; + dof->m_padding1[0] = 0; + dof->m_padding1[1] = 0; + dof->m_padding1[2] = 0; + dof->m_padding1[3] = 0; + return btGeneric6DofSpring2ConstraintDataName; } diff --git a/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h b/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h index f26e72105..636aa7fe3 100644 --- a/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h @@ -489,6 +489,14 @@ SIMD_FORCE_INLINE const char* btHingeConstraint::serialize(void* dataBuffer, btS hingeData->m_relaxationFactor = float(m_relaxationFactor); #endif + // Fill padding with zeros to appease msan. +#ifdef BT_USE_DOUBLE_PRECISION + hingeData->m_padding1[0] = 0; + hingeData->m_padding1[1] = 0; + hingeData->m_padding1[2] = 0; + hingeData->m_padding1[3] = 0; +#endif + return btHingeConstraintDataName; } diff --git a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp index 27bb88f2a..fc85b4f86 100644 --- a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp +++ b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp @@ -1511,6 +1511,9 @@ void btDiscreteDynamicsWorld::serializeDynamicsWorldInfo(btSerializer* serialize worldInfo->m_solverInfo.m_splitImpulse = getSolverInfo().m_splitImpulse; + // Fill padding with zeros to appease msan. + memset(worldInfo->m_solverInfo.m_padding, 0, sizeof(worldInfo->m_solverInfo.m_padding)); + #ifdef BT_USE_DOUBLE_PRECISION const char* structType = "btDynamicsWorldDoubleData"; #else//BT_USE_DOUBLE_PRECISION diff --git a/src/BulletDynamics/Dynamics/btRigidBody.cpp b/src/BulletDynamics/Dynamics/btRigidBody.cpp index 9402a658c..ca0714fcf 100644 --- a/src/BulletDynamics/Dynamics/btRigidBody.cpp +++ b/src/BulletDynamics/Dynamics/btRigidBody.cpp @@ -507,6 +507,11 @@ const char* btRigidBody::serialize(void* dataBuffer, class btSerializer* seriali rbd->m_linearSleepingThreshold=m_linearSleepingThreshold; rbd->m_angularSleepingThreshold = m_angularSleepingThreshold; + // Fill padding with zeros to appease msan. +#ifdef BT_USE_DOUBLE_PRECISION + memset(rbd->m_padding, 0, sizeof(rbd->m_padding)); +#endif + return btRigidBodyDataName; } diff --git a/src/BulletDynamics/Featherstone/btMultiBody.cpp b/src/BulletDynamics/Featherstone/btMultiBody.cpp index 6fcca2dd9..ca9652f1e 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -2013,5 +2013,10 @@ const char* btMultiBody::serialize(void* dataBuffer, class btSerializer* seriali } mbd->m_links = mbd->m_numLinks? (btMultiBodyLinkData*) serializer->getUniquePointer((void*)&m_links[0]):0; + // Fill padding with zeros to appease msan. +#ifdef BT_USE_DOUBLE_PRECISION + memset(mbd->m_padding, 0, sizeof(mbd->m_padding)); +#endif + return btMultiBodyDataName; } diff --git a/src/BulletDynamics/Featherstone/btMultiBodyLink.h b/src/BulletDynamics/Featherstone/btMultiBodyLink.h index 2734bf4bd..6cd8c69d3 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyLink.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyLink.h @@ -22,7 +22,8 @@ subject to the following restrictions: enum btMultiBodyLinkFlags { - BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION = 1 + BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION = 1, + BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION = 2, }; //both defines are now permanently enabled diff --git a/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h b/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h index 5080ea874..9a375e3e4 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h @@ -74,15 +74,47 @@ public: if (m_link>=0) { const btMultibodyLink& link = m_multiBody->getLink(this->m_link); - if ((link.m_flags&BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION) && link.m_parent == other->m_link) - return false; + if (link.m_flags&BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION) + { + if ( link.m_parent == other->m_link) + return false; + } + if (link.m_flags&BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION) + { + int parent_of_this = m_link; + while (1) + { + if (parent_of_this==-1) + break; + parent_of_this = m_multiBody->getLink(parent_of_this).m_parent; + if (parent_of_this==other->m_link) + { + return false; + } + } + } } if (other->m_link>=0) { const btMultibodyLink& otherLink = other->m_multiBody->getLink(other->m_link); - if ((otherLink.m_flags& BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION) && otherLink.m_parent == this->m_link) - return false; + if (otherLink.m_flags& BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION) + { + if (otherLink.m_parent == this->m_link) + return false; + } + if (otherLink.m_flags& BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION) + { + int parent_of_other = other->m_link; + while (1) + { + if (parent_of_other==-1) + break; + parent_of_other = m_multiBody->getLink(parent_of_other).m_parent; + if (parent_of_other==this->m_link) + return false; + } + } } return true; } diff --git a/src/LinearMath/btHashMap.h b/src/LinearMath/btHashMap.h index 8f723a646..3e8b75b7d 100644 --- a/src/LinearMath/btHashMap.h +++ b/src/LinearMath/btHashMap.h @@ -105,9 +105,10 @@ public: //to our success SIMD_FORCE_INLINE unsigned int getHash()const { - int key = m_uid; + unsigned int key = m_uid; // Thomas Wang's hash key += ~(key << 15); key ^= (key >> 10); key += (key << 3); key ^= (key >> 6); key += ~(key << 11); key ^= (key >> 16); + return key; } }; @@ -120,7 +121,7 @@ class btHashPtr union { const void* m_pointer; - int m_hashValues[2]; + unsigned int m_hashValues[2]; }; public: @@ -145,8 +146,7 @@ public: { const bool VOID_IS_8 = ((sizeof(void*)==8)); - int key = VOID_IS_8? m_hashValues[0]+m_hashValues[1] : m_hashValues[0]; - + unsigned int key = VOID_IS_8? m_hashValues[0]+m_hashValues[1] : m_hashValues[0]; // Thomas Wang's hash key += ~(key << 15); key ^= (key >> 10); key += (key << 3); key ^= (key >> 6); key += ~(key << 11); key ^= (key >> 16); return key; @@ -179,7 +179,7 @@ public: //to our success SIMD_FORCE_INLINE unsigned int getHash()const { - int key = m_uid; + unsigned int key = m_uid; // Thomas Wang's hash key += ~(key << 15); key ^= (key >> 10); key += (key << 3); key ^= (key >> 6); key += ~(key << 11); key ^= (key >> 16); return key; @@ -211,7 +211,7 @@ public: //to our success SIMD_FORCE_INLINE unsigned int getHash()const { - int key = m_uid; + unsigned int key = m_uid; // Thomas Wang's hash key += ~(key << 15); key ^= (key >> 10); key += (key << 3); key ^= (key >> 6); key += ~(key << 11); key ^= (key >> 16); return key; diff --git a/src/LinearMath/btQuaternion.h b/src/LinearMath/btQuaternion.h index a9b78022e..7bd39e6a3 100644 --- a/src/LinearMath/btQuaternion.h +++ b/src/LinearMath/btQuaternion.h @@ -355,7 +355,15 @@ public: { return btSqrt(length2()); } - + btQuaternion& safeNormalize() + { + btScalar l2 = length2(); + if (l2>SIMD_EPSILON) + { + normalize(); + } + return *this; + } /**@brief Normalize the quaternion * Such that x^2 + y^2 + z^2 +w^2 = 1 */ btQuaternion& normalize() diff --git a/src/LinearMath/btTransformUtil.h b/src/LinearMath/btTransformUtil.h index 2303c2742..182cc43fa 100644 --- a/src/LinearMath/btTransformUtil.h +++ b/src/LinearMath/btTransformUtil.h @@ -47,13 +47,19 @@ public: #ifdef QUATERNION_DERIVATIVE btQuaternion predictedOrn = curTrans.getRotation(); predictedOrn += (angvel * predictedOrn) * (timeStep * btScalar(0.5)); - predictedOrn.normalize(); + predictedOrn.safeNormalize(); #else //Exponential map //google for "Practical Parameterization of Rotations Using the Exponential Map", F. Sebastian Grassia btVector3 axis; - btScalar fAngle = angvel.length(); + btScalar fAngle2 = angvel.length2(); + btScalar fAngle = 0; + if (fAngle2>SIMD_EPSILON) + { + fAngle = btSqrt(fAngle2); + } + //limit the angular motion if (fAngle*timeStep > ANGULAR_MOTION_THRESHOLD) { @@ -74,9 +80,16 @@ public: btQuaternion orn0 = curTrans.getRotation(); btQuaternion predictedOrn = dorn * orn0; - predictedOrn.normalize(); + predictedOrn.safeNormalize(); #endif - predictedTransform.setRotation(predictedOrn); + if (predictedOrn.length2()>SIMD_EPSILON) + { + predictedTransform.setRotation(predictedOrn); + } + else + { + predictedTransform.setBasis(curTrans.getBasis()); + } } static void calculateVelocityQuaternion(const btVector3& pos0,const btVector3& pos1,const btQuaternion& orn0,const btQuaternion& orn1,btScalar timeStep,btVector3& linVel,btVector3& angVel)