diff --git a/examples/Heightfield/HeightfieldExample.cpp b/examples/Heightfield/HeightfieldExample.cpp index 3b1902b07..b93aa8df6 100644 --- a/examples/Heightfield/HeightfieldExample.cpp +++ b/examples/Heightfield/HeightfieldExample.cpp @@ -22,8 +22,8 @@ subject to the following restrictions: #include "../MultiThreadedDemo/CommonRigidBodyMTBase.h" #include "../CommonInterfaces/CommonParameterInterface.h" #include "../OpenGLWindow/GLInstanceGraphicsShape.h" -#include "../../Utils/b3BulletDefaultFileIO.h" -#include "../../Importers/ImportURDFDemo/urdfStringSplit.h" +#include "../Utils/b3BulletDefaultFileIO.h" +#include "../Importers/ImportURDFDemo/urdfStringSplit.h" #include "stb_image/stb_image.h" // constants ------------------------------------------------------------------- @@ -1112,7 +1112,7 @@ void HeightfieldExample::initPhysics() // set up basic state - m_type = PHY_FLOAT;// SHORT; + m_type = PHY_FLOAT; m_model = gHeightfieldType; m_isDynamic = true; @@ -1156,8 +1156,14 @@ void HeightfieldExample::resetPhysics(void) m_upAxis, m_type, flipQuadEdges); btAssert(m_heightfieldShape && "null heightfield"); + // set origin to middle of heightfield + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(0, 0, 0)); + if (m_model== eImageFile) { + tr.setOrigin(btVector3(0, 0, -24)); b3BulletDefaultFileIO fileIO; char relativeFileName[1024]; int found = fileIO.findFile("heightmaps/gimp_overlay_out.png", relativeFileName, 1024); @@ -1206,10 +1212,7 @@ void HeightfieldExample::resetPhysics(void) // stash this shape away m_collisionShapes.push_back(m_heightfieldShape); - // set origin to middle of heightfield - btTransform tr; - tr.setIdentity(); - tr.setOrigin(btVector3(0, 0, 0)); + // create ground object float mass = 0.0; @@ -1249,7 +1252,7 @@ void HeightfieldExample::clearWorld(void) m_collisionShapes.clear(); // delete raw heightfield data - delete m_rawHeightfieldData; + delete[] m_rawHeightfieldData; m_rawHeightfieldData = NULL; } } diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 4edf850b2..77c2fabf3 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -55,6 +55,7 @@ enum UrdfGeomTypes URDF_GEOM_PLANE, URDF_GEOM_CAPSULE, //non-standard URDF URDF_GEOM_CDF, //signed-distance-field, non-standard URDF + URDF_GEOM_HEIGHTFIELD, //heightfield, non-standard URDF URDF_GEOM_UNKNOWN, }; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 5132937d0..2e0b64334 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -14,7 +14,7 @@ #include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h" #include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h" #include "BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h" - +#include "../Utils/b3BulletDefaultFileIO.h" #include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h" @@ -4211,6 +4211,158 @@ bool PhysicsServerCommandProcessor::processSaveWorldCommand(const struct SharedM return hasStatus; } + + + + +#define MYLINELENGTH 16*32768 + +static unsigned char* MyGetRawHeightfieldData(const char* fileName, int& width, int& height) +{ + int s_gridSize = width; + btScalar s_gridSpacing = 0.5; + btScalar s_gridHeightScale = 0.02; + + PHY_ScalarType type = PHY_FLOAT; + if (1)//model == eImageFile) + { + b3BulletDefaultFileIO fileIO; + char relativeFileName[1024]; + int found = fileIO.findFile(fileName, relativeFileName, 1024); + + b3AlignedObjectArray buffer; + buffer.reserve(1024); + int fileId = fileIO.fileOpen(relativeFileName, "rb"); + if (fileId >= 0) + { + int size = fileIO.getFileSize(fileId); + if (size>0) + { + buffer.resize(size); + int actual = fileIO.fileRead(fileId, &buffer[0], size); + if (actual != size) + { + b3Warning("STL filesize mismatch!\n"); + buffer.resize(0); + } + } + fileIO.fileClose(fileId); + } + + if (buffer.size()) + { + int n; + + unsigned char* image = stbi_load_from_memory((const unsigned char*)&buffer[0], buffer.size(), &width, &height, &n, 3); + if (image) + { + + fileIO.fileClose(fileId); + long nElements = ((long)s_gridSize) * s_gridSize; + int bytesPerElement = sizeof(btScalar); + btAssert(bytesPerElement > 0 && "bad bytes per element"); + + long nBytes = nElements * bytesPerElement; + unsigned char * raw = new unsigned char[nBytes]; + btAssert(raw && "out of memory"); + + unsigned char * p = raw; + for (int i = 0; i < width; ++i) + { + float x = i * s_gridSpacing; + for (int j = 0; j < width; ++j) + { + float y = j * s_gridSpacing; + float z = double(image[i * 3 + width*j * 3])*(40. / 256.); + btScalar * pf = (btScalar *)p; + *pf = z; + p += bytesPerElement; + } + } + return raw; + } + } + } +#if 0 + if (model == eCSVFile) + { + { + b3BulletDefaultFileIO fileIO; + char relativePath[1024]; + int found = fileIO.findFile("heightmaps/ground0.txt", relativePath, 1024); + char lineBuffer[MYLINELENGTH]; + int slot = fileIO.fileOpen(relativePath, "r"); + int rows = 0; + int cols = 0; + + btAlignedObjectArray allValues; + if (slot >= 0) + { + char* lineChar; + while (lineChar = fileIO.readLine(slot, lineBuffer, MYLINELENGTH)) + { + rows = 0; + char** values = urdfStrSplit(lineChar, ","); + if (values) + { + int index = 0; + char* value; + while (value = values[index++]) + { + std::string strval(value); + double v; + if (sscanf(value, "%lf", &v) == 1) + { + //printf("strlen = %d\n", strval.length()); + //printf("value[%d,%d]=%s or (%f)", cols,rows,value, v); + allValues.push_back(v); + rows++; + } + } + } + cols++; + + } + printf("done, rows=%d, cols=%d\n", rows, cols); + int width = rows - 1; + s_gridSize = rows; + s_gridSpacing = 0.2; + s_gridHeightScale = 0.2; + fileIO.fileClose(slot); + long nElements = ((long)s_gridSize) * s_gridSize; + // std::cerr << " nElements = " << nElements << "\n"; + + int bytesPerElement = getByteSize(type); + // std::cerr << " bytesPerElement = " << bytesPerElement << "\n"; + btAssert(bytesPerElement > 0 && "bad bytes per element"); + + long nBytes = nElements * bytesPerElement; + // std::cerr << " nBytes = " << nBytes << "\n"; + unsigned char * raw = new unsigned char[nBytes]; + btAssert(raw && "out of memory"); + + byte_t * p = raw; + for (int i = 0; i < width; ++i) + { + float x = i * s_gridSpacing; + for (int j = 0; j < width; ++j) + { + float y = j * s_gridSpacing; + float z = allValues[i + width*j]; + convertFromFloat(p, z, type); + p += bytesPerElement; + } + } + return raw; + } + } + } +#endif + + return 0; +} + + bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) { bool hasStatus = true; @@ -4320,6 +4472,11 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str break; } + case GEOM_HEIGHTFIELD: + { + + break; + } case GEOM_PLANE: { btVector3 planeNormal(clientCmd.m_createUserShapeArgs.m_shapes[i].m_planeNormal[0], diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 56f6657cb..babf06d8f 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -886,6 +886,8 @@ enum eUrdfGeomTypes //sync with UrdfParser UrdfGeomTypes GEOM_MESH, GEOM_PLANE, GEOM_CAPSULE, //non-standard URDF? + GEOM_SDF, //signed-distance-field, non-standard URDF + GEOM_HEIGHTFIELD, GEOM_UNKNOWN, }; diff --git a/examples/pybullet/examples/heightfield.py b/examples/pybullet/examples/heightfield.py new file mode 100644 index 000000000..59b7b9922 --- /dev/null +++ b/examples/pybullet/examples/heightfield.py @@ -0,0 +1,73 @@ +import pybullet as p +import time + +p.connect(p.GUI) +p.createCollisionShape(p.GEOM_HEIGHTFIELD) +p.createMultiBody(0, 0) + +sphereRadius = 0.05 +colSphereId = p.createCollisionShape(p.GEOM_SPHERE, radius=sphereRadius) +colBoxId = p.createCollisionShape(p.GEOM_BOX, + halfExtents=[sphereRadius, sphereRadius, sphereRadius]) + +mass = 1 +visualShapeId = -1 + +link_Masses = [1] +linkCollisionShapeIndices = [colBoxId] +linkVisualShapeIndices = [-1] +linkPositions = [[0, 0, 0.11]] +linkOrientations = [[0, 0, 0, 1]] +linkInertialFramePositions = [[0, 0, 0]] +linkInertialFrameOrientations = [[0, 0, 0, 1]] +indices = [0] +jointTypes = [p.JOINT_REVOLUTE] +axis = [[0, 0, 1]] + +for i in range(3): + for j in range(3): + for k in range(3): + basePosition = [ + 1 + i * 5 * sphereRadius, 1 + j * 5 * sphereRadius, 1 + k * 5 * sphereRadius + 1 + ] + baseOrientation = [0, 0, 0, 1] + if (k & 2): + sphereUid = p.createMultiBody(mass, colSphereId, visualShapeId, basePosition, + baseOrientation) + else: + sphereUid = p.createMultiBody(mass, + colBoxId, + visualShapeId, + basePosition, + baseOrientation, + linkMasses=link_Masses, + linkCollisionShapeIndices=linkCollisionShapeIndices, + linkVisualShapeIndices=linkVisualShapeIndices, + linkPositions=linkPositions, + linkOrientations=linkOrientations, + linkInertialFramePositions=linkInertialFramePositions, + linkInertialFrameOrientations=linkInertialFrameOrientations, + linkParentIndices=indices, + linkJointTypes=jointTypes, + linkJointAxis=axis) + + p.changeDynamics(sphereUid, + -1, + spinningFriction=0.001, + rollingFriction=0.001, + linearDamping=0.0) + for joint in range(p.getNumJoints(sphereUid)): + p.setJointMotorControl2(sphereUid, joint, p.VELOCITY_CONTROL, targetVelocity=1, force=10) + +p.setGravity(0, 0, -10) +p.setRealTimeSimulation(1) + +p.getNumJoints(sphereUid) +for i in range(p.getNumJoints(sphereUid)): + p.getJointInfo(sphereUid, i) + +while (1): + keys = p.getKeyboardEvents() + print(keys) + + time.sleep(0.01) diff --git a/examples/pybullet/gym/pybullet_data/heightmaps/Maze.png b/examples/pybullet/gym/pybullet_data/heightmaps/Maze.png new file mode 100644 index 000000000..25654fed0 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/heightmaps/Maze.png differ diff --git a/examples/pybullet/gym/pybullet_data/heightmaps/gimp_overlay_out.png b/examples/pybullet/gym/pybullet_data/heightmaps/gimp_overlay_out.png new file mode 100644 index 000000000..a112c5fdc Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/heightmaps/gimp_overlay_out.png differ diff --git a/examples/pybullet/gym/pybullet_data/heightmaps/ground0.txt b/examples/pybullet/gym/pybullet_data/heightmaps/ground0.txt new file mode 100644 index 000000000..2a5b1141c --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/heightmaps/ground0.txt @@ -0,0 +1,401 @@ +-0.60575, -0.60948, -0.65511, -0.77243, -0.76525, -0.68419, -0.65576, -0.60841, -0.56404, -0.66318, -0.76960, -0.74814, -0.69321, -0.65239, -0.68686, -0.73690, -0.86802, -0.97506, -1.13730, -1.47566, -1.67885, -1.60319, -1.50291, -1.53900, -1.69098, -1.79824, -1.86313, -1.88329, -2.03698, -2.22492, -2.45773, -2.69267, -2.86467, -3.05220, -3.09779, -3.03938, -2.81959, -2.60810, -2.47421, -2.36606, -2.18378, -2.08089, -2.09309, -2.07302, -2.04148, -1.89813, -1.77496, -1.74555, -1.73489, -1.53036, -1.20510, -1.04637, -0.86257, -0.59006, -0.45898, -0.42830, -0.24411, -0.04286, 0.05054, 0.14034, 0.23489, 0.27915, 0.21442, 0.10847, 0.08893, 0.05872, 0.09334, 0.09531, 0.12995, 0.10841, 0.05954, 0.05088, 0.13851, 0.13753, 0.04586, 0.07737, 0.09127, 0.11242, 0.09636, 0.07749, 0.14875, 0.32770, 0.57904, 0.52040, 0.27875, 0.17188, 0.15345, 0.11236, 0.07413, 0.03986, 0.06007, 0.13139, 0.20008, 0.20578, 0.21875, 0.21205, 0.30483, 0.25996, 0.23441, 0.12446, 0.13010, 0.20496, 0.25090, 0.26197, 0.30055, 0.35018, 0.23838, 0.12612, 0.04039, 0.09057, 0.19088, 0.27284, 0.38600, 0.44535, 0.48295, 0.40519, 0.36931, 0.46325, 0.51763, 0.51949, 0.64949, 0.74736, 0.77567, 0.79068, 0.85001, 0.89954, 0.97444, 0.96872, 0.99581, 0.85816, 0.83140, 0.79605, 0.84867, 0.86960, 0.89351, 0.96139, 1.05841, 1.15899, 1.14759, 1.25156, 1.43237, 1.61722, 1.79627, 1.81428, 1.68787, 1.53361, 1.56014, 1.57977, 1.45371, 1.40128, 1.36429, 1.23063, 1.07908, 0.83098, 0.54765, 0.31044, 0.06470, -0.25626, -0.53945, -0.89456, -1.04975, -1.22908, -1.35739, -1.57892, -1.74781, -1.85197, -2.03684, -2.32596, -2.58742, -2.75016, -3.00987, -3.16497, -3.19933, -3.27962, -3.43168, -3.49732, -3.41156, -3.37183, -3.35134, -3.36114, -3.46500, -3.58316, -3.63790, -3.73107, -3.69994, -3.60669, -3.55574, -3.47821, -3.49400, -3.63515, -3.69696, -3.76763, -3.68201, -3.66325, -3.54992, -3.43030, -3.35786, -3.30492, -3.31306, -3.31690, -3.22558, -3.05588, -2.95924, -2.90870, -2.84037, -2.76894, -2.60863, -2.41581, -2.32701, -2.37908, -2.40855, -2.49814, -2.74111, -2.99882, -3.07728, -3.11275, -3.08884, -3.02502, -2.99344, -2.95957, -2.92535, -2.97260, -3.02795, -3.20475, -3.29737, -3.34511, -3.43339, -3.54978, -3.66102, -3.63132, -3.67782, -3.77023, -3.86416, -3.96288, -4.19014, -4.23815, -4.04571, -3.87769, -3.78944, -3.63875, -3.46145, -3.43144, -3.36549, -3.25960, -3.21009, -3.16004, -2.98388, -2.84523, -2.85614, -2.88787, -2.91723, -2.87146, -2.77412, -2.73362, -2.56729, -2.39029, -2.19158, -1.98806, -1.82002, -1.60154, -1.38053, -1.11460, -0.87316, -0.80300, -0.76458, -0.66119, -0.51986, -0.36146, -0.17710, -0.07037, -0.00818, 0.00693, -0.00046, -0.10063, -0.05331, 0.15276, 0.18078, 0.15091, 0.21119, 0.22965, 0.16332, 0.04847, -0.15818, -0.35246, -0.40678, -0.41467, -0.38427, -0.33646, -0.24665, -0.07115, -0.02532, 0.04572, -0.01452, -0.16624, -0.42858, -0.61601, -0.69523, -0.75166, -0.86949, -0.88174, -0.73615, -0.67296, -0.58470, -0.44311, -0.21282, -0.05747, 0.06684, 0.21209, 0.07734, -0.15554, -0.20427, -0.11286, -0.10769, -0.13914, -0.18409, -0.23250, -0.27910, -0.34801, -0.39660, -0.30137, -0.13143, 0.15973, 0.31772, 0.37779, 0.28632, 0.20939, 0.17467, 0.13321, 0.06622, 0.05795, 0.06607, 0.03902, 0.10699, 0.08082, 0.08333, 0.10382, 0.05870, -0.11915, -0.33454, -0.41501, -0.57448, -0.78744, -0.87836, -0.88018, -0.84841, -0.73454, -0.73982, -0.81729, -0.83170, -0.81489, -0.84174, -0.77304, -0.76142, -0.71486, -0.77452, -0.65098, -0.60646, -0.71322, -0.94030, -1.11296, -1.23940, -1.37153, -1.44383, -1.52287, -1.42607, -1.40428, -1.43389, -1.51559, -1.70156, -1.93592, -2.12483, -2.11856, -2.17503, -2.34039, -2.37974, -2.37080, -2.53613, -2.75573, -3.04128, -3.24657, -3.34692, -3.38971, -3.45133, -3.48283, -3.57767, -3.49965, -3.38086, -3.11941, -2.96550, -2.78968, -2.55674, -2.27151, -1.99843, -1.77076, -1.46585, -1.21439, -0.96456, -0.86317, -0.86165, -0.83599, -0.76762, +-0.67027, -0.74228, -0.76344, -0.79521, -0.70015, -0.56679, -0.51550, -0.51500, -0.57350, -0.62671, -0.68087, -0.68646, -0.73701, -0.78345, -0.74656, -0.73671, -0.79466, -0.90835, -1.16438, -1.49587, -1.69911, -1.68890, -1.61340, -1.58890, -1.62499, -1.67823, -1.76176, -1.77761, -1.81855, -1.98221, -2.29754, -2.54478, -2.71674, -2.95564, -3.04442, -2.96676, -2.73280, -2.46848, -2.30424, -2.17131, -2.02184, -1.95988, -2.05877, -2.08378, -2.03934, -1.87068, -1.61431, -1.49162, -1.41343, -1.16464, -0.94943, -0.83991, -0.69948, -0.52390, -0.45176, -0.41924, -0.17556, 0.08041, 0.12200, 0.12377, 0.23655, 0.32611, 0.25331, 0.24574, 0.26123, 0.19713, 0.18179, 0.15500, 0.11077, 0.13479, 0.10784, 0.08574, 0.07994, 0.07332, 0.00648, 0.03986, 0.07222, 0.05416, 0.10370, 0.14925, 0.19688, 0.38472, 0.53957, 0.51821, 0.36265, 0.24320, 0.22775, 0.24287, 0.25391, 0.25391, 0.15136, 0.05053, 0.12701, 0.18362, 0.13554, 0.18858, 0.29866, 0.26297, 0.21982, 0.18386, 0.19145, 0.24428, 0.17628, 0.16397, 0.18406, 0.28713, 0.23813, 0.10182, 0.01979, 0.01948, 0.13873, 0.29314, 0.38395, 0.49891, 0.46718, 0.37921, 0.43853, 0.57534, 0.63652, 0.66045, 0.78713, 0.95911, 0.98765, 0.93558, 1.01327, 1.11962, 1.11546, 1.07444, 1.03998, 0.92974, 0.89868, 0.91469, 0.92870, 0.99399, 1.01031, 1.11403, 1.20130, 1.28651, 1.27706, 1.26977, 1.33792, 1.38063, 1.53158, 1.68085, 1.58408, 1.52492, 1.54705, 1.58407, 1.54403, 1.50058, 1.38506, 1.23740, 1.12600, 0.96963, 0.66486, 0.30193, 0.03074, -0.20183, -0.51803, -0.82892, -0.98333, -1.24165, -1.53237, -1.74461, -1.91323, -1.95131, -2.14949, -2.45856, -2.74644, -2.91007, -3.12070, -3.28926, -3.31732, -3.40928, -3.51430, -3.41497, -3.26964, -3.13742, -3.19880, -3.36907, -3.54786, -3.69923, -3.79779, -3.86376, -3.81430, -3.64564, -3.60251, -3.70371, -3.80737, -3.84043, -3.91162, -3.98496, -3.91321, -3.86832, -3.78399, -3.58797, -3.47294, -3.36595, -3.37599, -3.42601, -3.41337, -3.30430, -3.15966, -3.05992, -2.95451, -2.88848, -2.66799, -2.29011, -2.13070, -2.09275, -2.18342, -2.37702, -2.57373, -2.79695, -2.90825, -2.93627, -2.89224, -2.73641, -2.67821, -2.74297, -2.78939, -2.86816, -3.05725, -3.28388, -3.35806, -3.38217, -3.53479, -3.66881, -3.77100, -3.72222, -3.78370, -3.91012, -4.02871, -4.12947, -4.28857, -4.31310, -4.10232, -3.94850, -3.88423, -3.69010, -3.55912, -3.49268, -3.42993, -3.39193, -3.32157, -3.25350, -3.13612, -3.09037, -3.14253, -3.08716, -3.08558, -3.17369, -3.19983, -3.09953, -2.90446, -2.68182, -2.36725, -2.08389, -1.91487, -1.72066, -1.50647, -1.24143, -0.95791, -0.84203, -0.79021, -0.70694, -0.49592, -0.30638, -0.14620, -0.10103, -0.13554, -0.06403, -0.00152, -0.03841, 0.03718, 0.16198, 0.21758, 0.26947, 0.36006, 0.41400, 0.36394, 0.21022, -0.05268, -0.34097, -0.47191, -0.40553, -0.34050, -0.32280, -0.14428, 0.07291, 0.08933, 0.10629, 0.06678, -0.06192, -0.26843, -0.43109, -0.44060, -0.45748, -0.48987, -0.49601, -0.41812, -0.35671, -0.28630, -0.07232, 0.17440, 0.27179, 0.32642, 0.23160, 0.00898, -0.17298, -0.22948, -0.18598, -0.17870, -0.14423, -0.10326, -0.16321, -0.28807, -0.31801, -0.32483, -0.32136, -0.12993, 0.15831, 0.32835, 0.40198, 0.38090, 0.33419, 0.39668, 0.37238, 0.31840, 0.25216, 0.22251, 0.18693, 0.20333, 0.14624, 0.08289, 0.13858, 0.17966, 0.02907, -0.11276, -0.27283, -0.49972, -0.78004, -0.96240, -1.00894, -0.95679, -0.81321, -0.78228, -0.93060, -1.07017, -1.07351, -1.08513, -1.12664, -1.07690, -0.98485, -1.01145, -0.90106, -0.75388, -0.81427, -0.95531, -1.17136, -1.32507, -1.45853, -1.47800, -1.47868, -1.41392, -1.41015, -1.53919, -1.69575, -1.82100, -2.01827, -2.12006, -2.21882, -2.34410, -2.44755, -2.44240, -2.40693, -2.52847, -2.72485, -2.96505, -3.26656, -3.54114, -3.61681, -3.55751, -3.55710, -3.54323, -3.37157, -3.16123, -2.91223, -2.69894, -2.55804, -2.34259, -2.12243, -1.88717, -1.72158, -1.44057, -1.15919, -0.93074, -0.79115, -0.78080, -0.69456, -0.52959, +-0.82000, -0.92479, -0.89566, -0.82769, -0.73489, -0.65273, -0.55871, -0.55609, -0.64809, -0.58133, -0.51206, -0.49485, -0.56785, -0.63146, -0.65629, -0.75959, -0.84920, -1.01742, -1.24090, -1.39371, -1.56319, -1.66644, -1.69093, -1.64836, -1.63836, -1.70496, -1.74049, -1.65798, -1.67049, -1.88471, -2.29833, -2.58494, -2.73515, -2.98282, -3.04664, -2.90551, -2.69081, -2.47969, -2.34022, -2.15732, -2.00464, -1.88012, -1.94342, -1.95101, -1.82751, -1.55709, -1.28603, -1.22118, -1.10962, -0.86856, -0.72651, -0.59495, -0.53050, -0.46473, -0.43198, -0.38747, -0.19249, -0.02212, 0.06307, 0.19873, 0.29731, 0.35317, 0.27077, 0.32968, 0.34589, 0.20399, 0.12490, 0.08908, 0.00878, 0.08620, 0.13102, 0.16131, 0.04449, 0.03235, 0.00032, 0.01008, 0.04894, 0.09158, 0.18672, 0.22614, 0.24644, 0.34733, 0.38034, 0.47821, 0.42542, 0.29482, 0.21774, 0.21782, 0.23087, 0.17966, 0.02368, -0.01340, 0.05693, 0.08717, 0.02385, 0.12562, 0.26405, 0.19318, 0.06314, 0.09809, 0.13007, 0.19221, 0.08536, 0.11132, 0.09878, 0.24162, 0.25632, 0.13864, 0.10455, 0.18338, 0.27027, 0.29600, 0.30119, 0.40952, 0.35823, 0.39600, 0.50582, 0.63050, 0.69502, 0.73887, 0.84385, 1.00261, 1.07966, 1.21176, 1.27066, 1.27018, 1.16161, 1.06687, 1.05430, 1.04494, 1.03534, 1.10612, 1.04506, 1.08429, 1.06197, 1.17832, 1.19505, 1.26503, 1.33739, 1.37348, 1.38147, 1.37665, 1.43548, 1.51158, 1.42452, 1.39664, 1.34548, 1.45963, 1.52279, 1.50718, 1.32258, 1.14912, 1.05453, 0.89963, 0.62628, 0.40449, 0.14768, -0.17804, -0.62514, -0.94435, -1.05563, -1.28546, -1.67624, -1.87459, -2.05306, -2.08477, -2.30501, -2.56261, -2.84009, -2.98473, -3.14776, -3.31062, -3.36755, -3.37350, -3.41330, -3.35726, -3.28684, -3.17381, -3.31597, -3.49838, -3.68286, -3.81909, -3.92965, -3.97337, -3.97157, -3.88794, -3.88393, -3.90746, -3.93367, -3.90138, -3.98804, -4.10595, -4.08313, -4.01210, -3.99953, -3.81664, -3.71499, -3.59846, -3.54971, -3.49018, -3.51468, -3.49268, -3.33902, -3.15388, -2.97771, -2.81788, -2.57457, -2.24197, -2.08729, -1.99938, -2.17116, -2.36337, -2.46316, -2.60793, -2.69740, -2.71147, -2.67802, -2.62134, -2.64994, -2.61968, -2.56779, -2.66551, -2.98215, -3.28711, -3.35753, -3.34453, -3.56189, -3.71773, -3.80653, -3.78867, -3.91868, -4.07230, -4.23830, -4.35606, -4.42689, -4.40651, -4.22378, -4.02593, -3.90401, -3.78387, -3.75653, -3.64282, -3.57571, -3.51199, -3.40827, -3.35449, -3.29806, -3.31123, -3.33033, -3.22487, -3.21820, -3.27985, -3.28038, -3.19091, -3.08662, -2.94335, -2.60293, -2.23691, -1.99923, -1.76314, -1.56863, -1.39585, -1.17030, -0.98638, -0.86453, -0.81081, -0.58497, -0.36854, -0.18443, -0.10029, -0.14037, -0.13396, -0.13016, -0.10043, 0.01494, 0.14521, 0.29224, 0.34174, 0.38881, 0.46203, 0.46450, 0.28847, -0.05770, -0.31607, -0.31739, -0.22387, -0.21709, -0.25525, -0.02119, 0.24136, 0.21474, 0.14322, 0.08990, -0.03788, -0.20406, -0.33041, -0.28933, -0.30403, -0.24086, -0.21712, -0.15741, -0.01976, 0.14149, 0.31687, 0.36709, 0.36329, 0.32870, 0.12059, 0.01856, -0.04568, -0.07442, -0.08912, -0.11218, -0.07511, -0.09428, -0.16792, -0.17483, -0.17711, -0.16867, -0.22158, -0.08966, 0.13305, 0.25832, 0.33070, 0.39355, 0.33709, 0.38204, 0.36575, 0.40530, 0.30496, 0.24988, 0.21725, 0.23044, 0.22949, 0.26728, 0.31144, 0.22919, -0.00743, -0.17825, -0.37070, -0.47566, -0.72370, -0.96135, -1.06276, -1.00655, -0.87395, -0.91115, -1.07588, -1.07570, -1.09075, -1.20922, -1.41457, -1.42118, -1.29024, -1.27004, -1.22365, -1.05685, -1.11746, -1.22043, -1.46823, -1.56590, -1.66268, -1.60269, -1.53580, -1.51228, -1.51212, -1.58785, -1.76632, -1.92160, -2.05830, -2.09695, -2.29163, -2.37567, -2.41195, -2.42316, -2.44761, -2.56108, -2.72410, -2.92628, -3.23029, -3.43952, -3.56136, -3.54552, -3.55231, -3.48879, -3.27701, -3.05066, -2.85905, -2.58358, -2.47626, -2.33314, -2.18442, -1.90728, -1.73372, -1.41550, -1.08378, -0.86738, -0.76238, -0.66526, -0.50515, -0.36440, +-1.07222, -1.12988, -1.02728, -0.91263, -0.85304, -0.81319, -0.68957, -0.63548, -0.60538, -0.48432, -0.37310, -0.25587, -0.33141, -0.44114, -0.49832, -0.58790, -0.77517, -1.02414, -1.20405, -1.31309, -1.41449, -1.54994, -1.64154, -1.55890, -1.57336, -1.63142, -1.67611, -1.66317, -1.74104, -2.00269, -2.27880, -2.53596, -2.80487, -3.04824, -3.06500, -2.92165, -2.71443, -2.56489, -2.44307, -2.23664, -1.98745, -1.77716, -1.76188, -1.66482, -1.51275, -1.28238, -1.03303, -0.91335, -0.80798, -0.65611, -0.52344, -0.46449, -0.40984, -0.33979, -0.33016, -0.24616, -0.17296, -0.10931, 0.02898, 0.19815, 0.27676, 0.26914, 0.30589, 0.40836, 0.28167, 0.07025, 0.03851, 0.00714, -0.02299, 0.06702, 0.17596, 0.24967, 0.17758, 0.15340, 0.08546, 0.11655, 0.14442, 0.14273, 0.26517, 0.40710, 0.44083, 0.38464, 0.38678, 0.44740, 0.44058, 0.34243, 0.14736, 0.10686, 0.08787, 0.01347, -0.05098, -0.04859, 0.01462, -0.06226, -0.05857, 0.10283, 0.15028, -0.00255, -0.09120, -0.03541, 0.06170, 0.16813, 0.15363, 0.19617, 0.21339, 0.33468, 0.29266, 0.22152, 0.23082, 0.27461, 0.33443, 0.36423, 0.39270, 0.40600, 0.42078, 0.45448, 0.52114, 0.64698, 0.69473, 0.79701, 0.91188, 1.04054, 1.20802, 1.39115, 1.42284, 1.26297, 1.18610, 1.17807, 1.13782, 1.10268, 1.20649, 1.31316, 1.26649, 1.24318, 1.22095, 1.29367, 1.30339, 1.37767, 1.43949, 1.55096, 1.57110, 1.45890, 1.43159, 1.49414, 1.46517, 1.29525, 1.16756, 1.19109, 1.26659, 1.36423, 1.21207, 1.10962, 1.05082, 0.82573, 0.59153, 0.39602, 0.14192, -0.35015, -0.82675, -1.05590, -1.19687, -1.44965, -1.71687, -1.90094, -2.07463, -2.18492, -2.40598, -2.64734, -2.86394, -2.94741, -3.13903, -3.27796, -3.28597, -3.29730, -3.32942, -3.29724, -3.26886, -3.35890, -3.53207, -3.75189, -3.96846, -4.02461, -4.14027, -4.15910, -4.16288, -4.18461, -4.13582, -4.07793, -4.00643, -4.00808, -4.05419, -4.04380, -4.08003, -4.14115, -4.09390, -3.93174, -3.83298, -3.74209, -3.61545, -3.46428, -3.44406, -3.39382, -3.29031, -3.06960, -2.80149, -2.66979, -2.53185, -2.27467, -2.04126, -2.00277, -2.15196, -2.31758, -2.42175, -2.49152, -2.59103, -2.60010, -2.53576, -2.61076, -2.66371, -2.57550, -2.45119, -2.53937, -2.84250, -3.05157, -3.17794, -3.33336, -3.54091, -3.68366, -3.77331, -3.81142, -3.98616, -4.16012, -4.32150, -4.37225, -4.45244, -4.46918, -4.32574, -4.19746, -4.09456, -3.98846, -3.88835, -3.80053, -3.74968, -3.66457, -3.62281, -3.53749, -3.47887, -3.47079, -3.37101, -3.27341, -3.22447, -3.20704, -3.19391, -3.16170, -3.13680, -2.93706, -2.62659, -2.37335, -2.05247, -1.71610, -1.53185, -1.42067, -1.25290, -1.03348, -0.86585, -0.77950, -0.66297, -0.52317, -0.26927, -0.14763, -0.18584, -0.18689, -0.12843, -0.13516, -0.09928, 0.05728, 0.17780, 0.23801, 0.28221, 0.35544, 0.47245, 0.34726, 0.04229, -0.14990, -0.13105, -0.08134, -0.15381, -0.08914, 0.18346, 0.33577, 0.29096, 0.26033, 0.20939, 0.11349, -0.04802, -0.15934, -0.16389, -0.14261, -0.05851, -0.06209, 0.05051, 0.21563, 0.33509, 0.45654, 0.46309, 0.39316, 0.23143, 0.07274, 0.01856, 0.05214, 0.11387, 0.09376, 0.12873, 0.15625, 0.09377, 0.04622, 0.05168, 0.04964, 0.01200, 0.05448, 0.17497, 0.21610, 0.24780, 0.38831, 0.46561, 0.38803, 0.30776, 0.29046, 0.38049, 0.38474, 0.37291, 0.30539, 0.34933, 0.34276, 0.30594, 0.31021, 0.21500, -0.07170, -0.39974, -0.55499, -0.61498, -0.74781, -0.90055, -1.04589, -0.97155, -0.87986, -0.98544, -1.09528, -1.06371, -1.09102, -1.35183, -1.54143, -1.50370, -1.45778, -1.50946, -1.45890, -1.39217, -1.47090, -1.60786, -1.82804, -1.89771, -1.90534, -1.79000, -1.75401, -1.71829, -1.68061, -1.76811, -1.89262, -1.93890, -1.96526, -2.07603, -2.22960, -2.32745, -2.34150, -2.30708, -2.39199, -2.46468, -2.57708, -2.75858, -2.95630, -3.14421, -3.28837, -3.40477, -3.35915, -3.19637, -3.11090, -3.08631, -2.87859, -2.58823, -2.43146, -2.32063, -2.16289, -1.89361, -1.70270, -1.36881, -1.08042, -0.86011, -0.75853, -0.70372, -0.52090, -0.28685, +-1.21051, -1.12501, -1.02887, -0.94766, -0.86822, -0.79856, -0.69026, -0.61752, -0.51421, -0.41996, -0.36350, -0.19317, -0.19062, -0.28827, -0.40784, -0.46901, -0.58332, -0.79775, -0.96495, -1.10509, -1.23691, -1.43569, -1.59319, -1.49222, -1.51403, -1.54354, -1.65934, -1.79717, -1.85500, -2.04946, -2.22299, -2.50049, -2.78658, -2.91337, -2.98787, -2.94665, -2.72153, -2.54852, -2.41978, -2.22894, -1.93208, -1.70013, -1.65333, -1.49869, -1.29475, -1.08948, -0.90976, -0.77103, -0.58688, -0.41768, -0.28836, -0.27653, -0.23861, -0.21472, -0.27103, -0.20192, -0.20689, -0.19169, -0.05795, 0.03134, 0.17338, 0.23755, 0.32458, 0.33826, 0.15980, 0.08956, 0.09870, 0.02504, 0.05509, 0.16694, 0.27501, 0.32856, 0.32102, 0.25507, 0.12896, 0.16387, 0.24158, 0.24784, 0.32872, 0.45290, 0.55818, 0.53358, 0.55792, 0.58480, 0.55264, 0.37224, 0.04666, -0.06828, -0.09945, -0.14381, -0.11552, -0.16403, -0.05924, -0.10332, -0.11905, -0.05360, -0.05974, -0.05606, -0.03378, -0.00831, 0.15158, 0.34386, 0.40609, 0.40022, 0.42155, 0.44495, 0.30934, 0.22140, 0.27409, 0.32021, 0.34938, 0.36049, 0.50979, 0.62256, 0.70614, 0.72383, 0.72077, 0.73308, 0.71741, 0.81077, 0.95536, 1.08806, 1.29589, 1.36952, 1.41809, 1.31968, 1.28975, 1.26155, 1.17651, 1.25002, 1.44353, 1.51524, 1.52293, 1.51354, 1.50824, 1.51678, 1.54538, 1.57760, 1.56044, 1.61203, 1.64975, 1.53365, 1.46923, 1.46540, 1.49087, 1.34127, 1.17628, 1.11991, 1.17209, 1.25681, 1.13677, 1.06642, 1.04649, 0.77350, 0.50493, 0.16518, -0.09673, -0.52085, -0.93319, -1.18269, -1.39633, -1.51546, -1.62006, -1.85879, -2.05227, -2.20438, -2.42280, -2.70873, -2.89323, -2.97762, -3.20564, -3.36065, -3.28215, -3.22895, -3.26270, -3.32283, -3.32896, -3.44833, -3.61893, -3.86078, -4.10182, -4.21442, -4.40079, -4.48240, -4.46286, -4.49231, -4.37987, -4.35427, -4.25223, -4.16967, -4.14545, -4.09352, -4.18612, -4.20342, -4.02653, -3.89123, -3.77726, -3.64970, -3.47460, -3.34795, -3.29149, -3.20655, -3.12893, -2.94553, -2.63821, -2.49985, -2.44019, -2.31140, -2.04092, -1.90852, -1.94800, -2.06353, -2.18073, -2.32880, -2.56036, -2.66581, -2.58469, -2.67401, -2.67378, -2.63117, -2.51638, -2.46420, -2.65374, -2.83778, -3.08234, -3.27871, -3.37211, -3.54106, -3.67801, -3.73297, -3.90418, -4.11500, -4.25708, -4.26704, -4.40293, -4.52306, -4.44678, -4.34661, -4.24923, -4.18924, -4.02960, -3.85799, -3.76499, -3.66877, -3.65068, -3.59264, -3.59067, -3.61758, -3.46350, -3.37035, -3.27407, -3.23856, -3.25561, -3.15863, -3.07250, -2.83919, -2.61886, -2.38862, -1.93252, -1.59751, -1.45553, -1.31932, -1.12594, -0.92233, -0.77801, -0.69254, -0.70147, -0.67776, -0.41765, -0.22195, -0.18780, -0.20766, -0.13211, -0.11791, -0.11897, 0.03720, 0.14270, 0.20687, 0.21252, 0.22596, 0.38935, 0.34085, 0.12551, -0.05782, -0.14008, -0.06946, -0.08051, 0.03824, 0.22920, 0.33371, 0.43653, 0.45849, 0.40158, 0.37766, 0.26109, 0.13535, 0.03947, 0.07020, 0.11428, 0.05443, 0.16150, 0.34049, 0.42503, 0.45788, 0.42800, 0.41002, 0.27921, 0.18229, 0.14486, 0.18355, 0.21359, 0.17097, 0.24517, 0.29901, 0.27707, 0.26843, 0.19150, 0.23762, 0.25118, 0.31383, 0.33544, 0.29139, 0.43724, 0.61861, 0.62044, 0.53989, 0.41592, 0.38659, 0.44598, 0.54301, 0.55753, 0.44488, 0.44398, 0.38576, 0.25117, 0.17248, 0.03648, -0.17028, -0.44664, -0.56291, -0.59653, -0.65760, -0.83126, -1.05285, -1.04150, -0.98678, -1.09415, -1.16410, -1.24631, -1.25647, -1.45448, -1.58317, -1.57012, -1.58854, -1.54896, -1.49158, -1.58998, -1.68670, -1.80765, -1.99196, -2.10526, -2.07775, -1.99486, -2.01545, -1.99498, -1.89456, -1.93156, -2.01153, -2.04000, -1.96482, -1.99646, -2.06563, -2.14591, -2.15648, -2.16156, -2.28679, -2.36298, -2.42441, -2.58138, -2.70649, -2.96685, -3.07620, -3.11418, -3.01988, -2.90477, -2.96090, -2.94265, -2.69328, -2.48070, -2.27206, -2.09627, -1.90749, -1.72880, -1.60181, -1.37469, -1.17096, -0.99283, -0.83127, -0.73053, -0.53816, -0.28767, +-1.08470, -1.02824, -0.98441, -0.95110, -0.89758, -0.78364, -0.71531, -0.61381, -0.50920, -0.47676, -0.38227, -0.19641, -0.19131, -0.22638, -0.37781, -0.49438, -0.56076, -0.72270, -0.86492, -1.06750, -1.30147, -1.47300, -1.52633, -1.42763, -1.51700, -1.57853, -1.64522, -1.78533, -1.86329, -2.01351, -2.27006, -2.51695, -2.65051, -2.77194, -2.92353, -2.94418, -2.79005, -2.57892, -2.40350, -2.16893, -1.87910, -1.67800, -1.52605, -1.29823, -1.13452, -0.95072, -0.79125, -0.67458, -0.47238, -0.36095, -0.28274, -0.29498, -0.33873, -0.32986, -0.31403, -0.24950, -0.36261, -0.42154, -0.24262, -0.08177, 0.10505, 0.24451, 0.21478, 0.12788, 0.07467, 0.07640, 0.06322, 0.05894, 0.10258, 0.24696, 0.30280, 0.33394, 0.35677, 0.23127, 0.14487, 0.23648, 0.29816, 0.34939, 0.41237, 0.39419, 0.46970, 0.47549, 0.53680, 0.55563, 0.42228, 0.18890, -0.06300, -0.14906, -0.23428, -0.30973, -0.23844, -0.22969, -0.16301, -0.11090, -0.23108, -0.29618, -0.20969, -0.07502, 0.03518, 0.18623, 0.36036, 0.63095, 0.69595, 0.64957, 0.62995, 0.49185, 0.37145, 0.40139, 0.42156, 0.42350, 0.44383, 0.40051, 0.57738, 0.75356, 0.89041, 0.93006, 0.81106, 0.71901, 0.76473, 0.93303, 1.07557, 1.14814, 1.31887, 1.38196, 1.37374, 1.39641, 1.33252, 1.23356, 1.25900, 1.40473, 1.50513, 1.60448, 1.61487, 1.64979, 1.63231, 1.59787, 1.66179, 1.62858, 1.58291, 1.63905, 1.61377, 1.51390, 1.50629, 1.41702, 1.39455, 1.25902, 1.12320, 1.09284, 1.07755, 1.09256, 1.05944, 1.07134, 1.02318, 0.71315, 0.37992, 0.00837, -0.36066, -0.66782, -0.99989, -1.33506, -1.47915, -1.46564, -1.61917, -1.84631, -2.11442, -2.31093, -2.51570, -2.78891, -2.93892, -3.12348, -3.34946, -3.37576, -3.28811, -3.22611, -3.20613, -3.35984, -3.49179, -3.65716, -3.81998, -3.99477, -4.24508, -4.47916, -4.68379, -4.77864, -4.80402, -4.84769, -4.72680, -4.60155, -4.52015, -4.36994, -4.33435, -4.37687, -4.37311, -4.22949, -4.08167, -3.89651, -3.72453, -3.51673, -3.30963, -3.24243, -3.13617, -3.03913, -2.92599, -2.65946, -2.39741, -2.30966, -2.21277, -2.16264, -1.98399, -1.84910, -1.84389, -1.90166, -2.03691, -2.27138, -2.54359, -2.67679, -2.68896, -2.79727, -2.72972, -2.60863, -2.51188, -2.36908, -2.47761, -2.75806, -3.01013, -3.10645, -3.20177, -3.32870, -3.49400, -3.62374, -3.78775, -4.02526, -4.14258, -4.17347, -4.33427, -4.41172, -4.42030, -4.40566, -4.24728, -4.15555, -4.00740, -3.84159, -3.76478, -3.69169, -3.69866, -3.71326, -3.70728, -3.65889, -3.53148, -3.50879, -3.43777, -3.32825, -3.32390, -3.19174, -3.04018, -2.90729, -2.67314, -2.30171, -1.90188, -1.64835, -1.49349, -1.32529, -1.05273, -0.89007, -0.77673, -0.72017, -0.76935, -0.68760, -0.43764, -0.28583, -0.17032, -0.17262, -0.14318, -0.11403, -0.15208, -0.04106, 0.01822, 0.06379, 0.15271, 0.23920, 0.39174, 0.32504, 0.12210, -0.01609, -0.14901, -0.12889, -0.02445, 0.04206, 0.16622, 0.33382, 0.46001, 0.48017, 0.48394, 0.48890, 0.47642, 0.34035, 0.19300, 0.21529, 0.22844, 0.27063, 0.41181, 0.46578, 0.49318, 0.43497, 0.30611, 0.29763, 0.20170, 0.15869, 0.13032, 0.08723, 0.08840, 0.11895, 0.22242, 0.24862, 0.23126, 0.29169, 0.28663, 0.33519, 0.41008, 0.34153, 0.29199, 0.39025, 0.61738, 0.73758, 0.74449, 0.65295, 0.62023, 0.59866, 0.62055, 0.72858, 0.69091, 0.60466, 0.62750, 0.46009, 0.22853, 0.06018, -0.19923, -0.33439, -0.48115, -0.55244, -0.55373, -0.64199, -0.85196, -1.05465, -1.13004, -1.18351, -1.27561, -1.28161, -1.35741, -1.45692, -1.53007, -1.67542, -1.73361, -1.64420, -1.52119, -1.57662, -1.73133, -1.86903, -1.89826, -2.00643, -2.13639, -2.13853, -2.17987, -2.22750, -2.12267, -2.03543, -2.02899, -2.02845, -2.11059, -2.04506, -2.04191, -2.06684, -2.10654, -2.16465, -2.22217, -2.26818, -2.26426, -2.32042, -2.50014, -2.61646, -2.77634, -2.87041, -2.77141, -2.72877, -2.77707, -2.78271, -2.66037, -2.49755, -2.30604, -2.12544, -1.88670, -1.69243, -1.57680, -1.48400, -1.43171, -1.31494, -1.08118, -0.86200, -0.66172, -0.39482, -0.16948, +-0.79482, -0.90603, -0.92981, -0.95428, -0.95604, -0.81377, -0.75639, -0.61513, -0.46048, -0.45204, -0.41903, -0.32095, -0.35073, -0.32797, -0.42268, -0.54742, -0.63345, -0.77671, -0.87428, -1.11633, -1.34378, -1.39434, -1.38328, -1.35073, -1.48673, -1.54249, -1.54222, -1.66862, -1.82316, -2.04146, -2.35352, -2.48613, -2.56844, -2.76873, -2.87278, -2.88894, -2.86104, -2.69975, -2.49474, -2.19173, -1.85390, -1.65659, -1.53322, -1.34111, -1.21729, -1.01719, -0.76583, -0.57010, -0.38275, -0.37911, -0.34937, -0.38112, -0.47372, -0.43193, -0.37799, -0.33452, -0.43378, -0.43060, -0.20257, -0.01985, 0.13756, 0.21329, 0.11999, 0.09882, 0.14265, 0.08498, 0.05429, 0.11544, 0.12037, 0.23176, 0.24859, 0.28016, 0.36189, 0.28478, 0.18733, 0.19553, 0.20165, 0.28187, 0.37460, 0.32540, 0.34210, 0.30663, 0.38674, 0.37055, 0.17346, 0.02292, -0.10309, -0.14522, -0.23986, -0.30840, -0.27513, -0.31825, -0.33850, -0.23767, -0.28994, -0.23888, -0.09687, -0.04577, 0.10740, 0.37917, 0.53075, 0.75144, 0.75935, 0.71173, 0.70595, 0.58412, 0.51309, 0.57129, 0.56862, 0.53393, 0.58382, 0.60104, 0.73396, 0.83152, 0.99598, 1.08025, 0.95555, 0.95805, 1.07587, 1.25478, 1.37921, 1.41746, 1.52697, 1.51952, 1.45308, 1.50079, 1.41731, 1.42083, 1.52895, 1.53769, 1.49571, 1.58206, 1.54526, 1.55495, 1.51202, 1.46141, 1.57476, 1.61171, 1.55272, 1.51453, 1.42406, 1.34447, 1.40829, 1.33638, 1.25794, 1.07938, 1.02506, 1.07734, 1.01393, 1.05130, 1.04128, 1.02507, 0.94969, 0.75729, 0.49913, 0.09142, -0.42887, -0.78230, -1.08328, -1.33038, -1.39273, -1.50588, -1.82653, -2.05639, -2.39245, -2.64151, -2.79786, -2.98323, -3.05056, -3.19253, -3.38738, -3.41145, -3.41249, -3.42109, -3.35472, -3.45152, -3.60147, -3.80732, -3.94853, -4.03159, -4.28655, -4.53165, -4.72822, -4.88958, -4.94304, -4.91992, -4.78302, -4.63317, -4.63610, -4.54678, -4.55057, -4.55112, -4.39945, -4.25239, -4.21082, -3.99303, -3.76785, -3.51849, -3.27641, -3.19313, -2.99309, -2.76406, -2.59678, -2.39970, -2.26352, -2.23918, -2.06185, -1.95359, -1.84769, -1.82831, -1.87722, -1.90530, -2.04001, -2.14053, -2.27177, -2.45043, -2.60545, -2.72291, -2.59920, -2.44744, -2.42482, -2.35570, -2.48628, -2.71281, -2.83534, -2.90379, -3.05466, -3.12055, -3.29532, -3.53424, -3.70871, -3.93453, -4.04993, -4.05102, -4.17348, -4.25728, -4.32686, -4.34968, -4.12591, -3.91272, -3.74641, -3.67482, -3.66551, -3.60938, -3.61363, -3.58999, -3.52012, -3.47484, -3.45101, -3.46945, -3.40742, -3.28816, -3.32174, -3.23376, -3.11114, -2.99636, -2.63610, -2.23581, -2.02253, -1.84918, -1.67733, -1.51765, -1.22230, -1.09722, -0.98815, -0.85907, -0.80390, -0.69687, -0.54624, -0.49495, -0.36850, -0.29862, -0.21003, -0.09477, -0.09317, -0.00368, -0.01926, 0.03898, 0.27452, 0.39786, 0.46371, 0.34273, 0.14991, 0.03048, -0.17674, -0.21864, -0.06744, 0.03561, 0.25359, 0.40817, 0.40200, 0.39550, 0.39546, 0.35113, 0.40640, 0.34348, 0.29026, 0.41937, 0.50481, 0.58208, 0.62074, 0.50447, 0.45331, 0.37455, 0.28952, 0.28917, 0.18260, 0.17812, 0.13107, 0.05045, 0.10733, 0.14580, 0.19742, 0.21482, 0.23582, 0.32686, 0.34007, 0.35807, 0.40183, 0.27702, 0.34946, 0.55714, 0.67985, 0.70646, 0.71640, 0.62385, 0.69801, 0.73322, 0.75313, 0.84768, 0.78796, 0.65680, 0.60261, 0.41982, 0.18520, -0.02187, -0.30820, -0.41520, -0.49926, -0.51161, -0.50660, -0.65382, -0.81754, -1.01452, -1.20975, -1.30213, -1.28066, -1.20449, -1.30337, -1.50720, -1.56135, -1.71829, -1.73195, -1.59613, -1.57546, -1.71154, -1.82825, -1.97130, -1.95079, -1.97420, -2.08587, -2.10834, -2.16258, -2.24414, -2.15431, -2.09714, -2.07197, -2.00292, -2.05030, -2.01300, -2.07096, -2.09374, -2.11191, -2.20441, -2.21219, -2.20161, -2.18104, -2.21202, -2.32437, -2.40493, -2.49968, -2.59921, -2.50745, -2.55483, -2.60280, -2.51897, -2.42527, -2.36913, -2.21710, -2.13770, -1.96274, -1.78487, -1.63982, -1.43114, -1.32876, -1.29094, -1.15516, -0.94291, -0.66378, -0.30546, -0.02155, +-0.74256, -0.85599, -0.89403, -0.92649, -0.89576, -0.71709, -0.60054, -0.51669, -0.47232, -0.42884, -0.44634, -0.41211, -0.34164, -0.29329, -0.38677, -0.55361, -0.66410, -0.76453, -0.85749, -1.04466, -1.24896, -1.35504, -1.36497, -1.35550, -1.48657, -1.52009, -1.55059, -1.71452, -1.88831, -2.14037, -2.40411, -2.52622, -2.69492, -2.82867, -2.81850, -2.80032, -2.79055, -2.68812, -2.48043, -2.23360, -2.00758, -1.78658, -1.67749, -1.54075, -1.31007, -1.04964, -0.77879, -0.57819, -0.40349, -0.37706, -0.38938, -0.41978, -0.53916, -0.61322, -0.57578, -0.48028, -0.48833, -0.38849, -0.16904, -0.03914, 0.08231, 0.09758, 0.05662, 0.08887, 0.10751, 0.10880, 0.12194, 0.18711, 0.21791, 0.33195, 0.40953, 0.42570, 0.41066, 0.36914, 0.28458, 0.15463, 0.17910, 0.27616, 0.32874, 0.27758, 0.25110, 0.21911, 0.23588, 0.17426, -0.01491, -0.21167, -0.31815, -0.29198, -0.33370, -0.35008, -0.35920, -0.48676, -0.52373, -0.37762, -0.25563, -0.05759, 0.02412, 0.04525, 0.22014, 0.49034, 0.67069, 0.86272, 0.88733, 0.83729, 0.73816, 0.65273, 0.67858, 0.68295, 0.77410, 0.83309, 0.86566, 0.89341, 0.94949, 1.02936, 1.17488, 1.27919, 1.23284, 1.20570, 1.29265, 1.47900, 1.57410, 1.60231, 1.66516, 1.58308, 1.54729, 1.60822, 1.55627, 1.65521, 1.69128, 1.64100, 1.60696, 1.63675, 1.59666, 1.59430, 1.57029, 1.50399, 1.49493, 1.50049, 1.50722, 1.38924, 1.34052, 1.34541, 1.35485, 1.24750, 1.11039, 0.96689, 0.92538, 0.97484, 0.93375, 0.89157, 0.81519, 0.80895, 0.76479, 0.71802, 0.57753, 0.14138, -0.41761, -0.85242, -1.18929, -1.35278, -1.48956, -1.71637, -2.05109, -2.32935, -2.65536, -2.87829, -2.96563, -3.06316, -3.15573, -3.29961, -3.39037, -3.49164, -3.54223, -3.52429, -3.50588, -3.58914, -3.73695, -3.87655, -3.97963, -4.04635, -4.26769, -4.57851, -4.83398, -4.98123, -4.98209, -4.88089, -4.74123, -4.65369, -4.68217, -4.61137, -4.60739, -4.49818, -4.36035, -4.26565, -4.18114, -3.98496, -3.72339, -3.41771, -3.08787, -2.86487, -2.66920, -2.48098, -2.26449, -2.20355, -2.14510, -2.06333, -1.93902, -1.87964, -1.86211, -1.87724, -1.93263, -1.96798, -2.03504, -2.05222, -2.12060, -2.27528, -2.45829, -2.60325, -2.52152, -2.43177, -2.43493, -2.38652, -2.51200, -2.60394, -2.68662, -2.77679, -2.85138, -2.90677, -3.06301, -3.29117, -3.44419, -3.59963, -3.80805, -3.93343, -3.98599, -4.09467, -4.17116, -4.07998, -3.86258, -3.66258, -3.55015, -3.50983, -3.48605, -3.44316, -3.38641, -3.36367, -3.38367, -3.37962, -3.37701, -3.37801, -3.30382, -3.22875, -3.29245, -3.20577, -3.11103, -2.95372, -2.61186, -2.32293, -2.11203, -1.94542, -1.78181, -1.61689, -1.34164, -1.18836, -1.13010, -1.09054, -0.96772, -0.87826, -0.80904, -0.69566, -0.56818, -0.49722, -0.37574, -0.14848, 0.00440, 0.09353, 0.06691, 0.07602, 0.20925, 0.31772, 0.39621, 0.28906, 0.12318, -0.01940, -0.25718, -0.26981, -0.10904, 0.06875, 0.32825, 0.39009, 0.38677, 0.38107, 0.32296, 0.27708, 0.38767, 0.47501, 0.50095, 0.58314, 0.70356, 0.75239, 0.63150, 0.51003, 0.43841, 0.32883, 0.29080, 0.31479, 0.28281, 0.28462, 0.25533, 0.19468, 0.16797, 0.15569, 0.21678, 0.26189, 0.31462, 0.36990, 0.33980, 0.37436, 0.41848, 0.35989, 0.49698, 0.61579, 0.69302, 0.70368, 0.68869, 0.64242, 0.76364, 0.88275, 0.89384, 0.83822, 0.72340, 0.57255, 0.39898, 0.32582, 0.19025, -0.06310, -0.36590, -0.51430, -0.52968, -0.50578, -0.47344, -0.60360, -0.85787, -1.10665, -1.29011, -1.33598, -1.22286, -1.11714, -1.23631, -1.41524, -1.46887, -1.60951, -1.61926, -1.62713, -1.66954, -1.76816, -1.86670, -1.94989, -1.89491, -1.84717, -1.94714, -2.08517, -2.17372, -2.19915, -2.17693, -2.07182, -1.96841, -1.92330, -1.95476, -1.94181, -1.95995, -1.98871, -2.01188, -2.08037, -2.18704, -2.24318, -2.18554, -2.14683, -2.12928, -2.13731, -2.23157, -2.30589, -2.25866, -2.34520, -2.35067, -2.37083, -2.36217, -2.31117, -2.23042, -2.18485, -2.04799, -1.84724, -1.63553, -1.41900, -1.30160, -1.22584, -1.23169, -1.04573, -0.67214, -0.30774, 0.00601, +-0.81298, -0.84004, -0.86457, -0.86602, -0.81773, -0.63722, -0.50533, -0.53160, -0.56398, -0.43021, -0.39901, -0.34236, -0.27603, -0.29841, -0.37509, -0.56013, -0.74177, -0.85895, -0.97449, -1.11151, -1.20850, -1.32002, -1.38054, -1.41968, -1.62633, -1.69337, -1.70701, -1.84514, -1.99417, -2.19806, -2.41307, -2.58098, -2.78119, -2.78810, -2.70824, -2.65729, -2.66515, -2.64321, -2.48626, -2.38426, -2.26780, -1.96993, -1.78242, -1.61384, -1.37318, -1.18929, -0.92385, -0.74535, -0.63881, -0.62745, -0.66284, -0.67032, -0.68889, -0.74059, -0.72271, -0.59784, -0.59050, -0.48567, -0.24356, -0.09328, -0.00844, 0.01011, -0.00513, -0.00267, 0.02891, 0.17457, 0.21412, 0.26047, 0.29233, 0.37077, 0.49978, 0.46025, 0.37787, 0.43479, 0.42704, 0.27712, 0.24603, 0.17738, 0.17208, 0.13135, 0.05030, -0.02841, -0.09263, -0.21265, -0.33239, -0.46386, -0.57973, -0.51626, -0.54229, -0.56423, -0.51265, -0.56020, -0.58457, -0.36923, -0.14383, 0.08023, 0.13391, 0.23898, 0.39306, 0.60541, 0.77330, 0.89665, 0.96632, 0.87397, 0.70666, 0.73147, 0.88012, 0.92199, 1.05534, 1.03694, 1.04719, 1.09262, 1.09727, 1.13111, 1.23097, 1.31954, 1.36501, 1.40663, 1.44509, 1.60525, 1.62091, 1.54409, 1.59086, 1.57916, 1.59492, 1.70712, 1.66507, 1.72928, 1.70155, 1.74429, 1.76619, 1.77079, 1.74843, 1.69354, 1.69613, 1.57165, 1.42570, 1.43914, 1.53534, 1.47011, 1.46762, 1.37181, 1.27460, 1.10845, 0.89559, 0.71075, 0.62076, 0.61748, 0.61420, 0.63959, 0.56066, 0.58899, 0.55600, 0.50654, 0.45141, 0.12690, -0.40540, -0.85346, -1.25193, -1.47660, -1.72064, -1.91309, -2.18491, -2.49372, -2.79093, -3.03489, -3.08981, -3.19067, -3.35483, -3.45803, -3.42752, -3.49450, -3.53585, -3.63621, -3.72644, -3.81241, -3.96193, -4.08597, -4.16316, -4.23144, -4.40959, -4.64272, -4.91067, -5.01727, -4.97401, -4.92538, -4.81599, -4.68895, -4.69193, -4.57387, -4.53304, -4.40778, -4.32480, -4.17874, -3.99649, -3.81819, -3.53948, -3.25224, -2.86538, -2.54950, -2.38712, -2.21066, -1.95156, -1.94444, -1.92068, -1.94355, -1.97808, -1.99115, -2.05013, -2.10938, -2.13178, -2.15421, -2.15992, -2.03597, -2.04090, -2.15557, -2.33009, -2.58868, -2.60780, -2.50078, -2.47208, -2.36988, -2.42604, -2.46974, -2.57443, -2.61027, -2.57764, -2.65283, -2.79959, -3.04460, -3.19230, -3.30426, -3.59010, -3.77519, -3.74183, -3.80503, -3.83936, -3.78001, -3.68873, -3.54441, -3.50749, -3.53720, -3.51948, -3.47867, -3.36954, -3.27495, -3.34234, -3.38860, -3.39597, -3.45465, -3.41230, -3.28775, -3.28896, -3.15841, -3.02683, -2.87333, -2.63145, -2.38897, -2.08815, -1.90781, -1.74498, -1.61814, -1.42805, -1.29792, -1.33033, -1.36036, -1.16552, -1.04074, -0.96209, -0.84986, -0.79804, -0.72521, -0.60208, -0.36758, -0.14504, -0.04817, -0.06115, -0.02849, 0.04544, 0.12513, 0.22962, 0.11149, -0.05824, -0.15094, -0.30407, -0.26258, -0.07001, 0.10769, 0.30182, 0.33162, 0.43870, 0.45454, 0.38832, 0.33290, 0.42163, 0.59717, 0.61971, 0.64617, 0.82113, 0.86403, 0.67632, 0.50208, 0.29317, 0.18499, 0.20170, 0.21685, 0.20814, 0.21107, 0.21079, 0.23928, 0.23345, 0.18708, 0.27222, 0.30017, 0.31182, 0.37840, 0.39928, 0.44917, 0.53828, 0.51784, 0.60245, 0.63925, 0.75228, 0.73843, 0.70543, 0.67482, 0.74414, 0.90129, 0.84817, 0.69321, 0.62945, 0.51730, 0.32062, 0.26675, 0.04819, -0.22847, -0.51138, -0.72376, -0.75976, -0.72377, -0.66414, -0.69726, -0.89336, -1.16648, -1.30243, -1.33109, -1.25338, -1.11996, -1.14832, -1.28141, -1.29349, -1.43122, -1.52289, -1.66687, -1.67786, -1.74304, -1.83142, -1.87388, -1.86321, -1.79072, -1.94268, -2.17409, -2.21785, -2.13734, -2.08064, -1.96865, -1.98586, -1.99525, -2.00345, -2.02157, -2.04724, -2.06900, -2.08442, -2.09049, -2.15688, -2.26569, -2.18765, -2.12100, -2.08946, -2.00750, -1.97328, -2.00199, -1.95647, -2.07702, -2.13480, -2.28314, -2.27672, -2.21965, -2.19327, -2.13228, -2.04134, -1.82407, -1.63066, -1.47015, -1.30040, -1.13874, -1.15436, -1.01752, -0.78515, -0.48765, -0.15310, +-0.91015, -0.91511, -0.90936, -0.83250, -0.77294, -0.68911, -0.64949, -0.66097, -0.64084, -0.50730, -0.45869, -0.38793, -0.38134, -0.39114, -0.36078, -0.51732, -0.72434, -0.83171, -1.05024, -1.25076, -1.22488, -1.26176, -1.38087, -1.48989, -1.75234, -1.85118, -1.86341, -1.92431, -1.99708, -2.14981, -2.31682, -2.51030, -2.68929, -2.72020, -2.64742, -2.54941, -2.56839, -2.63423, -2.56317, -2.50329, -2.40581, -2.16236, -1.92424, -1.69529, -1.50827, -1.38342, -1.09433, -0.95666, -0.92905, -0.92282, -0.98426, -0.98513, -0.78717, -0.69104, -0.73445, -0.66232, -0.62769, -0.51876, -0.30760, -0.16075, -0.04587, -0.02264, -0.04320, -0.10414, 0.00780, 0.15854, 0.15951, 0.19234, 0.20678, 0.17392, 0.23976, 0.22655, 0.24866, 0.35958, 0.40656, 0.30976, 0.17827, -0.04590, -0.07785, -0.15121, -0.25052, -0.27399, -0.37775, -0.62583, -0.67707, -0.67397, -0.77146, -0.68946, -0.66061, -0.66474, -0.52220, -0.49075, -0.46066, -0.26166, -0.02203, 0.13428, 0.25462, 0.41663, 0.54656, 0.70197, 0.79353, 0.76145, 0.82017, 0.78754, 0.74380, 0.82739, 0.99403, 1.08002, 1.15725, 1.01218, 1.07486, 1.17597, 1.23184, 1.31975, 1.35431, 1.30223, 1.41895, 1.59643, 1.58827, 1.66206, 1.65892, 1.51274, 1.53034, 1.54199, 1.64336, 1.73835, 1.67061, 1.59654, 1.60693, 1.70552, 1.74452, 1.78040, 1.81546, 1.69501, 1.67704, 1.57144, 1.47096, 1.47487, 1.52237, 1.48634, 1.50428, 1.32104, 1.21188, 0.97869, 0.67098, 0.48750, 0.39348, 0.28059, 0.29879, 0.47290, 0.46978, 0.48738, 0.46835, 0.37016, 0.33192, 0.05043, -0.37600, -0.77606, -1.18320, -1.58768, -1.89987, -2.08950, -2.30991, -2.56929, -2.80590, -3.13094, -3.27534, -3.41685, -3.54463, -3.62830, -3.58859, -3.58197, -3.54751, -3.76146, -3.91517, -4.01492, -4.16464, -4.20859, -4.22674, -4.35811, -4.48615, -4.56429, -4.79518, -4.91059, -4.82561, -4.84342, -4.79523, -4.70976, -4.63800, -4.48058, -4.41456, -4.37757, -4.27830, -4.06604, -3.83575, -3.61572, -3.31421, -3.11058, -2.81980, -2.51027, -2.21182, -1.94160, -1.73603, -1.80247, -1.82815, -1.98748, -2.06418, -2.07344, -2.19812, -2.22207, -2.11715, -2.17721, -2.19732, -1.96933, -1.92538, -2.05795, -2.18725, -2.44011, -2.51226, -2.47793, -2.43612, -2.28440, -2.23797, -2.29411, -2.38785, -2.37684, -2.36221, -2.45381, -2.60790, -2.92221, -3.13471, -3.22970, -3.34894, -3.45584, -3.48894, -3.57197, -3.57131, -3.60009, -3.59127, -3.46063, -3.48857, -3.54453, -3.48662, -3.48910, -3.40522, -3.24408, -3.32280, -3.46430, -3.48352, -3.56725, -3.57121, -3.45776, -3.36401, -3.14387, -2.93523, -2.78853, -2.62093, -2.37185, -2.11281, -1.92924, -1.70227, -1.59202, -1.55935, -1.56494, -1.56212, -1.51064, -1.30932, -1.16605, -1.06765, -0.98786, -0.92835, -0.81547, -0.76141, -0.58663, -0.31036, -0.23893, -0.26990, -0.11243, -0.00095, -0.00315, 0.06048, -0.02611, -0.14931, -0.20477, -0.27433, -0.17525, 0.00392, 0.13357, 0.19705, 0.24521, 0.38529, 0.47154, 0.53083, 0.46785, 0.39721, 0.50089, 0.60740, 0.72217, 0.84947, 0.84118, 0.64212, 0.38379, 0.09190, 0.06300, 0.10087, 0.09301, 0.13439, 0.11728, 0.07638, 0.20324, 0.27734, 0.19910, 0.29656, 0.37167, 0.39698, 0.47978, 0.51279, 0.58452, 0.62421, 0.59337, 0.59298, 0.65958, 0.71920, 0.63289, 0.62190, 0.61642, 0.59050, 0.69302, 0.65352, 0.61107, 0.59619, 0.45932, 0.23108, 0.08512, -0.23230, -0.45072, -0.67816, -0.86651, -0.85835, -0.85469, -0.90126, -0.82696, -0.84159, -1.08367, -1.20549, -1.20490, -1.17546, -1.05666, -1.09936, -1.17955, -1.18107, -1.27064, -1.43811, -1.62098, -1.71200, -1.81301, -1.83922, -1.83849, -1.95222, -1.95384, -2.09196, -2.22956, -2.23605, -2.13394, -2.05589, -2.01401, -2.18488, -2.18674, -2.16989, -2.21858, -2.20781, -2.19245, -2.24675, -2.16267, -2.05999, -2.15539, -2.12763, -2.04697, -2.05455, -1.91284, -1.78074, -1.67923, -1.64686, -1.79660, -1.97068, -2.11885, -2.11188, -2.08590, -2.06118, -1.92830, -1.89331, -1.77053, -1.64579, -1.44379, -1.24019, -1.09384, -1.07478, -0.96132, -0.91395, -0.67976, -0.37753, +-1.05109, -1.02905, -1.02977, -0.90879, -0.72102, -0.63768, -0.68221, -0.64573, -0.61609, -0.53361, -0.51096, -0.48565, -0.44766, -0.35442, -0.25990, -0.43064, -0.70758, -0.83495, -1.09140, -1.32742, -1.38069, -1.49414, -1.58067, -1.61946, -1.83235, -1.91656, -1.94025, -1.93614, -1.95406, -2.12090, -2.20667, -2.35366, -2.55328, -2.66631, -2.65775, -2.56680, -2.48389, -2.44424, -2.36899, -2.30173, -2.28104, -2.19015, -1.95247, -1.72663, -1.52296, -1.38053, -1.13526, -1.07948, -1.15015, -1.16817, -1.17966, -1.09001, -0.83908, -0.82345, -0.91917, -0.86468, -0.79504, -0.66416, -0.51495, -0.39752, -0.20866, -0.19620, -0.15280, -0.14182, -0.01104, 0.05380, -0.02311, -0.04824, 0.04383, 0.06252, 0.05154, 0.03823, 0.08552, 0.12196, 0.18939, 0.08903, -0.06142, -0.25989, -0.32764, -0.50216, -0.65115, -0.64365, -0.65862, -0.82685, -0.86050, -0.94411, -0.99533, -0.82987, -0.71867, -0.67139, -0.51935, -0.51411, -0.44137, -0.33520, -0.07095, 0.16209, 0.33539, 0.53785, 0.70089, 0.77205, 0.84189, 0.84176, 0.90019, 0.93569, 0.97251, 0.93297, 1.04937, 1.11126, 1.17812, 1.09282, 1.21412, 1.31391, 1.37235, 1.43221, 1.42951, 1.34515, 1.45255, 1.50284, 1.44811, 1.52504, 1.59726, 1.49384, 1.48183, 1.43561, 1.57679, 1.56334, 1.48621, 1.46957, 1.56107, 1.66369, 1.70598, 1.69923, 1.79736, 1.79599, 1.77383, 1.68516, 1.62288, 1.49591, 1.45503, 1.35160, 1.38901, 1.31165, 1.28558, 1.02631, 0.63260, 0.39081, 0.32251, 0.23047, 0.25119, 0.29842, 0.27797, 0.29603, 0.30863, 0.21683, 0.17196, -0.14485, -0.46587, -0.81116, -1.13820, -1.51639, -1.84956, -2.09110, -2.27505, -2.53936, -2.73755, -3.02165, -3.25576, -3.44621, -3.54388, -3.73542, -3.72811, -3.72030, -3.64084, -3.80829, -3.97264, -4.13185, -4.31860, -4.35477, -4.31293, -4.36561, -4.37403, -4.50741, -4.75481, -4.84134, -4.72042, -4.74324, -4.73180, -4.72015, -4.56184, -4.42209, -4.36627, -4.30085, -4.16973, -3.97718, -3.75069, -3.56837, -3.27417, -2.99786, -2.77305, -2.52025, -2.10921, -1.84688, -1.65461, -1.74480, -1.79655, -1.90355, -1.90764, -1.91477, -2.10557, -2.16912, -2.01972, -2.06297, -2.07476, -1.99088, -2.02209, -2.13770, -2.17827, -2.27385, -2.28190, -2.34615, -2.31558, -2.17032, -2.06787, -2.01574, -2.05892, -2.12060, -2.18908, -2.33717, -2.50927, -2.73213, -2.91547, -3.01009, -2.99826, -3.15288, -3.32095, -3.48228, -3.50528, -3.49658, -3.46518, -3.34223, -3.40211, -3.50505, -3.43556, -3.41791, -3.33393, -3.30381, -3.50820, -3.66881, -3.63428, -3.68002, -3.70971, -3.68951, -3.57437, -3.31671, -3.08570, -2.83756, -2.61692, -2.38284, -2.21160, -2.08052, -1.83143, -1.59554, -1.51046, -1.56768, -1.50786, -1.43884, -1.28908, -1.14636, -1.06805, -0.94818, -0.83099, -0.75052, -0.82080, -0.77594, -0.51441, -0.40884, -0.36096, -0.14329, -0.07953, -0.11353, -0.04607, -0.05610, -0.09315, -0.15125, -0.23090, -0.16467, -0.07722, 0.09389, 0.18143, 0.23196, 0.35425, 0.46751, 0.56595, 0.55495, 0.46121, 0.46128, 0.61212, 0.74327, 0.73266, 0.70203, 0.51700, 0.29653, 0.08643, 0.10215, 0.08235, 0.00376, 0.04767, 0.08343, 0.11253, 0.22708, 0.16602, 0.04967, 0.18626, 0.33953, 0.42453, 0.48987, 0.46908, 0.53541, 0.43088, 0.40552, 0.46187, 0.56099, 0.59259, 0.48776, 0.45335, 0.54010, 0.60953, 0.67212, 0.65162, 0.65619, 0.52297, 0.32859, 0.02539, -0.15584, -0.40141, -0.56110, -0.75883, -0.86944, -0.81389, -0.80992, -0.86777, -0.76629, -0.83284, -1.03633, -1.12991, -1.12796, -1.10465, -1.01712, -1.14125, -1.18830, -1.25882, -1.29367, -1.40050, -1.63131, -1.85488, -2.01637, -2.06444, -1.99815, -2.04686, -2.06563, -2.13414, -2.17682, -2.26856, -2.18566, -2.16769, -2.16135, -2.28110, -2.22917, -2.21876, -2.31544, -2.33996, -2.29958, -2.29856, -2.15737, -2.13055, -2.22604, -2.19455, -2.08928, -2.10363, -1.94535, -1.80080, -1.55138, -1.49694, -1.57989, -1.66772, -1.75721, -1.77393, -1.77308, -1.80744, -1.63729, -1.53648, -1.50185, -1.45306, -1.23766, -1.14539, -1.04608, -1.02493, -0.84768, -0.75177, -0.55851, -0.35566, +-1.16892, -1.05494, -1.03059, -0.95836, -0.75357, -0.58691, -0.60833, -0.56576, -0.52070, -0.43397, -0.38481, -0.42155, -0.41935, -0.28767, -0.23285, -0.45869, -0.74164, -0.89836, -1.16866, -1.40794, -1.55250, -1.67558, -1.70808, -1.69722, -1.87264, -1.97616, -1.97368, -1.90283, -1.88978, -2.01915, -2.12543, -2.32958, -2.52742, -2.58318, -2.53321, -2.49700, -2.43392, -2.29151, -2.15622, -2.11208, -2.14805, -2.11891, -1.88097, -1.70248, -1.55374, -1.42358, -1.26387, -1.26421, -1.30561, -1.29253, -1.26703, -1.11276, -0.93184, -0.98345, -1.08470, -1.08249, -1.02457, -0.93028, -0.79272, -0.62691, -0.39000, -0.31129, -0.23002, -0.21643, -0.08181, 0.01025, -0.07826, -0.19499, -0.13738, -0.05983, -0.06647, -0.13379, -0.14252, -0.14985, -0.07057, -0.21217, -0.42946, -0.58636, -0.69068, -0.92931, -1.06077, -1.02654, -0.97104, -0.98337, -0.99657, -1.08599, -1.07667, -0.93063, -0.80150, -0.78198, -0.68100, -0.66506, -0.57511, -0.41902, -0.08724, 0.17797, 0.36475, 0.65085, 0.87416, 0.86619, 0.85942, 0.91133, 1.02059, 1.06776, 1.09756, 0.99311, 1.09994, 1.17357, 1.22541, 1.23469, 1.37090, 1.41717, 1.44311, 1.45233, 1.40398, 1.36101, 1.43859, 1.43603, 1.41162, 1.45595, 1.56090, 1.44898, 1.40933, 1.38716, 1.51937, 1.50562, 1.44630, 1.45926, 1.60311, 1.79086, 1.88881, 1.82050, 1.84213, 1.88658, 1.89255, 1.76106, 1.65244, 1.47220, 1.41529, 1.30904, 1.29471, 1.27390, 1.30564, 1.04721, 0.64915, 0.39450, 0.27626, 0.20707, 0.19928, 0.15504, 0.10959, 0.04990, 0.06056, -0.02291, -0.03864, -0.28543, -0.56217, -0.82838, -1.06607, -1.41968, -1.75834, -1.95684, -2.08723, -2.38105, -2.66817, -2.98027, -3.21211, -3.41978, -3.52519, -3.73884, -3.73337, -3.71604, -3.73487, -3.92265, -4.08570, -4.29573, -4.46732, -4.43949, -4.37811, -4.32429, -4.24269, -4.39175, -4.58208, -4.67741, -4.56958, -4.61549, -4.62955, -4.56684, -4.34691, -4.18245, -4.10677, -4.07358, -4.00449, -3.82189, -3.60311, -3.50701, -3.33446, -3.06294, -2.80021, -2.55381, -2.15086, -1.90423, -1.65395, -1.64496, -1.72379, -1.80592, -1.77563, -1.83095, -2.03615, -2.09434, -2.02263, -2.06996, -2.06544, -2.04034, -2.01779, -2.12115, -2.15721, -2.19249, -2.16511, -2.20087, -2.14275, -1.97818, -1.82111, -1.73581, -1.80935, -1.90532, -1.96361, -2.11608, -2.33431, -2.51941, -2.61705, -2.70412, -2.75574, -3.00239, -3.21281, -3.36089, -3.43179, -3.42892, -3.37495, -3.29156, -3.35210, -3.42488, -3.38478, -3.36322, -3.27048, -3.32901, -3.53469, -3.67362, -3.64708, -3.70726, -3.79525, -3.82302, -3.71296, -3.45700, -3.19789, -2.93206, -2.70834, -2.43635, -2.21272, -2.07671, -1.90895, -1.67924, -1.46232, -1.44101, -1.38570, -1.33675, -1.20310, -1.02797, -0.97766, -0.90902, -0.82867, -0.85171, -0.99654, -0.94002, -0.67151, -0.54639, -0.43198, -0.20414, -0.08926, -0.08589, -0.04293, -0.03355, -0.07708, -0.12618, -0.19858, -0.18424, -0.09254, 0.11305, 0.22890, 0.32661, 0.51447, 0.63313, 0.59700, 0.49384, 0.44589, 0.45014, 0.57287, 0.67183, 0.61970, 0.63471, 0.47977, 0.25364, 0.10701, 0.10506, 0.04374, -0.01133, 0.04850, 0.11903, 0.23274, 0.31007, 0.20903, 0.08001, 0.14932, 0.29956, 0.33733, 0.35998, 0.35295, 0.40074, 0.28186, 0.24429, 0.26639, 0.36273, 0.49706, 0.46936, 0.37015, 0.41425, 0.55360, 0.64784, 0.60913, 0.55398, 0.31581, 0.10610, -0.19729, -0.38496, -0.52742, -0.67085, -0.87554, -0.89316, -0.77457, -0.77940, -0.78893, -0.70714, -0.79067, -0.93783, -1.09031, -1.13043, -1.15327, -1.07795, -1.14581, -1.17723, -1.24627, -1.30305, -1.49746, -1.80344, -2.00571, -2.14262, -2.24738, -2.23256, -2.22178, -2.16209, -2.18409, -2.21210, -2.33064, -2.23443, -2.20887, -2.24737, -2.29979, -2.20921, -2.21950, -2.30136, -2.31853, -2.32359, -2.27618, -2.13589, -2.16789, -2.24133, -2.25233, -2.14841, -2.18772, -2.03721, -1.82990, -1.50076, -1.30712, -1.26169, -1.30163, -1.37513, -1.34753, -1.31964, -1.42000, -1.38154, -1.32923, -1.29603, -1.26896, -1.05824, -0.99303, -0.90403, -0.86016, -0.70612, -0.57489, -0.41751, -0.31062, +-1.39040, -1.20376, -1.03144, -0.98094, -0.87480, -0.65523, -0.62746, -0.56029, -0.44262, -0.33152, -0.24963, -0.35225, -0.41706, -0.26854, -0.20957, -0.47669, -0.77746, -0.96111, -1.27021, -1.49626, -1.67477, -1.74528, -1.72628, -1.69319, -1.75918, -1.83882, -1.85066, -1.77078, -1.79120, -1.92434, -2.07533, -2.37534, -2.61571, -2.64872, -2.42973, -2.36487, -2.38263, -2.18358, -2.02844, -2.03402, -2.07800, -2.06937, -1.84044, -1.74563, -1.71045, -1.58947, -1.45293, -1.45556, -1.45472, -1.36871, -1.34064, -1.20583, -1.12902, -1.19402, -1.23680, -1.25245, -1.12474, -1.03401, -0.95319, -0.77636, -0.51889, -0.38909, -0.26204, -0.30934, -0.25704, -0.22786, -0.23768, -0.34382, -0.38368, -0.30063, -0.29785, -0.39995, -0.40365, -0.40260, -0.32970, -0.56569, -0.91184, -1.03464, -1.07836, -1.23016, -1.33048, -1.30185, -1.25982, -1.19990, -1.16246, -1.15973, -1.06222, -0.98465, -0.83424, -0.80904, -0.79556, -0.79331, -0.69952, -0.51949, -0.08308, 0.18214, 0.35857, 0.61007, 0.89086, 0.88746, 0.75790, 0.80729, 0.96495, 1.00833, 1.06915, 1.00566, 1.12422, 1.18812, 1.18870, 1.30555, 1.50340, 1.57007, 1.51073, 1.44137, 1.34677, 1.32122, 1.41851, 1.44739, 1.49124, 1.48914, 1.64673, 1.60695, 1.52623, 1.47281, 1.53504, 1.45677, 1.44380, 1.45551, 1.62971, 1.79568, 1.97529, 1.99114, 1.92289, 1.93876, 1.94646, 1.71401, 1.55616, 1.40742, 1.39708, 1.34357, 1.22796, 1.18854, 1.26133, 1.10822, 0.74315, 0.48716, 0.27904, 0.11376, 0.05553, -0.01356, -0.03606, -0.16305, -0.14294, -0.12989, -0.09509, -0.28303, -0.51552, -0.78633, -0.97400, -1.35923, -1.71744, -1.97560, -2.06536, -2.27570, -2.65548, -3.02920, -3.24485, -3.49603, -3.58720, -3.70295, -3.67401, -3.66868, -3.88991, -4.16601, -4.28205, -4.38425, -4.48592, -4.41409, -4.37712, -4.32271, -4.16507, -4.23808, -4.29969, -4.41199, -4.35983, -4.35968, -4.37434, -4.26897, -3.99499, -3.87214, -3.77822, -3.78791, -3.78637, -3.72061, -3.57071, -3.49443, -3.45927, -3.25309, -2.89872, -2.62491, -2.25014, -1.98812, -1.68780, -1.55818, -1.67661, -1.77893, -1.72801, -1.76053, -1.95254, -2.01751, -2.04621, -2.17198, -2.16783, -2.11478, -1.93200, -1.97894, -2.01490, -1.96225, -1.93823, -1.98759, -1.91003, -1.78899, -1.61154, -1.53903, -1.65961, -1.83906, -1.92427, -1.99056, -2.20371, -2.36718, -2.36984, -2.47668, -2.65452, -2.93980, -3.11675, -3.18032, -3.30674, -3.39223, -3.34321, -3.22858, -3.22858, -3.24859, -3.24572, -3.32015, -3.29595, -3.39609, -3.50391, -3.57488, -3.57958, -3.61729, -3.74469, -3.82107, -3.70997, -3.50990, -3.28471, -3.06026, -2.87019, -2.59216, -2.30105, -2.02436, -1.90881, -1.78823, -1.48691, -1.38175, -1.33009, -1.25314, -1.11226, -0.91762, -0.93019, -0.98646, -0.95811, -1.00018, -1.13365, -1.03310, -0.73591, -0.63450, -0.50455, -0.27778, -0.07632, -0.00719, -0.00328, 0.05435, 0.01571, -0.05703, -0.11162, -0.14616, -0.08866, 0.12290, 0.25226, 0.40265, 0.59342, 0.75622, 0.59682, 0.33971, 0.35069, 0.41499, 0.50562, 0.57931, 0.52521, 0.59321, 0.46794, 0.19816, 0.09280, 0.09256, 0.03406, 0.00174, 0.08039, 0.14653, 0.26897, 0.31306, 0.26480, 0.20241, 0.21239, 0.37896, 0.37022, 0.28836, 0.27799, 0.31829, 0.20800, 0.18757, 0.10232, 0.12855, 0.25854, 0.37233, 0.31074, 0.25537, 0.39553, 0.50072, 0.41641, 0.31277, 0.04200, -0.15043, -0.44026, -0.65504, -0.69217, -0.76216, -0.88162, -0.85689, -0.73471, -0.79621, -0.83780, -0.78806, -0.82524, -0.87865, -1.06954, -1.10593, -1.13435, -1.11076, -1.11032, -1.09176, -1.21202, -1.33462, -1.72340, -2.11341, -2.32993, -2.34720, -2.38729, -2.48556, -2.47718, -2.32991, -2.30330, -2.28716, -2.36123, -2.26984, -2.26329, -2.38624, -2.38762, -2.21088, -2.13634, -2.20185, -2.20438, -2.24933, -2.22783, -2.11375, -2.17744, -2.21889, -2.27059, -2.12831, -2.07019, -1.92523, -1.71262, -1.34850, -1.09296, -0.90687, -0.93855, -1.01454, -1.05843, -1.01313, -1.07719, -1.21780, -1.27619, -1.21948, -1.20635, -0.96194, -0.81270, -0.69163, -0.61518, -0.57601, -0.49598, -0.35727, -0.23920, +-1.51447, -1.32798, -1.12475, -1.00130, -0.88388, -0.72244, -0.61471, -0.49592, -0.40641, -0.33225, -0.31236, -0.38630, -0.34803, -0.23908, -0.22200, -0.48958, -0.80267, -0.99028, -1.22147, -1.36285, -1.58234, -1.74187, -1.71832, -1.64527, -1.67047, -1.68469, -1.68885, -1.72981, -1.82087, -1.93539, -2.03653, -2.22146, -2.46744, -2.56903, -2.36037, -2.24255, -2.18789, -2.04382, -1.93328, -1.97660, -2.08795, -2.11284, -1.95991, -1.91558, -1.84802, -1.72681, -1.63970, -1.65640, -1.68638, -1.57020, -1.48480, -1.34034, -1.35637, -1.47707, -1.41010, -1.27753, -1.11161, -1.04890, -1.03637, -0.98916, -0.76911, -0.54061, -0.34473, -0.30823, -0.33132, -0.43323, -0.45534, -0.54028, -0.56295, -0.59298, -0.63271, -0.68042, -0.69454, -0.71531, -0.72284, -1.01763, -1.29735, -1.36781, -1.35356, -1.37374, -1.48629, -1.53234, -1.52873, -1.40371, -1.31472, -1.29984, -1.15351, -1.03026, -0.93780, -0.91456, -0.88865, -0.92718, -0.86237, -0.64342, -0.16580, 0.22434, 0.43702, 0.56672, 0.74398, 0.67718, 0.58661, 0.60168, 0.75895, 0.86803, 0.95000, 0.97437, 1.08812, 1.09597, 1.14660, 1.35924, 1.54897, 1.62824, 1.47958, 1.35491, 1.32703, 1.45704, 1.62029, 1.57838, 1.58524, 1.63741, 1.77026, 1.77165, 1.68604, 1.50803, 1.41414, 1.32203, 1.36148, 1.50574, 1.71864, 1.77503, 1.93952, 2.00308, 2.04779, 2.02953, 1.94657, 1.69693, 1.48860, 1.35023, 1.38780, 1.35353, 1.24271, 1.19214, 1.17104, 1.08295, 0.76601, 0.48827, 0.24682, 0.05942, -0.05277, -0.18801, -0.21258, -0.21042, -0.19472, -0.17021, -0.09877, -0.28938, -0.52750, -0.76560, -0.96120, -1.27501, -1.58584, -1.94318, -2.08029, -2.32765, -2.61823, -2.94308, -3.22626, -3.50197, -3.64191, -3.72570, -3.70796, -3.79867, -4.08199, -4.29224, -4.35704, -4.29678, -4.31043, -4.30496, -4.31778, -4.23269, -4.02214, -4.04685, -4.08462, -4.10527, -4.11026, -4.10957, -4.06124, -3.94676, -3.74582, -3.65702, -3.55421, -3.46272, -3.39954, -3.48156, -3.49311, -3.55076, -3.49290, -3.25247, -2.88803, -2.55919, -2.26374, -2.08734, -1.82639, -1.68746, -1.72200, -1.71155, -1.68247, -1.71528, -1.89612, -2.00939, -2.05967, -2.12684, -2.09968, -2.07456, -1.89918, -1.80903, -1.78488, -1.73823, -1.74295, -1.83800, -1.83989, -1.73868, -1.54123, -1.42438, -1.44998, -1.66591, -1.85996, -2.02105, -2.15648, -2.18199, -2.19355, -2.30031, -2.54702, -2.83703, -2.92477, -2.92702, -3.02912, -3.13540, -3.18809, -3.11709, -3.06402, -3.06654, -3.08828, -3.17616, -3.19662, -3.33029, -3.44866, -3.43465, -3.46001, -3.59007, -3.74555, -3.81517, -3.76234, -3.61822, -3.41083, -3.15452, -2.83253, -2.51553, -2.20313, -1.93032, -1.83463, -1.73144, -1.53453, -1.40296, -1.32432, -1.26382, -1.12034, -0.99210, -1.02440, -1.03770, -1.01402, -1.04275, -1.13216, -1.06805, -0.80168, -0.64659, -0.44270, -0.25012, -0.13989, -0.02966, 0.02776, 0.06591, 0.04792, -0.02020, -0.09308, -0.12273, -0.07787, 0.10152, 0.33692, 0.54076, 0.64008, 0.70706, 0.49609, 0.32994, 0.37421, 0.51165, 0.59528, 0.52415, 0.41447, 0.43197, 0.34881, 0.19329, 0.10978, 0.05762, 0.00136, -0.04339, 0.02392, 0.12211, 0.26201, 0.25043, 0.15671, 0.18299, 0.29814, 0.41654, 0.36400, 0.25135, 0.19166, 0.23433, 0.21561, 0.19994, 0.11541, 0.04703, 0.01433, 0.11511, 0.08190, 0.10531, 0.18660, 0.22419, 0.13402, -0.02878, -0.25590, -0.41601, -0.68450, -0.82285, -0.78965, -0.82347, -0.83431, -0.84069, -0.82163, -0.90464, -0.90704, -0.87987, -0.96365, -0.98965, -1.02269, -1.05515, -1.12943, -1.16534, -1.20352, -1.18496, -1.32196, -1.53932, -1.93582, -2.27630, -2.50181, -2.44523, -2.48648, -2.56714, -2.59528, -2.46972, -2.34940, -2.32493, -2.38315, -2.34100, -2.39817, -2.46100, -2.37320, -2.18229, -2.04599, -2.12155, -2.14668, -2.13584, -2.03472, -1.96288, -2.14543, -2.22915, -2.15940, -1.98080, -1.83340, -1.66843, -1.54277, -1.25974, -0.97338, -0.69799, -0.58539, -0.58391, -0.74469, -0.79513, -0.94215, -1.07170, -1.13788, -1.11527, -1.07029, -0.87213, -0.70122, -0.53714, -0.46027, -0.44238, -0.39210, -0.33085, -0.19066, +-1.64512, -1.43881, -1.24409, -1.01103, -0.78127, -0.65891, -0.50194, -0.41914, -0.40930, -0.35086, -0.40413, -0.46488, -0.35894, -0.35345, -0.41284, -0.60176, -0.75740, -0.88352, -1.12382, -1.27759, -1.50078, -1.69956, -1.77094, -1.77961, -1.80722, -1.76251, -1.64988, -1.68565, -1.86253, -1.91801, -1.98767, -2.09370, -2.23084, -2.33083, -2.24324, -2.13357, -2.00411, -1.95513, -1.88384, -1.98169, -2.15390, -2.12448, -2.02106, -2.01209, -1.90875, -1.84635, -1.85131, -1.88348, -1.90670, -1.79954, -1.77654, -1.65459, -1.62146, -1.65160, -1.54850, -1.40839, -1.26655, -1.23874, -1.20788, -1.16660, -1.06574, -0.77364, -0.58443, -0.55689, -0.48445, -0.52625, -0.56451, -0.64970, -0.66121, -0.84086, -0.93743, -0.99143, -1.07250, -1.06941, -1.13450, -1.38817, -1.51219, -1.57443, -1.60346, -1.60591, -1.70509, -1.72058, -1.80879, -1.72076, -1.58938, -1.52315, -1.37670, -1.28414, -1.24621, -1.18639, -1.03337, -0.92182, -0.92076, -0.69873, -0.31758, -0.01101, 0.27382, 0.43152, 0.53889, 0.43767, 0.45026, 0.45920, 0.63772, 0.79933, 0.87911, 1.06171, 1.19967, 1.17393, 1.24002, 1.37991, 1.44106, 1.49927, 1.39769, 1.42050, 1.43498, 1.62823, 1.84348, 1.80234, 1.74503, 1.71540, 1.74289, 1.73538, 1.65453, 1.54654, 1.36185, 1.31372, 1.37707, 1.44962, 1.67141, 1.74803, 1.89666, 1.96099, 2.12148, 2.05953, 1.90855, 1.71657, 1.47480, 1.38446, 1.41225, 1.30840, 1.20038, 1.11962, 0.94399, 0.83127, 0.56944, 0.39781, 0.15270, -0.06354, -0.19106, -0.26975, -0.25304, -0.22057, -0.25516, -0.28070, -0.26432, -0.34721, -0.60394, -0.78627, -0.94967, -1.32604, -1.58009, -1.86166, -2.00374, -2.30904, -2.48167, -2.74547, -3.09052, -3.38361, -3.66917, -3.79082, -3.80957, -3.97091, -4.17585, -4.24737, -4.31495, -4.19771, -4.16669, -4.12747, -4.18928, -4.16950, -3.97671, -3.92072, -3.95485, -3.97511, -3.99468, -3.95363, -3.84918, -3.61449, -3.50872, -3.45954, -3.33017, -3.29955, -3.21463, -3.28476, -3.34798, -3.45349, -3.29269, -3.02390, -2.75806, -2.48356, -2.34039, -2.21536, -1.97971, -1.87413, -1.81834, -1.69934, -1.70692, -1.75971, -1.91819, -1.93445, -1.92777, -1.98008, -1.95398, -1.93726, -1.85711, -1.80558, -1.79891, -1.75194, -1.75600, -1.74916, -1.76971, -1.66830, -1.40720, -1.36668, -1.35491, -1.46542, -1.66444, -1.91156, -2.00203, -1.96734, -2.04100, -2.10750, -2.33086, -2.52419, -2.49760, -2.50013, -2.61101, -2.74880, -2.95794, -3.02920, -3.00343, -2.93182, -2.93436, -3.03444, -3.02860, -3.09095, -3.22000, -3.29719, -3.47544, -3.71334, -3.89519, -3.87047, -3.81141, -3.73402, -3.46168, -3.18486, -2.79300, -2.36869, -2.03528, -1.86622, -1.77979, -1.65453, -1.62023, -1.52733, -1.48668, -1.44532, -1.21576, -1.11760, -1.13400, -1.03632, -0.99135, -1.02796, -1.09071, -1.03868, -0.82632, -0.71040, -0.47626, -0.24253, -0.16707, -0.11905, -0.10453, -0.06838, -0.03126, 0.00411, 0.03235, -0.00372, 0.07414, 0.14261, 0.26995, 0.48581, 0.57061, 0.57986, 0.46476, 0.50307, 0.53684, 0.68396, 0.68799, 0.46082, 0.36254, 0.30026, 0.21102, 0.15415, 0.03636, -0.07453, -0.08943, -0.07960, 0.02151, 0.03818, 0.10923, 0.08849, -0.00510, 0.00067, 0.08877, 0.16034, 0.15497, 0.17838, 0.24705, 0.24765, 0.27455, 0.16056, -0.05142, -0.14096, -0.23435, -0.20064, -0.22304, -0.08677, -0.06052, -0.07764, -0.18303, -0.36202, -0.40613, -0.50053, -0.74606, -0.85401, -0.88836, -0.98710, -0.95472, -0.94183, -0.90854, -1.04772, -1.04829, -0.97782, -1.02573, -1.08974, -1.10683, -1.14966, -1.23499, -1.28809, -1.29553, -1.39871, -1.54478, -1.80856, -2.22404, -2.40882, -2.51520, -2.42328, -2.49048, -2.49489, -2.55549, -2.50336, -2.37880, -2.41562, -2.40498, -2.34427, -2.39339, -2.36876, -2.26786, -2.17927, -2.06213, -2.10554, -2.04258, -2.02680, -1.92326, -1.86445, -2.01669, -2.10100, -2.03500, -1.88306, -1.71738, -1.56478, -1.35411, -1.16667, -0.88762, -0.59021, -0.52033, -0.43468, -0.52855, -0.62224, -0.84386, -0.86507, -0.88315, -0.90708, -0.86842, -0.82821, -0.66300, -0.46072, -0.37729, -0.31439, -0.28090, -0.33485, -0.20436, +-1.74580, -1.61638, -1.36006, -1.00808, -0.72359, -0.56609, -0.40872, -0.35414, -0.39060, -0.39606, -0.44066, -0.52844, -0.56950, -0.60839, -0.61176, -0.67908, -0.78884, -0.93610, -1.17252, -1.37678, -1.63798, -1.83032, -1.84698, -1.83633, -1.89897, -1.86328, -1.67476, -1.58812, -1.78527, -1.93956, -1.96292, -1.94788, -2.04349, -2.21319, -2.18585, -2.04806, -1.97846, -1.97209, -1.89304, -1.98511, -2.15323, -2.13239, -2.01150, -1.99907, -2.01647, -2.02258, -2.00260, -1.99359, -2.06896, -2.10610, -2.12596, -2.01251, -1.94128, -1.90489, -1.73812, -1.57868, -1.52046, -1.56354, -1.50795, -1.36468, -1.30154, -1.14467, -0.97611, -0.84820, -0.67383, -0.68987, -0.70619, -0.68897, -0.76657, -1.01488, -1.13712, -1.23397, -1.37195, -1.42755, -1.49551, -1.63058, -1.73842, -1.81789, -1.81261, -1.82520, -1.95653, -2.04613, -2.13235, -2.05622, -1.94068, -1.87989, -1.67137, -1.49796, -1.48519, -1.43631, -1.20935, -0.93375, -0.91396, -0.85095, -0.60248, -0.29076, 0.00141, 0.13726, 0.25716, 0.30932, 0.35418, 0.39898, 0.64144, 0.85460, 0.98584, 1.21055, 1.37875, 1.42699, 1.39691, 1.36904, 1.40100, 1.48103, 1.42459, 1.41680, 1.45650, 1.66297, 1.86919, 1.81907, 1.79592, 1.80922, 1.75434, 1.65949, 1.55635, 1.58016, 1.48707, 1.37927, 1.38847, 1.48182, 1.67747, 1.69955, 1.79022, 1.92925, 2.04914, 1.93293, 1.78954, 1.66367, 1.45728, 1.34133, 1.28912, 1.15911, 0.97659, 0.81448, 0.67066, 0.61119, 0.39151, 0.15587, -0.05114, -0.22773, -0.34599, -0.40016, -0.31890, -0.19881, -0.27739, -0.42003, -0.49911, -0.49259, -0.66642, -0.86270, -1.02090, -1.31740, -1.52323, -1.80517, -1.99840, -2.21406, -2.36385, -2.64347, -2.97351, -3.25116, -3.58636, -3.79590, -3.88841, -3.99158, -4.14273, -4.21632, -4.22180, -4.05220, -4.01678, -4.09012, -4.17761, -4.17648, -4.01614, -3.96183, -3.96819, -3.86983, -3.81813, -3.77566, -3.66419, -3.33763, -3.18760, -3.20209, -3.15640, -3.12980, -3.04144, -3.14170, -3.25874, -3.23280, -3.00687, -2.79973, -2.63339, -2.48194, -2.41958, -2.31673, -2.10756, -1.92447, -1.82981, -1.76214, -1.69906, -1.66055, -1.77131, -1.84611, -1.84992, -1.89323, -1.87825, -1.91549, -1.91178, -1.83024, -1.82405, -1.79399, -1.77460, -1.66719, -1.58456, -1.48596, -1.29458, -1.24365, -1.18414, -1.28285, -1.51470, -1.66810, -1.69685, -1.71768, -1.79267, -1.80226, -1.92283, -2.02865, -2.01737, -2.01484, -2.17883, -2.47476, -2.74137, -2.84298, -2.85060, -2.86357, -2.91272, -2.95062, -2.85944, -2.88464, -3.02960, -3.12087, -3.37552, -3.71300, -3.94902, -3.90193, -3.76820, -3.71427, -3.50954, -3.16704, -2.69545, -2.29563, -2.09965, -1.99120, -1.84977, -1.75823, -1.77200, -1.70560, -1.68359, -1.63104, -1.38065, -1.21320, -1.17165, -1.10584, -1.01739, -0.97047, -0.98674, -1.02641, -0.95887, -0.85915, -0.60810, -0.33595, -0.24385, -0.17222, -0.14638, -0.12883, -0.07752, 0.03879, 0.21638, 0.20018, 0.16642, 0.17646, 0.25483, 0.36123, 0.34086, 0.37562, 0.47024, 0.58082, 0.60705, 0.72416, 0.66678, 0.39979, 0.27748, 0.21085, 0.15153, 0.02961, -0.12101, -0.14343, -0.06137, -0.06950, -0.08753, -0.12728, -0.10362, -0.14123, -0.26208, -0.26931, -0.17840, -0.14456, -0.11652, 0.03775, 0.28604, 0.30805, 0.17647, -0.04414, -0.23460, -0.34045, -0.51220, -0.51347, -0.42562, -0.30201, -0.29597, -0.31201, -0.40504, -0.52015, -0.48404, -0.51432, -0.67111, -0.87024, -1.02528, -1.10834, -1.04181, -1.01784, -1.07065, -1.21475, -1.20144, -1.10553, -1.14733, -1.19956, -1.18130, -1.26778, -1.39059, -1.43924, -1.38329, -1.53143, -1.80978, -2.10345, -2.38368, -2.47824, -2.59187, -2.52940, -2.48182, -2.46248, -2.52285, -2.48682, -2.38987, -2.44002, -2.43098, -2.32175, -2.23938, -2.24043, -2.23173, -2.14005, -1.98727, -1.98548, -2.00678, -2.01232, -1.91706, -1.85933, -1.97670, -1.99140, -1.85857, -1.75213, -1.67983, -1.57163, -1.23579, -0.99925, -0.82080, -0.60409, -0.50890, -0.39649, -0.49055, -0.62180, -0.73638, -0.72250, -0.74868, -0.78197, -0.76048, -0.78709, -0.67551, -0.48527, -0.29838, -0.20060, -0.22500, -0.25440, -0.07000, +-1.65796, -1.59114, -1.44465, -1.08817, -0.74046, -0.54208, -0.40973, -0.42461, -0.51782, -0.56960, -0.61518, -0.77594, -0.90858, -0.87754, -0.85971, -0.85687, -0.83240, -0.92934, -1.15522, -1.39362, -1.67698, -1.85483, -1.85345, -1.87614, -1.92596, -1.85011, -1.75637, -1.72936, -1.79961, -1.92657, -1.95413, -1.84397, -1.84050, -2.03270, -2.18378, -2.13213, -2.10894, -2.11647, -2.01206, -2.07541, -2.21354, -2.24402, -2.20911, -2.24814, -2.31767, -2.26993, -2.23826, -2.19888, -2.14354, -2.14711, -2.20599, -2.12533, -2.05233, -1.97657, -1.78649, -1.68724, -1.72312, -1.78796, -1.79653, -1.73136, -1.59639, -1.44270, -1.35046, -1.13237, -0.79710, -0.70974, -0.79823, -0.83345, -0.96088, -1.19416, -1.29661, -1.45009, -1.67075, -1.77777, -1.86624, -1.95545, -2.04033, -1.99496, -1.97416, -2.06704, -2.15128, -2.19799, -2.28727, -2.23202, -2.14471, -2.10614, -1.89270, -1.72518, -1.70673, -1.57098, -1.34493, -1.15650, -1.06120, -0.97867, -0.88952, -0.58597, -0.25046, -0.03500, 0.06548, 0.15901, 0.26459, 0.34091, 0.57857, 0.81702, 0.97914, 1.21523, 1.39091, 1.48758, 1.45741, 1.48637, 1.49038, 1.47866, 1.48153, 1.55249, 1.60881, 1.80108, 1.94816, 1.87056, 1.88743, 1.89790, 1.78307, 1.70283, 1.56448, 1.50613, 1.56027, 1.60240, 1.52807, 1.57732, 1.73879, 1.80768, 1.78693, 1.77603, 1.78372, 1.65176, 1.53316, 1.44975, 1.25899, 1.13210, 0.98641, 0.78076, 0.53081, 0.45091, 0.37366, 0.28078, 0.13674, -0.01810, -0.19321, -0.32955, -0.41173, -0.42042, -0.28716, -0.17230, -0.31658, -0.48323, -0.65546, -0.80123, -0.91580, -0.91962, -1.04915, -1.27215, -1.41782, -1.66237, -2.00530, -2.32301, -2.50390, -2.78089, -3.05534, -3.26092, -3.53335, -3.72982, -3.89697, -4.01298, -4.15605, -4.10481, -4.00465, -3.90131, -3.90489, -3.95846, -4.02738, -4.02331, -3.88818, -3.84301, -3.82726, -3.67670, -3.57731, -3.45283, -3.33389, -3.18090, -3.05337, -2.89698, -2.87747, -2.90864, -2.83076, -2.83111, -2.97490, -2.99382, -2.77206, -2.59392, -2.50960, -2.47816, -2.49232, -2.39401, -2.22488, -2.03007, -1.93879, -1.81517, -1.63967, -1.60357, -1.67175, -1.65817, -1.64154, -1.69345, -1.68685, -1.76196, -1.81738, -1.76377, -1.80749, -1.71795, -1.61422, -1.57592, -1.49478, -1.28650, -1.16543, -1.14477, -1.05009, -1.05076, -1.25457, -1.40588, -1.35335, -1.35046, -1.42140, -1.41382, -1.47865, -1.50826, -1.53544, -1.61651, -1.92027, -2.27738, -2.47914, -2.65849, -2.73776, -2.72602, -2.76364, -2.73667, -2.54832, -2.53087, -2.69482, -2.86906, -3.23028, -3.54564, -3.73960, -3.84348, -3.80464, -3.61061, -3.38691, -3.07646, -2.58984, -2.18174, -2.11240, -2.20751, -2.11312, -2.02852, -2.05240, -2.00529, -1.99724, -1.92732, -1.68589, -1.49734, -1.42859, -1.30654, -1.05953, -0.98808, -1.00634, -1.01365, -0.98192, -0.89377, -0.62627, -0.30157, -0.16046, -0.08070, -0.12167, -0.15767, -0.08658, -0.01914, 0.09016, 0.19482, 0.20866, 0.16871, 0.27501, 0.36139, 0.26936, 0.18164, 0.32040, 0.50644, 0.56601, 0.64251, 0.50873, 0.24398, 0.14285, 0.06549, -0.01389, -0.15587, -0.19527, -0.15258, -0.03770, 0.01978, -0.02228, -0.15455, -0.17218, -0.18730, -0.32138, -0.40962, -0.42329, -0.39713, -0.26018, -0.08742, 0.10269, 0.23256, 0.12319, -0.21473, -0.36998, -0.42733, -0.58443, -0.70553, -0.66141, -0.56252, -0.56430, -0.57408, -0.63817, -0.66951, -0.56347, -0.57964, -0.71424, -0.97577, -1.09460, -1.18503, -1.18620, -1.08252, -1.06053, -1.18357, -1.17659, -1.13173, -1.22188, -1.29721, -1.36402, -1.50355, -1.54150, -1.56728, -1.58762, -1.69011, -1.91128, -2.27257, -2.45084, -2.42917, -2.46367, -2.53458, -2.58109, -2.54312, -2.54598, -2.50949, -2.45297, -2.52027, -2.50354, -2.36512, -2.20961, -2.23708, -2.18608, -2.11662, -2.01509, -1.88795, -1.83338, -1.88331, -1.81039, -1.71979, -1.78154, -1.74468, -1.62397, -1.56577, -1.48993, -1.43783, -1.22663, -0.95688, -0.70722, -0.61869, -0.55875, -0.44484, -0.47175, -0.67411, -0.83237, -0.78543, -0.78150, -0.81449, -0.80358, -0.87316, -0.78543, -0.62760, -0.40203, -0.26000, -0.14786, -0.08516, 0.03654, +-1.55189, -1.40379, -1.28140, -1.02648, -0.72646, -0.56006, -0.55556, -0.62410, -0.67859, -0.67619, -0.77198, -0.96370, -1.02896, -0.97111, -1.01397, -1.07500, -1.00247, -1.02570, -1.19718, -1.36977, -1.61670, -1.80757, -1.86136, -1.87855, -1.86179, -1.74192, -1.76384, -1.89288, -1.91315, -1.95856, -1.98821, -1.95751, -1.91019, -1.96729, -2.09788, -2.11335, -2.13587, -2.16493, -2.18001, -2.24344, -2.28566, -2.31905, -2.43761, -2.55562, -2.53832, -2.48529, -2.50236, -2.45564, -2.22071, -2.08066, -2.15962, -2.10816, -2.08955, -2.06637, -1.93703, -1.86395, -1.88150, -1.89869, -1.92960, -1.98284, -1.83023, -1.64265, -1.56192, -1.40607, -1.07570, -0.85150, -0.90741, -1.00493, -1.14951, -1.26065, -1.36513, -1.55697, -1.76433, -1.84168, -1.98271, -2.18700, -2.21588, -2.09549, -2.11057, -2.25740, -2.26672, -2.21346, -2.30533, -2.25602, -2.19860, -2.21766, -2.10559, -1.98037, -1.88566, -1.65968, -1.46932, -1.47233, -1.38722, -1.23542, -1.12551, -0.87225, -0.55994, -0.22201, -0.08348, 0.04258, 0.18535, 0.33308, 0.48730, 0.68706, 0.90832, 1.17708, 1.35414, 1.41741, 1.55725, 1.69349, 1.58859, 1.40349, 1.36897, 1.51532, 1.57427, 1.77553, 1.90516, 1.82725, 1.84994, 1.86637, 1.81050, 1.79694, 1.67245, 1.47051, 1.50946, 1.62099, 1.55495, 1.50234, 1.58952, 1.80368, 1.80689, 1.69195, 1.55564, 1.47204, 1.32647, 1.12846, 0.93294, 0.85664, 0.69965, 0.40371, 0.23922, 0.27877, 0.18166, -0.01422, -0.12496, -0.15363, -0.32882, -0.43059, -0.46228, -0.45044, -0.36570, -0.34066, -0.47350, -0.57814, -0.72483, -1.00318, -1.14297, -1.07550, -1.15371, -1.35433, -1.51717, -1.68690, -2.06460, -2.42724, -2.70361, -2.94155, -3.15457, -3.32574, -3.41457, -3.47744, -3.66498, -3.92762, -4.05343, -3.87659, -3.77568, -3.80219, -3.83891, -3.76935, -3.77537, -3.71208, -3.56071, -3.52612, -3.53087, -3.44801, -3.34595, -3.16971, -3.03827, -3.05762, -2.97710, -2.67851, -2.56239, -2.62041, -2.61829, -2.47688, -2.53371, -2.61026, -2.51633, -2.33101, -2.26171, -2.33400, -2.34461, -2.19269, -2.02635, -1.95181, -1.83768, -1.59757, -1.45204, -1.53337, -1.60684, -1.48823, -1.47552, -1.54866, -1.53110, -1.58083, -1.63135, -1.63525, -1.68209, -1.56139, -1.42141, -1.44880, -1.42764, -1.20380, -1.09203, -1.07852, -1.06258, -0.97601, -0.99848, -1.02284, -0.89318, -0.82238, -0.88931, -0.99488, -1.07335, -1.03546, -1.06379, -1.30604, -1.67777, -1.92990, -2.11750, -2.42151, -2.59692, -2.54230, -2.54190, -2.51139, -2.32557, -2.31529, -2.51868, -2.80281, -3.14252, -3.31575, -3.40125, -3.59277, -3.68796, -3.42693, -3.17208, -2.96934, -2.66320, -2.29238, -2.17153, -2.28538, -2.26104, -2.18253, -2.17793, -2.21704, -2.20833, -2.07508, -1.83597, -1.72394, -1.64978, -1.38047, -1.10548, -1.13555, -1.20878, -1.11434, -0.97649, -0.85948, -0.58144, -0.27773, -0.16370, -0.13214, -0.19604, -0.24205, -0.16478, -0.14180, -0.19227, -0.06563, 0.05542, 0.07092, 0.16247, 0.21861, 0.16678, 0.02677, 0.09098, 0.28536, 0.42678, 0.43982, 0.29967, 0.16748, 0.17700, 0.08610, -0.04324, -0.07235, -0.04752, -0.09865, -0.10815, -0.02915, -0.02589, -0.21068, -0.19955, -0.15781, -0.30022, -0.50039, -0.59320, -0.50886, -0.31387, -0.21331, -0.19440, -0.02984, -0.02375, -0.30118, -0.48154, -0.53169, -0.55567, -0.67319, -0.68255, -0.65579, -0.65171, -0.72061, -0.78407, -0.71076, -0.55343, -0.61206, -0.81266, -0.94685, -0.96739, -1.13613, -1.29686, -1.21415, -1.09287, -1.17490, -1.14861, -1.17321, -1.35302, -1.51334, -1.69684, -1.82302, -1.73917, -1.67683, -1.75264, -1.85279, -2.02538, -2.39196, -2.61505, -2.58701, -2.46321, -2.52333, -2.60092, -2.55950, -2.44648, -2.42522, -2.44583, -2.47279, -2.40613, -2.31690, -2.30143, -2.27568, -2.16400, -2.17965, -2.15488, -1.91330, -1.68514, -1.73154, -1.63101, -1.48109, -1.54328, -1.58089, -1.52665, -1.41962, -1.24319, -1.15130, -1.09032, -0.87730, -0.61463, -0.57941, -0.62541, -0.63031, -0.58126, -0.74097, -0.89084, -0.88819, -0.85074, -0.91419, -0.95640, -0.93156, -0.73302, -0.57003, -0.47341, -0.28479, -0.02862, 0.04601, 0.03130, +-1.38122, -1.22615, -1.04961, -0.90177, -0.78526, -0.74656, -0.83001, -0.81070, -0.85355, -0.90374, -0.96977, -1.02555, -1.05083, -1.08964, -1.07076, -1.09825, -1.14060, -1.21297, -1.35823, -1.46300, -1.61815, -1.81848, -1.87887, -1.80869, -1.83390, -1.75091, -1.72589, -1.83961, -1.88267, -1.95729, -1.95029, -1.96195, -2.01410, -2.04066, -2.04309, -2.04699, -2.15503, -2.26733, -2.44432, -2.45367, -2.46897, -2.57671, -2.66933, -2.67005, -2.60098, -2.67494, -2.64029, -2.45221, -2.22496, -2.15507, -2.27614, -2.25203, -2.23402, -2.24343, -2.14180, -1.97286, -1.96143, -1.97504, -1.92959, -1.93426, -1.81232, -1.68737, -1.56713, -1.41981, -1.29487, -1.14916, -1.14445, -1.20353, -1.36433, -1.40572, -1.52964, -1.60576, -1.74423, -1.91993, -2.07457, -2.25622, -2.28316, -2.29306, -2.26971, -2.22829, -2.21890, -2.23890, -2.35467, -2.34203, -2.28256, -2.31521, -2.27014, -2.08219, -1.97892, -1.83203, -1.63980, -1.63333, -1.57697, -1.44604, -1.23697, -0.89820, -0.69359, -0.44385, -0.32287, -0.14186, -0.02334, 0.20083, 0.34112, 0.62249, 0.91496, 1.06272, 1.23637, 1.39587, 1.62716, 1.60790, 1.42876, 1.33036, 1.23371, 1.25606, 1.28284, 1.46981, 1.67239, 1.68500, 1.70119, 1.81807, 1.81761, 1.74549, 1.69889, 1.56145, 1.52077, 1.53646, 1.49022, 1.51644, 1.52243, 1.68334, 1.68484, 1.59880, 1.34932, 1.25927, 1.03958, 0.79348, 0.61712, 0.43969, 0.30215, 0.14627, 0.13010, 0.08770, -0.04961, -0.11730, -0.20336, -0.30593, -0.51030, -0.63229, -0.63348, -0.58836, -0.59142, -0.55720, -0.65676, -0.82314, -0.87746, -1.03760, -1.17640, -1.21561, -1.34605, -1.44180, -1.64415, -1.83429, -2.16929, -2.44762, -2.80388, -3.03404, -3.23142, -3.32403, -3.25191, -3.37764, -3.59843, -3.80946, -3.84462, -3.74857, -3.71955, -3.61893, -3.55614, -3.49769, -3.49586, -3.42115, -3.24500, -3.15922, -3.19248, -3.12533, -3.06889, -3.04483, -2.91505, -2.83905, -2.69999, -2.39613, -2.24776, -2.16209, -2.18113, -2.08343, -2.13289, -2.20602, -2.25224, -2.10978, -2.04634, -2.09389, -1.99556, -1.91635, -1.82341, -1.73540, -1.51934, -1.32858, -1.31090, -1.32381, -1.34358, -1.32216, -1.40493, -1.53374, -1.50644, -1.44793, -1.44713, -1.40244, -1.39500, -1.43685, -1.37629, -1.31474, -1.23897, -1.01264, -0.89745, -0.77077, -0.78353, -0.76294, -0.71870, -0.59894, -0.48452, -0.46623, -0.56305, -0.72334, -0.73797, -0.75730, -0.88257, -1.11153, -1.32858, -1.54817, -1.86138, -2.12662, -2.26370, -2.30956, -2.38219, -2.44418, -2.37010, -2.36071, -2.57568, -2.82314, -3.00442, -3.16167, -3.21076, -3.27055, -3.30758, -3.07137, -2.90452, -2.75734, -2.59115, -2.39599, -2.29443, -2.31642, -2.32028, -2.30563, -2.30361, -2.38343, -2.26000, -2.11607, -1.98645, -1.87002, -1.67563, -1.39199, -1.29704, -1.32634, -1.30638, -1.20972, -1.05960, -0.93067, -0.68375, -0.42537, -0.38493, -0.37231, -0.33167, -0.38390, -0.33649, -0.23740, -0.25591, -0.16074, -0.06206, 0.03044, 0.11313, -0.00239, -0.11635, -0.23471, -0.20470, -0.07735, 0.10561, 0.13756, 0.20871, 0.21790, 0.18550, 0.14400, 0.14203, 0.18708, 0.08742, -0.02318, -0.02965, -0.03293, -0.11150, -0.30021, -0.26913, -0.17951, -0.31265, -0.53775, -0.56385, -0.50926, -0.43370, -0.36061, -0.32719, -0.16642, -0.13027, -0.26763, -0.35981, -0.49103, -0.52734, -0.59718, -0.58231, -0.65352, -0.66976, -0.79992, -0.77452, -0.65270, -0.64743, -0.72903, -0.82478, -0.81857, -0.90875, -1.09902, -1.20494, -1.25451, -1.27610, -1.36313, -1.32884, -1.31515, -1.48862, -1.71095, -1.86427, -2.00076, -1.98020, -1.83619, -1.83496, -1.97141, -2.19437, -2.52982, -2.68959, -2.74603, -2.64271, -2.62291, -2.56969, -2.55677, -2.41483, -2.43173, -2.40800, -2.36314, -2.41745, -2.42970, -2.44457, -2.36010, -2.36485, -2.40153, -2.20708, -1.91559, -1.71069, -1.71655, -1.58946, -1.38193, -1.42181, -1.54386, -1.43497, -1.26844, -1.11944, -0.93158, -0.79347, -0.62176, -0.46664, -0.48574, -0.50370, -0.65123, -0.69936, -0.83930, -0.90708, -1.00617, -1.00609, -1.11107, -1.09275, -0.88753, -0.70380, -0.55460, -0.44572, -0.24179, -0.11723, -0.10461, 0.00904, +-1.19922, -1.02263, -0.84249, -0.75838, -0.80183, -0.84180, -0.95366, -1.02408, -1.04011, -1.01818, -1.08133, -1.15389, -1.18929, -1.17192, -1.05061, -1.08207, -1.18162, -1.24183, -1.38371, -1.53704, -1.69277, -1.84387, -1.91641, -1.86825, -1.84195, -1.77584, -1.76144, -1.79321, -1.83081, -1.94136, -1.93589, -1.93086, -1.99831, -2.00913, -1.97153, -1.98568, -2.15010, -2.32547, -2.57577, -2.73826, -2.78188, -2.75591, -2.74605, -2.74921, -2.71262, -2.73415, -2.58716, -2.37708, -2.22820, -2.21083, -2.34652, -2.38843, -2.38675, -2.33183, -2.23013, -2.09225, -1.98998, -1.95911, -1.94139, -1.87942, -1.75338, -1.67689, -1.56377, -1.41921, -1.41191, -1.34505, -1.32558, -1.36633, -1.50912, -1.54833, -1.64178, -1.78720, -1.91612, -1.99695, -2.11866, -2.34039, -2.43840, -2.45112, -2.33052, -2.21001, -2.21788, -2.24361, -2.34700, -2.41492, -2.40858, -2.40064, -2.35154, -2.21472, -2.08714, -1.94629, -1.82423, -1.76142, -1.68522, -1.57789, -1.34665, -0.96406, -0.77989, -0.60221, -0.52375, -0.36945, -0.24591, 0.03576, 0.29688, 0.50973, 0.76113, 0.99238, 1.20153, 1.32679, 1.45515, 1.35027, 1.21959, 1.18403, 1.04974, 1.04876, 1.07680, 1.18705, 1.38152, 1.48542, 1.53170, 1.61316, 1.66340, 1.65011, 1.59125, 1.50808, 1.43642, 1.38426, 1.34228, 1.44414, 1.47460, 1.58643, 1.56574, 1.45790, 1.19270, 1.04501, 0.84420, 0.48806, 0.21429, 0.08654, 0.01406, -0.09907, -0.12355, -0.18187, -0.23299, -0.20178, -0.30668, -0.42243, -0.59716, -0.77834, -0.84144, -0.77857, -0.77858, -0.80630, -0.89690, -1.00721, -1.07984, -1.17438, -1.26858, -1.38242, -1.58098, -1.63840, -1.79285, -1.91034, -2.13573, -2.38338, -2.71942, -2.95521, -3.07929, -3.20469, -3.23044, -3.34575, -3.50155, -3.67790, -3.72967, -3.66946, -3.58450, -3.37585, -3.27141, -3.18647, -3.14485, -3.09739, -2.96622, -2.85241, -2.84128, -2.86459, -2.90641, -2.88427, -2.79520, -2.65015, -2.40820, -2.11065, -1.97228, -1.80495, -1.76099, -1.67502, -1.70900, -1.80634, -1.90185, -1.83949, -1.74565, -1.80595, -1.80169, -1.72252, -1.58271, -1.49306, -1.32979, -1.20312, -1.14834, -1.07480, -1.11651, -1.15090, -1.23549, -1.39368, -1.41910, -1.32282, -1.23535, -1.20473, -1.22535, -1.28070, -1.31609, -1.25347, -1.07326, -0.76630, -0.60973, -0.43517, -0.40359, -0.38014, -0.30798, -0.18117, -0.13421, -0.22683, -0.31387, -0.47799, -0.59199, -0.62366, -0.69942, -0.90072, -1.10138, -1.34747, -1.64188, -1.82831, -1.98411, -2.09922, -2.18537, -2.33877, -2.44088, -2.48430, -2.62645, -2.82704, -2.96596, -3.03977, -3.07687, -3.09072, -3.01154, -2.77901, -2.67563, -2.57297, -2.45786, -2.35307, -2.27878, -2.28595, -2.31865, -2.36637, -2.35195, -2.40368, -2.36895, -2.22921, -2.02157, -1.88120, -1.72416, -1.51967, -1.43547, -1.38928, -1.36001, -1.29387, -1.11560, -0.98259, -0.83729, -0.67652, -0.63935, -0.63985, -0.59446, -0.51276, -0.42219, -0.33563, -0.26216, -0.14873, -0.09050, -0.01071, 0.02612, -0.18284, -0.32174, -0.41793, -0.39811, -0.30196, -0.10603, 0.01711, 0.09449, 0.15402, 0.23819, 0.26850, 0.27877, 0.29585, 0.21590, 0.13711, 0.08176, 0.00584, -0.06513, -0.21106, -0.24578, -0.22125, -0.32192, -0.52460, -0.59289, -0.53119, -0.48776, -0.48915, -0.40634, -0.23652, -0.20152, -0.27808, -0.30649, -0.43584, -0.46399, -0.49431, -0.48982, -0.58998, -0.63020, -0.72418, -0.79599, -0.74013, -0.68533, -0.73318, -0.83492, -0.85162, -0.92952, -1.04501, -1.13804, -1.31227, -1.40315, -1.48392, -1.49141, -1.45662, -1.55701, -1.78143, -1.98924, -2.10368, -2.07643, -2.00092, -1.99572, -2.15167, -2.39663, -2.70432, -2.80159, -2.85542, -2.76839, -2.68529, -2.57552, -2.55499, -2.45311, -2.42013, -2.47078, -2.48933, -2.49575, -2.54156, -2.64784, -2.62822, -2.63757, -2.55446, -2.25617, -1.99349, -1.77632, -1.70007, -1.59186, -1.41485, -1.40041, -1.49354, -1.42971, -1.24250, -1.03155, -0.85843, -0.67266, -0.48942, -0.38908, -0.44726, -0.45953, -0.63070, -0.71763, -0.83960, -0.91399, -1.04450, -1.10008, -1.14445, -1.15630, -0.98183, -0.71812, -0.51242, -0.43605, -0.35243, -0.32226, -0.26207, -0.02607, +-1.12091, -0.86514, -0.68776, -0.69614, -0.87753, -0.91649, -0.92630, -1.03804, -1.09438, -1.04734, -1.13662, -1.28898, -1.33989, -1.19826, -1.02979, -1.10738, -1.22389, -1.27002, -1.34767, -1.54586, -1.77066, -1.88754, -1.90651, -1.81291, -1.73815, -1.76193, -1.85971, -1.85928, -1.87730, -2.02973, -2.04221, -2.01073, -2.04725, -2.01686, -1.99907, -2.09163, -2.30546, -2.45535, -2.60785, -2.84979, -2.99515, -2.86461, -2.75066, -2.79894, -2.80361, -2.66206, -2.43038, -2.38538, -2.34572, -2.27498, -2.24705, -2.26017, -2.29371, -2.17383, -2.04935, -1.94156, -1.83663, -1.87308, -1.97680, -1.89676, -1.68875, -1.63085, -1.57709, -1.51970, -1.60994, -1.56500, -1.51164, -1.51715, -1.62955, -1.66162, -1.68103, -1.86106, -2.04011, -2.05333, -2.08289, -2.27305, -2.43640, -2.44757, -2.29408, -2.27309, -2.32381, -2.33314, -2.32985, -2.35660, -2.45616, -2.43509, -2.34160, -2.20759, -2.07692, -2.00208, -1.98591, -1.89070, -1.73825, -1.65060, -1.49829, -1.20229, -1.04038, -0.86599, -0.75976, -0.62625, -0.50159, -0.13952, 0.28701, 0.49002, 0.64484, 0.94958, 1.22079, 1.25511, 1.23597, 1.15303, 1.15270, 1.04801, 0.87796, 0.88202, 0.94173, 1.03179, 1.08096, 1.19909, 1.30371, 1.43972, 1.59750, 1.62157, 1.47864, 1.33932, 1.28039, 1.21607, 1.17534, 1.30820, 1.36062, 1.40761, 1.33321, 1.16401, 0.89370, 0.73036, 0.65765, 0.38549, -0.01585, -0.21335, -0.24458, -0.32852, -0.39875, -0.46250, -0.37600, -0.36697, -0.54054, -0.65698, -0.75687, -0.88363, -1.07083, -1.03459, -0.96286, -0.92497, -0.97202, -1.07948, -1.30010, -1.48540, -1.52154, -1.63653, -1.85672, -1.93673, -2.05606, -2.08379, -2.19976, -2.44068, -2.73556, -2.89449, -2.88320, -2.96188, -3.12236, -3.23225, -3.24133, -3.33931, -3.40926, -3.38753, -3.23818, -3.12146, -3.12946, -3.04320, -2.92278, -2.73828, -2.62418, -2.51871, -2.45804, -2.51309, -2.61818, -2.59884, -2.59182, -2.46479, -2.13115, -1.85526, -1.77750, -1.62169, -1.52009, -1.40953, -1.34244, -1.37599, -1.51350, -1.55766, -1.41550, -1.36843, -1.48144, -1.50733, -1.28958, -1.14774, -1.07487, -1.02751, -0.88802, -0.85776, -1.03444, -1.11930, -1.12143, -1.12187, -1.17827, -1.12683, -1.01259, -0.96346, -0.98256, -1.01558, -1.14230, -1.18064, -0.92019, -0.51978, -0.35389, -0.22224, -0.16109, -0.07251, 0.04364, 0.12805, 0.09460, -0.02404, 0.00332, -0.01140, -0.20066, -0.35936, -0.42531, -0.63589, -0.92849, -1.24685, -1.46338, -1.61498, -1.84576, -2.01827, -2.09127, -2.21827, -2.44606, -2.57271, -2.61160, -2.66462, -2.73746, -2.77883, -2.89550, -2.98271, -2.80808, -2.53903, -2.43287, -2.35223, -2.34400, -2.36967, -2.32735, -2.32006, -2.40627, -2.52338, -2.41457, -2.29005, -2.32733, -2.29285, -2.02914, -1.84949, -1.77577, -1.67106, -1.49738, -1.38604, -1.46837, -1.48543, -1.32314, -1.11632, -1.01746, -0.96095, -0.87242, -0.81933, -0.72905, -0.53162, -0.47546, -0.50629, -0.36308, -0.14996, -0.13037, -0.14062, -0.19004, -0.39158, -0.46189, -0.48291, -0.46634, -0.42527, -0.20116, 0.05075, 0.10662, 0.10429, 0.27453, 0.45053, 0.50394, 0.46867, 0.44349, 0.36902, 0.14580, 0.00626, 0.00423, 0.01780, -0.02913, -0.17672, -0.29739, -0.44492, -0.49406, -0.42316, -0.39738, -0.48508, -0.44964, -0.29750, -0.27876, -0.32860, -0.37757, -0.50669, -0.45204, -0.39382, -0.42620, -0.56762, -0.58935, -0.56951, -0.68243, -0.76002, -0.65362, -0.59201, -0.69418, -0.81210, -0.91465, -0.98347, -1.21177, -1.48017, -1.55796, -1.55982, -1.51698, -1.53351, -1.60311, -1.80496, -1.96794, -2.01744, -2.05129, -2.15604, -2.22293, -2.29393, -2.49143, -2.75359, -2.85452, -2.94009, -2.87136, -2.77738, -2.70559, -2.71468, -2.61634, -2.41408, -2.40092, -2.55289, -2.59768, -2.65183, -2.82015, -2.87881, -2.83959, -2.59088, -2.37729, -2.23312, -2.01651, -1.81323, -1.59250, -1.47703, -1.35704, -1.32426, -1.26140, -1.09752, -0.88723, -0.79183, -0.68719, -0.48441, -0.37099, -0.45253, -0.55448, -0.76890, -0.86273, -0.95113, -1.05931, -1.21547, -1.23959, -1.11227, -1.02560, -0.98184, -0.79237, -0.52798, -0.45473, -0.46618, -0.47504, -0.33258, -0.13562, +-1.06797, -0.88282, -0.73493, -0.71960, -0.80967, -0.85096, -0.88582, -0.92367, -1.01270, -1.11070, -1.21885, -1.33281, -1.42428, -1.35517, -1.14601, -1.10495, -1.21191, -1.35094, -1.47238, -1.61372, -1.79531, -1.97310, -2.02060, -1.92762, -1.89006, -1.95089, -2.01955, -1.98859, -2.02601, -2.18214, -2.19727, -2.09095, -2.10870, -2.13753, -2.14822, -2.22098, -2.36508, -2.51806, -2.65443, -2.82406, -2.98817, -2.95832, -2.84169, -2.80202, -2.82115, -2.71402, -2.46358, -2.42823, -2.43704, -2.33277, -2.19092, -2.07372, -1.99473, -1.87071, -1.78696, -1.72434, -1.69152, -1.75320, -1.86232, -1.79259, -1.62607, -1.60925, -1.63281, -1.59763, -1.67199, -1.68533, -1.63708, -1.55829, -1.59114, -1.69456, -1.82028, -1.98428, -2.12904, -2.20080, -2.16765, -2.14193, -2.30290, -2.47884, -2.37624, -2.28736, -2.33649, -2.42525, -2.44373, -2.40085, -2.48420, -2.50183, -2.41465, -2.27258, -2.19300, -2.15652, -2.12569, -1.96299, -1.80352, -1.70536, -1.62203, -1.38905, -1.24466, -1.14413, -0.99324, -0.78543, -0.57839, -0.23380, 0.09066, 0.28909, 0.45406, 0.69877, 0.93816, 1.02256, 0.96583, 0.84531, 0.91545, 0.91190, 0.78024, 0.72504, 0.71660, 0.80951, 0.84316, 0.94348, 1.01858, 1.16193, 1.31952, 1.34154, 1.20972, 1.12469, 1.13377, 1.15629, 1.13036, 1.28357, 1.31727, 1.16129, 0.95848, 0.75558, 0.55707, 0.41338, 0.31944, 0.14241, -0.24396, -0.59954, -0.69822, -0.63226, -0.65979, -0.83838, -0.76005, -0.65343, -0.82212, -0.98696, -1.08884, -1.15227, -1.32646, -1.31026, -1.25010, -1.16580, -1.20164, -1.30879, -1.55900, -1.73578, -1.77448, -1.82761, -1.98421, -2.04743, -2.12712, -2.24197, -2.39803, -2.60784, -2.77792, -2.81342, -2.83872, -2.93673, -3.05126, -3.12460, -3.07053, -2.98853, -2.96346, -3.05177, -2.99518, -2.87612, -2.91101, -2.85987, -2.75924, -2.50603, -2.32190, -2.20521, -2.18740, -2.23831, -2.30008, -2.25898, -2.26025, -2.09853, -1.81986, -1.61858, -1.60328, -1.48401, -1.31655, -1.24797, -1.14313, -1.06742, -1.14520, -1.20666, -1.15765, -1.10365, -1.19000, -1.32608, -1.17655, -0.93432, -0.82904, -0.88419, -0.79621, -0.72545, -0.91960, -1.07044, -1.08889, -1.00168, -0.95938, -0.85829, -0.79480, -0.76266, -0.77934, -0.77818, -0.85820, -0.86762, -0.63183, -0.27652, -0.15891, -0.08356, 0.02311, 0.10505, 0.15116, 0.18446, 0.20026, 0.22772, 0.27082, 0.26667, 0.13259, -0.12579, -0.32552, -0.52019, -0.76896, -1.15696, -1.45861, -1.56903, -1.76379, -1.99095, -2.13616, -2.24464, -2.35335, -2.40083, -2.43464, -2.44330, -2.52401, -2.61928, -2.76923, -2.83284, -2.62476, -2.36406, -2.21198, -2.13499, -2.19908, -2.38764, -2.48266, -2.47259, -2.51905, -2.59899, -2.51445, -2.40215, -2.41692, -2.42765, -2.22863, -1.99295, -1.84444, -1.80808, -1.70738, -1.54252, -1.57120, -1.63419, -1.58178, -1.41231, -1.25270, -1.11493, -0.99728, -0.94179, -0.85289, -0.69244, -0.66823, -0.70232, -0.52049, -0.28367, -0.28071, -0.37098, -0.41050, -0.53117, -0.61297, -0.57783, -0.47349, -0.38495, -0.20996, -0.02357, 0.07139, 0.08062, 0.19078, 0.44717, 0.65980, 0.60539, 0.48221, 0.45338, 0.37095, 0.26359, 0.23593, 0.25635, 0.21631, 0.01797, -0.19986, -0.39381, -0.45940, -0.45161, -0.40627, -0.46547, -0.48153, -0.43259, -0.41237, -0.43315, -0.46795, -0.58983, -0.57828, -0.48822, -0.48430, -0.55091, -0.55166, -0.57771, -0.68359, -0.78210, -0.73125, -0.60227, -0.53058, -0.65803, -0.91759, -1.02813, -1.19933, -1.43764, -1.53092, -1.55712, -1.47364, -1.49309, -1.61422, -1.87042, -2.01743, -2.08117, -2.18448, -2.36872, -2.41846, -2.41703, -2.52985, -2.73059, -2.80082, -2.90158, -2.96490, -2.93243, -2.85742, -2.81472, -2.72655, -2.57867, -2.55381, -2.73451, -2.89788, -2.93683, -2.89390, -2.89728, -2.92909, -2.67532, -2.43835, -2.35730, -2.23446, -2.05032, -1.73656, -1.54640, -1.31484, -1.23197, -1.19738, -1.10830, -0.91203, -0.79659, -0.70817, -0.57651, -0.46451, -0.57046, -0.73666, -0.94260, -1.09740, -1.19708, -1.29640, -1.39365, -1.34408, -1.21989, -1.08334, -1.02232, -0.95204, -0.72522, -0.49852, -0.42022, -0.50166, -0.42013, -0.20199, +-0.98544, -0.84035, -0.78769, -0.72513, -0.64942, -0.72163, -0.81502, -0.78596, -0.81076, -0.96120, -1.21887, -1.38516, -1.42791, -1.40802, -1.26147, -1.21932, -1.28776, -1.44390, -1.62503, -1.69699, -1.82263, -2.08184, -2.15367, -2.10629, -2.11416, -2.16648, -2.20099, -2.15665, -2.20173, -2.32589, -2.37094, -2.24311, -2.18140, -2.15423, -2.16943, -2.19172, -2.22579, -2.45135, -2.63972, -2.72737, -2.79894, -2.80244, -2.84803, -2.86779, -2.82635, -2.75201, -2.58233, -2.56307, -2.53082, -2.37907, -2.25034, -2.06627, -1.89250, -1.79091, -1.68994, -1.59276, -1.53449, -1.50758, -1.60184, -1.60273, -1.58249, -1.64912, -1.75628, -1.71530, -1.67219, -1.62414, -1.64409, -1.59625, -1.54983, -1.74675, -1.97103, -2.08547, -2.12463, -2.14916, -2.19268, -2.21679, -2.32092, -2.50085, -2.45101, -2.33270, -2.33252, -2.41477, -2.52958, -2.51658, -2.57452, -2.64853, -2.54644, -2.33919, -2.28634, -2.22047, -2.19882, -2.05946, -1.95207, -1.82593, -1.73705, -1.52038, -1.34854, -1.21220, -1.07574, -0.88558, -0.56657, -0.31454, -0.15554, 0.04342, 0.26513, 0.51517, 0.62662, 0.59556, 0.58893, 0.53215, 0.57886, 0.57983, 0.49160, 0.48330, 0.41963, 0.51436, 0.64242, 0.74055, 0.77811, 0.92326, 0.97512, 0.98872, 0.86994, 0.83676, 0.91674, 1.03313, 1.01506, 1.13364, 1.16110, 0.99450, 0.72765, 0.44098, 0.34542, 0.19411, 0.00003, -0.17332, -0.50836, -0.83607, -1.02299, -1.04637, -1.01766, -1.14428, -1.12420, -1.04319, -1.19051, -1.28973, -1.39611, -1.45268, -1.57947, -1.61129, -1.62451, -1.51126, -1.57434, -1.60407, -1.77362, -1.90341, -1.96550, -1.97692, -2.09120, -2.15352, -2.17668, -2.25425, -2.42817, -2.67605, -2.71731, -2.71040, -2.83369, -2.93699, -2.95357, -2.90689, -2.88363, -2.91300, -2.84912, -2.87373, -2.87447, -2.77721, -2.75567, -2.60420, -2.52571, -2.33080, -2.14382, -2.05778, -2.08628, -2.03073, -2.00537, -1.88994, -1.89414, -1.77806, -1.62225, -1.47841, -1.48184, -1.40812, -1.19040, -1.03265, -0.88461, -0.85397, -0.84997, -0.86627, -0.91880, -0.88062, -0.89583, -0.97736, -0.91842, -0.84973, -0.76009, -0.74207, -0.66407, -0.60973, -0.81173, -0.93766, -1.00967, -0.97733, -0.86492, -0.68992, -0.61780, -0.50906, -0.51319, -0.46604, -0.50245, -0.51009, -0.35890, -0.10190, -0.03916, -0.02439, 0.09586, 0.22731, 0.27224, 0.22113, 0.29185, 0.41903, 0.35958, 0.28067, 0.20116, 0.00394, -0.24724, -0.56083, -0.76618, -1.03640, -1.35955, -1.53676, -1.77509, -1.97384, -2.12933, -2.24673, -2.22047, -2.19508, -2.29009, -2.29132, -2.39969, -2.50226, -2.61876, -2.66348, -2.48152, -2.25140, -2.09823, -2.09725, -2.20080, -2.37086, -2.45063, -2.47687, -2.48311, -2.47869, -2.52630, -2.53726, -2.52854, -2.47377, -2.27126, -2.13836, -2.02274, -1.93145, -1.86948, -1.76186, -1.78967, -1.78481, -1.71244, -1.62447, -1.44454, -1.25451, -1.17761, -1.09961, -0.99660, -0.87775, -0.83299, -0.84837, -0.70024, -0.51674, -0.50752, -0.62954, -0.63511, -0.63736, -0.65171, -0.63747, -0.50424, -0.30364, -0.21625, -0.10628, 0.08705, 0.20950, 0.33317, 0.46094, 0.58848, 0.60480, 0.51376, 0.52355, 0.56181, 0.54236, 0.53320, 0.45363, 0.37653, 0.19556, -0.10189, -0.31666, -0.38187, -0.44926, -0.41818, -0.52763, -0.62245, -0.66017, -0.61361, -0.61070, -0.61197, -0.64541, -0.58301, -0.52622, -0.53437, -0.46253, -0.47961, -0.59011, -0.67643, -0.72825, -0.66655, -0.61919, -0.58934, -0.59225, -0.78103, -0.94288, -1.12260, -1.32175, -1.37917, -1.47950, -1.43233, -1.45329, -1.64596, -1.93140, -2.06530, -2.21045, -2.33113, -2.55716, -2.63409, -2.66273, -2.74229, -2.92334, -2.97429, -3.00649, -3.02303, -2.99606, -2.92398, -2.76489, -2.74111, -2.77900, -2.82927, -2.97908, -3.09361, -3.13547, -3.07980, -2.97621, -2.93648, -2.73947, -2.53869, -2.45337, -2.30858, -2.19036, -1.89274, -1.64122, -1.42454, -1.37768, -1.30539, -1.25085, -0.99481, -0.84295, -0.77312, -0.73382, -0.66566, -0.80858, -1.00239, -1.12253, -1.15591, -1.22449, -1.38052, -1.40612, -1.38985, -1.40299, -1.27993, -1.10297, -0.91563, -0.73426, -0.59465, -0.43968, -0.44116, -0.42390, -0.28243, +-0.99942, -0.84449, -0.81795, -0.80218, -0.66773, -0.61137, -0.60086, -0.51508, -0.60719, -0.82195, -1.10201, -1.28419, -1.30619, -1.28314, -1.28513, -1.40756, -1.48238, -1.59023, -1.70996, -1.75628, -1.87654, -2.09773, -2.14890, -2.11792, -2.21059, -2.28731, -2.26320, -2.19250, -2.29336, -2.44155, -2.44417, -2.36758, -2.26727, -2.16671, -2.15144, -2.20625, -2.23985, -2.38054, -2.51221, -2.52569, -2.59135, -2.65527, -2.73255, -2.78465, -2.74571, -2.69657, -2.66028, -2.75534, -2.69626, -2.52075, -2.37121, -2.17074, -1.95861, -1.75731, -1.57244, -1.39610, -1.31633, -1.24056, -1.25098, -1.27548, -1.42365, -1.66746, -1.79160, -1.80291, -1.72109, -1.61405, -1.67281, -1.75582, -1.80093, -1.92461, -2.05293, -2.02884, -2.01598, -2.08683, -2.17050, -2.29161, -2.40515, -2.49686, -2.45673, -2.44910, -2.42944, -2.48100, -2.60866, -2.64105, -2.73403, -2.76376, -2.59466, -2.29742, -2.24171, -2.19293, -2.10795, -1.97028, -1.94084, -1.94704, -1.81515, -1.65295, -1.49764, -1.31727, -1.21779, -1.11228, -0.83512, -0.53136, -0.33274, -0.04681, 0.17100, 0.27986, 0.31222, 0.23931, 0.24267, 0.25557, 0.28644, 0.15027, 0.10316, 0.17279, 0.14374, 0.25847, 0.40518, 0.57090, 0.64775, 0.81853, 0.78193, 0.69258, 0.62703, 0.66208, 0.77781, 0.81175, 0.84024, 0.87049, 0.81881, 0.70432, 0.45940, 0.15245, 0.03819, -0.04880, -0.21526, -0.35854, -0.68403, -1.06776, -1.28197, -1.36250, -1.34627, -1.39214, -1.37385, -1.45873, -1.60197, -1.63291, -1.68741, -1.70645, -1.85175, -1.86844, -1.85491, -1.69979, -1.76781, -1.84105, -1.89984, -1.93241, -1.97870, -2.11416, -2.21488, -2.30354, -2.33156, -2.31964, -2.43801, -2.67946, -2.75115, -2.72709, -2.79499, -2.77708, -2.73647, -2.75503, -2.78393, -2.87490, -2.80836, -2.74610, -2.72004, -2.76025, -2.73147, -2.50173, -2.39087, -2.20332, -2.09121, -2.00241, -1.95879, -1.75515, -1.61482, -1.52365, -1.50587, -1.42772, -1.38533, -1.41353, -1.41103, -1.33276, -1.13419, -0.89922, -0.73204, -0.76377, -0.79873, -0.74365, -0.69371, -0.55511, -0.51963, -0.65786, -0.68973, -0.72490, -0.67592, -0.59857, -0.46248, -0.51644, -0.76958, -0.86324, -0.92829, -0.89409, -0.80529, -0.59770, -0.41382, -0.17134, -0.09596, -0.10572, -0.15233, -0.13812, -0.03912, 0.04312, 0.05094, 0.04891, 0.08752, 0.20988, 0.27066, 0.20073, 0.19518, 0.30780, 0.29801, 0.28350, 0.27869, 0.06351, -0.23898, -0.57878, -0.75597, -0.93097, -1.17500, -1.46573, -1.81692, -1.98004, -2.08564, -2.13612, -2.07824, -2.04298, -2.10693, -2.10420, -2.22274, -2.37796, -2.45946, -2.40051, -2.20925, -2.10165, -2.07088, -2.14701, -2.32346, -2.42556, -2.41636, -2.43318, -2.49039, -2.48251, -2.49220, -2.49666, -2.46281, -2.45540, -2.31887, -2.21479, -2.12363, -1.99270, -1.87464, -1.85708, -2.00422, -1.96987, -1.84786, -1.74634, -1.59129, -1.44957, -1.36160, -1.22233, -1.05119, -0.95715, -0.88962, -0.81541, -0.68820, -0.64719, -0.73388, -0.81468, -0.85554, -0.80516, -0.72715, -0.68734, -0.57574, -0.36424, -0.20462, -0.03924, 0.25320, 0.39229, 0.45345, 0.51820, 0.56905, 0.62124, 0.63838, 0.66872, 0.64831, 0.67598, 0.69215, 0.56553, 0.42387, 0.22649, 0.00681, -0.10662, -0.11844, -0.27513, -0.39565, -0.56264, -0.69115, -0.80154, -0.85738, -0.80950, -0.82784, -0.79597, -0.64576, -0.58958, -0.64520, -0.57524, -0.48762, -0.53249, -0.54289, -0.58868, -0.60355, -0.58757, -0.59377, -0.54139, -0.59267, -0.74913, -1.06716, -1.28369, -1.34267, -1.44638, -1.42092, -1.47268, -1.60682, -1.82124, -1.93231, -2.18495, -2.41777, -2.63117, -2.73172, -2.84025, -3.05752, -3.18446, -3.22932, -3.21663, -3.14502, -3.09625, -3.04627, -2.90845, -2.83638, -2.89759, -2.94382, -3.08493, -3.24600, -3.25607, -3.18407, -3.03213, -2.89211, -2.72353, -2.69893, -2.61241, -2.41375, -2.26295, -1.97440, -1.78622, -1.61930, -1.58315, -1.42369, -1.32983, -1.10820, -0.90061, -0.80397, -0.81437, -0.92950, -1.06942, -1.27232, -1.34464, -1.22761, -1.22650, -1.40947, -1.48678, -1.46029, -1.48002, -1.31846, -1.08849, -0.90003, -0.71061, -0.59528, -0.44681, -0.38469, -0.35338, -0.39200, +-1.01501, -0.87466, -0.69967, -0.64909, -0.61501, -0.51079, -0.48781, -0.41658, -0.51223, -0.74014, -0.95154, -1.03684, -1.12926, -1.21546, -1.25098, -1.44765, -1.50465, -1.52214, -1.54461, -1.62779, -1.82925, -1.98615, -2.10551, -2.16550, -2.28550, -2.31699, -2.29388, -2.33403, -2.41440, -2.39514, -2.24057, -2.18816, -2.15588, -2.16161, -2.10798, -2.13122, -2.22519, -2.29947, -2.47875, -2.55052, -2.55244, -2.61566, -2.63001, -2.60308, -2.62066, -2.70694, -2.68565, -2.72046, -2.64128, -2.48927, -2.33967, -2.14799, -1.92670, -1.62028, -1.45460, -1.36626, -1.32469, -1.18461, -1.08382, -1.17335, -1.36949, -1.54283, -1.58296, -1.63087, -1.66373, -1.70192, -1.71558, -1.80457, -2.02211, -2.10151, -2.14931, -2.06629, -1.94891, -2.05514, -2.21055, -2.39123, -2.52031, -2.59094, -2.44673, -2.42307, -2.43636, -2.46766, -2.57380, -2.63140, -2.76913, -2.75046, -2.60725, -2.41248, -2.31928, -2.17676, -1.94462, -1.88311, -1.92516, -1.95707, -1.80776, -1.69432, -1.57394, -1.49785, -1.42602, -1.28026, -1.10969, -0.79594, -0.52861, -0.25940, 0.02212, 0.05641, 0.03111, 0.02032, 0.01982, -0.04965, 0.02181, -0.03347, -0.00629, 0.11848, 0.10506, 0.18248, 0.21481, 0.37770, 0.48294, 0.54097, 0.47318, 0.39171, 0.43399, 0.42771, 0.47851, 0.54542, 0.70658, 0.68042, 0.52406, 0.33260, 0.17341, 0.08171, -0.07937, -0.21146, -0.41378, -0.70227, -0.93593, -1.23743, -1.45475, -1.58348, -1.62775, -1.72711, -1.65881, -1.66922, -1.76371, -1.75417, -1.79924, -1.81352, -1.99094, -1.97187, -1.87544, -1.84273, -1.94843, -2.09572, -2.09237, -2.11728, -2.14495, -2.23734, -2.26910, -2.36339, -2.41737, -2.45413, -2.48645, -2.50963, -2.60360, -2.65991, -2.68468, -2.68959, -2.59781, -2.62250, -2.69986, -2.77575, -2.66698, -2.65639, -2.62036, -2.63606, -2.65748, -2.43630, -2.29425, -2.08771, -2.03041, -1.91934, -1.76070, -1.59215, -1.44812, -1.36094, -1.24142, -1.25136, -1.35927, -1.39288, -1.23980, -1.06281, -0.90530, -0.78715, -0.71309, -0.65097, -0.63795, -0.53610, -0.38571, -0.35821, -0.33392, -0.42754, -0.50722, -0.56446, -0.51052, -0.51613, -0.40251, -0.38967, -0.59872, -0.63319, -0.64237, -0.59386, -0.58487, -0.48131, -0.25168, -0.02643, 0.10409, 0.07797, 0.04081, 0.02266, 0.01064, 0.06676, 0.20232, 0.27782, 0.25074, 0.22041, 0.21026, 0.28104, 0.25196, 0.25054, 0.28062, 0.22919, 0.27844, 0.14292, -0.18747, -0.55665, -0.75586, -0.98335, -1.18198, -1.36905, -1.67409, -1.77457, -1.81814, -1.82661, -1.85492, -1.89096, -1.90097, -2.02981, -2.24823, -2.40798, -2.36349, -2.17913, -2.06969, -2.03945, -2.03839, -2.12268, -2.28256, -2.34821, -2.35666, -2.30885, -2.34805, -2.38884, -2.35459, -2.42534, -2.44032, -2.41978, -2.35882, -2.27023, -2.13525, -2.00377, -1.85932, -1.77605, -1.93162, -1.97657, -1.89090, -1.75512, -1.61645, -1.57859, -1.51207, -1.42071, -1.29616, -1.16825, -0.96102, -0.75705, -0.71415, -0.76475, -0.78421, -0.75211, -0.81729, -0.80626, -0.76695, -0.59796, -0.36101, -0.20473, -0.02992, 0.04882, 0.22032, 0.40785, 0.47931, 0.54251, 0.62464, 0.68670, 0.71324, 0.81860, 0.79430, 0.81390, 0.83277, 0.66396, 0.45329, 0.22803, 0.14434, 0.12861, 0.02894, -0.22418, -0.48042, -0.67116, -0.85004, -0.94720, -0.96329, -0.88927, -0.92060, -0.85511, -0.74305, -0.61324, -0.55563, -0.56112, -0.47005, -0.51078, -0.57176, -0.50687, -0.48752, -0.48948, -0.51053, -0.54622, -0.64635, -0.68909, -0.91477, -1.16255, -1.28356, -1.38717, -1.38249, -1.46147, -1.48964, -1.61852, -1.84827, -2.20714, -2.48789, -2.64471, -2.85910, -3.05278, -3.24086, -3.23964, -3.22780, -3.20537, -3.22623, -3.21085, -3.10280, -3.03015, -2.93072, -2.97983, -3.11592, -3.16180, -3.27215, -3.29509, -3.23884, -3.08366, -2.98885, -2.81161, -2.74953, -2.63567, -2.37110, -2.15231, -1.90773, -1.87819, -1.85040, -1.81908, -1.67794, -1.50312, -1.29729, -1.06263, -1.01320, -1.04682, -1.14227, -1.17213, -1.31815, -1.37183, -1.30749, -1.25489, -1.26309, -1.34156, -1.33058, -1.36988, -1.38631, -1.20100, -0.98335, -0.75304, -0.57529, -0.45182, -0.50241, -0.43501, -0.41827, +-1.03915, -0.83591, -0.63487, -0.56481, -0.54624, -0.50442, -0.47268, -0.37801, -0.36866, -0.48158, -0.71061, -0.86975, -0.99861, -1.12348, -1.17489, -1.32811, -1.35558, -1.28018, -1.25856, -1.39735, -1.59011, -1.68564, -1.88568, -2.03055, -2.09807, -2.16330, -2.24033, -2.33647, -2.38186, -2.30165, -2.10960, -2.03423, -2.03611, -2.07453, -2.09050, -2.13771, -2.16298, -2.21349, -2.41639, -2.51692, -2.47766, -2.48803, -2.54025, -2.58585, -2.57271, -2.58660, -2.52308, -2.47121, -2.43203, -2.32692, -2.20397, -2.06690, -1.81446, -1.48543, -1.40525, -1.44023, -1.39678, -1.26318, -1.15064, -1.20084, -1.36768, -1.49280, -1.52471, -1.53672, -1.69234, -1.81451, -1.84111, -1.94827, -2.09187, -2.11579, -2.13346, -2.03333, -1.91770, -1.98375, -2.21609, -2.50950, -2.56512, -2.49397, -2.30099, -2.26483, -2.36324, -2.41520, -2.47750, -2.56691, -2.64206, -2.55328, -2.48311, -2.44579, -2.29077, -2.10034, -1.88723, -1.85752, -1.93150, -2.01128, -1.95481, -1.81421, -1.70133, -1.61868, -1.56603, -1.47791, -1.29145, -1.00557, -0.76495, -0.48998, -0.15718, 0.00287, -0.01247, -0.10546, -0.11804, -0.12430, -0.04214, -0.01413, -0.00878, 0.03029, 0.01450, -0.01367, -0.02990, 0.15616, 0.25726, 0.17920, 0.12627, 0.07674, 0.09870, 0.07652, 0.05359, 0.12127, 0.30050, 0.35637, 0.23322, 0.08936, -0.00012, -0.08035, -0.23187, -0.37609, -0.63468, -0.91709, -1.03847, -1.16757, -1.38119, -1.70948, -1.85538, -1.86191, -1.74621, -1.64876, -1.70279, -1.73217, -1.76275, -1.85369, -1.99657, -1.89918, -1.79134, -1.93859, -2.07678, -2.26455, -2.34694, -2.36295, -2.33486, -2.34228, -2.38318, -2.43009, -2.48471, -2.54189, -2.51744, -2.49813, -2.49416, -2.46265, -2.46670, -2.45694, -2.35828, -2.31247, -2.39554, -2.59473, -2.57339, -2.53730, -2.50460, -2.49900, -2.59008, -2.48506, -2.30940, -2.15347, -2.08526, -1.87213, -1.63257, -1.57072, -1.48007, -1.35219, -1.22756, -1.23971, -1.32635, -1.29749, -1.12574, -0.90832, -0.79078, -0.72407, -0.64680, -0.53794, -0.37035, -0.13106, 0.01778, -0.05044, -0.07741, -0.08268, -0.13722, -0.30529, -0.33791, -0.31378, -0.22314, -0.17541, -0.33902, -0.42239, -0.40581, -0.42465, -0.46235, -0.37915, -0.14311, 0.00883, 0.16484, 0.22054, 0.13260, 0.05271, -0.00330, 0.03447, 0.16533, 0.29136, 0.31969, 0.29536, 0.32415, 0.40059, 0.37230, 0.38724, 0.38808, 0.30913, 0.33879, 0.25356, -0.03778, -0.52714, -0.87728, -1.07616, -1.18891, -1.29145, -1.52721, -1.64845, -1.64204, -1.69065, -1.83415, -1.85785, -1.80646, -2.00996, -2.26012, -2.33697, -2.27857, -2.12281, -2.06167, -2.05957, -2.10088, -2.13290, -2.14816, -2.14489, -2.12054, -2.13159, -2.17766, -2.13051, -2.08542, -2.18514, -2.22614, -2.19069, -2.13659, -2.14977, -2.11599, -1.95475, -1.75303, -1.65159, -1.79083, -1.97725, -1.95057, -1.81273, -1.69376, -1.62128, -1.53797, -1.52698, -1.50746, -1.34243, -1.11036, -0.87517, -0.76778, -0.76445, -0.73818, -0.67672, -0.68598, -0.68796, -0.61547, -0.42294, -0.19312, -0.00557, 0.14326, 0.12287, 0.19343, 0.39834, 0.56783, 0.59273, 0.57136, 0.66683, 0.78527, 0.87020, 0.79634, 0.72463, 0.72232, 0.59464, 0.37219, 0.23088, 0.26826, 0.25004, 0.00469, -0.26773, -0.59973, -0.80482, -0.90866, -0.95980, -0.98918, -0.99974, -0.97041, -0.85165, -0.67564, -0.49880, -0.42410, -0.38071, -0.32271, -0.41455, -0.49539, -0.39741, -0.29852, -0.35938, -0.54763, -0.67596, -0.70869, -0.68085, -0.78608, -1.05549, -1.24892, -1.33372, -1.41376, -1.47120, -1.39037, -1.46524, -1.77146, -2.09556, -2.38175, -2.59373, -2.84601, -3.07740, -3.24925, -3.26511, -3.20568, -3.20158, -3.23409, -3.26777, -3.23648, -3.10834, -2.95147, -3.01498, -3.16432, -3.16052, -3.14857, -3.23550, -3.39968, -3.30095, -3.10239, -2.86905, -2.69661, -2.57866, -2.35985, -2.12722, -2.01746, -2.04567, -2.01435, -1.91726, -1.80755, -1.55546, -1.35596, -1.22916, -1.18819, -1.18916, -1.22263, -1.23614, -1.27739, -1.29905, -1.23818, -1.14118, -1.12723, -1.13474, -1.11010, -1.23020, -1.35829, -1.26832, -0.97068, -0.69847, -0.60024, -0.52685, -0.51801, -0.42612, -0.37039, +-1.13806, -0.93577, -0.72982, -0.64522, -0.60031, -0.62198, -0.53151, -0.35369, -0.31119, -0.36822, -0.45368, -0.64089, -0.89518, -1.01890, -1.10524, -1.22578, -1.18471, -0.98857, -0.92121, -1.06483, -1.29551, -1.41340, -1.57025, -1.67894, -1.69823, -1.86791, -2.02120, -2.08789, -2.14661, -2.13094, -2.05173, -2.03713, -2.08585, -2.11632, -2.10336, -2.13994, -2.12508, -2.21002, -2.35123, -2.37957, -2.39901, -2.47559, -2.47737, -2.48623, -2.51245, -2.41944, -2.33218, -2.31706, -2.29672, -2.13408, -1.99412, -1.91854, -1.76722, -1.57863, -1.49079, -1.47858, -1.34849, -1.25185, -1.16588, -1.14028, -1.31945, -1.50139, -1.59491, -1.62329, -1.83988, -2.00446, -2.02226, -2.09595, -2.10591, -2.12235, -2.12436, -1.99719, -1.99795, -2.10674, -2.24131, -2.38887, -2.45516, -2.34206, -2.17458, -2.20736, -2.33225, -2.32122, -2.31039, -2.41999, -2.48746, -2.45603, -2.34940, -2.27545, -2.05314, -1.93096, -1.85163, -1.82330, -1.90867, -2.02849, -2.02182, -1.89519, -1.81726, -1.74958, -1.65022, -1.57384, -1.36040, -1.18252, -1.02958, -0.69240, -0.37632, -0.16907, -0.06216, -0.02776, -0.11022, -0.09705, -0.02994, -0.07644, -0.15386, -0.16200, -0.14725, -0.23427, -0.24659, -0.13212, 0.00081, -0.05524, -0.08835, -0.19321, -0.25312, -0.22921, -0.24507, -0.20326, -0.06687, 0.02753, -0.02711, -0.16807, -0.22471, -0.36628, -0.52623, -0.69007, -0.94594, -1.04873, -1.11406, -1.25211, -1.41658, -1.62125, -1.84677, -1.84377, -1.71632, -1.66947, -1.72067, -1.70908, -1.64584, -1.76657, -1.89248, -1.90229, -1.83544, -1.99525, -2.09411, -2.28818, -2.44114, -2.41442, -2.34530, -2.32545, -2.37682, -2.43226, -2.50709, -2.67335, -2.66608, -2.65181, -2.55398, -2.42400, -2.40805, -2.29110, -2.19107, -2.18462, -2.24123, -2.30616, -2.40711, -2.45358, -2.42561, -2.49009, -2.60377, -2.50632, -2.26658, -2.17118, -2.13146, -2.00250, -1.72846, -1.59842, -1.43663, -1.26270, -1.19402, -1.13063, -1.10400, -1.05965, -0.95564, -0.83969, -0.78350, -0.76204, -0.60236, -0.38704, -0.09530, 0.19854, 0.30615, 0.30335, 0.26825, 0.19645, 0.13179, 0.08883, 0.00071, -0.02612, 0.06252, 0.03270, -0.16301, -0.28954, -0.25613, -0.33138, -0.37721, -0.35404, -0.08987, 0.13231, 0.35838, 0.49413, 0.34452, 0.24125, 0.19181, 0.13854, 0.15225, 0.22069, 0.28443, 0.28711, 0.37471, 0.45506, 0.44346, 0.48161, 0.42209, 0.38922, 0.38852, 0.19850, -0.09556, -0.43943, -0.77679, -1.00809, -1.08754, -1.26134, -1.56531, -1.71772, -1.62460, -1.66467, -1.82778, -1.90337, -1.85112, -1.93748, -2.06298, -2.05896, -2.09690, -2.04716, -1.98717, -1.99541, -2.05502, -2.05865, -2.02027, -2.04258, -2.00278, -2.00487, -2.03477, -1.93205, -1.92789, -1.98001, -1.97296, -2.00193, -1.98059, -1.90099, -1.86174, -1.81818, -1.66554, -1.64865, -1.83975, -2.03890, -1.92089, -1.75132, -1.65112, -1.58626, -1.52267, -1.47016, -1.44554, -1.29577, -1.18557, -0.98459, -0.74895, -0.65417, -0.63167, -0.61821, -0.63042, -0.66332, -0.58540, -0.38141, -0.20674, -0.01510, 0.08581, 0.09553, 0.25528, 0.42321, 0.57293, 0.66355, 0.66579, 0.66771, 0.79589, 0.80818, 0.62424, 0.49275, 0.55140, 0.54123, 0.35779, 0.23360, 0.21839, 0.21002, -0.01765, -0.22264, -0.58361, -0.78070, -0.78552, -0.83252, -0.91077, -0.98728, -0.95592, -0.83478, -0.64451, -0.41449, -0.32733, -0.22457, -0.21148, -0.31778, -0.33216, -0.33692, -0.34665, -0.37834, -0.48110, -0.67443, -0.65263, -0.62303, -0.76548, -1.01273, -1.13131, -1.14381, -1.29862, -1.41730, -1.42605, -1.43436, -1.62920, -1.82289, -2.14141, -2.44572, -2.66411, -2.90363, -3.11787, -3.22482, -3.25406, -3.31371, -3.37785, -3.36903, -3.32321, -3.12108, -2.97296, -3.07085, -3.15319, -3.19000, -3.22289, -3.28977, -3.37016, -3.37676, -3.16671, -2.88732, -2.74068, -2.64810, -2.44127, -2.20609, -2.18544, -2.20768, -2.20416, -1.98032, -1.77181, -1.44320, -1.26062, -1.22435, -1.14375, -1.11746, -1.16120, -1.21647, -1.26077, -1.27117, -1.23385, -1.08285, -1.06042, -1.05018, -1.08513, -1.26647, -1.31247, -1.23621, -0.97110, -0.67451, -0.42680, -0.39014, -0.36620, -0.27051, -0.33720, +-1.12473, -0.97374, -0.77298, -0.62696, -0.60202, -0.69203, -0.66205, -0.48819, -0.30843, -0.28969, -0.33672, -0.52488, -0.86112, -1.03849, -1.08661, -1.05948, -0.91681, -0.71769, -0.66840, -0.76594, -0.93368, -1.10960, -1.25260, -1.30684, -1.37469, -1.59068, -1.75856, -1.85106, -1.95502, -1.95866, -1.93987, -1.96015, -2.00235, -2.04669, -1.99350, -1.96820, -2.01861, -2.21401, -2.36846, -2.39539, -2.35597, -2.43071, -2.45255, -2.38981, -2.41002, -2.36305, -2.28591, -2.22827, -2.14920, -1.95905, -1.86447, -1.83157, -1.73709, -1.66198, -1.59233, -1.51538, -1.40635, -1.33718, -1.23378, -1.18817, -1.41050, -1.60118, -1.69622, -1.67727, -1.83384, -2.04166, -2.11134, -2.10693, -2.04654, -2.11540, -2.15452, -2.14276, -2.16431, -2.20545, -2.26181, -2.23850, -2.29657, -2.31896, -2.22460, -2.20725, -2.27165, -2.23148, -2.21905, -2.27902, -2.28529, -2.27997, -2.22320, -2.10953, -1.92445, -1.85254, -1.81495, -1.80397, -1.93180, -2.03738, -1.98499, -1.83149, -1.75604, -1.74416, -1.66409, -1.51987, -1.30388, -1.28312, -1.21634, -0.93955, -0.59297, -0.29397, -0.15351, -0.02839, -0.09637, -0.17474, -0.18292, -0.24008, -0.35191, -0.37892, -0.39772, -0.48241, -0.45060, -0.35738, -0.28675, -0.30959, -0.40275, -0.56209, -0.60257, -0.48606, -0.47613, -0.45326, -0.34557, -0.20080, -0.15042, -0.29315, -0.42404, -0.61932, -0.80825, -1.04017, -1.23286, -1.26655, -1.27987, -1.35742, -1.50513, -1.58468, -1.77488, -1.87260, -1.80005, -1.70889, -1.69864, -1.63311, -1.59682, -1.72285, -1.80009, -1.80952, -1.84842, -1.99662, -2.12884, -2.35514, -2.46673, -2.38654, -2.35628, -2.36636, -2.39108, -2.40257, -2.44536, -2.67917, -2.77110, -2.73754, -2.58885, -2.51039, -2.49152, -2.39310, -2.25477, -2.14632, -2.18494, -2.18095, -2.30464, -2.45983, -2.49125, -2.53585, -2.59341, -2.46640, -2.27380, -2.23027, -2.19488, -2.04662, -1.81540, -1.57979, -1.36940, -1.24990, -1.19457, -1.02114, -0.91658, -0.87857, -0.81375, -0.77619, -0.71696, -0.64786, -0.42407, -0.07710, 0.28736, 0.48491, 0.55523, 0.54722, 0.50707, 0.47619, 0.41519, 0.44919, 0.39308, 0.27203, 0.23258, 0.15638, 0.00123, -0.09230, -0.12350, -0.25853, -0.28902, -0.19638, 0.05937, 0.32615, 0.53996, 0.60065, 0.45453, 0.41865, 0.36308, 0.21879, 0.17225, 0.23235, 0.33917, 0.38080, 0.44358, 0.53383, 0.58388, 0.55937, 0.42933, 0.34237, 0.27692, 0.13122, -0.12370, -0.38174, -0.63828, -0.92645, -1.11978, -1.36888, -1.67182, -1.78993, -1.68809, -1.69769, -1.80001, -1.84530, -1.85267, -1.84626, -1.85494, -1.89131, -1.99527, -1.99514, -1.95053, -1.95564, -1.93878, -1.87321, -1.82229, -1.87467, -1.88505, -1.86782, -1.84217, -1.79183, -1.83373, -1.85741, -1.84273, -1.82062, -1.79849, -1.70173, -1.60357, -1.63487, -1.65787, -1.73446, -1.89146, -1.99671, -1.81299, -1.66085, -1.56715, -1.47132, -1.43130, -1.36088, -1.32021, -1.30180, -1.27887, -1.04934, -0.75802, -0.65150, -0.61786, -0.60411, -0.58257, -0.59924, -0.57522, -0.41742, -0.24206, -0.08511, -0.03841, 0.01647, 0.20463, 0.42786, 0.60860, 0.68785, 0.73551, 0.69679, 0.70160, 0.66444, 0.49519, 0.34827, 0.40114, 0.43287, 0.33542, 0.25908, 0.17041, 0.08354, -0.08709, -0.28762, -0.59008, -0.69245, -0.66860, -0.77492, -0.85694, -0.90368, -0.84220, -0.69394, -0.50273, -0.25172, -0.09720, -0.01279, -0.12656, -0.25159, -0.28914, -0.29894, -0.32862, -0.39091, -0.40990, -0.56100, -0.59803, -0.62926, -0.76193, -0.96319, -1.00548, -0.99860, -1.15236, -1.28844, -1.34414, -1.37235, -1.47447, -1.67642, -2.03688, -2.32827, -2.49259, -2.76769, -3.02016, -3.17791, -3.25205, -3.30187, -3.37404, -3.35568, -3.23721, -3.02544, -2.98779, -3.11652, -3.24147, -3.26327, -3.23788, -3.28081, -3.28844, -3.35540, -3.29510, -3.05747, -2.86987, -2.76761, -2.58570, -2.44019, -2.41631, -2.34647, -2.22805, -1.96265, -1.68672, -1.40312, -1.26178, -1.19110, -1.06229, -1.06569, -1.11077, -1.14350, -1.17209, -1.17124, -1.16893, -1.03869, -0.94689, -0.91476, -1.07883, -1.27829, -1.32687, -1.18417, -0.82622, -0.55733, -0.26910, -0.22740, -0.27595, -0.24247, -0.34151, +-1.10331, -0.96233, -0.83375, -0.63436, -0.49202, -0.59212, -0.61725, -0.46524, -0.25231, -0.25000, -0.36273, -0.57814, -0.74565, -0.81252, -0.81414, -0.64305, -0.58015, -0.52440, -0.55771, -0.60121, -0.65908, -0.94689, -1.14828, -1.17423, -1.20668, -1.38916, -1.61188, -1.79259, -1.91708, -1.86572, -1.86968, -1.89788, -1.88715, -1.95000, -1.95279, -1.93628, -1.97605, -2.22433, -2.38427, -2.34834, -2.25582, -2.32737, -2.38324, -2.30321, -2.21191, -2.15773, -2.18405, -2.05890, -1.95874, -1.82936, -1.82320, -1.86939, -1.77264, -1.75969, -1.71452, -1.59915, -1.48345, -1.40345, -1.34446, -1.35904, -1.58788, -1.69596, -1.80427, -1.74600, -1.77652, -2.02531, -2.23666, -2.25923, -2.10729, -2.13761, -2.20484, -2.21834, -2.19431, -2.17412, -2.18176, -2.11934, -2.18420, -2.24069, -2.27855, -2.16372, -2.18241, -2.24797, -2.27517, -2.30721, -2.21465, -2.26173, -2.32162, -2.20977, -2.01518, -1.83948, -1.77999, -1.81164, -1.98710, -2.03444, -1.97822, -1.86927, -1.78344, -1.84380, -1.84693, -1.68132, -1.37079, -1.29332, -1.23308, -0.93802, -0.60236, -0.36601, -0.29940, -0.18585, -0.16941, -0.14533, -0.27614, -0.33939, -0.45213, -0.53222, -0.55952, -0.66126, -0.58102, -0.57311, -0.64658, -0.68546, -0.78187, -0.83083, -0.84269, -0.67877, -0.64700, -0.61968, -0.58638, -0.49783, -0.37073, -0.50978, -0.76598, -1.05439, -1.14679, -1.23878, -1.31981, -1.27317, -1.33956, -1.47968, -1.66632, -1.69610, -1.81149, -1.82696, -1.84180, -1.69180, -1.60853, -1.62315, -1.65675, -1.82396, -1.81014, -1.77005, -1.88965, -2.04151, -2.21014, -2.35872, -2.45360, -2.42440, -2.49947, -2.55012, -2.56293, -2.56621, -2.52360, -2.70856, -2.87368, -2.89578, -2.71570, -2.62068, -2.61615, -2.46897, -2.26628, -2.11779, -2.19421, -2.23249, -2.32526, -2.29119, -2.33412, -2.34468, -2.34797, -2.35600, -2.26999, -2.31218, -2.21675, -2.00346, -1.86062, -1.56025, -1.31600, -1.17371, -1.15254, -0.98915, -0.89688, -0.85209, -0.81400, -0.85039, -0.68664, -0.46920, -0.18314, 0.13519, 0.46477, 0.65654, 0.72698, 0.80689, 0.79627, 0.73175, 0.62445, 0.64840, 0.60711, 0.57888, 0.43126, 0.30008, 0.23296, 0.11973, 0.04298, -0.16359, -0.17434, -0.01013, 0.14974, 0.36214, 0.50124, 0.53590, 0.42681, 0.43227, 0.36835, 0.23909, 0.21332, 0.23408, 0.34471, 0.39994, 0.39432, 0.42039, 0.53390, 0.57562, 0.42527, 0.33241, 0.29537, 0.22954, -0.00518, -0.26038, -0.51391, -0.73821, -1.00113, -1.33686, -1.55510, -1.69309, -1.64914, -1.64258, -1.68127, -1.70405, -1.85992, -1.88240, -1.85143, -1.86889, -1.97667, -2.00518, -1.94374, -1.88095, -1.73953, -1.72149, -1.77250, -1.85520, -1.92165, -1.93011, -1.87866, -1.79535, -1.79784, -1.73370, -1.65443, -1.62268, -1.66745, -1.62072, -1.50185, -1.40944, -1.43284, -1.60975, -1.70022, -1.78903, -1.66576, -1.59107, -1.54868, -1.43838, -1.46710, -1.41983, -1.35455, -1.33958, -1.28502, -1.05969, -0.83388, -0.79322, -0.73710, -0.74485, -0.69796, -0.65563, -0.69244, -0.64250, -0.44656, -0.15692, -0.01979, 0.12293, 0.36354, 0.57105, 0.69577, 0.71621, 0.78189, 0.83133, 0.86010, 0.76214, 0.63926, 0.40303, 0.29377, 0.27923, 0.20281, 0.17958, -0.01977, -0.18655, -0.26047, -0.37413, -0.50847, -0.61672, -0.71929, -0.92340, -0.95148, -0.95524, -0.90449, -0.71804, -0.51461, -0.28498, -0.12167, -0.00124, -0.11369, -0.21232, -0.17569, -0.13919, -0.19482, -0.32322, -0.35467, -0.41603, -0.38055, -0.54033, -0.67826, -0.89544, -0.98406, -0.95739, -1.08337, -1.13519, -1.22575, -1.33426, -1.44900, -1.71301, -2.01675, -2.28772, -2.44768, -2.77131, -3.02395, -3.22826, -3.31612, -3.25103, -3.27726, -3.28976, -3.21481, -2.99605, -2.94140, -3.05134, -3.09520, -3.08789, -3.07244, -3.11304, -3.15435, -3.28062, -3.22516, -3.11999, -2.91882, -2.82853, -2.79418, -2.69133, -2.61545, -2.38403, -2.16373, -2.00297, -1.79481, -1.58804, -1.35588, -1.21557, -1.11336, -1.19167, -1.19258, -1.18850, -1.25201, -1.23632, -1.24032, -1.14819, -1.03919, -0.88931, -0.96257, -1.12807, -1.10473, -0.91205, -0.57583, -0.40811, -0.23101, -0.21996, -0.13548, -0.15093, -0.21659, +-0.99631, -0.84689, -0.65673, -0.45537, -0.28108, -0.34542, -0.41459, -0.34942, -0.24455, -0.29130, -0.34485, -0.43992, -0.46140, -0.42174, -0.38119, -0.24518, -0.28824, -0.35971, -0.36630, -0.32397, -0.49055, -0.82855, -1.00307, -1.07465, -1.09074, -1.21584, -1.47907, -1.70607, -1.77114, -1.69790, -1.69977, -1.73371, -1.81699, -1.94533, -1.93524, -1.94800, -1.98620, -2.15967, -2.28651, -2.25851, -2.20965, -2.29288, -2.26519, -2.07958, -1.94236, -1.89195, -1.93931, -1.83004, -1.71564, -1.63998, -1.64614, -1.66757, -1.72202, -1.75697, -1.63436, -1.53383, -1.42827, -1.33440, -1.34365, -1.44264, -1.59875, -1.63367, -1.74654, -1.66942, -1.75018, -2.08328, -2.28165, -2.31793, -2.18677, -2.14283, -2.21006, -2.24429, -2.19562, -2.17032, -2.09074, -1.95645, -2.07841, -2.19148, -2.27131, -2.16857, -2.18370, -2.33329, -2.39684, -2.34148, -2.33877, -2.48191, -2.48068, -2.36172, -2.15342, -1.87366, -1.77690, -1.85815, -1.99275, -1.99775, -1.99880, -1.93241, -1.91929, -2.07251, -2.01583, -1.78261, -1.45814, -1.25760, -1.15973, -0.91526, -0.65705, -0.54133, -0.46986, -0.25151, -0.16930, -0.12184, -0.27667, -0.38816, -0.49184, -0.56567, -0.59188, -0.58295, -0.59983, -0.77862, -0.84444, -0.90201, -0.98985, -0.92628, -0.90572, -0.77665, -0.70117, -0.63724, -0.66518, -0.61433, -0.54371, -0.78858, -1.03679, -1.25354, -1.27531, -1.21141, -1.21199, -1.22608, -1.41602, -1.67390, -1.83425, -1.71586, -1.75907, -1.78253, -1.83377, -1.72318, -1.64284, -1.69128, -1.75818, -1.78378, -1.77767, -1.84638, -1.88403, -2.00910, -2.21237, -2.32186, -2.45218, -2.55236, -2.66336, -2.67675, -2.69900, -2.68286, -2.63962, -2.87323, -2.98828, -2.93634, -2.77092, -2.61801, -2.57433, -2.43255, -2.23934, -2.16100, -2.23285, -2.17456, -2.17012, -2.03834, -2.03336, -2.04218, -2.07011, -2.16324, -2.18231, -2.14405, -2.03270, -1.94701, -1.77186, -1.43052, -1.23269, -1.08502, -1.07451, -1.00386, -0.92065, -0.79804, -0.76437, -0.74678, -0.49349, -0.29879, 0.02630, 0.34968, 0.56955, 0.77664, 0.90560, 1.02200, 0.99356, 0.82094, 0.67260, 0.76002, 0.76372, 0.73265, 0.56193, 0.40322, 0.32404, 0.21462, 0.10268, -0.01644, -0.01966, -0.04301, 0.06323, 0.26596, 0.33311, 0.38401, 0.34219, 0.33192, 0.28999, 0.28786, 0.29677, 0.32889, 0.42880, 0.37573, 0.34309, 0.42653, 0.54005, 0.61537, 0.51178, 0.41038, 0.37425, 0.30029, 0.08149, -0.08047, -0.27856, -0.51694, -0.80361, -1.15685, -1.35647, -1.48490, -1.50521, -1.42199, -1.42231, -1.63320, -1.85411, -1.85218, -1.85215, -1.84273, -1.89014, -1.89953, -1.78283, -1.59490, -1.41637, -1.48420, -1.65054, -1.87433, -1.98919, -1.91828, -1.86735, -1.78732, -1.72040, -1.62405, -1.55583, -1.58021, -1.65868, -1.54394, -1.33937, -1.19385, -1.19504, -1.38930, -1.50623, -1.62118, -1.60241, -1.52697, -1.44401, -1.48114, -1.54752, -1.43267, -1.37925, -1.33850, -1.22464, -1.04009, -0.89004, -0.82038, -0.74341, -0.75493, -0.68280, -0.69305, -0.78309, -0.68137, -0.42784, -0.06187, 0.20785, 0.40593, 0.60683, 0.72742, 0.77409, 0.84046, 1.02540, 1.11516, 1.12735, 0.99767, 0.79523, 0.47508, 0.23988, 0.19328, 0.19595, 0.04455, -0.25867, -0.32661, -0.33947, -0.40190, -0.43717, -0.61600, -0.85031, -1.02554, -0.98345, -0.96285, -0.91708, -0.82127, -0.71638, -0.44840, -0.25484, -0.13394, -0.12561, -0.15035, -0.10691, -0.07535, -0.18393, -0.29466, -0.25289, -0.31775, -0.33137, -0.53377, -0.71936, -0.93691, -1.03554, -0.98499, -0.95267, -1.03868, -1.22608, -1.27728, -1.41239, -1.70600, -1.93039, -2.17624, -2.37330, -2.64572, -2.83803, -3.05674, -3.10251, -3.03236, -3.13083, -3.11262, -3.03742, -2.87692, -2.74540, -2.79255, -2.81249, -2.83189, -2.91284, -2.94661, -2.93890, -3.09698, -3.10586, -3.06826, -2.93556, -2.88889, -2.91174, -2.78963, -2.51689, -2.28180, -2.18057, -2.04033, -1.88977, -1.72708, -1.40335, -1.20407, -1.17007, -1.24905, -1.19648, -1.21240, -1.28167, -1.30515, -1.39135, -1.24879, -1.04670, -0.83872, -0.75831, -0.83566, -0.81247, -0.68645, -0.50933, -0.39297, -0.17734, -0.14388, -0.02842, -0.02762, -0.07825, +-0.81145, -0.56411, -0.34344, -0.22000, -0.17641, -0.26394, -0.28927, -0.27943, -0.14901, -0.12302, -0.22332, -0.26078, -0.19227, -0.14455, -0.09253, 0.00876, -0.00751, -0.13178, -0.20136, -0.17228, -0.33323, -0.52329, -0.65128, -0.83990, -0.95350, -1.05304, -1.26902, -1.46033, -1.51989, -1.56994, -1.61406, -1.66060, -1.78926, -1.86525, -1.86998, -1.96474, -2.05668, -2.16375, -2.15521, -2.13124, -2.06548, -2.05737, -2.08113, -1.92050, -1.74671, -1.69149, -1.69175, -1.55951, -1.37705, -1.31707, -1.40892, -1.46958, -1.58442, -1.52492, -1.35704, -1.35781, -1.35263, -1.28663, -1.32024, -1.45440, -1.59478, -1.70546, -1.81836, -1.69905, -1.82289, -2.06836, -2.20639, -2.30559, -2.27528, -2.27506, -2.28903, -2.31124, -2.21961, -2.06264, -2.00033, -1.91883, -2.02228, -2.17928, -2.27361, -2.18726, -2.18332, -2.34909, -2.53469, -2.52923, -2.57069, -2.57475, -2.44686, -2.37234, -2.24586, -1.99364, -1.88217, -1.96468, -2.05541, -2.14279, -2.21390, -2.12263, -2.12186, -2.13177, -1.95360, -1.74882, -1.51563, -1.38231, -1.25403, -1.04761, -0.82860, -0.58892, -0.50694, -0.33047, -0.19132, -0.16860, -0.32094, -0.41663, -0.48112, -0.51356, -0.62459, -0.63416, -0.70635, -0.79709, -0.78211, -0.91262, -1.08050, -1.04077, -0.97541, -0.84748, -0.75490, -0.75867, -0.83271, -0.73441, -0.69352, -0.86166, -1.02975, -1.23496, -1.28745, -1.27910, -1.24184, -1.28081, -1.52080, -1.65400, -1.78132, -1.71322, -1.70852, -1.76895, -1.86252, -1.78024, -1.69494, -1.67780, -1.79384, -1.80550, -1.83630, -1.83091, -1.76496, -1.92479, -2.20670, -2.39743, -2.55512, -2.70225, -2.79894, -2.83639, -2.90121, -2.84762, -2.83538, -2.99954, -3.00632, -2.93078, -2.79001, -2.66465, -2.54779, -2.37094, -2.21981, -2.04599, -2.07727, -2.07691, -2.02008, -1.89047, -1.87939, -1.85634, -1.86332, -1.88822, -2.00044, -2.00204, -1.92431, -1.77340, -1.47232, -1.17193, -1.12492, -1.09869, -1.07935, -1.01489, -0.89015, -0.75575, -0.74889, -0.61324, -0.30471, -0.05963, 0.32575, 0.59608, 0.70763, 0.82018, 0.98596, 1.16225, 1.11553, 1.04003, 0.93007, 0.90912, 0.90510, 0.84441, 0.65010, 0.49048, 0.38407, 0.32407, 0.12901, -0.03807, -0.08187, -0.12312, 0.04796, 0.23354, 0.20822, 0.21163, 0.23730, 0.25172, 0.24677, 0.26671, 0.22131, 0.30964, 0.45782, 0.46735, 0.53989, 0.62565, 0.64435, 0.60300, 0.50320, 0.44908, 0.37367, 0.36531, 0.23560, 0.02104, -0.16530, -0.39458, -0.69822, -1.01521, -1.17711, -1.20916, -1.27426, -1.27368, -1.34271, -1.57702, -1.67274, -1.63002, -1.71217, -1.77183, -1.76775, -1.70451, -1.53306, -1.32280, -1.24542, -1.34374, -1.51918, -1.75844, -1.79340, -1.70428, -1.73524, -1.76178, -1.71620, -1.57258, -1.52447, -1.48722, -1.43950, -1.37110, -1.20321, -1.06533, -1.11839, -1.30702, -1.41665, -1.49388, -1.54423, -1.55211, -1.47831, -1.49573, -1.39510, -1.21677, -1.26578, -1.33134, -1.23545, -1.06311, -0.90507, -0.78500, -0.77451, -0.77485, -0.63923, -0.62636, -0.58162, -0.41331, -0.22014, 0.05704, 0.31059, 0.56942, 0.74679, 0.87848, 1.02743, 1.05976, 1.22162, 1.34214, 1.30170, 1.12883, 0.86857, 0.55703, 0.29330, 0.15007, 0.13212, -0.06660, -0.25177, -0.22732, -0.32021, -0.47570, -0.53077, -0.70097, -0.91662, -1.01677, -1.01497, -0.99986, -0.91716, -0.88007, -0.74181, -0.46322, -0.33522, -0.26799, -0.23043, -0.14168, -0.08462, -0.06075, -0.07540, -0.23349, -0.27676, -0.37039, -0.48522, -0.69990, -0.84734, -0.96385, -0.99063, -1.01402, -0.98602, -1.10780, -1.18056, -1.13585, -1.30767, -1.63128, -1.84495, -2.03886, -2.21016, -2.40405, -2.61579, -2.84737, -2.84653, -2.83115, -2.88430, -2.83785, -2.83333, -2.76847, -2.69413, -2.66486, -2.65107, -2.68457, -2.66984, -2.75691, -2.86798, -3.00660, -3.05867, -3.03779, -2.90749, -2.85152, -2.82215, -2.75889, -2.49074, -2.30813, -2.13918, -1.92165, -1.81609, -1.71616, -1.42262, -1.17773, -1.12815, -1.16152, -1.16914, -1.25345, -1.27463, -1.30768, -1.30279, -1.08097, -0.90071, -0.74865, -0.70850, -0.70176, -0.64635, -0.60547, -0.39357, -0.29444, -0.16212, -0.06872, 0.03674, 0.02526, -0.00643, +-0.65673, -0.31098, -0.14773, -0.08550, -0.07413, -0.19483, -0.21589, -0.19089, -0.03788, -0.00386, -0.16706, -0.18547, 0.00452, 0.10658, 0.10338, 0.11489, 0.06108, -0.00978, -0.05697, -0.09910, -0.19913, -0.27981, -0.44918, -0.65464, -0.76231, -0.85575, -0.92389, -1.00407, -1.18504, -1.36147, -1.52399, -1.65376, -1.69117, -1.72398, -1.86903, -2.07482, -2.09941, -2.07995, -1.95701, -1.87867, -1.77607, -1.72592, -1.80890, -1.76423, -1.58579, -1.44044, -1.39244, -1.26769, -1.11642, -1.04147, -1.09104, -1.20246, -1.31477, -1.26439, -1.23533, -1.33907, -1.36864, -1.37477, -1.40809, -1.46450, -1.63638, -1.76898, -1.85706, -1.80681, -1.87769, -2.03525, -2.19434, -2.40281, -2.41891, -2.45865, -2.47337, -2.39105, -2.20420, -2.01050, -2.01876, -2.05399, -2.10120, -2.14626, -2.24150, -2.23518, -2.29433, -2.46074, -2.61015, -2.65687, -2.65604, -2.51954, -2.37393, -2.38634, -2.32091, -2.21219, -2.13708, -2.06316, -2.12471, -2.27675, -2.39319, -2.41994, -2.31607, -2.11343, -1.87330, -1.77897, -1.59085, -1.48123, -1.37632, -1.18860, -0.97545, -0.67847, -0.59254, -0.50388, -0.34748, -0.22987, -0.33297, -0.41987, -0.49811, -0.57155, -0.65776, -0.73045, -0.80907, -0.79772, -0.82259, -1.04513, -1.17332, -1.16616, -1.08376, -0.83206, -0.77592, -0.88147, -0.92785, -0.93192, -0.87430, -0.92560, -1.05959, -1.28843, -1.31550, -1.35008, -1.38441, -1.44004, -1.61579, -1.64277, -1.76194, -1.81411, -1.80967, -1.76829, -1.82468, -1.76088, -1.68080, -1.64194, -1.65683, -1.72439, -1.83371, -1.81984, -1.81456, -2.04000, -2.26123, -2.51286, -2.75179, -2.81085, -2.87762, -2.95566, -2.97702, -3.04847, -3.05550, -3.07786, -3.02200, -3.02541, -2.87971, -2.70973, -2.55998, -2.35451, -2.19345, -1.97233, -1.98623, -2.06577, -2.03212, -1.86528, -1.82332, -1.80279, -1.79244, -1.80139, -1.85034, -1.84892, -1.75324, -1.47789, -1.15262, -0.99643, -1.03426, -1.12299, -1.15405, -0.99612, -0.83570, -0.76517, -0.67291, -0.48543, -0.13265, 0.18822, 0.52308, 0.62853, 0.70141, 0.82919, 0.99051, 1.18703, 1.21748, 1.26823, 1.21150, 1.10657, 1.06490, 1.08048, 0.94406, 0.71384, 0.50360, 0.31765, 0.12720, -0.00639, -0.06398, -0.07511, 0.03282, 0.07432, 0.05378, 0.08751, 0.12352, 0.22938, 0.29019, 0.25973, 0.24675, 0.30030, 0.43882, 0.59084, 0.72534, 0.69830, 0.61143, 0.53619, 0.43175, 0.40014, 0.33643, 0.33985, 0.22207, -0.07368, -0.29498, -0.43999, -0.65268, -0.89742, -0.98180, -0.98499, -0.99692, -1.01820, -1.20100, -1.41029, -1.46820, -1.54346, -1.68113, -1.76608, -1.75311, -1.52527, -1.25156, -1.16074, -1.16825, -1.31677, -1.51447, -1.64233, -1.63136, -1.64439, -1.75584, -1.77456, -1.72108, -1.54626, -1.42516, -1.27248, -1.15017, -1.18924, -1.16688, -1.08035, -1.09167, -1.21904, -1.29851, -1.42733, -1.52087, -1.51689, -1.46397, -1.36342, -1.15382, -1.05959, -1.16606, -1.24100, -1.21569, -1.04017, -0.80841, -0.73580, -0.75213, -0.74291, -0.65526, -0.51130, -0.31299, -0.14746, -0.07185, 0.13200, 0.33441, 0.56118, 0.76938, 0.95655, 1.14991, 1.17348, 1.30430, 1.48090, 1.52235, 1.33020, 0.99497, 0.62985, 0.35956, 0.21630, 0.10569, -0.09522, -0.19199, -0.19727, -0.39620, -0.62409, -0.79230, -0.91486, -0.93746, -1.00633, -1.03733, -1.00917, -1.00730, -0.92048, -0.71010, -0.47110, -0.43471, -0.31350, -0.21800, -0.12579, -0.05832, -0.05803, -0.04479, -0.21232, -0.35642, -0.51126, -0.63345, -0.82684, -0.92271, -0.95147, -0.93172, -0.92516, -0.95578, -1.05805, -1.04382, -1.05943, -1.30881, -1.57852, -1.80702, -1.95962, -1.98324, -2.14107, -2.35867, -2.52515, -2.65779, -2.69650, -2.71622, -2.73676, -2.86627, -2.82627, -2.75910, -2.67956, -2.56078, -2.52224, -2.45138, -2.60053, -2.86444, -2.99918, -2.95349, -2.91286, -2.81938, -2.79227, -2.74411, -2.59109, -2.40479, -2.31428, -2.13040, -1.94397, -1.89984, -1.76604, -1.53564, -1.29289, -1.07473, -1.05217, -1.10698, -1.12724, -1.19895, -1.15876, -1.02687, -0.85054, -0.84273, -0.77611, -0.71885, -0.63925, -0.51650, -0.50195, -0.31819, -0.24252, -0.18614, -0.04711, 0.14563, 0.14804, 0.10626, +-0.60685, -0.31088, -0.07048, 0.06440, 0.10667, 0.00251, -0.07238, -0.05574, 0.06172, 0.02837, -0.07774, -0.00880, 0.11108, 0.13634, 0.06947, 0.02231, -0.02094, 0.01814, 0.08153, -0.02864, -0.17907, -0.21052, -0.31471, -0.43189, -0.46107, -0.49408, -0.53258, -0.69020, -0.96227, -1.16715, -1.35743, -1.46169, -1.47070, -1.58088, -1.72477, -1.88333, -1.83929, -1.73490, -1.63368, -1.59700, -1.51732, -1.52155, -1.56262, -1.51598, -1.46643, -1.38858, -1.30796, -1.20535, -1.11464, -1.01017, -0.92443, -1.03689, -1.18752, -1.20358, -1.23594, -1.32905, -1.33919, -1.36133, -1.47581, -1.65937, -1.86520, -1.93176, -1.92298, -1.84008, -1.85819, -2.06743, -2.17205, -2.31182, -2.35211, -2.42207, -2.47821, -2.38256, -2.18670, -2.11329, -2.13940, -2.08856, -2.08783, -2.13600, -2.21646, -2.30801, -2.44866, -2.59564, -2.63324, -2.69728, -2.71936, -2.55004, -2.35072, -2.35640, -2.33767, -2.34227, -2.35778, -2.31105, -2.30811, -2.37503, -2.42350, -2.45325, -2.26736, -2.09665, -1.84569, -1.72671, -1.58786, -1.49720, -1.43475, -1.34729, -1.18014, -0.99022, -0.88438, -0.70615, -0.58025, -0.52495, -0.55722, -0.61968, -0.67788, -0.75782, -0.74836, -0.83289, -0.96415, -0.97239, -1.00515, -1.18424, -1.26446, -1.25575, -1.19802, -1.03716, -0.98378, -1.05359, -1.00343, -1.00163, -0.90736, -1.03112, -1.12783, -1.21501, -1.24430, -1.35405, -1.48123, -1.58563, -1.64682, -1.68655, -1.80133, -1.80336, -1.80950, -1.82012, -1.83820, -1.79936, -1.72867, -1.67247, -1.55214, -1.66243, -1.92475, -2.07541, -2.12227, -2.22226, -2.29536, -2.47915, -2.74300, -2.89817, -2.96226, -3.02800, -3.01496, -3.15003, -3.16647, -3.23871, -3.15886, -3.07038, -2.90866, -2.73078, -2.57178, -2.42608, -2.27772, -2.14442, -2.16661, -2.13208, -2.05841, -1.99494, -1.94216, -1.92460, -1.88930, -1.87334, -1.79024, -1.71302, -1.64839, -1.40875, -1.07649, -0.88322, -0.87979, -0.97358, -1.03857, -0.97815, -0.84186, -0.74859, -0.50172, -0.20650, 0.17066, 0.36040, 0.56966, 0.73752, 0.89615, 1.05376, 1.20418, 1.32728, 1.41910, 1.49388, 1.43480, 1.40828, 1.39788, 1.34772, 1.21228, 0.87850, 0.53794, 0.19291, 0.07174, 0.09878, 0.04747, -0.02886, 0.01200, 0.05664, 0.11398, 0.18901, 0.17214, 0.15571, 0.15861, 0.14866, 0.25362, 0.34470, 0.48608, 0.59470, 0.66611, 0.66981, 0.56633, 0.46073, 0.36321, 0.30455, 0.26651, 0.21179, 0.02435, -0.21602, -0.37375, -0.55679, -0.73894, -0.91695, -0.96010, -0.96745, -0.88788, -0.80917, -1.04672, -1.33181, -1.41959, -1.49577, -1.58628, -1.63440, -1.59978, -1.39741, -1.22872, -1.23813, -1.22633, -1.27615, -1.37346, -1.48019, -1.56084, -1.56568, -1.62746, -1.63021, -1.57886, -1.44628, -1.29604, -1.09568, -1.02215, -1.09625, -1.11494, -1.19787, -1.22989, -1.23363, -1.25514, -1.40802, -1.48026, -1.36620, -1.32530, -1.27420, -1.11336, -1.02714, -1.05794, -1.05246, -1.04199, -0.97769, -0.89054, -0.86689, -0.81828, -0.73231, -0.63369, -0.43834, -0.24703, 0.02674, 0.18077, 0.32574, 0.45816, 0.58414, 0.75401, 0.94743, 1.06369, 1.13387, 1.35074, 1.49210, 1.50873, 1.37193, 1.02826, 0.62541, 0.37492, 0.32599, 0.16676, -0.11587, -0.24257, -0.25402, -0.46821, -0.73541, -0.94934, -1.03094, -1.02596, -1.03787, -0.99765, -0.89563, -0.88438, -0.78364, -0.69701, -0.44864, -0.31963, -0.13923, -0.02573, -0.01764, -0.04609, -0.11492, -0.17288, -0.25836, -0.29648, -0.51546, -0.74623, -0.87871, -0.93076, -0.94920, -0.94780, -0.86314, -0.90984, -1.04734, -1.07641, -1.12865, -1.34256, -1.54154, -1.73307, -1.89194, -2.00612, -2.13491, -2.24400, -2.25472, -2.39267, -2.49018, -2.68619, -2.75972, -2.82658, -2.79038, -2.73899, -2.66535, -2.56047, -2.47124, -2.46016, -2.59473, -2.76046, -2.88812, -2.88902, -2.79362, -2.71830, -2.72613, -2.68279, -2.43161, -2.32347, -2.40296, -2.33607, -2.10939, -1.94265, -1.72558, -1.50258, -1.29246, -1.12988, -1.07486, -1.07459, -0.95419, -0.96022, -0.83008, -0.80139, -0.73012, -0.73232, -0.73909, -0.64686, -0.48373, -0.35674, -0.33208, -0.26562, -0.20456, -0.04943, 0.07359, 0.12141, 0.11304, 0.06028, +-0.55635, -0.34599, -0.09146, 0.09919, 0.22507, 0.17645, 0.08610, 0.08721, 0.18261, 0.17138, 0.06044, 0.08739, 0.09437, 0.02135, 0.01893, 0.04492, 0.09942, 0.16643, 0.14821, 0.03941, -0.06043, -0.07640, -0.16189, -0.27890, -0.26183, -0.23858, -0.31328, -0.53403, -0.74455, -0.93515, -1.14014, -1.16240, -1.15684, -1.30288, -1.44955, -1.56462, -1.49038, -1.37703, -1.35948, -1.38075, -1.34903, -1.34435, -1.38822, -1.40513, -1.45669, -1.48575, -1.35083, -1.18222, -1.07777, -0.96218, -0.94942, -1.05795, -1.11899, -1.11203, -1.15145, -1.23322, -1.22414, -1.23606, -1.44918, -1.78359, -2.01493, -2.06963, -2.07152, -1.88268, -1.81293, -1.98828, -2.09515, -2.17284, -2.19302, -2.23423, -2.32436, -2.26472, -2.15231, -2.10670, -2.11911, -2.04131, -2.01029, -2.12188, -2.17420, -2.21868, -2.38091, -2.51050, -2.66799, -2.81920, -2.80833, -2.62780, -2.42569, -2.41977, -2.41527, -2.42096, -2.49023, -2.51630, -2.45057, -2.40601, -2.44572, -2.38076, -2.15393, -2.02503, -1.89098, -1.78757, -1.69409, -1.59257, -1.57410, -1.53648, -1.45038, -1.30279, -1.18403, -1.01913, -0.91449, -0.93591, -0.92062, -0.84331, -0.81287, -0.76851, -0.79477, -0.92270, -1.00972, -1.01849, -1.07530, -1.24877, -1.38477, -1.38140, -1.37771, -1.32861, -1.21879, -1.17280, -1.15163, -1.06131, -0.89965, -0.99138, -1.10891, -1.15547, -1.22832, -1.33200, -1.49026, -1.56188, -1.59078, -1.62740, -1.71919, -1.75332, -1.78252, -1.87854, -1.93163, -1.83942, -1.78557, -1.67194, -1.61162, -1.83299, -2.11015, -2.30536, -2.37672, -2.38810, -2.39371, -2.45059, -2.67392, -2.91910, -2.98637, -3.02607, -3.15335, -3.30314, -3.32034, -3.38359, -3.33708, -3.20394, -3.04538, -2.83093, -2.68111, -2.55159, -2.45929, -2.38299, -2.39266, -2.35333, -2.22456, -2.18285, -2.11585, -1.95472, -1.86555, -1.74111, -1.65678, -1.66622, -1.61941, -1.38765, -1.07224, -0.81451, -0.75419, -0.77708, -0.85810, -0.89494, -0.74597, -0.52972, -0.27718, 0.05480, 0.44128, 0.61342, 0.75430, 0.97707, 1.18164, 1.38118, 1.52195, 1.62561, 1.70997, 1.76794, 1.69278, 1.60250, 1.55350, 1.41511, 1.22473, 0.94841, 0.58576, 0.27201, 0.16498, 0.15921, 0.14655, 0.10553, 0.12142, 0.18462, 0.24205, 0.29754, 0.18264, 0.01076, -0.05044, 0.03210, 0.14520, 0.25143, 0.42727, 0.53485, 0.54367, 0.53513, 0.41778, 0.32144, 0.22861, 0.17603, 0.18320, 0.13647, -0.02222, -0.25205, -0.40812, -0.63589, -0.83868, -0.92100, -0.94946, -0.91198, -0.82132, -0.80335, -1.00006, -1.25397, -1.38298, -1.43105, -1.47520, -1.46992, -1.43193, -1.36142, -1.32278, -1.30184, -1.27209, -1.25813, -1.23209, -1.30083, -1.42644, -1.45569, -1.49861, -1.49812, -1.48929, -1.43194, -1.30648, -1.13678, -1.05898, -1.16013, -1.22662, -1.37584, -1.42124, -1.27685, -1.18825, -1.25816, -1.28605, -1.24786, -1.23052, -1.22108, -1.15527, -1.05943, -1.02254, -0.93883, -0.90399, -0.95011, -1.00294, -0.95770, -0.88168, -0.81380, -0.64342, -0.40243, -0.19764, 0.11442, 0.37827, 0.55182, 0.67431, 0.72960, 0.84768, 0.97574, 1.07306, 1.10767, 1.24379, 1.32789, 1.29073, 1.26819, 1.06857, 0.70628, 0.48602, 0.37667, 0.20960, -0.04682, -0.21953, -0.28699, -0.51568, -0.77543, -0.93398, -0.99227, -1.02007, -0.94972, -0.82689, -0.75075, -0.67251, -0.58355, -0.59678, -0.44272, -0.28107, -0.09348, 0.04824, 0.00496, -0.06452, -0.19177, -0.23227, -0.27486, -0.32697, -0.55652, -0.84536, -0.90485, -0.83234, -0.88141, -0.89463, -0.89695, -0.98671, -1.07886, -1.12392, -1.20175, -1.37928, -1.54429, -1.66945, -1.85753, -2.08145, -2.15974, -2.15076, -2.14054, -2.15507, -2.23074, -2.47309, -2.61861, -2.65870, -2.64508, -2.57710, -2.57627, -2.53382, -2.48452, -2.47396, -2.54420, -2.67576, -2.79547, -2.85280, -2.69123, -2.47216, -2.48578, -2.42695, -2.30419, -2.33938, -2.44787, -2.40176, -2.15197, -1.90745, -1.66623, -1.40253, -1.23620, -1.18539, -1.12060, -1.05630, -0.97506, -0.89375, -0.71162, -0.69178, -0.70360, -0.69578, -0.71644, -0.54069, -0.35095, -0.20973, -0.19042, -0.14091, -0.06173, 0.04198, 0.05301, -0.07160, -0.10769, -0.04407, +-0.54309, -0.43284, -0.20596, 0.00922, 0.16354, 0.13460, 0.07089, 0.08842, 0.16752, 0.22524, 0.12693, 0.08101, 0.06938, 0.01460, -0.00358, -0.01390, 0.09553, 0.13505, 0.10995, 0.14333, 0.13019, 0.10119, -0.03576, -0.20635, -0.21308, -0.21645, -0.23670, -0.31207, -0.44854, -0.66645, -0.90711, -0.89125, -0.85452, -1.04218, -1.23320, -1.33340, -1.29849, -1.25519, -1.32309, -1.35333, -1.35381, -1.28079, -1.30568, -1.37876, -1.42597, -1.42534, -1.31468, -1.22833, -1.13446, -1.07053, -1.11852, -1.09773, -1.04241, -1.00205, -1.07238, -1.17020, -1.17976, -1.24875, -1.45371, -1.69021, -1.95307, -2.10236, -2.18751, -1.95942, -1.80626, -1.94052, -2.08652, -2.10699, -2.12525, -2.15223, -2.25883, -2.21363, -2.20622, -2.12460, -2.08761, -2.01163, -1.94400, -2.01245, -2.09637, -2.23392, -2.41281, -2.55066, -2.82035, -2.92821, -2.88698, -2.74116, -2.60289, -2.60171, -2.58284, -2.60530, -2.65089, -2.53997, -2.44920, -2.42500, -2.52201, -2.42105, -2.16311, -2.07973, -2.11659, -2.02765, -1.98020, -1.87986, -1.90049, -1.84322, -1.82338, -1.64297, -1.46720, -1.31643, -1.20206, -1.17563, -1.16561, -1.13932, -1.04610, -0.88659, -0.94960, -0.96198, -0.98565, -1.01534, -1.12367, -1.33683, -1.54125, -1.61974, -1.65575, -1.48978, -1.32302, -1.26906, -1.33183, -1.21350, -0.98648, -1.00872, -1.19907, -1.25795, -1.40314, -1.49548, -1.65940, -1.64571, -1.68764, -1.69835, -1.73360, -1.77887, -1.79660, -1.82572, -1.92798, -1.99042, -2.01697, -1.89343, -1.93410, -2.07255, -2.26914, -2.45645, -2.56423, -2.58634, -2.57353, -2.59674, -2.78286, -2.87658, -2.89922, -3.01606, -3.33404, -3.53499, -3.53545, -3.54655, -3.59528, -3.45971, -3.32718, -3.08935, -2.95094, -2.77269, -2.73313, -2.69043, -2.65776, -2.61086, -2.40706, -2.20912, -2.08957, -1.96373, -1.90483, -1.71130, -1.66141, -1.61232, -1.52054, -1.29291, -1.02289, -0.77061, -0.66132, -0.65298, -0.74493, -0.65387, -0.41124, -0.16548, -0.00922, 0.23888, 0.60951, 0.84517, 0.92740, 1.17436, 1.37894, 1.58143, 1.69479, 1.83726, 1.90891, 1.94226, 1.85734, 1.67475, 1.56597, 1.46262, 1.27681, 0.95976, 0.55435, 0.32057, 0.20562, 0.25116, 0.33601, 0.33588, 0.31019, 0.32686, 0.34980, 0.30516, 0.05610, -0.08106, -0.07397, 0.02462, 0.03753, 0.07150, 0.26046, 0.42897, 0.37820, 0.34398, 0.20968, 0.09220, -0.01924, -0.02099, 0.06996, 0.07274, 0.00027, -0.20938, -0.38867, -0.55749, -0.70977, -0.84851, -1.00218, -0.96113, -0.91634, -0.89281, -0.95151, -1.14429, -1.32099, -1.39416, -1.41796, -1.40617, -1.42981, -1.38814, -1.31439, -1.28293, -1.31580, -1.34088, -1.26925, -1.27891, -1.44430, -1.51166, -1.53897, -1.56347, -1.63644, -1.65404, -1.54475, -1.42958, -1.29624, -1.35327, -1.41680, -1.47354, -1.41578, -1.26089, -1.22511, -1.23701, -1.25261, -1.24058, -1.13520, -1.16303, -1.20538, -1.13768, -1.05425, -0.92697, -0.92509, -0.96471, -0.92852, -0.86431, -0.85394, -0.87888, -0.70603, -0.43478, -0.23725, 0.05857, 0.43799, 0.65040, 0.76182, 0.77277, 0.87250, 0.92515, 1.05776, 1.07228, 1.10702, 1.19347, 1.21503, 1.20370, 0.96993, 0.63823, 0.42866, 0.29065, 0.26750, 0.07761, -0.15085, -0.32078, -0.57437, -0.80461, -0.95530, -0.96672, -0.85149, -0.74284, -0.65316, -0.65701, -0.55696, -0.45526, -0.54836, -0.55282, -0.39231, -0.25571, -0.12297, -0.18617, -0.21814, -0.37386, -0.35150, -0.35623, -0.44296, -0.62729, -0.81373, -0.85059, -0.85384, -0.97255, -1.01437, -1.07833, -1.03147, -1.04332, -1.11205, -1.24341, -1.41980, -1.55342, -1.68321, -1.87642, -1.99030, -2.04788, -2.05959, -2.10798, -2.03600, -2.03390, -2.24790, -2.48958, -2.52001, -2.54414, -2.47323, -2.55159, -2.52797, -2.53752, -2.49121, -2.48762, -2.60309, -2.69057, -2.66067, -2.47135, -2.31244, -2.36709, -2.33240, -2.37449, -2.37011, -2.42396, -2.38202, -2.17570, -1.95264, -1.71840, -1.48476, -1.35047, -1.18301, -1.09351, -1.10134, -1.16647, -1.09004, -0.87641, -0.79454, -0.86500, -0.80959, -0.80868, -0.57988, -0.40957, -0.21748, -0.20590, -0.12351, 0.00413, 0.04061, -0.05475, -0.17981, -0.21613, -0.21266, +-0.61565, -0.51388, -0.25140, -0.04561, 0.03824, 0.00930, 0.03085, 0.09823, 0.17091, 0.18237, 0.12125, 0.08911, -0.00818, -0.09175, -0.09038, -0.04133, 0.00974, -0.00649, -0.00464, 0.05006, 0.15075, 0.20315, 0.13244, 0.01054, -0.09342, -0.13527, -0.11762, -0.09474, -0.17288, -0.37110, -0.50221, -0.51385, -0.61327, -0.84199, -1.01945, -1.14535, -1.17495, -1.24530, -1.35245, -1.34986, -1.27208, -1.16142, -1.18250, -1.22709, -1.31453, -1.35423, -1.22649, -1.09409, -1.06844, -1.18919, -1.26813, -1.24077, -1.09654, -0.99443, -1.06422, -1.11723, -1.22115, -1.34391, -1.44695, -1.57407, -1.82890, -2.06511, -2.08981, -1.87393, -1.85326, -1.99638, -2.02987, -2.01338, -2.07022, -2.15130, -2.20889, -2.19410, -2.23378, -2.17216, -2.12670, -1.99328, -1.95145, -2.07860, -2.20016, -2.32344, -2.47904, -2.68828, -2.92263, -3.08524, -3.06561, -2.92290, -2.84790, -2.75290, -2.68672, -2.70206, -2.66731, -2.52018, -2.44328, -2.52169, -2.57006, -2.43005, -2.27280, -2.32747, -2.38437, -2.29446, -2.22246, -2.14311, -2.15391, -2.10779, -2.08905, -1.89715, -1.67839, -1.41916, -1.30932, -1.39290, -1.41449, -1.34021, -1.16108, -1.07050, -1.11086, -1.15102, -1.20106, -1.18926, -1.27683, -1.38814, -1.59064, -1.76069, -1.75655, -1.56391, -1.41468, -1.42849, -1.40191, -1.21408, -1.09461, -1.20995, -1.33951, -1.44848, -1.65483, -1.79148, -1.89975, -1.84508, -1.86127, -1.85692, -1.90858, -1.86813, -1.80850, -1.82887, -1.93490, -2.05940, -2.11041, -2.15856, -2.25190, -2.36903, -2.49491, -2.57513, -2.69754, -2.69444, -2.66468, -2.74913, -2.86222, -2.85529, -2.84698, -3.12122, -3.47681, -3.59850, -3.62570, -3.72617, -3.77848, -3.68069, -3.57865, -3.37778, -3.16866, -2.92651, -2.89521, -2.91170, -2.91184, -2.76553, -2.44673, -2.22527, -2.10104, -1.99415, -1.91703, -1.81254, -1.71557, -1.61486, -1.50169, -1.20862, -0.93922, -0.65554, -0.50161, -0.49919, -0.47621, -0.28578, -0.03842, 0.11577, 0.25594, 0.49760, 0.75731, 0.88703, 1.02226, 1.29236, 1.49226, 1.64016, 1.74449, 1.92559, 2.04926, 2.12139, 1.98878, 1.76727, 1.65150, 1.47545, 1.23491, 0.95417, 0.68216, 0.44375, 0.32972, 0.36740, 0.44179, 0.49423, 0.45521, 0.49173, 0.52827, 0.32312, 0.02667, -0.03766, 0.03705, 0.07782, 0.01148, 0.06292, 0.17763, 0.23632, 0.24164, 0.26586, 0.10324, -0.11382, -0.22697, -0.14207, 0.05171, 0.12635, 0.04064, -0.16372, -0.31774, -0.48834, -0.62814, -0.76726, -0.89489, -0.94591, -0.97121, -0.98685, -1.07066, -1.16006, -1.27667, -1.33456, -1.33817, -1.38454, -1.42941, -1.40869, -1.36075, -1.37654, -1.45974, -1.43201, -1.39721, -1.53351, -1.71891, -1.73004, -1.71029, -1.72836, -1.83683, -1.88642, -1.79070, -1.69226, -1.59963, -1.57479, -1.47748, -1.44756, -1.38749, -1.25136, -1.16568, -1.20002, -1.27917, -1.25227, -1.18903, -1.24265, -1.29095, -1.17429, -0.94833, -0.81340, -0.84835, -0.86033, -0.80160, -0.74143, -0.77064, -0.73363, -0.63365, -0.55658, -0.39440, -0.00737, 0.44822, 0.67229, 0.73209, 0.72197, 0.79121, 0.86770, 1.00408, 1.02803, 1.11693, 1.19524, 1.17125, 1.09813, 0.88508, 0.59908, 0.34859, 0.22142, 0.15358, 0.02361, -0.16647, -0.39800, -0.59602, -0.80197, -0.96008, -0.91714, -0.75945, -0.66754, -0.67747, -0.60703, -0.44529, -0.41282, -0.59004, -0.62394, -0.50641, -0.44746, -0.40980, -0.41390, -0.37319, -0.46034, -0.46211, -0.50499, -0.52277, -0.67669, -0.87602, -0.90325, -0.89662, -1.04097, -1.19208, -1.19282, -1.08866, -1.03658, -1.07503, -1.24108, -1.35240, -1.44368, -1.58052, -1.70298, -1.81723, -1.93464, -2.04285, -2.01133, -1.83809, -1.89297, -2.18525, -2.41106, -2.45882, -2.46272, -2.41513, -2.45250, -2.40775, -2.38873, -2.34662, -2.40043, -2.44233, -2.44869, -2.42193, -2.28773, -2.18727, -2.21743, -2.34631, -2.48410, -2.54421, -2.57226, -2.47325, -2.31166, -2.05439, -1.83230, -1.69496, -1.50405, -1.24239, -1.11099, -1.24827, -1.35551, -1.24440, -1.13799, -1.14920, -1.09392, -0.93126, -0.85060, -0.67284, -0.49194, -0.26042, -0.20531, -0.10388, -0.00440, 0.04767, -0.07935, -0.25720, -0.28734, -0.25212, +-0.71561, -0.45842, -0.20340, -0.07185, -0.04408, -0.05465, -0.00535, 0.05492, 0.10350, 0.02393, -0.08551, -0.06813, -0.11159, -0.16978, -0.17642, -0.07280, 0.00513, 0.00679, 0.02975, 0.05813, 0.20174, 0.27513, 0.22928, 0.21553, 0.12576, 0.12132, 0.10337, 0.09853, 0.17068, 0.09342, 0.00717, -0.17222, -0.37797, -0.50407, -0.72395, -0.96988, -1.02315, -1.10242, -1.19594, -1.18157, -1.01122, -0.91436, -1.04395, -1.12434, -1.22077, -1.30820, -1.20623, -1.01539, -0.92757, -1.07346, -1.13664, -1.12567, -1.02070, -1.05728, -1.26021, -1.32426, -1.44245, -1.50093, -1.52807, -1.67603, -1.81319, -1.97851, -1.93499, -1.83656, -1.97774, -1.98901, -1.91533, -1.97064, -2.06805, -2.16423, -2.18316, -2.19924, -2.17470, -2.12551, -2.14643, -2.06493, -2.04292, -2.20811, -2.39769, -2.53357, -2.59708, -2.75742, -2.87434, -3.01155, -3.00365, -2.94286, -3.00349, -2.89395, -2.73270, -2.66028, -2.61025, -2.63801, -2.53308, -2.58899, -2.60603, -2.53409, -2.49331, -2.45491, -2.41924, -2.39363, -2.27803, -2.18455, -2.21555, -2.27022, -2.24388, -2.08169, -1.89108, -1.61570, -1.44554, -1.54640, -1.57887, -1.47363, -1.23903, -1.21820, -1.25684, -1.33688, -1.40729, -1.40592, -1.52263, -1.61095, -1.74287, -1.88640, -1.82555, -1.79642, -1.68496, -1.64043, -1.49304, -1.33583, -1.39982, -1.46609, -1.47149, -1.64928, -1.82194, -1.92151, -1.97425, -1.99991, -2.00082, -1.98432, -2.10622, -2.11509, -1.97447, -1.94308, -1.98518, -2.09290, -2.08051, -2.16698, -2.28232, -2.38358, -2.44479, -2.51222, -2.75935, -2.88297, -2.82127, -2.89359, -2.93158, -3.00269, -2.96465, -3.17293, -3.42240, -3.49730, -3.61069, -3.68829, -3.69536, -3.73525, -3.68974, -3.49929, -3.21488, -2.99211, -2.92541, -2.93221, -2.96814, -2.84919, -2.51816, -2.35485, -2.25646, -2.18499, -2.01827, -1.84882, -1.66537, -1.50680, -1.35508, -1.05517, -0.83918, -0.66281, -0.49501, -0.42249, -0.23025, -0.10707, 0.06471, 0.24748, 0.45531, 0.72519, 0.87786, 1.02388, 1.29757, 1.47810, 1.62547, 1.77272, 1.88072, 1.99168, 2.14103, 2.27865, 2.15409, 1.87564, 1.76734, 1.55858, 1.27191, 1.00793, 0.91221, 0.77450, 0.65351, 0.64652, 0.69905, 0.72249, 0.59160, 0.52814, 0.58945, 0.39457, 0.20436, 0.11873, 0.16990, 0.23522, 0.14285, 0.16782, 0.10158, 0.09531, 0.26682, 0.30195, 0.11997, -0.07910, -0.12622, -0.03993, 0.11128, 0.16798, 0.02498, -0.26365, -0.39147, -0.50551, -0.62306, -0.77546, -0.82670, -0.84592, -0.88166, -0.96172, -1.11988, -1.17023, -1.28525, -1.45955, -1.50513, -1.54716, -1.51195, -1.50370, -1.52063, -1.47756, -1.52741, -1.50027, -1.61094, -1.82879, -1.91259, -1.93240, -1.93568, -1.87645, -1.87726, -1.91101, -1.85375, -1.74607, -1.71552, -1.69492, -1.48554, -1.36948, -1.36192, -1.30679, -1.16213, -1.14123, -1.22850, -1.18658, -1.15536, -1.18460, -1.22293, -1.13474, -0.82921, -0.65859, -0.66581, -0.70666, -0.78535, -0.68086, -0.63945, -0.53372, -0.54889, -0.59538, -0.30079, 0.12029, 0.44353, 0.61627, 0.66712, 0.62672, 0.63674, 0.78529, 0.91402, 0.90109, 1.00967, 1.12709, 1.07517, 0.89210, 0.67288, 0.51419, 0.32352, 0.19044, 0.03255, -0.07106, -0.25384, -0.52282, -0.66616, -0.78981, -0.88301, -0.84649, -0.82847, -0.70803, -0.71489, -0.59423, -0.47043, -0.48731, -0.48856, -0.46312, -0.46962, -0.45916, -0.45579, -0.40634, -0.36975, -0.40576, -0.51138, -0.67813, -0.71943, -0.84110, -1.05814, -1.10063, -1.05876, -1.05886, -1.12408, -1.03101, -0.89641, -0.82833, -0.92421, -1.18377, -1.33777, -1.37621, -1.43545, -1.47399, -1.71053, -1.81426, -1.87385, -1.79445, -1.73412, -1.96276, -2.17288, -2.32248, -2.44770, -2.39090, -2.29231, -2.24963, -2.23395, -2.15829, -2.13293, -2.32036, -2.42450, -2.33893, -2.30039, -2.27355, -2.28030, -2.22810, -2.34065, -2.44903, -2.52675, -2.54057, -2.48328, -2.45343, -2.28142, -2.05553, -1.95201, -1.71065, -1.53393, -1.33039, -1.36119, -1.40477, -1.32594, -1.37756, -1.33186, -1.08138, -0.90332, -0.77914, -0.64403, -0.44511, -0.26194, -0.18214, -0.08754, -0.05532, -0.05776, -0.10713, -0.23711, -0.25939, -0.22986, +-0.77576, -0.52581, -0.28244, -0.15294, -0.14347, -0.13681, -0.11387, -0.05952, -0.08348, -0.23190, -0.25091, -0.13222, -0.09114, -0.05491, -0.08729, -0.04328, 0.06961, 0.10623, 0.13135, 0.11463, 0.16705, 0.24760, 0.32206, 0.38369, 0.29187, 0.28908, 0.32581, 0.35857, 0.51409, 0.55597, 0.34893, 0.07915, -0.02506, -0.13528, -0.40941, -0.68008, -0.78121, -0.84577, -0.95233, -0.93972, -0.80851, -0.81753, -0.93650, -0.98942, -1.11419, -1.19236, -1.14060, -1.03584, -0.90132, -0.96185, -0.99424, -1.01336, -1.06669, -1.25910, -1.47150, -1.54561, -1.69487, -1.73826, -1.69909, -1.79457, -1.89769, -1.94502, -1.97398, -1.96596, -2.03105, -1.99277, -1.94709, -1.99178, -2.12817, -2.20133, -2.22742, -2.20679, -2.12982, -2.14419, -2.12630, -2.00061, -2.01652, -2.15437, -2.38043, -2.64851, -2.71283, -2.81768, -2.88782, -2.98950, -3.04592, -3.06402, -3.10124, -2.97343, -2.82916, -2.76121, -2.70384, -2.71861, -2.61306, -2.55566, -2.64699, -2.69203, -2.58834, -2.47093, -2.46869, -2.43496, -2.35949, -2.26521, -2.34322, -2.43650, -2.42416, -2.37895, -2.16784, -1.80020, -1.59753, -1.59571, -1.57575, -1.55183, -1.36661, -1.38096, -1.45484, -1.54974, -1.66419, -1.71032, -1.77122, -1.82310, -1.99989, -2.18399, -2.11308, -2.06134, -1.99797, -1.83880, -1.70922, -1.67642, -1.70003, -1.66733, -1.69879, -1.79823, -1.92356, -1.96745, -2.01318, -2.06973, -2.04742, -2.09197, -2.19977, -2.14170, -2.01469, -1.94666, -1.92375, -2.08406, -2.08188, -2.13536, -2.26662, -2.36090, -2.45012, -2.61411, -2.88853, -3.01681, -2.98133, -3.07052, -3.07769, -3.06909, -3.03129, -3.08415, -3.28311, -3.46317, -3.54000, -3.53577, -3.64146, -3.71329, -3.73385, -3.56679, -3.29267, -3.10054, -2.97619, -2.99639, -2.99870, -2.78026, -2.50602, -2.39995, -2.28047, -2.27351, -2.08647, -1.82079, -1.60872, -1.44441, -1.34733, -1.15875, -0.93621, -0.72510, -0.57902, -0.50429, -0.25598, -0.05352, 0.08458, 0.35118, 0.59444, 0.78299, 0.99333, 1.26873, 1.50295, 1.66298, 1.78568, 1.94473, 2.04226, 2.08191, 2.23693, 2.32051, 2.21328, 2.05448, 1.95484, 1.73971, 1.49149, 1.18184, 1.08367, 1.00745, 0.87060, 0.84597, 0.86755, 0.78015, 0.63037, 0.61374, 0.66952, 0.48122, 0.33663, 0.30761, 0.31042, 0.38154, 0.26841, 0.11177, -0.03695, 0.01867, 0.16014, 0.20567, 0.09315, -0.01395, 0.01397, 0.08123, 0.18610, 0.13301, -0.05707, -0.25137, -0.31973, -0.40661, -0.47764, -0.70961, -0.86652, -0.89275, -0.94176, -1.05378, -1.25917, -1.39997, -1.52323, -1.65739, -1.73368, -1.81867, -1.76880, -1.65884, -1.64304, -1.56108, -1.55588, -1.66797, -1.83763, -1.94830, -2.05070, -2.12357, -2.11877, -2.03136, -1.92847, -1.92030, -1.83191, -1.74366, -1.76505, -1.65689, -1.38241, -1.28064, -1.27296, -1.28075, -1.20733, -1.15878, -1.21967, -1.17341, -1.15529, -1.23346, -1.25876, -1.09005, -0.76208, -0.63202, -0.65725, -0.66246, -0.76334, -0.67078, -0.54166, -0.52411, -0.57452, -0.48984, -0.16318, 0.18666, 0.43004, 0.50675, 0.56734, 0.50786, 0.53564, 0.69514, 0.75495, 0.77908, 0.91547, 1.00336, 0.98591, 0.76340, 0.44279, 0.31120, 0.16743, 0.02192, -0.17178, -0.34638, -0.53239, -0.65329, -0.69233, -0.80149, -0.88795, -0.83319, -0.80830, -0.70729, -0.65202, -0.64895, -0.63288, -0.55132, -0.44205, -0.43137, -0.42856, -0.45395, -0.42526, -0.37958, -0.35301, -0.41528, -0.66540, -0.83082, -0.81003, -0.95577, -1.14020, -1.17584, -1.20189, -1.12901, -1.08562, -0.95988, -0.82149, -0.82161, -0.97582, -1.16443, -1.28766, -1.36072, -1.43309, -1.43429, -1.59152, -1.68692, -1.64741, -1.66810, -1.82029, -2.04012, -2.14607, -2.30374, -2.35811, -2.27763, -2.11950, -2.07228, -2.08509, -1.99288, -2.05224, -2.23880, -2.27791, -2.21694, -2.18121, -2.20462, -2.37234, -2.35178, -2.39171, -2.43868, -2.48690, -2.55699, -2.60147, -2.57319, -2.39434, -2.22985, -2.21226, -2.00829, -1.80249, -1.61207, -1.48279, -1.51152, -1.55329, -1.55332, -1.37578, -1.12716, -0.88753, -0.76110, -0.60079, -0.37620, -0.20019, -0.10005, -0.09855, -0.07678, 0.00801, -0.02185, -0.11706, -0.12183, -0.20630, +-0.78823, -0.71593, -0.49712, -0.35458, -0.37039, -0.34182, -0.33831, -0.25189, -0.20488, -0.31810, -0.30429, -0.16785, -0.10762, 0.01347, 0.06521, 0.13961, 0.23558, 0.24884, 0.29037, 0.21009, 0.22682, 0.39563, 0.52065, 0.56863, 0.52521, 0.58774, 0.68221, 0.68421, 0.79148, 0.83881, 0.59047, 0.42622, 0.38263, 0.13455, -0.17000, -0.42798, -0.61286, -0.69484, -0.82346, -0.79621, -0.63483, -0.67883, -0.84741, -0.95530, -1.12329, -1.15591, -1.04437, -0.93829, -0.82754, -0.88208, -0.86959, -0.92996, -1.07713, -1.26739, -1.48706, -1.64426, -1.81954, -1.82407, -1.74545, -1.84869, -2.02166, -2.07424, -2.14077, -2.02864, -2.00848, -2.10956, -2.13807, -2.15336, -2.33811, -2.39799, -2.42898, -2.35391, -2.17740, -2.14479, -2.11137, -2.00574, -2.05375, -2.15646, -2.32556, -2.60593, -2.73595, -2.91044, -2.97120, -3.06534, -3.15160, -3.09447, -3.10047, -3.04956, -2.93068, -2.79291, -2.69955, -2.70212, -2.65484, -2.59073, -2.73038, -2.70960, -2.55256, -2.58433, -2.67641, -2.61762, -2.61387, -2.55490, -2.67205, -2.75382, -2.67224, -2.58017, -2.36255, -2.02593, -1.84042, -1.75914, -1.62627, -1.54902, -1.41837, -1.53808, -1.62462, -1.72709, -1.89199, -1.86469, -1.86789, -1.97571, -2.21861, -2.37261, -2.28972, -2.22915, -2.24639, -2.09609, -2.00861, -1.90442, -1.81151, -1.86057, -1.98848, -2.01094, -2.13890, -2.17603, -2.21570, -2.24054, -2.11073, -2.05141, -2.12053, -2.10355, -2.05901, -2.02068, -1.93422, -2.01946, -2.02036, -2.13734, -2.28221, -2.37219, -2.50209, -2.61044, -2.85533, -3.04246, -3.05604, -3.07386, -3.03314, -2.97893, -3.01636, -3.06166, -3.24814, -3.35697, -3.31124, -3.39184, -3.66925, -3.74178, -3.82051, -3.69896, -3.45213, -3.28551, -3.08019, -2.96806, -2.90769, -2.68494, -2.49142, -2.44440, -2.25481, -2.15820, -1.94681, -1.72475, -1.52754, -1.37462, -1.37667, -1.18816, -0.92530, -0.74759, -0.64807, -0.50324, -0.19476, 0.08536, 0.16994, 0.40419, 0.62575, 0.85579, 1.20114, 1.44477, 1.52086, 1.69396, 1.81580, 1.95763, 2.05204, 2.04527, 2.22885, 2.38376, 2.31860, 2.19453, 2.06466, 1.81863, 1.63576, 1.40162, 1.32133, 1.19302, 1.00832, 0.98509, 0.95884, 0.89768, 0.82107, 0.79755, 0.79402, 0.67638, 0.61364, 0.63343, 0.52468, 0.46413, 0.25538, 0.03560, -0.03976, -0.00813, -0.03999, 0.00719, -0.03287, -0.08265, 0.00910, 0.07500, 0.18939, 0.18613, 0.03653, -0.13011, -0.22783, -0.35722, -0.38168, -0.58184, -0.79771, -0.93382, -1.06328, -1.18206, -1.42431, -1.56068, -1.60468, -1.72301, -1.86317, -1.93207, -1.82753, -1.64351, -1.66772, -1.66225, -1.68137, -1.81579, -1.85777, -1.92234, -2.20016, -2.34708, -2.34593, -2.29408, -2.12831, -2.05413, -1.87041, -1.67126, -1.65025, -1.53734, -1.31041, -1.28198, -1.26960, -1.23336, -1.14934, -1.12914, -1.22879, -1.17862, -1.20086, -1.27492, -1.18071, -0.97249, -0.71962, -0.61648, -0.59918, -0.55611, -0.68939, -0.67210, -0.54973, -0.56076, -0.45910, -0.27422, -0.11548, 0.12530, 0.31570, 0.28515, 0.34551, 0.28096, 0.35141, 0.59516, 0.69989, 0.71436, 0.76941, 0.78166, 0.79485, 0.64838, 0.36429, 0.20096, -0.00572, -0.14988, -0.36923, -0.57909, -0.65277, -0.67366, -0.71924, -0.80700, -0.80454, -0.69717, -0.68119, -0.67138, -0.66608, -0.77382, -0.70610, -0.56457, -0.57939, -0.61916, -0.56821, -0.63413, -0.59220, -0.54748, -0.49095, -0.49864, -0.73652, -0.90977, -0.92702, -1.11776, -1.28579, -1.26860, -1.26212, -1.17525, -1.14517, -0.99781, -0.87495, -0.92861, -0.97498, -1.05983, -1.19190, -1.27362, -1.28856, -1.26806, -1.39184, -1.55746, -1.56107, -1.68464, -1.82895, -1.96751, -2.14525, -2.36034, -2.34168, -2.28039, -2.10137, -2.05988, -2.07678, -1.92246, -1.92120, -2.08282, -2.13921, -2.14813, -2.15296, -2.16074, -2.32564, -2.34882, -2.43998, -2.45891, -2.49628, -2.62511, -2.60357, -2.51730, -2.38926, -2.29016, -2.26745, -2.10780, -1.92245, -1.83950, -1.71281, -1.74573, -1.71344, -1.58177, -1.46073, -1.31292, -1.00298, -0.87741, -0.69576, -0.42789, -0.21361, -0.03052, 0.02861, 0.03946, 0.08671, 0.01544, -0.09061, -0.04922, -0.11131, +-0.87062, -0.81127, -0.62018, -0.49726, -0.48505, -0.40768, -0.32982, -0.27193, -0.28030, -0.29948, -0.26231, -0.15169, -0.02748, 0.11156, 0.17759, 0.27229, 0.43269, 0.51774, 0.58513, 0.52392, 0.46666, 0.52298, 0.59703, 0.69647, 0.76561, 0.89687, 0.96356, 0.88921, 0.96728, 0.99966, 0.81842, 0.69049, 0.57464, 0.36875, 0.12928, -0.15143, -0.40153, -0.54362, -0.60930, -0.59028, -0.54291, -0.61285, -0.84307, -1.02228, -1.06477, -0.96383, -0.82058, -0.74858, -0.67854, -0.69813, -0.68594, -0.74654, -0.94496, -1.22240, -1.43422, -1.55660, -1.76798, -1.85037, -1.83581, -1.97740, -2.12703, -2.19985, -2.23828, -2.09907, -2.13192, -2.22992, -2.25748, -2.30244, -2.47077, -2.50620, -2.45606, -2.39296, -2.34953, -2.31636, -2.25899, -2.18996, -2.10335, -2.09365, -2.22470, -2.50806, -2.72764, -2.93312, -3.07098, -3.14894, -3.18685, -3.18090, -3.21903, -3.18876, -3.05810, -2.85472, -2.74433, -2.77453, -2.70635, -2.61802, -2.71002, -2.68387, -2.69466, -2.83553, -2.90334, -2.84979, -2.84290, -2.81509, -2.90444, -2.95094, -2.89578, -2.73326, -2.46810, -2.24833, -2.03483, -1.85798, -1.70328, -1.59559, -1.49420, -1.54415, -1.57728, -1.64791, -1.85330, -1.97684, -2.02400, -2.10204, -2.31858, -2.44570, -2.39709, -2.41701, -2.40871, -2.24425, -2.13773, -1.95402, -1.89870, -1.97352, -2.06225, -2.13574, -2.31237, -2.37771, -2.37452, -2.30622, -2.15331, -2.03597, -1.98322, -2.05494, -2.06025, -2.01068, -1.99509, -2.03597, -2.00812, -2.05450, -2.19507, -2.30597, -2.40488, -2.55638, -2.83797, -3.02282, -3.02959, -2.96169, -2.90187, -2.96052, -3.07120, -3.14562, -3.26593, -3.23602, -3.20547, -3.35884, -3.63213, -3.73329, -3.78549, -3.63883, -3.38507, -3.21301, -3.09537, -3.00628, -2.85328, -2.68425, -2.48519, -2.29994, -2.04102, -1.86985, -1.70602, -1.50966, -1.31362, -1.17713, -1.18356, -1.09839, -0.94083, -0.80110, -0.67049, -0.44235, -0.10595, 0.13510, 0.23560, 0.48503, 0.71542, 0.98651, 1.23522, 1.36575, 1.44396, 1.62704, 1.80363, 1.97478, 2.12924, 2.16828, 2.24739, 2.29860, 2.26978, 2.14278, 2.05820, 1.95020, 1.78290, 1.55571, 1.47514, 1.38724, 1.21966, 1.17225, 1.16355, 1.11027, 0.98802, 0.90945, 0.86815, 0.81027, 0.83044, 0.81266, 0.63307, 0.48293, 0.19516, 0.01006, -0.05819, -0.07026, -0.09076, -0.06244, -0.09167, -0.10595, 0.03218, 0.17363, 0.24548, 0.21812, 0.19673, 0.02974, -0.15388, -0.24935, -0.25532, -0.43923, -0.68361, -0.86401, -1.02726, -1.19288, -1.39136, -1.52552, -1.63503, -1.76941, -1.87417, -1.86874, -1.72553, -1.63242, -1.76552, -1.79467, -1.83394, -1.87010, -1.85138, -1.96805, -2.21896, -2.40911, -2.49032, -2.49547, -2.32701, -2.08867, -1.82722, -1.63969, -1.56944, -1.50069, -1.33666, -1.22933, -1.19482, -1.16935, -1.07954, -1.00386, -1.06154, -1.09122, -1.17210, -1.25994, -1.19062, -1.00270, -0.76447, -0.66764, -0.63262, -0.60761, -0.72986, -0.64949, -0.52135, -0.47994, -0.34109, -0.23547, -0.11915, 0.06719, 0.18280, 0.15934, 0.25572, 0.26347, 0.27682, 0.40604, 0.56015, 0.60295, 0.58372, 0.64850, 0.71238, 0.58671, 0.36688, 0.21924, 0.03586, -0.14561, -0.35774, -0.55346, -0.69959, -0.79450, -0.86316, -0.90919, -0.83489, -0.70094, -0.70349, -0.67339, -0.67489, -0.81670, -0.79077, -0.81428, -0.89969, -0.87873, -0.80526, -0.83408, -0.79943, -0.70580, -0.60663, -0.66866, -0.89307, -1.04537, -1.12894, -1.20436, -1.29711, -1.34883, -1.38602, -1.29872, -1.16773, -1.01758, -0.90580, -0.95591, -1.03988, -1.09165, -1.10357, -1.08561, -1.05666, -1.09056, -1.31589, -1.50919, -1.55963, -1.70104, -1.78572, -1.92300, -2.05913, -2.22150, -2.27602, -2.24197, -2.05690, -1.94642, -1.91770, -1.84618, -1.86066, -1.95803, -2.04950, -2.00731, -1.95110, -2.00337, -2.16095, -2.19832, -2.25933, -2.35048, -2.45679, -2.58469, -2.62021, -2.53698, -2.37204, -2.23963, -2.16344, -2.08718, -2.06546, -2.07911, -1.99041, -1.95039, -1.78520, -1.67099, -1.61940, -1.45644, -1.13242, -0.94982, -0.73246, -0.39106, -0.06983, 0.11925, 0.13807, 0.13100, 0.03441, -0.00557, 0.03147, 0.06931, 0.01034, +-0.82609, -0.65169, -0.48594, -0.38870, -0.38314, -0.28039, -0.14790, -0.21059, -0.31931, -0.19550, -0.05693, 0.07177, 0.15704, 0.18701, 0.24800, 0.30028, 0.40541, 0.52208, 0.63605, 0.68334, 0.68690, 0.66316, 0.65829, 0.78162, 0.88379, 1.02463, 1.10460, 1.00797, 1.04729, 1.07496, 0.93278, 0.76258, 0.60756, 0.57033, 0.41640, 0.13345, -0.15603, -0.36365, -0.39241, -0.47603, -0.56130, -0.53711, -0.69494, -0.86881, -0.86497, -0.80434, -0.66353, -0.62623, -0.66329, -0.71555, -0.71896, -0.75143, -0.89200, -1.17117, -1.36766, -1.43302, -1.69443, -1.89268, -1.90841, -2.00137, -2.10211, -2.15484, -2.19942, -2.15568, -2.27256, -2.25708, -2.26846, -2.36264, -2.53356, -2.56829, -2.43178, -2.46468, -2.59198, -2.49786, -2.36823, -2.32508, -2.19920, -2.24051, -2.31804, -2.52960, -2.83894, -3.11894, -3.35283, -3.43098, -3.36624, -3.34961, -3.43145, -3.40673, -3.29704, -3.09902, -2.92819, -2.86835, -2.77421, -2.63111, -2.69260, -2.76924, -2.96245, -3.08458, -3.11259, -3.06260, -3.00989, -2.96232, -2.95630, -3.03954, -3.07835, -2.83834, -2.50085, -2.32964, -2.13293, -2.06043, -1.92741, -1.77629, -1.70853, -1.70393, -1.66208, -1.67357, -1.82793, -2.00124, -2.10569, -2.13082, -2.30789, -2.46604, -2.43723, -2.43564, -2.41296, -2.21149, -2.09138, -1.95432, -2.00890, -1.99400, -2.00399, -2.13934, -2.34983, -2.46089, -2.42443, -2.40240, -2.34237, -2.14842, -1.89522, -1.91096, -1.93321, -2.03482, -2.15372, -2.16615, -2.13641, -2.16186, -2.28732, -2.40628, -2.42464, -2.51996, -2.81469, -2.96725, -2.98462, -2.93707, -2.89186, -2.97994, -3.16065, -3.25952, -3.34171, -3.27578, -3.29236, -3.32736, -3.46631, -3.57982, -3.59448, -3.46789, -3.21486, -3.09936, -3.15875, -3.10840, -2.82111, -2.61117, -2.35897, -2.15482, -1.88052, -1.61271, -1.47744, -1.34154, -1.14462, -1.00771, -0.95416, -0.87088, -0.82925, -0.75109, -0.63895, -0.44699, -0.12603, 0.13667, 0.25358, 0.54473, 0.80034, 1.03749, 1.12538, 1.24418, 1.38338, 1.51066, 1.71424, 1.90270, 2.16620, 2.27075, 2.19672, 2.13871, 2.17645, 2.10581, 2.09481, 1.99774, 1.76575, 1.55661, 1.47090, 1.37950, 1.25217, 1.19553, 1.23063, 1.27317, 1.10779, 0.96644, 0.87657, 0.76183, 0.79366, 0.81369, 0.64383, 0.50463, 0.21429, 0.01990, -0.12334, -0.12355, -0.03608, -0.02390, -0.06122, -0.08394, 0.08421, 0.26712, 0.23024, 0.17776, 0.34104, 0.26794, 0.07952, -0.06197, -0.14436, -0.27341, -0.49664, -0.74622, -0.95176, -1.18663, -1.35669, -1.42200, -1.58705, -1.77193, -1.86085, -1.85081, -1.70935, -1.63347, -1.79654, -1.83217, -1.89473, -1.94486, -1.99680, -2.12119, -2.18487, -2.35052, -2.49011, -2.56188, -2.43230, -2.08752, -1.85648, -1.72118, -1.54637, -1.44656, -1.28557, -1.15642, -1.18915, -1.15214, -1.04464, -0.96046, -1.00674, -1.12479, -1.26071, -1.32097, -1.28310, -1.15219, -0.91640, -0.83877, -0.82067, -0.76986, -0.81144, -0.67970, -0.51843, -0.44752, -0.38280, -0.35205, -0.14497, 0.01256, 0.08026, 0.09254, 0.21581, 0.30593, 0.20372, 0.19728, 0.46656, 0.63556, 0.65182, 0.73968, 0.71825, 0.59661, 0.43250, 0.25702, 0.05359, -0.19915, -0.42478, -0.55421, -0.73998, -0.94516, -1.04852, -1.11398, -1.08779, -0.96256, -0.90859, -0.83257, -0.74604, -0.87329, -0.97182, -1.17095, -1.22055, -1.14536, -1.06282, -1.04722, -1.03987, -0.89763, -0.84507, -0.98756, -1.10772, -1.15513, -1.21520, -1.19093, -1.35511, -1.48121, -1.55106, -1.52657, -1.37165, -1.22710, -1.09138, -1.02789, -1.06690, -1.12209, -1.04436, -0.99569, -1.01427, -1.08874, -1.32607, -1.54349, -1.58450, -1.71576, -1.79505, -1.92775, -1.88622, -1.94767, -2.05925, -2.03524, -1.87399, -1.67598, -1.66490, -1.73166, -1.72567, -1.72500, -1.78747, -1.69152, -1.72346, -1.85845, -2.00114, -2.07424, -2.16479, -2.33470, -2.51194, -2.60129, -2.66404, -2.66297, -2.47475, -2.30856, -2.20116, -2.14331, -2.15578, -2.25194, -2.19244, -2.10404, -1.91157, -1.86868, -1.77023, -1.54897, -1.22993, -0.96908, -0.72239, -0.30377, 0.04661, 0.17736, 0.19135, 0.23712, 0.09496, 0.09200, 0.12069, 0.12946, 0.14279, +-0.63182, -0.43891, -0.27224, -0.16012, -0.23747, -0.24721, -0.15341, -0.18895, -0.25977, -0.12992, 0.05659, 0.25393, 0.29431, 0.28630, 0.36980, 0.33625, 0.36714, 0.52488, 0.64535, 0.74567, 0.90968, 0.96802, 0.93122, 1.05414, 1.13290, 1.21749, 1.26155, 1.16020, 1.18703, 1.18979, 0.99250, 0.76189, 0.66136, 0.67743, 0.57679, 0.36403, 0.06521, -0.24866, -0.33264, -0.40366, -0.44295, -0.38850, -0.50395, -0.64897, -0.73721, -0.80279, -0.67354, -0.66638, -0.72605, -0.70886, -0.69728, -0.74375, -0.79500, -1.00358, -1.23141, -1.29945, -1.54308, -1.78552, -1.83163, -1.90340, -1.96491, -2.01506, -2.10039, -2.17653, -2.30040, -2.28445, -2.29788, -2.38779, -2.60389, -2.76288, -2.65735, -2.62641, -2.64290, -2.50982, -2.38921, -2.38812, -2.37783, -2.51848, -2.52750, -2.68679, -2.99941, -3.24341, -3.49059, -3.61475, -3.46311, -3.33548, -3.43674, -3.43690, -3.33398, -3.20056, -3.02523, -2.92034, -2.77658, -2.61934, -2.69638, -2.90021, -3.09154, -3.19698, -3.21331, -3.11498, -3.02385, -3.03551, -3.03003, -3.09838, -3.10423, -2.90588, -2.63590, -2.46433, -2.31428, -2.33285, -2.14509, -1.96623, -1.92179, -1.86815, -1.78090, -1.80188, -1.82941, -1.83707, -1.94449, -1.98894, -2.14764, -2.37540, -2.36007, -2.34973, -2.30262, -2.09569, -1.97066, -1.96941, -2.04375, -2.00096, -1.99484, -2.06671, -2.21802, -2.43240, -2.47272, -2.53038, -2.45813, -2.21356, -1.92413, -1.86209, -1.90436, -2.15333, -2.28102, -2.27404, -2.25164, -2.21874, -2.28686, -2.43165, -2.37654, -2.31825, -2.58762, -2.76590, -2.79297, -2.85200, -2.87005, -2.99624, -3.16345, -3.25894, -3.32478, -3.34500, -3.31204, -3.21519, -3.27226, -3.34469, -3.36080, -3.40996, -3.27932, -3.21149, -3.22061, -3.09395, -2.78251, -2.51871, -2.27397, -2.19400, -1.90212, -1.55310, -1.35532, -1.13626, -0.88454, -0.80121, -0.73792, -0.55508, -0.53525, -0.55784, -0.50694, -0.42752, -0.15461, 0.07787, 0.21753, 0.53382, 0.82339, 1.01666, 1.12992, 1.30403, 1.42410, 1.48910, 1.68158, 1.79430, 2.02850, 2.14630, 2.12746, 2.11357, 2.13578, 2.09927, 2.10749, 1.90762, 1.67154, 1.52084, 1.44213, 1.39090, 1.33486, 1.24140, 1.28000, 1.45418, 1.32044, 1.12021, 1.01356, 0.82012, 0.80354, 0.80876, 0.68915, 0.60629, 0.34368, 0.06549, -0.13967, -0.13238, -0.03537, 0.00952, 0.03705, -0.01002, 0.08855, 0.21721, 0.18010, 0.15893, 0.32425, 0.31496, 0.21229, 0.01182, -0.09367, -0.15290, -0.36642, -0.61236, -0.78300, -1.09785, -1.33142, -1.30575, -1.43026, -1.68913, -1.80718, -1.83789, -1.71832, -1.59401, -1.66920, -1.66359, -1.75736, -1.94345, -2.09551, -2.16898, -2.17117, -2.28934, -2.39456, -2.51817, -2.49843, -2.19112, -1.91784, -1.71663, -1.53640, -1.42347, -1.24198, -1.19445, -1.27666, -1.18089, -1.06410, -0.96598, -0.95869, -1.12164, -1.31651, -1.30164, -1.21759, -1.16370, -0.96889, -0.91936, -0.95950, -0.92291, -0.94488, -0.81192, -0.63314, -0.55341, -0.51269, -0.39704, -0.16037, -0.03166, 0.00996, -0.03684, -0.04000, 0.02841, 0.00520, 0.09770, 0.40484, 0.61345, 0.68065, 0.72160, 0.64458, 0.58098, 0.42665, 0.24975, 0.08559, -0.22903, -0.55053, -0.62559, -0.72595, -0.93825, -1.05038, -1.14143, -1.23516, -1.19596, -1.13428, -0.99917, -0.85376, -0.96149, -1.16210, -1.35002, -1.39178, -1.32068, -1.21371, -1.20242, -1.32026, -1.23211, -1.16830, -1.23800, -1.30819, -1.32770, -1.32942, -1.31243, -1.54823, -1.61790, -1.66459, -1.65030, -1.44157, -1.28717, -1.17952, -0.99985, -0.89423, -0.95770, -0.93605, -0.94064, -1.05596, -1.14363, -1.33611, -1.47590, -1.47843, -1.59307, -1.76332, -1.84004, -1.72183, -1.71911, -1.74366, -1.69257, -1.66485, -1.53148, -1.53693, -1.55910, -1.51823, -1.53540, -1.57608, -1.49674, -1.64252, -1.78046, -1.92790, -2.03141, -2.07440, -2.19400, -2.42380, -2.48728, -2.49494, -2.58462, -2.46370, -2.28627, -2.21654, -2.15186, -2.16037, -2.22882, -2.16799, -2.07095, -1.98058, -1.92383, -1.78538, -1.55915, -1.21594, -0.92012, -0.76771, -0.40014, -0.05764, 0.14898, 0.22771, 0.28244, 0.19319, 0.21252, 0.16541, 0.23182, 0.33938, +-0.43126, -0.27039, -0.13559, -0.00919, -0.02350, -0.09433, -0.09906, -0.06151, -0.09952, -0.01909, 0.14547, 0.34607, 0.45903, 0.54490, 0.65849, 0.51166, 0.42361, 0.62244, 0.77145, 0.90948, 1.07469, 1.11058, 1.09796, 1.24949, 1.35196, 1.41534, 1.38723, 1.27700, 1.25705, 1.13244, 0.93912, 0.75348, 0.67878, 0.65804, 0.55126, 0.39247, 0.23973, -0.00455, -0.14459, -0.18221, -0.22517, -0.25885, -0.36670, -0.54012, -0.63444, -0.67128, -0.54890, -0.62730, -0.75119, -0.65644, -0.56898, -0.56580, -0.61789, -0.93034, -1.19090, -1.23406, -1.36943, -1.55824, -1.68093, -1.80843, -1.85359, -1.98845, -2.04577, -2.10745, -2.26250, -2.35951, -2.42385, -2.52296, -2.62368, -2.72231, -2.68392, -2.57275, -2.47649, -2.41965, -2.33830, -2.44863, -2.50904, -2.59780, -2.57706, -2.80070, -3.15697, -3.33341, -3.49749, -3.59478, -3.44152, -3.41097, -3.48763, -3.43940, -3.29759, -3.18609, -3.07835, -3.02552, -2.83868, -2.78481, -2.83975, -3.00604, -3.14363, -3.25105, -3.25040, -3.16203, -2.98952, -2.90660, -2.92529, -2.97401, -2.93431, -2.89808, -2.72630, -2.64285, -2.50683, -2.42488, -2.15460, -2.00075, -2.01476, -1.95369, -1.81115, -1.78852, -1.71102, -1.76767, -1.89834, -1.94577, -2.04732, -2.24101, -2.24706, -2.30866, -2.23822, -2.15909, -2.02994, -2.00035, -2.01078, -1.99792, -2.00298, -2.05732, -2.08535, -2.19394, -2.30055, -2.43456, -2.34137, -2.20568, -1.98810, -2.00136, -2.04871, -2.21274, -2.26353, -2.28415, -2.32713, -2.26980, -2.21067, -2.28219, -2.17642, -2.23387, -2.52620, -2.69232, -2.68450, -2.75953, -2.84697, -3.08688, -3.19516, -3.33465, -3.38335, -3.38751, -3.30640, -3.18543, -3.18980, -3.26649, -3.23840, -3.23704, -3.19745, -3.18885, -3.10093, -3.00445, -2.71697, -2.48638, -2.26061, -2.14784, -1.80700, -1.43138, -1.20194, -0.93141, -0.61012, -0.52093, -0.42530, -0.35166, -0.39151, -0.46743, -0.45511, -0.41638, -0.20076, -0.07125, 0.15007, 0.43341, 0.73141, 1.01765, 1.24578, 1.43731, 1.53212, 1.50733, 1.69755, 1.91106, 2.09407, 2.13673, 2.21379, 2.17160, 2.13410, 2.02991, 1.99665, 1.84775, 1.72597, 1.63071, 1.50137, 1.41947, 1.44346, 1.39093, 1.47285, 1.56010, 1.36719, 1.14986, 1.08493, 0.94507, 0.89789, 0.77127, 0.66995, 0.58750, 0.33338, 0.10606, -0.04944, -0.05723, 0.00529, 0.02806, 0.11414, 0.21583, 0.31072, 0.34791, 0.34489, 0.25206, 0.30153, 0.27310, 0.22413, 0.10351, 0.06916, 0.05211, -0.19178, -0.46130, -0.57233, -0.89721, -1.17260, -1.26234, -1.49013, -1.77187, -1.82967, -1.79786, -1.66253, -1.55698, -1.55271, -1.52131, -1.68476, -1.89763, -2.05108, -2.11997, -2.18604, -2.34039, -2.40449, -2.39547, -2.36570, -2.17224, -1.87091, -1.66446, -1.55076, -1.46093, -1.33372, -1.29186, -1.29622, -1.13423, -1.05466, -1.00551, -0.94914, -1.08191, -1.24209, -1.23573, -1.26890, -1.30077, -1.13249, -1.03661, -1.06581, -1.09914, -1.13952, -1.00811, -0.90229, -0.75672, -0.62067, -0.42165, -0.21542, -0.12459, -0.11709, -0.11846, -0.13355, -0.13251, -0.04553, 0.11859, 0.31873, 0.50632, 0.56047, 0.63944, 0.67203, 0.67551, 0.45682, 0.21106, 0.07095, -0.21056, -0.50458, -0.59657, -0.80831, -1.01177, -1.07869, -1.11978, -1.24386, -1.32647, -1.33282, -1.15350, -1.10533, -1.17060, -1.30365, -1.42609, -1.51354, -1.49481, -1.42330, -1.32774, -1.38117, -1.38397, -1.34005, -1.38031, -1.54771, -1.56670, -1.58365, -1.53788, -1.65355, -1.60628, -1.61702, -1.59568, -1.35605, -1.17694, -1.05538, -0.82084, -0.80111, -0.89215, -0.88977, -0.88693, -1.00847, -1.12860, -1.33709, -1.35528, -1.39699, -1.44275, -1.55801, -1.58953, -1.51490, -1.48584, -1.45778, -1.32494, -1.27166, -1.24595, -1.27713, -1.23662, -1.29791, -1.37653, -1.51196, -1.46165, -1.54071, -1.59548, -1.73308, -1.89429, -1.92845, -1.96100, -2.15602, -2.19673, -2.36755, -2.56164, -2.47802, -2.26701, -2.20299, -2.16818, -2.22967, -2.20505, -2.21942, -2.13305, -2.02613, -1.90896, -1.77718, -1.57267, -1.29321, -0.97575, -0.75349, -0.44969, -0.14398, 0.15222, 0.18158, 0.24388, 0.19012, 0.28430, 0.34419, 0.50159, 0.64801, +-0.31972, -0.09926, 0.02872, 0.10988, 0.11934, 0.05593, -0.00812, 0.00604, 0.02951, 0.16699, 0.34269, 0.46628, 0.55061, 0.68837, 0.78986, 0.62744, 0.53896, 0.73432, 0.89756, 1.02338, 1.15222, 1.26719, 1.35144, 1.46184, 1.46564, 1.45141, 1.44968, 1.37428, 1.27026, 1.05953, 0.86355, 0.73869, 0.69635, 0.70468, 0.59352, 0.41022, 0.31759, 0.23624, 0.14065, 0.02670, -0.11880, -0.22021, -0.28440, -0.47290, -0.56769, -0.51549, -0.42761, -0.59653, -0.75134, -0.65401, -0.50061, -0.39998, -0.43909, -0.74555, -0.99505, -1.08177, -1.22387, -1.45046, -1.62538, -1.78274, -1.84637, -1.95761, -1.99213, -2.01198, -2.15888, -2.27974, -2.40602, -2.57724, -2.59642, -2.55651, -2.50388, -2.44000, -2.37905, -2.34759, -2.24400, -2.38227, -2.50120, -2.55767, -2.62838, -2.99435, -3.32804, -3.41132, -3.46474, -3.48541, -3.40020, -3.41400, -3.38190, -3.30050, -3.22094, -3.23508, -3.17845, -3.09354, -2.92420, -2.89340, -2.94031, -3.04661, -3.12280, -3.08944, -3.03630, -3.05664, -2.96745, -2.83536, -2.79373, -2.84720, -2.81228, -2.79821, -2.65543, -2.64868, -2.59354, -2.45766, -2.18266, -2.07879, -2.04698, -1.95363, -1.80905, -1.70928, -1.62180, -1.73414, -1.87099, -1.96610, -2.06859, -2.27739, -2.29445, -2.30462, -2.22608, -2.19393, -2.10524, -2.03022, -1.93647, -1.82852, -1.81976, -1.96660, -2.04047, -2.06209, -2.10252, -2.23939, -2.18999, -2.13627, -2.02715, -2.14628, -2.22075, -2.25893, -2.25164, -2.36639, -2.45135, -2.35898, -2.18941, -2.10606, -2.02247, -2.20229, -2.45943, -2.59083, -2.59902, -2.76506, -2.92525, -3.15852, -3.23724, -3.30149, -3.33667, -3.37452, -3.35028, -3.19149, -3.10583, -3.20064, -3.17710, -3.07885, -3.00585, -3.03985, -2.99138, -2.93605, -2.65336, -2.40733, -2.18411, -2.02038, -1.69588, -1.39400, -1.14481, -0.84263, -0.54233, -0.39531, -0.26995, -0.26550, -0.29690, -0.36376, -0.39083, -0.47642, -0.37318, -0.22998, 0.09703, 0.43459, 0.74754, 1.05275, 1.30998, 1.58671, 1.77148, 1.73747, 1.86782, 2.10595, 2.25165, 2.21134, 2.28968, 2.25326, 2.21219, 2.04792, 1.91311, 1.79957, 1.78481, 1.67580, 1.49538, 1.40032, 1.45664, 1.52820, 1.65456, 1.64206, 1.44643, 1.24906, 1.19796, 1.06945, 0.94104, 0.71822, 0.55552, 0.47563, 0.29275, 0.13332, 0.06446, 0.15938, 0.27542, 0.25717, 0.26514, 0.39331, 0.54049, 0.57073, 0.55465, 0.38571, 0.34410, 0.29850, 0.23093, 0.12428, 0.09647, 0.02753, -0.20400, -0.42047, -0.52237, -0.77104, -1.02964, -1.27319, -1.58076, -1.82502, -1.80103, -1.75718, -1.67313, -1.60262, -1.57111, -1.49797, -1.60386, -1.77280, -1.91508, -1.97612, -2.09118, -2.31018, -2.39151, -2.30214, -2.19229, -2.07479, -1.87016, -1.70970, -1.57682, -1.47453, -1.44437, -1.45824, -1.39568, -1.22214, -1.16638, -1.11889, -1.06731, -1.14002, -1.19156, -1.18186, -1.28823, -1.40661, -1.35444, -1.29871, -1.34722, -1.38784, -1.35645, -1.17604, -1.05524, -0.89513, -0.72599, -0.47932, -0.21617, -0.10595, -0.14213, -0.17406, -0.17858, -0.19544, -0.12334, -0.00550, 0.11120, 0.29479, 0.36442, 0.46677, 0.59069, 0.63491, 0.38483, 0.11019, -0.06881, -0.28147, -0.41195, -0.52881, -0.82184, -1.05215, -1.14911, -1.18398, -1.33083, -1.43487, -1.43381, -1.27322, -1.29650, -1.36802, -1.40026, -1.42375, -1.44724, -1.48533, -1.53422, -1.45184, -1.39792, -1.41958, -1.48931, -1.61579, -1.80883, -1.77902, -1.78661, -1.75252, -1.75722, -1.63341, -1.57387, -1.43864, -1.20974, -1.08328, -0.93197, -0.70384, -0.71652, -0.78787, -0.76783, -0.74520, -0.92566, -1.08701, -1.26702, -1.23669, -1.21971, -1.17453, -1.18394, -1.19505, -1.10805, -1.06452, -1.08522, -1.01929, -0.97935, -0.98152, -1.03452, -1.02033, -1.13416, -1.19893, -1.37243, -1.42119, -1.47747, -1.46419, -1.55468, -1.69790, -1.76767, -1.84704, -1.96517, -1.99052, -2.21828, -2.40249, -2.35319, -2.18799, -2.26978, -2.29929, -2.28606, -2.18327, -2.18173, -2.14495, -2.04195, -1.88589, -1.65623, -1.44888, -1.30800, -1.10309, -0.83819, -0.50558, -0.22896, 0.03891, 0.05233, 0.17666, 0.25258, 0.42376, 0.54585, 0.69075, 0.77169, +-0.44003, -0.17043, 0.06901, 0.11752, 0.12638, 0.16767, 0.08935, 0.04606, 0.11309, 0.30124, 0.52396, 0.51077, 0.45147, 0.61648, 0.77331, 0.68642, 0.68273, 0.88033, 0.98412, 1.11019, 1.27773, 1.56321, 1.73228, 1.75371, 1.74690, 1.68196, 1.63354, 1.54769, 1.33001, 1.05808, 0.86111, 0.71983, 0.67139, 0.69856, 0.69796, 0.50597, 0.35786, 0.39675, 0.33163, 0.12881, -0.05907, -0.18142, -0.19754, -0.43979, -0.62607, -0.51077, -0.40776, -0.59129, -0.74896, -0.66881, -0.55821, -0.42976, -0.41192, -0.56932, -0.75709, -0.94613, -1.07930, -1.34216, -1.59497, -1.76653, -1.86999, -1.97768, -2.00631, -2.07002, -2.15943, -2.25789, -2.32643, -2.53866, -2.64281, -2.52157, -2.42870, -2.45687, -2.44331, -2.39564, -2.24061, -2.37749, -2.59353, -2.62739, -2.70801, -3.05746, -3.31114, -3.29877, -3.33551, -3.36014, -3.30695, -3.24617, -3.10481, -3.09671, -3.03475, -3.09150, -3.08744, -2.96377, -2.82725, -2.83273, -2.85778, -3.02126, -3.07448, -2.98602, -2.83807, -2.87959, -2.95153, -2.82927, -2.72957, -2.81687, -2.78059, -2.72876, -2.59069, -2.64898, -2.76525, -2.64018, -2.35327, -2.20991, -2.10258, -1.92874, -1.82929, -1.75849, -1.69835, -1.78919, -1.86665, -2.06378, -2.14875, -2.30558, -2.35904, -2.28837, -2.11683, -2.08799, -2.00207, -2.02628, -1.92968, -1.81334, -1.74132, -1.90637, -2.14424, -2.16020, -2.09665, -2.21007, -2.16391, -2.11055, -2.03881, -2.16860, -2.32487, -2.30636, -2.23988, -2.34110, -2.42797, -2.26904, -2.09123, -2.00629, -1.93840, -2.10071, -2.20839, -2.34369, -2.36475, -2.53403, -2.78956, -3.04427, -3.11798, -3.19598, -3.22805, -3.39363, -3.45151, -3.33276, -3.15298, -3.15268, -3.20107, -3.08969, -2.94157, -3.01132, -3.01342, -2.95280, -2.66700, -2.37769, -2.22372, -2.05914, -1.73447, -1.42741, -1.18124, -0.83539, -0.58150, -0.48087, -0.34279, -0.32081, -0.24930, -0.29823, -0.28287, -0.33471, -0.33496, -0.23691, 0.12538, 0.44863, 0.78733, 0.99152, 1.19224, 1.48391, 1.79082, 1.92119, 1.98455, 2.16042, 2.34875, 2.29304, 2.36891, 2.38228, 2.35688, 2.19220, 1.91831, 1.76062, 1.80419, 1.73487, 1.55283, 1.52045, 1.61307, 1.69770, 1.83581, 1.80404, 1.70863, 1.49952, 1.39985, 1.30994, 1.07468, 0.74642, 0.54424, 0.41457, 0.29459, 0.13781, 0.08534, 0.22597, 0.40326, 0.47144, 0.36543, 0.38814, 0.59203, 0.62269, 0.58139, 0.40667, 0.32126, 0.28271, 0.09836, -0.10361, -0.12102, -0.16264, -0.33716, -0.46072, -0.55800, -0.78485, -0.97697, -1.25833, -1.51928, -1.76580, -1.77343, -1.65947, -1.61584, -1.64141, -1.61111, -1.54052, -1.56994, -1.69423, -1.88250, -1.97406, -2.09211, -2.20158, -2.29276, -2.25218, -2.06699, -1.98781, -1.88089, -1.73259, -1.58048, -1.45066, -1.53177, -1.64971, -1.50360, -1.25871, -1.16810, -1.08237, -1.03621, -1.15371, -1.18459, -1.18076, -1.25904, -1.42402, -1.53988, -1.49220, -1.56077, -1.64402, -1.54550, -1.34449, -1.20705, -1.04769, -0.96162, -0.72881, -0.43895, -0.20536, -0.23545, -0.37780, -0.36638, -0.39126, -0.40394, -0.32501, -0.22788, -0.01724, 0.03701, 0.06722, 0.26431, 0.44915, 0.34081, 0.12309, -0.06860, -0.34418, -0.45621, -0.58389, -0.84151, -1.08643, -1.30506, -1.29774, -1.40356, -1.51914, -1.49108, -1.35911, -1.40801, -1.43093, -1.47496, -1.44976, -1.45101, -1.44373, -1.53497, -1.58477, -1.50790, -1.53338, -1.70847, -1.85536, -1.97072, -1.85425, -1.84707, -1.89702, -1.82170, -1.60291, -1.41988, -1.20060, -0.97193, -0.94767, -0.85934, -0.65710, -0.61289, -0.61674, -0.65403, -0.58253, -0.74342, -0.96435, -1.13195, -1.08173, -1.03305, -0.88228, -0.89047, -0.89653, -0.83943, -0.74509, -0.77542, -0.88293, -0.90187, -0.89791, -0.99790, -1.00696, -1.09297, -1.05754, -1.16432, -1.34884, -1.42455, -1.38071, -1.39073, -1.50243, -1.58438, -1.79983, -1.97777, -1.99301, -2.13958, -2.19234, -2.21094, -2.06166, -2.14267, -2.21076, -2.14326, -1.98941, -2.01026, -1.98749, -1.99181, -1.86407, -1.64918, -1.40967, -1.27388, -1.21534, -0.95258, -0.54815, -0.30054, -0.05053, 0.02015, 0.21831, 0.41464, 0.53729, 0.65244, 0.81161, 0.91884, +-0.44694, -0.24364, -0.01096, 0.09001, 0.20235, 0.27867, 0.23146, 0.15177, 0.12545, 0.28265, 0.48933, 0.47350, 0.44752, 0.60172, 0.79591, 0.77790, 0.74657, 0.90068, 1.06440, 1.31085, 1.52271, 1.78952, 2.03231, 2.09748, 2.06941, 1.99456, 1.85957, 1.61658, 1.30124, 1.00073, 0.85582, 0.82168, 0.74592, 0.70753, 0.72729, 0.59261, 0.50377, 0.51978, 0.44646, 0.23618, 0.01180, -0.10556, -0.13275, -0.38198, -0.56511, -0.52123, -0.47238, -0.63081, -0.84680, -0.84222, -0.70604, -0.49675, -0.44393, -0.59237, -0.70375, -0.81578, -0.95654, -1.20555, -1.48112, -1.74370, -1.90016, -2.01968, -2.04174, -2.01296, -2.05987, -2.20512, -2.27332, -2.49420, -2.61704, -2.53943, -2.44140, -2.46636, -2.50721, -2.47667, -2.34924, -2.49701, -2.68404, -2.70899, -2.75164, -2.94199, -3.14106, -3.16112, -3.16466, -3.11796, -3.06224, -3.03646, -2.87863, -2.80250, -2.76886, -2.83380, -2.84843, -2.81614, -2.74269, -2.74694, -2.73458, -2.78718, -2.81831, -2.82500, -2.69302, -2.71994, -2.75696, -2.66338, -2.58049, -2.65852, -2.70159, -2.72767, -2.67033, -2.78273, -2.90996, -2.79320, -2.53117, -2.31883, -2.20462, -2.07782, -1.96187, -1.81455, -1.74359, -1.87711, -1.95223, -2.05920, -2.15699, -2.29664, -2.34531, -2.29840, -2.07501, -1.98789, -1.88435, -1.86341, -1.81815, -1.83338, -1.78179, -1.95467, -2.16798, -2.19706, -2.14565, -2.23031, -2.23450, -2.20770, -2.11603, -2.18381, -2.27257, -2.21965, -2.16971, -2.19888, -2.26688, -2.16214, -2.00370, -1.85953, -1.75906, -1.92254, -1.97580, -1.96208, -1.99116, -2.18363, -2.48733, -2.86364, -3.03645, -3.17343, -3.24019, -3.33781, -3.36319, -3.33114, -3.15569, -3.13656, -3.15411, -3.07262, -2.96762, -3.00387, -3.03808, -2.99833, -2.72318, -2.45876, -2.30322, -2.12312, -1.84718, -1.49695, -1.22923, -0.93065, -0.68112, -0.51001, -0.34747, -0.36803, -0.32043, -0.21967, -0.10925, -0.11734, -0.13094, -0.16297, 0.05403, 0.32538, 0.66260, 0.93654, 1.19757, 1.43365, 1.74189, 1.90283, 2.01476, 2.20342, 2.40352, 2.43848, 2.50740, 2.48355, 2.45355, 2.27643, 2.02305, 1.90756, 1.91377, 1.88815, 1.75824, 1.70662, 1.81117, 1.96620, 2.13201, 2.07181, 1.94697, 1.80611, 1.67957, 1.50867, 1.20433, 0.79849, 0.52727, 0.38792, 0.30526, 0.24560, 0.27039, 0.33253, 0.44586, 0.50108, 0.40782, 0.43093, 0.58255, 0.60543, 0.51281, 0.26807, 0.15174, 0.08118, -0.10452, -0.27611, -0.31672, -0.31741, -0.42426, -0.56776, -0.69252, -0.82625, -0.90553, -1.18691, -1.49533, -1.71935, -1.74119, -1.63934, -1.58523, -1.65118, -1.69517, -1.64505, -1.64907, -1.71163, -1.82616, -1.96631, -2.11105, -2.15601, -2.19335, -2.12894, -1.98572, -1.91033, -1.82187, -1.72560, -1.59796, -1.49962, -1.58103, -1.64773, -1.48167, -1.20712, -1.06366, -1.01498, -1.02798, -1.12910, -1.13194, -1.18411, -1.34767, -1.49316, -1.59720, -1.60764, -1.70248, -1.83188, -1.83509, -1.69726, -1.55330, -1.34090, -1.15562, -0.93636, -0.72170, -0.48882, -0.49645, -0.61038, -0.63090, -0.65573, -0.67457, -0.65743, -0.58274, -0.40269, -0.35968, -0.29888, -0.08287, 0.20316, 0.29401, 0.12983, -0.10728, -0.42364, -0.54331, -0.69305, -0.99141, -1.20239, -1.34836, -1.36527, -1.47546, -1.62788, -1.70498, -1.61990, -1.60529, -1.51675, -1.42756, -1.39233, -1.48696, -1.49904, -1.59071, -1.63998, -1.63900, -1.70428, -1.86619, -2.01624, -2.06526, -1.90364, -1.85827, -1.83142, -1.69712, -1.44533, -1.16757, -0.97333, -0.83070, -0.80278, -0.65645, -0.47086, -0.49389, -0.50892, -0.49557, -0.47167, -0.61867, -0.82512, -1.04366, -0.99416, -0.89230, -0.67619, -0.56121, -0.54950, -0.60100, -0.52686, -0.56470, -0.66979, -0.74738, -0.80122, -0.91171, -0.98542, -1.08064, -0.98963, -1.03104, -1.17120, -1.23954, -1.27040, -1.25377, -1.37191, -1.53967, -1.78858, -1.92068, -1.93297, -2.11280, -2.15372, -2.06683, -1.91597, -1.93198, -1.94275, -1.93643, -1.83531, -1.87091, -1.85408, -1.79195, -1.67607, -1.61139, -1.42721, -1.31126, -1.21529, -0.93752, -0.54331, -0.25194, -0.00968, 0.08298, 0.31608, 0.52804, 0.66994, 0.82178, 0.98294, 1.17952, +-0.47322, -0.28785, -0.13321, 0.03797, 0.30288, 0.37122, 0.38719, 0.27496, 0.14758, 0.28177, 0.42053, 0.44899, 0.57890, 0.70195, 0.86127, 0.89228, 0.89956, 1.01436, 1.12106, 1.44305, 1.77004, 2.01460, 2.19570, 2.19051, 2.11578, 2.06166, 1.99453, 1.72038, 1.31545, 1.05701, 0.82716, 0.74809, 0.72865, 0.73679, 0.78014, 0.73350, 0.74627, 0.63406, 0.52562, 0.30510, 0.03960, 0.01983, 0.00401, -0.20052, -0.31631, -0.44621, -0.59324, -0.76501, -0.96059, -0.95925, -0.87539, -0.63531, -0.50039, -0.60636, -0.73139, -0.85532, -0.96529, -1.12663, -1.33544, -1.60736, -1.88429, -1.96108, -2.05800, -2.08297, -2.01218, -2.07406, -2.16363, -2.37275, -2.43670, -2.49508, -2.44953, -2.48009, -2.57918, -2.49491, -2.40701, -2.56600, -2.70207, -2.79089, -2.89616, -2.93399, -2.98011, -2.92473, -2.98008, -2.94974, -2.87521, -2.83216, -2.69372, -2.61755, -2.62675, -2.68750, -2.70678, -2.69056, -2.73960, -2.63514, -2.55406, -2.61204, -2.57314, -2.58628, -2.52668, -2.57803, -2.49549, -2.44506, -2.38219, -2.42916, -2.60547, -2.69173, -2.74524, -2.89942, -2.96898, -2.88229, -2.73291, -2.50125, -2.34867, -2.15431, -2.08082, -1.91024, -1.75408, -1.82804, -1.97756, -2.16058, -2.35032, -2.47363, -2.48073, -2.32107, -2.09098, -1.86025, -1.72338, -1.77681, -1.74154, -1.77816, -1.78483, -2.00461, -2.06591, -2.10747, -2.11072, -2.18350, -2.34833, -2.33814, -2.22560, -2.20334, -2.13885, -2.05916, -2.12856, -2.16611, -2.20491, -2.01801, -1.87994, -1.71129, -1.56092, -1.64749, -1.73558, -1.75293, -1.84748, -2.01134, -2.26656, -2.58871, -2.92227, -3.11831, -3.22086, -3.39397, -3.34930, -3.22366, -3.01758, -3.03643, -2.96809, -2.95693, -2.98002, -2.96508, -3.07694, -3.01552, -2.72265, -2.49980, -2.31339, -2.12582, -1.99650, -1.66503, -1.31997, -0.90673, -0.69135, -0.55811, -0.40875, -0.39372, -0.39642, -0.28083, -0.11592, -0.03836, -0.00588, 0.02634, 0.06445, 0.25425, 0.57895, 0.78110, 1.13100, 1.46957, 1.81642, 1.90472, 2.06192, 2.24652, 2.37831, 2.53782, 2.57011, 2.52673, 2.52556, 2.32413, 2.14582, 2.12957, 2.07985, 2.06256, 1.98351, 2.01478, 2.06889, 2.14934, 2.30052, 2.33394, 2.22832, 2.03477, 1.77917, 1.48035, 1.12836, 0.82253, 0.53745, 0.43822, 0.47681, 0.39697, 0.42951, 0.48120, 0.53631, 0.48486, 0.42741, 0.49310, 0.53055, 0.55785, 0.37713, 0.06582, -0.02216, -0.10293, -0.19690, -0.27508, -0.43528, -0.52844, -0.62343, -0.68756, -0.80762, -0.93331, -0.91814, -1.09603, -1.40810, -1.68635, -1.82487, -1.79612, -1.74107, -1.69914, -1.72255, -1.69990, -1.61757, -1.76165, -1.93315, -2.04199, -2.14502, -2.16909, -2.13022, -1.99296, -1.96900, -1.90028, -1.84227, -1.78182, -1.55475, -1.45565, -1.50665, -1.49619, -1.44737, -1.30316, -1.16343, -1.03028, -0.98588, -1.13635, -1.17585, -1.25562, -1.46392, -1.64952, -1.79825, -1.84745, -1.91820, -1.98016, -2.01974, -2.02481, -1.82994, -1.65252, -1.48196, -1.18056, -0.93807, -0.76307, -0.76503, -0.77922, -0.86905, -0.84819, -0.81763, -0.88401, -0.80112, -0.71842, -0.72198, -0.60187, -0.44210, -0.16877, 0.09446, 0.08479, -0.05795, -0.43617, -0.62677, -0.78510, -1.07938, -1.28239, -1.40806, -1.46785, -1.57405, -1.74850, -1.89056, -1.95239, -1.82642, -1.66863, -1.58120, -1.47331, -1.55969, -1.64720, -1.77719, -1.72767, -1.78142, -1.85416, -1.97781, -2.18070, -2.14169, -1.96903, -1.87822, -1.66602, -1.46768, -1.29701, -1.02955, -0.87162, -0.69960, -0.69360, -0.51215, -0.27938, -0.27737, -0.34885, -0.42087, -0.51369, -0.63359, -0.76335, -0.88138, -0.86973, -0.64965, -0.41298, -0.35836, -0.29790, -0.32160, -0.24576, -0.28924, -0.30462, -0.47567, -0.64512, -0.77517, -0.96968, -1.02780, -0.89293, -0.87140, -0.90318, -0.96261, -1.14529, -1.19969, -1.34284, -1.47065, -1.74032, -1.84225, -1.82708, -1.96346, -2.08258, -2.07086, -1.99567, -1.93642, -1.83141, -1.72653, -1.72694, -1.74116, -1.74279, -1.78132, -1.62785, -1.51213, -1.35397, -1.32435, -1.14470, -0.89664, -0.57350, -0.20702, 0.03509, 0.23756, 0.50690, 0.66805, 0.81709, 0.99044, 1.07246, 1.30932, +-0.56969, -0.42461, -0.20187, 0.04279, 0.26746, 0.32853, 0.37760, 0.34199, 0.27980, 0.36004, 0.46592, 0.52118, 0.67718, 0.85653, 1.09476, 1.20854, 1.14998, 1.12955, 1.14165, 1.41683, 1.74130, 1.95350, 2.13572, 2.11529, 1.98584, 1.92202, 1.95498, 1.82234, 1.38164, 1.00648, 0.74342, 0.65955, 0.61446, 0.60197, 0.76015, 0.86393, 0.85168, 0.68680, 0.58476, 0.40974, 0.19713, 0.19977, 0.22187, 0.09458, -0.05599, -0.26843, -0.46910, -0.66709, -0.94002, -1.04943, -0.99169, -0.75317, -0.59660, -0.67335, -0.74963, -0.83085, -0.91056, -1.04070, -1.19171, -1.34813, -1.65052, -1.84578, -1.99716, -2.05104, -2.04018, -2.14571, -2.18205, -2.17463, -2.19832, -2.33970, -2.38950, -2.47296, -2.53440, -2.44268, -2.34848, -2.43367, -2.63145, -2.81627, -2.92390, -2.89179, -2.87964, -2.87975, -2.94607, -2.94711, -2.90122, -2.86713, -2.67192, -2.51920, -2.55121, -2.64977, -2.67479, -2.58044, -2.66187, -2.63986, -2.50532, -2.48455, -2.44514, -2.51275, -2.44572, -2.34138, -2.25686, -2.26277, -2.22787, -2.27256, -2.43677, -2.54111, -2.63634, -2.74752, -2.85096, -2.84058, -2.68116, -2.42958, -2.29073, -2.19936, -2.15246, -1.98477, -1.79759, -1.87625, -2.06464, -2.26689, -2.50435, -2.64435, -2.62474, -2.34071, -2.10537, -1.95837, -1.81500, -1.74488, -1.66531, -1.77939, -1.86688, -1.95718, -1.93502, -1.97938, -1.97425, -2.04835, -2.27313, -2.32212, -2.25901, -2.14705, -2.03932, -2.02446, -2.08298, -2.10219, -2.14684, -2.05870, -1.91666, -1.71819, -1.54553, -1.59919, -1.67802, -1.67299, -1.80308, -1.97220, -2.16925, -2.37071, -2.72744, -3.08030, -3.23049, -3.33975, -3.25160, -3.14261, -2.96489, -2.83288, -2.70763, -2.74260, -2.81042, -2.80252, -2.90037, -2.79891, -2.50535, -2.24344, -2.09253, -2.03255, -1.94579, -1.60567, -1.22815, -0.90992, -0.75619, -0.65632, -0.51325, -0.49229, -0.50127, -0.36259, -0.20611, -0.11191, -0.01219, 0.22082, 0.29656, 0.29424, 0.44535, 0.64768, 1.08860, 1.45942, 1.82868, 2.06063, 2.23215, 2.31961, 2.37566, 2.52831, 2.57419, 2.55544, 2.56396, 2.43618, 2.30481, 2.25119, 2.26474, 2.32734, 2.27318, 2.20910, 2.15985, 2.15177, 2.24730, 2.30614, 2.24491, 2.06250, 1.72482, 1.32822, 0.99412, 0.85356, 0.70212, 0.56636, 0.55635, 0.53571, 0.61815, 0.61779, 0.56156, 0.53777, 0.52075, 0.54655, 0.54616, 0.54642, 0.34737, 0.05243, -0.03483, -0.04618, -0.07531, -0.23846, -0.46653, -0.57945, -0.66436, -0.78366, -0.96648, -1.13441, -1.14544, -1.30158, -1.56244, -1.72533, -1.87113, -1.95693, -1.97491, -1.83364, -1.69057, -1.69185, -1.66267, -1.79046, -1.97629, -2.15174, -2.33912, -2.28870, -2.13072, -2.01411, -2.02874, -1.98004, -1.91959, -1.80164, -1.50298, -1.33539, -1.35610, -1.43058, -1.48762, -1.42090, -1.34097, -1.25991, -1.25707, -1.42844, -1.51681, -1.61473, -1.77619, -1.87969, -1.99664, -2.09396, -2.17612, -2.14341, -2.04412, -2.09719, -2.02945, -1.86757, -1.66038, -1.35497, -1.15228, -0.95698, -0.85083, -0.86949, -0.96268, -0.89268, -0.81762, -0.89121, -0.86739, -0.84356, -0.84822, -0.80804, -0.72894, -0.46636, -0.16381, -0.12834, -0.24959, -0.53213, -0.73792, -0.95489, -1.27175, -1.38933, -1.40869, -1.48953, -1.60512, -1.78208, -1.90779, -2.09642, -2.15098, -2.00000, -1.85303, -1.73578, -1.87093, -1.98174, -2.00677, -1.95479, -1.99780, -2.04158, -2.13803, -2.28093, -2.20020, -2.01112, -1.84122, -1.57974, -1.37598, -1.20258, -0.97333, -0.87029, -0.75605, -0.70526, -0.50236, -0.28082, -0.27612, -0.30345, -0.32644, -0.44937, -0.56826, -0.62229, -0.54940, -0.47515, -0.33322, -0.12940, -0.06139, -0.01886, -0.08858, 0.00062, 0.11181, 0.08128, -0.15969, -0.37054, -0.51063, -0.70064, -0.76340, -0.68760, -0.64731, -0.70149, -0.80134, -0.92972, -1.01492, -1.25134, -1.52837, -1.77637, -1.82513, -1.79699, -1.88997, -2.00474, -2.02180, -2.04191, -2.04027, -1.88473, -1.62061, -1.58740, -1.71753, -1.79121, -1.82499, -1.65800, -1.54376, -1.41816, -1.28784, -1.09793, -0.90202, -0.60681, -0.23014, 0.09562, 0.38887, 0.65032, 0.82198, 0.93461, 1.04878, 1.16600, 1.44373, +-0.57664, -0.44458, -0.30101, -0.06635, 0.06406, 0.06420, 0.14873, 0.20521, 0.24731, 0.30088, 0.39562, 0.44573, 0.61844, 0.93700, 1.22847, 1.44351, 1.48806, 1.42831, 1.35135, 1.50963, 1.74902, 1.90787, 2.09783, 2.05597, 1.90552, 1.87222, 1.83559, 1.66965, 1.36375, 0.99639, 0.72616, 0.74267, 0.75880, 0.69697, 0.72755, 0.82435, 0.80350, 0.67310, 0.67376, 0.58350, 0.39868, 0.32649, 0.30403, 0.20770, 0.06623, -0.00845, -0.18747, -0.43317, -0.69831, -0.85869, -0.84149, -0.62820, -0.47826, -0.54747, -0.58823, -0.68893, -0.81952, -0.93346, -1.11329, -1.27147, -1.38670, -1.52632, -1.78086, -1.85851, -1.93908, -2.13781, -2.27617, -2.18548, -2.12930, -2.27786, -2.37774, -2.50422, -2.59050, -2.55649, -2.47710, -2.45995, -2.63777, -2.73493, -2.83233, -2.84296, -2.76078, -2.74299, -2.79954, -2.80006, -2.77530, -2.76694, -2.58004, -2.45887, -2.53642, -2.58678, -2.59832, -2.53912, -2.51969, -2.45466, -2.42675, -2.35822, -2.27117, -2.28481, -2.26327, -2.15551, -2.11267, -2.21557, -2.25198, -2.27994, -2.39340, -2.43536, -2.50003, -2.55051, -2.67775, -2.59982, -2.40534, -2.19785, -2.02851, -1.96484, -1.96453, -1.85025, -1.74098, -1.89840, -2.11778, -2.32486, -2.56017, -2.62825, -2.62158, -2.46956, -2.26343, -2.08168, -2.00804, -1.80614, -1.59878, -1.66095, -1.87276, -2.00252, -1.96220, -1.99996, -1.96279, -1.94478, -2.14080, -2.22817, -2.25038, -2.13497, -2.05957, -1.98666, -1.96250, -1.99409, -2.00438, -1.94173, -1.87025, -1.72067, -1.54967, -1.55920, -1.56436, -1.50230, -1.66358, -1.80638, -2.01518, -2.31540, -2.62839, -2.83548, -2.99932, -3.05224, -2.93755, -2.85161, -2.84271, -2.76374, -2.59113, -2.56474, -2.60591, -2.56724, -2.63478, -2.50488, -2.23923, -1.94672, -1.85259, -1.80913, -1.69695, -1.44687, -1.11943, -0.85897, -0.75608, -0.64994, -0.44933, -0.39519, -0.40636, -0.30138, -0.27012, -0.16703, -0.00345, 0.23119, 0.37439, 0.44367, 0.43798, 0.58319, 1.06888, 1.52095, 1.86779, 2.13127, 2.34846, 2.39994, 2.38551, 2.49829, 2.53826, 2.54161, 2.55418, 2.51734, 2.41041, 2.38024, 2.46649, 2.48836, 2.43990, 2.39759, 2.32772, 2.27824, 2.32584, 2.34063, 2.23015, 2.03111, 1.62858, 1.28435, 1.07457, 0.92219, 0.79717, 0.74802, 0.64875, 0.61320, 0.78115, 0.86734, 0.70547, 0.54034, 0.50135, 0.50220, 0.48642, 0.50722, 0.33995, 0.08599, -0.01889, -0.01224, -0.09172, -0.32017, -0.49418, -0.61334, -0.64771, -0.71447, -0.93452, -1.19610, -1.31994, -1.51204, -1.74752, -1.80520, -1.95245, -2.09042, -2.13296, -2.08884, -1.95414, -1.81842, -1.76004, -1.84562, -1.93696, -2.06931, -2.35843, -2.44494, -2.27884, -2.16143, -2.15796, -2.06835, -1.97097, -1.82562, -1.57658, -1.42448, -1.45152, -1.55142, -1.53402, -1.52771, -1.54221, -1.50384, -1.58086, -1.78436, -1.87260, -1.89368, -1.94361, -1.95440, -2.08640, -2.25336, -2.32016, -2.30648, -2.17038, -2.03154, -1.94833, -1.86967, -1.61543, -1.27481, -1.11409, -1.03842, -0.93247, -0.95096, -1.02559, -0.93247, -0.86086, -0.96006, -1.00406, -0.99800, -0.96025, -0.97123, -0.85822, -0.68266, -0.49462, -0.40344, -0.46063, -0.63248, -0.78600, -1.01019, -1.33115, -1.40848, -1.40905, -1.51339, -1.55555, -1.74110, -1.97007, -2.14540, -2.27554, -2.27695, -2.08853, -1.92562, -2.04614, -2.26500, -2.30722, -2.28303, -2.36294, -2.40287, -2.43243, -2.46883, -2.31089, -2.09197, -1.86449, -1.64513, -1.39599, -1.22271, -1.04808, -0.85305, -0.67078, -0.58972, -0.40846, -0.25703, -0.27890, -0.25268, -0.18736, -0.24745, -0.26510, -0.28945, -0.23784, -0.03882, 0.18241, 0.27775, 0.35774, 0.40247, 0.33274, 0.27942, 0.31713, 0.25774, 0.02447, -0.11609, -0.14112, -0.28808, -0.39126, -0.47283, -0.52578, -0.67732, -0.72650, -0.76548, -0.89743, -1.14317, -1.46096, -1.73124, -1.77386, -1.73858, -1.76854, -1.81108, -1.83013, -1.94306, -1.97609, -1.85631, -1.66600, -1.54594, -1.54721, -1.69934, -1.71844, -1.55346, -1.45391, -1.47909, -1.40485, -1.17725, -0.93888, -0.62227, -0.21014, 0.11752, 0.39153, 0.60077, 0.81164, 0.93631, 1.12497, 1.30067, 1.49776, +-0.75855, -0.49398, -0.35950, -0.19045, -0.10320, -0.12546, -0.11842, -0.03874, 0.15059, 0.28465, 0.29962, 0.31070, 0.59071, 0.96847, 1.19149, 1.42171, 1.63425, 1.64848, 1.53929, 1.62198, 1.76728, 1.84165, 1.94153, 1.89670, 1.81922, 1.83976, 1.70167, 1.40157, 1.17813, 0.93481, 0.74968, 0.78817, 0.87896, 0.90312, 0.84509, 0.84615, 0.84723, 0.82756, 0.84296, 0.75877, 0.64344, 0.56440, 0.40741, 0.24766, 0.24399, 0.31199, 0.09270, -0.26549, -0.49641, -0.60470, -0.61809, -0.42869, -0.30634, -0.41128, -0.51821, -0.67087, -0.79545, -0.86667, -1.06019, -1.28579, -1.27366, -1.28967, -1.56019, -1.75519, -1.92411, -2.07617, -2.23451, -2.17281, -2.07883, -2.15759, -2.34081, -2.57694, -2.66828, -2.61898, -2.60484, -2.60530, -2.60984, -2.57725, -2.71971, -2.84469, -2.71788, -2.59110, -2.62163, -2.58303, -2.56559, -2.60653, -2.53519, -2.52250, -2.55717, -2.48846, -2.43577, -2.44964, -2.38419, -2.26803, -2.31315, -2.33242, -2.22924, -2.05155, -1.97871, -1.93938, -1.97806, -2.12269, -2.28419, -2.39587, -2.41018, -2.26205, -2.26166, -2.37272, -2.39805, -2.19563, -2.04828, -1.97997, -1.81440, -1.68481, -1.73453, -1.68122, -1.68655, -1.94812, -2.23427, -2.49179, -2.63479, -2.57820, -2.57701, -2.62008, -2.51124, -2.30456, -2.22014, -2.02891, -1.77311, -1.64997, -1.81807, -1.99551, -2.00657, -1.98577, -1.95148, -1.93963, -2.03255, -2.02623, -2.07430, -2.10727, -2.00294, -1.81026, -1.78161, -1.91213, -1.92924, -1.80213, -1.81886, -1.72876, -1.55978, -1.53261, -1.48112, -1.42358, -1.52254, -1.57708, -1.80253, -2.23668, -2.53369, -2.58101, -2.65392, -2.73929, -2.69772, -2.58711, -2.63695, -2.62738, -2.47596, -2.31845, -2.32566, -2.37277, -2.39098, -2.13525, -1.84191, -1.66834, -1.56806, -1.43108, -1.36032, -1.31057, -1.11526, -0.82778, -0.73219, -0.58924, -0.32165, -0.24331, -0.28204, -0.29747, -0.32731, -0.15551, 0.06107, 0.20556, 0.32755, 0.45875, 0.44574, 0.49823, 0.89197, 1.44301, 1.88403, 2.21649, 2.45497, 2.56265, 2.53868, 2.51720, 2.54368, 2.64553, 2.72817, 2.63783, 2.56111, 2.65108, 2.69797, 2.54615, 2.43941, 2.50743, 2.50238, 2.46286, 2.48409, 2.41454, 2.18698, 1.87470, 1.49311, 1.32529, 1.25408, 1.03635, 0.82366, 0.76575, 0.64852, 0.56622, 0.69132, 0.88927, 0.78067, 0.53997, 0.42040, 0.44250, 0.45030, 0.40115, 0.26400, 0.14114, 0.10641, -0.00193, -0.17431, -0.32503, -0.46575, -0.66718, -0.71592, -0.68529, -0.87461, -1.19741, -1.41374, -1.66018, -1.92723, -2.04499, -2.19643, -2.27869, -2.30101, -2.38775, -2.39392, -2.21200, -2.04863, -2.03932, -2.10206, -2.14295, -2.33343, -2.45861, -2.35879, -2.22128, -2.14546, -2.09761, -2.01449, -1.80902, -1.57908, -1.56244, -1.65707, -1.63167, -1.53244, -1.64828, -1.81645, -1.82339, -1.93030, -2.14414, -2.18487, -2.10881, -2.08127, -2.10234, -2.25355, -2.39392, -2.40487, -2.41821, -2.33432, -2.06316, -1.88631, -1.83661, -1.66308, -1.31313, -1.06068, -1.01551, -0.97872, -1.00347, -1.01482, -0.99990, -1.01635, -1.06627, -1.05202, -1.08479, -1.08582, -1.00715, -0.85301, -0.84265, -0.85987, -0.74238, -0.68078, -0.78607, -0.87144, -1.06951, -1.39371, -1.53674, -1.59339, -1.64390, -1.57260, -1.73003, -2.09282, -2.28467, -2.40467, -2.47712, -2.38534, -2.22377, -2.19021, -2.39258, -2.49631, -2.53050, -2.61913, -2.72837, -2.77556, -2.64789, -2.29521, -2.04884, -1.89551, -1.64524, -1.35969, -1.26039, -1.19296, -0.90301, -0.56531, -0.47115, -0.31666, -0.24574, -0.31648, -0.30467, -0.20345, -0.09971, 0.04072, 0.04920, -0.00265, 0.23543, 0.54094, 0.61956, 0.60734, 0.60373, 0.64657, 0.55066, 0.47293, 0.37818, 0.25944, 0.19086, 0.19882, 0.14361, 0.10773, -0.09760, -0.39175, -0.56094, -0.53894, -0.62358, -0.89670, -1.15166, -1.37721, -1.67519, -1.72961, -1.70004, -1.69862, -1.69976, -1.76283, -1.85224, -1.81602, -1.71335, -1.66935, -1.53699, -1.40220, -1.50587, -1.58385, -1.51126, -1.37741, -1.43386, -1.41096, -1.17502, -0.80819, -0.47882, -0.16181, 0.13321, 0.43780, 0.63918, 0.75425, 0.96941, 1.30011, 1.43417, 1.42952, +-0.93873, -0.66129, -0.43070, -0.30092, -0.31778, -0.40307, -0.43212, -0.18922, 0.06706, 0.15686, 0.18028, 0.32259, 0.62409, 0.83091, 1.03767, 1.37234, 1.62812, 1.62040, 1.50649, 1.57367, 1.67287, 1.61887, 1.66439, 1.74261, 1.62611, 1.58340, 1.48788, 1.26949, 1.15257, 1.00454, 0.96327, 0.99492, 1.00022, 1.00787, 0.94706, 0.93135, 0.93865, 1.02607, 1.02557, 1.03526, 0.92197, 0.67348, 0.45635, 0.39139, 0.47719, 0.47365, 0.28723, -0.00559, -0.27865, -0.43461, -0.47039, -0.31797, -0.19793, -0.36287, -0.53924, -0.63002, -0.79220, -0.87168, -0.94317, -1.09625, -1.07281, -1.09448, -1.28712, -1.48759, -1.85488, -2.07901, -2.19193, -2.10392, -2.05368, -2.10212, -2.36024, -2.51144, -2.60016, -2.75257, -2.82280, -2.71450, -2.54965, -2.60883, -2.73016, -2.73486, -2.65429, -2.62766, -2.65897, -2.57275, -2.52551, -2.61394, -2.62755, -2.49601, -2.45991, -2.39529, -2.25091, -2.23179, -2.16532, -2.13094, -2.21477, -2.18893, -2.13726, -1.89746, -1.78384, -1.76841, -1.96243, -2.16772, -2.43417, -2.46897, -2.35287, -2.22198, -2.16084, -2.16802, -2.04480, -1.90956, -1.79785, -1.65471, -1.52482, -1.52072, -1.65858, -1.69436, -1.74637, -2.00113, -2.31747, -2.48995, -2.61506, -2.64456, -2.58612, -2.60793, -2.59804, -2.48735, -2.37458, -2.07731, -1.86084, -1.71135, -1.80049, -1.87594, -1.99634, -2.00440, -2.04557, -1.92993, -1.84157, -1.92847, -1.99251, -1.99095, -1.82891, -1.77678, -1.81178, -1.81897, -1.84492, -1.84943, -1.94216, -1.83686, -1.59755, -1.48903, -1.46490, -1.34836, -1.37062, -1.53775, -1.74588, -2.05537, -2.24977, -2.22729, -2.27250, -2.30582, -2.41346, -2.43999, -2.52921, -2.46855, -2.40084, -2.19399, -2.21428, -2.24589, -2.11750, -1.88978, -1.61266, -1.41014, -1.19827, -1.15000, -1.21519, -1.15633, -0.98287, -0.75754, -0.67372, -0.53801, -0.27309, -0.15464, -0.22021, -0.21481, -0.25875, -0.22049, 0.02559, 0.26694, 0.42553, 0.53102, 0.51069, 0.64527, 0.90771, 1.33085, 1.77583, 2.27019, 2.51262, 2.62725, 2.61869, 2.58707, 2.68600, 2.69166, 2.73146, 2.69859, 2.74002, 2.77657, 2.68927, 2.62641, 2.60701, 2.64709, 2.59375, 2.49975, 2.48745, 2.35351, 2.00577, 1.73624, 1.51960, 1.37137, 1.32357, 1.15927, 0.91020, 0.75430, 0.57954, 0.56288, 0.62662, 0.75158, 0.64481, 0.45413, 0.27361, 0.27981, 0.29308, 0.23434, 0.25801, 0.14154, 0.03527, -0.09531, -0.15775, -0.24601, -0.46988, -0.63415, -0.63992, -0.66020, -0.88212, -1.25866, -1.58168, -1.85645, -2.17351, -2.28997, -2.34710, -2.51240, -2.57772, -2.61700, -2.66923, -2.56497, -2.41659, -2.22259, -2.21143, -2.30020, -2.40948, -2.44192, -2.41864, -2.37273, -2.26833, -2.23393, -2.05701, -1.89252, -1.79983, -1.76885, -1.72778, -1.62957, -1.69060, -1.85756, -2.00986, -2.16916, -2.38792, -2.56615, -2.52225, -2.32604, -2.29329, -2.31737, -2.37130, -2.55935, -2.59331, -2.50891, -2.34678, -2.02163, -1.84546, -1.74181, -1.57377, -1.33363, -1.09180, -1.00365, -0.99715, -1.13138, -1.15074, -1.21658, -1.11081, -1.06141, -1.12710, -1.17964, -1.11169, -0.95455, -0.93054, -1.00017, -1.04827, -1.00341, -0.97926, -1.03683, -1.07477, -1.22512, -1.52987, -1.70181, -1.70681, -1.81725, -1.81340, -1.84111, -2.13482, -2.35016, -2.49237, -2.55388, -2.51335, -2.51745, -2.46496, -2.58438, -2.68774, -2.85945, -2.93935, -3.04780, -2.93049, -2.65294, -2.38549, -2.14517, -1.91720, -1.63501, -1.49347, -1.38030, -1.15011, -0.81949, -0.55687, -0.49842, -0.40639, -0.37923, -0.45832, -0.46156, -0.20325, 0.00240, 0.11216, 0.20908, 0.25301, 0.52981, 0.81729, 0.92431, 0.94197, 0.78836, 0.78152, 0.69142, 0.67546, 0.54929, 0.51904, 0.44865, 0.55701, 0.63984, 0.50449, 0.18977, -0.18580, -0.31650, -0.42231, -0.56637, -0.75590, -1.02656, -1.30583, -1.62183, -1.73827, -1.75932, -1.74628, -1.72180, -1.67313, -1.70967, -1.72484, -1.58788, -1.53434, -1.41634, -1.25399, -1.29302, -1.32085, -1.41368, -1.34437, -1.33663, -1.20645, -1.04438, -0.69548, -0.44116, -0.13777, 0.17302, 0.35222, 0.55759, 0.76855, 1.13922, 1.36996, 1.38335, 1.38692, +-1.05501, -0.85803, -0.60889, -0.44219, -0.44410, -0.49552, -0.52068, -0.34585, -0.09541, 0.04397, 0.11413, 0.31820, 0.60297, 0.76005, 0.98180, 1.29048, 1.50482, 1.49593, 1.38765, 1.43101, 1.48832, 1.38494, 1.34718, 1.39704, 1.30576, 1.21732, 1.14377, 1.12906, 1.15843, 1.08949, 1.08479, 1.09352, 1.07240, 1.06953, 1.04968, 1.10614, 1.16727, 1.29722, 1.23369, 1.08590, 0.93310, 0.76290, 0.64356, 0.60413, 0.63617, 0.58470, 0.44534, 0.18920, -0.13571, -0.31860, -0.38875, -0.33863, -0.23818, -0.37012, -0.60044, -0.76545, -0.88272, -0.87914, -0.87813, -0.92191, -0.95611, -1.04929, -1.19016, -1.29730, -1.64274, -1.88006, -1.97489, -1.91093, -1.91618, -1.99830, -2.24303, -2.42128, -2.52699, -2.71151, -2.85821, -2.81571, -2.69180, -2.76539, -2.75745, -2.62128, -2.58987, -2.64105, -2.68847, -2.64321, -2.61241, -2.68570, -2.71492, -2.55281, -2.40598, -2.28321, -2.19534, -2.15994, -2.09113, -2.11839, -2.18181, -2.04234, -1.94373, -1.73153, -1.70226, -1.78570, -2.03234, -2.22009, -2.38669, -2.46449, -2.37288, -2.20621, -2.10760, -2.07228, -1.95661, -1.84363, -1.67681, -1.45599, -1.35222, -1.40833, -1.60881, -1.78732, -1.88234, -2.03363, -2.30373, -2.54607, -2.74520, -2.80478, -2.75138, -2.64127, -2.57375, -2.49595, -2.37443, -2.02397, -1.81182, -1.67795, -1.69495, -1.66743, -1.76374, -1.85069, -1.93644, -1.92623, -1.87575, -1.93745, -1.93903, -1.89294, -1.81085, -1.88182, -1.89964, -1.79424, -1.86083, -1.95915, -2.06104, -1.94514, -1.66639, -1.48092, -1.49904, -1.50292, -1.50584, -1.62486, -1.78130, -1.88564, -1.92911, -1.90912, -2.04030, -2.08061, -2.20341, -2.23693, -2.26646, -2.20725, -2.18761, -2.07495, -2.10698, -2.19955, -2.12201, -1.85627, -1.53210, -1.29090, -1.07075, -1.08027, -1.15111, -1.02613, -0.84412, -0.60191, -0.48181, -0.43632, -0.30753, -0.18185, -0.18479, -0.17003, -0.18631, -0.11305, 0.10926, 0.39783, 0.58935, 0.65581, 0.64191, 0.89105, 1.16348, 1.47230, 1.84335, 2.31611, 2.56889, 2.65780, 2.73851, 2.71306, 2.69713, 2.63873, 2.69191, 2.70046, 2.70931, 2.64904, 2.58767, 2.71723, 2.77893, 2.78915, 2.65237, 2.42468, 2.32381, 2.16934, 1.87856, 1.64407, 1.48658, 1.37927, 1.22794, 1.05352, 0.86035, 0.72848, 0.57634, 0.59032, 0.62445, 0.63254, 0.47057, 0.26922, 0.06798, 0.03191, 0.06392, 0.01594, 0.02500, -0.06067, -0.12721, -0.23448, -0.25362, -0.30529, -0.46969, -0.56310, -0.62663, -0.71270, -0.91064, -1.27228, -1.64377, -1.92657, -2.22410, -2.41968, -2.56262, -2.74064, -2.81647, -2.78530, -2.77404, -2.75299, -2.69815, -2.46473, -2.36791, -2.44235, -2.46362, -2.42448, -2.45099, -2.49917, -2.40533, -2.37211, -2.32226, -2.23840, -2.11074, -1.98279, -1.89376, -1.85302, -2.02096, -2.18178, -2.31682, -2.54204, -2.72584, -2.83250, -2.78240, -2.59405, -2.58191, -2.63430, -2.67789, -2.72700, -2.66849, -2.53530, -2.28776, -1.99620, -1.87315, -1.75391, -1.56410, -1.37595, -1.18205, -1.08723, -1.08698, -1.27779, -1.34353, -1.41563, -1.33196, -1.21923, -1.20417, -1.28094, -1.29945, -1.19804, -1.16746, -1.12242, -1.10094, -1.09992, -1.09177, -1.16125, -1.28077, -1.44133, -1.64032, -1.75368, -1.81632, -1.97028, -2.03421, -2.08036, -2.26610, -2.46898, -2.59565, -2.63449, -2.62069, -2.71700, -2.70189, -2.78663, -2.92140, -3.15507, -3.22155, -3.21301, -3.09667, -2.83462, -2.59184, -2.35585, -2.10816, -1.85250, -1.67030, -1.39933, -1.02094, -0.75107, -0.61274, -0.59962, -0.58381, -0.52075, -0.49152, -0.47471, -0.27871, -0.08122, 0.04401, 0.14737, 0.31107, 0.62914, 0.88915, 1.02730, 1.12220, 0.94710, 0.87684, 0.79818, 0.84616, 0.79345, 0.79283, 0.72701, 0.71869, 0.78060, 0.71400, 0.45852, 0.09172, -0.09378, -0.27014, -0.40634, -0.53768, -0.84008, -1.09714, -1.34025, -1.55479, -1.69621, -1.71807, -1.69669, -1.68848, -1.69363, -1.60731, -1.46791, -1.37804, -1.26255, -1.11335, -1.12635, -1.12959, -1.27101, -1.22068, -1.12357, -0.94965, -0.84291, -0.65702, -0.45740, -0.25939, -0.03034, 0.21794, 0.51769, 0.78992, 1.08506, 1.16685, 1.18016, 1.30035, +-1.30869, -1.11821, -0.86181, -0.69257, -0.65845, -0.56622, -0.44102, -0.37748, -0.24165, -0.03386, 0.08125, 0.25722, 0.52118, 0.77302, 0.98642, 1.10730, 1.23944, 1.29338, 1.29924, 1.28938, 1.23863, 1.16790, 1.14291, 1.16873, 1.12894, 0.97221, 0.78355, 0.85336, 1.01245, 1.00685, 1.01066, 0.99431, 0.98387, 1.06575, 1.15428, 1.25119, 1.29745, 1.46182, 1.47312, 1.20434, 0.95678, 0.93992, 0.96468, 0.88503, 0.83000, 0.81226, 0.68346, 0.28795, -0.11062, -0.27411, -0.28498, -0.30885, -0.31281, -0.36734, -0.55111, -0.73671, -0.81032, -0.83417, -0.92337, -0.94184, -0.94615, -1.05791, -1.19495, -1.27886, -1.53235, -1.67321, -1.72333, -1.72418, -1.82822, -1.92046, -2.02234, -2.20199, -2.37845, -2.51655, -2.66268, -2.76402, -2.77333, -2.79381, -2.68634, -2.64046, -2.66270, -2.66179, -2.60667, -2.55783, -2.62584, -2.65405, -2.64069, -2.47610, -2.26721, -2.15467, -2.21498, -2.23218, -2.11932, -2.13951, -2.17334, -2.02804, -1.93530, -1.74562, -1.75398, -1.91078, -2.17874, -2.27284, -2.19160, -2.24011, -2.26022, -2.07290, -1.91439, -1.90113, -1.86783, -1.74536, -1.50527, -1.40142, -1.35442, -1.35766, -1.49481, -1.69954, -1.94408, -2.07527, -2.27027, -2.51552, -2.72322, -2.79935, -2.85606, -2.74177, -2.52754, -2.39338, -2.27984, -1.98665, -1.81857, -1.66839, -1.58974, -1.49354, -1.55132, -1.66286, -1.65779, -1.68260, -1.80098, -1.87177, -1.80949, -1.79730, -1.82196, -1.91332, -1.84018, -1.82406, -1.98384, -2.07684, -2.12164, -1.96126, -1.78777, -1.61402, -1.60098, -1.62568, -1.60122, -1.63634, -1.79466, -1.87461, -1.79719, -1.76581, -1.96184, -2.05039, -2.15768, -2.09486, -1.98838, -1.93178, -1.97413, -1.97788, -1.94380, -1.98146, -2.05128, -1.82717, -1.42791, -1.17874, -0.99553, -0.99186, -0.95128, -0.89707, -0.82821, -0.57703, -0.37110, -0.26785, -0.28160, -0.19475, -0.09885, 0.01346, 0.10183, 0.26834, 0.39733, 0.55370, 0.75904, 0.83611, 0.82241, 1.09036, 1.36802, 1.63965, 2.00735, 2.41999, 2.62270, 2.65975, 2.86399, 2.95703, 2.80350, 2.66308, 2.76778, 2.76806, 2.68030, 2.55428, 2.58483, 2.70426, 2.67668, 2.67551, 2.57647, 2.40438, 2.19233, 1.98540, 1.81555, 1.65075, 1.50104, 1.40922, 1.10869, 0.79080, 0.67293, 0.66734, 0.56777, 0.54576, 0.50637, 0.42106, 0.26280, 0.06791, -0.18585, -0.31108, -0.20252, -0.09465, -0.12319, -0.22159, -0.18623, -0.26717, -0.36017, -0.44813, -0.48026, -0.56616, -0.78057, -0.90089, -1.00598, -1.19259, -1.55653, -1.89886, -2.14552, -2.36663, -2.59989, -2.77228, -2.92687, -2.98841, -2.92166, -2.88453, -2.88945, -2.71943, -2.64159, -2.69525, -2.61722, -2.50980, -2.56661, -2.68672, -2.55486, -2.40796, -2.48701, -2.54639, -2.38331, -2.22436, -2.20701, -2.25546, -2.37342, -2.51402, -2.76808, -2.99537, -3.03891, -2.99293, -2.98085, -2.93178, -2.89990, -2.89049, -2.86253, -2.70522, -2.58439, -2.52666, -2.26601, -1.96767, -1.87198, -1.77878, -1.65890, -1.53742, -1.34036, -1.21574, -1.22577, -1.45646, -1.50445, -1.45090, -1.43168, -1.40861, -1.31644, -1.37489, -1.50925, -1.50094, -1.38603, -1.20507, -1.23216, -1.25942, -1.18840, -1.18700, -1.36615, -1.63487, -1.73861, -1.73395, -1.77545, -1.89979, -2.04318, -2.25759, -2.45890, -2.60995, -2.72950, -2.78648, -2.83436, -2.97199, -2.93718, -2.96866, -3.12895, -3.41063, -3.47440, -3.30949, -3.20737, -3.07249, -2.81262, -2.52675, -2.31498, -2.08505, -1.77125, -1.35484, -1.07109, -0.90754, -0.77361, -0.68312, -0.62633, -0.57766, -0.44902, -0.36590, -0.20770, -0.02779, 0.08249, 0.08283, 0.21112, 0.57760, 0.85035, 1.01059, 1.13131, 0.98366, 0.94208, 0.91612, 0.95644, 0.91050, 0.92940, 0.99569, 0.97842, 0.92029, 0.89644, 0.77673, 0.43752, 0.17688, 0.00031, -0.08356, -0.34974, -0.72491, -0.89478, -0.97766, -1.13940, -1.42749, -1.50644, -1.48265, -1.49231, -1.47586, -1.34276, -1.29696, -1.27691, -1.11266, -0.94798, -0.96599, -1.01018, -1.19215, -1.15773, -1.00540, -0.84861, -0.81200, -0.74482, -0.48724, -0.27563, -0.16406, 0.11603, 0.50126, 0.73928, 0.89059, 0.91093, 1.03290, 1.14450, +-1.49564, -1.40179, -1.18958, -1.00684, -0.87661, -0.73746, -0.58044, -0.46524, -0.39848, -0.27372, -0.07507, 0.21499, 0.45486, 0.63608, 0.84523, 0.95319, 1.03319, 1.05700, 1.10239, 1.14884, 1.12937, 1.04783, 0.97907, 0.95532, 0.89249, 0.73649, 0.55996, 0.61576, 0.76808, 0.80613, 0.86780, 0.93434, 0.93937, 1.00038, 1.13854, 1.29925, 1.40825, 1.54189, 1.52667, 1.31875, 1.06262, 1.02392, 1.15270, 1.18821, 1.08435, 0.95966, 0.82773, 0.46465, 0.03124, -0.23053, -0.29560, -0.30682, -0.29364, -0.31861, -0.48895, -0.67626, -0.79437, -0.85634, -0.92810, -0.90321, -0.89352, -0.99685, -1.14571, -1.22118, -1.43092, -1.60367, -1.65432, -1.64157, -1.72887, -1.83512, -1.94204, -2.03039, -2.17891, -2.39444, -2.52135, -2.54158, -2.61163, -2.74345, -2.64924, -2.58009, -2.62697, -2.66596, -2.60873, -2.48312, -2.47008, -2.43532, -2.44041, -2.33749, -2.18819, -2.11411, -2.16657, -2.15121, -2.07351, -2.10926, -2.16200, -2.04761, -1.99888, -1.95792, -2.00310, -2.11000, -2.27082, -2.24679, -2.11000, -2.07782, -2.08201, -1.98194, -1.78901, -1.61780, -1.59580, -1.62596, -1.45803, -1.35591, -1.33528, -1.37191, -1.50990, -1.66085, -1.90223, -2.03445, -2.23369, -2.45258, -2.64286, -2.73137, -2.80168, -2.66460, -2.42754, -2.26529, -2.15749, -1.89602, -1.76188, -1.71835, -1.63363, -1.45719, -1.41058, -1.47068, -1.50043, -1.51351, -1.64559, -1.83072, -1.80360, -1.68768, -1.71669, -1.91286, -1.89261, -1.85597, -1.99835, -2.11344, -2.20024, -2.05128, -1.89630, -1.72826, -1.71815, -1.73277, -1.72334, -1.75648, -1.88077, -1.89625, -1.80208, -1.77735, -1.96209, -2.02134, -2.05710, -1.99296, -1.85967, -1.78378, -1.80469, -1.79652, -1.79944, -1.80204, -1.86428, -1.77789, -1.44359, -1.07809, -0.83996, -0.88443, -0.86184, -0.77947, -0.74108, -0.56005, -0.37141, -0.18628, -0.12382, 0.01762, 0.11577, 0.25971, 0.40853, 0.59988, 0.72876, 0.89292, 1.05761, 1.10625, 1.09023, 1.35114, 1.63134, 1.79085, 2.07799, 2.46146, 2.69744, 2.80002, 2.99406, 3.11391, 2.99034, 2.74896, 2.74701, 2.80899, 2.76750, 2.56070, 2.48820, 2.56495, 2.52258, 2.49256, 2.41126, 2.32554, 2.16773, 2.00784, 1.83055, 1.64568, 1.45331, 1.28266, 0.94099, 0.64239, 0.55240, 0.59086, 0.50876, 0.44422, 0.37133, 0.19332, -0.00909, -0.17124, -0.38328, -0.48661, -0.41076, -0.27905, -0.22480, -0.33535, -0.34712, -0.34840, -0.39351, -0.55914, -0.64636, -0.68317, -0.84577, -0.98352, -1.11240, -1.23064, -1.47435, -1.73661, -1.98326, -2.24350, -2.54697, -2.79974, -3.00413, -3.05708, -2.98923, -2.99440, -3.03998, -2.92386, -2.84484, -2.91788, -2.87638, -2.74668, -2.75191, -2.81747, -2.72922, -2.61201, -2.65757, -2.78893, -2.77735, -2.63007, -2.54692, -2.64209, -2.79399, -2.87123, -3.06028, -3.27152, -3.33697, -3.27877, -3.22515, -3.17301, -3.14206, -3.11291, -3.02009, -2.77849, -2.59649, -2.49097, -2.20990, -1.92600, -1.81226, -1.72003, -1.63121, -1.60756, -1.54412, -1.45325, -1.42559, -1.58257, -1.62954, -1.60300, -1.57274, -1.60459, -1.61071, -1.61756, -1.62948, -1.66845, -1.66247, -1.46116, -1.39371, -1.39880, -1.35314, -1.34763, -1.47676, -1.70076, -1.76436, -1.73173, -1.75585, -1.90322, -2.08223, -2.31123, -2.49266, -2.66306, -2.80550, -2.90521, -2.98045, -3.14782, -3.21593, -3.23200, -3.31105, -3.50734, -3.58461, -3.48705, -3.36826, -3.26442, -3.08967, -2.76493, -2.40882, -2.16541, -1.92804, -1.50258, -1.17171, -1.01919, -0.91261, -0.80056, -0.62684, -0.47765, -0.31034, -0.25950, -0.15045, -0.02525, 0.06512, 0.08063, 0.21695, 0.52415, 0.77562, 0.93992, 1.10585, 1.02737, 0.94136, 0.92164, 0.98268, 0.99816, 1.07236, 1.15096, 1.19102, 1.11254, 0.96341, 0.86243, 0.71395, 0.48582, 0.21884, 0.10623, -0.12523, -0.48082, -0.65128, -0.68815, -0.75295, -1.00154, -1.07846, -1.10731, -1.14801, -1.16780, -1.07322, -1.05026, -1.02263, -0.90381, -0.78277, -0.81015, -0.84844, -1.03014, -1.14549, -1.07223, -0.92726, -0.86399, -0.76418, -0.55812, -0.34149, -0.23472, -0.08250, 0.24614, 0.58403, 0.74511, 0.69220, 0.81452, 1.02076, +-1.42977, -1.40180, -1.35787, -1.23675, -1.07960, -1.02883, -0.91186, -0.67687, -0.49196, -0.39094, -0.28668, 0.02223, 0.32690, 0.45035, 0.61173, 0.72922, 0.87932, 0.93481, 0.95825, 1.06558, 1.06870, 0.90095, 0.76288, 0.66096, 0.62854, 0.57816, 0.45817, 0.41372, 0.47765, 0.54730, 0.65476, 0.89010, 1.04313, 1.16305, 1.24527, 1.40418, 1.59797, 1.56964, 1.47155, 1.40925, 1.32034, 1.31319, 1.29067, 1.26539, 1.19282, 1.03536, 0.91598, 0.61797, 0.27022, -0.01190, -0.25191, -0.32701, -0.35021, -0.43615, -0.55616, -0.69015, -0.81001, -0.83309, -0.89231, -0.85531, -0.81013, -0.87275, -1.08804, -1.23228, -1.40998, -1.54624, -1.62443, -1.58355, -1.55304, -1.75808, -1.95908, -1.96881, -1.98997, -2.15612, -2.35895, -2.40494, -2.40069, -2.54578, -2.50475, -2.44367, -2.49983, -2.53688, -2.60370, -2.46975, -2.30777, -2.21253, -2.17558, -2.12157, -2.09671, -2.03992, -2.07708, -2.02733, -1.99382, -2.00559, -2.15116, -2.14006, -2.10968, -2.13742, -2.19310, -2.21355, -2.13999, -2.10423, -2.10355, -2.05771, -1.96812, -1.78635, -1.60275, -1.44069, -1.32681, -1.40103, -1.39714, -1.37911, -1.42575, -1.42659, -1.58446, -1.69405, -1.84828, -2.02423, -2.23922, -2.34552, -2.47364, -2.50122, -2.60453, -2.57609, -2.43742, -2.21120, -2.09007, -1.83969, -1.67620, -1.64545, -1.58775, -1.42937, -1.24253, -1.31877, -1.48260, -1.49839, -1.52094, -1.62533, -1.66789, -1.65275, -1.65832, -1.84799, -1.95977, -1.94089, -1.99338, -1.96404, -2.07285, -2.04932, -1.94970, -1.90245, -1.91921, -1.83312, -1.84909, -1.84155, -2.00307, -2.06396, -2.03011, -1.97574, -2.06786, -2.03414, -1.90748, -1.76285, -1.68501, -1.69701, -1.64240, -1.60857, -1.69195, -1.69053, -1.62873, -1.50057, -1.31162, -1.10801, -0.87721, -0.84417, -0.82977, -0.71445, -0.65822, -0.43899, -0.27958, -0.05303, 0.16140, 0.29791, 0.31050, 0.43690, 0.56590, 0.84980, 1.03145, 1.21677, 1.31523, 1.36550, 1.36050, 1.55676, 1.83025, 1.97034, 2.19725, 2.50538, 2.86828, 3.06551, 3.16090, 3.22472, 3.17686, 3.00019, 2.84680, 2.74582, 2.75942, 2.66285, 2.51961, 2.46594, 2.35312, 2.35108, 2.32764, 2.31046, 2.26621, 2.12443, 1.81229, 1.58558, 1.30771, 1.09318, 0.79754, 0.54979, 0.45535, 0.48837, 0.35657, 0.19123, 0.10830, 0.00442, -0.12444, -0.26961, -0.33064, -0.36962, -0.48013, -0.48593, -0.39305, -0.37732, -0.39805, -0.49354, -0.53093, -0.64999, -0.77912, -0.76721, -0.84125, -0.93575, -1.10771, -1.34025, -1.51102, -1.67937, -1.95023, -2.16336, -2.49274, -2.78430, -3.00251, -3.10064, -3.12705, -3.19351, -3.25036, -3.19234, -3.06892, -3.05137, -2.98141, -2.90951, -2.86468, -2.84762, -2.95901, -2.96630, -2.90244, -2.88575, -2.91635, -2.98651, -2.98100, -3.03063, -3.11914, -3.09801, -3.18370, -3.32259, -3.45290, -3.53191, -3.48534, -3.42763, -3.42467, -3.33113, -3.15926, -2.90422, -2.69964, -2.58444, -2.33716, -2.02123, -1.78081, -1.65583, -1.51795, -1.50672, -1.55060, -1.61448, -1.61943, -1.63463, -1.76276, -1.83616, -1.77490, -1.74755, -1.75500, -1.80202, -1.80066, -1.82863, -1.91828, -1.84118, -1.73125, -1.63692, -1.52483, -1.54794, -1.63651, -1.79068, -1.90321, -1.88045, -1.88684, -2.06413, -2.20115, -2.40465, -2.57443, -2.76018, -2.86931, -3.04081, -3.14715, -3.28865, -3.40214, -3.41940, -3.38518, -3.33396, -3.47098, -3.58200, -3.51573, -3.37868, -3.12880, -2.82964, -2.48703, -2.19564, -2.03172, -1.68916, -1.34684, -1.13768, -0.90439, -0.77423, -0.51906, -0.31703, -0.27355, -0.31240, -0.22689, -0.12573, 0.05363, 0.12353, 0.26734, 0.46155, 0.68357, 0.78152, 0.95009, 1.03038, 1.04794, 1.06167, 1.12108, 1.27100, 1.32837, 1.34449, 1.39509, 1.31402, 1.12648, 0.87185, 0.68627, 0.57217, 0.37454, 0.25602, 0.07705, -0.21421, -0.30693, -0.37753, -0.42765, -0.58918, -0.69914, -0.76437, -0.76025, -0.82052, -0.70491, -0.72960, -0.76420, -0.78344, -0.72576, -0.75126, -0.74109, -0.79461, -0.92437, -0.98275, -0.96321, -0.81665, -0.66602, -0.56021, -0.37639, -0.24698, -0.13417, 0.05693, 0.26744, 0.49852, 0.58105, 0.73126, 1.00101, +-1.27139, -1.27407, -1.39319, -1.47731, -1.39224, -1.26943, -1.05002, -0.72151, -0.53745, -0.46970, -0.41250, -0.16157, 0.16947, 0.33478, 0.38678, 0.39863, 0.57935, 0.69023, 0.77148, 0.89062, 0.89019, 0.74760, 0.61885, 0.53528, 0.50807, 0.49810, 0.50042, 0.46283, 0.39090, 0.35519, 0.47745, 0.75834, 1.04701, 1.31718, 1.40081, 1.46338, 1.63869, 1.63057, 1.59633, 1.66778, 1.63074, 1.57162, 1.40054, 1.24684, 1.17048, 1.07680, 0.93079, 0.55731, 0.29166, 0.06899, -0.21668, -0.37699, -0.46942, -0.50189, -0.51478, -0.54109, -0.65117, -0.68814, -0.69746, -0.61322, -0.60471, -0.79818, -1.04046, -1.29883, -1.48160, -1.51545, -1.60647, -1.64605, -1.62551, -1.75498, -1.88194, -1.79770, -1.78811, -1.94588, -2.14282, -2.23921, -2.19874, -2.25908, -2.27235, -2.38038, -2.48013, -2.52483, -2.62310, -2.47269, -2.22416, -1.97427, -1.78520, -1.66775, -1.72908, -1.79920, -1.85615, -1.78036, -1.80253, -1.94003, -2.10569, -2.20345, -2.22126, -2.22632, -2.27864, -2.30488, -2.15929, -2.03120, -2.04643, -1.93777, -1.82882, -1.66092, -1.45828, -1.35591, -1.19236, -1.17192, -1.25986, -1.47914, -1.61000, -1.57973, -1.68015, -1.72640, -1.82551, -1.92619, -2.07108, -2.03033, -2.08804, -2.16339, -2.25476, -2.27593, -2.22885, -2.13311, -1.99497, -1.78849, -1.65877, -1.56697, -1.52414, -1.47292, -1.33014, -1.34282, -1.47550, -1.41455, -1.38886, -1.50522, -1.55937, -1.64106, -1.67477, -1.78413, -1.93130, -2.04924, -2.04201, -1.88522, -1.90117, -1.91482, -1.93177, -1.97174, -2.00494, -1.83735, -1.85046, -1.90654, -2.06610, -2.11241, -2.09697, -2.17598, -2.18989, -2.07106, -1.85744, -1.60836, -1.58484, -1.71385, -1.73328, -1.63741, -1.63094, -1.51401, -1.34188, -1.22271, -1.11326, -1.05545, -0.88853, -0.73439, -0.64716, -0.63098, -0.57872, -0.32358, -0.13161, 0.17041, 0.42922, 0.58330, 0.61271, 0.76398, 0.90795, 1.16682, 1.38840, 1.62934, 1.70763, 1.61394, 1.57499, 1.69160, 1.86998, 2.04145, 2.25191, 2.46914, 2.80096, 3.07731, 3.25618, 3.40754, 3.41545, 3.20944, 2.97373, 2.77604, 2.77994, 2.81551, 2.74981, 2.50139, 2.24836, 2.20420, 2.20533, 2.27739, 2.27937, 2.19196, 1.89775, 1.70315, 1.40899, 1.07215, 0.78454, 0.61651, 0.54317, 0.39830, 0.11242, -0.12703, -0.27784, -0.27207, -0.26770, -0.38060, -0.38424, -0.34461, -0.42467, -0.41726, -0.31519, -0.30691, -0.35679, -0.50879, -0.57752, -0.63660, -0.70608, -0.75492, -0.87756, -0.97038, -1.14280, -1.41379, -1.59055, -1.69565, -1.87483, -1.97770, -2.25724, -2.62465, -2.90521, -3.03534, -3.12642, -3.34405, -3.52740, -3.51153, -3.42014, -3.31096, -3.14770, -3.12223, -3.16145, -3.14596, -3.23086, -3.16952, -2.99436, -2.90920, -2.93140, -3.10605, -3.21779, -3.27208, -3.25677, -3.21756, -3.32380, -3.39359, -3.52833, -3.65015, -3.65413, -3.64041, -3.57997, -3.39406, -3.14040, -2.97055, -2.85161, -2.69651, -2.43038, -2.13641, -1.91013, -1.70813, -1.52215, -1.46509, -1.50696, -1.69572, -1.83953, -1.83450, -1.87748, -1.88777, -1.75944, -1.75266, -1.81051, -1.87158, -1.93949, -2.00048, -2.07784, -2.14503, -2.16573, -2.01247, -1.83063, -1.80792, -1.88604, -2.02717, -2.09585, -2.05044, -2.01048, -2.22077, -2.40875, -2.55912, -2.66625, -2.87918, -3.10650, -3.30325, -3.46755, -3.58342, -3.60138, -3.56311, -3.50511, -3.31429, -3.28338, -3.37769, -3.30504, -3.24987, -3.06861, -2.77877, -2.49027, -2.17991, -1.96943, -1.68772, -1.50121, -1.26933, -0.92566, -0.70840, -0.41097, -0.27561, -0.28425, -0.33878, -0.23197, -0.14281, 0.00848, 0.16120, 0.40839, 0.55532, 0.59247, 0.65674, 0.81253, 1.01317, 1.22477, 1.31575, 1.33636, 1.48082, 1.61319, 1.67912, 1.75672, 1.59233, 1.27884, 0.91617, 0.65757, 0.59483, 0.54586, 0.47562, 0.19343, -0.05795, -0.09957, -0.16061, -0.18633, -0.32153, -0.37904, -0.39426, -0.29994, -0.36419, -0.34635, -0.40982, -0.47043, -0.59054, -0.73503, -0.73824, -0.69365, -0.64331, -0.63852, -0.75114, -0.89211, -0.85670, -0.65538, -0.49689, -0.23566, -0.09692, -0.08695, 0.02479, 0.11697, 0.35150, 0.60970, 0.84517, 0.97666, +-1.14174, -1.26419, -1.34819, -1.50975, -1.52635, -1.31076, -1.10708, -0.80177, -0.62453, -0.60160, -0.50572, -0.23065, 0.01350, 0.16170, 0.26280, 0.24417, 0.39193, 0.50839, 0.64173, 0.74659, 0.67900, 0.57513, 0.41916, 0.34063, 0.33165, 0.37327, 0.44593, 0.35469, 0.27316, 0.32462, 0.48151, 0.68596, 0.97030, 1.26419, 1.53283, 1.65812, 1.73162, 1.75852, 1.68173, 1.71433, 1.71737, 1.61448, 1.43518, 1.28940, 1.11848, 0.95480, 0.85107, 0.49486, 0.25581, 0.07130, -0.18412, -0.38329, -0.54350, -0.50946, -0.50557, -0.55149, -0.64552, -0.63523, -0.57845, -0.58712, -0.63229, -0.78706, -0.94935, -1.26249, -1.44445, -1.51174, -1.54159, -1.56322, -1.67712, -1.74672, -1.81907, -1.74182, -1.63975, -1.76024, -1.88866, -1.93737, -1.96462, -2.09019, -2.06240, -2.17265, -2.30585, -2.37938, -2.45559, -2.27651, -2.06037, -1.75522, -1.49661, -1.39321, -1.44351, -1.53593, -1.60538, -1.68468, -1.76672, -1.84600, -1.87044, -2.01164, -2.08963, -2.21363, -2.26536, -2.21633, -2.14826, -1.96829, -1.93610, -1.86590, -1.70442, -1.58322, -1.40621, -1.29067, -1.17512, -1.21670, -1.26055, -1.47452, -1.61123, -1.55789, -1.61730, -1.62510, -1.74797, -1.81065, -1.89144, -1.88105, -1.89390, -1.94504, -1.92101, -1.99602, -1.97030, -1.84855, -1.62904, -1.51167, -1.47955, -1.49545, -1.44911, -1.31202, -1.27365, -1.28979, -1.38679, -1.42649, -1.38242, -1.51140, -1.56733, -1.60333, -1.66025, -1.84876, -1.92713, -1.96060, -1.92079, -1.73229, -1.69192, -1.68048, -1.80072, -1.94618, -2.03444, -2.01356, -2.04152, -2.10392, -2.12605, -2.18266, -2.18992, -2.25704, -2.15255, -2.01011, -1.78583, -1.57506, -1.54790, -1.56411, -1.68729, -1.65284, -1.58696, -1.52305, -1.28745, -1.13801, -1.04353, -0.94891, -0.76737, -0.66397, -0.51974, -0.43739, -0.37156, -0.10264, 0.11783, 0.46457, 0.67327, 0.79404, 0.89988, 1.01836, 1.22559, 1.48298, 1.77759, 1.96615, 1.94795, 1.82923, 1.88280, 1.96908, 2.05360, 2.12249, 2.26768, 2.54683, 2.78924, 3.01055, 3.28097, 3.40998, 3.46540, 3.29120, 3.05359, 2.90817, 2.90543, 2.84612, 2.81500, 2.61404, 2.32735, 2.22733, 2.16822, 2.25861, 2.24013, 2.15541, 1.98831, 1.76818, 1.47245, 1.06097, 0.79125, 0.61028, 0.45315, 0.26447, 0.04229, -0.19130, -0.42573, -0.48655, -0.48829, -0.44074, -0.40402, -0.37605, -0.35037, -0.37035, -0.26162, -0.23680, -0.34744, -0.49072, -0.54619, -0.68830, -0.75708, -0.75333, -0.88817, -0.97821, -1.12260, -1.32452, -1.48973, -1.62788, -1.72855, -1.85712, -2.14730, -2.54091, -2.79729, -2.93862, -3.16029, -3.44876, -3.61301, -3.62177, -3.63249, -3.56540, -3.43201, -3.30588, -3.35620, -3.43572, -3.42353, -3.34307, -3.17703, -3.03845, -3.05014, -3.17854, -3.26545, -3.42560, -3.46610, -3.34579, -3.39185, -3.38390, -3.45312, -3.54008, -3.58330, -3.69647, -3.64882, -3.50914, -3.29701, -3.14795, -2.98358, -2.76121, -2.58433, -2.32166, -2.00735, -1.70653, -1.53785, -1.48665, -1.59726, -1.73257, -1.84763, -1.93907, -1.93592, -1.95552, -1.88383, -1.85683, -1.96320, -2.03484, -2.10750, -2.25887, -2.39590, -2.40171, -2.38006, -2.20727, -2.01524, -1.97754, -2.08012, -2.28393, -2.31820, -2.27591, -2.28628, -2.49725, -2.68560, -2.79434, -2.98551, -3.21400, -3.38535, -3.49701, -3.71003, -3.81779, -3.82259, -3.65130, -3.47690, -3.30863, -3.13647, -3.14867, -3.12885, -3.09964, -3.03935, -2.78317, -2.45619, -2.15392, -1.97009, -1.62921, -1.42352, -1.20828, -0.86120, -0.60483, -0.29363, -0.23187, -0.24306, -0.28957, -0.28387, -0.22658, -0.09255, 0.14814, 0.35851, 0.49696, 0.56573, 0.74792, 0.92315, 1.17714, 1.38521, 1.55575, 1.69576, 1.74955, 1.88122, 1.93610, 1.86833, 1.68427, 1.32442, 0.97308, 0.79649, 0.73339, 0.62975, 0.62445, 0.40428, 0.19572, 0.18705, 0.16126, 0.17991, 0.02104, -0.03709, -0.02978, -0.01647, -0.08353, -0.11810, -0.14753, -0.32118, -0.52469, -0.66172, -0.54769, -0.51924, -0.45970, -0.47474, -0.57235, -0.63222, -0.76314, -0.66130, -0.47881, -0.28812, -0.07768, -0.05027, 0.03990, 0.16090, 0.36103, 0.52931, 0.81117, 0.97096, +-1.02171, -1.15596, -1.28086, -1.46626, -1.44951, -1.24291, -1.11340, -0.87244, -0.62844, -0.53359, -0.51878, -0.36052, -0.12231, 0.06685, 0.23521, 0.21048, 0.21279, 0.29454, 0.42659, 0.53576, 0.55296, 0.52341, 0.32145, 0.18023, 0.18820, 0.17970, 0.20370, 0.14565, 0.14493, 0.26112, 0.42211, 0.63087, 0.90830, 1.26008, 1.63617, 1.84031, 1.96205, 1.95911, 1.75526, 1.67345, 1.70351, 1.70072, 1.49964, 1.23987, 1.04331, 0.89476, 0.81497, 0.51490, 0.21344, 0.01331, -0.21202, -0.43174, -0.54032, -0.46111, -0.53798, -0.69021, -0.74885, -0.74957, -0.73458, -0.76127, -0.78711, -0.89189, -1.03921, -1.28308, -1.43920, -1.48828, -1.52361, -1.55355, -1.59840, -1.61211, -1.68313, -1.64111, -1.46482, -1.41541, -1.52469, -1.71827, -1.81477, -1.90721, -1.84983, -1.86282, -2.01513, -2.13545, -2.18221, -2.05752, -1.85816, -1.53518, -1.32579, -1.30614, -1.29301, -1.37437, -1.51931, -1.66974, -1.76653, -1.77756, -1.71703, -1.74440, -1.82684, -1.99509, -2.13019, -2.15280, -2.06243, -1.82067, -1.75551, -1.72962, -1.55351, -1.35283, -1.24567, -1.31423, -1.27762, -1.27342, -1.26888, -1.37716, -1.52617, -1.55088, -1.60506, -1.64622, -1.72652, -1.71072, -1.79203, -1.89116, -1.83637, -1.81564, -1.77808, -1.82833, -1.77262, -1.61127, -1.42953, -1.28433, -1.25419, -1.27134, -1.22567, -1.12512, -1.06894, -1.05626, -1.19622, -1.38685, -1.41785, -1.45121, -1.50713, -1.64375, -1.70760, -1.81599, -1.82623, -1.76059, -1.76034, -1.68574, -1.64161, -1.65102, -1.75958, -1.87788, -2.02920, -2.22665, -2.28968, -2.30750, -2.26259, -2.25966, -2.22591, -2.24659, -2.19253, -2.01362, -1.75676, -1.48376, -1.38160, -1.40216, -1.51341, -1.46895, -1.43849, -1.45838, -1.24573, -0.96825, -0.83020, -0.83799, -0.69983, -0.56531, -0.40970, -0.23457, -0.15733, 0.02511, 0.25779, 0.57906, 0.81480, 1.02252, 1.17506, 1.19917, 1.42514, 1.71223, 1.95911, 2.11538, 2.11192, 2.05001, 2.09218, 2.18546, 2.26431, 2.32136, 2.44740, 2.62101, 2.80165, 3.03870, 3.30234, 3.41393, 3.50562, 3.48215, 3.32878, 3.05544, 2.91355, 2.82101, 2.79061, 2.68605, 2.42075, 2.20743, 2.08573, 2.10280, 2.07201, 2.09463, 2.07176, 1.80581, 1.49948, 1.08796, 0.71798, 0.46511, 0.29896, 0.19052, 0.01155, -0.19971, -0.41996, -0.50123, -0.49210, -0.44540, -0.38023, -0.26276, -0.19614, -0.24811, -0.17713, -0.11953, -0.22925, -0.49800, -0.66545, -0.81091, -0.86643, -0.79885, -0.87970, -1.02588, -1.15918, -1.33524, -1.48672, -1.57419, -1.62461, -1.81312, -2.10940, -2.43938, -2.72449, -2.93099, -3.17755, -3.44800, -3.64944, -3.74816, -3.79192, -3.73871, -3.58296, -3.42968, -3.45414, -3.46803, -3.42349, -3.41222, -3.33786, -3.18044, -3.11737, -3.27468, -3.44534, -3.60902, -3.64913, -3.48879, -3.45605, -3.43849, -3.42823, -3.46738, -3.52548, -3.65976, -3.65838, -3.64184, -3.51858, -3.28228, -3.08139, -2.87061, -2.69111, -2.41522, -2.08405, -1.79078, -1.57892, -1.50884, -1.59673, -1.72466, -1.84990, -1.93664, -1.96178, -2.05082, -2.06528, -2.03248, -2.08212, -2.22647, -2.42918, -2.60528, -2.71147, -2.66743, -2.56461, -2.45603, -2.32180, -2.25894, -2.36222, -2.51581, -2.49787, -2.51133, -2.61894, -2.77950, -3.00041, -3.20870, -3.43042, -3.62542, -3.72772, -3.78159, -3.87568, -3.90414, -3.82492, -3.63296, -3.47704, -3.26710, -3.02149, -2.98623, -2.99130, -2.96086, -2.87444, -2.70651, -2.53066, -2.21678, -1.91893, -1.53062, -1.24689, -1.12517, -0.90568, -0.64884, -0.35271, -0.19966, -0.10351, -0.15830, -0.27816, -0.21900, -0.10564, 0.08468, 0.29156, 0.47236, 0.61193, 0.82029, 1.08055, 1.35248, 1.58348, 1.78220, 1.91545, 1.98665, 2.10907, 2.09931, 1.92688, 1.71867, 1.46005, 1.12502, 0.83780, 0.73207, 0.67984, 0.73827, 0.67424, 0.48942, 0.42394, 0.43393, 0.45537, 0.36522, 0.36110, 0.30963, 0.15917, 0.08965, 0.05363, -0.00682, -0.20124, -0.39305, -0.47948, -0.41502, -0.37913, -0.34127, -0.34139, -0.39683, -0.47034, -0.61990, -0.57104, -0.46210, -0.36175, -0.11116, 0.09753, 0.21437, 0.19592, 0.26934, 0.40119, 0.66958, 0.92485, +-1.07969, -1.14449, -1.27364, -1.45161, -1.38938, -1.28322, -1.15655, -0.90703, -0.68618, -0.56539, -0.46504, -0.37720, -0.20984, 0.05106, 0.19953, 0.11404, 0.02235, 0.16610, 0.29116, 0.36482, 0.40905, 0.44490, 0.36298, 0.23829, 0.23230, 0.06491, -0.03025, 0.01079, 0.09983, 0.24954, 0.42779, 0.63983, 0.85862, 1.19660, 1.59050, 1.84007, 2.05449, 2.01459, 1.78593, 1.68753, 1.61289, 1.61154, 1.55121, 1.30908, 1.05149, 0.99045, 0.87252, 0.49234, 0.10231, -0.05289, -0.20561, -0.43880, -0.55116, -0.56409, -0.66888, -0.82013, -0.79189, -0.86260, -0.94867, -0.93563, -0.91307, -1.00161, -1.19139, -1.41793, -1.59407, -1.66073, -1.69136, -1.70565, -1.58448, -1.55611, -1.59685, -1.47820, -1.33155, -1.22667, -1.19508, -1.33823, -1.54505, -1.58021, -1.56609, -1.63449, -1.76220, -1.77931, -1.72321, -1.73666, -1.67147, -1.50549, -1.33367, -1.26152, -1.11279, -1.17687, -1.34804, -1.45164, -1.56190, -1.63373, -1.61869, -1.59885, -1.66625, -1.83759, -2.00651, -2.13466, -2.02529, -1.78290, -1.68055, -1.55369, -1.41667, -1.22548, -1.09726, -1.15766, -1.29018, -1.26004, -1.22823, -1.36034, -1.52727, -1.58845, -1.61934, -1.73717, -1.78119, -1.80518, -1.85345, -1.91233, -1.70537, -1.62139, -1.64020, -1.62220, -1.54823, -1.44663, -1.37095, -1.23485, -1.14994, -1.15250, -1.07712, -1.03753, -0.93162, -0.90023, -1.07544, -1.22287, -1.35863, -1.45123, -1.50808, -1.54486, -1.63210, -1.62436, -1.56531, -1.62936, -1.76485, -1.78931, -1.72559, -1.76449, -1.81814, -1.95421, -2.03738, -2.24259, -2.28114, -2.31891, -2.33757, -2.24280, -2.11860, -2.11300, -2.15558, -2.04113, -1.79629, -1.50552, -1.29639, -1.33011, -1.36773, -1.26766, -1.29471, -1.25845, -1.11959, -0.89029, -0.69315, -0.55144, -0.48918, -0.40021, -0.27104, -0.17583, -0.11191, 0.04889, 0.34863, 0.62980, 0.93784, 1.13819, 1.33669, 1.40968, 1.68544, 1.97249, 2.08174, 2.24718, 2.34932, 2.31073, 2.27278, 2.29170, 2.37097, 2.42019, 2.59421, 2.69331, 2.84172, 3.08697, 3.25122, 3.45807, 3.63093, 3.64937, 3.56021, 3.32094, 3.00083, 2.79121, 2.73290, 2.59353, 2.31888, 2.10228, 2.07901, 2.03100, 1.95896, 1.90080, 1.93201, 1.77172, 1.58135, 1.26575, 0.76081, 0.43029, 0.29585, 0.23462, 0.05219, -0.20114, -0.39266, -0.48709, -0.46151, -0.46110, -0.41883, -0.23124, -0.17182, -0.12348, -0.04138, -0.12315, -0.30227, -0.49200, -0.69590, -0.88859, -0.93569, -0.92395, -0.99383, -1.14725, -1.18947, -1.34783, -1.52662, -1.68627, -1.75603, -1.85343, -2.00991, -2.22075, -2.60139, -2.89575, -3.08737, -3.33335, -3.59288, -3.80215, -3.88948, -3.88139, -3.73263, -3.56032, -3.51996, -3.40098, -3.38321, -3.43390, -3.42040, -3.42490, -3.41379, -3.42577, -3.55752, -3.71472, -3.67339, -3.58074, -3.62455, -3.66501, -3.53553, -3.48185, -3.52042, -3.67007, -3.75434, -3.74597, -3.59073, -3.20981, -3.03186, -2.87064, -2.59701, -2.29449, -2.03961, -1.86497, -1.71664, -1.67730, -1.72824, -1.81566, -1.97045, -2.06630, -2.19018, -2.28948, -2.23877, -2.29209, -2.40415, -2.47647, -2.61519, -2.85708, -2.92274, -2.92411, -2.91829, -2.90376, -2.75015, -2.59238, -2.66878, -2.80141, -2.83939, -2.82840, -2.88094, -2.91560, -3.18684, -3.51067, -3.69259, -3.86268, -3.99197, -4.03277, -4.00807, -3.92602, -3.78936, -3.64232, -3.57804, -3.36797, -3.14355, -3.03120, -2.88100, -2.83503, -2.76330, -2.58321, -2.40544, -2.22514, -1.86222, -1.47669, -1.24361, -1.18181, -1.00148, -0.71286, -0.46684, -0.22535, -0.10990, -0.07835, -0.10227, 0.07247, 0.13076, 0.18190, 0.39086, 0.60497, 0.75436, 0.92941, 1.15926, 1.35895, 1.54532, 1.78433, 1.90961, 2.02834, 2.10290, 2.06615, 2.02869, 1.78825, 1.50164, 1.22041, 1.00134, 0.76799, 0.74672, 0.86487, 0.82060, 0.63845, 0.57833, 0.67540, 0.68429, 0.67445, 0.63060, 0.58999, 0.44794, 0.43191, 0.35157, 0.20891, 0.09278, -0.01162, -0.12323, -0.24081, -0.32388, -0.38977, -0.43982, -0.41077, -0.47873, -0.53324, -0.48903, -0.48372, -0.34993, -0.16296, 0.03380, 0.20441, 0.31102, 0.25569, 0.32105, 0.53899, 0.71435, +-0.97809, -1.05983, -1.16388, -1.27955, -1.25495, -1.22542, -1.16700, -0.98950, -0.76958, -0.65884, -0.52918, -0.42282, -0.34282, -0.16413, -0.01960, -0.02388, -0.02242, 0.15341, 0.24217, 0.26108, 0.30467, 0.34761, 0.36351, 0.28649, 0.18207, -0.05102, -0.12308, 0.00502, 0.14159, 0.35151, 0.60955, 0.86917, 1.07253, 1.30118, 1.59528, 1.85421, 2.04405, 1.98354, 1.78073, 1.64218, 1.55980, 1.53229, 1.48390, 1.30984, 1.01930, 0.90072, 0.76268, 0.38756, 0.00504, -0.13908, -0.28065, -0.47941, -0.56845, -0.65044, -0.78589, -0.90484, -0.89577, -0.98128, -1.05688, -1.01909, -1.00600, -1.07790, -1.25934, -1.45051, -1.59867, -1.70183, -1.73254, -1.68160, -1.54659, -1.56702, -1.60238, -1.51396, -1.32344, -1.13832, -1.01154, -0.97344, -1.14885, -1.26966, -1.33161, -1.44658, -1.53808, -1.47262, -1.38917, -1.43567, -1.45043, -1.39644, -1.27479, -1.11861, -0.97187, -1.02888, -1.09874, -1.10876, -1.23595, -1.38385, -1.46369, -1.45271, -1.48508, -1.63645, -1.78628, -1.89504, -1.84275, -1.75477, -1.70376, -1.63188, -1.47522, -1.22072, -1.08517, -1.08464, -1.28537, -1.39285, -1.39045, -1.48757, -1.60283, -1.63055, -1.69330, -1.79789, -1.77883, -1.78458, -1.84714, -1.83299, -1.61733, -1.54722, -1.53322, -1.42681, -1.34754, -1.27573, -1.23148, -1.10973, -1.01057, -1.03834, -0.98475, -0.91505, -0.80248, -0.86011, -1.03478, -1.18279, -1.30092, -1.36635, -1.48149, -1.48986, -1.56875, -1.61473, -1.55661, -1.65055, -1.82674, -1.85336, -1.81993, -1.81218, -1.81289, -1.90966, -1.95764, -2.08095, -2.14879, -2.31734, -2.40744, -2.24408, -2.07285, -1.99586, -1.98506, -1.86738, -1.63256, -1.40719, -1.24005, -1.23027, -1.20965, -1.14914, -1.19064, -1.21227, -1.11731, -0.85813, -0.63711, -0.37518, -0.27657, -0.30853, -0.26666, -0.18313, -0.05707, 0.18398, 0.47058, 0.75339, 1.10317, 1.32620, 1.50041, 1.65792, 1.94389, 2.14876, 2.21898, 2.41589, 2.51738, 2.45632, 2.39879, 2.39708, 2.49664, 2.54660, 2.72976, 2.90939, 3.10363, 3.24673, 3.29308, 3.39591, 3.57338, 3.69582, 3.66094, 3.46812, 3.11925, 2.76470, 2.61140, 2.47588, 2.23245, 2.10216, 2.12395, 2.07257, 1.98812, 1.84565, 1.76235, 1.67174, 1.56873, 1.30396, 0.84660, 0.56641, 0.41733, 0.29705, 0.09573, -0.16134, -0.31348, -0.39484, -0.41656, -0.42594, -0.38019, -0.25919, -0.22707, -0.18074, -0.10594, -0.17935, -0.38185, -0.50600, -0.62048, -0.86793, -1.02236, -1.05705, -1.09792, -1.19205, -1.21344, -1.34972, -1.49908, -1.66214, -1.78960, -1.85174, -1.95514, -2.20128, -2.60955, -2.88002, -3.04605, -3.30294, -3.52924, -3.68926, -3.74026, -3.74971, -3.71483, -3.59591, -3.49694, -3.37938, -3.40804, -3.54220, -3.62504, -3.65996, -3.64943, -3.57437, -3.60637, -3.75504, -3.75625, -3.70183, -3.75972, -3.84411, -3.74413, -3.66622, -3.62031, -3.66445, -3.74669, -3.72285, -3.54228, -3.23118, -3.09310, -2.89895, -2.56165, -2.25971, -2.03859, -1.92207, -1.82671, -1.81334, -1.90026, -1.96837, -2.06497, -2.21845, -2.45344, -2.56737, -2.51187, -2.53341, -2.64779, -2.70308, -2.75003, -3.03122, -3.21675, -3.26673, -3.26936, -3.25688, -3.09716, -2.95561, -3.00196, -3.10854, -3.18877, -3.18133, -3.15821, -3.20070, -3.45595, -3.69143, -3.78992, -3.96666, -4.13957, -4.18062, -4.06277, -3.87037, -3.71485, -3.60596, -3.52677, -3.35856, -3.20552, -3.04482, -2.87802, -2.73621, -2.58092, -2.39542, -2.17539, -2.13841, -1.98149, -1.66902, -1.40912, -1.26309, -1.01845, -0.74775, -0.50792, -0.25555, -0.13956, -0.06928, 0.05121, 0.25172, 0.25549, 0.28315, 0.50090, 0.68840, 0.83106, 1.01193, 1.24021, 1.41208, 1.53520, 1.77701, 2.00001, 2.13804, 2.10115, 2.04764, 1.99588, 1.78267, 1.55266, 1.30711, 1.19456, 0.94061, 0.78908, 0.84780, 0.81759, 0.67604, 0.67416, 0.77677, 0.83439, 0.89215, 0.90690, 0.91298, 0.86460, 0.80738, 0.58047, 0.38535, 0.34486, 0.27562, 0.15275, -0.03659, -0.17727, -0.28867, -0.37983, -0.34674, -0.34925, -0.33096, -0.35642, -0.40532, -0.37965, -0.31167, -0.14245, 0.02868, 0.26853, 0.27106, 0.21956, 0.33181, 0.44438, +-0.83171, -0.98136, -1.15565, -1.21024, -1.10548, -1.07002, -1.01013, -0.88266, -0.74295, -0.73664, -0.69732, -0.62302, -0.46617, -0.33521, -0.26558, -0.12451, -0.06101, 0.07313, 0.07497, 0.02719, 0.11571, 0.08338, 0.09228, 0.07292, 0.00162, -0.16230, -0.17061, -0.01787, 0.12651, 0.38917, 0.63073, 0.91030, 1.18682, 1.34808, 1.48369, 1.72059, 1.96098, 1.94201, 1.83078, 1.74451, 1.67183, 1.54801, 1.35195, 1.14230, 0.94043, 0.83545, 0.61345, 0.32759, -0.03273, -0.23561, -0.43701, -0.66215, -0.66038, -0.79088, -0.99188, -1.09392, -1.06843, -1.06431, -1.11998, -1.12372, -1.17673, -1.22415, -1.40855, -1.55874, -1.57718, -1.64786, -1.72719, -1.68136, -1.54140, -1.57473, -1.57807, -1.44680, -1.22149, -1.02675, -0.91863, -0.79789, -0.81438, -0.86623, -1.05503, -1.17228, -1.27860, -1.28567, -1.24093, -1.30642, -1.25296, -1.25168, -1.19783, -0.99232, -0.86508, -0.84667, -0.87545, -0.87385, -1.01567, -1.15211, -1.31257, -1.34589, -1.30713, -1.41439, -1.59354, -1.72112, -1.66367, -1.67313, -1.70922, -1.63976, -1.47629, -1.21983, -1.14267, -1.16778, -1.31730, -1.35635, -1.46446, -1.51279, -1.55687, -1.61391, -1.70036, -1.82856, -1.68315, -1.63736, -1.77490, -1.73967, -1.58068, -1.45558, -1.40718, -1.27548, -1.20012, -1.08326, -1.04595, -0.99695, -0.90853, -0.93751, -0.95697, -0.93045, -0.78245, -0.84857, -1.02046, -1.08436, -1.15151, -1.21555, -1.44249, -1.57651, -1.67093, -1.62535, -1.64610, -1.68974, -1.80029, -1.87846, -1.84364, -1.84669, -1.76737, -1.81860, -1.96516, -2.06605, -2.16118, -2.31264, -2.44761, -2.30808, -2.17255, -2.01716, -1.92018, -1.80341, -1.52903, -1.32890, -1.28127, -1.31417, -1.21628, -1.10850, -1.13792, -1.12069, -1.00984, -0.72740, -0.55692, -0.33572, -0.18863, -0.07549, -0.10875, -0.01936, 0.21533, 0.43241, 0.67245, 0.86480, 1.22428, 1.50174, 1.58153, 1.77549, 2.07504, 2.33905, 2.43065, 2.57662, 2.55613, 2.47371, 2.43537, 2.39841, 2.53844, 2.64173, 2.78568, 2.95698, 3.22505, 3.37355, 3.33700, 3.36896, 3.51487, 3.66881, 3.62585, 3.41748, 3.08540, 2.85522, 2.66912, 2.51823, 2.34533, 2.16653, 2.12482, 1.99352, 1.93100, 1.81929, 1.56572, 1.45744, 1.38771, 1.25734, 0.94096, 0.71219, 0.49526, 0.28180, 0.04744, -0.25465, -0.38280, -0.41093, -0.50135, -0.59812, -0.51212, -0.34798, -0.32079, -0.23592, -0.10356, -0.10753, -0.33025, -0.48970, -0.56000, -0.66949, -0.86840, -1.00123, -1.00366, -1.13103, -1.20176, -1.37171, -1.46628, -1.51860, -1.74243, -1.89233, -2.05045, -2.28543, -2.63470, -2.89275, -3.11234, -3.40334, -3.56516, -3.68250, -3.67425, -3.62857, -3.70723, -3.76428, -3.67960, -3.52464, -3.54369, -3.64081, -3.70945, -3.71503, -3.70217, -3.66483, -3.70006, -3.74821, -3.76019, -3.79182, -3.76905, -3.89542, -3.90695, -3.88258, -3.79784, -3.65900, -3.73453, -3.74146, -3.57451, -3.34811, -3.20983, -3.01460, -2.72404, -2.46901, -2.23190, -2.15864, -2.06800, -1.99264, -2.11192, -2.25378, -2.30184, -2.37748, -2.61390, -2.69368, -2.57014, -2.54415, -2.67724, -2.82622, -2.92686, -3.14919, -3.32859, -3.48374, -3.41573, -3.40421, -3.34483, -3.32391, -3.44443, -3.46084, -3.57600, -3.63573, -3.58253, -3.62805, -3.75745, -3.88107, -3.94746, -4.14401, -4.30690, -4.39478, -4.26022, -3.95766, -3.75438, -3.68211, -3.58935, -3.34084, -3.13559, -2.92428, -2.70436, -2.52220, -2.36069, -2.23853, -2.05943, -2.04541, -1.92958, -1.77824, -1.47254, -1.24230, -1.01886, -0.78095, -0.60853, -0.33283, -0.23359, -0.20221, -0.00069, 0.21156, 0.29354, 0.33394, 0.52655, 0.64847, 0.79115, 0.94597, 1.16244, 1.39930, 1.52888, 1.72246, 1.97424, 2.20242, 2.18871, 2.12754, 2.09483, 1.91182, 1.71636, 1.45946, 1.36068, 1.16580, 1.08161, 0.96222, 0.91157, 0.82481, 0.77334, 0.84766, 0.86662, 1.01511, 1.12275, 1.12212, 1.13655, 1.03211, 0.78131, 0.51290, 0.43007, 0.30334, 0.21541, 0.03630, -0.14614, -0.20138, -0.23942, -0.27003, -0.32384, -0.25942, -0.28169, -0.35163, -0.33122, -0.33876, -0.23155, -0.14233, 0.06797, 0.15143, 0.23591, 0.23489, 0.28927, +-0.73823, -0.92711, -1.02061, -1.02157, -0.85618, -0.78543, -0.75722, -0.75199, -0.82450, -0.91818, -0.81334, -0.69945, -0.58217, -0.49302, -0.45095, -0.30022, -0.23349, -0.15808, -0.10304, -0.10103, -0.16952, -0.28730, -0.25738, -0.24492, -0.21159, -0.26484, -0.22476, -0.03259, 0.21635, 0.52910, 0.70157, 0.89464, 1.08682, 1.20070, 1.38658, 1.65198, 1.94598, 2.04249, 1.98393, 1.90291, 1.75969, 1.47886, 1.20435, 1.02541, 0.86332, 0.80572, 0.60439, 0.32850, -0.01305, -0.25719, -0.46156, -0.67337, -0.84533, -1.08766, -1.24362, -1.33693, -1.24962, -1.12919, -1.16294, -1.20438, -1.23946, -1.21663, -1.35359, -1.44550, -1.47327, -1.58861, -1.60932, -1.59337, -1.51095, -1.44258, -1.38532, -1.28020, -1.16767, -1.08957, -0.94058, -0.68635, -0.61063, -0.60692, -0.77835, -0.91331, -1.06834, -1.17983, -1.16881, -1.13154, -1.13975, -1.25067, -1.14085, -0.91466, -0.76493, -0.65883, -0.71175, -0.77172, -0.84019, -0.87413, -1.02237, -1.06022, -1.06018, -1.24610, -1.39816, -1.51243, -1.49541, -1.52341, -1.66600, -1.66803, -1.55935, -1.38470, -1.26591, -1.18567, -1.26693, -1.25867, -1.39109, -1.48518, -1.55797, -1.64898, -1.70972, -1.70129, -1.55282, -1.58152, -1.65333, -1.62820, -1.52443, -1.31687, -1.20725, -1.06262, -0.94159, -0.76032, -0.73783, -0.78205, -0.79816, -0.90330, -0.88121, -0.86129, -0.80784, -0.82465, -0.98247, -1.05234, -1.15038, -1.33964, -1.57470, -1.65966, -1.78236, -1.76422, -1.82060, -1.84351, -1.91090, -1.99838, -1.92987, -1.77033, -1.67598, -1.86314, -2.04148, -2.17690, -2.28200, -2.34297, -2.43688, -2.33943, -2.19736, -1.95694, -1.83183, -1.70317, -1.44659, -1.40181, -1.41115, -1.38507, -1.25135, -1.00230, -0.95920, -0.94143, -0.84483, -0.67197, -0.53987, -0.26961, -0.10087, 0.07550, 0.08446, 0.19552, 0.47069, 0.67235, 0.86767, 1.10309, 1.39875, 1.53800, 1.66699, 1.92795, 2.21094, 2.53183, 2.66146, 2.70134, 2.63125, 2.66256, 2.68055, 2.61471, 2.68358, 2.67318, 2.79102, 2.99621, 3.23351, 3.42164, 3.40730, 3.36944, 3.40248, 3.38760, 3.30211, 3.22681, 2.99924, 2.84947, 2.72824, 2.61239, 2.46103, 2.23319, 2.06375, 1.94866, 1.89727, 1.64491, 1.38454, 1.32100, 1.26097, 1.24595, 1.06240, 0.86935, 0.64585, 0.41761, 0.12019, -0.21744, -0.37118, -0.48866, -0.62829, -0.71047, -0.62502, -0.40370, -0.32876, -0.26095, -0.15687, -0.20784, -0.42443, -0.47319, -0.42895, -0.45769, -0.62464, -0.80468, -0.86250, -1.00149, -1.09464, -1.17267, -1.23213, -1.43543, -1.72418, -1.93062, -2.15776, -2.30592, -2.54298, -2.83747, -3.13166, -3.36782, -3.48056, -3.58383, -3.58866, -3.63960, -3.79011, -3.87839, -3.87487, -3.75112, -3.71305, -3.76154, -3.83390, -3.89898, -3.91613, -3.80407, -3.75801, -3.78975, -3.84862, -3.92068, -3.88671, -3.99285, -4.02527, -3.93981, -3.77492, -3.71656, -3.81012, -3.74383, -3.61180, -3.46430, -3.34443, -3.18639, -2.93904, -2.62885, -2.35601, -2.30451, -2.21352, -2.18961, -2.37962, -2.51723, -2.57136, -2.59832, -2.71424, -2.74518, -2.59854, -2.59630, -2.79047, -2.93987, -3.00182, -3.16957, -3.30920, -3.47755, -3.47957, -3.53533, -3.59140, -3.65948, -3.74372, -3.81148, -3.98720, -4.03383, -4.02009, -4.02737, -4.01890, -4.06550, -4.11605, -4.21708, -4.26974, -4.37220, -4.28960, -4.07693, -3.94518, -3.79194, -3.64716, -3.36072, -3.01095, -2.74093, -2.51208, -2.38738, -2.37462, -2.26093, -1.99913, -1.94931, -1.81458, -1.69744, -1.43941, -1.22299, -1.03778, -0.78890, -0.55858, -0.44097, -0.49361, -0.37955, -0.10652, 0.17655, 0.37286, 0.43605, 0.59658, 0.73078, 0.88767, 0.95157, 1.08502, 1.26851, 1.31834, 1.56211, 1.89531, 2.17604, 2.30901, 2.26945, 2.22091, 2.06101, 1.82041, 1.61700, 1.60866, 1.45934, 1.38895, 1.18280, 1.08590, 1.04117, 0.96450, 0.97441, 1.04300, 1.14927, 1.15324, 1.23048, 1.27982, 1.17693, 0.99799, 0.69361, 0.49346, 0.32129, 0.29527, 0.13379, -0.07608, -0.15645, -0.26148, -0.27060, -0.28914, -0.27675, -0.28031, -0.35441, -0.36404, -0.41851, -0.44044, -0.38416, -0.11032, 0.02431, 0.17769, 0.19690, 0.19008, +-0.72360, -0.80208, -0.77632, -0.77606, -0.74684, -0.75246, -0.72052, -0.83654, -0.92502, -0.92020, -0.81505, -0.67883, -0.62827, -0.63925, -0.62492, -0.53260, -0.44508, -0.44113, -0.38351, -0.28236, -0.36963, -0.40596, -0.35841, -0.41792, -0.38339, -0.34600, -0.29423, -0.11994, 0.19654, 0.45981, 0.61053, 0.77395, 0.90020, 1.10822, 1.41879, 1.68804, 1.91360, 1.99122, 1.95496, 1.83148, 1.71609, 1.52247, 1.17945, 0.97736, 0.83505, 0.74635, 0.57367, 0.32617, 0.09778, -0.13841, -0.43659, -0.70577, -1.03248, -1.20540, -1.25056, -1.40673, -1.42477, -1.30865, -1.30663, -1.35287, -1.34426, -1.32872, -1.37815, -1.32772, -1.39576, -1.46090, -1.39056, -1.43381, -1.44596, -1.34368, -1.16257, -1.08318, -1.05769, -0.93889, -0.83783, -0.63078, -0.52942, -0.55073, -0.63754, -0.67273, -0.77162, -0.93655, -1.07791, -1.02097, -1.05724, -1.07316, -0.91000, -0.80937, -0.74197, -0.61140, -0.65177, -0.75214, -0.73459, -0.75256, -0.84493, -0.77247, -0.81420, -1.00152, -1.15226, -1.31773, -1.39882, -1.49239, -1.62056, -1.68405, -1.63204, -1.36652, -1.24286, -1.16960, -1.15972, -1.17484, -1.33610, -1.47308, -1.55958, -1.60109, -1.69203, -1.62421, -1.54996, -1.51466, -1.43757, -1.46821, -1.48359, -1.26357, -1.05586, -0.88152, -0.73685, -0.63387, -0.65603, -0.65794, -0.69838, -0.70004, -0.55945, -0.58261, -0.71948, -0.86314, -1.01074, -1.15321, -1.35337, -1.47483, -1.64715, -1.71416, -1.83115, -1.95364, -2.10849, -2.11752, -2.10310, -2.09256, -2.11818, -1.93692, -1.84342, -1.94854, -2.02426, -2.21610, -2.39812, -2.44648, -2.43352, -2.34300, -2.18397, -2.03056, -2.01845, -1.81100, -1.53733, -1.42940, -1.33219, -1.25043, -1.14736, -0.94164, -0.82504, -0.77908, -0.71679, -0.47198, -0.35052, -0.18033, -0.01721, 0.14763, 0.19885, 0.34361, 0.60317, 0.85449, 0.96506, 1.16973, 1.39018, 1.58956, 1.91426, 2.22041, 2.36038, 2.58075, 2.76521, 2.78106, 2.79538, 2.93739, 2.97649, 2.98006, 2.98034, 2.93139, 3.06166, 3.18759, 3.25839, 3.30368, 3.35681, 3.36209, 3.24887, 3.17875, 3.07214, 2.99120, 2.87343, 2.74096, 2.58363, 2.47960, 2.38618, 2.27103, 1.98648, 1.81116, 1.72990, 1.50351, 1.42768, 1.42405, 1.27195, 1.15765, 1.02758, 0.89019, 0.74624, 0.57122, 0.19647, -0.10579, -0.26647, -0.42812, -0.52575, -0.59691, -0.57731, -0.46741, -0.40395, -0.33403, -0.32272, -0.29752, -0.38214, -0.45216, -0.41052, -0.44891, -0.61810, -0.80351, -0.87135, -0.87651, -0.97430, -1.06766, -1.20308, -1.49513, -1.67820, -1.85873, -2.14207, -2.27187, -2.38090, -2.66361, -2.99991, -3.19631, -3.39640, -3.52637, -3.55342, -3.66849, -3.70665, -3.73475, -3.87838, -3.96974, -3.99535, -3.95904, -4.04610, -4.10003, -4.09083, -4.05255, -3.98365, -4.00043, -4.14151, -4.22444, -4.15154, -4.09803, -4.07379, -4.00257, -3.84069, -3.88549, -3.87072, -3.68182, -3.60141, -3.53475, -3.41522, -3.27686, -3.06619, -2.72859, -2.54331, -2.49051, -2.32300, -2.32768, -2.46333, -2.58937, -2.74397, -2.84652, -2.93214, -2.90164, -2.83276, -2.83589, -2.90722, -3.10083, -3.17413, -3.25345, -3.39820, -3.57755, -3.68578, -3.76202, -3.87207, -4.05174, -4.07828, -4.12782, -4.13768, -4.10406, -4.20754, -4.26646, -4.21483, -4.22669, -4.26190, -4.22783, -4.19024, -4.23358, -4.14434, -4.08379, -3.95737, -3.70692, -3.56679, -3.38851, -3.12477, -2.80889, -2.56903, -2.44842, -2.37023, -2.29660, -2.04832, -1.90379, -1.76708, -1.64805, -1.43821, -1.26713, -1.09979, -0.91984, -0.64294, -0.58333, -0.54427, -0.28444, -0.02102, 0.23512, 0.46533, 0.58736, 0.75331, 0.92890, 0.98580, 0.91095, 1.01225, 1.12488, 1.22518, 1.51843, 1.79667, 2.01272, 2.15385, 2.19397, 2.17540, 2.07493, 2.00291, 1.81873, 1.72524, 1.62239, 1.51578, 1.30763, 1.27614, 1.34410, 1.36246, 1.23312, 1.25086, 1.27931, 1.31015, 1.47300, 1.48195, 1.33425, 1.22655, 0.98613, 0.68406, 0.45293, 0.34140, 0.13384, -0.02417, -0.19236, -0.34166, -0.30549, -0.30938, -0.39048, -0.51811, -0.56786, -0.57131, -0.64928, -0.57347, -0.52476, -0.35982, -0.24973, -0.13727, -0.08194, -0.03965, +-0.76565, -0.74101, -0.75257, -0.79344, -0.80310, -0.87573, -0.85531, -0.94634, -0.94657, -0.86938, -0.82923, -0.73604, -0.63253, -0.60103, -0.59789, -0.56920, -0.55995, -0.56246, -0.50146, -0.39497, -0.37977, -0.34466, -0.38434, -0.48536, -0.44843, -0.42675, -0.34819, -0.14910, 0.09865, 0.34066, 0.50613, 0.62753, 0.81804, 1.08764, 1.31631, 1.49774, 1.73653, 1.79622, 1.74437, 1.65143, 1.60209, 1.52092, 1.17106, 0.88507, 0.77124, 0.73601, 0.58272, 0.36113, 0.15701, -0.03411, -0.33634, -0.69898, -1.00970, -1.09415, -1.18026, -1.40460, -1.52553, -1.55167, -1.51721, -1.44517, -1.46531, -1.45920, -1.44787, -1.40747, -1.39520, -1.34746, -1.28620, -1.40486, -1.38157, -1.25634, -1.04772, -0.89982, -0.83880, -0.68663, -0.65520, -0.58472, -0.46409, -0.37932, -0.38281, -0.34073, -0.42016, -0.58218, -0.73584, -0.75935, -0.77044, -0.71447, -0.69932, -0.79392, -0.78239, -0.70966, -0.68188, -0.61839, -0.59955, -0.67193, -0.75140, -0.74604, -0.72697, -0.82454, -1.03855, -1.34229, -1.43862, -1.49451, -1.58334, -1.62761, -1.58333, -1.29947, -1.22429, -1.25552, -1.20392, -1.11893, -1.26401, -1.41064, -1.49850, -1.49292, -1.51278, -1.50809, -1.50299, -1.42644, -1.36798, -1.49401, -1.53470, -1.37385, -1.13355, -0.80180, -0.67048, -0.66406, -0.66024, -0.70629, -0.65680, -0.49390, -0.34730, -0.50483, -0.70738, -0.90528, -1.09738, -1.26244, -1.47634, -1.53315, -1.67285, -1.80682, -1.93102, -2.01975, -2.20040, -2.21537, -2.18524, -2.17147, -2.22615, -2.16109, -2.06241, -2.00997, -2.02351, -2.27720, -2.45573, -2.57026, -2.57725, -2.36991, -2.21059, -2.20266, -2.23279, -2.10739, -1.78834, -1.44853, -1.23131, -1.21640, -1.12161, -0.93132, -0.81929, -0.72703, -0.62686, -0.31328, -0.20177, -0.16212, -0.01011, 0.27528, 0.40954, 0.56869, 0.75108, 0.93219, 1.07123, 1.20899, 1.38925, 1.71732, 2.09437, 2.30704, 2.38600, 2.51068, 2.68740, 2.87773, 3.03304, 3.17386, 3.28189, 3.27900, 3.27633, 3.32014, 3.41877, 3.32438, 3.25073, 3.23209, 3.27750, 3.31105, 3.17601, 3.11486, 2.99451, 2.82960, 2.71866, 2.66087, 2.48818, 2.36717, 2.31701, 2.25830, 2.06912, 1.87361, 1.73644, 1.57919, 1.51607, 1.39813, 1.19895, 0.98829, 0.81449, 0.81415, 0.80808, 0.66873, 0.35676, 0.02467, -0.18736, -0.29563, -0.38549, -0.58306, -0.64699, -0.56854, -0.53914, -0.46146, -0.40642, -0.27067, -0.27833, -0.45287, -0.55733, -0.59416, -0.69215, -0.84658, -0.89653, -0.88002, -0.92718, -1.05035, -1.29347, -1.54873, -1.68032, -1.91930, -2.17924, -2.28998, -2.37006, -2.51139, -2.73060, -2.96738, -3.19925, -3.39574, -3.51425, -3.57743, -3.54132, -3.64670, -3.92523, -4.09657, -4.18204, -4.12681, -4.16079, -4.19008, -4.24296, -4.35843, -4.37903, -4.32109, -4.34587, -4.37302, -4.26955, -4.20516, -4.14662, -4.07099, -3.98393, -4.01732, -3.94259, -3.80109, -3.72385, -3.60441, -3.50373, -3.33223, -3.06567, -2.83950, -2.74222, -2.71000, -2.59233, -2.51410, -2.55902, -2.74836, -3.00144, -3.08532, -3.16059, -3.15552, -3.13584, -3.12753, -3.11888, -3.34932, -3.49512, -3.49799, -3.53847, -3.70550, -3.87061, -4.00305, -4.11698, -4.26462, -4.30394, -4.28503, -4.17152, -4.16835, -4.33761, -4.38569, -4.36356, -4.31438, -4.17885, -4.09285, -3.99876, -3.96222, -3.96126, -3.91299, -3.74186, -3.53743, -3.51460, -3.41330, -3.28337, -3.02773, -2.72553, -2.50182, -2.29513, -2.23588, -2.09952, -1.94152, -1.72839, -1.58400, -1.39716, -1.30223, -1.17631, -0.98683, -0.74146, -0.59540, -0.41715, -0.18344, -0.01021, 0.23455, 0.41954, 0.58571, 0.90904, 1.07972, 1.03987, 0.93674, 0.92481, 1.05265, 1.24922, 1.45900, 1.51316, 1.68391, 1.85163, 1.92962, 2.00464, 2.00498, 2.05171, 1.86382, 1.63855, 1.56469, 1.59046, 1.48803, 1.54706, 1.65299, 1.69941, 1.59736, 1.51565, 1.50678, 1.60305, 1.71399, 1.62100, 1.49447, 1.39025, 1.18988, 0.99863, 0.72649, 0.47713, 0.24888, -0.02917, -0.28333, -0.44758, -0.47559, -0.60078, -0.66571, -0.75690, -0.79556, -0.77042, -0.85641, -0.75483, -0.74120, -0.74368, -0.69901, -0.51435, -0.38966, -0.25238, +-0.84873, -0.85921, -0.80980, -0.81168, -0.82944, -0.91446, -0.96218, -1.03268, -1.00672, -0.96881, -0.89175, -0.73868, -0.64875, -0.59472, -0.60342, -0.64188, -0.71314, -0.66634, -0.49773, -0.45065, -0.49264, -0.44214, -0.46277, -0.49632, -0.40848, -0.39556, -0.38757, -0.28510, -0.09198, 0.22299, 0.50320, 0.66016, 0.84815, 0.99707, 1.16786, 1.33082, 1.55966, 1.62593, 1.54848, 1.45659, 1.42160, 1.33250, 1.06926, 0.83670, 0.66260, 0.58870, 0.44888, 0.21283, -0.01201, -0.14137, -0.29356, -0.66332, -0.99688, -1.04945, -1.12382, -1.31363, -1.46406, -1.59486, -1.62696, -1.62184, -1.66607, -1.60086, -1.48700, -1.44177, -1.37550, -1.36390, -1.24158, -1.26636, -1.21177, -1.09323, -0.93484, -0.78272, -0.66166, -0.56727, -0.51937, -0.38239, -0.26265, -0.16000, -0.10685, -0.10969, -0.21365, -0.32162, -0.30784, -0.33144, -0.42178, -0.42729, -0.50830, -0.65783, -0.65020, -0.61101, -0.57411, -0.54167, -0.54866, -0.62310, -0.67165, -0.71991, -0.65158, -0.79444, -0.95378, -1.18145, -1.27575, -1.29715, -1.38338, -1.48808, -1.46569, -1.32088, -1.28177, -1.25262, -1.22026, -1.18005, -1.28780, -1.47149, -1.54474, -1.47855, -1.32315, -1.30219, -1.43297, -1.45822, -1.41860, -1.51607, -1.50939, -1.37425, -1.17162, -0.91975, -0.80812, -0.78421, -0.66280, -0.68632, -0.55930, -0.46945, -0.34835, -0.44839, -0.64924, -0.87667, -1.11480, -1.34610, -1.51960, -1.61615, -1.74986, -1.82137, -1.95337, -2.09350, -2.23472, -2.30085, -2.30724, -2.33133, -2.30432, -2.23479, -2.20290, -2.16105, -2.10113, -2.27921, -2.38965, -2.53253, -2.63474, -2.54588, -2.42980, -2.44420, -2.36273, -2.24819, -1.88783, -1.53941, -1.26842, -1.16183, -1.05966, -0.90728, -0.81585, -0.76607, -0.63121, -0.37440, -0.28257, -0.16240, 0.04769, 0.33480, 0.54626, 0.67537, 0.77361, 0.87109, 1.13661, 1.36694, 1.49411, 1.76696, 2.13324, 2.32879, 2.43495, 2.55598, 2.71268, 2.88067, 3.06711, 3.21215, 3.45234, 3.52139, 3.58477, 3.57430, 3.59304, 3.49815, 3.39152, 3.32814, 3.32076, 3.24060, 3.10038, 3.00676, 2.87550, 2.79183, 2.71978, 2.59908, 2.42195, 2.27007, 2.22256, 2.17875, 2.18618, 2.14041, 1.93597, 1.65975, 1.49504, 1.30658, 1.11972, 0.92080, 0.74198, 0.69990, 0.70077, 0.61313, 0.46424, 0.19044, -0.03069, -0.21313, -0.38628, -0.55224, -0.62100, -0.58562, -0.58408, -0.56473, -0.45839, -0.29140, -0.32053, -0.47297, -0.63359, -0.78472, -0.85558, -0.98246, -1.04409, -1.07912, -1.05196, -1.07510, -1.38498, -1.70957, -1.85098, -2.07274, -2.24920, -2.30627, -2.36638, -2.48142, -2.67921, -2.91980, -3.04961, -3.17736, -3.30296, -3.39620, -3.47340, -3.59132, -3.86620, -4.06272, -4.15908, -4.15665, -4.18886, -4.23612, -4.41060, -4.55098, -4.55934, -4.52577, -4.47246, -4.43515, -4.36066, -4.38197, -4.32540, -4.14251, -4.09998, -4.18194, -4.09285, -3.95069, -3.79357, -3.56179, -3.44548, -3.33393, -3.18918, -3.07991, -2.96866, -2.88045, -2.79929, -2.72464, -2.84594, -2.98922, -3.15357, -3.20332, -3.27204, -3.34691, -3.42166, -3.42392, -3.44792, -3.61287, -3.68047, -3.70846, -3.74758, -3.87964, -4.08803, -4.26442, -4.34130, -4.32434, -4.36271, -4.41856, -4.33310, -4.32234, -4.43293, -4.41568, -4.36792, -4.28795, -4.14935, -4.02436, -3.84074, -3.68698, -3.69756, -3.63282, -3.56174, -3.36222, -3.30815, -3.26803, -3.23407, -3.06640, -2.79235, -2.47280, -2.23480, -2.12581, -1.94486, -1.87430, -1.75510, -1.58806, -1.45491, -1.39197, -1.25838, -0.94912, -0.68388, -0.55541, -0.39626, -0.20011, -0.04867, 0.20857, 0.39646, 0.56391, 0.82282, 0.96977, 0.95624, 0.97160, 0.96541, 1.12860, 1.22078, 1.36109, 1.37528, 1.50749, 1.68596, 1.77360, 1.83358, 1.89136, 1.89881, 1.72627, 1.59027, 1.54253, 1.57944, 1.59474, 1.65518, 1.73487, 1.77048, 1.81997, 1.76582, 1.66247, 1.69884, 1.79809, 1.73474, 1.67632, 1.57682, 1.35737, 1.10238, 0.80841, 0.53836, 0.37542, 0.03168, -0.27654, -0.61521, -0.72212, -0.80085, -0.80487, -0.81736, -0.83794, -0.88444, -1.01778, -1.06368, -1.10981, -1.07146, -1.01741, -0.86540, -0.68085, -0.52439, +-0.83168, -0.87787, -0.82972, -0.84146, -0.84870, -0.89103, -0.94266, -1.00388, -0.99850, -0.97753, -0.90826, -0.75529, -0.70611, -0.69481, -0.62717, -0.63042, -0.67502, -0.61533, -0.55184, -0.59575, -0.65618, -0.59812, -0.52605, -0.48500, -0.38253, -0.37616, -0.42775, -0.37654, -0.13262, 0.19882, 0.49689, 0.74032, 0.92660, 1.02075, 1.13832, 1.23850, 1.39009, 1.45424, 1.43285, 1.37204, 1.29174, 1.19760, 0.96284, 0.73389, 0.47386, 0.26387, 0.21229, 0.13770, -0.03078, -0.17683, -0.40114, -0.74406, -1.00416, -1.03711, -1.05042, -1.16372, -1.34331, -1.53099, -1.65179, -1.73163, -1.69948, -1.61090, -1.53613, -1.46331, -1.37974, -1.34786, -1.19594, -1.12714, -1.04661, -0.92716, -0.81897, -0.68077, -0.56338, -0.47257, -0.40233, -0.24051, -0.10751, -0.03560, 0.08230, 0.13605, 0.03445, 0.00022, 0.01916, -0.04181, -0.15116, -0.21573, -0.29154, -0.37440, -0.39405, -0.39268, -0.43747, -0.54067, -0.54104, -0.54326, -0.63331, -0.67174, -0.62344, -0.74541, -0.79334, -0.89364, -0.98005, -0.97223, -1.08700, -1.23523, -1.32429, -1.32094, -1.29716, -1.22930, -1.23756, -1.36833, -1.46973, -1.50543, -1.54365, -1.41326, -1.26268, -1.29408, -1.46348, -1.55231, -1.50134, -1.47020, -1.41036, -1.29578, -1.19570, -1.15026, -1.04332, -0.90649, -0.78581, -0.70865, -0.54265, -0.49770, -0.44061, -0.50044, -0.69334, -0.90132, -1.17447, -1.42196, -1.58455, -1.66919, -1.77895, -1.87488, -2.02652, -2.23590, -2.32028, -2.26127, -2.29776, -2.30625, -2.28932, -2.27848, -2.25126, -2.22887, -2.15250, -2.22172, -2.29775, -2.38831, -2.55689, -2.68504, -2.64621, -2.55638, -2.40000, -2.20418, -1.83089, -1.49949, -1.26135, -1.11106, -1.05733, -0.94178, -0.83918, -0.74085, -0.63355, -0.48518, -0.39207, -0.22020, 0.00996, 0.22512, 0.47081, 0.74685, 0.82667, 0.95598, 1.25646, 1.49058, 1.67463, 1.90477, 2.19894, 2.38539, 2.48212, 2.63448, 2.75705, 2.80716, 2.96604, 3.18293, 3.41235, 3.55185, 3.69219, 3.67726, 3.63244, 3.55604, 3.46106, 3.42374, 3.36776, 3.19803, 3.02190, 2.92560, 2.87020, 2.82683, 2.73733, 2.52053, 2.35769, 2.36573, 2.35463, 2.36214, 2.40791, 2.30871, 2.10444, 1.82866, 1.57300, 1.33214, 1.08289, 0.92299, 0.80483, 0.65872, 0.60529, 0.61700, 0.50811, 0.28522, 0.07240, -0.15978, -0.34792, -0.44387, -0.53417, -0.57473, -0.60095, -0.59496, -0.51422, -0.39225, -0.40119, -0.55093, -0.78702, -1.05893, -1.14748, -1.08940, -1.06364, -1.11291, -1.13315, -1.29676, -1.62029, -1.90943, -2.06383, -2.21356, -2.33751, -2.36915, -2.42300, -2.59795, -2.81971, -2.96463, -3.03843, -3.11548, -3.14291, -3.21878, -3.38596, -3.56876, -3.83503, -4.00347, -4.05360, -4.07475, -4.15098, -4.24391, -4.39748, -4.51902, -4.57329, -4.62918, -4.62065, -4.47552, -4.32469, -4.32686, -4.31751, -4.28572, -4.31865, -4.33175, -4.16686, -3.96952, -3.74625, -3.46281, -3.32983, -3.32323, -3.37807, -3.30685, -3.14845, -3.04332, -2.96165, -2.97404, -3.14479, -3.26731, -3.37350, -3.39685, -3.41151, -3.51587, -3.66621, -3.71472, -3.69536, -3.74120, -3.76713, -3.87814, -4.02060, -4.10125, -4.17530, -4.29934, -4.33458, -4.35657, -4.44705, -4.52226, -4.49833, -4.48458, -4.52854, -4.48876, -4.40524, -4.33589, -4.24460, -4.01877, -3.75592, -3.61917, -3.53319, -3.41411, -3.34044, -3.17496, -3.11336, -3.09314, -3.01529, -2.86354, -2.62571, -2.33201, -2.07766, -1.93415, -1.75557, -1.74037, -1.78457, -1.64414, -1.43706, -1.31131, -1.07334, -0.81812, -0.62153, -0.47897, -0.35867, -0.20752, -0.08925, 0.13113, 0.39341, 0.56519, 0.65092, 0.75945, 0.85311, 0.89630, 0.97410, 1.16111, 1.23680, 1.30814, 1.29362, 1.39727, 1.63873, 1.78210, 1.83707, 1.81780, 1.75984, 1.58486, 1.49774, 1.47161, 1.45032, 1.54057, 1.73415, 1.79301, 1.84012, 1.85424, 1.72839, 1.62184, 1.63166, 1.73561, 1.77794, 1.76154, 1.66726, 1.37837, 1.00064, 0.74643, 0.59304, 0.38415, 0.04392, -0.26813, -0.61975, -0.77878, -0.84463, -0.84317, -0.77889, -0.78254, -0.83680, -1.02498, -1.20323, -1.32656, -1.32064, -1.22224, -1.10390, -0.91596, -0.62536, +-0.76331, -0.88185, -0.89998, -0.93234, -0.89425, -0.86051, -0.87131, -0.91566, -0.94738, -0.88081, -0.83650, -0.75205, -0.66113, -0.61029, -0.57598, -0.69104, -0.71849, -0.68727, -0.67123, -0.64469, -0.68334, -0.67047, -0.63190, -0.60710, -0.52633, -0.57490, -0.56200, -0.34620, -0.05296, 0.17896, 0.34689, 0.60928, 0.86086, 0.97891, 1.10503, 1.18548, 1.22055, 1.21558, 1.19365, 1.16396, 1.02467, 0.95597, 0.69258, 0.40548, 0.16945, -0.00044, 0.00502, -0.04376, -0.14196, -0.30715, -0.57078, -0.70976, -0.88674, -0.98770, -1.04369, -1.12747, -1.25585, -1.45499, -1.58151, -1.55204, -1.48340, -1.51392, -1.59499, -1.53342, -1.36374, -1.25484, -1.14596, -1.01907, -0.95432, -0.83928, -0.78019, -0.64393, -0.57215, -0.39978, -0.29022, -0.18566, -0.00123, 0.17382, 0.30706, 0.27569, 0.17276, 0.18811, 0.16420, 0.20540, 0.10549, -0.03505, -0.13789, -0.19129, -0.22389, -0.31387, -0.47102, -0.53670, -0.52629, -0.48535, -0.58360, -0.59286, -0.54110, -0.62219, -0.67877, -0.68694, -0.79289, -0.80579, -1.01439, -1.16795, -1.36837, -1.37380, -1.29938, -1.25404, -1.25844, -1.38372, -1.49492, -1.55670, -1.64442, -1.52332, -1.44714, -1.33322, -1.39919, -1.48548, -1.47387, -1.42007, -1.33460, -1.29657, -1.30218, -1.23290, -1.07476, -0.89289, -0.87627, -0.78257, -0.58986, -0.51224, -0.57557, -0.63472, -0.85387, -1.02898, -1.35525, -1.59151, -1.78008, -1.78163, -1.80817, -1.95623, -2.09504, -2.20166, -2.24158, -2.25299, -2.38252, -2.36720, -2.38929, -2.24494, -2.15486, -2.18306, -2.21671, -2.33250, -2.38195, -2.36595, -2.48129, -2.55096, -2.53605, -2.45002, -2.36156, -2.16648, -1.79578, -1.46822, -1.39618, -1.27261, -1.28723, -1.15556, -1.02539, -0.82339, -0.73922, -0.62026, -0.45817, -0.29079, -0.10849, 0.12979, 0.41756, 0.70901, 0.79339, 1.04517, 1.33667, 1.71423, 2.02153, 2.20080, 2.36409, 2.43794, 2.53853, 2.71213, 2.75700, 2.83741, 3.00589, 3.21527, 3.30958, 3.39614, 3.58604, 3.67129, 3.53617, 3.43237, 3.33505, 3.34589, 3.25723, 3.08542, 2.89876, 2.84758, 2.91693, 2.84456, 2.69333, 2.52997, 2.46493, 2.50587, 2.41826, 2.43784, 2.38261, 2.29637, 2.21531, 2.06670, 1.81021, 1.45661, 1.10699, 0.91976, 0.77524, 0.65972, 0.64002, 0.63749, 0.40548, 0.13301, -0.05051, -0.17774, -0.35336, -0.41492, -0.52177, -0.61781, -0.67863, -0.67475, -0.68815, -0.66544, -0.60104, -0.73688, -0.99338, -1.19609, -1.22107, -1.11924, -1.16127, -1.24034, -1.36194, -1.57595, -1.73378, -1.92528, -2.12414, -2.31914, -2.45617, -2.48093, -2.58368, -2.74504, -2.86333, -2.94259, -3.08285, -3.22580, -3.17007, -3.12814, -3.33927, -3.60781, -3.86771, -4.01776, -4.05429, -4.11330, -4.22866, -4.35556, -4.36521, -4.44352, -4.59206, -4.67876, -4.68490, -4.57153, -4.48541, -4.37791, -4.34111, -4.40491, -4.37410, -4.33058, -4.16745, -4.01238, -3.80832, -3.54239, -3.47100, -3.48331, -3.50435, -3.41399, -3.28027, -3.24930, -3.18333, -3.21668, -3.40949, -3.60041, -3.73290, -3.79616, -3.75946, -3.83463, -3.92893, -3.98014, -3.83252, -3.77025, -3.84402, -3.98294, -4.09969, -4.17265, -4.22573, -4.27907, -4.28848, -4.37613, -4.36799, -4.42142, -4.49945, -4.59823, -4.68088, -4.63898, -4.59998, -4.54900, -4.32359, -4.01014, -3.76145, -3.71633, -3.55334, -3.32214, -3.19607, -3.14754, -3.09858, -3.08810, -2.90507, -2.73926, -2.49877, -2.30601, -2.03214, -1.86734, -1.73780, -1.62667, -1.58380, -1.50461, -1.42382, -1.30875, -1.00137, -0.82503, -0.53783, -0.38508, -0.34592, -0.29943, -0.26411, -0.02764, 0.28984, 0.48305, 0.63557, 0.73935, 0.85468, 0.80916, 0.86237, 1.06953, 1.21951, 1.22363, 1.25554, 1.35146, 1.65214, 1.80362, 1.85470, 1.70535, 1.64444, 1.51878, 1.44413, 1.45840, 1.51549, 1.61844, 1.73363, 1.72394, 1.77257, 1.67410, 1.64644, 1.61321, 1.58222, 1.60787, 1.64314, 1.66594, 1.56204, 1.21425, 0.93969, 0.76848, 0.64371, 0.28721, -0.09627, -0.35439, -0.57001, -0.81037, -0.90236, -0.97585, -0.89965, -0.92966, -0.91276, -1.05248, -1.19210, -1.32721, -1.43590, -1.35532, -1.15279, -0.97035, -0.76917, +-0.88997, -1.03693, -1.00401, -0.98108, -0.90222, -0.81396, -0.75206, -0.74450, -0.76222, -0.72087, -0.63865, -0.49384, -0.40650, -0.37430, -0.38868, -0.54572, -0.67481, -0.72379, -0.71340, -0.69728, -0.71018, -0.70760, -0.66428, -0.62358, -0.64780, -0.74629, -0.66491, -0.37428, -0.11785, 0.04262, 0.24015, 0.49355, 0.65718, 0.78179, 1.02208, 1.13609, 1.08433, 0.94640, 0.86771, 0.84187, 0.71095, 0.60269, 0.34662, 0.13690, -0.07529, -0.21660, -0.17674, -0.18284, -0.26796, -0.45457, -0.64883, -0.73332, -0.86303, -0.95808, -0.98432, -0.96702, -1.09412, -1.31269, -1.38859, -1.31161, -1.32504, -1.50194, -1.56906, -1.48765, -1.34654, -1.23689, -1.06685, -0.89148, -0.82699, -0.75736, -0.67444, -0.50880, -0.42117, -0.25645, -0.13046, 0.03567, 0.22259, 0.39244, 0.52685, 0.51391, 0.41688, 0.34209, 0.30441, 0.28942, 0.16954, 0.03233, -0.08269, -0.07123, -0.15364, -0.35530, -0.51479, -0.53229, -0.54449, -0.54228, -0.49896, -0.41896, -0.42483, -0.59687, -0.63684, -0.59595, -0.68640, -0.77362, -0.99632, -1.13421, -1.33838, -1.36682, -1.30160, -1.19737, -1.18957, -1.32563, -1.43864, -1.51315, -1.63525, -1.66587, -1.59333, -1.46479, -1.47259, -1.48713, -1.47474, -1.35230, -1.31768, -1.42049, -1.41743, -1.26238, -1.05950, -0.94844, -0.91939, -0.78415, -0.64182, -0.64228, -0.66574, -0.68318, -0.88463, -1.10931, -1.43305, -1.65828, -1.83195, -1.81418, -1.80678, -1.82600, -1.90377, -2.01537, -2.08162, -2.16125, -2.30946, -2.42190, -2.46867, -2.34331, -2.26023, -2.26262, -2.32275, -2.36580, -2.38814, -2.38295, -2.35488, -2.28339, -2.25625, -2.32348, -2.29452, -2.07203, -1.77100, -1.60032, -1.57253, -1.45785, -1.47665, -1.37680, -1.20752, -0.94270, -0.80636, -0.66444, -0.50152, -0.25799, -0.07752, 0.10302, 0.38121, 0.67759, 0.85812, 1.08794, 1.41105, 1.81485, 2.10397, 2.28846, 2.41938, 2.54986, 2.69103, 2.75511, 2.76699, 2.90304, 3.07962, 3.18499, 3.24532, 3.38132, 3.55785, 3.56722, 3.44632, 3.35986, 3.27421, 3.24874, 3.17938, 3.08675, 2.96244, 2.94183, 2.99218, 2.95599, 2.84017, 2.65797, 2.57353, 2.57084, 2.48859, 2.40089, 2.28857, 2.19728, 2.12405, 2.10190, 1.93840, 1.64887, 1.29135, 0.91896, 0.68595, 0.62742, 0.64169, 0.54036, 0.24890, 0.03757, -0.12729, -0.29141, -0.42310, -0.42600, -0.49988, -0.63459, -0.72769, -0.72467, -0.79625, -0.84811, -0.83714, -0.91951, -1.07463, -1.25178, -1.28999, -1.23387, -1.30310, -1.48364, -1.66647, -1.85208, -1.95521, -2.06479, -2.23757, -2.37206, -2.43772, -2.52683, -2.64769, -2.72078, -2.75454, -2.86139, -3.05576, -3.15823, -3.08862, -3.10474, -3.30501, -3.51226, -3.74900, -3.94311, -4.04902, -4.11999, -4.22008, -4.34367, -4.38631, -4.45205, -4.55812, -4.68110, -4.74950, -4.69673, -4.61838, -4.48791, -4.44182, -4.48784, -4.49277, -4.47749, -4.33755, -4.14999, -3.87170, -3.67495, -3.66032, -3.61609, -3.56030, -3.48100, -3.42369, -3.37313, -3.31794, -3.45240, -3.70170, -3.87259, -4.02597, -4.13516, -4.12602, -4.12789, -4.11843, -4.10576, -3.95335, -3.86639, -3.88421, -4.02769, -4.14603, -4.18340, -4.15282, -4.17189, -4.24310, -4.31310, -4.31580, -4.35421, -4.43336, -4.55327, -4.58777, -4.60779, -4.67253, -4.60429, -4.29723, -3.97509, -3.77349, -3.64435, -3.41661, -3.22997, -3.17639, -3.12499, -3.06119, -3.06141, -2.92644, -2.73224, -2.45153, -2.25987, -2.03161, -1.88709, -1.67962, -1.48375, -1.40069, -1.35319, -1.33692, -1.29618, -1.12540, -0.93623, -0.65589, -0.50890, -0.46238, -0.43416, -0.31775, -0.07287, 0.18349, 0.43472, 0.69753, 0.82416, 0.86312, 0.83946, 0.89156, 1.01879, 1.10056, 1.17004, 1.28374, 1.40135, 1.63191, 1.76202, 1.79427, 1.62545, 1.54567, 1.44577, 1.50313, 1.55740, 1.59376, 1.67489, 1.75045, 1.73638, 1.66506, 1.55850, 1.53001, 1.50938, 1.49256, 1.48069, 1.59426, 1.63586, 1.46699, 1.17718, 1.01497, 0.87375, 0.63655, 0.26447, -0.07321, -0.37536, -0.68582, -0.91190, -0.98105, -1.06070, -1.05204, -1.07032, -0.98135, -1.00452, -1.08532, -1.25134, -1.34564, -1.32401, -1.20163, -1.06152, -0.92727, +-1.08639, -1.10952, -1.06220, -1.03437, -0.86552, -0.69372, -0.63242, -0.62584, -0.56493, -0.55431, -0.55134, -0.36281, -0.22667, -0.20148, -0.25014, -0.34430, -0.47171, -0.56317, -0.56584, -0.59015, -0.57952, -0.63034, -0.72980, -0.74128, -0.80681, -0.84361, -0.78114, -0.59568, -0.31605, -0.12620, 0.18991, 0.38713, 0.43779, 0.68785, 0.97600, 1.02453, 0.95232, 0.75704, 0.58073, 0.47735, 0.41172, 0.27229, -0.04888, -0.22414, -0.37159, -0.49033, -0.44816, -0.37140, -0.37107, -0.52694, -0.62618, -0.67652, -0.71522, -0.80078, -0.91916, -0.89371, -0.96572, -1.08622, -1.14577, -1.21860, -1.27092, -1.48739, -1.48489, -1.44046, -1.37843, -1.14081, -0.91391, -0.81320, -0.70616, -0.61467, -0.51417, -0.39152, -0.21506, -0.04169, 0.02333, 0.18933, 0.41507, 0.55734, 0.66807, 0.73243, 0.74918, 0.65427, 0.60198, 0.46145, 0.30073, 0.12500, -0.11846, -0.15579, -0.22566, -0.38147, -0.46099, -0.57934, -0.56766, -0.53511, -0.34263, -0.23023, -0.33832, -0.44548, -0.44317, -0.50047, -0.55801, -0.64558, -0.83042, -1.02154, -1.15862, -1.18177, -1.22790, -1.21085, -1.18993, -1.35352, -1.47758, -1.51597, -1.52636, -1.58718, -1.49689, -1.40596, -1.37433, -1.36218, -1.45052, -1.41256, -1.40641, -1.52342, -1.46116, -1.40543, -1.14844, -1.02994, -0.95178, -0.82648, -0.81625, -0.76797, -0.66629, -0.73831, -0.87629, -1.06956, -1.33557, -1.61681, -1.73734, -1.67682, -1.70653, -1.71949, -1.69288, -1.80293, -1.92894, -2.08232, -2.16879, -2.32729, -2.38874, -2.32591, -2.25206, -2.21953, -2.30860, -2.38240, -2.35526, -2.29717, -2.11362, -2.09931, -2.06477, -2.17789, -2.17410, -1.96961, -1.84898, -1.73766, -1.61874, -1.60292, -1.60578, -1.46954, -1.23841, -1.02693, -0.84626, -0.64638, -0.53918, -0.36181, -0.12046, 0.04245, 0.27843, 0.55973, 0.90469, 1.19241, 1.56429, 1.94552, 2.18440, 2.36157, 2.41961, 2.48235, 2.68042, 2.72407, 2.77259, 2.78913, 2.92078, 3.02124, 3.11705, 3.32195, 3.41264, 3.42210, 3.47970, 3.36641, 3.27729, 3.26275, 3.25272, 3.16927, 3.12085, 3.19413, 3.16780, 3.00131, 2.92305, 2.74161, 2.60132, 2.52778, 2.52198, 2.44224, 2.35740, 2.26317, 2.15520, 2.18918, 2.03385, 1.67509, 1.33965, 0.89699, 0.65324, 0.50923, 0.45629, 0.36456, 0.12476, 0.01243, -0.20591, -0.38069, -0.34163, -0.35783, -0.45975, -0.57694, -0.64598, -0.69439, -0.80128, -0.84871, -0.95241, -1.15174, -1.24033, -1.37312, -1.45257, -1.47671, -1.50177, -1.66224, -1.83184, -1.95921, -2.03738, -2.09605, -2.29757, -2.51486, -2.52681, -2.58955, -2.62233, -2.67521, -2.74021, -2.79084, -2.93831, -2.95485, -2.97472, -3.08005, -3.12591, -3.28384, -3.55420, -3.74180, -3.88988, -4.03855, -4.16637, -4.22153, -4.33581, -4.52688, -4.63018, -4.71598, -4.80640, -4.82028, -4.70931, -4.51462, -4.43281, -4.42847, -4.47121, -4.48127, -4.43052, -4.35587, -4.07105, -3.85760, -3.75922, -3.69398, -3.70339, -3.56626, -3.51313, -3.42179, -3.47114, -3.73693, -3.87290, -3.98107, -4.17688, -4.25626, -4.24400, -4.22452, -4.20100, -4.08335, -3.96107, -3.99135, -4.03546, -4.12967, -4.24218, -4.24293, -4.08493, -3.99546, -4.07477, -4.10810, -4.14014, -4.15393, -4.25505, -4.47029, -4.51180, -4.52126, -4.55294, -4.47319, -4.30348, -3.96228, -3.73712, -3.47772, -3.24513, -3.16727, -3.06789, -3.00116, -3.02813, -3.00677, -2.89033, -2.68208, -2.43697, -2.14043, -1.89023, -1.84204, -1.67910, -1.41508, -1.33009, -1.32573, -1.32164, -1.27566, -1.20229, -0.99338, -0.75417, -0.58395, -0.52422, -0.57082, -0.44705, -0.13964, 0.15441, 0.46622, 0.62048, 0.79432, 0.85804, 0.93927, 1.00695, 0.99963, 1.12222, 1.30609, 1.38506, 1.54012, 1.72562, 1.80659, 1.70512, 1.56571, 1.50226, 1.36277, 1.40581, 1.50970, 1.51021, 1.55062, 1.62568, 1.70431, 1.60748, 1.54892, 1.51603, 1.51906, 1.51660, 1.41371, 1.46437, 1.54114, 1.41239, 1.24413, 1.00347, 0.87563, 0.59134, 0.24324, -0.05949, -0.49100, -0.81107, -0.93344, -1.06743, -1.08418, -1.03117, -0.99860, -0.95948, -0.88797, -0.88554, -1.12011, -1.32185, -1.34628, -1.33268, -1.27072, -1.18937, +-1.16951, -1.14467, -1.09704, -1.04036, -0.82211, -0.61164, -0.57832, -0.58129, -0.56892, -0.59755, -0.52636, -0.30278, -0.13295, -0.02558, -0.08713, -0.19281, -0.27488, -0.37879, -0.45603, -0.55656, -0.63515, -0.71601, -0.78420, -0.84825, -1.00435, -1.04994, -0.95257, -0.76961, -0.45532, -0.17111, 0.10844, 0.26345, 0.38249, 0.63082, 0.84482, 0.86014, 0.75380, 0.60063, 0.41179, 0.26199, 0.11317, -0.12417, -0.33442, -0.40566, -0.52271, -0.59263, -0.60299, -0.59712, -0.56430, -0.67816, -0.72719, -0.70078, -0.67174, -0.74069, -0.85305, -0.85735, -0.94204, -1.02764, -1.07148, -1.17722, -1.23458, -1.35306, -1.43703, -1.48316, -1.33675, -1.05153, -0.88847, -0.80434, -0.69127, -0.54378, -0.45068, -0.35302, -0.17783, -0.05605, 0.10036, 0.38669, 0.60963, 0.76751, 0.81818, 0.78875, 0.88579, 0.88834, 0.80614, 0.55669, 0.25943, -0.02035, -0.23940, -0.24717, -0.34141, -0.48447, -0.46052, -0.52081, -0.51771, -0.38830, -0.24103, -0.21587, -0.23585, -0.18216, -0.18818, -0.27730, -0.40013, -0.47833, -0.60479, -0.76445, -0.88569, -1.03415, -1.13100, -1.11141, -1.18222, -1.37172, -1.49252, -1.57842, -1.46287, -1.41105, -1.37061, -1.33721, -1.34147, -1.39679, -1.50598, -1.49166, -1.53970, -1.69398, -1.62947, -1.54344, -1.29624, -1.09363, -1.08714, -1.13241, -1.09577, -0.92268, -0.83538, -0.87896, -0.96871, -1.06291, -1.24246, -1.47582, -1.58032, -1.62693, -1.67301, -1.58877, -1.49836, -1.52614, -1.65061, -1.97469, -2.10544, -2.20623, -2.27482, -2.21844, -2.17433, -2.18590, -2.17975, -2.17028, -2.17473, -2.18176, -2.00232, -1.95938, -1.94312, -1.91051, -1.92093, -1.93371, -1.91373, -1.75251, -1.63504, -1.60229, -1.59060, -1.41617, -1.17191, -0.98120, -0.83119, -0.77176, -0.68878, -0.40610, -0.07855, 0.11806, 0.30778, 0.44476, 0.80831, 1.22260, 1.59634, 1.95141, 2.15109, 2.22076, 2.26581, 2.38791, 2.57605, 2.53808, 2.52789, 2.51880, 2.60069, 2.78465, 2.88759, 2.95135, 3.06699, 3.26900, 3.43052, 3.40602, 3.33219, 3.32699, 3.31365, 3.23705, 3.27376, 3.32644, 3.26244, 3.11989, 3.04610, 2.89098, 2.78369, 2.60933, 2.53722, 2.53127, 2.49509, 2.37783, 2.19239, 2.07967, 1.89946, 1.60060, 1.28389, 0.84262, 0.57629, 0.39810, 0.25368, 0.22946, 0.10995, -0.07406, -0.28566, -0.32741, -0.26867, -0.29168, -0.43676, -0.57326, -0.60923, -0.64351, -0.69370, -0.85893, -1.13808, -1.34917, -1.39304, -1.49372, -1.57431, -1.70190, -1.77756, -1.85224, -1.96425, -2.04481, -2.11635, -2.27931, -2.52533, -2.69181, -2.66648, -2.74142, -2.77531, -2.78522, -2.81432, -2.75961, -2.76361, -2.84838, -2.94878, -2.97963, -3.01350, -3.16475, -3.38381, -3.54600, -3.70630, -3.93779, -4.07811, -4.17156, -4.35508, -4.49996, -4.57197, -4.61941, -4.63995, -4.74802, -4.78729, -4.60207, -4.47931, -4.44900, -4.47248, -4.51015, -4.52173, -4.46315, -4.23691, -4.06939, -3.93605, -3.81767, -3.80150, -3.64211, -3.53096, -3.57523, -3.79514, -4.01839, -4.05872, -4.08676, -4.14475, -4.20594, -4.21530, -4.23504, -4.19046, -4.09402, -4.10526, -4.12719, -4.10648, -4.17655, -4.21998, -4.19993, -4.09780, -3.97402, -4.00712, -4.04505, -4.07006, -4.13455, -4.29753, -4.46105, -4.44585, -4.45948, -4.47546, -4.37879, -4.25851, -3.97722, -3.70100, -3.48667, -3.30101, -3.11087, -2.94429, -2.95455, -2.97706, -2.95328, -2.79172, -2.57568, -2.32897, -1.97962, -1.77284, -1.72057, -1.54750, -1.34144, -1.24908, -1.29272, -1.40200, -1.33145, -1.23535, -1.08701, -0.90980, -0.76422, -0.70421, -0.66358, -0.46239, -0.17470, 0.08244, 0.39033, 0.50808, 0.65400, 0.86519, 1.00057, 1.04218, 1.07212, 1.24650, 1.40131, 1.54502, 1.69754, 1.84685, 1.85698, 1.69311, 1.53083, 1.35882, 1.24549, 1.34996, 1.41103, 1.40628, 1.42649, 1.40134, 1.48744, 1.45782, 1.41600, 1.42672, 1.44465, 1.42107, 1.36126, 1.42219, 1.43566, 1.23699, 1.10672, 0.93607, 0.80704, 0.59584, 0.19587, -0.22019, -0.59837, -0.77245, -0.89467, -0.99478, -0.93860, -0.79096, -0.75270, -0.76927, -0.71389, -0.80843, -1.05491, -1.17409, -1.21219, -1.25634, -1.28516, -1.38617, +-1.16180, -1.24513, -1.21771, -1.14247, -0.94892, -0.72037, -0.71636, -0.67006, -0.54590, -0.52607, -0.44332, -0.30025, -0.22677, -0.06148, -0.02229, -0.08310, -0.21931, -0.40628, -0.53585, -0.75108, -0.86539, -0.84264, -0.83278, -0.92006, -1.07101, -1.05465, -0.87911, -0.72386, -0.50209, -0.25455, -0.06206, 0.16792, 0.33740, 0.37982, 0.48443, 0.49797, 0.34457, 0.30690, 0.20745, 0.11207, 0.02022, -0.19382, -0.32524, -0.38752, -0.57720, -0.67301, -0.67524, -0.65449, -0.65916, -0.82527, -0.82061, -0.76278, -0.69069, -0.65452, -0.76832, -0.88590, -0.98579, -0.97765, -0.96124, -1.06812, -1.15721, -1.23507, -1.39419, -1.36217, -1.15045, -1.06276, -1.02264, -0.90304, -0.79319, -0.57658, -0.49891, -0.42456, -0.20199, -0.04184, 0.15706, 0.43658, 0.56767, 0.71447, 0.79534, 0.77038, 0.87292, 0.85163, 0.81504, 0.55735, 0.18807, -0.02454, -0.17554, -0.21924, -0.32651, -0.38304, -0.29743, -0.34238, -0.43083, -0.31635, -0.24058, -0.12815, -0.01019, 0.02862, 0.00265, -0.05351, -0.27140, -0.33800, -0.41363, -0.51987, -0.56610, -0.74299, -0.91219, -0.96406, -1.16709, -1.40367, -1.44674, -1.46155, -1.30840, -1.32675, -1.33740, -1.35645, -1.42989, -1.41544, -1.50908, -1.57432, -1.63657, -1.70032, -1.61499, -1.50779, -1.38999, -1.24706, -1.34007, -1.35970, -1.18784, -1.07982, -1.11777, -1.12294, -1.22205, -1.23394, -1.33347, -1.51594, -1.55088, -1.56182, -1.63316, -1.57412, -1.51136, -1.51202, -1.50234, -1.74406, -1.89191, -2.06898, -2.13160, -2.04329, -2.03346, -1.95009, -1.86509, -1.88706, -1.95702, -1.94846, -1.78370, -1.71970, -1.80693, -1.71078, -1.70142, -1.74424, -1.69038, -1.62154, -1.62847, -1.53999, -1.54591, -1.39671, -1.16044, -0.97373, -0.78681, -0.70378, -0.62657, -0.34349, -0.05815, 0.05847, 0.24513, 0.38333, 0.73286, 1.08800, 1.41512, 1.77857, 1.96155, 2.09253, 2.20352, 2.31529, 2.43053, 2.40979, 2.39990, 2.43572, 2.43162, 2.56573, 2.59870, 2.59717, 2.83009, 3.08608, 3.18172, 3.25220, 3.19960, 3.19583, 3.18249, 3.08795, 3.22141, 3.38889, 3.39705, 3.30205, 3.18987, 2.99464, 2.97370, 2.86625, 2.76352, 2.65704, 2.53163, 2.36195, 2.06900, 1.91958, 1.79932, 1.51726, 1.17456, 0.88320, 0.72745, 0.58578, 0.31209, 0.22850, 0.13925, -0.05389, -0.15606, -0.21602, -0.35534, -0.38754, -0.54363, -0.70531, -0.69254, -0.71920, -0.71295, -0.87987, -1.24856, -1.51771, -1.62111, -1.78908, -1.84806, -1.89827, -1.90497, -1.97858, -2.10472, -2.13990, -2.25546, -2.43865, -2.59232, -2.69574, -2.68383, -2.71955, -2.71502, -2.69435, -2.77432, -2.75946, -2.73883, -2.87259, -2.89115, -2.88409, -3.11736, -3.30723, -3.46486, -3.61978, -3.70350, -3.93918, -4.05272, -4.07248, -4.22160, -4.34054, -4.45971, -4.58948, -4.61807, -4.73210, -4.83201, -4.74673, -4.68403, -4.60709, -4.60690, -4.53504, -4.38504, -4.32480, -4.24275, -4.11125, -3.90305, -3.72559, -3.75668, -3.74081, -3.68515, -3.82485, -3.99018, -4.12976, -4.26655, -4.26291, -4.19384, -4.29126, -4.30297, -4.37234, -4.31534, -4.16990, -4.20401, -4.19985, -4.14715, -4.24931, -4.25341, -4.15177, -4.04311, -3.97031, -4.06666, -4.06381, -4.06261, -4.13497, -4.19055, -4.29780, -4.32257, -4.32827, -4.26261, -4.15230, -4.10894, -4.00461, -3.82477, -3.70499, -3.40434, -3.04779, -2.93212, -2.99315, -2.95540, -2.95665, -2.73663, -2.51732, -2.26367, -1.84769, -1.63439, -1.60809, -1.50145, -1.41915, -1.36132, -1.37186, -1.44491, -1.32043, -1.26371, -1.14787, -1.01823, -0.88762, -0.65904, -0.49823, -0.34240, -0.13004, 0.16787, 0.49407, 0.59129, 0.61685, 0.82973, 0.94490, 1.06971, 1.17941, 1.21970, 1.25570, 1.47968, 1.59826, 1.73570, 1.74133, 1.59964, 1.49962, 1.35686, 1.24309, 1.29464, 1.24678, 1.20070, 1.29789, 1.33784, 1.41104, 1.29333, 1.22790, 1.26496, 1.28040, 1.38898, 1.41200, 1.40522, 1.32710, 1.13169, 1.02490, 0.91766, 0.72353, 0.54413, 0.12586, -0.23207, -0.43692, -0.60641, -0.82316, -0.86369, -0.82791, -0.68729, -0.67473, -0.74134, -0.66139, -0.71385, -0.95307, -1.04017, -1.07476, -1.17426, -1.22118, -1.33214, +-1.19125, -1.26607, -1.25281, -1.18841, -1.01109, -0.77772, -0.69075, -0.60340, -0.46571, -0.38642, -0.36146, -0.32111, -0.23852, -0.07586, -0.04466, -0.13156, -0.27540, -0.44975, -0.62135, -0.86640, -1.01477, -1.03633, -0.98399, -0.97002, -1.05419, -0.99590, -0.85049, -0.76116, -0.59102, -0.42241, -0.27987, -0.08869, -0.00685, 0.00024, 0.11764, 0.14157, -0.00258, 0.01653, 0.07183, 0.06210, -0.02468, -0.16730, -0.27964, -0.38656, -0.52586, -0.62863, -0.67258, -0.64274, -0.60631, -0.68721, -0.66502, -0.60255, -0.57632, -0.64948, -0.80038, -0.90611, -0.96857, -0.89110, -0.85066, -0.95613, -0.98283, -1.03979, -1.17233, -1.10955, -0.99723, -1.00219, -0.99491, -0.87635, -0.72353, -0.49258, -0.36787, -0.30237, -0.17238, -0.02840, 0.13107, 0.27112, 0.39888, 0.59235, 0.67201, 0.66924, 0.79110, 0.82974, 0.83284, 0.63631, 0.28231, 0.01568, -0.14814, -0.17464, -0.24935, -0.26032, -0.22087, -0.34626, -0.41811, -0.28511, -0.13789, 0.07857, 0.15343, 0.16011, 0.16817, 0.09932, -0.12420, -0.20439, -0.21783, -0.25533, -0.33746, -0.54354, -0.73100, -0.87794, -1.03809, -1.17146, -1.20090, -1.20583, -1.10913, -1.15163, -1.20014, -1.24041, -1.32495, -1.37339, -1.51585, -1.58474, -1.60713, -1.60688, -1.53297, -1.50551, -1.42410, -1.32894, -1.42937, -1.35981, -1.20649, -1.16930, -1.21044, -1.23933, -1.32674, -1.32189, -1.35975, -1.48503, -1.56540, -1.58950, -1.64586, -1.68175, -1.59587, -1.48618, -1.39872, -1.53981, -1.67762, -1.81914, -1.88439, -1.79599, -1.75462, -1.70098, -1.69279, -1.73023, -1.77811, -1.71103, -1.53492, -1.55504, -1.68520, -1.58298, -1.52971, -1.48942, -1.48530, -1.51967, -1.53100, -1.44260, -1.43649, -1.32584, -1.07251, -0.79704, -0.60196, -0.51292, -0.40939, -0.24676, -0.04686, 0.07968, 0.24290, 0.37993, 0.69820, 1.06745, 1.36874, 1.71056, 1.92442, 2.03281, 2.10362, 2.21905, 2.35905, 2.40707, 2.42969, 2.43576, 2.42263, 2.51718, 2.50221, 2.51809, 2.69938, 2.88007, 2.99451, 3.07595, 3.05766, 3.07324, 3.09568, 3.08415, 3.20765, 3.34939, 3.45337, 3.36152, 3.25512, 3.16081, 3.16340, 3.06436, 2.93044, 2.78600, 2.55954, 2.29114, 1.97664, 1.80907, 1.68228, 1.41956, 1.11612, 0.94033, 0.87093, 0.70018, 0.39003, 0.28682, 0.18544, 0.04973, -0.08783, -0.29642, -0.48977, -0.52507, -0.64196, -0.76777, -0.72445, -0.68325, -0.73627, -1.00798, -1.36661, -1.69827, -1.84662, -1.93698, -1.97468, -1.98923, -1.94684, -1.96253, -2.04875, -2.08513, -2.18540, -2.37011, -2.53110, -2.57813, -2.49427, -2.46950, -2.44631, -2.50249, -2.65775, -2.66738, -2.69368, -2.82533, -2.85290, -2.92990, -3.19153, -3.37719, -3.52551, -3.66928, -3.69816, -3.82661, -3.94428, -4.02959, -4.16220, -4.31566, -4.49379, -4.60157, -4.68796, -4.86871, -4.99570, -4.88670, -4.75047, -4.64851, -4.60947, -4.46009, -4.28641, -4.23266, -4.17202, -4.05359, -3.84762, -3.72034, -3.83565, -3.87854, -3.86901, -3.96568, -4.04890, -4.19574, -4.31898, -4.27856, -4.22810, -4.34063, -4.34656, -4.35602, -4.28588, -4.20634, -4.23972, -4.22016, -4.18150, -4.19602, -4.13951, -4.04454, -3.94164, -3.87313, -3.91946, -3.88315, -3.83246, -3.86984, -3.93558, -4.03908, -4.03612, -4.00449, -3.93073, -3.90853, -3.99300, -3.96043, -3.86293, -3.75359, -3.39826, -3.06769, -2.91589, -2.90282, -2.85867, -2.85779, -2.66459, -2.42357, -2.16231, -1.85927, -1.72294, -1.72476, -1.69726, -1.54870, -1.40040, -1.42468, -1.48817, -1.33130, -1.19937, -1.08677, -0.95556, -0.79772, -0.57354, -0.39410, -0.23055, -0.02785, 0.30287, 0.62410, 0.67491, 0.69538, 0.86258, 0.94226, 1.05786, 1.06791, 1.04452, 1.10292, 1.34106, 1.48790, 1.62241, 1.70247, 1.65454, 1.52453, 1.37076, 1.26624, 1.21301, 1.17563, 1.20986, 1.33032, 1.40859, 1.47031, 1.37659, 1.27123, 1.29319, 1.33810, 1.40992, 1.39229, 1.37954, 1.30642, 1.14729, 1.03811, 0.86185, 0.67273, 0.54714, 0.20354, -0.03675, -0.23338, -0.44275, -0.63300, -0.68314, -0.70194, -0.67414, -0.68576, -0.70297, -0.63136, -0.66759, -0.86631, -1.02527, -1.02455, -1.03346, -1.10226, -1.20327, +-1.25584, -1.17774, -1.16142, -1.10523, -0.97104, -0.74726, -0.56904, -0.52905, -0.44022, -0.24574, -0.22944, -0.23926, -0.16884, -0.13560, -0.15800, -0.33229, -0.56656, -0.72917, -0.90925, -1.09297, -1.19374, -1.29753, -1.25917, -1.15057, -1.18673, -1.09958, -0.93724, -0.87901, -0.77733, -0.68710, -0.61504, -0.55596, -0.56411, -0.43757, -0.25058, -0.16438, -0.22933, -0.13648, 0.04196, -0.01377, -0.16866, -0.17166, -0.20067, -0.30218, -0.38338, -0.56366, -0.65006, -0.64137, -0.62528, -0.60005, -0.55585, -0.50991, -0.53735, -0.75853, -0.93740, -0.95719, -0.96345, -0.85958, -0.77573, -0.80585, -0.75259, -0.73709, -0.82823, -0.84294, -0.91278, -0.89136, -0.87658, -0.74822, -0.52462, -0.29136, -0.11215, -0.12695, -0.13677, 0.03974, 0.18778, 0.17217, 0.26722, 0.38438, 0.48412, 0.56357, 0.65196, 0.69170, 0.69691, 0.57258, 0.33102, 0.04919, -0.15553, -0.17736, -0.26480, -0.29459, -0.28936, -0.39756, -0.44426, -0.26530, -0.02074, 0.23078, 0.21520, 0.29221, 0.30850, 0.18054, -0.01967, -0.11564, -0.05997, -0.12614, -0.30402, -0.43357, -0.52458, -0.70627, -0.77066, -0.85669, -0.88317, -0.89646, -0.97054, -1.11331, -1.18184, -1.20340, -1.21570, -1.32395, -1.56845, -1.63760, -1.62683, -1.58365, -1.49488, -1.46231, -1.44948, -1.39601, -1.47543, -1.36825, -1.30200, -1.22874, -1.21995, -1.25509, -1.26391, -1.23985, -1.22746, -1.42254, -1.66217, -1.67748, -1.59863, -1.63276, -1.51469, -1.45019, -1.38254, -1.42227, -1.56930, -1.71382, -1.79460, -1.75295, -1.65993, -1.62414, -1.73173, -1.76262, -1.78829, -1.69752, -1.47712, -1.45306, -1.58587, -1.48740, -1.43716, -1.39052, -1.50858, -1.54357, -1.48268, -1.40478, -1.32809, -1.20306, -0.91392, -0.63672, -0.51162, -0.35469, -0.10645, -0.01278, 0.08582, 0.11623, 0.22865, 0.42931, 0.70990, 0.99802, 1.23488, 1.51245, 1.79726, 1.95350, 1.96153, 2.06555, 2.18825, 2.25230, 2.33115, 2.43466, 2.45697, 2.52038, 2.47034, 2.49834, 2.56407, 2.71884, 2.89621, 2.91915, 2.94721, 3.02305, 3.16449, 3.23985, 3.22341, 3.25625, 3.48687, 3.45241, 3.40142, 3.33926, 3.26503, 3.15292, 2.96077, 2.71499, 2.40054, 2.04306, 1.75260, 1.64196, 1.50904, 1.28490, 1.03363, 0.88074, 0.81959, 0.68193, 0.38648, 0.26589, 0.14480, 0.02465, -0.22410, -0.51510, -0.66241, -0.73858, -0.77586, -0.77926, -0.66284, -0.58283, -0.83024, -1.22418, -1.40893, -1.64920, -1.76788, -1.85545, -1.99265, -1.99017, -1.90968, -1.92169, -1.98506, -2.07813, -2.19080, -2.32467, -2.49646, -2.47819, -2.31475, -2.28836, -2.26949, -2.29785, -2.43424, -2.47211, -2.57764, -2.76988, -2.90688, -3.03692, -3.13988, -3.28565, -3.44217, -3.58436, -3.58509, -3.61889, -3.85049, -4.07489, -4.13723, -4.28681, -4.49798, -4.62633, -4.87198, -5.10009, -5.23774, -5.14118, -4.92088, -4.78894, -4.69093, -4.45192, -4.32415, -4.30460, -4.24603, -4.18714, -4.03094, -3.90664, -3.98731, -4.03971, -4.06186, -4.13240, -4.17822, -4.27790, -4.23794, -4.19130, -4.22903, -4.32057, -4.25584, -4.12543, -4.12022, -4.19654, -4.16390, -4.05785, -3.97120, -3.88767, -3.89591, -3.86695, -3.82133, -3.82568, -3.83825, -3.76263, -3.66279, -3.62523, -3.69508, -3.77095, -3.68686, -3.64951, -3.64580, -3.70719, -3.80920, -3.79758, -3.69715, -3.57666, -3.29276, -3.08155, -2.80221, -2.69396, -2.64952, -2.61467, -2.47236, -2.24148, -2.11337, -2.04095, -1.92660, -1.86243, -1.84880, -1.59583, -1.43650, -1.45645, -1.47730, -1.37505, -1.25455, -1.15987, -1.03556, -0.82727, -0.62993, -0.48178, -0.26778, -0.07476, 0.21545, 0.52552, 0.67272, 0.75656, 0.89105, 0.88020, 0.84201, 0.69776, 0.78256, 0.95772, 1.19736, 1.39088, 1.54336, 1.74592, 1.75106, 1.53856, 1.41699, 1.36937, 1.23019, 1.22625, 1.23651, 1.34995, 1.46262, 1.44507, 1.33112, 1.22500, 1.24133, 1.33910, 1.34731, 1.22345, 1.23823, 1.20568, 1.10244, 1.02444, 0.86566, 0.67573, 0.60068, 0.34477, 0.16418, -0.10155, -0.27235, -0.41095, -0.52290, -0.59433, -0.67109, -0.68224, -0.71966, -0.73811, -0.71919, -0.76389, -0.92594, -0.90208, -0.96106, -1.09976, -1.17667, +-1.20366, -1.06153, -1.00869, -0.92067, -0.90505, -0.80008, -0.61129, -0.49379, -0.34439, -0.19192, -0.21598, -0.22452, -0.24980, -0.33166, -0.40247, -0.64472, -0.87373, -0.96966, -1.12982, -1.29583, -1.32101, -1.40426, -1.45398, -1.36700, -1.42085, -1.34572, -1.15123, -1.09695, -1.03681, -0.98750, -0.97792, -0.96542, -0.93289, -0.78614, -0.58691, -0.41968, -0.44726, -0.40532, -0.25432, -0.27869, -0.33699, -0.27454, -0.24667, -0.28073, -0.37794, -0.56546, -0.62841, -0.68587, -0.69563, -0.57191, -0.51324, -0.54872, -0.57308, -0.70631, -0.82211, -0.75079, -0.71882, -0.70050, -0.62376, -0.60845, -0.49549, -0.39108, -0.47510, -0.58442, -0.70201, -0.69397, -0.66508, -0.48611, -0.30007, -0.23842, -0.12774, -0.10687, -0.03418, 0.13268, 0.19378, 0.11603, 0.13029, 0.15586, 0.33886, 0.47174, 0.53108, 0.57627, 0.53605, 0.38276, 0.27141, 0.15906, -0.02668, -0.09528, -0.24170, -0.37444, -0.34811, -0.36752, -0.36160, -0.16089, 0.08043, 0.27450, 0.31242, 0.41481, 0.36241, 0.20774, -0.00748, -0.23268, -0.20765, -0.25453, -0.31456, -0.29142, -0.34163, -0.50546, -0.58234, -0.70733, -0.69041, -0.74684, -0.92555, -1.05047, -1.06251, -1.07392, -1.02310, -1.08532, -1.40932, -1.56557, -1.58060, -1.58556, -1.47740, -1.41819, -1.43487, -1.38019, -1.42739, -1.38207, -1.32368, -1.24764, -1.24278, -1.19425, -1.11529, -1.19937, -1.25328, -1.47646, -1.65225, -1.59235, -1.46831, -1.45084, -1.39541, -1.50523, -1.48626, -1.50994, -1.63696, -1.72315, -1.77688, -1.82977, -1.74285, -1.58525, -1.65941, -1.66525, -1.67814, -1.69268, -1.49321, -1.41674, -1.48724, -1.37370, -1.36820, -1.44143, -1.56716, -1.55478, -1.47464, -1.35967, -1.19275, -1.10738, -0.89027, -0.68585, -0.50784, -0.20759, 0.07275, 0.15794, 0.18420, 0.11027, 0.28811, 0.58770, 0.85598, 1.06225, 1.23337, 1.37964, 1.65345, 1.97426, 2.01914, 2.07939, 2.16099, 2.15571, 2.27623, 2.46236, 2.50959, 2.55174, 2.48822, 2.46786, 2.54291, 2.72295, 2.87352, 2.90045, 3.01294, 3.06738, 3.23514, 3.31438, 3.27319, 3.28312, 3.43317, 3.42156, 3.41988, 3.28649, 3.19264, 3.06113, 2.81362, 2.55089, 2.28349, 1.90254, 1.59472, 1.58104, 1.48546, 1.26172, 1.04042, 0.78828, 0.63255, 0.49663, 0.24698, 0.15376, 0.04066, -0.15931, -0.41100, -0.62863, -0.80657, -0.94292, -0.93001, -0.91875, -0.85050, -0.81537, -1.04674, -1.29076, -1.33200, -1.42146, -1.48826, -1.73631, -1.97201, -1.98937, -1.91801, -1.89187, -1.90503, -2.05907, -2.24168, -2.25454, -2.30743, -2.25850, -2.10099, -2.16569, -2.19808, -2.15452, -2.20481, -2.24123, -2.39542, -2.67715, -2.84749, -2.89582, -2.90294, -3.03098, -3.20626, -3.46182, -3.63741, -3.72935, -3.94577, -4.11523, -4.18034, -4.36506, -4.58586, -4.81486, -5.11227, -5.29131, -5.44478, -5.37165, -5.09846, -4.93796, -4.82954, -4.50752, -4.34462, -4.36256, -4.33035, -4.35297, -4.29240, -4.16386, -4.12763, -4.09512, -4.12952, -4.27144, -4.33108, -4.28165, -4.16761, -4.14686, -4.18898, -4.23567, -4.17339, -3.96619, -3.92744, -4.00652, -3.97639, -3.87929, -3.72256, -3.64253, -3.72501, -3.71229, -3.73794, -3.76067, -3.69920, -3.59848, -3.55720, -3.46686, -3.40229, -3.39218, -3.25053, -3.24921, -3.37666, -3.46046, -3.49522, -3.42530, -3.26807, -3.19509, -3.06810, -2.90361, -2.64181, -2.52239, -2.42733, -2.38626, -2.41216, -2.32251, -2.28485, -2.22208, -2.05355, -1.95299, -1.89568, -1.68373, -1.59809, -1.53283, -1.50197, -1.43845, -1.33598, -1.25063, -1.18178, -0.93737, -0.64067, -0.50410, -0.25173, -0.05544, 0.08331, 0.33110, 0.55558, 0.73094, 0.85626, 0.74447, 0.54611, 0.46690, 0.68514, 0.95548, 1.22038, 1.38611, 1.41975, 1.60115, 1.67277, 1.57772, 1.53489, 1.45506, 1.30120, 1.27437, 1.18722, 1.31594, 1.38634, 1.29217, 1.20200, 1.16503, 1.15695, 1.26397, 1.35563, 1.23757, 1.28189, 1.30933, 1.18991, 1.11198, 0.96324, 0.77288, 0.70718, 0.50606, 0.29544, 0.09394, -0.02739, -0.20565, -0.35358, -0.45047, -0.65327, -0.73587, -0.82718, -0.83172, -0.72762, -0.71667, -0.81442, -0.84363, -1.08650, -1.23621, -1.29860, +-1.17537, -1.08759, -1.04138, -0.88421, -0.73112, -0.61531, -0.48834, -0.28422, -0.17227, -0.17585, -0.28882, -0.36663, -0.42110, -0.49116, -0.55271, -0.82413, -1.03271, -1.03777, -1.19918, -1.40430, -1.51577, -1.69902, -1.83755, -1.76975, -1.76314, -1.66093, -1.50321, -1.42821, -1.37675, -1.40555, -1.31873, -1.22345, -1.16337, -1.10787, -1.00538, -0.82557, -0.70482, -0.61964, -0.53078, -0.46165, -0.43387, -0.40088, -0.32969, -0.34186, -0.37569, -0.42097, -0.40316, -0.54226, -0.65749, -0.52344, -0.47642, -0.53480, -0.52896, -0.63386, -0.68611, -0.53938, -0.42777, -0.43582, -0.43153, -0.44839, -0.32318, -0.29324, -0.32361, -0.39663, -0.45241, -0.47570, -0.45501, -0.27872, -0.06761, -0.05679, -0.06773, -0.00930, 0.12740, 0.15595, 0.14035, 0.03288, 0.08164, 0.17421, 0.41762, 0.46812, 0.41475, 0.49125, 0.45275, 0.27959, 0.23048, 0.08986, -0.06342, -0.10722, -0.20604, -0.32261, -0.28275, -0.28998, -0.22169, -0.16519, 0.02541, 0.19792, 0.29627, 0.35197, 0.26405, 0.09540, -0.03094, -0.18974, -0.21287, -0.22331, -0.13689, -0.10979, -0.13630, -0.33065, -0.43396, -0.53641, -0.47998, -0.58534, -0.81156, -0.83797, -0.76881, -0.79875, -0.75590, -0.98485, -1.38392, -1.60884, -1.62765, -1.61708, -1.52624, -1.50724, -1.41408, -1.41726, -1.41925, -1.37981, -1.32503, -1.32632, -1.33472, -1.26362, -1.07564, -1.09358, -1.20450, -1.37219, -1.37470, -1.37767, -1.31056, -1.40287, -1.42413, -1.52272, -1.49258, -1.55472, -1.73874, -1.79324, -1.75923, -1.84084, -1.73967, -1.64798, -1.67038, -1.62383, -1.57388, -1.60654, -1.50425, -1.52799, -1.49623, -1.44628, -1.44136, -1.51845, -1.58669, -1.57171, -1.47644, -1.36241, -1.08700, -0.87277, -0.72421, -0.60102, -0.35740, -0.13131, 0.10030, 0.14918, 0.21611, 0.27995, 0.58606, 0.92896, 1.09808, 1.20863, 1.38510, 1.42914, 1.66745, 1.90632, 1.92257, 1.97984, 2.14495, 2.22053, 2.36069, 2.45041, 2.51563, 2.46762, 2.38443, 2.38479, 2.51014, 2.66101, 2.79509, 2.87508, 3.12607, 3.31422, 3.44388, 3.40271, 3.39885, 3.32541, 3.32999, 3.23801, 3.23039, 3.15435, 3.16323, 3.06639, 2.74423, 2.47979, 2.36517, 2.01907, 1.72167, 1.57567, 1.34389, 1.05852, 0.87411, 0.65118, 0.45253, 0.20842, 0.02166, -0.06279, -0.18038, -0.35819, -0.53539, -0.71081, -0.93636, -1.13729, -1.12743, -1.04517, -1.01106, -1.03101, -1.06361, -1.14470, -1.15253, -1.20563, -1.30059, -1.58367, -1.78149, -1.81447, -1.86067, -1.88929, -1.83170, -1.96830, -2.10122, -2.10979, -2.19150, -2.18140, -2.03586, -2.06649, -2.09893, -2.11266, -2.12155, -2.16881, -2.36786, -2.55928, -2.64186, -2.65608, -2.72293, -2.94276, -3.14502, -3.35341, -3.62878, -3.86589, -4.02465, -4.15821, -4.29845, -4.52328, -4.78652, -4.97924, -5.13040, -5.20826, -5.43064, -5.48791, -5.22833, -5.06214, -4.93247, -4.61554, -4.53767, -4.59010, -4.52654, -4.46880, -4.39016, -4.31897, -4.22578, -4.10724, -4.21505, -4.34621, -4.41268, -4.33790, -4.26962, -4.25879, -4.20843, -4.04773, -3.91125, -3.74141, -3.65361, -3.70403, -3.77615, -3.74267, -3.63953, -3.53652, -3.53147, -3.42400, -3.46346, -3.52222, -3.39465, -3.29429, -3.31739, -3.23754, -3.24412, -3.22083, -3.03999, -2.97707, -3.06556, -3.12226, -3.12673, -2.98762, -2.94665, -2.92115, -2.84907, -2.70706, -2.57466, -2.50745, -2.40472, -2.26472, -2.27522, -2.33116, -2.33110, -2.18967, -2.05003, -1.93697, -1.92558, -1.78084, -1.67566, -1.50749, -1.45829, -1.44134, -1.31491, -1.20092, -1.15037, -0.87589, -0.68321, -0.59846, -0.33020, -0.06819, 0.05236, 0.21362, 0.33244, 0.54700, 0.55895, 0.46885, 0.34141, 0.40279, 0.62313, 0.90181, 1.12841, 1.34354, 1.43374, 1.52518, 1.60798, 1.65321, 1.56200, 1.48963, 1.32901, 1.30880, 1.26478, 1.40532, 1.38181, 1.17587, 1.08838, 1.11367, 1.08073, 1.20791, 1.24747, 1.19287, 1.29246, 1.41050, 1.31772, 1.17596, 0.94181, 0.81882, 0.65242, 0.49297, 0.33310, 0.23525, 0.10692, -0.10544, -0.30090, -0.31734, -0.41022, -0.57043, -0.74629, -0.74036, -0.75404, -0.76657, -0.88299, -0.93039, -1.15359, -1.24138, -1.28656, +-1.12907, -1.04581, -1.01570, -0.86903, -0.59944, -0.36534, -0.23186, -0.06669, -0.05553, -0.14446, -0.29296, -0.46884, -0.59609, -0.68398, -0.79852, -1.04823, -1.20209, -1.21349, -1.35580, -1.59193, -1.84065, -2.07677, -2.20402, -2.14652, -2.17122, -2.10587, -1.93303, -1.81606, -1.75912, -1.77339, -1.60571, -1.43395, -1.36433, -1.32208, -1.30568, -1.21349, -1.05231, -0.85535, -0.69084, -0.57993, -0.54590, -0.49843, -0.35756, -0.33706, -0.32294, -0.28814, -0.27913, -0.45070, -0.59546, -0.54117, -0.49268, -0.47606, -0.46379, -0.53361, -0.51717, -0.36215, -0.29696, -0.37422, -0.37492, -0.38152, -0.28702, -0.27037, -0.25730, -0.23498, -0.19356, -0.13277, -0.11254, -0.03034, 0.12453, 0.16119, 0.13789, 0.14027, 0.19364, 0.12806, 0.09463, 0.00936, 0.08559, 0.22187, 0.39979, 0.31356, 0.20835, 0.28381, 0.30096, 0.24413, 0.19589, 0.01766, -0.06423, -0.05780, -0.15606, -0.31041, -0.26215, -0.25356, -0.20697, -0.20400, -0.07258, 0.11786, 0.22856, 0.34187, 0.30698, 0.10469, -0.01134, -0.06965, -0.04577, -0.04439, 0.05250, 0.06176, 0.08002, -0.07671, -0.19780, -0.29877, -0.29154, -0.46035, -0.65146, -0.64437, -0.57037, -0.56034, -0.61170, -0.98828, -1.38823, -1.63436, -1.71387, -1.78233, -1.71383, -1.65033, -1.47237, -1.42171, -1.40005, -1.32112, -1.28856, -1.26245, -1.23870, -1.23349, -1.08270, -1.03270, -1.08402, -1.17099, -1.12868, -1.20325, -1.21429, -1.41551, -1.51447, -1.56192, -1.53113, -1.65594, -1.84939, -1.91205, -1.84380, -1.80985, -1.70640, -1.69277, -1.65914, -1.57179, -1.52750, -1.65170, -1.64856, -1.69960, -1.65335, -1.56478, -1.49955, -1.49133, -1.52355, -1.44570, -1.29651, -1.21561, -0.96367, -0.69659, -0.52219, -0.40205, -0.19646, -0.07841, 0.12586, 0.20315, 0.32439, 0.51534, 0.85025, 1.11173, 1.20739, 1.25455, 1.40752, 1.49823, 1.69664, 1.80520, 1.81371, 1.92542, 2.16536, 2.24037, 2.35340, 2.40917, 2.43958, 2.38471, 2.31362, 2.34755, 2.46755, 2.64038, 2.83772, 2.96938, 3.24365, 3.48564, 3.60598, 3.47635, 3.41432, 3.26439, 3.21710, 3.11021, 3.07361, 3.04757, 3.11563, 2.99968, 2.67396, 2.43670, 2.37002, 2.12516, 1.84658, 1.53562, 1.19054, 0.86676, 0.65246, 0.39292, 0.17200, -0.08492, -0.25489, -0.30588, -0.38325, -0.48774, -0.61810, -0.76038, -0.94362, -1.15899, -1.23162, -1.17512, -1.10569, -1.08003, -1.00421, -1.01181, -0.99769, -1.03612, -1.18550, -1.46260, -1.62566, -1.73654, -1.87024, -1.94215, -1.90427, -1.92763, -1.92407, -1.96797, -2.07776, -2.07792, -1.96638, -2.02382, -2.09018, -2.14347, -2.17079, -2.21993, -2.36496, -2.41995, -2.41016, -2.41366, -2.51723, -2.84295, -3.13823, -3.34219, -3.59147, -3.85955, -4.05778, -4.24122, -4.40474, -4.60333, -4.87496, -5.01994, -5.07601, -5.16555, -5.43716, -5.56856, -5.40652, -5.22040, -5.02083, -4.73121, -4.66766, -4.69135, -4.61319, -4.54773, -4.48649, -4.41626, -4.30306, -4.17205, -4.24859, -4.31758, -4.35803, -4.31319, -4.22256, -4.18928, -4.11906, -3.88424, -3.67303, -3.50548, -3.45114, -3.52821, -3.63081, -3.60788, -3.54791, -3.44486, -3.36853, -3.21537, -3.21514, -3.24362, -3.13433, -3.03717, -3.01614, -2.97870, -3.05635, -3.04241, -2.87821, -2.81986, -2.89225, -2.87242, -2.82603, -2.69841, -2.72293, -2.75364, -2.66063, -2.53102, -2.39807, -2.35100, -2.32502, -2.19657, -2.14319, -2.21018, -2.25446, -2.13279, -2.02189, -1.89872, -1.90847, -1.83025, -1.71470, -1.54355, -1.50318, -1.42583, -1.27397, -1.13787, -0.99774, -0.74701, -0.65956, -0.59993, -0.37128, -0.15221, -0.08902, 0.04432, 0.11298, 0.26859, 0.27334, 0.24209, 0.26477, 0.39815, 0.64790, 0.90619, 1.03100, 1.22818, 1.40774, 1.52146, 1.59679, 1.64812, 1.52550, 1.52116, 1.43301, 1.40753, 1.38986, 1.45957, 1.32134, 1.09316, 0.96657, 0.95604, 0.98606, 1.11060, 1.11914, 1.16601, 1.31529, 1.42691, 1.23916, 1.02882, 0.81243, 0.72487, 0.59438, 0.48893, 0.42769, 0.38361, 0.32300, 0.14547, -0.10936, -0.14481, -0.17771, -0.34232, -0.57209, -0.66257, -0.80274, -0.83633, -0.93252, -0.95722, -1.09649, -1.17359, -1.26527, +-1.21465, -1.10518, -0.96935, -0.87232, -0.60596, -0.21849, -0.05488, 0.01933, -0.03764, -0.13304, -0.21777, -0.54681, -0.88118, -0.99102, -1.08765, -1.28034, -1.33620, -1.34559, -1.56527, -1.85743, -2.17117, -2.31806, -2.44113, -2.48559, -2.47659, -2.45201, -2.33250, -2.17857, -2.12629, -2.08151, -1.87807, -1.77623, -1.72789, -1.67059, -1.60209, -1.59488, -1.52256, -1.20359, -0.91777, -0.77062, -0.68545, -0.62261, -0.45001, -0.45949, -0.51763, -0.44199, -0.38696, -0.48297, -0.50339, -0.41623, -0.46422, -0.47049, -0.45372, -0.36733, -0.25630, -0.19897, -0.15885, -0.29091, -0.31165, -0.26317, -0.20994, -0.20489, -0.17014, -0.19405, -0.06922, 0.09426, 0.22319, 0.20731, 0.16711, 0.25711, 0.30180, 0.20991, 0.16496, 0.07949, 0.09701, 0.01731, -0.00419, 0.15862, 0.30508, 0.16205, 0.06043, 0.18002, 0.16128, 0.12698, 0.09786, 0.01703, 0.02357, -0.04444, -0.08276, -0.20061, -0.18257, -0.16038, -0.16206, -0.21370, -0.12656, -0.07431, 0.01549, 0.18651, 0.32704, 0.19434, -0.00106, -0.03507, 0.01157, -0.01559, 0.07832, 0.10936, 0.22217, 0.16270, 0.01694, -0.03859, -0.06349, -0.25333, -0.42092, -0.35202, -0.36280, -0.44392, -0.62072, -1.01295, -1.30429, -1.63952, -1.74347, -1.83233, -1.83443, -1.72201, -1.47043, -1.37740, -1.31239, -1.38133, -1.41350, -1.33386, -1.16600, -1.15412, -1.18238, -1.11151, -1.03312, -1.07551, -1.02519, -1.10712, -1.16728, -1.43438, -1.69909, -1.73784, -1.68534, -1.78795, -1.94802, -1.93895, -1.92261, -1.90845, -1.79413, -1.72777, -1.55362, -1.55066, -1.53094, -1.66164, -1.77038, -1.83127, -1.76691, -1.65469, -1.47256, -1.49321, -1.53253, -1.47614, -1.28853, -1.14960, -1.04719, -0.84388, -0.56872, -0.40338, -0.15012, -0.00424, 0.19000, 0.31067, 0.35581, 0.58628, 0.95375, 1.18412, 1.19596, 1.26296, 1.38342, 1.42899, 1.59004, 1.67326, 1.79308, 1.88715, 2.16917, 2.32122, 2.36730, 2.34467, 2.34838, 2.31063, 2.33077, 2.26776, 2.29184, 2.48105, 2.79904, 3.07337, 3.25977, 3.44083, 3.60581, 3.41759, 3.29925, 3.15655, 3.10766, 3.05121, 2.91054, 2.83784, 2.93076, 2.84844, 2.57001, 2.46135, 2.41202, 2.12398, 1.83357, 1.45532, 1.14866, 0.74855, 0.44716, 0.23737, 0.00523, -0.25842, -0.40560, -0.52636, -0.60088, -0.73083, -0.92522, -1.06291, -1.11570, -1.14257, -1.23808, -1.26729, -1.13737, -1.08211, -0.96927, -0.87563, -0.80914, -0.80643, -1.11025, -1.47148, -1.57493, -1.68835, -1.86837, -1.91412, -1.89699, -1.92075, -1.81597, -1.82610, -1.83490, -1.90416, -1.91260, -1.88957, -1.96206, -2.10514, -2.15465, -2.20869, -2.26514, -2.27494, -2.31667, -2.33550, -2.43640, -2.72303, -3.12036, -3.43619, -3.62898, -3.89924, -4.16972, -4.38399, -4.55610, -4.67745, -4.97089, -5.14111, -5.10305, -5.16156, -5.41946, -5.53797, -5.43935, -5.34903, -5.15527, -4.85567, -4.64587, -4.61088, -4.62838, -4.56712, -4.55852, -4.52172, -4.39959, -4.29416, -4.28525, -4.25687, -4.30707, -4.27388, -4.17075, -4.04617, -3.99713, -3.83855, -3.55749, -3.38714, -3.43062, -3.49861, -3.54063, -3.45530, -3.45277, -3.45404, -3.31502, -3.07796, -2.96713, -2.90342, -2.78048, -2.81260, -2.81776, -2.74909, -2.73186, -2.72596, -2.72023, -2.60887, -2.62585, -2.59405, -2.49351, -2.38707, -2.44874, -2.51456, -2.54230, -2.44832, -2.31419, -2.19693, -2.21560, -2.24438, -2.17148, -2.18832, -2.26268, -2.12078, -1.98061, -1.82888, -1.86277, -1.94066, -1.82360, -1.62779, -1.53213, -1.34408, -1.07952, -0.98046, -0.87626, -0.71702, -0.64831, -0.56348, -0.53167, -0.34886, -0.25420, -0.12267, 0.00828, 0.13002, 0.11007, 0.13220, 0.12847, 0.30370, 0.57604, 0.86115, 0.92200, 0.99329, 1.23887, 1.44601, 1.49534, 1.55178, 1.47243, 1.56858, 1.57428, 1.43579, 1.37764, 1.35327, 1.19004, 1.02556, 0.96224, 0.82684, 0.78731, 0.92662, 1.01882, 1.20365, 1.26580, 1.37116, 1.17987, 0.89080, 0.71340, 0.66503, 0.55985, 0.53789, 0.42472, 0.36832, 0.33124, 0.26421, 0.07402, -0.07478, -0.14303, -0.27541, -0.56537, -0.73546, -0.90293, -0.92071, -0.94669, -1.01269, -1.07825, -1.10389, -1.19845, +-1.16405, -1.11515, -0.95313, -0.83414, -0.59208, -0.24411, -0.07012, -0.03857, -0.13547, -0.18753, -0.23873, -0.59948, -1.00404, -1.16175, -1.21690, -1.38984, -1.54785, -1.61224, -1.76775, -1.96633, -2.27256, -2.45270, -2.52654, -2.54997, -2.55892, -2.57016, -2.56349, -2.52260, -2.48843, -2.42136, -2.18161, -2.05312, -2.07448, -2.08286, -1.94870, -1.87124, -1.77434, -1.48735, -1.20058, -1.02104, -0.91750, -0.85728, -0.72681, -0.73256, -0.77477, -0.72514, -0.60606, -0.55782, -0.50657, -0.43261, -0.49524, -0.48724, -0.51523, -0.45146, -0.24949, -0.09995, -0.05433, -0.15205, -0.16457, -0.16006, -0.13642, -0.15870, -0.08317, -0.01954, 0.06009, 0.12689, 0.28257, 0.26589, 0.21798, 0.33187, 0.42295, 0.31798, 0.18680, 0.09588, 0.12510, 0.00427, -0.06650, 0.08072, 0.23989, 0.18829, 0.07763, 0.12579, 0.12891, 0.17164, 0.16522, 0.06990, 0.09333, 0.10845, 0.10790, 0.03005, -0.00377, -0.12429, -0.20475, -0.29266, -0.17323, -0.03730, 0.01988, 0.05451, 0.21453, 0.18753, 0.08406, 0.04949, 0.06152, 0.04894, 0.10469, 0.11928, 0.29151, 0.33157, 0.31152, 0.30428, 0.23113, 0.05770, -0.19715, -0.27200, -0.33433, -0.41046, -0.62331, -1.03248, -1.24626, -1.43367, -1.53211, -1.64364, -1.69601, -1.71075, -1.55515, -1.51306, -1.43318, -1.44333, -1.46072, -1.41534, -1.17264, -1.11162, -1.13838, -1.03681, -0.91923, -0.96946, -1.00275, -1.11963, -1.19509, -1.45814, -1.71526, -1.74084, -1.68892, -1.70235, -1.82919, -1.88836, -1.92068, -1.87299, -1.74000, -1.71296, -1.56288, -1.51556, -1.51800, -1.63060, -1.71214, -1.82020, -1.79481, -1.73937, -1.55764, -1.45636, -1.43781, -1.50880, -1.38342, -1.22370, -1.14864, -0.99941, -0.70239, -0.44465, -0.11285, 0.05562, 0.22002, 0.30838, 0.31886, 0.54971, 0.89557, 1.16530, 1.16761, 1.17074, 1.29668, 1.42519, 1.61106, 1.65038, 1.77115, 1.94845, 2.19568, 2.31710, 2.32739, 2.18524, 2.14940, 2.16131, 2.26313, 2.29619, 2.35315, 2.48844, 2.79319, 3.04284, 3.19053, 3.35664, 3.52628, 3.39748, 3.28884, 3.14741, 3.11289, 3.05899, 2.91412, 2.82419, 2.83945, 2.79237, 2.57389, 2.41872, 2.30399, 2.02059, 1.74315, 1.34251, 1.04896, 0.74569, 0.43774, 0.16571, -0.10979, -0.43216, -0.64276, -0.85360, -0.98514, -1.04002, -1.18843, -1.37721, -1.36988, -1.23798, -1.18272, -1.18215, -1.09501, -1.04628, -0.96332, -0.87357, -0.78287, -0.78355, -1.08913, -1.40117, -1.48558, -1.54777, -1.71066, -1.84240, -1.88165, -1.88103, -1.74916, -1.77283, -1.79989, -1.82945, -1.79680, -1.72430, -1.75846, -1.96460, -2.09725, -2.14854, -2.19850, -2.20311, -2.22304, -2.30181, -2.44401, -2.66756, -3.01425, -3.31640, -3.53077, -3.81017, -4.11485, -4.40328, -4.62843, -4.74583, -4.98641, -5.10263, -5.07052, -5.09825, -5.27860, -5.41099, -5.35846, -5.26757, -5.06980, -4.85666, -4.70160, -4.58862, -4.54453, -4.53110, -4.55661, -4.55564, -4.55075, -4.49323, -4.42049, -4.23996, -4.10113, -4.09843, -4.12814, -4.04238, -4.01732, -3.86912, -3.60955, -3.44300, -3.47441, -3.51390, -3.49110, -3.35972, -3.34771, -3.33378, -3.18803, -2.94793, -2.78628, -2.74056, -2.68538, -2.72491, -2.63863, -2.50118, -2.47139, -2.44928, -2.40373, -2.27888, -2.29289, -2.33700, -2.34254, -2.25865, -2.29524, -2.29193, -2.23341, -2.18523, -2.18475, -2.09001, -2.10567, -2.17249, -2.16170, -2.16823, -2.19501, -2.07183, -1.97297, -1.85978, -1.90067, -1.93901, -1.77381, -1.54950, -1.37937, -1.22181, -1.02299, -0.89533, -0.74799, -0.66621, -0.70598, -0.64231, -0.62333, -0.50685, -0.38236, -0.20622, -0.08898, -0.01911, -0.08490, -0.05060, 0.04695, 0.25404, 0.43464, 0.70511, 0.79872, 0.92659, 1.21789, 1.47473, 1.55953, 1.60297, 1.53018, 1.60550, 1.57252, 1.40596, 1.29744, 1.19865, 1.12571, 1.03412, 0.94424, 0.78997, 0.79588, 0.96202, 0.98465, 1.09944, 1.21009, 1.31789, 1.18744, 0.94971, 0.73632, 0.67899, 0.57750, 0.59552, 0.59505, 0.54047, 0.37550, 0.32393, 0.19410, 0.03781, -0.11653, -0.31429, -0.60045, -0.76117, -0.88763, -0.87862, -0.89773, -0.95456, -0.96642, -0.96344, -1.00602, +-1.00697, -0.94723, -0.88076, -0.75670, -0.54159, -0.37719, -0.17750, -0.17445, -0.29335, -0.25635, -0.32903, -0.64734, -0.95634, -1.20942, -1.33555, -1.50915, -1.64551, -1.69452, -1.82822, -1.91522, -2.11830, -2.33224, -2.46874, -2.56542, -2.62519, -2.65568, -2.65561, -2.70344, -2.71993, -2.55187, -2.40443, -2.34013, -2.31673, -2.29741, -2.17228, -2.03084, -1.82894, -1.69145, -1.47238, -1.33191, -1.29572, -1.14262, -1.00394, -0.96840, -0.90319, -0.91931, -0.85965, -0.72657, -0.59461, -0.52656, -0.67199, -0.65068, -0.64149, -0.57330, -0.37251, -0.19838, -0.09657, -0.07274, -0.01246, -0.02339, -0.07530, -0.00018, 0.04430, 0.06334, 0.13430, 0.17094, 0.28019, 0.26143, 0.35251, 0.40348, 0.48612, 0.40027, 0.16998, 0.13622, 0.14796, -0.00682, -0.02828, 0.07437, 0.15288, 0.19430, 0.15734, 0.24186, 0.19519, 0.26640, 0.31842, 0.25625, 0.23511, 0.23436, 0.21846, 0.19158, 0.15621, -0.00829, -0.21140, -0.20469, -0.07837, 0.00637, 0.09226, 0.07358, 0.13285, 0.08626, 0.17680, 0.17454, 0.21285, 0.26375, 0.21710, 0.26950, 0.45177, 0.51775, 0.59277, 0.53671, 0.30690, 0.13793, -0.13584, -0.21178, -0.36679, -0.43972, -0.55751, -0.84844, -1.05531, -1.21555, -1.34859, -1.45447, -1.52528, -1.59987, -1.67997, -1.62546, -1.53746, -1.58982, -1.50729, -1.39567, -1.15487, -1.13226, -1.00864, -0.89338, -0.80926, -0.84434, -1.03377, -1.14279, -1.19840, -1.43035, -1.58448, -1.57909, -1.63147, -1.60270, -1.65451, -1.60879, -1.69641, -1.66976, -1.52949, -1.50027, -1.46185, -1.49952, -1.58274, -1.65405, -1.65150, -1.66629, -1.74148, -1.69313, -1.55841, -1.53632, -1.43891, -1.41906, -1.28031, -1.21806, -1.07052, -0.94375, -0.72182, -0.38845, -0.15814, -0.03482, 0.11559, 0.16432, 0.21028, 0.47026, 0.68449, 0.95318, 1.04355, 1.18275, 1.28630, 1.42457, 1.65184, 1.75588, 1.84269, 1.95617, 2.04353, 2.09874, 2.10090, 2.02337, 1.93650, 2.03115, 2.23981, 2.26320, 2.40449, 2.61998, 2.89961, 2.96242, 3.11701, 3.30143, 3.41047, 3.41337, 3.28118, 3.14909, 3.18043, 3.11334, 3.01847, 2.97782, 2.83164, 2.71923, 2.52990, 2.43134, 2.22871, 1.87650, 1.60795, 1.29425, 1.02261, 0.73175, 0.36797, 0.00323, -0.34172, -0.63318, -0.92810, -1.12613, -1.17426, -1.28710, -1.39732, -1.47926, -1.38787, -1.27131, -1.12915, -1.08711, -1.11520, -1.03041, -1.02847, -1.00775, -0.87472, -0.87983, -1.06718, -1.22031, -1.39153, -1.51005, -1.63879, -1.69789, -1.73604, -1.80179, -1.70853, -1.68243, -1.71482, -1.75160, -1.73703, -1.68455, -1.68901, -1.80998, -1.97112, -2.03551, -2.01909, -2.16180, -2.23952, -2.26296, -2.35728, -2.59194, -2.86624, -3.05602, -3.35291, -3.60458, -3.94355, -4.32753, -4.52473, -4.66348, -4.83932, -4.84418, -4.90320, -4.99720, -5.10060, -5.12015, -5.02299, -4.99878, -4.83485, -4.70030, -4.65979, -4.60378, -4.56999, -4.54409, -4.50905, -4.45248, -4.50114, -4.51607, -4.31580, -4.14584, -4.02859, -4.00979, -4.07262, -4.09772, -4.12824, -3.90755, -3.74595, -3.54263, -3.48787, -3.54867, -3.43631, -3.29475, -3.24471, -3.11999, -3.02593, -2.93783, -2.80401, -2.71015, -2.59139, -2.62961, -2.45769, -2.23546, -2.17189, -2.16864, -2.14587, -2.06980, -2.09094, -2.16427, -2.20519, -2.18837, -2.05902, -2.01862, -1.99469, -1.91192, -1.93403, -1.92880, -2.00997, -1.99013, -2.05981, -2.06228, -2.02264, -2.01181, -1.91989, -1.86060, -1.90408, -1.80578, -1.61044, -1.47667, -1.28964, -1.16677, -0.96743, -0.89350, -0.71264, -0.56650, -0.57754, -0.57939, -0.62948, -0.61109, -0.48277, -0.29810, -0.20895, -0.29929, -0.28468, -0.24077, -0.17676, 0.12361, 0.35436, 0.63410, 0.74203, 1.03462, 1.30463, 1.54188, 1.69156, 1.63838, 1.59677, 1.59948, 1.46160, 1.33084, 1.20527, 0.99623, 0.99153, 0.98378, 1.02622, 0.88220, 0.92594, 1.11953, 1.11077, 1.06760, 1.10333, 1.16142, 1.12695, 0.99685, 0.86410, 0.72196, 0.70505, 0.75229, 0.69674, 0.69404, 0.56274, 0.50767, 0.30328, 0.20982, -0.02958, -0.33254, -0.54933, -0.74148, -0.77812, -0.71837, -0.75707, -0.78519, -0.76891, -0.86806, -0.89101, +-0.94791, -0.89688, -0.78387, -0.64000, -0.55123, -0.50120, -0.34308, -0.33121, -0.37106, -0.29638, -0.36045, -0.64178, -0.96436, -1.23384, -1.34119, -1.49373, -1.67332, -1.75397, -1.85417, -1.88133, -2.04685, -2.28450, -2.43785, -2.55984, -2.66561, -2.75351, -2.71967, -2.68983, -2.76515, -2.69501, -2.58626, -2.52587, -2.50033, -2.49555, -2.31470, -2.07051, -1.87908, -1.82147, -1.70868, -1.63879, -1.59112, -1.35746, -1.14139, -1.06965, -1.04214, -1.08165, -0.99568, -0.84777, -0.78424, -0.84121, -1.01844, -0.98180, -0.93636, -0.83462, -0.59044, -0.36536, -0.20523, -0.11693, 0.01553, 0.12875, 0.05620, 0.03477, 0.06207, 0.07735, 0.08930, 0.07352, 0.21862, 0.34827, 0.47558, 0.48404, 0.50481, 0.38179, 0.17381, 0.17907, 0.21161, 0.10012, 0.04688, 0.08226, 0.16419, 0.24280, 0.19572, 0.19539, 0.13878, 0.22443, 0.29703, 0.25401, 0.25565, 0.28104, 0.26610, 0.25145, 0.26405, 0.24714, 0.03422, -0.08031, -0.00798, 0.04836, 0.10201, -0.00064, -0.00006, 0.07896, 0.24272, 0.33528, 0.45284, 0.50112, 0.46624, 0.56797, 0.74656, 0.81516, 0.79792, 0.58887, 0.33012, 0.17926, -0.10918, -0.27982, -0.46675, -0.53118, -0.57215, -0.77195, -0.92991, -1.03287, -1.15443, -1.28601, -1.37856, -1.40434, -1.60555, -1.72660, -1.67149, -1.67699, -1.54655, -1.45803, -1.25739, -1.10421, -0.91501, -0.78903, -0.69407, -0.74868, -0.95570, -1.03917, -1.08432, -1.24865, -1.39416, -1.46332, -1.50030, -1.41496, -1.42491, -1.42141, -1.51523, -1.50740, -1.39706, -1.40811, -1.40846, -1.46596, -1.58343, -1.67203, -1.64077, -1.49616, -1.53652, -1.64206, -1.62542, -1.62308, -1.48627, -1.38553, -1.20467, -1.04064, -0.86478, -0.75242, -0.56033, -0.28942, -0.15225, -0.07851, 0.04726, 0.13054, 0.17835, 0.34877, 0.52944, 0.80848, 0.94285, 1.04560, 1.12495, 1.27648, 1.54156, 1.68016, 1.77925, 1.86848, 1.84965, 1.82458, 1.81700, 1.90203, 1.91210, 1.93322, 2.09787, 2.17112, 2.38347, 2.61281, 2.85126, 2.95997, 3.11090, 3.24178, 3.32816, 3.34513, 3.23357, 3.16522, 3.25061, 3.24604, 3.15612, 3.01785, 2.81696, 2.68105, 2.46819, 2.26551, 1.98439, 1.60698, 1.33713, 1.03969, 0.78434, 0.54171, 0.19302, -0.23243, -0.63588, -0.84546, -1.06420, -1.27988, -1.36238, -1.48521, -1.54729, -1.56061, -1.43768, -1.21908, -1.04072, -1.05249, -1.10491, -1.03917, -1.07071, -1.05558, -0.93912, -0.91641, -1.03192, -1.20037, -1.40222, -1.49928, -1.58939, -1.67414, -1.73101, -1.82246, -1.77174, -1.73169, -1.73200, -1.70537, -1.67654, -1.68602, -1.72586, -1.73548, -1.76164, -1.87262, -1.95358, -2.15034, -2.26066, -2.30722, -2.40915, -2.53975, -2.68337, -2.84502, -3.12047, -3.35607, -3.70412, -4.06245, -4.22649, -4.33176, -4.46534, -4.51110, -4.60010, -4.65206, -4.71090, -4.75813, -4.73590, -4.76050, -4.64451, -4.61338, -4.67060, -4.63600, -4.56557, -4.47017, -4.38218, -4.25850, -4.19071, -4.24067, -4.14710, -4.02577, -3.97154, -4.01771, -4.12854, -4.13756, -4.08164, -3.88807, -3.77495, -3.57902, -3.49752, -3.50945, -3.35670, -3.17480, -3.06416, -2.96533, -2.93514, -2.90327, -2.82204, -2.75373, -2.65654, -2.62339, -2.39349, -2.15809, -2.08976, -2.04849, -2.00066, -1.96082, -2.00788, -2.05627, -1.98456, -1.99329, -1.94075, -1.89275, -1.86950, -1.81217, -1.87397, -1.87922, -1.87409, -1.85841, -1.93508, -1.92289, -1.88201, -1.87045, -1.76563, -1.71469, -1.73128, -1.65998, -1.53852, -1.41245, -1.23670, -1.19636, -1.12339, -1.07227, -0.85454, -0.61159, -0.55990, -0.54678, -0.57348, -0.58781, -0.52302, -0.38698, -0.27068, -0.44124, -0.53771, -0.49008, -0.37314, -0.02932, 0.20981, 0.52490, 0.81265, 1.14676, 1.38840, 1.61867, 1.75098, 1.69124, 1.67393, 1.61178, 1.42875, 1.25115, 1.05528, 0.89305, 0.95019, 0.96056, 0.97217, 0.88568, 0.97255, 1.16629, 1.13180, 1.03113, 1.03290, 1.05473, 1.04024, 0.98099, 1.00736, 0.88572, 0.77174, 0.77906, 0.72021, 0.73361, 0.61266, 0.55807, 0.47051, 0.38541, 0.10910, -0.20336, -0.42559, -0.59438, -0.56308, -0.47155, -0.46505, -0.52767, -0.60909, -0.71648, -0.69210, +-0.74257, -0.74829, -0.75609, -0.66593, -0.69309, -0.71651, -0.55005, -0.46167, -0.43138, -0.42605, -0.51438, -0.78936, -1.09520, -1.23976, -1.29261, -1.34081, -1.46446, -1.60713, -1.72907, -1.73089, -1.88247, -2.16772, -2.29189, -2.41385, -2.57111, -2.70800, -2.75213, -2.73109, -2.71607, -2.72372, -2.68061, -2.50261, -2.40178, -2.46386, -2.44392, -2.22974, -2.06885, -2.05013, -1.94800, -1.86992, -1.82379, -1.60725, -1.36790, -1.29988, -1.33249, -1.23939, -1.10178, -0.99882, -0.96359, -1.05186, -1.17142, -1.08944, -0.98995, -0.87494, -0.59876, -0.38096, -0.27676, -0.16138, -0.04634, 0.09390, 0.19982, 0.18425, 0.10999, 0.16642, 0.17596, 0.11338, 0.15900, 0.37127, 0.52296, 0.45222, 0.38822, 0.25564, 0.08028, 0.06118, 0.12281, 0.14520, 0.05097, 0.07980, 0.14897, 0.22624, 0.22099, 0.14665, 0.09748, 0.23106, 0.31157, 0.25436, 0.29860, 0.34868, 0.28500, 0.29897, 0.35055, 0.40528, 0.34503, 0.23213, 0.10566, 0.13937, 0.18614, 0.03088, -0.10911, -0.01070, 0.18801, 0.34533, 0.51557, 0.59444, 0.58620, 0.71403, 0.85652, 0.89382, 0.72819, 0.54079, 0.37951, 0.25457, 0.04472, -0.17301, -0.39622, -0.47695, -0.52245, -0.69455, -0.79498, -0.80427, -0.89904, -1.01582, -1.16710, -1.31919, -1.52458, -1.62981, -1.68379, -1.57971, -1.38876, -1.36603, -1.38388, -1.26652, -1.02694, -0.88426, -0.72924, -0.65520, -0.84129, -0.99634, -1.10294, -1.17584, -1.35672, -1.44012, -1.38329, -1.24386, -1.18836, -1.21077, -1.31341, -1.32336, -1.26345, -1.32958, -1.31138, -1.29548, -1.44484, -1.54741, -1.57002, -1.49655, -1.46157, -1.49169, -1.60207, -1.58004, -1.38240, -1.19802, -1.11916, -1.01673, -0.81349, -0.65899, -0.48442, -0.25740, -0.19327, -0.13943, -0.02959, 0.13810, 0.17100, 0.28937, 0.48148, 0.68899, 0.80506, 0.87148, 0.92463, 1.12292, 1.46687, 1.63127, 1.73208, 1.82810, 1.71829, 1.66785, 1.67999, 1.78661, 1.88603, 1.97299, 1.98666, 2.07257, 2.39016, 2.66700, 2.81756, 2.90271, 3.02236, 3.04517, 3.07537, 3.14939, 3.07070, 3.00057, 3.09397, 3.20126, 3.07933, 2.86783, 2.71363, 2.53814, 2.29835, 2.04247, 1.73813, 1.40272, 1.15988, 0.84112, 0.53166, 0.34368, 0.00766, -0.39918, -0.76363, -1.01771, -1.19181, -1.25782, -1.43158, -1.61988, -1.58230, -1.46130, -1.41235, -1.30308, -1.12895, -1.11224, -1.12029, -0.99495, -1.00696, -1.05749, -1.06925, -1.07458, -1.22564, -1.43933, -1.55954, -1.58361, -1.56473, -1.59591, -1.66326, -1.76747, -1.72188, -1.65807, -1.61934, -1.46662, -1.45547, -1.57877, -1.68012, -1.73413, -1.69378, -1.67723, -1.78349, -2.00860, -2.10977, -2.19669, -2.39652, -2.57186, -2.65168, -2.80156, -3.00369, -3.13181, -3.43228, -3.77518, -3.96451, -4.03795, -4.15877, -4.26237, -4.23061, -4.18758, -4.19920, -4.25816, -4.36876, -4.45987, -4.37247, -4.38784, -4.48515, -4.42505, -4.33383, -4.21715, -4.09522, -4.03394, -3.93791, -3.83347, -3.81485, -3.86115, -3.80229, -3.79319, -3.93125, -4.02320, -3.93545, -3.80450, -3.76249, -3.61072, -3.53698, -3.54896, -3.43321, -3.18248, -2.96339, -2.92355, -2.86559, -2.86125, -2.81331, -2.69651, -2.58607, -2.45656, -2.19401, -2.00675, -1.98865, -1.89199, -1.79844, -1.80613, -1.78400, -1.81449, -1.79947, -1.77004, -1.73486, -1.76991, -1.71305, -1.66366, -1.73694, -1.84535, -1.85833, -1.86879, -1.94424, -1.90810, -1.83386, -1.82188, -1.72190, -1.64877, -1.60046, -1.64196, -1.57107, -1.44415, -1.29610, -1.23091, -1.20691, -1.17190, -0.92486, -0.62081, -0.54306, -0.49614, -0.43449, -0.45817, -0.44933, -0.44650, -0.44359, -0.51550, -0.54996, -0.56440, -0.36029, 0.00298, 0.21983, 0.38217, 0.65489, 0.98286, 1.20314, 1.48431, 1.69595, 1.62520, 1.55026, 1.40447, 1.25461, 1.02344, 0.88712, 0.86828, 0.94158, 0.96706, 0.93682, 0.89214, 1.03660, 1.23934, 1.25092, 1.17834, 1.14539, 1.04441, 1.03520, 1.01159, 0.98338, 0.92143, 0.90684, 0.81265, 0.75384, 0.79356, 0.70869, 0.53839, 0.42131, 0.34819, 0.11773, -0.12218, -0.25723, -0.43476, -0.46827, -0.41447, -0.31913, -0.40459, -0.48116, -0.52785, -0.49393, +-0.71786, -0.68473, -0.78974, -0.80122, -0.77978, -0.73475, -0.65925, -0.58559, -0.46804, -0.46150, -0.68616, -1.02761, -1.17986, -1.20535, -1.30869, -1.34465, -1.35406, -1.47192, -1.62256, -1.60496, -1.75048, -2.09311, -2.31422, -2.47817, -2.58300, -2.70201, -2.82137, -2.88564, -2.82842, -2.81326, -2.80498, -2.63582, -2.44816, -2.40707, -2.45783, -2.34614, -2.18712, -2.11081, -2.04268, -2.00818, -1.90581, -1.66723, -1.57143, -1.63382, -1.59152, -1.37482, -1.31350, -1.35871, -1.28645, -1.22011, -1.23909, -1.10463, -0.96014, -0.85487, -0.65607, -0.50786, -0.35999, -0.15234, -0.06721, -0.03161, 0.13332, 0.16933, 0.05158, 0.06284, 0.18289, 0.30433, 0.32748, 0.48789, 0.60934, 0.50471, 0.29781, 0.04005, -0.06930, 0.00251, 0.04227, 0.04250, 0.02306, 0.09637, 0.06470, 0.03938, 0.09098, 0.08909, 0.04288, 0.20878, 0.28546, 0.20525, 0.23918, 0.25628, 0.24170, 0.35788, 0.43666, 0.44393, 0.47112, 0.44923, 0.25562, 0.17106, 0.19570, 0.16866, 0.03298, 0.06649, 0.24564, 0.43834, 0.52598, 0.49297, 0.53780, 0.79199, 0.87943, 0.72627, 0.56265, 0.55570, 0.44367, 0.23204, 0.09239, -0.00953, -0.23812, -0.31144, -0.35781, -0.51850, -0.62877, -0.69314, -0.74573, -0.78583, -0.97896, -1.29329, -1.44168, -1.42114, -1.48832, -1.43579, -1.29924, -1.24927, -1.37438, -1.38355, -1.15683, -0.93591, -0.75282, -0.69346, -0.84162, -0.94031, -1.07431, -1.23420, -1.37756, -1.36460, -1.31623, -1.28888, -1.23765, -1.15316, -1.21958, -1.20565, -1.17940, -1.29670, -1.29295, -1.32145, -1.42417, -1.40456, -1.43216, -1.51582, -1.48700, -1.38977, -1.45116, -1.47442, -1.30728, -1.03352, -0.99769, -0.99723, -0.82144, -0.57681, -0.43173, -0.37585, -0.33452, -0.11427, 0.06430, 0.13547, 0.18865, 0.39598, 0.54487, 0.56062, 0.60126, 0.76009, 0.82450, 1.04214, 1.39672, 1.54077, 1.61693, 1.65406, 1.63757, 1.75718, 1.82130, 1.82937, 1.86639, 1.97359, 1.94172, 1.94923, 2.24496, 2.61953, 2.81732, 2.86855, 2.89162, 2.87016, 2.86122, 2.85006, 2.76274, 2.76803, 2.90064, 2.91173, 2.74382, 2.62895, 2.52371, 2.22702, 1.90348, 1.71269, 1.45675, 1.18047, 0.97593, 0.65745, 0.30999, 0.04737, -0.24746, -0.45857, -0.68750, -1.02191, -1.27368, -1.31457, -1.52349, -1.80239, -1.80316, -1.56405, -1.48180, -1.47619, -1.34777, -1.19712, -1.10894, -1.04145, -1.07484, -1.09385, -1.13086, -1.29507, -1.52370, -1.62376, -1.67284, -1.76328, -1.77061, -1.68922, -1.67332, -1.70386, -1.54125, -1.41734, -1.37094, -1.27310, -1.33691, -1.45840, -1.57766, -1.74689, -1.78200, -1.70145, -1.72439, -1.95386, -2.15652, -2.25337, -2.38603, -2.55225, -2.65406, -2.76325, -2.86769, -3.00915, -3.32852, -3.56018, -3.62792, -3.74482, -3.93853, -3.95652, -3.80820, -3.79162, -3.85927, -3.85889, -3.95353, -4.08274, -3.99356, -3.98695, -4.07336, -4.08064, -4.04598, -3.89811, -3.75199, -3.79232, -3.81313, -3.65625, -3.63769, -3.79846, -3.81333, -3.68894, -3.68082, -3.77973, -3.74598, -3.65509, -3.61736, -3.58482, -3.61269, -3.56686, -3.37641, -3.16547, -3.02696, -2.93122, -2.79416, -2.82101, -2.79310, -2.57687, -2.34655, -2.18284, -1.94135, -1.81874, -1.87437, -1.83383, -1.77543, -1.72321, -1.55662, -1.58544, -1.75291, -1.76175, -1.67838, -1.72634, -1.76308, -1.73872, -1.69422, -1.82611, -1.93469, -1.95467, -1.93520, -1.92971, -1.95592, -1.91201, -1.69387, -1.61401, -1.64282, -1.64049, -1.50622, -1.45052, -1.41998, -1.27588, -1.11073, -1.08005, -0.84629, -0.58408, -0.54908, -0.54039, -0.50813, -0.47319, -0.43023, -0.53623, -0.69531, -0.68791, -0.61330, -0.61409, -0.46296, -0.13388, 0.18467, 0.30607, 0.49676, 0.80388, 1.07778, 1.33264, 1.43873, 1.37328, 1.38917, 1.28324, 1.11746, 0.97013, 0.99778, 0.99731, 0.91995, 0.91639, 0.96280, 0.93131, 1.11674, 1.32779, 1.38267, 1.30294, 1.12395, 0.97692, 1.06818, 1.07855, 0.88283, 0.78385, 0.85340, 0.74413, 0.58743, 0.61195, 0.69712, 0.54641, 0.34855, 0.24845, 0.14164, -0.03287, -0.21034, -0.36001, -0.31418, -0.25545, -0.24272, -0.24804, -0.15776, -0.21134, -0.34432, +-0.78756, -0.79800, -0.86766, -0.95247, -0.91830, -0.82001, -0.80275, -0.61690, -0.51532, -0.61103, -0.85972, -1.08481, -1.13947, -1.23906, -1.32771, -1.32064, -1.37303, -1.52682, -1.67157, -1.62234, -1.72828, -2.12579, -2.39187, -2.49551, -2.66321, -2.81810, -2.86722, -2.90498, -2.84423, -2.85148, -2.81390, -2.70664, -2.61957, -2.52248, -2.45919, -2.35771, -2.27206, -2.17797, -2.16875, -2.01912, -1.88422, -1.79202, -1.78980, -1.80212, -1.68738, -1.60501, -1.59103, -1.59741, -1.54280, -1.47779, -1.46590, -1.31413, -1.13577, -1.05336, -0.87962, -0.61002, -0.41035, -0.17132, -0.00182, 0.02485, 0.13655, 0.11947, 0.04646, 0.08631, 0.19294, 0.40729, 0.47659, 0.59889, 0.57906, 0.46020, 0.16367, -0.00534, -0.03817, -0.06905, -0.06929, -0.03915, 0.01251, -0.03747, -0.10489, -0.04226, 0.02089, -0.01391, -0.07200, 0.08407, 0.17671, 0.09372, 0.13008, 0.28825, 0.30384, 0.36909, 0.50341, 0.52809, 0.57747, 0.58424, 0.47318, 0.41815, 0.30430, 0.27261, 0.15515, 0.18362, 0.23257, 0.40549, 0.38436, 0.42062, 0.56293, 0.70033, 0.73289, 0.59368, 0.54121, 0.47130, 0.32409, 0.17338, 0.04874, -0.06849, -0.27267, -0.29247, -0.24253, -0.33596, -0.47663, -0.48036, -0.56225, -0.72285, -0.87620, -1.15101, -1.22314, -1.17259, -1.23788, -1.18556, -1.23382, -1.24443, -1.38120, -1.37249, -1.25897, -1.00861, -0.87634, -0.78096, -0.82209, -1.00180, -1.14708, -1.25613, -1.26161, -1.32074, -1.37854, -1.34648, -1.31358, -1.27357, -1.31774, -1.26658, -1.23196, -1.35874, -1.43286, -1.40417, -1.43462, -1.44104, -1.35783, -1.38830, -1.36138, -1.26317, -1.30394, -1.26355, -1.21691, -1.01102, -0.98798, -0.92658, -0.86056, -0.62473, -0.54055, -0.48842, -0.32082, -0.14276, -0.00092, 0.05274, 0.21871, 0.38580, 0.42614, 0.46871, 0.55844, 0.70365, 0.74573, 0.92922, 1.22097, 1.34771, 1.37940, 1.52255, 1.70086, 1.81958, 1.92948, 1.96002, 1.95434, 2.02963, 1.98177, 2.04322, 2.22662, 2.52695, 2.71598, 2.79289, 2.67210, 2.60879, 2.57304, 2.55991, 2.60111, 2.54884, 2.57993, 2.52305, 2.44597, 2.34752, 2.18009, 1.93042, 1.63310, 1.38914, 1.09567, 0.82702, 0.64393, 0.39959, 0.06992, -0.13062, -0.29399, -0.50972, -0.67923, -0.94637, -1.21818, -1.31594, -1.57560, -1.80533, -1.91903, -1.80085, -1.72997, -1.66953, -1.60894, -1.45747, -1.35571, -1.32731, -1.23267, -1.26738, -1.39968, -1.58850, -1.66187, -1.66686, -1.80388, -1.90322, -1.90240, -1.84380, -1.80952, -1.74777, -1.46867, -1.27137, -1.26851, -1.20206, -1.21017, -1.40062, -1.55366, -1.68943, -1.74350, -1.67532, -1.71980, -1.91199, -2.19579, -2.38870, -2.45264, -2.48333, -2.58402, -2.71663, -2.79264, -2.97583, -3.13839, -3.28544, -3.36959, -3.47071, -3.56752, -3.52241, -3.50603, -3.51402, -3.53452, -3.52506, -3.60858, -3.73380, -3.64661, -3.61376, -3.72866, -3.76063, -3.64298, -3.56871, -3.49574, -3.51304, -3.58485, -3.48739, -3.52537, -3.66638, -3.71891, -3.68741, -3.64659, -3.68980, -3.67859, -3.67536, -3.62631, -3.64602, -3.51442, -3.37314, -3.28410, -3.14550, -3.00320, -2.83269, -2.79603, -2.78920, -2.61895, -2.38911, -2.19465, -2.05633, -1.84670, -1.72334, -1.81330, -1.80349, -1.63290, -1.57413, -1.46465, -1.46794, -1.66903, -1.69982, -1.61734, -1.60462, -1.64763, -1.76118, -1.72732, -1.83728, -1.94094, -2.03731, -1.95068, -2.00304, -1.96351, -1.86756, -1.77868, -1.73003, -1.69800, -1.52748, -1.43555, -1.41862, -1.33540, -1.19132, -1.06011, -1.04542, -0.84578, -0.62770, -0.63189, -0.66781, -0.55635, -0.52882, -0.59063, -0.68043, -0.84828, -0.84584, -0.80178, -0.79602, -0.63249, -0.43476, -0.10849, 0.08974, 0.38630, 0.62662, 0.92556, 1.06928, 1.17196, 1.20239, 1.15152, 1.10769, 1.07451, 1.10153, 1.08379, 1.01634, 0.97125, 0.96292, 0.95919, 0.91403, 1.10562, 1.32371, 1.36861, 1.20934, 1.07910, 0.96779, 1.00409, 1.08936, 0.90608, 0.77662, 0.79287, 0.66247, 0.54492, 0.47849, 0.59997, 0.50398, 0.36608, 0.14939, 0.06129, -0.13748, -0.24856, -0.20186, -0.17031, -0.13442, -0.11262, 0.02172, 0.07924, -0.06577, -0.20155, +-0.79707, -0.88493, -0.95131, -1.03577, -1.00970, -0.89852, -0.90582, -0.80134, -0.77401, -0.86969, -1.03594, -1.15319, -1.18192, -1.28166, -1.29286, -1.30061, -1.43255, -1.58533, -1.73849, -1.73813, -1.82932, -2.18367, -2.49852, -2.66893, -2.84259, -2.99930, -2.98564, -2.90710, -2.84545, -2.87586, -2.79353, -2.66755, -2.65039, -2.59511, -2.48989, -2.36416, -2.30487, -2.23230, -2.27442, -2.20488, -2.09058, -2.00162, -1.96891, -1.93081, -1.85027, -1.86805, -1.83268, -1.75572, -1.72647, -1.69075, -1.70401, -1.61297, -1.39545, -1.22693, -1.06155, -0.81717, -0.56368, -0.26540, -0.02334, 0.11340, 0.17302, 0.09139, 0.06746, 0.20650, 0.32840, 0.52404, 0.60312, 0.66330, 0.52534, 0.35987, 0.08443, -0.07990, -0.08657, -0.11156, -0.13753, -0.16340, -0.17215, -0.24543, -0.22066, -0.04392, 0.00172, -0.05028, -0.12518, -0.06105, 0.03510, 0.03167, 0.08690, 0.23445, 0.28543, 0.38093, 0.55979, 0.70657, 0.76102, 0.72489, 0.66374, 0.69352, 0.54456, 0.41902, 0.24129, 0.21192, 0.19774, 0.31944, 0.30796, 0.31761, 0.44506, 0.53149, 0.53819, 0.44965, 0.39410, 0.26788, 0.15998, 0.12771, 0.03233, -0.07263, -0.24696, -0.30387, -0.20457, -0.17448, -0.28287, -0.34600, -0.47961, -0.66078, -0.79442, -0.91919, -0.93448, -0.92532, -1.00018, -0.95445, -1.11642, -1.22954, -1.35913, -1.31539, -1.21486, -1.01572, -0.93265, -0.96841, -1.03869, -1.16424, -1.24788, -1.29467, -1.30001, -1.41897, -1.48809, -1.39205, -1.38817, -1.40444, -1.44416, -1.44674, -1.42366, -1.47886, -1.53041, -1.55228, -1.58291, -1.56026, -1.42295, -1.30121, -1.22519, -1.18966, -1.27110, -1.18101, -1.14633, -1.01223, -0.97296, -0.86993, -0.82846, -0.69346, -0.64242, -0.62710, -0.47949, -0.30207, -0.15210, -0.05673, 0.14158, 0.26956, 0.30848, 0.45810, 0.57788, 0.69768, 0.73947, 0.82422, 1.01616, 1.17764, 1.26252, 1.42694, 1.67358, 1.85312, 1.98283, 2.07050, 2.05808, 2.08341, 2.04457, 2.20486, 2.38553, 2.56788, 2.64668, 2.62279, 2.44818, 2.35899, 2.33667, 2.27296, 2.26223, 2.19509, 2.19089, 2.11968, 2.04386, 1.90437, 1.76055, 1.65632, 1.41270, 1.14690, 0.86585, 0.54862, 0.31836, 0.13060, -0.10881, -0.28954, -0.42027, -0.60086, -0.77424, -0.95202, -1.15394, -1.29365, -1.56976, -1.73610, -1.88362, -1.93623, -1.95464, -1.89283, -1.85038, -1.74482, -1.65216, -1.65083, -1.56690, -1.58248, -1.70723, -1.85837, -1.86979, -1.86783, -1.98374, -1.98462, -1.96083, -1.92205, -1.84703, -1.75307, -1.47372, -1.23100, -1.19272, -1.21893, -1.31382, -1.49669, -1.62892, -1.66696, -1.63574, -1.62168, -1.77234, -1.98720, -2.23253, -2.42931, -2.47143, -2.44439, -2.50699, -2.62812, -2.70103, -2.89726, -3.06515, -3.16208, -3.17187, -3.19731, -3.23905, -3.20555, -3.21183, -3.15513, -3.13749, -3.17138, -3.24465, -3.37708, -3.35496, -3.33963, -3.44147, -3.50058, -3.41683, -3.33905, -3.26443, -3.23774, -3.26952, -3.29506, -3.43375, -3.55489, -3.58107, -3.61601, -3.63062, -3.65635, -3.61876, -3.62825, -3.60308, -3.63100, -3.51474, -3.33908, -3.21758, -3.08964, -2.96846, -2.82004, -2.79268, -2.66622, -2.37452, -2.16966, -2.02262, -1.97012, -1.89505, -1.77575, -1.77808, -1.72238, -1.57217, -1.52245, -1.48811, -1.53280, -1.61969, -1.62581, -1.57690, -1.54384, -1.53336, -1.68424, -1.73433, -1.85549, -1.94677, -2.04997, -1.96695, -2.01920, -2.04357, -1.95599, -1.85422, -1.79348, -1.73060, -1.54727, -1.44420, -1.34111, -1.15006, -1.06043, -1.01168, -1.02785, -0.93425, -0.74795, -0.68276, -0.69684, -0.66563, -0.71220, -0.81055, -0.89975, -0.97160, -0.99118, -1.03349, -1.03207, -0.79309, -0.61255, -0.35117, -0.12574, 0.22729, 0.49013, 0.77571, 0.87984, 0.88299, 0.92096, 0.93426, 0.98648, 1.06062, 1.12878, 1.07845, 1.00836, 1.04456, 1.03538, 1.01782, 1.00202, 1.10878, 1.26282, 1.27503, 1.06287, 0.89947, 0.82000, 0.87751, 0.96782, 0.90503, 0.79621, 0.71758, 0.55252, 0.50444, 0.44618, 0.53059, 0.45382, 0.33854, 0.12892, 0.02434, -0.16466, -0.32087, -0.25593, -0.15393, -0.06894, -0.00248, 0.10287, 0.06976, -0.06874, -0.10807, +-0.94756, -0.96334, -0.95276, -1.02174, -1.11647, -1.00685, -0.88182, -0.92083, -1.03029, -1.02998, -1.09416, -1.15646, -1.16561, -1.16867, -1.20145, -1.41755, -1.55425, -1.54694, -1.57198, -1.71616, -1.96566, -2.22581, -2.49595, -2.70470, -2.80295, -2.98762, -3.11308, -3.01742, -2.88046, -2.86200, -2.72812, -2.62789, -2.67560, -2.65547, -2.58176, -2.48751, -2.47213, -2.37123, -2.33153, -2.40280, -2.39469, -2.22010, -2.09861, -2.06277, -2.00563, -1.97242, -1.91784, -1.92801, -1.90653, -1.79049, -1.71550, -1.67875, -1.52089, -1.23983, -1.03789, -0.85697, -0.60386, -0.33923, -0.17274, 0.01212, 0.13443, 0.09938, 0.13337, 0.30505, 0.37101, 0.55281, 0.68217, 0.65751, 0.37447, 0.19398, 0.11877, 0.00216, -0.07204, -0.05777, -0.12559, -0.31645, -0.36144, -0.27176, -0.11372, -0.09463, -0.13101, -0.06113, -0.01151, 0.02107, 0.02694, 0.10863, 0.19976, 0.30261, 0.42000, 0.57252, 0.70763, 0.85915, 0.94761, 0.84946, 0.73092, 0.74949, 0.60711, 0.47960, 0.27020, 0.14273, 0.03675, 0.10311, 0.27242, 0.31960, 0.34937, 0.43439, 0.45297, 0.33910, 0.24048, 0.16268, 0.15516, 0.04665, -0.03775, -0.01134, -0.07580, -0.15942, -0.22171, -0.14643, -0.13985, -0.19843, -0.31538, -0.44652, -0.64992, -0.79453, -0.80863, -0.83434, -0.90497, -0.92769, -1.16918, -1.26868, -1.28396, -1.17133, -1.10949, -1.04108, -0.94922, -1.05921, -1.20105, -1.18782, -1.15135, -1.28474, -1.39648, -1.47567, -1.44495, -1.45864, -1.54248, -1.52257, -1.52018, -1.53290, -1.61574, -1.61207, -1.52407, -1.54526, -1.59017, -1.57568, -1.56064, -1.46699, -1.28708, -1.24177, -1.38978, -1.35230, -1.34651, -1.21039, -1.04642, -0.86632, -0.82443, -0.82195, -0.69840, -0.59840, -0.56537, -0.39629, -0.17377, -0.08785, 0.09041, 0.24374, 0.38419, 0.43784, 0.40640, 0.55222, 0.71077, 0.84300, 0.89667, 1.06242, 1.28764, 1.49579, 1.69968, 1.93901, 2.02711, 2.00328, 2.01878, 2.09899, 2.12348, 2.34685, 2.48166, 2.54359, 2.51751, 2.39326, 2.22403, 2.11757, 2.18459, 2.12934, 1.94783, 1.86592, 1.92955, 1.82435, 1.67957, 1.52323, 1.48554, 1.38562, 1.09897, 0.93626, 0.82821, 0.59774, 0.22307, -0.09982, -0.27275, -0.37610, -0.46041, -0.55344, -0.82278, -1.10991, -1.25219, -1.33746, -1.55600, -1.67586, -1.85819, -2.03861, -2.08029, -2.00268, -2.00299, -2.01794, -1.89035, -1.77674, -1.76584, -1.80869, -1.85433, -2.04151, -2.17628, -2.19419, -2.12613, -2.06336, -2.12168, -2.01964, -1.77834, -1.56919, -1.44621, -1.31696, -1.18755, -1.23612, -1.41486, -1.51703, -1.63777, -1.71795, -1.65373, -1.65739, -1.91157, -2.15399, -2.30890, -2.41116, -2.37328, -2.34595, -2.41773, -2.55307, -2.55958, -2.60227, -2.80996, -2.93318, -2.83758, -2.81992, -2.90014, -2.85433, -2.70565, -2.62076, -2.78891, -2.94921, -2.96760, -2.97599, -3.01651, -3.14627, -3.22792, -3.24637, -3.18715, -3.02830, -2.93680, -2.97634, -3.00909, -3.09323, -3.29196, -3.41895, -3.48110, -3.57260, -3.57095, -3.53903, -3.47790, -3.53314, -3.52773, -3.48720, -3.49747, -3.38941, -3.12837, -2.95276, -2.90451, -2.76156, -2.57915, -2.36326, -2.25548, -2.11600, -1.88953, -1.80748, -1.85046, -1.84604, -1.71779, -1.52277, -1.40747, -1.37085, -1.46073, -1.64033, -1.62702, -1.49452, -1.45728, -1.50308, -1.52707, -1.67875, -1.71636, -1.78896, -1.87095, -2.01490, -1.98334, -1.91790, -1.97259, -1.93482, -1.71651, -1.62163, -1.67864, -1.62952, -1.44507, -1.17981, -1.06149, -1.06700, -1.01514, -0.97214, -0.94979, -0.89627, -0.73531, -0.62256, -0.62492, -0.72369, -0.84174, -1.03227, -1.13722, -1.13534, -1.20203, -1.20420, -0.95446, -0.79540, -0.56308, -0.35590, -0.06496, 0.18405, 0.46121, 0.69225, 0.70773, 0.70932, 0.85749, 0.99457, 0.98304, 1.01287, 1.04591, 1.06737, 0.99715, 0.94766, 1.06302, 1.19263, 1.24958, 1.16735, 1.05224, 0.88769, 0.80020, 0.80479, 0.87769, 0.81044, 0.72619, 0.72728, 0.66789, 0.50063, 0.46317, 0.38706, 0.43598, 0.40558, 0.31534, 0.16019, 0.04565, -0.03241, -0.19649, -0.31724, -0.18099, 0.02649, 0.06956, 0.04653, -0.03639, -0.06529, -0.18272, +-1.22362, -1.24859, -1.16717, -1.16501, -1.27370, -1.23434, -1.08487, -1.07584, -1.23082, -1.25983, -1.18720, -1.10293, -1.15092, -1.22642, -1.27818, -1.48083, -1.55890, -1.51592, -1.49245, -1.65922, -1.93081, -2.15502, -2.40763, -2.61667, -2.72775, -2.91637, -3.05485, -2.97492, -2.84730, -2.81722, -2.69559, -2.64862, -2.78759, -2.89977, -2.88960, -2.78408, -2.71547, -2.58728, -2.53356, -2.57496, -2.63784, -2.59337, -2.41600, -2.22797, -2.13774, -2.10554, -2.00485, -1.96404, -1.92989, -1.83225, -1.71939, -1.61553, -1.43284, -1.16206, -1.00675, -0.88116, -0.71954, -0.50665, -0.31800, -0.09222, 0.02947, 0.02938, 0.11634, 0.31695, 0.29300, 0.34120, 0.47531, 0.48114, 0.25093, 0.11440, 0.09076, 0.07024, -0.06071, -0.18314, -0.24182, -0.28273, -0.23580, -0.13533, 0.04680, 0.02470, -0.05551, 0.02684, 0.14763, 0.28203, 0.35282, 0.49113, 0.53788, 0.58042, 0.66996, 0.80656, 0.93699, 1.07890, 1.12228, 0.94762, 0.77463, 0.78662, 0.65135, 0.45833, 0.22939, 0.08630, -0.03801, -0.02267, 0.12178, 0.24680, 0.28656, 0.28789, 0.34576, 0.40204, 0.34244, 0.20447, 0.19737, 0.11763, 0.03506, 0.01713, -0.04338, -0.08245, -0.16268, -0.04415, -0.00467, -0.05735, -0.20307, -0.35675, -0.55113, -0.68713, -0.80593, -0.91403, -0.97321, -0.96837, -1.15419, -1.27543, -1.24637, -1.10092, -1.07894, -1.06516, -1.05159, -1.09769, -1.14631, -1.16567, -1.10676, -1.15578, -1.28263, -1.42910, -1.41980, -1.43926, -1.53832, -1.57390, -1.62915, -1.62293, -1.67474, -1.60152, -1.51083, -1.56662, -1.64883, -1.71126, -1.72917, -1.58617, -1.38595, -1.35588, -1.52807, -1.52311, -1.54825, -1.53820, -1.37758, -1.12117, -0.98373, -0.89415, -0.74720, -0.56685, -0.50970, -0.45583, -0.26207, -0.04422, 0.16509, 0.22101, 0.31803, 0.35147, 0.28200, 0.39978, 0.57735, 0.76937, 0.83782, 1.07360, 1.33890, 1.53168, 1.63661, 1.81002, 1.92914, 1.99412, 2.08152, 2.19134, 2.25539, 2.46987, 2.52421, 2.41045, 2.26067, 2.14474, 2.07133, 2.04926, 2.09322, 2.00175, 1.80405, 1.63806, 1.65863, 1.66347, 1.58793, 1.37573, 1.27705, 1.19140, 0.97027, 0.84935, 0.76113, 0.57462, 0.20389, -0.13911, -0.33025, -0.41198, -0.47201, -0.56785, -0.84444, -1.10111, -1.24842, -1.38984, -1.59712, -1.67568, -1.81342, -2.04715, -2.14769, -2.07950, -2.08737, -2.11389, -2.03557, -1.92347, -1.91360, -2.06771, -2.18472, -2.30547, -2.39355, -2.43669, -2.35608, -2.24715, -2.26428, -2.13011, -1.86150, -1.62599, -1.55603, -1.42920, -1.27319, -1.30861, -1.48318, -1.60407, -1.72211, -1.78751, -1.75896, -1.81956, -2.08032, -2.21683, -2.21136, -2.25821, -2.25793, -2.26943, -2.31537, -2.37226, -2.34121, -2.32093, -2.42501, -2.56816, -2.55773, -2.47399, -2.43447, -2.40197, -2.32300, -2.27895, -2.48861, -2.74482, -2.82140, -2.78088, -2.75851, -2.85571, -2.92408, -2.94199, -2.91492, -2.82005, -2.74303, -2.74254, -2.72880, -2.83408, -3.06116, -3.20204, -3.28524, -3.44140, -3.52325, -3.49493, -3.43456, -3.49518, -3.51443, -3.52056, -3.52493, -3.44217, -3.23432, -2.99413, -2.81446, -2.63692, -2.46437, -2.26195, -2.22876, -2.13816, -1.93812, -1.81676, -1.79047, -1.75932, -1.59125, -1.41396, -1.36766, -1.39888, -1.52785, -1.61128, -1.44738, -1.25985, -1.25823, -1.37970, -1.42814, -1.58803, -1.69381, -1.74215, -1.76474, -1.87391, -1.86748, -1.82241, -1.80890, -1.77965, -1.68003, -1.59176, -1.56152, -1.56614, -1.43836, -1.11857, -0.94321, -0.95391, -0.97090, -0.95296, -0.94425, -0.93816, -0.74109, -0.59332, -0.56368, -0.66935, -0.81345, -0.99699, -1.07811, -1.10765, -1.20624, -1.22725, -1.02660, -0.93609, -0.83833, -0.70998, -0.45533, -0.17965, 0.14032, 0.37685, 0.48800, 0.56352, 0.67007, 0.80064, 0.86800, 0.93174, 0.95362, 1.03367, 1.02556, 0.99412, 1.09090, 1.19142, 1.22007, 1.06564, 0.93441, 0.82374, 0.81219, 0.83954, 0.85244, 0.73477, 0.72073, 0.78621, 0.75648, 0.62350, 0.60395, 0.49928, 0.39627, 0.31667, 0.25232, 0.14737, 0.06450, -0.03248, -0.16952, -0.33683, -0.31929, -0.10801, 0.07599, 0.06907, -0.10846, -0.16260, -0.30875, +-1.47978, -1.53631, -1.46460, -1.33869, -1.34272, -1.46165, -1.43983, -1.34536, -1.35252, -1.37997, -1.37054, -1.25664, -1.28337, -1.41777, -1.45085, -1.54664, -1.51463, -1.48704, -1.54513, -1.66774, -1.90234, -2.19614, -2.43886, -2.65312, -2.76393, -2.90221, -3.03462, -3.00868, -2.89800, -2.83060, -2.82372, -2.84228, -2.98249, -3.14158, -3.16818, -2.99391, -2.81688, -2.80155, -2.83072, -2.79271, -2.77467, -2.81591, -2.78630, -2.57095, -2.37725, -2.30681, -2.15030, -2.02866, -1.92744, -1.80386, -1.73589, -1.57487, -1.38967, -1.28229, -1.19118, -1.08244, -0.93820, -0.66871, -0.48860, -0.32692, -0.26217, -0.19314, -0.10228, 0.13542, 0.16779, 0.18554, 0.28178, 0.36282, 0.32738, 0.11755, -0.02401, -0.02702, -0.10955, -0.22414, -0.31322, -0.23167, -0.02308, 0.06635, 0.21691, 0.24425, 0.20650, 0.33003, 0.41344, 0.60648, 0.75716, 0.82730, 0.82180, 0.84654, 0.87679, 1.02523, 1.06695, 1.09862, 1.07631, 0.97719, 0.81667, 0.83649, 0.76105, 0.57957, 0.36366, 0.24357, 0.21339, 0.04677, -0.04671, 0.05380, 0.17911, 0.25427, 0.28731, 0.37300, 0.42261, 0.29455, 0.25645, 0.23513, 0.14174, 0.09682, -0.04682, -0.07374, -0.06260, 0.02841, 0.03231, -0.01868, -0.25816, -0.40220, -0.61875, -0.80289, -1.00021, -1.05716, -1.10855, -1.05443, -1.07393, -1.14129, -1.12052, -1.04495, -0.98807, -1.06862, -1.21352, -1.22272, -1.13517, -1.09662, -1.09545, -1.15869, -1.21777, -1.38222, -1.45752, -1.45896, -1.55179, -1.56120, -1.69243, -1.70975, -1.68958, -1.67693, -1.71888, -1.80312, -1.92767, -1.91362, -1.88181, -1.73849, -1.60707, -1.51667, -1.65700, -1.68597, -1.69179, -1.76496, -1.67858, -1.43856, -1.12329, -0.93809, -0.88386, -0.73646, -0.59367, -0.47799, -0.34694, -0.17484, 0.05140, 0.07127, 0.09763, 0.18728, 0.19872, 0.41082, 0.54709, 0.67484, 0.76204, 0.95622, 1.14272, 1.34142, 1.38330, 1.58460, 1.74286, 1.88795, 2.01793, 2.21071, 2.31168, 2.43268, 2.45874, 2.31040, 2.13014, 2.01789, 2.08330, 2.09784, 1.97762, 1.79840, 1.67311, 1.58449, 1.55115, 1.50073, 1.49026, 1.31805, 1.15498, 1.10924, 0.96604, 0.91367, 0.74836, 0.48011, 0.17435, -0.14523, -0.39101, -0.45478, -0.54821, -0.59397, -0.80506, -1.04371, -1.27138, -1.47063, -1.67342, -1.76819, -1.80733, -1.94629, -2.05666, -2.07241, -2.03659, -2.03829, -2.16198, -2.20636, -2.20918, -2.33263, -2.47887, -2.62716, -2.60577, -2.55256, -2.51202, -2.40592, -2.40388, -2.22532, -1.98381, -1.82480, -1.71277, -1.57091, -1.50553, -1.50156, -1.65538, -1.77564, -1.88251, -2.00764, -2.07734, -2.12154, -2.23039, -2.24283, -2.09096, -2.05330, -2.06283, -2.12133, -2.09768, -2.05176, -2.15016, -2.21771, -2.21630, -2.23244, -2.22794, -2.21139, -2.12757, -2.07624, -2.13589, -2.15307, -2.31588, -2.50096, -2.55526, -2.58156, -2.51160, -2.54104, -2.66294, -2.68211, -2.69399, -2.69623, -2.62903, -2.64111, -2.64908, -2.73059, -2.88679, -3.07493, -3.15732, -3.28154, -3.39971, -3.43959, -3.40861, -3.41944, -3.58562, -3.71728, -3.64403, -3.44881, -3.24173, -3.09169, -2.90286, -2.64664, -2.49498, -2.30775, -2.22737, -2.11433, -1.91797, -1.83085, -1.73313, -1.66539, -1.63215, -1.57218, -1.57904, -1.63103, -1.63084, -1.59231, -1.38912, -1.20312, -1.11140, -1.24498, -1.29159, -1.40138, -1.52731, -1.59087, -1.57003, -1.54541, -1.63927, -1.72989, -1.68426, -1.61120, -1.57403, -1.59713, -1.55488, -1.45165, -1.30311, -0.99766, -0.74817, -0.70230, -0.69984, -0.79252, -0.85489, -0.90681, -0.84928, -0.76121, -0.67875, -0.76480, -0.83561, -1.02030, -1.13025, -1.19894, -1.21252, -1.25368, -1.14007, -1.06629, -1.02488, -0.93962, -0.68697, -0.29906, -0.05949, 0.01574, 0.13321, 0.33528, 0.51819, 0.60315, 0.68158, 0.84179, 0.89294, 0.99835, 1.09424, 1.08717, 1.17239, 1.11401, 1.06098, 0.93619, 0.77290, 0.66082, 0.69053, 0.67842, 0.75702, 0.66880, 0.68347, 0.75459, 0.84244, 0.75791, 0.72276, 0.64674, 0.48922, 0.34711, 0.23205, 0.18910, 0.02369, -0.23014, -0.37751, -0.43290, -0.34586, -0.21303, -0.06192, 0.02510, -0.12262, -0.23700, -0.38928, +-1.83048, -1.80560, -1.76629, -1.65170, -1.56150, -1.65070, -1.65115, -1.52959, -1.48771, -1.50661, -1.59528, -1.60248, -1.58844, -1.61085, -1.65802, -1.74069, -1.67938, -1.69286, -1.78024, -1.87405, -2.04656, -2.30688, -2.47969, -2.60952, -2.73864, -2.90026, -3.02556, -3.00737, -2.97189, -2.98613, -3.04151, -3.15890, -3.26668, -3.33474, -3.36989, -3.26461, -3.08534, -3.04260, -3.02185, -2.88733, -2.84231, -2.93627, -3.02674, -2.89704, -2.62972, -2.44069, -2.31548, -2.27123, -2.12193, -1.94585, -1.86373, -1.71296, -1.57112, -1.48611, -1.36577, -1.19570, -1.07305, -0.86656, -0.70837, -0.56831, -0.58512, -0.59738, -0.47512, -0.20547, -0.05398, 0.07828, 0.11835, 0.13515, 0.19818, 0.08692, -0.03894, -0.03669, -0.12675, -0.19616, -0.21767, -0.08278, 0.21461, 0.37942, 0.47140, 0.40672, 0.40178, 0.54118, 0.64438, 0.88278, 1.06233, 1.14730, 1.11771, 1.16221, 1.15350, 1.22761, 1.21481, 1.20141, 1.11447, 0.93286, 0.83201, 0.83625, 0.78221, 0.71609, 0.52688, 0.35442, 0.33252, 0.15653, -0.00920, 0.11090, 0.22601, 0.27997, 0.29402, 0.31293, 0.43877, 0.45903, 0.40419, 0.23771, 0.09516, 0.04021, -0.10080, -0.11309, -0.07802, 0.03827, 0.04389, 0.03234, -0.25613, -0.48502, -0.71196, -0.84660, -1.03700, -1.22818, -1.31016, -1.23833, -1.13345, -1.02935, -1.03007, -1.15834, -1.18830, -1.21969, -1.30448, -1.18413, -1.08705, -1.11102, -1.14271, -1.26777, -1.30834, -1.39752, -1.49068, -1.61427, -1.71697, -1.71671, -1.87632, -1.89879, -1.85349, -1.80762, -1.88582, -1.94391, -2.06613, -2.06582, -1.97006, -1.79002, -1.71434, -1.79034, -1.94055, -1.97547, -1.97785, -1.98007, -1.91422, -1.76053, -1.44061, -1.16430, -1.06488, -0.84452, -0.65889, -0.55674, -0.46484, -0.41754, -0.24848, -0.13117, -0.05291, -0.03871, 0.00343, 0.25148, 0.37215, 0.46184, 0.51326, 0.72269, 0.91559, 1.20775, 1.28222, 1.39012, 1.51652, 1.75634, 1.98221, 2.09139, 2.14178, 2.17130, 2.17035, 2.16584, 2.10149, 1.97092, 1.97422, 1.98176, 1.87030, 1.77627, 1.69923, 1.59226, 1.56190, 1.46453, 1.44432, 1.35993, 1.20866, 1.05405, 0.91006, 0.89967, 0.70193, 0.39874, 0.09103, -0.15749, -0.34118, -0.35221, -0.46090, -0.59417, -0.79723, -0.96245, -1.17753, -1.52935, -1.81007, -1.88794, -1.89252, -1.89450, -1.93962, -2.05575, -2.10994, -2.12607, -2.28769, -2.36193, -2.39526, -2.53064, -2.64727, -2.80263, -2.76789, -2.61938, -2.52881, -2.54557, -2.63344, -2.45326, -2.22132, -2.03624, -1.90131, -1.76914, -1.72927, -1.64909, -1.72106, -1.90692, -2.09486, -2.26286, -2.32106, -2.37806, -2.40446, -2.27713, -2.10184, -1.99634, -1.92552, -2.01869, -2.07842, -2.03286, -2.07428, -2.05532, -1.96478, -1.96782, -1.99573, -2.04162, -1.99916, -1.89676, -1.93787, -2.06037, -2.28849, -2.38573, -2.36737, -2.39956, -2.36572, -2.40056, -2.47330, -2.41904, -2.38862, -2.49753, -2.52112, -2.52456, -2.51788, -2.66642, -2.91553, -3.10479, -3.19518, -3.25878, -3.30085, -3.42497, -3.54697, -3.56830, -3.68553, -3.76863, -3.62109, -3.43667, -3.27181, -3.19165, -3.07925, -2.75659, -2.48844, -2.29426, -2.29598, -2.21660, -2.05735, -1.94987, -1.81655, -1.77529, -1.81080, -1.82859, -1.79682, -1.82349, -1.74074, -1.57547, -1.32962, -1.19253, -1.16100, -1.22178, -1.27008, -1.33385, -1.31601, -1.35344, -1.41154, -1.39657, -1.46404, -1.52469, -1.38232, -1.30913, -1.34890, -1.44137, -1.47628, -1.27810, -0.97757, -0.71276, -0.62594, -0.60808, -0.59508, -0.70438, -0.81964, -0.96651, -0.95424, -0.87259, -0.72873, -0.82546, -0.94846, -1.11164, -1.16798, -1.24841, -1.35925, -1.40192, -1.34543, -1.25787, -1.10531, -1.01958, -0.88618, -0.55927, -0.31027, -0.23572, -0.02527, 0.23945, 0.45104, 0.58649, 0.61502, 0.77166, 0.91497, 1.05547, 1.05431, 1.00791, 1.02519, 0.86891, 0.79162, 0.68768, 0.62524, 0.56204, 0.62423, 0.57556, 0.62333, 0.60558, 0.69576, 0.79403, 0.83451, 0.80737, 0.75094, 0.63268, 0.52151, 0.35499, 0.12414, 0.01407, -0.16001, -0.41034, -0.46499, -0.43911, -0.34845, -0.26993, -0.25646, -0.17754, -0.17696, -0.24123, -0.52993, +-2.09281, -2.03847, -1.87463, -1.75576, -1.70340, -1.74622, -1.85479, -1.80215, -1.76090, -1.83037, -1.91770, -1.93534, -1.94350, -1.85619, -1.76689, -1.82275, -1.84701, -1.95476, -2.04785, -2.11809, -2.30381, -2.52277, -2.70169, -2.79233, -2.91351, -3.03438, -3.14832, -3.23300, -3.21700, -3.13350, -3.10838, -3.31535, -3.46722, -3.56309, -3.50267, -3.42310, -3.38238, -3.31149, -3.28253, -3.10578, -2.98210, -3.08223, -3.13375, -2.96401, -2.76632, -2.62997, -2.48083, -2.43987, -2.24584, -2.02370, -1.91932, -1.82360, -1.79361, -1.65121, -1.48683, -1.31006, -1.20261, -1.04760, -0.90651, -0.90141, -0.93855, -0.85421, -0.62169, -0.36453, -0.15501, -0.06031, 0.00475, 0.04130, 0.03512, 0.01281, -0.10186, -0.14212, -0.12026, -0.11475, 0.01871, 0.28290, 0.47648, 0.53646, 0.65302, 0.62213, 0.65225, 0.76940, 0.87951, 1.13071, 1.23406, 1.29688, 1.22769, 1.21435, 1.21920, 1.31313, 1.38253, 1.26647, 1.13072, 0.98962, 1.00047, 0.91034, 0.80754, 0.66939, 0.55758, 0.51542, 0.43032, 0.31167, 0.16742, 0.22444, 0.33642, 0.27495, 0.26539, 0.36469, 0.51676, 0.52641, 0.51608, 0.31602, 0.16148, 0.16125, 0.07205, 0.07816, 0.02084, 0.05908, 0.04853, -0.02642, -0.28406, -0.51459, -0.66999, -0.83520, -1.01884, -1.24461, -1.28835, -1.29223, -1.17792, -1.11201, -1.13838, -1.24546, -1.36590, -1.33915, -1.30005, -1.22069, -1.19827, -1.35768, -1.41860, -1.42697, -1.46081, -1.66285, -1.72945, -1.82550, -1.91481, -1.90669, -2.07429, -2.06517, -2.04356, -1.98788, -2.00013, -2.10489, -2.20309, -2.21470, -2.03057, -1.93537, -1.96890, -2.14189, -2.19553, -2.22491, -2.21667, -2.21952, -2.12621, -1.84862, -1.62504, -1.40958, -1.25397, -1.06054, -0.81683, -0.74655, -0.71041, -0.63975, -0.46551, -0.34837, -0.16011, -0.07144, -0.01870, 0.19473, 0.27695, 0.36255, 0.36765, 0.53952, 0.77648, 1.06856, 1.18964, 1.19386, 1.31916, 1.52512, 1.72943, 1.80826, 1.92909, 1.94745, 1.99307, 2.06313, 2.10285, 2.09252, 1.91555, 1.77994, 1.73216, 1.66714, 1.63545, 1.48938, 1.44191, 1.45232, 1.47249, 1.29904, 1.14578, 1.02936, 0.91721, 0.96428, 0.79112, 0.50992, 0.15002, -0.14578, -0.27737, -0.35896, -0.50915, -0.74839, -0.88263, -0.98607, -1.22008, -1.58137, -1.75574, -1.77548, -1.82364, -1.87442, -1.95163, -1.97367, -2.08776, -2.22628, -2.37760, -2.53510, -2.56623, -2.62695, -2.70767, -2.74193, -2.66094, -2.62548, -2.55637, -2.55520, -2.64449, -2.45936, -2.24557, -1.98869, -1.87023, -1.87776, -1.87427, -1.84412, -1.90249, -2.14593, -2.34206, -2.47854, -2.52564, -2.51050, -2.33265, -2.12611, -2.09834, -2.08413, -2.05073, -2.01032, -2.10220, -2.20312, -2.16328, -2.09708, -1.98279, -1.97293, -2.06650, -2.05574, -1.93061, -1.84472, -1.86229, -1.92339, -2.13169, -2.16751, -2.12118, -2.15140, -2.20369, -2.38002, -2.40457, -2.31098, -2.24805, -2.36289, -2.36833, -2.33697, -2.45972, -2.70424, -2.91778, -3.01749, -3.14084, -3.21187, -3.31163, -3.39560, -3.50426, -3.58685, -3.61306, -3.66259, -3.56913, -3.42765, -3.36115, -3.25747, -3.05149, -2.75088, -2.49000, -2.17796, -2.18113, -2.17953, -2.10743, -2.01213, -1.89926, -1.99241, -2.09681, -2.13519, -2.05666, -1.99444, -1.79484, -1.56266, -1.47721, -1.40453, -1.27989, -1.13908, -1.21625, -1.29186, -1.27442, -1.20056, -1.19964, -1.32442, -1.37070, -1.36977, -1.20337, -1.04011, -1.11634, -1.19989, -1.17106, -0.98973, -0.75006, -0.48695, -0.49562, -0.55849, -0.54913, -0.62846, -0.73261, -0.97304, -0.99773, -0.91672, -0.85774, -0.99919, -1.15260, -1.22578, -1.32370, -1.41885, -1.50698, -1.43053, -1.37877, -1.23644, -1.09754, -0.96632, -0.81561, -0.69224, -0.47998, -0.34649, -0.10660, 0.24898, 0.45507, 0.67869, 0.79702, 0.86667, 0.87012, 1.03183, 1.01465, 0.90924, 0.86293, 0.71145, 0.71587, 0.60538, 0.57562, 0.49159, 0.40705, 0.32545, 0.38018, 0.52274, 0.57574, 0.64129, 0.71891, 0.84878, 0.74546, 0.54199, 0.32974, 0.16875, 0.04608, -0.14795, -0.33466, -0.52086, -0.59862, -0.51587, -0.48814, -0.47309, -0.45958, -0.41622, -0.43865, -0.38704, -0.60060, +-2.11909, -2.02415, -1.85193, -1.74262, -1.70466, -1.80812, -2.05266, -2.11346, -2.03294, -2.05910, -2.24122, -2.32715, -2.26188, -2.08352, -1.87373, -1.89579, -2.07925, -2.27053, -2.37603, -2.42015, -2.52371, -2.69346, -2.97676, -3.15605, -3.25322, -3.37854, -3.50549, -3.57857, -3.50867, -3.35910, -3.27459, -3.42766, -3.58971, -3.69384, -3.65633, -3.60344, -3.55026, -3.46733, -3.45882, -3.30830, -3.08857, -3.05613, -3.13474, -3.06388, -2.88864, -2.74920, -2.54224, -2.40917, -2.24238, -2.04586, -1.94935, -1.90083, -1.85326, -1.63761, -1.52415, -1.44756, -1.33902, -1.24390, -1.16991, -1.20128, -1.19443, -1.01971, -0.75174, -0.42649, -0.20843, -0.11778, -0.03931, 0.00832, 0.04052, 0.05495, -0.08276, -0.15750, 0.00898, 0.20493, 0.36336, 0.50746, 0.61155, 0.65615, 0.81247, 0.90741, 0.91669, 0.94855, 1.01599, 1.19656, 1.28592, 1.37162, 1.24742, 1.12468, 1.15912, 1.27479, 1.35948, 1.24404, 1.12563, 1.03645, 1.02307, 0.94766, 0.83705, 0.71120, 0.66275, 0.67874, 0.64684, 0.58090, 0.42335, 0.37571, 0.48580, 0.50534, 0.46443, 0.45648, 0.60945, 0.66047, 0.68257, 0.58364, 0.42042, 0.38866, 0.31853, 0.28709, 0.20789, 0.24492, 0.17940, -0.04220, -0.26833, -0.46984, -0.64251, -0.81811, -1.00139, -1.19821, -1.26820, -1.25351, -1.15630, -1.11845, -1.16921, -1.27522, -1.33850, -1.26604, -1.23276, -1.31299, -1.39542, -1.49804, -1.57563, -1.67882, -1.74285, -1.95666, -2.03499, -2.03197, -2.11797, -2.16974, -2.29911, -2.27014, -2.21345, -2.07606, -2.05796, -2.29318, -2.39708, -2.41549, -2.29498, -2.26435, -2.32674, -2.45658, -2.48052, -2.43043, -2.37124, -2.31633, -2.16201, -1.85235, -1.61010, -1.38429, -1.23719, -1.13385, -0.90065, -0.73172, -0.70577, -0.76979, -0.62504, -0.43668, -0.18888, 0.03868, 0.09873, 0.19173, 0.23986, 0.28707, 0.30273, 0.53426, 0.77757, 0.92833, 1.00358, 0.97487, 1.04141, 1.19192, 1.38163, 1.51201, 1.65358, 1.78123, 1.96446, 2.12420, 2.23552, 2.19862, 1.94637, 1.78409, 1.72714, 1.60360, 1.54756, 1.48276, 1.45107, 1.35691, 1.31714, 1.15111, 1.02950, 1.04413, 0.97880, 0.96936, 0.80726, 0.51223, 0.13851, -0.13166, -0.27815, -0.51530, -0.72304, -0.94457, -1.05939, -1.15107, -1.35390, -1.62140, -1.73657, -1.69131, -1.69006, -1.73468, -1.79590, -1.81247, -1.93249, -2.08151, -2.27106, -2.53509, -2.59816, -2.51787, -2.50118, -2.58810, -2.59098, -2.58987, -2.52657, -2.44499, -2.47362, -2.36649, -2.20052, -1.96185, -1.88235, -1.89646, -1.89902, -2.00441, -2.13704, -2.36289, -2.56394, -2.66116, -2.62080, -2.50154, -2.25431, -2.07553, -2.10098, -2.14003, -2.11471, -2.04817, -2.14383, -2.25871, -2.24063, -2.24104, -2.18351, -2.09793, -2.09184, -2.11115, -2.05164, -1.93169, -1.87740, -1.82720, -1.93041, -2.01474, -2.02702, -2.07938, -2.17170, -2.32629, -2.28476, -2.24909, -2.24394, -2.30310, -2.30506, -2.29792, -2.44433, -2.67454, -2.83301, -2.88643, -2.92763, -2.97903, -3.07381, -3.15155, -3.23473, -3.26495, -3.28013, -3.39078, -3.42604, -3.29985, -3.18034, -3.12755, -3.00359, -2.71216, -2.43997, -2.08034, -2.03548, -2.14372, -2.18709, -2.13567, -2.07361, -2.17419, -2.25107, -2.30316, -2.26231, -2.13148, -1.91416, -1.75799, -1.74432, -1.65082, -1.41090, -1.16454, -1.13500, -1.18647, -1.15845, -1.06234, -1.05504, -1.16451, -1.17912, -1.17718, -1.07185, -0.83867, -0.77920, -0.88771, -0.98585, -0.87234, -0.68539, -0.44670, -0.41213, -0.54582, -0.60509, -0.67322, -0.78320, -0.98603, -0.95808, -0.91713, -1.00276, -1.14582, -1.30003, -1.38628, -1.48299, -1.54824, -1.55280, -1.42837, -1.25389, -1.04175, -0.88323, -0.74211, -0.63291, -0.55374, -0.35706, -0.23141, -0.04404, 0.34594, 0.67551, 0.90124, 0.87627, 0.86073, 0.81893, 0.95157, 1.00830, 0.85366, 0.72430, 0.63940, 0.69381, 0.63027, 0.64909, 0.47439, 0.18458, 0.08925, 0.17804, 0.34599, 0.38698, 0.44072, 0.55987, 0.68716, 0.61885, 0.40769, 0.19705, 0.06052, -0.05304, -0.21558, -0.36794, -0.56445, -0.74902, -0.71556, -0.63521, -0.64742, -0.77253, -0.76192, -0.72379, -0.60371, -0.64079, +-2.20270, -2.06340, -1.92290, -1.85646, -1.82955, -2.05638, -2.28081, -2.32734, -2.31537, -2.34593, -2.44689, -2.55425, -2.47934, -2.21955, -2.05876, -2.15261, -2.42795, -2.54354, -2.62402, -2.68190, -2.78024, -2.93384, -3.20588, -3.38813, -3.40251, -3.60617, -3.76950, -3.75362, -3.66618, -3.56875, -3.54500, -3.68080, -3.85723, -3.93909, -3.93123, -3.90176, -3.74286, -3.64075, -3.53417, -3.29220, -3.11698, -3.07020, -3.07248, -3.03586, -2.92341, -2.67614, -2.46627, -2.36125, -2.24381, -1.99948, -1.87527, -1.89651, -1.87713, -1.71779, -1.60719, -1.53591, -1.34639, -1.33434, -1.35410, -1.33602, -1.30440, -1.14877, -0.92958, -0.60108, -0.43084, -0.32399, -0.18679, -0.12188, 0.03110, 0.05807, -0.04037, 0.02528, 0.19972, 0.42011, 0.63855, 0.75924, 0.76306, 0.89814, 1.04431, 1.09832, 1.06108, 1.10374, 1.18365, 1.22949, 1.28591, 1.31972, 1.25134, 1.15756, 1.28106, 1.34652, 1.33610, 1.28076, 1.19880, 1.07901, 0.96070, 0.86583, 0.75946, 0.69774, 0.75323, 0.76457, 0.81741, 0.75245, 0.57581, 0.61258, 0.67547, 0.71350, 0.74188, 0.76969, 0.82649, 0.95544, 0.97884, 0.83585, 0.62687, 0.56875, 0.55115, 0.41881, 0.33777, 0.31505, 0.27727, 0.05372, -0.07913, -0.27825, -0.54661, -0.70674, -0.90530, -1.13706, -1.27521, -1.27837, -1.20935, -1.20854, -1.24167, -1.38320, -1.37104, -1.29554, -1.32760, -1.35983, -1.51697, -1.64965, -1.70280, -1.75539, -1.92603, -2.08459, -2.17642, -2.25126, -2.36442, -2.41326, -2.39401, -2.39506, -2.31766, -2.24623, -2.20622, -2.44474, -2.47852, -2.50180, -2.54212, -2.53216, -2.55706, -2.64287, -2.68190, -2.63123, -2.55167, -2.48164, -2.24472, -1.95175, -1.62807, -1.31790, -1.19002, -0.98914, -0.78921, -0.67007, -0.63937, -0.63938, -0.60520, -0.39191, -0.11851, 0.05482, 0.08074, 0.11435, 0.24032, 0.21852, 0.24271, 0.42398, 0.69036, 0.81042, 0.89140, 0.88879, 0.84249, 0.96204, 1.18233, 1.31961, 1.42050, 1.58573, 1.85219, 2.03735, 2.22070, 2.14194, 1.91571, 1.81241, 1.69929, 1.65544, 1.59440, 1.48062, 1.43175, 1.39303, 1.26051, 1.11901, 1.08280, 1.06643, 0.95148, 0.84794, 0.74933, 0.41299, 0.03793, -0.29478, -0.46210, -0.69848, -0.83435, -0.91212, -1.06700, -1.18687, -1.33622, -1.58374, -1.74524, -1.72942, -1.67958, -1.69288, -1.67635, -1.71123, -1.82989, -1.92600, -2.17895, -2.38746, -2.44177, -2.42528, -2.40647, -2.41045, -2.48010, -2.50201, -2.38435, -2.35117, -2.41856, -2.39023, -2.16658, -1.97436, -1.96639, -2.02523, -2.02078, -2.10653, -2.19735, -2.31182, -2.56653, -2.67152, -2.53575, -2.39702, -2.22642, -2.15246, -2.20475, -2.28753, -2.24168, -2.18468, -2.28042, -2.32096, -2.37204, -2.35466, -2.24943, -2.19511, -2.13945, -2.05653, -2.03798, -1.97144, -1.82926, -1.77989, -1.88763, -2.03746, -2.01690, -2.04857, -2.16472, -2.27774, -2.21033, -2.14955, -2.12522, -2.08398, -2.16644, -2.23331, -2.29715, -2.46468, -2.62393, -2.70566, -2.70603, -2.74961, -2.79577, -2.85133, -2.96599, -2.94122, -3.01651, -3.14388, -3.14350, -3.10587, -3.01529, -2.91183, -2.80697, -2.60677, -2.28410, -2.01069, -2.08300, -2.28562, -2.31619, -2.23297, -2.24429, -2.34150, -2.42864, -2.40188, -2.32293, -2.09845, -1.96278, -1.92746, -1.86402, -1.72395, -1.46458, -1.21966, -1.12023, -1.14019, -1.09156, -0.97215, -0.99258, -1.00215, -0.99471, -0.98744, -0.80690, -0.64603, -0.60517, -0.66563, -0.75926, -0.80098, -0.61675, -0.44509, -0.48465, -0.64850, -0.68775, -0.69348, -0.88097, -1.06096, -1.06766, -0.98005, -1.02601, -1.03494, -1.19831, -1.38664, -1.44821, -1.48225, -1.47785, -1.38973, -1.20125, -0.99169, -0.83164, -0.65367, -0.58945, -0.44812, -0.25219, -0.14948, 0.14394, 0.48717, 0.78717, 1.00808, 0.97907, 0.83200, 0.83134, 0.93441, 0.91373, 0.71282, 0.59045, 0.64507, 0.65552, 0.61692, 0.56715, 0.40725, 0.12246, 0.12021, 0.22615, 0.29511, 0.35451, 0.41445, 0.48000, 0.50032, 0.40246, 0.20762, 0.02350, -0.05427, -0.22394, -0.35013, -0.48506, -0.72652, -0.82631, -0.87866, -0.88179, -0.88498, -0.91976, -0.95621, -0.82803, -0.67202, -0.74373, +-2.19738, -2.05857, -1.91270, -1.85427, -1.95417, -2.30285, -2.57776, -2.66488, -2.66516, -2.70447, -2.71647, -2.69003, -2.64143, -2.49541, -2.43386, -2.58647, -2.80410, -2.83778, -2.87099, -2.90425, -2.99761, -3.14522, -3.34023, -3.45628, -3.48844, -3.69381, -3.76785, -3.71771, -3.71086, -3.70815, -3.76072, -3.85052, -3.97164, -4.06881, -4.09412, -4.03621, -3.84630, -3.70336, -3.53199, -3.30651, -3.12773, -3.04668, -2.96647, -2.86512, -2.83994, -2.67533, -2.46432, -2.34848, -2.20857, -1.93820, -1.79905, -1.79323, -1.81312, -1.79183, -1.73502, -1.65308, -1.51726, -1.54430, -1.54201, -1.45512, -1.38157, -1.19573, -0.97521, -0.64939, -0.51719, -0.45989, -0.27872, -0.12686, 0.03596, 0.01741, -0.05196, 0.08087, 0.32577, 0.54002, 0.74062, 0.91422, 0.89753, 0.96699, 1.09214, 1.12474, 1.10983, 1.21588, 1.29863, 1.35118, 1.39800, 1.40238, 1.39000, 1.34069, 1.37358, 1.30369, 1.25726, 1.32154, 1.31169, 1.19477, 1.00176, 0.87982, 0.81909, 0.81004, 0.93901, 1.00988, 1.05707, 0.93498, 0.76114, 0.74400, 0.79010, 0.86283, 0.94236, 1.08204, 1.09145, 1.09909, 1.11110, 0.99062, 0.78791, 0.70923, 0.63407, 0.48237, 0.38725, 0.32462, 0.27702, 0.13916, 0.04509, -0.17116, -0.42209, -0.52236, -0.75426, -1.02376, -1.17739, -1.20722, -1.18608, -1.27984, -1.34325, -1.39227, -1.35805, -1.41807, -1.54327, -1.65787, -1.79097, -1.87012, -1.91123, -1.87467, -2.05672, -2.30411, -2.41716, -2.48411, -2.54508, -2.46867, -2.36147, -2.34187, -2.30919, -2.36545, -2.39327, -2.51323, -2.49843, -2.60310, -2.74233, -2.70781, -2.69032, -2.70531, -2.70053, -2.65543, -2.56040, -2.48103, -2.21468, -1.86920, -1.51521, -1.24628, -1.11053, -0.94213, -0.77368, -0.65010, -0.60314, -0.47430, -0.45447, -0.42455, -0.24851, -0.12634, -0.10187, -0.01037, 0.11425, 0.12738, 0.20994, 0.38215, 0.62087, 0.78600, 0.83676, 0.75373, 0.68438, 0.83462, 1.03747, 1.14538, 1.26608, 1.52078, 1.84924, 1.99124, 2.11944, 2.07866, 1.93984, 1.81247, 1.66506, 1.56878, 1.49907, 1.42698, 1.39186, 1.46876, 1.39086, 1.20151, 1.15092, 1.06769, 0.87393, 0.70902, 0.57635, 0.30797, 0.00825, -0.36229, -0.63066, -0.80694, -0.84748, -0.86758, -0.98826, -1.06608, -1.19335, -1.43161, -1.58989, -1.59686, -1.53659, -1.54036, -1.52364, -1.53009, -1.63267, -1.78921, -2.07130, -2.28990, -2.39656, -2.44146, -2.46614, -2.40962, -2.42315, -2.51479, -2.47500, -2.44955, -2.47575, -2.39564, -2.16053, -1.98854, -2.00719, -2.10264, -2.13574, -2.17789, -2.22974, -2.36828, -2.59954, -2.57906, -2.39219, -2.32351, -2.25311, -2.24186, -2.28306, -2.38468, -2.39944, -2.34253, -2.36850, -2.40517, -2.48525, -2.45974, -2.34059, -2.21098, -2.10157, -1.98581, -1.95463, -2.03930, -1.98988, -1.88381, -1.90800, -2.02127, -2.01393, -2.02153, -2.05189, -2.08365, -2.03087, -1.96561, -1.90528, -1.88744, -2.01597, -2.08336, -2.09941, -2.23901, -2.36579, -2.42836, -2.40522, -2.42655, -2.46601, -2.47861, -2.57779, -2.65536, -2.85757, -3.04567, -3.08817, -3.04854, -2.96549, -2.79755, -2.56980, -2.43063, -2.24740, -2.07590, -2.22851, -2.44559, -2.45296, -2.38929, -2.39801, -2.49683, -2.57781, -2.45175, -2.30722, -2.16789, -2.15915, -2.12439, -1.96037, -1.78476, -1.51113, -1.23964, -1.05924, -1.00339, -0.94396, -0.77833, -0.70410, -0.65449, -0.69363, -0.75068, -0.67629, -0.60751, -0.56830, -0.54444, -0.50193, -0.65163, -0.69300, -0.60183, -0.63414, -0.72967, -0.71448, -0.74235, -0.90517, -1.05036, -1.08856, -1.00360, -0.96151, -0.94460, -1.14338, -1.33455, -1.35280, -1.37904, -1.34612, -1.23136, -1.06535, -0.91223, -0.82684, -0.66656, -0.53298, -0.36892, -0.25146, -0.12622, 0.17906, 0.53097, 0.83710, 1.03357, 1.07135, 0.87990, 0.73619, 0.75384, 0.68219, 0.48567, 0.47321, 0.60987, 0.64568, 0.57255, 0.43270, 0.28243, 0.13384, 0.16142, 0.19756, 0.24652, 0.37896, 0.44110, 0.47604, 0.47678, 0.38891, 0.25443, 0.05324, -0.08273, -0.26923, -0.45883, -0.66932, -0.87204, -0.97975, -1.10251, -1.16771, -1.16387, -1.02064, -0.97414, -0.93641, -0.83481, -0.90422, +-2.25143, -2.17398, -2.14328, -2.08145, -2.18396, -2.57610, -2.84147, -2.90741, -2.84709, -2.89131, -2.94497, -2.87469, -2.74382, -2.72245, -2.83033, -2.91875, -3.05188, -3.06689, -3.13402, -3.15965, -3.11272, -3.26932, -3.46007, -3.55093, -3.57348, -3.69377, -3.71416, -3.76490, -3.91168, -3.99737, -4.13873, -4.12801, -4.07162, -4.13492, -4.22630, -4.11133, -3.81698, -3.64785, -3.47441, -3.27563, -3.07544, -2.97216, -2.92259, -2.83849, -2.76549, -2.63545, -2.51874, -2.31813, -2.17713, -1.98781, -1.91186, -1.91483, -1.82124, -1.89540, -1.96670, -1.90685, -1.81327, -1.76891, -1.72909, -1.65379, -1.61230, -1.39329, -1.18799, -0.83798, -0.60106, -0.52956, -0.39973, -0.18713, 0.06925, 0.06546, 0.05151, 0.26988, 0.55681, 0.73406, 0.80717, 0.96078, 1.07790, 1.20178, 1.21259, 1.28288, 1.29459, 1.36343, 1.38177, 1.37026, 1.50817, 1.51934, 1.44688, 1.36491, 1.26570, 1.14839, 1.08901, 1.23711, 1.28165, 1.24502, 1.03627, 0.92402, 0.99193, 1.03336, 1.06211, 1.09013, 1.17437, 1.05275, 0.90819, 0.89421, 0.92697, 1.00522, 1.02011, 1.12241, 1.14326, 1.17530, 1.09196, 1.06086, 0.94609, 0.79382, 0.62472, 0.37658, 0.34369, 0.30016, 0.13373, 0.01200, -0.12141, -0.27515, -0.47745, -0.53647, -0.77876, -1.02072, -1.18408, -1.24093, -1.19179, -1.31011, -1.48747, -1.56190, -1.50846, -1.65446, -1.83961, -1.90434, -1.91811, -1.89680, -1.99069, -2.02784, -2.19119, -2.34857, -2.57553, -2.62608, -2.59062, -2.48557, -2.35546, -2.43156, -2.39465, -2.48329, -2.64965, -2.65895, -2.61790, -2.68307, -2.86009, -2.84821, -2.86217, -2.85605, -2.87342, -2.87411, -2.70479, -2.51173, -2.26214, -1.96096, -1.56655, -1.31109, -1.17643, -0.98401, -0.82270, -0.65232, -0.62134, -0.49535, -0.43106, -0.35253, -0.33292, -0.27137, -0.19330, -0.13451, -0.06679, -0.13636, -0.00159, 0.26181, 0.39734, 0.60184, 0.66428, 0.62888, 0.59074, 0.75075, 0.88722, 0.96642, 1.11046, 1.37377, 1.73641, 1.90094, 1.94094, 1.90191, 1.93571, 1.87422, 1.71625, 1.62294, 1.57479, 1.57946, 1.49467, 1.50051, 1.44290, 1.39291, 1.26803, 1.05134, 0.83375, 0.53601, 0.33686, 0.07911, -0.10945, -0.34284, -0.73022, -0.88707, -0.87243, -0.83675, -0.94164, -1.02340, -1.19897, -1.42852, -1.54884, -1.60793, -1.53713, -1.47426, -1.50419, -1.59131, -1.66890, -1.81038, -2.08966, -2.25184, -2.33125, -2.37228, -2.47613, -2.51717, -2.52735, -2.50756, -2.53394, -2.58698, -2.53199, -2.46377, -2.29144, -2.19594, -2.19790, -2.18493, -2.30343, -2.34929, -2.35858, -2.45881, -2.59498, -2.51234, -2.40995, -2.46119, -2.45359, -2.47473, -2.44544, -2.46292, -2.53786, -2.57521, -2.51974, -2.46741, -2.54316, -2.47085, -2.28607, -2.05066, -1.94356, -1.97343, -2.03077, -2.12283, -2.09156, -1.96577, -1.79767, -1.83678, -1.86697, -1.89568, -1.87219, -1.76936, -1.83152, -1.87911, -1.83718, -1.84306, -1.94613, -2.03727, -2.11313, -2.28748, -2.35301, -2.40539, -2.34573, -2.25376, -2.26520, -2.30949, -2.36872, -2.45536, -2.73930, -2.94847, -2.96385, -2.87330, -2.80018, -2.71832, -2.52703, -2.35498, -2.22400, -2.20446, -2.31021, -2.52441, -2.59914, -2.58736, -2.60863, -2.58200, -2.64154, -2.54360, -2.39917, -2.35831, -2.35465, -2.25761, -2.03693, -1.87161, -1.56828, -1.29572, -1.03478, -0.82286, -0.72311, -0.60227, -0.46647, -0.29686, -0.36022, -0.49564, -0.49437, -0.50416, -0.44386, -0.41315, -0.35023, -0.47801, -0.56739, -0.63142, -0.61163, -0.69682, -0.80351, -0.92087, -1.12353, -1.13387, -1.14944, -1.16429, -1.08797, -1.08640, -1.21731, -1.39396, -1.43759, -1.50172, -1.41041, -1.24936, -1.07171, -0.88935, -0.82299, -0.75777, -0.61716, -0.37929, -0.29215, -0.17488, 0.14701, 0.50845, 0.83993, 0.98056, 0.99438, 0.83286, 0.73223, 0.61119, 0.55226, 0.39823, 0.36128, 0.46794, 0.40076, 0.35875, 0.25903, 0.11168, 0.11244, 0.15178, 0.21026, 0.24744, 0.38150, 0.36761, 0.35624, 0.32820, 0.24315, 0.22837, 0.07016, -0.20314, -0.48573, -0.67529, -0.85085, -0.97170, -1.00619, -1.13262, -1.19610, -1.24086, -1.11409, -1.05535, -0.98218, -1.00870, -1.04821, +-2.43695, -2.47579, -2.48110, -2.45340, -2.47774, -2.77183, -3.01526, -3.05475, -3.01807, -3.07644, -3.05922, -2.93936, -2.80285, -2.81419, -2.97694, -3.05305, -3.16982, -3.22228, -3.24272, -3.21302, -3.23662, -3.41032, -3.57616, -3.71329, -3.70614, -3.74514, -3.77989, -3.90571, -4.07273, -4.16921, -4.33893, -4.30141, -4.24598, -4.30291, -4.31023, -4.13358, -3.75360, -3.51943, -3.42049, -3.28833, -3.16741, -3.13359, -3.02680, -2.86311, -2.73337, -2.56673, -2.46367, -2.27231, -2.17257, -2.07579, -2.01024, -1.98099, -1.94481, -2.06750, -2.12075, -2.08258, -1.96321, -1.82539, -1.76140, -1.71363, -1.68383, -1.45302, -1.27753, -0.95212, -0.71136, -0.67055, -0.51714, -0.25133, 0.11044, 0.26975, 0.30506, 0.52061, 0.73897, 0.80810, 0.89848, 1.14991, 1.34587, 1.51178, 1.49475, 1.53998, 1.52366, 1.51670, 1.48155, 1.45433, 1.49095, 1.38762, 1.31763, 1.19047, 1.05989, 0.99426, 0.96404, 1.14757, 1.27460, 1.36392, 1.19860, 1.09287, 1.16008, 1.10038, 1.05853, 1.05920, 1.15622, 1.15874, 1.04928, 1.02769, 1.00893, 0.95870, 0.96397, 1.11784, 1.14881, 1.21597, 1.12346, 1.10110, 1.04784, 0.89595, 0.72301, 0.52486, 0.42051, 0.21910, 0.01924, -0.16555, -0.37375, -0.46887, -0.61921, -0.64284, -0.78888, -0.92436, -1.10459, -1.20184, -1.18832, -1.42612, -1.65488, -1.76213, -1.74330, -1.78675, -1.92812, -1.92630, -1.88033, -1.93396, -2.03101, -2.02279, -2.17649, -2.29258, -2.58291, -2.71748, -2.70316, -2.63847, -2.50741, -2.50715, -2.49467, -2.71952, -2.86220, -2.81429, -2.76804, -2.75321, -2.91633, -2.95415, -2.97834, -2.94936, -3.03064, -3.07700, -2.89468, -2.73028, -2.45447, -2.12791, -1.74296, -1.39575, -1.23197, -1.04443, -0.90194, -0.82844, -0.78934, -0.55868, -0.38864, -0.20748, -0.20055, -0.18518, -0.13932, -0.16131, -0.15198, -0.19292, -0.11671, -0.00876, 0.12482, 0.38997, 0.51968, 0.60596, 0.61628, 0.76854, 0.91339, 1.04749, 1.17653, 1.35541, 1.64412, 1.71289, 1.74993, 1.80856, 1.92513, 1.99795, 1.90982, 1.82667, 1.77073, 1.66320, 1.46756, 1.44670, 1.39762, 1.40503, 1.27211, 0.99369, 0.72995, 0.35774, 0.13776, -0.00987, -0.14504, -0.46151, -0.84443, -0.95662, -0.93302, -0.86673, -0.97595, -1.07860, -1.25071, -1.39517, -1.47750, -1.57688, -1.54880, -1.57406, -1.65312, -1.73615, -1.82296, -1.88301, -2.08523, -2.21856, -2.25329, -2.35319, -2.52809, -2.54017, -2.50892, -2.43548, -2.45043, -2.56033, -2.57603, -2.58885, -2.49576, -2.35970, -2.31568, -2.42637, -2.60528, -2.58329, -2.52605, -2.51413, -2.55710, -2.49973, -2.46706, -2.50739, -2.49675, -2.54310, -2.53522, -2.61732, -2.73544, -2.73909, -2.63801, -2.48649, -2.48735, -2.42160, -2.23143, -2.05827, -2.04098, -2.07728, -2.11146, -2.16929, -2.07200, -1.90055, -1.67542, -1.66166, -1.67586, -1.62449, -1.53706, -1.57792, -1.79994, -1.88126, -1.89371, -1.90162, -1.96826, -2.08782, -2.19663, -2.31837, -2.30346, -2.34428, -2.28890, -2.21861, -2.26941, -2.27050, -2.25958, -2.27294, -2.46464, -2.66117, -2.67158, -2.62590, -2.65423, -2.61858, -2.46557, -2.32267, -2.21072, -2.23378, -2.35020, -2.59822, -2.73796, -2.67391, -2.58569, -2.59767, -2.72540, -2.60970, -2.48629, -2.43762, -2.35218, -2.20683, -1.98301, -1.78259, -1.42409, -1.16395, -0.90310, -0.69435, -0.68094, -0.56788, -0.39302, -0.16058, -0.10877, -0.25909, -0.30982, -0.39754, -0.43250, -0.37615, -0.25098, -0.34826, -0.40965, -0.51740, -0.55412, -0.74924, -1.00901, -1.15578, -1.28802, -1.33384, -1.45200, -1.44122, -1.34873, -1.31424, -1.33754, -1.48691, -1.55095, -1.57641, -1.39950, -1.21187, -1.00913, -0.82880, -0.84774, -0.78449, -0.62379, -0.37286, -0.19301, -0.12430, 0.10707, 0.39719, 0.60263, 0.76402, 0.87999, 0.75949, 0.72209, 0.61836, 0.56018, 0.38276, 0.24937, 0.28409, 0.25159, 0.18560, 0.02181, -0.00196, 0.09446, 0.16817, 0.30058, 0.33198, 0.40403, 0.33055, 0.27481, 0.16380, 0.03642, 0.02763, -0.19090, -0.46820, -0.71976, -0.87010, -0.87194, -0.92643, -0.95942, -1.10268, -1.28317, -1.35831, -1.20924, -1.21124, -1.14469, -1.17220, -1.19705, +-2.62841, -2.68110, -2.65791, -2.70972, -2.81416, -3.02369, -3.16324, -3.21031, -3.11205, -3.06619, -3.04111, -2.91223, -2.84664, -2.95200, -3.14009, -3.21510, -3.24775, -3.37351, -3.42954, -3.36939, -3.43147, -3.44876, -3.51835, -3.79029, -3.87896, -3.85703, -3.91871, -4.08861, -4.21068, -4.37210, -4.50058, -4.39651, -4.38709, -4.35233, -4.22297, -4.04534, -3.75591, -3.56885, -3.51281, -3.48701, -3.38000, -3.26243, -3.15310, -2.93603, -2.75591, -2.61234, -2.48765, -2.30165, -2.16093, -2.15304, -2.18496, -2.13318, -2.12648, -2.07124, -1.98121, -2.02020, -1.97928, -1.78103, -1.67253, -1.65196, -1.60359, -1.47228, -1.31999, -0.95293, -0.76626, -0.66620, -0.42591, -0.15696, 0.15745, 0.36071, 0.49475, 0.63809, 0.78990, 0.93681, 1.03845, 1.33044, 1.56464, 1.64866, 1.60695, 1.63683, 1.67406, 1.66279, 1.50534, 1.44189, 1.34924, 1.29532, 1.31399, 1.10827, 0.89754, 0.87252, 0.89911, 1.05517, 1.26156, 1.35819, 1.22414, 1.23023, 1.25207, 1.16633, 1.12577, 1.10002, 1.12332, 1.12741, 1.10290, 1.05249, 0.98573, 1.00380, 1.00820, 1.15389, 1.19978, 1.16290, 1.04163, 1.02076, 1.08747, 1.06150, 0.82863, 0.66728, 0.43910, 0.22155, 0.10429, -0.18255, -0.54898, -0.66230, -0.73989, -0.77120, -0.80598, -0.91783, -1.13950, -1.16423, -1.22018, -1.48375, -1.66458, -1.80826, -1.90578, -1.96953, -1.99531, -1.94045, -1.89907, -1.87343, -1.96611, -1.98562, -2.10570, -2.29496, -2.66790, -2.91884, -2.94083, -2.84579, -2.82200, -2.74667, -2.75400, -2.92368, -2.88937, -2.82665, -2.87207, -2.87245, -2.98337, -3.08796, -3.09431, -3.12002, -3.31784, -3.28026, -3.08639, -2.89456, -2.53029, -2.17647, -1.88401, -1.60746, -1.37719, -1.17935, -1.10833, -0.99376, -0.90842, -0.65125, -0.33549, -0.12118, -0.13206, -0.15424, -0.14007, -0.11197, -0.19688, -0.21263, -0.21129, -0.14057, 0.14357, 0.46603, 0.56926, 0.67772, 0.77159, 0.89112, 1.05353, 1.19438, 1.21207, 1.34988, 1.53100, 1.53679, 1.66150, 1.82294, 1.91331, 1.92995, 1.92018, 1.89726, 1.79601, 1.71358, 1.47243, 1.31244, 1.25543, 1.20756, 1.01504, 0.72767, 0.47897, 0.23070, -0.02336, -0.12511, -0.26096, -0.60004, -0.82113, -0.86612, -0.94212, -0.98880, -1.08971, -1.20551, -1.33499, -1.40123, -1.54275, -1.60883, -1.59311, -1.67919, -1.69716, -1.72102, -1.88646, -2.05733, -2.21391, -2.27320, -2.29485, -2.31694, -2.43822, -2.49396, -2.44275, -2.38408, -2.43414, -2.57325, -2.65087, -2.62181, -2.62862, -2.53809, -2.50505, -2.70160, -2.76479, -2.62458, -2.59763, -2.58666, -2.54827, -2.54782, -2.58327, -2.58073, -2.64397, -2.67304, -2.64976, -2.79112, -2.82069, -2.69795, -2.58758, -2.48650, -2.47471, -2.39468, -2.27913, -2.13789, -2.09388, -2.16178, -2.15226, -2.16562, -2.08527, -1.90226, -1.65959, -1.51024, -1.49434, -1.43522, -1.32238, -1.50847, -1.69466, -1.70248, -1.82168, -1.92584, -1.97136, -2.10856, -2.24326, -2.27068, -2.27114, -2.28329, -2.19226, -2.21596, -2.22946, -2.13206, -2.07661, -2.12453, -2.29336, -2.41901, -2.47632, -2.43722, -2.39718, -2.44287, -2.37097, -2.26986, -2.27030, -2.33526, -2.46317, -2.63624, -2.76280, -2.71699, -2.54174, -2.59477, -2.61736, -2.41777, -2.38366, -2.39420, -2.24848, -2.06592, -1.89019, -1.64496, -1.34863, -1.11253, -0.78042, -0.63116, -0.63127, -0.48849, -0.32250, -0.16679, -0.11068, -0.17122, -0.25615, -0.37143, -0.33907, -0.32035, -0.22206, -0.28703, -0.41204, -0.54394, -0.63759, -0.88359, -1.19477, -1.43220, -1.49877, -1.61535, -1.68247, -1.54705, -1.48862, -1.48698, -1.43976, -1.52098, -1.63440, -1.60375, -1.44077, -1.25658, -0.91009, -0.74675, -0.75763, -0.63214, -0.48252, -0.32243, -0.18924, -0.11496, 0.01018, 0.20440, 0.44778, 0.60067, 0.72904, 0.68851, 0.62992, 0.55041, 0.49244, 0.33279, 0.18837, 0.03620, 0.01456, -0.09066, -0.16153, 0.02758, 0.15447, 0.17102, 0.30548, 0.37544, 0.36604, 0.27503, 0.10013, -0.15302, -0.21685, -0.25805, -0.45266, -0.59932, -0.75488, -0.90076, -0.90695, -0.90022, -0.95979, -1.17246, -1.30534, -1.39661, -1.34196, -1.40688, -1.44883, -1.48082, -1.47724, +-2.75939, -2.75976, -2.83268, -2.98420, -3.12225, -3.26508, -3.24804, -3.18947, -3.03486, -2.93119, -2.94468, -2.92312, -2.90499, -3.00350, -3.16826, -3.24982, -3.32763, -3.47709, -3.61303, -3.62767, -3.57649, -3.44576, -3.50563, -3.82002, -3.98422, -4.01786, -4.05852, -4.12018, -4.22494, -4.37727, -4.50597, -4.47317, -4.39044, -4.24894, -4.16917, -4.08760, -3.83427, -3.72377, -3.70747, -3.64953, -3.46322, -3.23213, -3.17368, -3.05039, -2.83251, -2.60319, -2.38936, -2.15383, -2.04943, -2.13129, -2.24377, -2.24151, -2.12426, -1.91890, -1.85001, -1.95617, -1.98412, -1.83203, -1.62179, -1.43802, -1.40286, -1.35319, -1.22829, -0.97230, -0.78500, -0.56397, -0.32087, -0.15888, 0.09653, 0.29043, 0.48899, 0.64221, 0.77775, 1.01706, 1.11582, 1.30116, 1.52643, 1.64873, 1.60504, 1.65155, 1.71638, 1.75334, 1.61264, 1.44209, 1.33679, 1.35258, 1.27531, 0.99900, 0.81085, 0.76340, 0.81189, 1.04292, 1.22460, 1.26008, 1.14547, 1.11320, 1.18738, 1.19587, 1.11300, 0.99043, 1.04865, 1.10403, 1.10636, 1.08515, 1.02185, 1.13043, 1.16090, 1.21330, 1.23119, 1.17084, 1.03865, 1.07108, 1.19534, 1.21659, 0.98520, 0.70393, 0.40405, 0.25165, 0.11026, -0.26478, -0.65903, -0.84577, -0.89007, -0.80328, -0.84492, -0.99137, -1.15804, -1.25626, -1.36419, -1.51956, -1.67499, -1.97813, -2.13134, -2.16319, -2.12280, -1.99168, -1.92466, -1.81217, -1.93101, -2.09298, -2.20691, -2.30917, -2.65464, -2.94562, -3.04776, -3.02622, -3.06450, -3.04048, -2.97741, -2.94437, -2.88010, -2.92287, -2.98803, -3.06090, -3.17744, -3.15864, -3.14329, -3.27983, -3.48617, -3.46263, -3.19873, -2.82645, -2.46138, -2.28669, -2.09055, -1.83362, -1.55608, -1.28396, -1.22166, -1.08132, -0.96517, -0.76597, -0.40374, -0.10087, -0.09160, -0.11800, -0.15040, -0.11595, -0.13473, -0.16106, -0.14540, 0.05944, 0.39468, 0.61187, 0.68839, 0.78734, 0.92517, 1.13725, 1.26561, 1.29895, 1.27337, 1.23506, 1.28185, 1.37380, 1.54304, 1.58505, 1.61380, 1.62882, 1.63552, 1.70209, 1.68528, 1.72354, 1.50977, 1.16610, 1.00216, 0.94614, 0.73501, 0.52579, 0.37512, 0.21962, 0.01218, -0.16252, -0.33627, -0.57192, -0.74108, -0.87270, -1.00637, -1.17054, -1.31173, -1.28595, -1.27573, -1.34715, -1.52281, -1.66895, -1.72564, -1.70496, -1.62119, -1.72023, -2.00145, -2.25179, -2.39789, -2.36245, -2.29436, -2.22389, -2.30127, -2.48256, -2.53690, -2.42877, -2.39805, -2.46360, -2.51647, -2.50280, -2.53290, -2.59213, -2.69117, -2.79944, -2.75903, -2.69648, -2.74217, -2.74228, -2.71152, -2.69295, -2.69821, -2.73281, -2.82994, -2.91212, -2.94717, -2.98110, -2.88816, -2.76869, -2.66471, -2.49994, -2.44698, -2.36006, -2.24912, -2.13147, -2.09596, -2.20537, -2.20617, -2.12242, -2.00318, -1.82824, -1.56661, -1.39773, -1.34091, -1.29309, -1.25710, -1.41803, -1.52310, -1.55997, -1.70155, -1.83234, -1.96171, -2.07714, -2.12307, -2.14012, -2.12717, -2.12998, -2.15853, -2.20806, -2.13393, -2.05919, -2.06891, -2.12066, -2.28977, -2.40118, -2.42919, -2.31884, -2.17671, -2.26850, -2.32835, -2.23931, -2.22481, -2.34146, -2.46489, -2.56767, -2.60802, -2.58221, -2.51124, -2.47948, -2.36892, -2.26382, -2.33395, -2.34641, -2.24422, -2.04673, -1.78300, -1.58875, -1.40413, -1.18938, -0.90651, -0.68413, -0.56358, -0.49060, -0.46447, -0.36052, -0.30933, -0.26916, -0.23213, -0.27865, -0.21288, -0.28623, -0.33787, -0.40846, -0.48061, -0.59279, -0.68197, -0.97231, -1.28597, -1.51170, -1.62032, -1.70742, -1.70104, -1.63165, -1.67425, -1.63384, -1.56200, -1.56361, -1.57482, -1.57970, -1.46394, -1.23767, -0.92632, -0.74388, -0.64462, -0.57079, -0.58730, -0.44282, -0.29555, -0.19171, -0.03424, 0.15726, 0.44027, 0.50029, 0.49252, 0.53258, 0.61431, 0.55043, 0.48415, 0.33641, 0.15523, -0.10142, -0.25837, -0.33058, -0.23960, -0.03566, 0.01699, 0.02588, 0.08736, 0.17768, 0.31054, 0.24400, -0.03582, -0.34304, -0.48649, -0.55138, -0.59953, -0.63006, -0.79489, -0.89284, -0.92300, -0.94639, -0.99151, -1.22029, -1.30388, -1.42851, -1.57334, -1.73592, -1.73639, -1.71392, -1.61521, +-2.92812, -2.96352, -2.99950, -3.13142, -3.28576, -3.36929, -3.28822, -3.15810, -3.02381, -2.96935, -2.91722, -2.85543, -2.87104, -2.93987, -3.11693, -3.29219, -3.49458, -3.61052, -3.65890, -3.77365, -3.77828, -3.59853, -3.58754, -3.77249, -3.87741, -3.93895, -4.02677, -4.07490, -4.15068, -4.19062, -4.29099, -4.35988, -4.27160, -4.19666, -4.13265, -4.06511, -3.84824, -3.75987, -3.76526, -3.67250, -3.43290, -3.22167, -3.16396, -3.03517, -2.86436, -2.62236, -2.36302, -2.16152, -2.10592, -2.15202, -2.10852, -2.09785, -2.05215, -1.91213, -1.89398, -1.97619, -1.96207, -1.80539, -1.57114, -1.37302, -1.35426, -1.27975, -1.09000, -0.93159, -0.78256, -0.62889, -0.33800, -0.16519, 0.01051, 0.17704, 0.37892, 0.55215, 0.76007, 1.00030, 1.14642, 1.34381, 1.50048, 1.61505, 1.57147, 1.51633, 1.54740, 1.65420, 1.76075, 1.66291, 1.50194, 1.47250, 1.30822, 1.04303, 0.94475, 0.88389, 0.83448, 0.92846, 1.04302, 1.06821, 1.03530, 0.96427, 1.10081, 1.09601, 1.09596, 1.07447, 1.18801, 1.27998, 1.24567, 1.17619, 1.12971, 1.18700, 1.25668, 1.37651, 1.38455, 1.30371, 1.21211, 1.18311, 1.21783, 1.14425, 1.01788, 0.73280, 0.32487, 0.13364, -0.02737, -0.39431, -0.71823, -0.91749, -0.97534, -0.95861, -1.07588, -1.22072, -1.22921, -1.38385, -1.52536, -1.73624, -1.83761, -2.04089, -2.12946, -2.10782, -2.05268, -1.98015, -1.89809, -1.82707, -1.99245, -2.16680, -2.29430, -2.38440, -2.60614, -2.93025, -3.11292, -3.20021, -3.17764, -3.08374, -3.02736, -2.98107, -2.97102, -3.08731, -3.09163, -3.16398, -3.30124, -3.30097, -3.27766, -3.40292, -3.42193, -3.36409, -3.02951, -2.69444, -2.41174, -2.27446, -2.14911, -1.93273, -1.64569, -1.40001, -1.28042, -1.15031, -1.01153, -0.74146, -0.42305, -0.23324, -0.19942, -0.28155, -0.33949, -0.29935, -0.11875, 0.03214, 0.05301, 0.24945, 0.59503, 0.73961, 0.81698, 0.94202, 1.09185, 1.22085, 1.22960, 1.17028, 1.23741, 1.16358, 1.18751, 1.23137, 1.34317, 1.36307, 1.36341, 1.38069, 1.37251, 1.39295, 1.46094, 1.55950, 1.41253, 1.13756, 0.95557, 0.81245, 0.60770, 0.41995, 0.32417, 0.17462, 0.04893, -0.05050, -0.28464, -0.58832, -0.78962, -0.98463, -1.09712, -1.23086, -1.34395, -1.29953, -1.25572, -1.36491, -1.48569, -1.64953, -1.76021, -1.76294, -1.69516, -1.73980, -1.99256, -2.23394, -2.34347, -2.32663, -2.27442, -2.25653, -2.36623, -2.52035, -2.56174, -2.46603, -2.36003, -2.38656, -2.45486, -2.50893, -2.49007, -2.52360, -2.76965, -2.93727, -2.87721, -2.90091, -2.98423, -2.94444, -2.89762, -2.86990, -2.86821, -2.92710, -2.94832, -3.01288, -3.07248, -3.05288, -2.99000, -2.82038, -2.64070, -2.39772, -2.23688, -2.15198, -2.05792, -1.98946, -2.04453, -2.09232, -2.00240, -1.93065, -1.85487, -1.73948, -1.54740, -1.45312, -1.34848, -1.15193, -1.14450, -1.31765, -1.35570, -1.38099, -1.45817, -1.54660, -1.73853, -1.90402, -2.01338, -2.07691, -1.98721, -1.91008, -1.99844, -2.05546, -2.04632, -1.96991, -2.03282, -2.16688, -2.34348, -2.49132, -2.50918, -2.32527, -2.19027, -2.23539, -2.26568, -2.22428, -2.21917, -2.37753, -2.58482, -2.66270, -2.59467, -2.44276, -2.43916, -2.43931, -2.28874, -2.19212, -2.23253, -2.17736, -2.10447, -1.97088, -1.77212, -1.64706, -1.51510, -1.26781, -1.04039, -0.74748, -0.61317, -0.50658, -0.46498, -0.39483, -0.33509, -0.23857, -0.14383, -0.14013, -0.20065, -0.33165, -0.37959, -0.50850, -0.60465, -0.67505, -0.81144, -1.08755, -1.33446, -1.38889, -1.47087, -1.65422, -1.73524, -1.75243, -1.85435, -1.74966, -1.62647, -1.57296, -1.57081, -1.56945, -1.41517, -1.08685, -0.90393, -0.76701, -0.74407, -0.69542, -0.68644, -0.51888, -0.34039, -0.21438, -0.07970, 0.14392, 0.35099, 0.31759, 0.30759, 0.39430, 0.51972, 0.47225, 0.29251, 0.12872, -0.05258, -0.16014, -0.26476, -0.38228, -0.32009, -0.16912, -0.14857, -0.09173, -0.06942, -0.00579, 0.11577, 0.08738, -0.13463, -0.29763, -0.47186, -0.53212, -0.61566, -0.57533, -0.61991, -0.70020, -0.80799, -0.90029, -1.03070, -1.26808, -1.42462, -1.58960, -1.72470, -1.88311, -1.88220, -1.79302, -1.72395, +-3.07458, -3.15764, -3.13198, -3.18852, -3.29043, -3.31474, -3.19735, -3.05281, -2.96304, -2.92898, -2.83869, -2.73083, -2.79567, -2.92949, -3.03591, -3.17098, -3.38136, -3.50863, -3.66381, -3.87331, -3.90577, -3.73456, -3.62178, -3.67942, -3.71768, -3.75037, -3.90481, -4.01939, -4.00771, -3.97381, -4.07008, -4.12049, -4.05680, -4.04402, -3.98615, -3.90779, -3.72493, -3.64237, -3.65298, -3.56783, -3.37266, -3.21390, -3.15892, -3.01725, -2.92211, -2.78832, -2.47214, -2.18847, -2.09678, -2.06956, -2.03346, -2.05035, -2.01597, -1.93919, -1.89680, -1.89898, -1.83812, -1.64468, -1.48021, -1.42627, -1.41352, -1.30730, -1.10977, -0.90784, -0.77679, -0.67929, -0.38057, -0.16398, -0.01273, 0.15434, 0.34645, 0.54861, 0.78103, 1.00726, 1.18771, 1.41704, 1.52491, 1.54370, 1.53969, 1.55259, 1.58065, 1.72803, 1.84781, 1.74385, 1.61631, 1.56813, 1.40708, 1.21105, 1.11757, 1.03573, 0.85411, 0.73036, 0.82486, 0.90918, 0.88641, 0.89353, 1.05720, 1.05673, 1.12753, 1.22469, 1.37209, 1.48895, 1.43541, 1.35676, 1.28421, 1.27809, 1.36127, 1.52578, 1.53510, 1.38702, 1.34011, 1.40186, 1.37094, 1.23194, 1.03492, 0.65098, 0.24482, 0.04079, -0.11986, -0.41191, -0.74449, -0.94390, -1.04956, -1.19970, -1.33859, -1.40311, -1.39093, -1.47782, -1.60756, -1.84381, -1.91098, -1.96008, -1.96649, -1.90331, -1.86223, -1.82068, -1.77595, -1.77432, -1.96911, -2.15630, -2.32209, -2.52054, -2.69080, -2.86215, -3.04537, -3.14296, -3.17224, -3.18500, -3.13395, -3.10557, -3.13193, -3.17785, -3.14114, -3.15386, -3.27808, -3.38739, -3.35003, -3.34215, -3.29416, -3.15138, -2.80102, -2.55149, -2.35467, -2.20075, -2.11715, -1.93419, -1.67794, -1.45203, -1.31435, -1.18674, -1.02056, -0.71561, -0.45748, -0.44820, -0.43651, -0.37638, -0.35746, -0.22300, 0.01228, 0.11979, 0.15042, 0.34614, 0.68791, 0.90168, 0.97558, 1.10144, 1.20767, 1.14960, 1.06046, 1.04132, 1.11227, 1.10597, 1.16552, 1.14246, 1.18257, 1.22431, 1.22453, 1.25531, 1.23109, 1.22415, 1.29919, 1.38668, 1.29725, 1.11388, 0.95305, 0.70178, 0.46491, 0.41341, 0.38945, 0.28418, 0.14987, -0.04242, -0.29333, -0.60758, -0.83721, -0.97990, -1.07748, -1.17619, -1.27508, -1.34909, -1.37503, -1.43984, -1.55147, -1.67735, -1.76363, -1.81578, -1.79149, -1.77669, -1.94630, -2.11031, -2.17692, -2.16262, -2.15672, -2.21938, -2.33006, -2.42248, -2.41739, -2.39277, -2.33708, -2.27453, -2.31694, -2.37955, -2.38116, -2.53592, -2.86110, -3.05250, -3.02822, -3.02558, -3.09533, -3.04295, -2.97817, -2.99253, -3.03106, -3.02210, -2.98634, -3.00160, -2.97735, -2.93259, -2.90199, -2.70752, -2.47895, -2.20386, -1.98558, -1.88490, -1.81170, -1.80899, -1.90660, -1.91701, -1.78707, -1.79580, -1.83437, -1.66970, -1.41794, -1.32387, -1.21372, -1.07876, -1.11081, -1.24156, -1.25144, -1.20534, -1.20229, -1.27251, -1.46611, -1.71569, -1.96987, -2.03223, -1.90678, -1.82147, -1.83579, -1.88357, -1.93190, -1.86877, -1.94847, -2.13637, -2.30466, -2.45353, -2.45495, -2.28545, -2.18495, -2.22256, -2.25690, -2.28961, -2.37647, -2.46913, -2.56649, -2.59793, -2.47908, -2.37169, -2.43678, -2.42250, -2.26155, -2.09899, -2.04325, -1.97888, -1.90556, -1.84810, -1.79686, -1.67350, -1.53219, -1.33668, -1.08334, -0.80051, -0.69044, -0.55855, -0.45457, -0.37835, -0.27935, -0.15556, -0.04005, -0.06582, -0.20809, -0.34606, -0.37582, -0.55636, -0.76266, -0.78171, -0.78743, -1.01202, -1.20573, -1.29779, -1.47753, -1.70497, -1.85335, -1.89776, -1.96424, -1.87019, -1.70764, -1.64593, -1.70354, -1.61720, -1.34650, -1.01533, -0.83077, -0.74085, -0.78151, -0.74242, -0.65268, -0.47245, -0.27259, -0.16647, -0.06796, 0.11692, 0.25002, 0.19265, 0.19669, 0.26773, 0.29163, 0.26771, 0.20642, 0.06428, -0.05297, -0.11639, -0.26944, -0.38730, -0.35347, -0.22286, -0.12761, -0.06363, -0.04538, -0.03895, -0.06903, -0.08338, -0.16298, -0.26452, -0.35241, -0.38986, -0.51576, -0.48167, -0.44835, -0.54633, -0.68873, -0.82600, -0.99922, -1.27910, -1.50904, -1.68516, -1.79212, -1.95053, -2.06804, -1.99773, -1.83231, +-3.18890, -3.33235, -3.32713, -3.33915, -3.36396, -3.32744, -3.18146, -3.03782, -2.97137, -2.84579, -2.76418, -2.70010, -2.72154, -2.83888, -2.94916, -3.12775, -3.27054, -3.42387, -3.64083, -3.77939, -3.81256, -3.72974, -3.68242, -3.69714, -3.63735, -3.65792, -3.79836, -3.83301, -3.73786, -3.73779, -3.93675, -3.96796, -3.84057, -3.85234, -3.87328, -3.82359, -3.70034, -3.62571, -3.63494, -3.54119, -3.40936, -3.21903, -3.20738, -3.15511, -3.04401, -2.88310, -2.56749, -2.33731, -2.19364, -2.09650, -2.07211, -1.93799, -1.85722, -1.86918, -1.89533, -1.89623, -1.78858, -1.61970, -1.51034, -1.43924, -1.43645, -1.40277, -1.31548, -1.07642, -0.85825, -0.72369, -0.50055, -0.25859, -0.12047, 0.08144, 0.24612, 0.47843, 0.67340, 0.97051, 1.18376, 1.36604, 1.52551, 1.61030, 1.62384, 1.56627, 1.56252, 1.72816, 1.77767, 1.84722, 1.83507, 1.75717, 1.51503, 1.26960, 1.18296, 1.06796, 0.77391, 0.63543, 0.73443, 0.81607, 0.69724, 0.73896, 0.95614, 1.04675, 1.11011, 1.29903, 1.45168, 1.60057, 1.49235, 1.43789, 1.32040, 1.37856, 1.50592, 1.59347, 1.63182, 1.57949, 1.55997, 1.56524, 1.43751, 1.26885, 0.94696, 0.65740, 0.32180, 0.07629, -0.16397, -0.50456, -0.84779, -1.05991, -1.23502, -1.35823, -1.45773, -1.48464, -1.57563, -1.63123, -1.68759, -1.81369, -1.93348, -1.90220, -1.90018, -1.79508, -1.80581, -1.74379, -1.75422, -1.73010, -1.89485, -2.20608, -2.42782, -2.59229, -2.73130, -2.87256, -3.06913, -3.10696, -3.25296, -3.22318, -3.10053, -3.09109, -3.22243, -3.33318, -3.25983, -3.18153, -3.29669, -3.34275, -3.25347, -3.16120, -3.16694, -3.01238, -2.64609, -2.37623, -2.34106, -2.21605, -2.18163, -1.97601, -1.77460, -1.54722, -1.43649, -1.24890, -0.99835, -0.76870, -0.59641, -0.58405, -0.53992, -0.44418, -0.42813, -0.17840, 0.01986, 0.19660, 0.32490, 0.52550, 0.78596, 0.92395, 0.98832, 1.12769, 1.14257, 1.05725, 0.97794, 0.99653, 0.95811, 0.92812, 1.02161, 1.06492, 0.99990, 1.03006, 1.02163, 1.09120, 1.03366, 1.00616, 1.02862, 1.12044, 1.15345, 1.00439, 0.84880, 0.66149, 0.45458, 0.41552, 0.35800, 0.32964, 0.11257, -0.08553, -0.22057, -0.48236, -0.78315, -1.02732, -1.16603, -1.21672, -1.32944, -1.40829, -1.41572, -1.47037, -1.69894, -1.87737, -1.90524, -1.85270, -1.88283, -1.89012, -2.01091, -2.07988, -2.11329, -2.08749, -2.13370, -2.23113, -2.21991, -2.29031, -2.32358, -2.27012, -2.19780, -2.15326, -2.29729, -2.34499, -2.42013, -2.62643, -2.83329, -2.97570, -3.03640, -3.12794, -3.22100, -3.13143, -3.08264, -3.07654, -3.03715, -2.96146, -2.96347, -3.00116, -2.87018, -2.69698, -2.69074, -2.58828, -2.38662, -2.12303, -1.88127, -1.75565, -1.68259, -1.72602, -1.74995, -1.76053, -1.68185, -1.67011, -1.70661, -1.55122, -1.35352, -1.21602, -1.12678, -1.07497, -0.99531, -1.03347, -1.05364, -1.05505, -1.06055, -1.10866, -1.33146, -1.60766, -1.82316, -1.86321, -1.81453, -1.85320, -1.80605, -1.75232, -1.80393, -1.84323, -1.96335, -2.19212, -2.32149, -2.48156, -2.48689, -2.39008, -2.22795, -2.27201, -2.41705, -2.45357, -2.49938, -2.55246, -2.64210, -2.61852, -2.46427, -2.42545, -2.34847, -2.24935, -2.12078, -2.02648, -2.00374, -1.92481, -1.85497, -1.81610, -1.70212, -1.54774, -1.46553, -1.45265, -1.22177, -0.92150, -0.77910, -0.70478, -0.56337, -0.49416, -0.33904, -0.22245, -0.06349, -0.14581, -0.24602, -0.35808, -0.46117, -0.61899, -0.78065, -0.80137, -0.84043, -1.03407, -1.15261, -1.34521, -1.44816, -1.66034, -1.89036, -2.03890, -2.16259, -2.05686, -1.87591, -1.83002, -1.76389, -1.55988, -1.23814, -1.02349, -0.86156, -0.74867, -0.72314, -0.77870, -0.67985, -0.54193, -0.29996, -0.24833, -0.16321, -0.06430, 0.09015, 0.07369, 0.01116, 0.08009, 0.15233, 0.15565, 0.10164, -0.03478, -0.04267, -0.14723, -0.18464, -0.21797, -0.19837, -0.13580, -0.08544, -0.00898, 0.01114, -0.08564, -0.11260, -0.10004, -0.10411, -0.25838, -0.31578, -0.30616, -0.36444, -0.43899, -0.40061, -0.56259, -0.70792, -0.90909, -1.07051, -1.39850, -1.61478, -1.75248, -1.93694, -2.09418, -2.15347, -2.09075, -1.98002, +-3.28607, -3.44572, -3.39935, -3.36628, -3.35595, -3.26379, -3.04733, -2.87052, -2.80482, -2.67152, -2.52551, -2.45026, -2.56802, -2.74930, -2.91056, -3.08621, -3.22677, -3.39314, -3.55943, -3.68712, -3.77668, -3.77567, -3.74936, -3.67581, -3.60995, -3.62917, -3.65707, -3.59070, -3.50757, -3.54228, -3.70197, -3.72690, -3.66510, -3.69343, -3.67579, -3.67324, -3.69270, -3.73477, -3.70351, -3.54792, -3.43223, -3.29424, -3.28340, -3.18546, -3.05922, -2.84656, -2.53856, -2.35746, -2.27475, -2.23994, -2.17357, -1.99735, -1.89078, -1.85804, -1.77820, -1.64663, -1.62718, -1.63683, -1.52745, -1.37423, -1.40265, -1.48185, -1.40788, -1.18128, -0.97156, -0.83433, -0.57716, -0.30907, -0.18429, -0.00918, 0.18737, 0.41188, 0.51131, 0.74123, 0.97311, 1.26269, 1.49274, 1.62733, 1.68451, 1.60593, 1.51991, 1.54940, 1.56189, 1.69377, 1.78029, 1.76032, 1.53820, 1.34322, 1.19746, 0.96757, 0.67563, 0.60786, 0.67248, 0.69528, 0.61701, 0.64385, 0.76861, 0.80083, 0.96885, 1.27617, 1.45741, 1.55894, 1.45985, 1.45794, 1.38286, 1.48826, 1.64423, 1.77905, 1.78516, 1.70534, 1.66185, 1.59943, 1.41025, 1.15306, 0.87603, 0.63503, 0.26311, -0.04938, -0.29427, -0.51449, -0.84087, -1.16829, -1.35162, -1.38377, -1.44282, -1.52006, -1.60606, -1.63208, -1.68234, -1.81226, -1.86713, -1.81042, -1.87477, -1.86139, -1.88856, -1.77503, -1.75787, -1.74899, -1.88869, -2.14121, -2.42640, -2.66109, -2.84965, -2.98765, -3.12390, -3.22080, -3.38605, -3.38616, -3.27162, -3.23411, -3.36225, -3.37568, -3.26256, -3.19630, -3.22489, -3.15716, -3.06929, -3.06117, -3.02660, -2.81900, -2.49632, -2.35258, -2.36922, -2.23714, -2.17721, -1.97669, -1.78165, -1.55324, -1.48195, -1.34420, -1.11758, -0.83582, -0.67000, -0.62447, -0.50211, -0.38433, -0.38369, -0.24988, -0.03274, 0.21887, 0.39772, 0.61370, 0.83751, 1.02531, 1.11917, 1.13882, 1.09080, 1.05852, 1.01023, 0.96453, 0.88992, 0.81608, 0.79893, 0.72469, 0.62958, 0.71230, 0.75651, 0.80911, 0.78632, 0.79136, 0.77029, 0.79562, 0.79974, 0.80089, 0.76608, 0.63112, 0.43602, 0.35053, 0.31390, 0.24574, 0.02047, -0.15063, -0.25994, -0.43559, -0.72952, -0.98046, -1.17165, -1.35802, -1.47249, -1.45504, -1.41589, -1.55957, -1.85110, -1.99415, -1.96033, -1.89169, -1.91487, -1.90320, -2.01946, -2.12055, -2.15619, -2.08572, -2.10697, -2.15714, -2.07207, -2.03390, -2.07344, -2.09415, -2.03670, -2.01862, -2.17518, -2.31805, -2.47861, -2.68765, -2.84569, -2.93199, -3.00307, -3.06090, -3.09212, -3.06327, -3.05866, -3.03076, -2.97570, -2.94997, -2.99187, -2.94201, -2.72397, -2.53788, -2.49251, -2.38463, -2.24283, -2.09720, -1.94012, -1.74685, -1.61167, -1.65471, -1.71659, -1.70454, -1.55195, -1.52348, -1.56125, -1.44406, -1.26404, -1.12727, -1.10449, -1.11542, -1.09343, -1.10947, -1.06376, -0.99155, -0.90552, -1.00635, -1.28564, -1.49445, -1.57534, -1.60627, -1.66608, -1.75700, -1.76236, -1.78617, -1.88670, -1.91632, -2.01229, -2.20866, -2.30928, -2.42961, -2.48784, -2.48713, -2.36366, -2.36032, -2.42612, -2.48247, -2.54402, -2.59158, -2.62919, -2.57465, -2.47526, -2.42161, -2.29605, -2.13480, -1.99648, -1.97722, -1.96945, -1.96596, -1.98667, -1.87204, -1.61664, -1.45153, -1.43718, -1.48754, -1.35401, -1.20409, -1.16368, -1.02242, -0.80405, -0.71717, -0.60833, -0.46909, -0.23623, -0.29197, -0.39847, -0.48309, -0.47997, -0.56631, -0.72661, -0.81788, -0.94246, -1.13056, -1.27749, -1.46046, -1.56520, -1.79517, -2.04125, -2.20299, -2.20460, -2.07941, -1.99870, -1.94071, -1.76626, -1.53058, -1.26551, -1.04604, -0.85499, -0.71735, -0.69077, -0.73376, -0.69225, -0.63204, -0.45065, -0.37199, -0.24769, -0.19126, -0.10214, -0.11717, -0.05553, 0.04426, 0.10970, 0.11482, 0.07092, -0.00069, -0.06020, -0.20151, -0.25506, -0.26702, -0.21370, -0.11953, 0.05022, 0.15863, 0.10215, -0.04456, -0.04666, -0.08863, -0.18193, -0.26881, -0.24711, -0.24181, -0.39530, -0.49119, -0.42163, -0.59726, -0.82478, -1.05132, -1.16000, -1.43867, -1.69630, -1.91118, -2.07598, -2.20719, -2.24098, -2.20145, -2.16652, +-3.23579, -3.24540, -3.19279, -3.19075, -3.13780, -2.97515, -2.75327, -2.59700, -2.46753, -2.37398, -2.33011, -2.27643, -2.46883, -2.74169, -2.95814, -3.07520, -3.20294, -3.36270, -3.44031, -3.53802, -3.61519, -3.71155, -3.86039, -3.76698, -3.65030, -3.55897, -3.53707, -3.52273, -3.39730, -3.39631, -3.40471, -3.46554, -3.53577, -3.44270, -3.39808, -3.53642, -3.64598, -3.76664, -3.75265, -3.60473, -3.38967, -3.24514, -3.31288, -3.22234, -3.08526, -2.91307, -2.65111, -2.41308, -2.31198, -2.32886, -2.20088, -2.02669, -1.86464, -1.78816, -1.73142, -1.53046, -1.49634, -1.51183, -1.40931, -1.35814, -1.34983, -1.46195, -1.31289, -1.15326, -1.07873, -0.83573, -0.51247, -0.34922, -0.22665, -0.05452, 0.15935, 0.29931, 0.40577, 0.58923, 0.69669, 0.92993, 1.19713, 1.33118, 1.44925, 1.50785, 1.48315, 1.41949, 1.43255, 1.55567, 1.73325, 1.76371, 1.46102, 1.23578, 1.09678, 0.89095, 0.65483, 0.47071, 0.53859, 0.55502, 0.59301, 0.59232, 0.53159, 0.59841, 0.91065, 1.20338, 1.47005, 1.62944, 1.60813, 1.56675, 1.58035, 1.71552, 1.75209, 1.79297, 1.77546, 1.60432, 1.51489, 1.46655, 1.33228, 1.02621, 0.83583, 0.61150, 0.25938, -0.05501, -0.36291, -0.55042, -0.75871, -1.03295, -1.14070, -1.29658, -1.33905, -1.44137, -1.45840, -1.47393, -1.66792, -1.75324, -1.65108, -1.67895, -1.76434, -1.79170, -1.82746, -1.84237, -1.81184, -1.77620, -1.95770, -2.24085, -2.51604, -2.83524, -3.09332, -3.19260, -3.17321, -3.29639, -3.43085, -3.48693, -3.38728, -3.29871, -3.46180, -3.49743, -3.30163, -3.13781, -2.99705, -3.00282, -2.92425, -2.96426, -2.85336, -2.56992, -2.38868, -2.28552, -2.18691, -2.14947, -2.07607, -1.87225, -1.65458, -1.51985, -1.46993, -1.32722, -1.20672, -1.03758, -0.84000, -0.76280, -0.58129, -0.39064, -0.25099, -0.15768, 0.11924, 0.42873, 0.65609, 0.91691, 1.05393, 1.12006, 1.22835, 1.20857, 1.19284, 1.02339, 0.91896, 0.84692, 0.80106, 0.76074, 0.55359, 0.36721, 0.35792, 0.34234, 0.37082, 0.44637, 0.53505, 0.53804, 0.50316, 0.55516, 0.46563, 0.42225, 0.50321, 0.41669, 0.21865, 0.12370, 0.22841, 0.18907, 0.02421, -0.10651, -0.21724, -0.29138, -0.61570, -1.01848, -1.25015, -1.50339, -1.54321, -1.56072, -1.54870, -1.66935, -1.91780, -1.94759, -1.96818, -1.95927, -1.83864, -1.84878, -2.01569, -2.11938, -2.11754, -2.07775, -2.09651, -2.01201, -1.90902, -1.92175, -1.94058, -1.99090, -1.97339, -1.95905, -1.99203, -2.14670, -2.34524, -2.54896, -2.71485, -2.72404, -2.81341, -2.98429, -2.98085, -2.93157, -2.85369, -2.86604, -2.92334, -2.90450, -2.96913, -2.82982, -2.65101, -2.51900, -2.24941, -2.08601, -2.04647, -1.96619, -1.87235, -1.70244, -1.58336, -1.54321, -1.65615, -1.76092, -1.57586, -1.49435, -1.53770, -1.44358, -1.17929, -0.98221, -1.00488, -1.04858, -1.12688, -1.12975, -1.06561, -1.05314, -0.88784, -0.90204, -1.06718, -1.24521, -1.39919, -1.42121, -1.55195, -1.61978, -1.75678, -1.96200, -1.97261, -1.95219, -2.08860, -2.18325, -2.21144, -2.30157, -2.45079, -2.43564, -2.34410, -2.40283, -2.43300, -2.46051, -2.56869, -2.63832, -2.56703, -2.41667, -2.35906, -2.28508, -2.18878, -1.96460, -1.82517, -1.97617, -2.04474, -2.05736, -2.08545, -1.96570, -1.81250, -1.59954, -1.55467, -1.52478, -1.49316, -1.58533, -1.54900, -1.31663, -1.14951, -1.00868, -0.90635, -0.74776, -0.54168, -0.47432, -0.52138, -0.66496, -0.65213, -0.62673, -0.80819, -0.95893, -1.07713, -1.18909, -1.36349, -1.49091, -1.60392, -1.78046, -2.00897, -2.28134, -2.30413, -2.15292, -2.06551, -1.96034, -1.91473, -1.64919, -1.39085, -1.07569, -0.83004, -0.75576, -0.63674, -0.55267, -0.63663, -0.59769, -0.44175, -0.31551, -0.25268, -0.17671, -0.09868, -0.22203, -0.20267, -0.04900, -0.03269, -0.06802, -0.05639, 0.04174, -0.02219, -0.11881, -0.19161, -0.16441, -0.09239, -0.09556, 0.03881, 0.22445, 0.24661, 0.17187, 0.00060, -0.10712, -0.26794, -0.24960, -0.13397, -0.24128, -0.43117, -0.43233, -0.45022, -0.61529, -0.86758, -1.08603, -1.25891, -1.45417, -1.66864, -2.01164, -2.30415, -2.40266, -2.45378, -2.45081, -2.40179, +-2.95794, -2.90467, -2.85479, -2.85265, -2.80265, -2.62356, -2.40711, -2.26832, -2.24001, -2.25002, -2.19492, -2.11055, -2.26520, -2.50984, -2.81826, -3.05146, -3.15755, -3.25799, -3.29965, -3.36440, -3.51333, -3.68448, -3.82177, -3.71960, -3.63650, -3.55197, -3.49770, -3.47098, -3.26095, -3.14161, -3.20369, -3.33688, -3.32952, -3.17108, -3.17189, -3.36675, -3.52484, -3.65881, -3.66387, -3.51126, -3.31441, -3.21078, -3.22076, -3.10916, -3.01360, -2.89498, -2.75020, -2.58893, -2.40183, -2.30005, -2.12451, -1.94204, -1.86201, -1.88098, -1.80122, -1.55867, -1.49808, -1.49178, -1.38195, -1.35537, -1.32107, -1.33279, -1.24267, -1.20753, -1.10341, -0.77668, -0.46554, -0.33391, -0.26077, -0.09975, 0.09255, 0.23898, 0.34683, 0.41688, 0.49320, 0.68366, 0.89619, 1.07705, 1.20831, 1.24446, 1.30878, 1.34893, 1.38545, 1.52074, 1.66349, 1.61950, 1.34658, 1.15709, 0.99439, 0.75231, 0.52024, 0.31998, 0.39091, 0.52616, 0.53796, 0.42250, 0.40285, 0.59971, 0.93609, 1.26572, 1.57488, 1.82222, 1.85148, 1.80130, 1.77249, 1.71260, 1.66198, 1.69930, 1.65352, 1.52030, 1.41327, 1.24189, 1.08248, 0.81381, 0.61306, 0.40767, 0.09900, -0.22768, -0.46735, -0.55472, -0.70379, -0.95187, -1.01047, -1.16944, -1.25041, -1.25981, -1.29758, -1.47239, -1.69052, -1.65768, -1.53343, -1.50475, -1.54279, -1.55167, -1.63254, -1.77799, -1.84651, -1.96559, -2.16839, -2.37197, -2.62613, -2.89439, -3.13723, -3.32079, -3.26832, -3.28142, -3.39770, -3.46634, -3.40675, -3.42015, -3.56645, -3.54160, -3.32485, -3.15474, -2.95501, -2.91507, -2.81908, -2.72734, -2.59302, -2.44019, -2.28352, -2.05581, -1.95096, -1.94194, -1.91031, -1.74924, -1.55492, -1.44802, -1.39518, -1.35723, -1.29430, -1.11282, -0.95130, -0.85275, -0.63586, -0.49500, -0.27064, -0.00991, 0.31678, 0.64592, 0.86342, 1.01267, 1.12344, 1.18960, 1.23322, 1.11791, 1.06330, 0.84095, 0.66268, 0.66978, 0.66008, 0.53820, 0.32882, 0.25076, 0.21889, 0.10614, 0.07470, 0.16300, 0.29736, 0.31741, 0.29478, 0.25691, 0.12667, 0.15862, 0.29142, 0.27262, 0.13232, -0.02317, 0.08741, 0.17066, 0.07050, -0.03557, -0.14779, -0.30645, -0.65068, -1.02236, -1.26587, -1.58081, -1.63460, -1.64528, -1.63504, -1.62640, -1.78420, -1.91362, -2.00847, -1.93994, -1.78330, -1.78064, -1.91379, -1.96464, -1.92557, -1.91721, -1.98034, -2.00787, -1.98536, -1.93359, -1.86104, -1.84377, -1.80020, -1.87513, -1.96505, -2.04519, -2.18802, -2.38536, -2.56536, -2.64359, -2.74232, -2.86800, -2.85342, -2.83679, -2.75490, -2.70889, -2.74868, -2.67107, -2.70260, -2.72437, -2.64554, -2.40094, -2.00853, -1.80794, -1.76875, -1.70496, -1.63025, -1.51668, -1.44145, -1.47990, -1.68435, -1.75458, -1.52075, -1.40522, -1.39888, -1.36604, -1.18129, -0.93205, -0.90997, -0.96728, -1.07243, -1.16195, -1.15293, -1.08658, -0.84991, -0.82113, -0.95620, -1.11676, -1.33002, -1.39043, -1.48633, -1.66349, -1.91046, -2.03761, -1.94171, -1.91275, -2.03998, -2.11354, -2.09957, -2.17217, -2.29849, -2.31889, -2.34177, -2.37565, -2.34513, -2.35196, -2.41155, -2.53805, -2.57384, -2.37613, -2.24700, -2.19834, -2.13468, -1.97185, -1.89281, -1.98469, -2.00984, -2.06746, -2.18629, -2.14445, -2.04646, -1.82122, -1.64702, -1.65226, -1.75805, -1.83961, -1.72607, -1.51533, -1.35534, -1.21779, -1.09809, -0.94482, -0.74862, -0.67538, -0.79318, -0.89619, -0.80161, -0.73279, -0.84278, -1.00095, -1.21036, -1.28054, -1.35646, -1.46552, -1.55362, -1.73333, -2.04341, -2.31909, -2.36815, -2.30942, -2.28130, -2.15759, -2.08598, -1.78100, -1.38450, -1.08774, -0.97371, -0.87059, -0.61488, -0.48837, -0.51597, -0.47029, -0.32460, -0.23399, -0.23540, -0.20476, -0.26135, -0.42565, -0.38824, -0.24706, -0.20571, -0.27341, -0.36217, -0.19237, -0.06702, -0.02881, -0.00721, 0.04263, 0.00121, -0.04733, 0.10162, 0.27331, 0.27949, 0.22369, 0.02945, -0.11448, -0.17358, -0.15205, -0.15571, -0.25689, -0.32658, -0.33061, -0.37096, -0.56934, -0.83760, -1.08406, -1.30101, -1.49118, -1.80085, -2.16010, -2.39690, -2.49121, -2.50931, -2.50990, -2.55209, +-2.54870, -2.64136, -2.61733, -2.60328, -2.61061, -2.45247, -2.30747, -2.15321, -2.04200, -2.03620, -1.97752, -1.93487, -2.13967, -2.31358, -2.55168, -2.81790, -3.00787, -3.13893, -3.15753, -3.28812, -3.46386, -3.52365, -3.59989, -3.59214, -3.55953, -3.45129, -3.30486, -3.28393, -3.16142, -3.07104, -3.22737, -3.25041, -3.13190, -3.13592, -3.22680, -3.40911, -3.60327, -3.65630, -3.65948, -3.49248, -3.23524, -3.09679, -3.03515, -2.95476, -2.97456, -2.87270, -2.70623, -2.55074, -2.37456, -2.26608, -2.03157, -1.87883, -1.86480, -1.84161, -1.75026, -1.58947, -1.49981, -1.38687, -1.22824, -1.22480, -1.27191, -1.25369, -1.23416, -1.13314, -0.95114, -0.80144, -0.60431, -0.43902, -0.38759, -0.17500, -0.02433, 0.13119, 0.32867, 0.40356, 0.46323, 0.55399, 0.61486, 0.80229, 0.99306, 1.03137, 1.10904, 1.15697, 1.25940, 1.37726, 1.43977, 1.47250, 1.30873, 1.09973, 0.88869, 0.67423, 0.47496, 0.31229, 0.29507, 0.44048, 0.37865, 0.33136, 0.46900, 0.63080, 0.88803, 1.25673, 1.51095, 1.83217, 1.90608, 1.85861, 1.87866, 1.78319, 1.66761, 1.62722, 1.46348, 1.32740, 1.29733, 1.13092, 0.91992, 0.53857, 0.30609, 0.11003, -0.16318, -0.31915, -0.43638, -0.51417, -0.63141, -0.74389, -0.72084, -0.82820, -1.07065, -1.14919, -1.29640, -1.47393, -1.54170, -1.54703, -1.55206, -1.44323, -1.47433, -1.43828, -1.54256, -1.79570, -1.89097, -2.02394, -2.27324, -2.50584, -2.80268, -3.04040, -3.16163, -3.30727, -3.27023, -3.32540, -3.38940, -3.42273, -3.45481, -3.45144, -3.52426, -3.50289, -3.33322, -3.11458, -2.87745, -2.74335, -2.70702, -2.56105, -2.45429, -2.35081, -2.10863, -1.89023, -1.90664, -1.86240, -1.85630, -1.68720, -1.49243, -1.42515, -1.31112, -1.21902, -1.16919, -1.00473, -0.93335, -0.90688, -0.63113, -0.42458, -0.13195, 0.11725, 0.41153, 0.73452, 0.88515, 1.05840, 1.24080, 1.27461, 1.17885, 1.02373, 0.94958, 0.78799, 0.54187, 0.53112, 0.48709, 0.35119, 0.30757, 0.27997, 0.07509, -0.09019, -0.18370, -0.10049, 0.02229, -0.02846, 0.00355, 0.04427, -0.06403, -0.01761, 0.06126, 0.01276, 0.00916, -0.04756, 0.05368, 0.06694, -0.05225, -0.11125, -0.26352, -0.41699, -0.66414, -0.99124, -1.26859, -1.51016, -1.51953, -1.48114, -1.55970, -1.56089, -1.69151, -1.88626, -1.87818, -1.76956, -1.78925, -1.79897, -1.89034, -1.89962, -1.80377, -1.84245, -1.90585, -1.93745, -1.97105, -1.89659, -1.80204, -1.81771, -1.74618, -1.79295, -1.89389, -2.00879, -2.16118, -2.31117, -2.54811, -2.65310, -2.63808, -2.66888, -2.65430, -2.60927, -2.48438, -2.34480, -2.40254, -2.38140, -2.44619, -2.61782, -2.48001, -2.14392, -1.92691, -1.77878, -1.68690, -1.61925, -1.50989, -1.48781, -1.44107, -1.42427, -1.58636, -1.61313, -1.43390, -1.42081, -1.37327, -1.26975, -1.09803, -0.91503, -0.95216, -0.97975, -1.09162, -1.17967, -1.08908, -1.00755, -0.85534, -0.80101, -0.84671, -0.94897, -1.20204, -1.38329, -1.52166, -1.81937, -1.97741, -1.95042, -1.94613, -1.94014, -1.98940, -2.08629, -2.02731, -2.10501, -2.17257, -2.12568, -2.17805, -2.20230, -2.17590, -2.24882, -2.28579, -2.38191, -2.49253, -2.39470, -2.35944, -2.28510, -2.20192, -2.07406, -1.89273, -1.88463, -1.93046, -2.00164, -2.09784, -2.08828, -2.03785, -1.93558, -1.80689, -1.92468, -1.96248, -1.90124, -1.89581, -1.81590, -1.63228, -1.53127, -1.34149, -1.21457, -1.06290, -0.94541, -1.02779, -1.07559, -0.96421, -0.95545, -1.03656, -1.09594, -1.24935, -1.29702, -1.43362, -1.55257, -1.64337, -1.82802, -2.01989, -2.22216, -2.33214, -2.34603, -2.28925, -2.14224, -2.01849, -1.78897, -1.38471, -1.16510, -1.03640, -0.82535, -0.64664, -0.59370, -0.49484, -0.47815, -0.34458, -0.31071, -0.36819, -0.30416, -0.35555, -0.54184, -0.57192, -0.56292, -0.57481, -0.54973, -0.54581, -0.32789, -0.17890, -0.01994, 0.12425, 0.20092, 0.24314, 0.23222, 0.31868, 0.40450, 0.39753, 0.33350, 0.19241, -0.05000, -0.12876, -0.20847, -0.23766, -0.18823, -0.24376, -0.38922, -0.43412, -0.71606, -0.98412, -1.23676, -1.49737, -1.63524, -1.89308, -2.21573, -2.38691, -2.50286, -2.57795, -2.55227, -2.56909, +-2.31645, -2.43766, -2.42976, -2.40975, -2.42884, -2.33441, -2.21546, -2.07360, -1.90462, -1.80344, -1.79584, -1.84726, -2.01956, -2.12098, -2.28771, -2.50561, -2.66090, -2.75057, -2.80844, -3.02178, -3.20454, -3.21333, -3.23563, -3.26414, -3.29567, -3.21093, -3.06719, -3.08350, -3.05968, -3.08730, -3.23553, -3.16750, -3.08900, -3.17492, -3.30747, -3.48319, -3.65291, -3.62776, -3.53919, -3.38408, -3.19294, -3.04008, -2.95290, -2.91470, -2.87291, -2.66862, -2.47453, -2.33214, -2.16001, -2.01151, -1.77755, -1.64967, -1.64392, -1.65692, -1.62503, -1.51217, -1.41403, -1.26981, -1.15062, -1.21875, -1.25667, -1.21363, -1.15111, -0.95959, -0.80107, -0.77116, -0.65896, -0.51901, -0.40402, -0.16449, -0.00036, 0.13017, 0.26089, 0.34423, 0.39490, 0.40202, 0.47176, 0.71446, 0.86386, 0.84847, 0.96460, 1.14261, 1.30952, 1.38813, 1.37438, 1.37033, 1.27256, 1.11465, 0.87819, 0.65116, 0.46117, 0.30827, 0.30670, 0.42383, 0.36777, 0.42381, 0.57093, 0.72038, 0.95121, 1.21939, 1.37642, 1.64006, 1.78298, 1.79788, 1.82244, 1.77593, 1.63969, 1.44348, 1.23515, 1.15134, 1.13391, 0.98352, 0.79132, 0.44372, 0.16873, -0.04812, -0.28209, -0.40310, -0.50128, -0.54661, -0.57713, -0.56408, -0.49904, -0.62528, -0.88602, -1.06402, -1.29518, -1.41060, -1.42626, -1.48270, -1.53592, -1.49683, -1.56159, -1.54001, -1.59924, -1.79199, -1.92425, -2.06926, -2.37497, -2.75321, -2.99490, -3.05088, -3.07981, -3.21981, -3.22052, -3.21758, -3.19366, -3.19758, -3.29046, -3.36199, -3.43365, -3.36793, -3.19605, -2.97802, -2.76642, -2.67871, -2.62132, -2.41557, -2.31274, -2.20727, -2.05117, -1.94152, -1.93894, -1.88237, -1.81882, -1.60212, -1.37634, -1.27148, -1.18629, -1.09840, -1.03251, -0.95190, -0.86327, -0.75095, -0.48492, -0.27950, 0.00295, 0.25710, 0.48350, 0.73359, 0.86987, 1.03653, 1.20158, 1.26025, 1.17016, 0.99533, 0.87350, 0.67846, 0.49864, 0.50425, 0.42551, 0.31049, 0.26595, 0.19056, -0.00512, -0.16305, -0.26446, -0.21797, -0.17702, -0.24561, -0.19002, -0.09127, -0.13229, -0.19272, -0.17617, -0.12231, -0.00331, 0.00072, 0.04720, 0.03465, -0.06211, -0.08732, -0.22706, -0.39804, -0.64308, -0.91501, -1.10217, -1.20064, -1.18196, -1.24526, -1.42165, -1.44426, -1.55307, -1.69965, -1.64543, -1.58056, -1.66204, -1.72347, -1.83135, -1.84639, -1.74166, -1.71446, -1.74446, -1.81474, -1.88573, -1.89961, -1.84296, -1.80152, -1.74231, -1.80872, -1.89909, -1.96092, -2.05945, -2.13814, -2.33294, -2.46657, -2.47828, -2.43857, -2.29581, -2.18239, -2.07100, -2.03331, -2.16142, -2.14229, -2.20831, -2.34658, -2.19572, -1.94794, -1.87746, -1.79893, -1.66310, -1.54015, -1.41945, -1.41676, -1.40394, -1.38813, -1.44769, -1.49336, -1.43432, -1.41938, -1.30732, -1.15751, -0.99187, -0.83270, -0.85802, -0.87025, -0.92593, -0.95513, -0.92566, -0.94956, -0.89027, -0.83292, -0.82837, -0.95446, -1.21075, -1.35817, -1.53436, -1.84156, -1.95264, -1.93588, -1.94415, -1.87736, -1.84348, -1.91837, -1.88913, -1.93086, -1.95984, -1.95791, -2.03928, -2.09941, -2.11088, -2.12442, -2.11116, -2.19436, -2.35244, -2.36242, -2.38395, -2.29162, -2.11559, -1.95965, -1.80830, -1.83453, -1.86046, -1.86590, -1.89101, -1.90191, -1.93957, -1.89327, -1.89919, -2.06090, -1.98930, -1.89833, -1.95443, -1.95679, -1.83300, -1.73150, -1.52192, -1.39049, -1.28155, -1.23034, -1.25872, -1.25148, -1.19388, -1.15724, -1.15273, -1.16628, -1.23798, -1.22682, -1.36296, -1.55446, -1.69215, -1.83891, -1.98160, -2.15178, -2.18111, -2.12657, -2.05027, -1.95614, -1.92497, -1.72705, -1.37686, -1.16304, -0.95104, -0.79070, -0.73279, -0.69942, -0.59535, -0.60707, -0.56296, -0.54856, -0.56010, -0.52211, -0.56587, -0.70565, -0.84132, -0.90084, -0.89686, -0.80341, -0.65561, -0.37260, -0.15487, 0.02319, 0.23612, 0.41695, 0.52767, 0.53495, 0.60782, 0.65055, 0.56071, 0.43801, 0.26743, 0.04696, -0.07703, -0.25250, -0.25834, -0.19142, -0.26781, -0.45122, -0.58202, -0.91177, -1.18445, -1.39346, -1.59426, -1.75313, -1.98974, -2.24153, -2.39935, -2.45248, -2.49725, -2.53939, -2.58753, +-2.35364, -2.37207, -2.38502, -2.34158, -2.25650, -2.10279, -1.95488, -1.96687, -1.92126, -1.67477, -1.63064, -1.72701, -1.86668, -2.00063, -2.10613, -2.26683, -2.42330, -2.48034, -2.57156, -2.75346, -2.86317, -2.90889, -2.92714, -2.95415, -3.02959, -2.97597, -2.85756, -2.92039, -2.99599, -3.11526, -3.22302, -3.16524, -3.16897, -3.17259, -3.30952, -3.47570, -3.56904, -3.46238, -3.28347, -3.25222, -3.22049, -2.97324, -2.80373, -2.77442, -2.64381, -2.44845, -2.24567, -2.10700, -2.00669, -1.86751, -1.68803, -1.57773, -1.53790, -1.64004, -1.68721, -1.58401, -1.51312, -1.37944, -1.26396, -1.31513, -1.32652, -1.25737, -1.14457, -0.94171, -0.80385, -0.66983, -0.58131, -0.51088, -0.36107, -0.09623, 0.13061, 0.12247, 0.04685, 0.18689, 0.32020, 0.30597, 0.45150, 0.65337, 0.77028, 0.78591, 0.89645, 1.13640, 1.31179, 1.36391, 1.35360, 1.26822, 1.14314, 1.02843, 0.78636, 0.58174, 0.46475, 0.41656, 0.45471, 0.56514, 0.53171, 0.59443, 0.63128, 0.83351, 1.03077, 1.16011, 1.27072, 1.49425, 1.71315, 1.68389, 1.57624, 1.59840, 1.55844, 1.27977, 1.09115, 0.96195, 0.90310, 0.78750, 0.56884, 0.24084, -0.06319, -0.29702, -0.46923, -0.62290, -0.75581, -0.74195, -0.70625, -0.61605, -0.52464, -0.58174, -0.76599, -0.95920, -1.23296, -1.38042, -1.53258, -1.56878, -1.60132, -1.67988, -1.76133, -1.72680, -1.68825, -1.84819, -2.09641, -2.22805, -2.40670, -2.79267, -2.91247, -2.89532, -2.92064, -3.02821, -3.09253, -3.08408, -3.03561, -3.06048, -3.13530, -3.25428, -3.35000, -3.21426, -3.03782, -2.84028, -2.66924, -2.58743, -2.52151, -2.31027, -2.23277, -2.14472, -2.15473, -2.06882, -1.96660, -1.92339, -1.77920, -1.49437, -1.19437, -1.08032, -1.15067, -1.11690, -0.92162, -0.86303, -0.70661, -0.55289, -0.36276, -0.15867, 0.02479, 0.18765, 0.33637, 0.49056, 0.65215, 0.80602, 0.88947, 1.02076, 1.04806, 0.92355, 0.78899, 0.59571, 0.44162, 0.44728, 0.34363, 0.21407, 0.02830, -0.06475, -0.12964, -0.26590, -0.32028, -0.25288, -0.18106, -0.19950, -0.23908, -0.18323, -0.06732, -0.16025, -0.14949, -0.04108, 0.04842, 0.07984, 0.05945, -0.00736, -0.06239, -0.07796, -0.15779, -0.30963, -0.61224, -0.83655, -0.92636, -0.93717, -0.90734, -0.98666, -1.19188, -1.24133, -1.35506, -1.47847, -1.53059, -1.54486, -1.57395, -1.70222, -1.83498, -1.83917, -1.69460, -1.58666, -1.69534, -1.86539, -1.83661, -1.86786, -1.85065, -1.78218, -1.81449, -1.88563, -1.97901, -2.05507, -2.10830, -2.10851, -2.14640, -2.21778, -2.32001, -2.29825, -2.10045, -1.96406, -1.88253, -1.91976, -2.08433, -2.06787, -2.12147, -2.19257, -2.12113, -1.98507, -1.85118, -1.76853, -1.59385, -1.39315, -1.21795, -1.16134, -1.26289, -1.35582, -1.27135, -1.28410, -1.29303, -1.23192, -1.13649, -0.95477, -0.79849, -0.71616, -0.74378, -0.78020, -0.78721, -0.76688, -0.88079, -1.02498, -1.02548, -1.00761, -1.00196, -1.12718, -1.33502, -1.44436, -1.62806, -1.90307, -2.05932, -2.11877, -1.99408, -1.85216, -1.75867, -1.75311, -1.69520, -1.66276, -1.79333, -1.95509, -1.97047, -1.97406, -2.00797, -1.95097, -1.99771, -2.05731, -2.18119, -2.31517, -2.41130, -2.38650, -2.18566, -1.96500, -1.89706, -2.00576, -1.99280, -1.94159, -1.89455, -1.86803, -1.89840, -1.87637, -1.92806, -2.05366, -1.96721, -1.95416, -1.93393, -1.94965, -1.89123, -1.76028, -1.54427, -1.37487, -1.37936, -1.47999, -1.39101, -1.23829, -1.20422, -1.09811, -1.11442, -1.14150, -1.16206, -1.20882, -1.38701, -1.64043, -1.80981, -1.88211, -2.03347, -2.21416, -2.14212, -2.02607, -1.93475, -1.87439, -1.87748, -1.72639, -1.44317, -1.24664, -1.04123, -1.03095, -0.96489, -0.91103, -0.87236, -0.86661, -0.83411, -0.75733, -0.78415, -0.88481, -0.89216, -0.82297, -0.93308, -0.95876, -1.00864, -0.96216, -0.73236, -0.45839, -0.23536, -0.08657, 0.13985, 0.44339, 0.58683, 0.57346, 0.66762, 0.69642, 0.59734, 0.48546, 0.35257, 0.15321, -0.00622, -0.23954, -0.26135, -0.32079, -0.38099, -0.52626, -0.73424, -1.01405, -1.20403, -1.29794, -1.47328, -1.76932, -2.01700, -2.11096, -2.25929, -2.26068, -2.34087, -2.48655, -2.53849, +-2.27047, -2.25953, -2.27973, -2.20779, -2.12056, -1.98435, -1.84604, -1.88930, -1.87283, -1.62453, -1.51946, -1.55242, -1.74245, -1.91250, -1.97352, -2.12817, -2.29136, -2.32895, -2.41449, -2.53111, -2.48371, -2.46608, -2.51583, -2.56224, -2.72073, -2.75797, -2.68123, -2.77470, -2.87895, -3.00604, -3.14912, -3.13809, -3.10540, -3.05575, -3.17141, -3.29993, -3.41803, -3.40530, -3.25803, -3.22372, -3.13734, -2.82184, -2.58905, -2.49448, -2.42379, -2.34811, -2.15458, -2.01985, -1.93528, -1.79236, -1.65500, -1.60211, -1.51876, -1.57062, -1.66138, -1.57780, -1.55950, -1.50159, -1.36348, -1.34523, -1.30812, -1.19156, -1.10145, -0.95420, -0.71768, -0.47802, -0.38988, -0.35892, -0.32183, -0.21226, -0.01015, -0.02820, -0.07823, 0.10765, 0.26152, 0.28490, 0.37317, 0.45722, 0.62122, 0.72602, 0.87687, 1.13345, 1.28966, 1.29762, 1.34002, 1.35633, 1.20635, 1.07448, 0.81823, 0.56495, 0.52589, 0.59643, 0.69601, 0.86164, 0.82302, 0.79274, 0.81223, 0.99809, 1.10133, 1.16220, 1.20566, 1.27487, 1.45619, 1.40627, 1.29965, 1.34182, 1.30717, 1.08926, 0.88117, 0.62986, 0.57774, 0.47435, 0.24306, -0.06730, -0.36279, -0.61009, -0.70494, -0.70418, -0.81192, -0.78416, -0.74760, -0.75034, -0.66757, -0.64768, -0.73244, -0.84552, -1.12947, -1.42793, -1.67378, -1.70015, -1.74253, -1.83062, -1.91919, -2.00573, -1.99214, -2.15511, -2.37020, -2.41114, -2.48663, -2.69650, -2.74816, -2.83883, -2.85813, -2.94031, -3.00774, -2.98277, -2.94068, -3.02089, -3.07133, -3.04178, -3.08899, -2.94176, -2.78244, -2.71176, -2.58373, -2.48535, -2.41346, -2.20062, -2.15268, -2.16161, -2.18411, -2.02839, -1.88928, -1.82373, -1.67449, -1.53654, -1.29786, -1.19502, -1.24694, -1.14622, -0.91720, -0.79627, -0.62924, -0.60394, -0.44352, -0.23509, -0.09328, 0.02893, 0.13524, 0.20270, 0.33902, 0.60032, 0.69093, 0.84990, 0.97736, 0.82249, 0.68377, 0.49784, 0.32043, 0.34542, 0.25479, 0.04777, -0.16450, -0.19727, -0.22715, -0.35010, -0.38469, -0.40471, -0.32899, -0.27353, -0.26223, -0.14577, 0.00251, -0.03226, 0.01003, 0.01275, 0.05186, 0.09226, 0.05916, 0.00299, -0.00359, -0.02610, -0.08899, -0.09222, -0.32715, -0.53416, -0.58650, -0.67695, -0.68447, -0.71102, -0.85804, -0.86137, -0.96017, -1.18161, -1.35362, -1.42409, -1.49453, -1.66075, -1.80109, -1.89697, -1.82277, -1.71912, -1.80131, -1.90264, -1.82624, -1.80176, -1.74925, -1.77529, -1.86924, -1.91941, -2.01619, -2.08493, -2.09578, -2.03991, -1.97442, -1.87898, -1.92495, -1.98585, -1.87154, -1.85052, -1.85123, -1.88225, -2.00349, -1.95471, -1.98986, -2.12638, -2.13893, -1.98210, -1.76559, -1.61037, -1.39687, -1.25446, -1.15700, -1.09489, -1.16279, -1.19328, -1.07353, -1.06190, -1.04371, -1.05219, -1.01712, -0.81251, -0.67445, -0.61468, -0.63372, -0.70090, -0.74523, -0.68200, -0.77602, -0.97666, -1.02033, -1.09146, -1.17748, -1.28941, -1.45606, -1.55320, -1.69950, -1.97844, -2.17498, -2.16946, -1.95587, -1.77821, -1.64526, -1.65517, -1.67674, -1.63202, -1.73596, -1.84828, -1.80814, -1.78330, -1.78052, -1.79406, -1.96443, -1.98525, -2.07127, -2.23814, -2.36847, -2.44283, -2.34251, -2.06674, -1.89681, -2.00311, -1.97121, -1.93781, -1.96640, -1.93606, -1.92601, -1.87749, -1.84345, -1.92210, -1.90728, -1.88665, -1.82036, -1.84121, -1.78067, -1.69067, -1.62814, -1.50212, -1.51697, -1.56618, -1.37582, -1.16380, -1.05877, -0.96790, -1.09185, -1.10951, -1.14220, -1.25098, -1.44434, -1.69726, -1.88565, -1.88247, -1.89068, -2.05233, -1.99140, -1.92255, -1.94255, -1.89534, -1.86957, -1.73063, -1.46665, -1.34229, -1.28666, -1.31980, -1.22232, -1.16950, -1.12329, -1.11649, -1.19092, -1.12155, -1.14037, -1.20594, -1.13074, -0.95388, -0.91603, -0.92522, -1.11281, -1.11925, -0.91501, -0.64359, -0.38925, -0.21525, -0.00460, 0.34256, 0.60663, 0.57396, 0.63085, 0.64480, 0.50465, 0.45502, 0.38561, 0.21058, 0.07913, -0.16601, -0.28905, -0.38259, -0.41836, -0.56758, -0.76062, -0.98761, -1.22690, -1.30582, -1.46174, -1.71930, -1.89444, -1.95962, -2.06424, -2.10336, -2.33816, -2.49617, -2.52656, +-2.22120, -2.27505, -2.32043, -2.19014, -1.95194, -1.78084, -1.69638, -1.62502, -1.61444, -1.50448, -1.44305, -1.45904, -1.56400, -1.61579, -1.59022, -1.80606, -2.07044, -2.09625, -2.22508, -2.28371, -2.15413, -2.18251, -2.30219, -2.36492, -2.48904, -2.54371, -2.54693, -2.62500, -2.73273, -2.95386, -3.12181, -3.15723, -3.12567, -3.10113, -3.15006, -3.18607, -3.21988, -3.28790, -3.28028, -3.15314, -2.96182, -2.67391, -2.40370, -2.27685, -2.19397, -2.12553, -1.92914, -1.85384, -1.83361, -1.64033, -1.52767, -1.52974, -1.45302, -1.58202, -1.72958, -1.63358, -1.49855, -1.39534, -1.32531, -1.34017, -1.28313, -1.25542, -1.14823, -1.00886, -0.66917, -0.41419, -0.32032, -0.26537, -0.21099, -0.19951, -0.14218, -0.10834, -0.01413, 0.12244, 0.26686, 0.25451, 0.27663, 0.34387, 0.57171, 0.72558, 0.88328, 1.18922, 1.33503, 1.26643, 1.33087, 1.30624, 1.16948, 1.08449, 0.92453, 0.71477, 0.64794, 0.67947, 0.84853, 0.96311, 1.02003, 0.97740, 0.98623, 1.00253, 0.97530, 0.99181, 1.08560, 1.15300, 1.24862, 1.22260, 1.20456, 1.11271, 1.01634, 0.79473, 0.59954, 0.39007, 0.41488, 0.30258, 0.00896, -0.25604, -0.50121, -0.76147, -0.72818, -0.71724, -0.84476, -0.85737, -0.79755, -0.80287, -0.77213, -0.80854, -0.74624, -0.88107, -1.11672, -1.45156, -1.72689, -1.87912, -1.99146, -2.07564, -2.03750, -2.07483, -2.13755, -2.32610, -2.46302, -2.57228, -2.62837, -2.73768, -2.70587, -2.76383, -2.72416, -2.81431, -2.95129, -2.89554, -2.76321, -2.87016, -2.87587, -2.88225, -2.96251, -2.87422, -2.68741, -2.56867, -2.41296, -2.39920, -2.28936, -2.23005, -2.21703, -2.24290, -2.19117, -2.02051, -1.85895, -1.76940, -1.56544, -1.45849, -1.35687, -1.30595, -1.23624, -1.15388, -0.94873, -0.84254, -0.68209, -0.65406, -0.43823, -0.19054, -0.08058, 0.02661, 0.13457, 0.06546, 0.16123, 0.35941, 0.40997, 0.55932, 0.82728, 0.79726, 0.69611, 0.43656, 0.27817, 0.18951, 0.05536, -0.15211, -0.27336, -0.29776, -0.34398, -0.50038, -0.52842, -0.51894, -0.47954, -0.38865, -0.19549, -0.06924, 0.02121, -0.04621, -0.00616, 0.02174, 0.16995, 0.29481, 0.20540, 0.12454, 0.17236, 0.08030, 0.03186, 0.07754, -0.09527, -0.30620, -0.32413, -0.40815, -0.42934, -0.50108, -0.54056, -0.52343, -0.62765, -0.86898, -1.09798, -1.30517, -1.51652, -1.74855, -1.86778, -1.90206, -1.88241, -1.85143, -1.80309, -1.84502, -1.80315, -1.74807, -1.63765, -1.64413, -1.69885, -1.72299, -1.90537, -2.00902, -1.92794, -1.84244, -1.67622, -1.51061, -1.57279, -1.70865, -1.67336, -1.69485, -1.75889, -1.85220, -1.87969, -1.80668, -1.89047, -2.06217, -2.14403, -2.02386, -1.83486, -1.61512, -1.32599, -1.10729, -1.05888, -1.08618, -1.03838, -0.97035, -0.86933, -0.84752, -0.85351, -0.88884, -0.84457, -0.62424, -0.57393, -0.53787, -0.43977, -0.53185, -0.65374, -0.66512, -0.85547, -1.09925, -1.12721, -1.12972, -1.19837, -1.35018, -1.52202, -1.63666, -1.86471, -2.09340, -2.26591, -2.19105, -1.99546, -1.81553, -1.64141, -1.55488, -1.57814, -1.56445, -1.51759, -1.52060, -1.57277, -1.60969, -1.66993, -1.71608, -1.86278, -1.79544, -1.87201, -2.08483, -2.15962, -2.26594, -2.29691, -2.06218, -1.97263, -2.06546, -1.96552, -1.85076, -1.86411, -1.92481, -2.00289, -1.93748, -1.95592, -1.92508, -1.91089, -1.86450, -1.87989, -1.94447, -1.87736, -1.69435, -1.60143, -1.54501, -1.52206, -1.47282, -1.37068, -1.19046, -1.10168, -0.94923, -0.96934, -0.91577, -1.02456, -1.27970, -1.44736, -1.64266, -1.84296, -1.75774, -1.77292, -1.92335, -1.89894, -1.84249, -1.88059, -1.88238, -1.92546, -1.74182, -1.61554, -1.53018, -1.56895, -1.60685, -1.58226, -1.51682, -1.41439, -1.31628, -1.37571, -1.40664, -1.42346, -1.35793, -1.31814, -1.09005, -0.97397, -0.92680, -1.04760, -0.99062, -0.85323, -0.69488, -0.42504, -0.15332, 0.04699, 0.42300, 0.61186, 0.48212, 0.42916, 0.45468, 0.39301, 0.41885, 0.31129, 0.22118, -0.00758, -0.25354, -0.41399, -0.45132, -0.49235, -0.64697, -0.83867, -0.98140, -1.17451, -1.32701, -1.49108, -1.55492, -1.71120, -1.81794, -2.00804, -2.13323, -2.37029, -2.43337, -2.41199, +-2.00118, -2.03272, -2.10379, -2.03192, -1.79969, -1.59679, -1.48359, -1.32275, -1.29444, -1.26943, -1.26739, -1.29853, -1.28762, -1.23294, -1.21206, -1.42500, -1.74050, -1.85645, -1.99477, -2.01383, -1.93200, -2.01874, -2.13184, -2.20594, -2.37264, -2.47769, -2.50029, -2.58348, -2.72738, -2.98516, -3.12922, -3.14739, -3.14818, -3.10862, -3.11010, -3.14468, -3.15299, -3.18825, -3.15689, -2.96826, -2.76431, -2.51881, -2.24122, -2.07768, -1.91545, -1.77437, -1.61998, -1.59870, -1.60592, -1.44348, -1.29808, -1.25002, -1.25525, -1.48482, -1.63345, -1.52607, -1.38127, -1.31146, -1.28557, -1.32925, -1.27330, -1.23180, -1.08374, -0.90790, -0.61656, -0.35974, -0.23980, -0.14523, -0.02827, -0.01659, -0.03833, -0.02461, 0.11072, 0.22058, 0.38417, 0.39577, 0.39298, 0.44190, 0.57892, 0.66432, 0.82681, 1.10017, 1.26457, 1.26460, 1.29084, 1.19241, 1.12554, 1.12029, 0.98273, 0.76103, 0.68948, 0.69150, 0.83041, 0.94142, 1.06923, 1.10532, 1.05894, 0.99840, 0.92887, 0.87675, 0.94961, 1.02900, 1.08701, 1.06425, 1.06322, 0.91820, 0.82036, 0.61897, 0.45121, 0.32018, 0.34332, 0.17684, -0.12270, -0.39786, -0.59672, -0.72398, -0.64256, -0.70987, -0.84313, -0.85486, -0.80840, -0.85579, -0.86062, -0.95573, -0.94484, -1.08610, -1.25575, -1.41219, -1.64537, -1.85964, -2.04723, -2.19946, -2.10974, -2.06156, -2.09257, -2.25083, -2.41444, -2.63582, -2.73575, -2.82133, -2.74340, -2.72350, -2.67641, -2.82219, -2.96461, -2.91442, -2.72013, -2.69337, -2.68974, -2.79741, -2.88515, -2.81153, -2.67296, -2.60630, -2.44990, -2.47263, -2.41712, -2.40809, -2.35354, -2.24141, -2.12896, -1.94366, -1.76179, -1.68072, -1.46133, -1.31022, -1.23086, -1.19833, -1.12593, -1.09397, -0.89195, -0.77549, -0.61818, -0.53299, -0.30917, -0.10783, 0.00115, 0.04776, 0.08688, 0.03787, 0.11815, 0.19501, 0.21047, 0.33938, 0.57569, 0.53551, 0.48519, 0.32548, 0.19733, 0.03387, -0.15987, -0.27550, -0.28938, -0.27221, -0.26202, -0.42259, -0.51148, -0.51125, -0.49845, -0.39519, -0.15882, -0.07237, -0.00367, -0.06930, -0.03215, 0.07055, 0.29615, 0.41110, 0.30466, 0.20215, 0.23063, 0.18827, 0.16027, 0.14974, 0.01693, -0.14865, -0.17700, -0.29912, -0.28740, -0.30755, -0.30767, -0.30291, -0.41127, -0.57546, -0.77825, -1.04527, -1.31995, -1.62980, -1.80811, -1.81176, -1.75970, -1.71854, -1.63219, -1.67860, -1.64174, -1.54439, -1.40493, -1.37589, -1.41972, -1.49711, -1.69027, -1.78500, -1.70208, -1.57576, -1.38476, -1.28237, -1.34538, -1.39092, -1.37550, -1.52729, -1.70117, -1.79911, -1.75854, -1.67285, -1.72060, -1.81939, -1.90765, -1.86907, -1.74022, -1.54641, -1.28855, -1.04285, -0.95432, -0.98057, -0.90864, -0.83475, -0.72728, -0.67870, -0.70478, -0.72298, -0.66625, -0.53071, -0.56305, -0.53307, -0.42424, -0.49163, -0.60761, -0.72070, -0.95725, -1.16227, -1.19246, -1.25626, -1.36745, -1.49058, -1.61912, -1.72488, -1.93965, -2.07694, -2.13442, -2.01173, -1.77949, -1.60077, -1.46840, -1.35126, -1.30642, -1.24736, -1.14002, -1.15496, -1.28407, -1.34835, -1.42005, -1.45044, -1.56147, -1.58039, -1.76053, -1.99603, -2.05699, -2.06020, -2.04768, -1.95063, -2.00712, -2.04954, -1.86238, -1.74177, -1.75098, -1.82239, -1.97233, -1.98934, -2.06594, -1.97985, -1.87013, -1.81947, -1.84241, -1.93137, -1.92898, -1.72258, -1.53524, -1.46019, -1.43755, -1.39605, -1.37673, -1.23354, -1.16638, -0.96159, -0.87073, -0.84017, -1.04380, -1.32100, -1.46070, -1.57609, -1.67038, -1.62036, -1.71806, -1.81181, -1.74441, -1.71980, -1.82397, -1.85589, -1.92731, -1.78062, -1.71896, -1.67275, -1.68835, -1.76285, -1.76204, -1.68334, -1.61443, -1.52197, -1.52714, -1.54325, -1.51945, -1.42086, -1.43714, -1.24873, -1.14147, -1.04168, -0.99606, -0.83068, -0.75444, -0.67464, -0.47858, -0.15692, 0.17707, 0.52881, 0.61764, 0.46151, 0.34712, 0.28715, 0.15108, 0.19815, 0.11051, 0.03475, -0.20305, -0.43539, -0.51002, -0.50987, -0.50965, -0.64474, -0.88357, -1.02183, -1.15898, -1.31835, -1.48467, -1.49351, -1.67229, -1.81443, -2.04719, -2.17542, -2.28700, -2.28490, -2.30390, +-1.82068, -1.72084, -1.68719, -1.74621, -1.70953, -1.49980, -1.36471, -1.18064, -1.07442, -1.03909, -1.00984, -1.14517, -1.20127, -1.08615, -1.04779, -1.19092, -1.38598, -1.51321, -1.74186, -1.80080, -1.76152, -1.75168, -1.84932, -2.00765, -2.13981, -2.30529, -2.42447, -2.55185, -2.77249, -3.01188, -3.12512, -3.19605, -3.20427, -3.12005, -3.04480, -3.15595, -3.24779, -3.14681, -2.98620, -2.78088, -2.57632, -2.38515, -2.11582, -1.99040, -1.85180, -1.56070, -1.34921, -1.32976, -1.28361, -1.10157, -1.01443, -0.96850, -1.01231, -1.18199, -1.31578, -1.35367, -1.24754, -1.26909, -1.31041, -1.29575, -1.18628, -1.06001, -0.89440, -0.87132, -0.70777, -0.46556, -0.23329, -0.11082, -0.02475, 0.06349, 0.05788, -0.00052, 0.12386, 0.24300, 0.47288, 0.53763, 0.47177, 0.54089, 0.61089, 0.61529, 0.78502, 1.08564, 1.20125, 1.22955, 1.26317, 1.24744, 1.24677, 1.11874, 1.01821, 0.82978, 0.76796, 0.83199, 0.93416, 1.01095, 1.11117, 1.00461, 0.90955, 0.88986, 0.94147, 0.85422, 0.74521, 0.75739, 0.78001, 0.70377, 0.73631, 0.69360, 0.70226, 0.54300, 0.28980, 0.20980, 0.23675, 0.06351, -0.18670, -0.36573, -0.57839, -0.68915, -0.63841, -0.70360, -0.76128, -0.87117, -0.76827, -0.77338, -0.84120, -0.96098, -1.05404, -1.23661, -1.33625, -1.50216, -1.68320, -1.87034, -2.01439, -2.20202, -2.26080, -2.21040, -2.14439, -2.24884, -2.38840, -2.61991, -2.74514, -2.84261, -2.88226, -2.82813, -2.73800, -2.84813, -2.93483, -2.78331, -2.64337, -2.65735, -2.66127, -2.72543, -2.64871, -2.65282, -2.56058, -2.53251, -2.50833, -2.56547, -2.52310, -2.47811, -2.28524, -2.20261, -2.10915, -1.94570, -1.72055, -1.58778, -1.45720, -1.27791, -1.11096, -1.11004, -1.06590, -1.02041, -0.79136, -0.60509, -0.54192, -0.45446, -0.21299, -0.03763, 0.02829, 0.10189, 0.06520, -0.02578, 0.08546, 0.16210, 0.25445, 0.22291, 0.30581, 0.26760, 0.20982, 0.15476, 0.11501, -0.07654, -0.25439, -0.44667, -0.48573, -0.42393, -0.27042, -0.26324, -0.43272, -0.50824, -0.46433, -0.40045, -0.19140, -0.08220, 0.02551, 0.05502, 0.00659, 0.07610, 0.30089, 0.37695, 0.27226, 0.29466, 0.36717, 0.32090, 0.30939, 0.26978, 0.22700, 0.01326, -0.07221, -0.09596, -0.04109, -0.03191, -0.00737, -0.08688, -0.19849, -0.40806, -0.65049, -0.88294, -1.10219, -1.36641, -1.67763, -1.77760, -1.63987, -1.56063, -1.46758, -1.46929, -1.40154, -1.24912, -1.24634, -1.31916, -1.32419, -1.35244, -1.44503, -1.39277, -1.30255, -1.29852, -1.21227, -1.18003, -1.13216, -1.13007, -1.17425, -1.31805, -1.55674, -1.69285, -1.60030, -1.52002, -1.46509, -1.49406, -1.64484, -1.65482, -1.54788, -1.33556, -1.20016, -1.06708, -0.88463, -0.86209, -0.81958, -0.75294, -0.67968, -0.60789, -0.70675, -0.77420, -0.61807, -0.47045, -0.51774, -0.45949, -0.39437, -0.56220, -0.69009, -0.78607, -0.87811, -1.06015, -1.25201, -1.38247, -1.57005, -1.69810, -1.70106, -1.72426, -1.83743, -1.90886, -1.99831, -1.83787, -1.52977, -1.25715, -1.20316, -1.21078, -1.09754, -1.00757, -0.96579, -0.99503, -1.10767, -1.08163, -1.12416, -1.22368, -1.29091, -1.39663, -1.68644, -1.90553, -1.92392, -1.93677, -1.91958, -1.89831, -1.93525, -1.94525, -1.86483, -1.70610, -1.66601, -1.71300, -1.82233, -1.89375, -2.00611, -1.92108, -1.89732, -1.83870, -1.79128, -1.78003, -1.83399, -1.78626, -1.60172, -1.50619, -1.51933, -1.44239, -1.36873, -1.18114, -1.13623, -1.07355, -0.97027, -0.94446, -1.12602, -1.26852, -1.25529, -1.39062, -1.51683, -1.55992, -1.64943, -1.65874, -1.66501, -1.58562, -1.68747, -1.78807, -1.84579, -1.74308, -1.72261, -1.69060, -1.84993, -1.98186, -1.97590, -1.85640, -1.85681, -1.91618, -1.87262, -1.74061, -1.63859, -1.49835, -1.50602, -1.37276, -1.31557, -1.30124, -1.13172, -0.82922, -0.69884, -0.60954, -0.38829, -0.16011, 0.12675, 0.43865, 0.58679, 0.57947, 0.35670, 0.26142, 0.09845, 0.07611, 0.03693, -0.00076, -0.19673, -0.35372, -0.51567, -0.57484, -0.60382, -0.69354, -0.91494, -1.14656, -1.24899, -1.32755, -1.52285, -1.58166, -1.78741, -1.92629, -2.08328, -2.21634, -2.20838, -2.13863, -2.18716, +-1.57690, -1.46057, -1.35062, -1.39999, -1.46577, -1.34430, -1.22382, -1.03913, -0.90420, -0.85382, -0.84051, -1.02949, -1.14672, -1.06928, -0.99069, -1.02334, -1.19165, -1.35013, -1.54875, -1.58476, -1.58781, -1.59889, -1.61978, -1.71675, -1.83809, -2.04500, -2.29886, -2.57134, -2.85978, -3.10357, -3.10149, -3.05628, -3.10860, -3.11990, -3.05284, -3.13371, -3.18843, -3.00865, -2.76075, -2.55122, -2.39488, -2.29309, -2.11018, -2.00806, -1.83548, -1.44547, -1.12968, -1.04827, -1.04234, -0.91336, -0.79402, -0.69682, -0.75973, -0.96806, -1.07869, -1.11611, -1.10479, -1.20168, -1.29371, -1.30933, -1.15616, -1.00179, -0.79761, -0.75573, -0.74137, -0.66149, -0.38582, -0.16910, -0.01915, 0.10586, 0.11245, 0.02172, 0.08847, 0.19035, 0.43361, 0.57036, 0.56503, 0.63606, 0.69194, 0.70454, 0.79297, 0.98381, 1.11546, 1.23994, 1.30726, 1.29076, 1.31364, 1.23890, 1.16563, 1.02898, 1.00116, 1.02096, 1.06329, 1.02544, 1.04429, 0.95894, 0.83637, 0.74753, 0.85642, 0.79276, 0.60899, 0.49297, 0.41532, 0.30295, 0.34653, 0.40350, 0.49312, 0.35849, 0.10924, 0.04087, 0.07257, -0.03083, -0.27197, -0.49314, -0.66343, -0.70541, -0.69222, -0.82422, -0.85329, -0.85999, -0.70747, -0.67219, -0.75564, -0.96669, -1.15970, -1.42352, -1.49706, -1.54119, -1.66626, -1.93898, -2.08269, -2.26093, -2.38427, -2.37916, -2.29874, -2.32392, -2.41990, -2.65061, -2.79476, -2.92565, -3.00503, -2.95398, -2.83321, -2.81333, -2.85479, -2.76646, -2.67232, -2.67241, -2.66456, -2.72300, -2.54398, -2.41836, -2.33378, -2.36753, -2.46066, -2.62364, -2.59326, -2.51813, -2.24674, -2.06604, -1.96699, -1.97279, -1.80750, -1.63092, -1.48450, -1.27327, -1.09507, -1.11835, -1.10528, -1.05274, -0.80336, -0.58846, -0.52211, -0.43541, -0.20956, 0.00934, 0.03975, 0.01045, -0.05125, -0.08613, 0.06786, 0.10224, 0.16506, 0.14484, 0.12684, 0.05328, 0.00228, -0.06434, -0.08914, -0.31602, -0.50518, -0.64469, -0.66497, -0.67868, -0.48379, -0.30108, -0.38153, -0.46028, -0.42716, -0.37855, -0.19538, -0.07985, 0.07325, 0.15638, 0.10179, 0.13689, 0.27887, 0.36353, 0.29456, 0.30901, 0.44219, 0.49836, 0.53722, 0.43100, 0.33733, 0.20940, 0.17372, 0.22828, 0.32714, 0.28003, 0.22941, 0.02650, -0.15254, -0.30849, -0.47658, -0.73110, -0.97622, -1.20992, -1.51581, -1.63511, -1.49454, -1.38708, -1.27984, -1.26864, -1.19039, -1.06872, -1.15607, -1.27820, -1.27440, -1.17940, -1.12111, -1.05346, -0.99550, -1.03058, -1.03583, -1.10353, -1.08670, -0.99232, -0.96883, -1.08139, -1.30291, -1.49272, -1.46679, -1.42137, -1.32694, -1.19832, -1.24019, -1.33205, -1.33716, -1.14599, -1.03539, -0.94629, -0.76122, -0.71729, -0.70145, -0.69227, -0.69449, -0.66466, -0.77599, -0.80755, -0.57818, -0.34947, -0.33798, -0.38712, -0.47035, -0.65576, -0.73336, -0.79085, -0.85996, -0.99397, -1.19932, -1.42170, -1.65589, -1.80331, -1.78747, -1.73230, -1.78755, -1.75553, -1.72064, -1.56757, -1.33482, -1.03995, -0.97956, -1.03376, -0.94938, -0.89143, -0.90182, -0.94395, -1.01632, -0.92687, -0.91065, -0.98898, -1.04219, -1.16900, -1.47568, -1.76313, -1.87042, -1.87587, -1.82581, -1.85203, -1.94462, -1.94530, -1.83145, -1.67436, -1.58247, -1.57759, -1.71720, -1.82225, -1.97281, -1.86413, -1.76169, -1.71553, -1.73173, -1.67655, -1.71321, -1.73868, -1.64621, -1.58016, -1.58438, -1.46856, -1.32670, -1.11829, -1.09497, -1.12218, -1.08058, -1.02685, -1.06420, -1.10095, -1.08195, -1.19887, -1.32409, -1.46892, -1.65098, -1.64826, -1.55785, -1.44080, -1.54039, -1.68973, -1.83584, -1.78961, -1.84307, -1.82696, -1.94638, -2.12643, -2.26056, -2.18894, -2.20732, -2.28261, -2.20970, -1.98594, -1.78851, -1.62197, -1.62299, -1.55281, -1.56254, -1.54362, -1.30430, -0.90551, -0.63771, -0.54659, -0.44704, -0.30847, -0.05747, 0.20544, 0.35163, 0.46518, 0.39101, 0.32666, 0.18051, 0.13451, 0.04324, 0.01384, -0.16090, -0.26625, -0.36001, -0.47544, -0.69923, -0.82917, -1.00109, -1.19884, -1.26856, -1.33465, -1.54436, -1.69359, -1.95337, -2.07594, -2.15311, -2.17312, -2.07207, -1.97291, -1.99067, +-1.23731, -1.11411, -1.06375, -1.05282, -1.10451, -1.16800, -1.02678, -0.87258, -0.78631, -0.69433, -0.73815, -0.90295, -0.96396, -1.05519, -1.10001, -1.06079, -1.08410, -1.21736, -1.40768, -1.37427, -1.36282, -1.47192, -1.54306, -1.64180, -1.78894, -2.02972, -2.30882, -2.62719, -2.87589, -2.93303, -2.93548, -2.90553, -2.90805, -2.95987, -3.01898, -3.04806, -2.90662, -2.72518, -2.44288, -2.29970, -2.30478, -2.25499, -2.16942, -2.06130, -1.76599, -1.38345, -1.10737, -0.97061, -0.90260, -0.72126, -0.60212, -0.45220, -0.46438, -0.71834, -0.92180, -1.04924, -1.13622, -1.19630, -1.22999, -1.27523, -1.19473, -0.92192, -0.73574, -0.72936, -0.75439, -0.75639, -0.53811, -0.30053, 0.03053, 0.11960, 0.14356, 0.09651, 0.02693, 0.10607, 0.28439, 0.47407, 0.64761, 0.69254, 0.65654, 0.71517, 0.77549, 0.91267, 0.98225, 1.19542, 1.33888, 1.32608, 1.31115, 1.30651, 1.28558, 1.24927, 1.24324, 1.17476, 1.07608, 1.05268, 0.96466, 0.84927, 0.83605, 0.80736, 0.85530, 0.66672, 0.52988, 0.26561, 0.09648, 0.00979, -0.04926, 0.08102, 0.19189, 0.05530, -0.09374, -0.14144, -0.21423, -0.27107, -0.44627, -0.58830, -0.78410, -0.79350, -0.73656, -0.80604, -0.85343, -0.86468, -0.79771, -0.74304, -0.77505, -0.96700, -1.31230, -1.52124, -1.57819, -1.63052, -1.64985, -1.89003, -2.05871, -2.32230, -2.38909, -2.48975, -2.50796, -2.42356, -2.56294, -2.78663, -2.91064, -3.05179, -3.10554, -3.08013, -3.07173, -2.96310, -2.94126, -2.79852, -2.75779, -2.68727, -2.58397, -2.55546, -2.41283, -2.31312, -2.28706, -2.36466, -2.49221, -2.59003, -2.58031, -2.34932, -2.04523, -1.95255, -1.83661, -1.87408, -1.76084, -1.71045, -1.48182, -1.26556, -1.18184, -1.16907, -1.26141, -1.20396, -0.91921, -0.70757, -0.55766, -0.42664, -0.35518, -0.15934, -0.07085, 0.04748, -0.00490, -0.04342, 0.08521, 0.12036, 0.10897, 0.03693, -0.13410, -0.25984, -0.28366, -0.27824, -0.37420, -0.55895, -0.68440, -0.85637, -0.85180, -0.86105, -0.67154, -0.50647, -0.41909, -0.44091, -0.45620, -0.31659, -0.24243, -0.19960, 0.01126, 0.11950, 0.10683, 0.16749, 0.15551, 0.25664, 0.29805, 0.45888, 0.59115, 0.64299, 0.73136, 0.62920, 0.47067, 0.39953, 0.40556, 0.51037, 0.60097, 0.54325, 0.34672, 0.09326, -0.02509, -0.22662, -0.33434, -0.49968, -0.73511, -1.07938, -1.32274, -1.35673, -1.30490, -1.13069, -1.06571, -1.14294, -1.07028, -1.03661, -1.10247, -1.09473, -1.15059, -1.07305, -0.94022, -0.75658, -0.67952, -0.78373, -0.88509, -0.99140, -1.03634, -0.93923, -0.90312, -0.99665, -1.13235, -1.23618, -1.31562, -1.34518, -1.15011, -0.98070, -0.94115, -0.98915, -0.99615, -0.92980, -0.88467, -0.78551, -0.70913, -0.61800, -0.66698, -0.81503, -0.81093, -0.76716, -0.79691, -0.68473, -0.53954, -0.39809, -0.33549, -0.39842, -0.52904, -0.72349, -0.70664, -0.67520, -0.79365, -0.98488, -1.25015, -1.54435, -1.74326, -1.82555, -1.81760, -1.74983, -1.63551, -1.58694, -1.49497, -1.24558, -1.02449, -0.82719, -0.81709, -0.82911, -0.88941, -0.86411, -0.84398, -0.91687, -0.89304, -0.81965, -0.80055, -0.75404, -0.81160, -1.03523, -1.34975, -1.62107, -1.71783, -1.77681, -1.71765, -1.74515, -1.85250, -1.89341, -1.83976, -1.78614, -1.67417, -1.57499, -1.70799, -1.88592, -1.87009, -1.76326, -1.71590, -1.64190, -1.63716, -1.61835, -1.75089, -1.73723, -1.73250, -1.61760, -1.51421, -1.46505, -1.31365, -1.15853, -1.16560, -1.18594, -1.18546, -1.16116, -1.02499, -0.91952, -0.84169, -1.01986, -1.16763, -1.34410, -1.55517, -1.62659, -1.55036, -1.49073, -1.58860, -1.74326, -1.90744, -1.96535, -1.93265, -1.92824, -2.10365, -2.27081, -2.44760, -2.45840, -2.53718, -2.44217, -2.36751, -2.17329, -1.91365, -1.82904, -1.78941, -1.76611, -1.85559, -1.74176, -1.42391, -1.06363, -0.71184, -0.58896, -0.44368, -0.40691, -0.24942, -0.06149, 0.10042, 0.26953, 0.29017, 0.23315, 0.17961, 0.16460, 0.05634, -0.08316, -0.11346, -0.15090, -0.32688, -0.45966, -0.68591, -0.79317, -1.02489, -1.11321, -1.24347, -1.41134, -1.58124, -1.90887, -2.17980, -2.22057, -2.20767, -2.07206, -1.91048, -1.93671, -1.98722, +-1.12943, -1.05112, -0.91083, -0.76193, -0.75044, -0.82612, -0.72344, -0.62966, -0.56580, -0.48166, -0.53662, -0.64379, -0.72150, -0.92279, -1.05915, -1.07325, -1.12556, -1.28651, -1.44784, -1.35176, -1.34848, -1.54271, -1.67724, -1.79357, -1.96731, -2.25657, -2.46833, -2.59823, -2.77080, -2.79933, -2.82899, -2.87318, -2.86855, -2.91594, -2.89019, -2.73248, -2.49494, -2.31568, -2.15449, -2.15851, -2.21292, -2.12321, -1.99003, -1.86064, -1.61485, -1.34063, -1.11665, -0.98041, -0.93654, -0.78968, -0.66294, -0.49014, -0.45569, -0.70620, -0.96862, -1.17224, -1.29923, -1.31302, -1.24622, -1.17803, -1.21117, -1.06402, -0.88794, -0.85733, -0.83269, -0.82216, -0.57011, -0.22773, 0.11680, 0.19032, 0.21868, 0.20975, 0.16965, 0.24499, 0.35713, 0.52134, 0.68447, 0.66088, 0.63466, 0.73330, 0.72970, 0.72856, 0.74372, 0.98114, 1.15790, 1.14926, 1.14688, 1.23950, 1.31017, 1.32584, 1.29809, 1.25232, 1.07937, 0.92183, 0.81531, 0.74414, 0.79922, 0.77712, 0.73585, 0.56282, 0.41335, 0.15738, 0.02101, -0.10182, -0.20705, -0.09868, -0.04227, -0.18447, -0.36164, -0.49183, -0.58814, -0.62451, -0.74854, -0.88578, -1.07390, -1.07703, -0.96815, -0.95037, -0.97524, -1.03082, -1.08571, -1.08369, -1.05534, -1.02288, -1.29696, -1.56949, -1.64901, -1.73029, -1.75393, -1.98635, -2.13304, -2.22869, -2.25505, -2.43643, -2.55238, -2.55118, -2.71070, -2.89448, -2.97125, -3.05028, -3.14147, -3.25185, -3.29070, -3.14996, -3.12178, -3.04959, -3.02045, -2.87467, -2.68872, -2.61210, -2.53387, -2.51351, -2.49816, -2.56499, -2.60424, -2.44182, -2.32081, -2.16958, -1.99555, -1.99369, -1.88045, -1.85250, -1.68943, -1.56480, -1.36193, -1.25617, -1.26921, -1.33047, -1.48129, -1.40179, -1.10911, -0.86229, -0.66474, -0.58875, -0.57765, -0.39344, -0.23901, -0.05647, -0.07398, -0.15510, -0.13460, -0.15106, -0.18571, -0.23865, -0.40029, -0.53139, -0.54444, -0.41957, -0.50778, -0.79667, -0.94056, -1.05178, -1.00961, -1.03450, -0.89803, -0.66260, -0.49359, -0.50427, -0.47628, -0.30962, -0.28677, -0.25217, -0.02196, 0.12711, 0.10470, 0.05369, -0.01096, 0.15582, 0.27827, 0.43712, 0.49158, 0.49228, 0.60720, 0.54262, 0.45180, 0.47992, 0.54913, 0.62580, 0.61035, 0.60122, 0.45862, 0.19959, 0.10797, -0.08951, -0.19927, -0.37970, -0.63374, -0.90780, -1.08586, -1.12435, -1.10157, -0.94998, -0.90435, -0.98420, -0.94829, -0.95888, -0.99447, -0.97369, -1.04425, -0.99645, -0.91162, -0.75556, -0.68172, -0.76024, -0.85421, -0.97287, -1.05010, -0.98703, -0.96932, -1.04468, -1.09316, -0.99349, -0.97141, -1.11460, -1.03718, -0.90049, -0.84201, -0.87250, -0.84125, -0.71932, -0.66554, -0.64509, -0.63199, -0.57517, -0.70697, -0.90341, -0.86723, -0.74312, -0.69805, -0.61749, -0.61551, -0.54742, -0.47991, -0.57305, -0.70160, -0.84179, -0.76782, -0.75333, -0.96534, -1.18639, -1.41721, -1.60755, -1.69750, -1.67017, -1.57010, -1.58692, -1.54421, -1.48807, -1.38565, -1.12513, -0.92717, -0.71595, -0.61877, -0.65994, -0.80628, -0.83808, -0.80733, -0.79720, -0.69239, -0.66145, -0.70711, -0.68322, -0.74874, -0.89650, -1.13877, -1.41070, -1.57070, -1.69925, -1.70491, -1.75960, -1.83718, -1.82380, -1.78865, -1.81696, -1.77925, -1.65959, -1.66565, -1.86595, -1.85712, -1.72774, -1.72743, -1.68785, -1.68911, -1.65807, -1.74313, -1.77140, -1.77036, -1.58275, -1.44321, -1.40391, -1.30818, -1.22375, -1.23647, -1.28142, -1.29058, -1.18766, -0.95167, -0.85117, -0.88630, -1.10185, -1.23275, -1.32694, -1.48844, -1.59583, -1.60299, -1.65887, -1.82082, -1.98092, -2.04275, -2.14534, -2.21754, -2.21896, -2.38090, -2.54603, -2.75216, -2.77410, -2.69394, -2.50381, -2.42836, -2.31971, -2.17924, -2.11281, -1.99346, -1.90634, -1.93439, -1.79438, -1.52100, -1.18483, -0.84345, -0.73971, -0.62467, -0.58893, -0.50649, -0.41214, -0.30588, -0.12968, -0.05449, -0.06373, -0.02416, 0.01915, 0.02501, -0.13045, -0.22421, -0.26212, -0.48742, -0.65467, -0.84100, -0.87108, -0.95947, -1.04743, -1.30183, -1.54255, -1.75353, -2.09247, -2.24662, -2.19236, -2.09476, -1.98376, -1.96489, -2.04288, -2.06720, +-1.01753, -1.04461, -0.94382, -0.69603, -0.60953, -0.63672, -0.49647, -0.40197, -0.40073, -0.41995, -0.44295, -0.49231, -0.60154, -0.75420, -0.89495, -0.93771, -1.03329, -1.25789, -1.42462, -1.33217, -1.35786, -1.59758, -1.70601, -1.84808, -2.08305, -2.37482, -2.59922, -2.64757, -2.64389, -2.67353, -2.73782, -2.70861, -2.66488, -2.75974, -2.74683, -2.47394, -2.23395, -2.10629, -1.99897, -2.02385, -2.10157, -2.03122, -1.82082, -1.64844, -1.51527, -1.27112, -1.06544, -0.92316, -0.88604, -0.83073, -0.71878, -0.53822, -0.47510, -0.70080, -0.92518, -1.15352, -1.37912, -1.40803, -1.34849, -1.24926, -1.20422, -1.11617, -1.02521, -0.88398, -0.75088, -0.74614, -0.58361, -0.19943, 0.10378, 0.14775, 0.21314, 0.30571, 0.31617, 0.34114, 0.43060, 0.61386, 0.66860, 0.64790, 0.65522, 0.75972, 0.75646, 0.65218, 0.63584, 0.86805, 1.05134, 1.04744, 1.07970, 1.21520, 1.25847, 1.29355, 1.24287, 1.18308, 1.08376, 0.91279, 0.73509, 0.76265, 0.84477, 0.74539, 0.52069, 0.35441, 0.20278, -0.01149, -0.06917, -0.13679, -0.27529, -0.29373, -0.32771, -0.42416, -0.70994, -0.88965, -0.95072, -0.96056, -0.98568, -1.11281, -1.26953, -1.25899, -1.15396, -1.13989, -1.14349, -1.18233, -1.34763, -1.38523, -1.35098, -1.24919, -1.33504, -1.53217, -1.73075, -1.78520, -1.81846, -2.07712, -2.32732, -2.34053, -2.31739, -2.52791, -2.66846, -2.66099, -2.83847, -3.05900, -3.15750, -3.13343, -3.28199, -3.43807, -3.43360, -3.28684, -3.22065, -3.22104, -3.23873, -3.10778, -2.91558, -2.83332, -2.75194, -2.68459, -2.69605, -2.71498, -2.64197, -2.39248, -2.15164, -1.97150, -1.98309, -1.97888, -1.81656, -1.71149, -1.61460, -1.50726, -1.34814, -1.36256, -1.44584, -1.48748, -1.67444, -1.67608, -1.45801, -1.12126, -0.91388, -0.84831, -0.77528, -0.58525, -0.38456, -0.22316, -0.24859, -0.34862, -0.37813, -0.43398, -0.48109, -0.42923, -0.55473, -0.67452, -0.67474, -0.58813, -0.65742, -0.89008, -1.13495, -1.17731, -1.03604, -1.03114, -1.02732, -0.84672, -0.65575, -0.68249, -0.64045, -0.39713, -0.34297, -0.32094, -0.14204, 0.08463, 0.04266, -0.10214, -0.14898, 0.01392, 0.17963, 0.31410, 0.31765, 0.31376, 0.45222, 0.44061, 0.43399, 0.59781, 0.66974, 0.68227, 0.62684, 0.59039, 0.53794, 0.47407, 0.36830, 0.17928, 0.12982, -0.05055, -0.41440, -0.72419, -0.87819, -0.97347, -0.98243, -0.79591, -0.71166, -0.80879, -0.87727, -0.88570, -0.94778, -1.01595, -1.03872, -0.98874, -0.90070, -0.76288, -0.73430, -0.76861, -0.79927, -0.90835, -1.00923, -0.92039, -0.94418, -1.04934, -1.03283, -0.86714, -0.75731, -0.80481, -0.83745, -0.78885, -0.67181, -0.67443, -0.72689, -0.67820, -0.59673, -0.62739, -0.65671, -0.58244, -0.69596, -0.92463, -0.98323, -0.84030, -0.76211, -0.77775, -0.78006, -0.71876, -0.63911, -0.70208, -0.83897, -0.95159, -0.86751, -0.89394, -1.14577, -1.28375, -1.41797, -1.50184, -1.46476, -1.41072, -1.29372, -1.25370, -1.27911, -1.29153, -1.13845, -0.89490, -0.79834, -0.68692, -0.51449, -0.56698, -0.76081, -0.80300, -0.75020, -0.73967, -0.68880, -0.67392, -0.69941, -0.75883, -0.77306, -0.79416, -0.91912, -1.13424, -1.37195, -1.56247, -1.63087, -1.71377, -1.77732, -1.66496, -1.58138, -1.67927, -1.68319, -1.62776, -1.63462, -1.73867, -1.73572, -1.68355, -1.61228, -1.56087, -1.62557, -1.71644, -1.77804, -1.84994, -1.89839, -1.68859, -1.48186, -1.44951, -1.45020, -1.41583, -1.36918, -1.46205, -1.41750, -1.23480, -0.97073, -0.86131, -0.99158, -1.20954, -1.28679, -1.27812, -1.38502, -1.46971, -1.49801, -1.69792, -1.92032, -2.12900, -2.24469, -2.31411, -2.39725, -2.48527, -2.52845, -2.63219, -2.86368, -3.01349, -2.90112, -2.70569, -2.66529, -2.59157, -2.44212, -2.38132, -2.28786, -2.15067, -2.00905, -1.89910, -1.64779, -1.30319, -1.00381, -0.88627, -0.83041, -0.78841, -0.72276, -0.66700, -0.60755, -0.43662, -0.28917, -0.32020, -0.25757, -0.18845, -0.17185, -0.23786, -0.27626, -0.41429, -0.59237, -0.74451, -0.95062, -1.09377, -1.15493, -1.24183, -1.55307, -1.80181, -1.94052, -2.21791, -2.34607, -2.30921, -2.12918, -2.11466, -2.18724, -2.21922, -2.18652, +-1.01042, -0.97088, -0.94126, -0.74381, -0.57824, -0.51137, -0.42264, -0.36967, -0.31192, -0.30182, -0.39863, -0.46831, -0.43871, -0.49042, -0.72282, -0.86178, -0.88727, -1.05294, -1.23443, -1.17893, -1.25610, -1.53994, -1.76192, -1.99141, -2.14132, -2.32490, -2.60283, -2.75951, -2.67255, -2.61258, -2.65594, -2.59636, -2.45332, -2.43890, -2.46569, -2.25930, -2.01867, -1.89298, -1.87337, -1.94902, -1.94058, -1.75957, -1.59594, -1.52555, -1.36203, -1.06056, -0.93506, -0.88092, -0.78141, -0.69140, -0.63800, -0.49212, -0.45232, -0.66979, -0.93188, -1.23169, -1.43217, -1.40769, -1.40096, -1.39502, -1.25387, -1.08820, -1.04783, -0.96371, -0.74648, -0.58741, -0.45280, -0.13162, 0.16523, 0.25450, 0.29044, 0.34659, 0.44724, 0.56938, 0.61177, 0.68747, 0.78351, 0.87658, 0.82822, 0.79657, 0.81333, 0.78139, 0.71456, 0.90956, 1.09223, 1.09946, 1.07570, 1.07068, 1.12073, 1.25817, 1.22185, 1.08234, 1.04008, 0.95956, 0.73974, 0.68148, 0.74710, 0.70984, 0.42237, 0.18997, 0.05914, -0.04652, -0.11080, -0.27962, -0.41682, -0.38124, -0.46236, -0.66669, -0.93785, -1.03894, -1.16018, -1.30060, -1.27609, -1.23459, -1.34237, -1.31106, -1.23154, -1.26183, -1.31085, -1.44126, -1.58204, -1.53494, -1.54445, -1.60472, -1.63705, -1.70165, -1.91714, -2.04073, -2.09938, -2.24723, -2.50551, -2.55759, -2.50847, -2.64377, -2.79615, -2.88781, -3.03291, -3.11795, -3.19628, -3.26805, -3.40647, -3.44138, -3.47157, -3.48105, -3.40575, -3.28787, -3.34191, -3.29055, -3.14631, -3.07916, -2.97518, -2.94518, -2.90862, -2.75536, -2.62046, -2.48763, -2.24842, -1.99796, -2.02572, -2.06186, -1.88286, -1.61129, -1.51237, -1.51988, -1.43564, -1.43677, -1.53033, -1.66629, -1.87365, -1.83289, -1.65820, -1.45333, -1.25181, -1.02258, -0.89839, -0.82767, -0.66645, -0.41342, -0.42059, -0.49982, -0.51347, -0.59336, -0.68266, -0.72806, -0.81158, -0.76643, -0.71154, -0.75679, -0.88324, -1.03174, -1.25670, -1.31504, -1.16347, -1.03699, -1.01844, -0.92435, -0.76169, -0.72094, -0.65122, -0.49019, -0.44171, -0.31188, -0.12497, -0.00495, -0.05945, -0.08256, -0.12940, -0.16474, -0.08728, 0.13538, 0.20477, 0.24800, 0.41320, 0.42807, 0.43101, 0.52425, 0.58219, 0.69856, 0.72285, 0.62245, 0.57311, 0.67590, 0.63673, 0.40927, 0.32803, 0.24863, -0.04361, -0.39373, -0.59649, -0.70334, -0.73189, -0.66093, -0.62716, -0.63241, -0.67053, -0.79484, -0.95540, -0.96647, -0.93683, -0.97692, -0.94362, -0.73903, -0.69218, -0.73025, -0.71456, -0.79751, -0.90548, -0.90627, -0.99635, -1.01618, -0.91314, -0.79677, -0.74699, -0.71434, -0.71248, -0.72148, -0.63750, -0.55421, -0.53681, -0.55961, -0.54228, -0.56392, -0.58984, -0.58477, -0.71589, -0.84846, -0.88812, -0.88933, -0.92112, -0.87628, -0.77392, -0.77859, -0.78905, -0.77444, -0.84723, -0.96533, -0.88532, -0.92998, -1.15980, -1.28944, -1.37656, -1.27148, -1.08634, -1.07847, -1.08569, -0.98992, -0.94273, -0.98669, -0.90934, -0.68794, -0.55910, -0.53434, -0.42251, -0.43685, -0.57982, -0.69248, -0.75146, -0.71642, -0.59819, -0.61913, -0.71478, -0.73208, -0.65708, -0.71687, -0.88060, -0.99759, -1.13474, -1.34114, -1.43315, -1.52752, -1.58512, -1.48131, -1.44397, -1.48558, -1.40528, -1.40951, -1.54730, -1.59533, -1.51412, -1.50418, -1.49305, -1.43418, -1.43336, -1.58103, -1.70357, -1.77599, -1.82357, -1.71200, -1.61392, -1.54469, -1.43104, -1.41953, -1.47241, -1.52781, -1.38507, -1.26063, -1.14342, -1.01844, -1.02569, -1.20889, -1.21897, -1.14380, -1.23565, -1.35978, -1.50037, -1.69326, -1.82323, -2.07505, -2.39296, -2.51889, -2.56273, -2.69397, -2.76818, -2.81725, -2.90477, -3.08143, -3.07161, -2.90748, -2.81726, -2.75105, -2.68766, -2.62298, -2.44391, -2.29578, -2.19682, -2.04171, -1.67213, -1.37913, -1.25950, -1.15588, -0.99426, -0.93905, -0.87309, -0.83617, -0.81171, -0.68341, -0.62172, -0.62345, -0.44019, -0.36736, -0.48623, -0.54923, -0.50264, -0.63155, -0.82253, -0.96187, -1.08492, -1.28403, -1.43274, -1.51373, -1.69968, -1.89779, -2.09097, -2.33425, -2.36500, -2.34149, -2.30308, -2.32751, -2.27833, -2.28588, -2.32970, +-1.01428, -0.92509, -0.87693, -0.82931, -0.73835, -0.61077, -0.52861, -0.30571, -0.19579, -0.25569, -0.39271, -0.36354, -0.22733, -0.35364, -0.62006, -0.74675, -0.75591, -0.90404, -1.07367, -1.05407, -1.18270, -1.55219, -1.87013, -2.05573, -2.17681, -2.26678, -2.41660, -2.62301, -2.57188, -2.52206, -2.46342, -2.33574, -2.19863, -2.08882, -2.09177, -2.00569, -1.87407, -1.77824, -1.80787, -1.68819, -1.54823, -1.42227, -1.38523, -1.34182, -1.13289, -0.93240, -0.80734, -0.70050, -0.55808, -0.48776, -0.52562, -0.47039, -0.51494, -0.77579, -1.02668, -1.19565, -1.38123, -1.39198, -1.34140, -1.31884, -1.08821, -0.91705, -0.88585, -0.92084, -0.83909, -0.57922, -0.35729, -0.01328, 0.21699, 0.34642, 0.32070, 0.47837, 0.66980, 0.71553, 0.71690, 0.82437, 1.06793, 1.11686, 1.02444, 0.97729, 0.94498, 0.87142, 0.71544, 0.85713, 1.07699, 1.12407, 1.09590, 1.09950, 1.07751, 1.12490, 1.18429, 1.12903, 1.15321, 1.10295, 0.84965, 0.69342, 0.58206, 0.52164, 0.28772, 0.13563, -0.03149, -0.08023, -0.28527, -0.44685, -0.51906, -0.55337, -0.61738, -0.78136, -0.87123, -1.02792, -1.28084, -1.47497, -1.50480, -1.43781, -1.48397, -1.39764, -1.30500, -1.38045, -1.50156, -1.53007, -1.59651, -1.65864, -1.71257, -1.92448, -2.01395, -2.03806, -2.20961, -2.28881, -2.46298, -2.58843, -2.80767, -2.81220, -2.85567, -2.93683, -3.13264, -3.16375, -3.12123, -3.19036, -3.24473, -3.32807, -3.35353, -3.42563, -3.60638, -3.65915, -3.54636, -3.37959, -3.42433, -3.46197, -3.41176, -3.40303, -3.30408, -3.10484, -2.93638, -2.78965, -2.63223, -2.55760, -2.35774, -2.13103, -2.09973, -2.01628, -1.88899, -1.61867, -1.58350, -1.60906, -1.68254, -1.64905, -1.72190, -1.81305, -1.83571, -1.85679, -1.80870, -1.73058, -1.47687, -1.20478, -1.10895, -1.01204, -0.84386, -0.62649, -0.64552, -0.65564, -0.61151, -0.72368, -0.93149, -1.03176, -1.04498, -0.98936, -0.85019, -0.85580, -0.99559, -1.13495, -1.34805, -1.35192, -1.30569, -1.20099, -1.15254, -0.98031, -0.86981, -0.77822, -0.69663, -0.56973, -0.39217, -0.27274, -0.19514, -0.14089, -0.03092, 0.06825, -0.05532, -0.22241, -0.23976, -0.09533, 0.01045, 0.15994, 0.37797, 0.42175, 0.32280, 0.38945, 0.53003, 0.61693, 0.76033, 0.78920, 0.80640, 0.93872, 0.85036, 0.65196, 0.47142, 0.39392, 0.22551, 0.00413, -0.21515, -0.37134, -0.48123, -0.55423, -0.46118, -0.42720, -0.49982, -0.66555, -0.75551, -0.72755, -0.80481, -0.83886, -0.77422, -0.65061, -0.69634, -0.82239, -0.80944, -0.83194, -0.95572, -0.94394, -0.94438, -1.00202, -0.90606, -0.77175, -0.76370, -0.72187, -0.71562, -0.65279, -0.59017, -0.53396, -0.44380, -0.42596, -0.48294, -0.57686, -0.64692, -0.69641, -0.61721, -0.59306, -0.68938, -0.84715, -0.90877, -0.82368, -0.76512, -0.74723, -0.72612, -0.73305, -0.88273, -1.03651, -0.97332, -1.00510, -1.17949, -1.21609, -1.08947, -0.95528, -0.82041, -0.79970, -0.86205, -0.71330, -0.59817, -0.55603, -0.49193, -0.42585, -0.34034, -0.35982, -0.32440, -0.36621, -0.43247, -0.59222, -0.56241, -0.48064, -0.44418, -0.45050, -0.47718, -0.44199, -0.52080, -0.72146, -0.86655, -0.94104, -1.04373, -1.21013, -1.28473, -1.36472, -1.45053, -1.38532, -1.25029, -1.27406, -1.22740, -1.17035, -1.30604, -1.31159, -1.21269, -1.20002, -1.23185, -1.32363, -1.35465, -1.46681, -1.53033, -1.61607, -1.63610, -1.70123, -1.60865, -1.48135, -1.38317, -1.34409, -1.36392, -1.32476, -1.33959, -1.34955, -1.28823, -1.18905, -1.13161, -1.23065, -1.15648, -1.08641, -1.25999, -1.46174, -1.53082, -1.64985, -1.78851, -1.97177, -2.31635, -2.52372, -2.65452, -2.85436, -2.94901, -3.05262, -3.04685, -3.14884, -3.11313, -3.06565, -2.92546, -2.85676, -2.72448, -2.60370, -2.55465, -2.50874, -2.40543, -2.09307, -1.75191, -1.54261, -1.46289, -1.39600, -1.27197, -1.24281, -1.17936, -1.15184, -1.16036, -1.08378, -0.92947, -0.85175, -0.71870, -0.62291, -0.76738, -0.86415, -0.85238, -0.92713, -0.98839, -1.13955, -1.25133, -1.50710, -1.66263, -1.83676, -1.86501, -1.99467, -2.10701, -2.22540, -2.37747, -2.44180, -2.50052, -2.42610, -2.32613, -2.35411, -2.35381, +-0.88723, -0.85383, -0.82178, -0.84328, -0.81406, -0.65452, -0.56260, -0.32850, -0.22175, -0.29469, -0.38250, -0.30907, -0.21893, -0.38177, -0.54590, -0.60954, -0.66433, -0.83394, -1.04396, -1.11184, -1.26507, -1.63017, -2.00503, -2.19028, -2.24994, -2.25289, -2.20016, -2.25211, -2.23750, -2.25798, -2.17057, -1.95889, -1.82549, -1.70913, -1.68783, -1.65554, -1.60550, -1.57841, -1.63340, -1.47995, -1.29208, -1.18689, -1.20889, -1.17623, -1.03495, -0.91028, -0.68592, -0.46770, -0.31773, -0.26503, -0.39322, -0.48848, -0.59469, -0.81152, -1.03632, -1.17419, -1.31504, -1.31927, -1.20258, -1.02979, -0.78067, -0.68955, -0.66600, -0.71961, -0.72700, -0.49570, -0.23429, 0.12813, 0.32750, 0.44335, 0.40681, 0.52345, 0.69956, 0.73371, 0.75788, 0.91452, 1.15754, 1.15817, 1.12719, 1.16872, 1.06820, 0.91354, 0.69275, 0.75507, 1.01400, 1.16311, 1.19298, 1.16069, 1.07659, 1.04050, 1.10457, 1.21902, 1.28895, 1.21977, 0.97963, 0.83769, 0.63579, 0.44731, 0.21749, 0.11188, -0.05114, -0.14465, -0.45609, -0.70282, -0.80039, -0.84122, -0.83940, -0.89772, -0.89513, -1.05742, -1.29090, -1.39670, -1.48022, -1.45736, -1.48526, -1.44836, -1.35117, -1.38856, -1.53408, -1.58445, -1.65669, -1.80899, -1.92450, -2.11638, -2.25368, -2.32862, -2.48020, -2.47624, -2.67932, -2.87319, -3.07847, -3.07476, -3.14963, -3.23708, -3.43438, -3.49606, -3.40833, -3.43083, -3.42367, -3.43290, -3.44940, -3.60110, -3.80354, -3.72592, -3.58449, -3.44356, -3.44872, -3.58765, -3.61998, -3.62191, -3.54588, -3.32457, -3.09030, -2.89323, -2.70084, -2.51267, -2.30224, -2.16589, -2.11174, -1.89676, -1.75490, -1.62314, -1.72533, -1.81345, -1.96193, -1.94783, -1.97877, -2.06502, -1.99259, -1.96870, -1.94256, -1.86199, -1.62579, -1.39385, -1.26598, -1.00993, -0.81611, -0.69045, -0.73788, -0.78402, -0.75019, -0.84851, -1.08586, -1.28456, -1.30772, -1.22277, -1.04603, -0.91120, -1.00158, -1.19294, -1.42529, -1.38121, -1.36025, -1.34199, -1.32930, -1.14774, -1.03287, -0.92995, -0.82875, -0.74897, -0.58419, -0.47352, -0.41449, -0.28715, -0.08804, 0.02889, -0.05274, -0.13347, -0.18406, -0.19200, -0.14117, -0.01296, 0.20336, 0.32877, 0.24789, 0.26860, 0.40370, 0.48578, 0.69990, 0.92357, 1.07651, 1.14262, 0.95275, 0.79525, 0.61784, 0.49891, 0.35824, 0.20671, 0.06691, -0.07849, -0.23517, -0.41168, -0.37401, -0.31669, -0.35706, -0.44389, -0.47090, -0.49425, -0.62184, -0.55076, -0.46564, -0.49889, -0.66343, -0.92990, -0.98564, -0.94336, -1.01345, -1.01650, -1.03280, -1.10773, -1.03585, -0.85301, -0.77632, -0.76402, -0.79642, -0.66415, -0.52522, -0.48426, -0.40778, -0.38765, -0.47073, -0.60897, -0.70741, -0.75155, -0.61682, -0.48709, -0.51203, -0.66546, -0.74302, -0.76673, -0.78730, -0.66418, -0.54404, -0.57808, -0.77685, -0.97245, -0.97436, -0.98031, -1.04008, -0.99990, -0.80834, -0.69212, -0.62778, -0.56271, -0.53081, -0.37421, -0.27303, -0.16787, -0.00794, -0.01306, -0.05434, -0.13881, -0.13723, -0.16499, -0.19457, -0.33183, -0.30630, -0.22677, -0.20080, -0.15846, -0.14584, -0.19690, -0.41031, -0.64265, -0.70765, -0.79369, -0.91609, -1.07653, -1.20545, -1.26552, -1.30876, -1.28184, -1.17556, -1.19371, -1.16875, -1.06023, -1.04091, -1.02135, -0.97451, -0.96777, -0.96947, -1.13822, -1.26548, -1.34824, -1.36014, -1.39150, -1.37923, -1.51217, -1.52753, -1.47708, -1.40774, -1.32291, -1.26269, -1.21312, -1.33035, -1.34304, -1.21598, -1.17476, -1.14005, -1.20060, -1.17110, -1.16816, -1.37137, -1.61129, -1.71673, -1.80243, -1.92827, -2.05306, -2.20741, -2.41787, -2.67447, -2.93398, -2.97802, -3.06303, -3.07839, -3.12787, -3.05832, -3.03718, -2.90530, -2.81647, -2.73136, -2.65315, -2.65736, -2.65526, -2.49340, -2.16527, -1.91697, -1.73367, -1.59018, -1.58461, -1.57699, -1.60774, -1.64039, -1.63830, -1.62156, -1.55939, -1.41824, -1.31387, -1.19393, -1.09870, -1.10709, -1.17315, -1.20583, -1.21142, -1.10755, -1.15931, -1.28860, -1.58795, -1.78041, -2.02010, -2.03071, -2.09220, -2.18091, -2.25552, -2.43359, -2.51641, -2.56617, -2.50148, -2.44001, -2.42533, -2.28027, +-0.86982, -0.80728, -0.73978, -0.76036, -0.75548, -0.48983, -0.27481, -0.19115, -0.17759, -0.16192, -0.24085, -0.26855, -0.23976, -0.27172, -0.36489, -0.56233, -0.67915, -0.77797, -0.92512, -1.12350, -1.40536, -1.70084, -2.00668, -2.14619, -2.07761, -2.07796, -2.06340, -1.98793, -1.88150, -1.90880, -1.88009, -1.71662, -1.57921, -1.37231, -1.25289, -1.24013, -1.29815, -1.30084, -1.28342, -1.25969, -1.14234, -0.90711, -0.88294, -0.93276, -0.87051, -0.68369, -0.41606, -0.33376, -0.23948, -0.10997, -0.18739, -0.41893, -0.65581, -0.77713, -0.92039, -1.04819, -1.08728, -1.09327, -1.07860, -0.87680, -0.59856, -0.53991, -0.52755, -0.58072, -0.56398, -0.26967, 0.03287, 0.33370, 0.43644, 0.53648, 0.64297, 0.67839, 0.75975, 0.90797, 0.96837, 0.98907, 1.11166, 1.18059, 1.24995, 1.18910, 1.02734, 0.94995, 0.84406, 0.88071, 1.01731, 1.20330, 1.30730, 1.26932, 1.22081, 1.14019, 1.00322, 1.07187, 1.21110, 1.19234, 1.01780, 0.89276, 0.66410, 0.45154, 0.21083, 0.03706, -0.19264, -0.33478, -0.52449, -0.82626, -1.05042, -1.02028, -0.95521, -1.06219, -1.07774, -1.10510, -1.16630, -1.31773, -1.43587, -1.33431, -1.29394, -1.32512, -1.39658, -1.43901, -1.53423, -1.62670, -1.71848, -1.89413, -2.16108, -2.40308, -2.46772, -2.52478, -2.69559, -2.73080, -2.96309, -3.12716, -3.24430, -3.23735, -3.33126, -3.46541, -3.54639, -3.65777, -3.72420, -3.67247, -3.56912, -3.62016, -3.70691, -3.82371, -3.86863, -3.80886, -3.75180, -3.58549, -3.48629, -3.60329, -3.76803, -3.80086, -3.71525, -3.51874, -3.24129, -2.92084, -2.74542, -2.57620, -2.29346, -2.15765, -2.13574, -1.93953, -1.82336, -1.73197, -1.83649, -1.98348, -2.20497, -2.30176, -2.22786, -2.25980, -2.25519, -2.11375, -1.94993, -1.89282, -1.72420, -1.48130, -1.22512, -1.00547, -0.93729, -0.83143, -0.81474, -0.83949, -0.95094, -1.09146, -1.23222, -1.39532, -1.37741, -1.19605, -1.11297, -1.08908, -1.13335, -1.28693, -1.51775, -1.48667, -1.48381, -1.48239, -1.44400, -1.30697, -1.24204, -1.21399, -1.01190, -0.86226, -0.83783, -0.72515, -0.53183, -0.38169, -0.25613, -0.15266, -0.05333, -0.07464, -0.21384, -0.26064, -0.19833, -0.05220, 0.04132, 0.14335, 0.21205, 0.27867, 0.40281, 0.55452, 0.69599, 0.84445, 1.10215, 1.23666, 1.05269, 0.89901, 0.70210, 0.54575, 0.44674, 0.32154, 0.19861, 0.01984, -0.05774, -0.13886, -0.21046, -0.14978, -0.04858, -0.10148, -0.19986, -0.26567, -0.27504, -0.20288, -0.31317, -0.45613, -0.59461, -0.80188, -0.94495, -0.98184, -0.97355, -0.97023, -1.03907, -1.04666, -1.03815, -0.98542, -0.84977, -0.77637, -0.81516, -0.69632, -0.54920, -0.48678, -0.34302, -0.29398, -0.42092, -0.64260, -0.68441, -0.58862, -0.56830, -0.47317, -0.32141, -0.41291, -0.58409, -0.72153, -0.70990, -0.55085, -0.53598, -0.54640, -0.57230, -0.62693, -0.70325, -0.82289, -0.80405, -0.69190, -0.49643, -0.29554, -0.26767, -0.30609, -0.23562, -0.03931, 0.03824, 0.11417, 0.25632, 0.22950, 0.19911, 0.14333, 0.14085, 0.09003, 0.10729, 0.13776, 0.08880, 0.08802, 0.22088, 0.26590, 0.12882, -0.04623, -0.20998, -0.36946, -0.53367, -0.66325, -0.69662, -0.76883, -0.97284, -1.14616, -1.12838, -1.05679, -0.98172, -0.94751, -0.95936, -0.99699, -0.95764, -0.86306, -0.81765, -0.83321, -0.86950, -1.06016, -1.13674, -1.14704, -1.18756, -1.25308, -1.22799, -1.22551, -1.34251, -1.47478, -1.38738, -1.27811, -1.29245, -1.25434, -1.22907, -1.10576, -1.08156, -1.15157, -1.08980, -1.07650, -1.10892, -1.26909, -1.46890, -1.66601, -1.81760, -1.88811, -2.00517, -2.23687, -2.35990, -2.47176, -2.72553, -2.99635, -3.03201, -3.10233, -3.08433, -3.06319, -3.00931, -3.02693, -2.94220, -2.73916, -2.70411, -2.74163, -2.64209, -2.52942, -2.40593, -2.18066, -1.96154, -1.75868, -1.77976, -1.91064, -1.88966, -1.85295, -1.90945, -2.05444, -2.07621, -1.99970, -1.89482, -1.77068, -1.60424, -1.60721, -1.62987, -1.56818, -1.49536, -1.43070, -1.29373, -1.30126, -1.36891, -1.59501, -1.81894, -2.15127, -2.28934, -2.23284, -2.27152, -2.39236, -2.44457, -2.41979, -2.53761, -2.60991, -2.57765, -2.43631, -2.31745, +-0.89278, -0.84009, -0.73726, -0.70505, -0.61855, -0.31013, -0.05730, 0.03252, -0.02803, -0.06436, -0.09009, -0.09594, -0.13033, -0.16380, -0.23334, -0.49581, -0.71614, -0.85142, -0.95668, -1.12135, -1.34288, -1.55087, -1.76553, -1.86303, -1.83534, -1.86883, -1.84991, -1.70425, -1.57548, -1.61611, -1.62545, -1.51381, -1.41609, -1.22451, -1.01688, -0.93850, -0.98100, -1.00322, -1.03091, -1.02909, -0.98567, -0.76340, -0.58127, -0.50336, -0.46787, -0.33757, -0.11932, -0.11910, -0.11479, -0.04446, -0.09956, -0.31243, -0.53004, -0.60195, -0.72310, -0.82821, -0.85543, -0.88153, -0.88219, -0.67503, -0.42028, -0.38951, -0.38223, -0.42024, -0.39730, -0.15715, 0.12905, 0.42849, 0.57762, 0.73599, 0.88784, 0.96946, 1.00514, 1.08197, 1.17350, 1.19732, 1.19449, 1.18955, 1.26318, 1.21096, 1.08227, 1.03930, 1.03840, 1.12930, 1.21065, 1.37210, 1.43725, 1.40372, 1.33884, 1.18993, 0.97088, 0.99125, 1.09718, 1.07611, 0.99451, 0.93642, 0.70906, 0.39282, 0.05287, -0.19561, -0.44472, -0.52480, -0.63021, -0.85573, -1.11203, -1.18337, -1.09615, -1.08572, -1.08361, -1.08848, -1.05501, -1.15786, -1.25717, -1.21324, -1.21232, -1.24808, -1.37357, -1.40963, -1.52189, -1.63647, -1.75181, -1.97977, -2.29139, -2.52430, -2.59833, -2.71369, -2.92217, -2.96961, -3.16071, -3.33801, -3.42223, -3.39315, -3.45434, -3.52784, -3.59744, -3.73132, -3.90758, -3.98696, -3.88096, -3.78661, -3.81228, -3.92911, -3.90920, -3.87701, -3.90313, -3.83913, -3.75655, -3.77053, -3.89379, -3.85493, -3.78445, -3.61121, -3.34773, -3.03338, -2.79265, -2.54945, -2.25160, -2.17787, -2.23162, -2.08952, -1.99872, -1.96259, -2.06575, -2.23332, -2.46010, -2.52706, -2.43995, -2.39542, -2.35528, -2.23372, -2.00470, -1.80179, -1.61124, -1.46838, -1.26155, -1.10417, -1.11026, -1.09487, -1.10546, -1.05447, -1.11908, -1.17246, -1.25761, -1.37372, -1.34479, -1.22247, -1.20287, -1.17209, -1.16968, -1.32077, -1.55335, -1.54349, -1.54356, -1.59495, -1.60172, -1.54463, -1.52827, -1.45896, -1.22522, -0.97934, -0.91092, -0.86627, -0.67011, -0.44773, -0.33453, -0.32211, -0.22045, -0.17771, -0.27585, -0.33754, -0.31867, -0.16149, -0.08543, 0.07904, 0.26074, 0.38080, 0.49857, 0.57252, 0.61935, 0.76434, 1.07582, 1.27013, 1.14683, 1.00752, 0.81489, 0.58996, 0.43309, 0.29217, 0.18355, 0.08476, 0.06796, 0.06768, 0.03352, 0.00465, 0.06990, 0.12882, 0.10886, 0.00643, -0.03014, 0.01092, -0.15862, -0.39054, -0.59196, -0.74992, -0.86266, -0.88376, -0.85415, -0.82526, -0.86869, -0.90223, -0.94514, -0.90983, -0.73688, -0.65002, -0.70664, -0.63933, -0.50877, -0.45616, -0.32936, -0.23813, -0.32219, -0.48676, -0.49366, -0.41061, -0.43039, -0.45680, -0.35747, -0.31955, -0.38047, -0.55317, -0.61846, -0.50262, -0.51555, -0.48772, -0.39501, -0.29820, -0.29521, -0.40983, -0.40266, -0.30125, -0.10672, 0.11258, 0.13754, 0.10644, 0.22487, 0.40630, 0.42530, 0.44081, 0.52995, 0.46667, 0.38710, 0.35402, 0.37951, 0.35237, 0.41816, 0.51995, 0.53565, 0.46792, 0.48694, 0.54730, 0.47332, 0.23078, -0.02083, -0.19895, -0.39746, -0.56092, -0.60117, -0.57549, -0.66360, -0.79874, -0.74410, -0.68523, -0.62246, -0.60922, -0.70125, -0.81969, -0.77424, -0.67529, -0.65319, -0.64806, -0.66767, -0.84295, -0.95633, -0.99951, -1.07943, -1.17262, -1.12478, -1.07888, -1.15516, -1.36939, -1.44593, -1.34843, -1.26812, -1.17318, -1.07082, -0.87015, -0.85324, -1.01616, -1.08419, -1.09591, -1.08818, -1.23271, -1.39396, -1.60941, -1.77822, -1.88577, -2.06454, -2.32306, -2.40038, -2.46572, -2.72465, -2.98695, -3.03985, -3.15066, -3.21423, -3.19369, -3.13630, -3.15511, -3.05195, -2.81946, -2.68928, -2.71673, -2.68225, -2.50736, -2.26397, -2.09075, -1.99905, -1.84338, -1.92407, -2.12599, -2.18016, -2.14138, -2.12095, -2.25699, -2.28980, -2.30060, -2.24506, -2.14365, -2.00625, -1.97180, -1.89330, -1.72367, -1.60341, -1.53889, -1.42617, -1.45839, -1.57523, -1.77119, -1.98566, -2.34090, -2.51094, -2.47191, -2.43567, -2.47864, -2.51631, -2.43616, -2.44068, -2.57738, -2.68433, -2.55904, -2.41579, +-0.78695, -0.72369, -0.62560, -0.46833, -0.27549, -0.14356, -0.04446, 0.09922, 0.15497, 0.08989, -0.02132, -0.01605, -0.04347, -0.13062, -0.15120, -0.35247, -0.55990, -0.73096, -0.92874, -1.05434, -1.17876, -1.36529, -1.47211, -1.57582, -1.63157, -1.66172, -1.69441, -1.58989, -1.43820, -1.37769, -1.37045, -1.23575, -1.13605, -1.03310, -0.86729, -0.67633, -0.58207, -0.71889, -0.89683, -0.88180, -0.77878, -0.55030, -0.33223, -0.13821, -0.03092, 0.03927, 0.20311, 0.18566, 0.12172, 0.10373, -0.03499, -0.18693, -0.32518, -0.48394, -0.63707, -0.73340, -0.73170, -0.66866, -0.69044, -0.56757, -0.33201, -0.19427, -0.20430, -0.21051, -0.14575, 0.00379, 0.22013, 0.57629, 0.91200, 1.00280, 1.02890, 1.14117, 1.26329, 1.34459, 1.37777, 1.40888, 1.39130, 1.28844, 1.30102, 1.31854, 1.29715, 1.36357, 1.38493, 1.46322, 1.48143, 1.45984, 1.39145, 1.35869, 1.27550, 1.19924, 0.99367, 0.93276, 0.94316, 0.95640, 0.87034, 0.86238, 0.72297, 0.37206, -0.04656, -0.33922, -0.51030, -0.66005, -0.84764, -1.03139, -1.17895, -1.20943, -1.18450, -1.14580, -1.09421, -1.11651, -1.04202, -0.99190, -1.02360, -1.01551, -1.16647, -1.25354, -1.33807, -1.44429, -1.64075, -1.76441, -1.88789, -2.02661, -2.34753, -2.62098, -2.78270, -2.87817, -3.12708, -3.17817, -3.23712, -3.40420, -3.49914, -3.46901, -3.39197, -3.47660, -3.67620, -3.86277, -4.02731, -4.12396, -4.13728, -4.02613, -3.90325, -3.95411, -3.91815, -3.88515, -3.99881, -4.00556, -4.05382, -4.03427, -4.01981, -3.92703, -3.85963, -3.67105, -3.48696, -3.18413, -2.95693, -2.71342, -2.45724, -2.29638, -2.35433, -2.27991, -2.16746, -2.15602, -2.25648, -2.43659, -2.51318, -2.53101, -2.58571, -2.59244, -2.47647, -2.26751, -2.03619, -1.79606, -1.54699, -1.50821, -1.46051, -1.31654, -1.32135, -1.29052, -1.38232, -1.33232, -1.22879, -1.20890, -1.32315, -1.39544, -1.42349, -1.32341, -1.34746, -1.32320, -1.31988, -1.38306, -1.57163, -1.61066, -1.55636, -1.60289, -1.63306, -1.63225, -1.53564, -1.42135, -1.36335, -1.18446, -0.97997, -0.81296, -0.64972, -0.54122, -0.45037, -0.50550, -0.51051, -0.35645, -0.33016, -0.25704, -0.23785, -0.16400, -0.07661, 0.03960, 0.14086, 0.28907, 0.38759, 0.48807, 0.52261, 0.64148, 0.90232, 1.18974, 1.20057, 1.06010, 0.95110, 0.75128, 0.52794, 0.30878, 0.25508, 0.24794, 0.12513, 0.06193, 0.10456, 0.09971, 0.09150, 0.13498, 0.24531, 0.20211, 0.06969, 0.12055, 0.02620, -0.16524, -0.43013, -0.65795, -0.72310, -0.74575, -0.81674, -0.75489, -0.75607, -0.77155, -0.79790, -0.78569, -0.64988, -0.51357, -0.46413, -0.42871, -0.27318, -0.19715, -0.14849, -0.08095, -0.02030, -0.02063, -0.17023, -0.33637, -0.41771, -0.47116, -0.44721, -0.39225, -0.31298, -0.35930, -0.46847, -0.38491, -0.36876, -0.31584, -0.17877, -0.05278, 0.08197, 0.06459, -0.03729, -0.00200, 0.13820, 0.35369, 0.45275, 0.43643, 0.56473, 0.77296, 0.84815, 0.77654, 0.80749, 0.76023, 0.65101, 0.62472, 0.72094, 0.76849, 0.69999, 0.70242, 0.81022, 0.81068, 0.74069, 0.70954, 0.71535, 0.51245, 0.14292, -0.08569, -0.24275, -0.38552, -0.40709, -0.36706, -0.30936, -0.34899, -0.38609, -0.39649, -0.35047, -0.35894, -0.39465, -0.53342, -0.53569, -0.46989, -0.39699, -0.38948, -0.34436, -0.40500, -0.56261, -0.73556, -0.86190, -0.92852, -1.02860, -1.10056, -1.13688, -1.23333, -1.31633, -1.32173, -1.23013, -1.08705, -0.98891, -0.76054, -0.62466, -0.77104, -0.90919, -1.06628, -1.07903, -1.15979, -1.39485, -1.68517, -1.83181, -1.96279, -2.09988, -2.38635, -2.51777, -2.59614, -2.72899, -2.96266, -3.05447, -3.19371, -3.35685, -3.36679, -3.27508, -3.18968, -3.19229, -3.08700, -2.87970, -2.77111, -2.68856, -2.55220, -2.29383, -2.10640, -2.11811, -2.02616, -2.03083, -2.23648, -2.30389, -2.35068, -2.30278, -2.33423, -2.41527, -2.53369, -2.50630, -2.47139, -2.30246, -2.20657, -2.03832, -1.79754, -1.55965, -1.55423, -1.53053, -1.59442, -1.77199, -1.94931, -2.13783, -2.33220, -2.53821, -2.69762, -2.72999, -2.69836, -2.64210, -2.56509, -2.50978, -2.57844, -2.76508, -2.73834, -2.51592, +-0.58696, -0.44610, -0.42214, -0.31020, -0.06258, 0.06520, 0.15288, 0.30126, 0.33917, 0.23574, -0.00675, -0.10731, -0.06861, -0.08168, -0.14801, -0.33612, -0.45963, -0.60985, -0.85694, -1.05172, -1.15257, -1.25953, -1.23005, -1.25443, -1.37385, -1.43388, -1.45520, -1.32559, -1.24509, -1.24954, -1.20354, -1.05028, -0.87733, -0.74135, -0.72741, -0.64000, -0.47979, -0.51692, -0.60210, -0.51482, -0.40522, -0.20891, -0.07716, 0.04307, 0.22659, 0.38244, 0.44770, 0.28412, 0.15875, 0.08593, -0.08179, -0.21130, -0.26944, -0.36304, -0.45506, -0.47129, -0.43573, -0.34774, -0.35878, -0.25273, -0.10241, -0.05882, -0.07069, -0.06448, 0.08337, 0.33265, 0.48595, 0.72045, 1.06694, 1.18888, 1.22355, 1.39008, 1.53467, 1.61768, 1.59979, 1.56710, 1.61656, 1.59807, 1.51436, 1.36375, 1.35693, 1.49835, 1.56885, 1.63158, 1.60040, 1.53604, 1.44434, 1.47967, 1.37226, 1.26136, 1.09251, 1.04970, 0.98642, 0.82604, 0.64743, 0.60434, 0.53574, 0.37509, -0.01007, -0.41824, -0.61053, -0.77302, -0.98560, -1.10483, -1.21164, -1.21165, -1.22578, -1.30836, -1.23714, -1.13533, -1.03880, -1.04576, -1.02481, -0.99310, -1.18142, -1.29129, -1.33728, -1.38922, -1.58412, -1.65666, -1.79464, -1.97119, -2.29232, -2.53267, -2.72453, -2.94634, -3.22497, -3.31804, -3.36114, -3.40266, -3.50309, -3.60211, -3.52706, -3.55887, -3.73151, -3.81032, -3.93806, -4.05862, -4.17691, -4.25865, -4.11295, -3.98501, -3.89733, -3.99958, -4.17914, -4.21474, -4.29150, -4.23932, -4.16771, -3.97141, -3.83059, -3.54436, -3.39187, -3.24754, -3.15320, -2.93158, -2.68701, -2.55921, -2.56009, -2.49130, -2.38613, -2.29412, -2.39418, -2.67530, -2.72576, -2.64318, -2.67747, -2.62818, -2.48739, -2.25977, -2.02890, -1.90281, -1.67266, -1.56391, -1.55993, -1.56929, -1.58257, -1.50326, -1.58710, -1.51209, -1.33888, -1.22752, -1.29933, -1.26872, -1.28334, -1.26842, -1.34922, -1.33706, -1.35729, -1.51241, -1.71730, -1.77387, -1.70999, -1.63096, -1.58530, -1.62302, -1.52021, -1.35461, -1.34983, -1.19769, -0.96440, -0.76079, -0.59463, -0.64094, -0.62630, -0.60043, -0.56320, -0.45618, -0.41710, -0.25612, -0.18755, -0.13550, -0.08435, -0.03544, -0.02876, 0.14703, 0.27424, 0.39077, 0.46236, 0.62395, 0.87919, 1.05537, 1.03128, 0.90573, 0.83709, 0.77338, 0.60469, 0.27278, 0.13683, 0.16941, 0.07089, 0.05266, 0.14831, 0.14475, 0.11966, 0.09731, 0.23694, 0.34661, 0.27778, 0.23875, 0.10130, -0.06072, -0.32390, -0.54841, -0.59169, -0.58257, -0.65076, -0.55406, -0.53303, -0.59753, -0.65524, -0.62440, -0.46360, -0.37610, -0.32075, -0.21059, -0.02475, 0.12435, 0.17419, 0.10190, 0.09939, 0.16906, 0.04042, -0.17667, -0.28258, -0.37088, -0.35171, -0.32417, -0.26409, -0.15686, -0.13717, -0.12607, -0.20821, -0.21057, -0.11068, 0.04092, 0.24913, 0.37653, 0.34882, 0.39782, 0.50971, 0.60247, 0.63148, 0.64034, 0.83720, 1.03039, 1.03628, 0.94304, 0.92825, 0.93980, 0.94631, 0.90108, 0.93670, 1.01077, 0.96863, 1.01041, 1.22172, 1.23786, 1.11036, 0.96578, 0.86297, 0.69958, 0.39475, 0.11405, -0.11508, -0.21481, -0.19189, -0.14504, -0.06326, -0.05984, -0.08301, -0.09755, -0.02052, -0.06777, -0.09526, -0.14345, -0.07979, -0.06570, -0.15400, -0.20000, -0.15340, -0.12351, -0.15056, -0.39768, -0.67102, -0.76597, -0.85203, -0.91766, -0.90254, -0.94891, -1.00561, -1.06871, -1.11435, -1.01495, -0.86715, -0.66776, -0.60205, -0.68167, -0.79726, -1.01101, -1.09815, -1.24394, -1.50831, -1.81338, -1.88492, -2.01510, -2.19209, -2.47813, -2.59333, -2.68926, -2.89225, -3.09688, -3.19687, -3.33342, -3.40471, -3.41281, -3.39694, -3.31311, -3.31734, -3.23469, -2.95166, -2.79397, -2.68100, -2.54439, -2.38702, -2.19124, -2.12356, -2.09624, -2.25250, -2.48003, -2.54370, -2.60737, -2.54919, -2.53932, -2.52961, -2.58485, -2.48061, -2.48050, -2.42505, -2.34713, -2.08985, -1.79217, -1.62045, -1.65452, -1.68601, -1.77042, -1.82099, -1.95835, -2.24769, -2.41381, -2.56200, -2.74673, -2.76597, -2.79133, -2.76770, -2.68790, -2.68864, -2.67261, -2.71303, -2.69488, -2.61642, +-0.31543, -0.22510, -0.13183, -0.07775, 0.08956, 0.30220, 0.38484, 0.49825, 0.43552, 0.21871, 0.00829, -0.07105, -0.09941, -0.09560, -0.12581, -0.27468, -0.30375, -0.42163, -0.66163, -0.96328, -1.19754, -1.25734, -1.17394, -1.11017, -1.21835, -1.21216, -1.14343, -1.06382, -1.05181, -1.03326, -0.94528, -0.87762, -0.70882, -0.60450, -0.56631, -0.52279, -0.44250, -0.32765, -0.29050, -0.14307, -0.02082, 0.04851, 0.13686, 0.27258, 0.38848, 0.51884, 0.58158, 0.34557, 0.20957, 0.13706, -0.00391, -0.13398, -0.21469, -0.19796, -0.20901, -0.17691, -0.09504, 0.06274, 0.12534, 0.12116, 0.15927, 0.18209, 0.25135, 0.20126, 0.38186, 0.63659, 0.84702, 1.03371, 1.17690, 1.32798, 1.40586, 1.57616, 1.73667, 1.73133, 1.73396, 1.80611, 1.86177, 1.82543, 1.74663, 1.47786, 1.43183, 1.58636, 1.69267, 1.76718, 1.64775, 1.57654, 1.53883, 1.60385, 1.49443, 1.35694, 1.24333, 1.10708, 0.99163, 0.78949, 0.64092, 0.48392, 0.40780, 0.28352, 0.01893, -0.32276, -0.64963, -0.84563, -1.07838, -1.21098, -1.28401, -1.36581, -1.38465, -1.41254, -1.36041, -1.27534, -1.11499, -1.14414, -1.07470, -0.96365, -1.10015, -1.17806, -1.25216, -1.27587, -1.41813, -1.51228, -1.67467, -1.90346, -2.13896, -2.42047, -2.62540, -2.86245, -3.04009, -3.25480, -3.40759, -3.51300, -3.60477, -3.66882, -3.73851, -3.77426, -3.86258, -3.88056, -3.92464, -4.12048, -4.29117, -4.37900, -4.27597, -4.18347, -4.01394, -4.11184, -4.28906, -4.30126, -4.33346, -4.22785, -4.21131, -4.03782, -3.84901, -3.56725, -3.39644, -3.36119, -3.28484, -3.16060, -2.97477, -2.84063, -2.65412, -2.58638, -2.51610, -2.50065, -2.63063, -2.81290, -2.93996, -2.85340, -2.79122, -2.72912, -2.53610, -2.36369, -2.17488, -2.00952, -1.77853, -1.71537, -1.67536, -1.70883, -1.69613, -1.53993, -1.56696, -1.43695, -1.32069, -1.25057, -1.24089, -1.17769, -1.12669, -1.16288, -1.19696, -1.27158, -1.42662, -1.65496, -1.74988, -1.81494, -1.80876, -1.75613, -1.68547, -1.56186, -1.49848, -1.38318, -1.33680, -1.26286, -1.04418, -0.89473, -0.75302, -0.70842, -0.65712, -0.66138, -0.53025, -0.38531, -0.35861, -0.18118, -0.12121, -0.05683, -0.06984, -0.14303, -0.15615, -0.01582, 0.14501, 0.27341, 0.47876, 0.69573, 0.87708, 0.92248, 0.93540, 0.84513, 0.73533, 0.67378, 0.50680, 0.26730, 0.07113, 0.02773, 0.00970, -0.00907, 0.12282, 0.11898, 0.05102, 0.11473, 0.35653, 0.47026, 0.46094, 0.43438, 0.25393, 0.12445, -0.09772, -0.24389, -0.27840, -0.32340, -0.34501, -0.30223, -0.32550, -0.44280, -0.45740, -0.38139, -0.29752, -0.26575, -0.11012, 0.12018, 0.25809, 0.36839, 0.33151, 0.24742, 0.16428, 0.12462, 0.09396, -0.08246, -0.17153, -0.23996, -0.22965, -0.11280, 0.01415, 0.08623, 0.11604, 0.14560, 0.01768, -0.01410, 0.05347, 0.24125, 0.45797, 0.59377, 0.67482, 0.74448, 0.81050, 0.76296, 0.74644, 0.80778, 0.94269, 1.10438, 1.16652, 1.17091, 1.10125, 1.12410, 1.12801, 1.16602, 1.22858, 1.22276, 1.26363, 1.35781, 1.60572, 1.63892, 1.40892, 1.23760, 1.13122, 0.90433, 0.59644, 0.39408, 0.18609, 0.15536, 0.22549, 0.25522, 0.27546, 0.19970, 0.19668, 0.18987, 0.24179, 0.16849, 0.18179, 0.28904, 0.31819, 0.28067, 0.13927, 0.10627, 0.03806, 0.05062, 0.02843, -0.14070, -0.39018, -0.59527, -0.60427, -0.62148, -0.62733, -0.66320, -0.81058, -0.86159, -0.85247, -0.83858, -0.78040, -0.56686, -0.54791, -0.57717, -0.63873, -0.84341, -0.99582, -1.33448, -1.67350, -1.96044, -2.03863, -2.15198, -2.33723, -2.52666, -2.69184, -2.81562, -3.02432, -3.10527, -3.23751, -3.36848, -3.46216, -3.41647, -3.32091, -3.36248, -3.37909, -3.30091, -3.07632, -2.88817, -2.82980, -2.65048, -2.38496, -2.18438, -2.16869, -2.16464, -2.41931, -2.65171, -2.69081, -2.74328, -2.67551, -2.73074, -2.68945, -2.62190, -2.49738, -2.48557, -2.52247, -2.41403, -2.21031, -1.94398, -1.78001, -1.68481, -1.76882, -1.86370, -1.89435, -1.99076, -2.21198, -2.50251, -2.67178, -2.78638, -2.81583, -2.84759, -2.92654, -2.85820, -2.75476, -2.66375, -2.70372, -2.63284, -2.62873, +0.05395, 0.11049, 0.23750, 0.30915, 0.43847, 0.59669, 0.56683, 0.54309, 0.46920, 0.30960, 0.08860, -0.04341, -0.13850, -0.15316, -0.07096, -0.11395, -0.15865, -0.29866, -0.52769, -0.84805, -1.11224, -1.19271, -1.23877, -1.20822, -1.23353, -1.17945, -1.07253, -0.97165, -0.90012, -0.81496, -0.73989, -0.70370, -0.55447, -0.43772, -0.33182, -0.23606, -0.13220, 0.02211, 0.04216, 0.14777, 0.34894, 0.42711, 0.35122, 0.34914, 0.41871, 0.54400, 0.68221, 0.52850, 0.36279, 0.26552, 0.13167, -0.01054, -0.07584, 0.02117, -0.00248, -0.02627, 0.12136, 0.33445, 0.42322, 0.38226, 0.38297, 0.46324, 0.60346, 0.64681, 0.82734, 1.04328, 1.26187, 1.38610, 1.43286, 1.59548, 1.67678, 1.73723, 1.87227, 1.91905, 1.88214, 1.88076, 1.93122, 1.89103, 1.88515, 1.72227, 1.59381, 1.62164, 1.67064, 1.73740, 1.65097, 1.63573, 1.58781, 1.57355, 1.50446, 1.37974, 1.21319, 0.99567, 0.88839, 0.77302, 0.67501, 0.57145, 0.49090, 0.36018, 0.14740, -0.13177, -0.45268, -0.71140, -1.05934, -1.32500, -1.37264, -1.34873, -1.39700, -1.54694, -1.51883, -1.43638, -1.24920, -1.17942, -1.14221, -1.05816, -1.12532, -1.15422, -1.16169, -1.08732, -1.22228, -1.46910, -1.67950, -1.89986, -2.09369, -2.35289, -2.55583, -2.74370, -2.89890, -3.14339, -3.37841, -3.50496, -3.57013, -3.65662, -3.82399, -3.89095, -3.98195, -4.08651, -4.09949, -4.17816, -4.32296, -4.50600, -4.47371, -4.44264, -4.27084, -4.19518, -4.32750, -4.38940, -4.39243, -4.26780, -4.23322, -4.01782, -3.89432, -3.81029, -3.65545, -3.60960, -3.52196, -3.42375, -3.25223, -3.04536, -2.79258, -2.62953, -2.52672, -2.57391, -2.74475, -2.87850, -2.97438, -2.84766, -2.76092, -2.80659, -2.61962, -2.35942, -2.20959, -2.20630, -2.07106, -2.02280, -1.93925, -1.80817, -1.71040, -1.54584, -1.50856, -1.36988, -1.28331, -1.14732, -1.07295, -1.09799, -1.07647, -1.13117, -1.18209, -1.36450, -1.59115, -1.72396, -1.73117, -1.76735, -1.81228, -1.79683, -1.71780, -1.54304, -1.47115, -1.36242, -1.29606, -1.34594, -1.22391, -1.04064, -0.89083, -0.87854, -0.82166, -0.80048, -0.60449, -0.29813, -0.21252, -0.12321, -0.16032, -0.16178, -0.18976, -0.20857, -0.16732, -0.13613, -0.00754, 0.15296, 0.40865, 0.65764, 0.82788, 0.84599, 0.83811, 0.80273, 0.74896, 0.71996, 0.58083, 0.38191, 0.20926, 0.16187, 0.12231, -0.04009, -0.02132, 0.04920, 0.04513, 0.06952, 0.30937, 0.46162, 0.50974, 0.59396, 0.47417, 0.35551, 0.19094, 0.10950, 0.06269, 0.03262, 0.03482, -0.10897, -0.24250, -0.30726, -0.27525, -0.23692, -0.22937, -0.16642, 0.05464, 0.33732, 0.49115, 0.56257, 0.51116, 0.41487, 0.27304, 0.16391, 0.13082, -0.05109, -0.16081, -0.11010, 0.03031, 0.14471, 0.23718, 0.28282, 0.24962, 0.31884, 0.26716, 0.20436, 0.25937, 0.46523, 0.67561, 0.85080, 1.01208, 1.03102, 0.98637, 0.85005, 0.76198, 0.81392, 0.94991, 1.17596, 1.33507, 1.41224, 1.43518, 1.48130, 1.47326, 1.50421, 1.55091, 1.55068, 1.61661, 1.67390, 1.84343, 1.93284, 1.78009, 1.51354, 1.27473, 1.05649, 0.80518, 0.73311, 0.64722, 0.60733, 0.63431, 0.59649, 0.57164, 0.55514, 0.63112, 0.52432, 0.40101, 0.32676, 0.35988, 0.49432, 0.51065, 0.49152, 0.42926, 0.38978, 0.29485, 0.23496, 0.18600, 0.08537, -0.11893, -0.30920, -0.27692, -0.29943, -0.39947, -0.43395, -0.55887, -0.67307, -0.75821, -0.75782, -0.70713, -0.47204, -0.37303, -0.44037, -0.54609, -0.72640, -0.92743, -1.36505, -1.72198, -2.04003, -2.22185, -2.29358, -2.45721, -2.63423, -2.79878, -2.90833, -3.05398, -3.12805, -3.21984, -3.32115, -3.40315, -3.31287, -3.16640, -3.21398, -3.25384, -3.27991, -3.24170, -3.02766, -2.83279, -2.64032, -2.49462, -2.32088, -2.32978, -2.35804, -2.49185, -2.66894, -2.74303, -2.83686, -2.83019, -2.88503, -2.77278, -2.68227, -2.68201, -2.65672, -2.66619, -2.58114, -2.45889, -2.25675, -2.03329, -1.86490, -1.87871, -1.93570, -1.93116, -1.97256, -2.13800, -2.45680, -2.68005, -2.80816, -2.93127, -2.93469, -2.87937, -2.79552, -2.79236, -2.72514, -2.75459, -2.64584, -2.55367, +0.19077, 0.29533, 0.42492, 0.51025, 0.64565, 0.64601, 0.61917, 0.58569, 0.47419, 0.40218, 0.31860, 0.15268, 0.00782, 0.05666, 0.12240, 0.02908, -0.12335, -0.20941, -0.39274, -0.67326, -0.94984, -1.10267, -1.23823, -1.20268, -1.06271, -1.05311, -1.04212, -0.92932, -0.81997, -0.73390, -0.70888, -0.68461, -0.55882, -0.36908, -0.18585, -0.04450, 0.17281, 0.26582, 0.26476, 0.42733, 0.61592, 0.73422, 0.68587, 0.58293, 0.56454, 0.76056, 0.87179, 0.69483, 0.48986, 0.46067, 0.36489, 0.15692, 0.07802, 0.18591, 0.22348, 0.21843, 0.43877, 0.55743, 0.58247, 0.59276, 0.58614, 0.66820, 0.81149, 0.92803, 1.05805, 1.23560, 1.45665, 1.51196, 1.64647, 1.85231, 1.99282, 2.12774, 2.14443, 2.16098, 2.14134, 2.05267, 1.98322, 2.03608, 2.08110, 1.97722, 1.77744, 1.71609, 1.71285, 1.67417, 1.63356, 1.60737, 1.54446, 1.47231, 1.52226, 1.40240, 1.13768, 0.93343, 0.85021, 0.75725, 0.65500, 0.59114, 0.49471, 0.32847, 0.11019, -0.19038, -0.38414, -0.59820, -0.96210, -1.15026, -1.25727, -1.24931, -1.29742, -1.49182, -1.56338, -1.38626, -1.22547, -1.22459, -1.27270, -1.18666, -1.10273, -1.16543, -1.16223, -1.13359, -1.21406, -1.49695, -1.65126, -1.84140, -2.08460, -2.28341, -2.50828, -2.75287, -2.97263, -3.23673, -3.46323, -3.53624, -3.52090, -3.68652, -3.87306, -3.94921, -4.09708, -4.15700, -4.23555, -4.30353, -4.33517, -4.41086, -4.49789, -4.46052, -4.34211, -4.27899, -4.39541, -4.49962, -4.46633, -4.47072, -4.40265, -4.19924, -4.06561, -4.05324, -3.83621, -3.72388, -3.68910, -3.57317, -3.38669, -3.23198, -3.08092, -2.89389, -2.71742, -2.69800, -2.77113, -2.92066, -2.94361, -2.75672, -2.71561, -2.68142, -2.51859, -2.30177, -2.20275, -2.25019, -2.30284, -2.20068, -2.04130, -1.91585, -1.85278, -1.73710, -1.53764, -1.44017, -1.34615, -1.19206, -1.02701, -1.04797, -1.03200, -1.07406, -1.23706, -1.47143, -1.62781, -1.66339, -1.65788, -1.71535, -1.80732, -1.82508, -1.71785, -1.64138, -1.58387, -1.41978, -1.33810, -1.25607, -1.18312, -1.11243, -1.01145, -0.92197, -0.91061, -0.84085, -0.62267, -0.37153, -0.28932, -0.27596, -0.26977, -0.35381, -0.38514, -0.37478, -0.24067, -0.19624, -0.03364, 0.17102, 0.31378, 0.54641, 0.80913, 0.88261, 0.83403, 0.78177, 0.77059, 0.75420, 0.68931, 0.48082, 0.34665, 0.37652, 0.24596, 0.06333, 0.01012, 0.01952, 0.04247, 0.10821, 0.21822, 0.35941, 0.53311, 0.61698, 0.51127, 0.41326, 0.41902, 0.37648, 0.25362, 0.17705, 0.19171, 0.02232, -0.05269, 0.06434, 0.07909, 0.03156, 0.03022, 0.10210, 0.24884, 0.41915, 0.53585, 0.56964, 0.62507, 0.56513, 0.36284, 0.25124, 0.13011, 0.03426, 0.03020, 0.06314, 0.19329, 0.34832, 0.40815, 0.43511, 0.46040, 0.47579, 0.39769, 0.29949, 0.45223, 0.69394, 0.83556, 0.95429, 1.09526, 1.15335, 1.15650, 1.15421, 0.99149, 0.96470, 1.15264, 1.40811, 1.55880, 1.62581, 1.73588, 1.80148, 1.81932, 1.81287, 1.77880, 1.86842, 1.92242, 1.95003, 2.09279, 2.08640, 1.94990, 1.69683, 1.39879, 1.17670, 1.10214, 1.06594, 0.92943, 0.83059, 0.89169, 0.89696, 0.85394, 0.93470, 1.05770, 0.94640, 0.75331, 0.77081, 0.72561, 0.71498, 0.74121, 0.74874, 0.75019, 0.68858, 0.54518, 0.37671, 0.29500, 0.25447, 0.03969, -0.08346, -0.11265, -0.16833, -0.16834, -0.25119, -0.40598, -0.51272, -0.61948, -0.67642, -0.50563, -0.30215, -0.29972, -0.51101, -0.66022, -0.74174, -0.98224, -1.36876, -1.73978, -2.01606, -2.20621, -2.17133, -2.34433, -2.61313, -2.72423, -2.81114, -2.98108, -3.15420, -3.25992, -3.33145, -3.36467, -3.25246, -3.21861, -3.23131, -3.27818, -3.41105, -3.33941, -3.14829, -2.92464, -2.71771, -2.64675, -2.59764, -2.51141, -2.51240, -2.59368, -2.71043, -2.76351, -2.79975, -2.92458, -2.95687, -2.89991, -2.81594, -2.86046, -2.72680, -2.61885, -2.60297, -2.54159, -2.41703, -2.24448, -2.10751, -2.09556, -2.15774, -2.18540, -2.16627, -2.33336, -2.57015, -2.76573, -2.93272, -2.93744, -2.91362, -2.81808, -2.70541, -2.72176, -2.84284, -2.82973, -2.67316, -2.57598, +0.32243, 0.39176, 0.53944, 0.64075, 0.68485, 0.57078, 0.50235, 0.46351, 0.40049, 0.38668, 0.44575, 0.39631, 0.20247, 0.19986, 0.24079, 0.11584, -0.02156, -0.06432, -0.19791, -0.41351, -0.71475, -0.93549, -1.05391, -0.97877, -0.85213, -0.88442, -0.90912, -0.82357, -0.73228, -0.63058, -0.56032, -0.49542, -0.39703, -0.25623, -0.06278, 0.13273, 0.36108, 0.39363, 0.35510, 0.49254, 0.68914, 0.86558, 0.93626, 0.89436, 0.75511, 0.81468, 0.86794, 0.68124, 0.52750, 0.58779, 0.55414, 0.40555, 0.34110, 0.44348, 0.54790, 0.59284, 0.70931, 0.69050, 0.72100, 0.80014, 0.79310, 0.87900, 1.02978, 1.15950, 1.24858, 1.35211, 1.58972, 1.71728, 1.90147, 2.08537, 2.23170, 2.36689, 2.37386, 2.36884, 2.37520, 2.34860, 2.18596, 2.13810, 2.19046, 2.12139, 1.94901, 1.90790, 1.87090, 1.82170, 1.75509, 1.64829, 1.52680, 1.43886, 1.46972, 1.33378, 1.14870, 1.06611, 0.99618, 0.87314, 0.71808, 0.62465, 0.50652, 0.25601, 0.02036, -0.21824, -0.36231, -0.54564, -0.84040, -1.02962, -1.16250, -1.20948, -1.27863, -1.38522, -1.51714, -1.45599, -1.33352, -1.36519, -1.39039, -1.20008, -1.04708, -1.07019, -1.13819, -1.23907, -1.31251, -1.52050, -1.67714, -1.90875, -2.13947, -2.25991, -2.50328, -2.78715, -3.01841, -3.26360, -3.44980, -3.55505, -3.53615, -3.64379, -3.81848, -3.96694, -4.14238, -4.24800, -4.34585, -4.39960, -4.36213, -4.24775, -4.34725, -4.44622, -4.38979, -4.35900, -4.46278, -4.52879, -4.56439, -4.62390, -4.55980, -4.38636, -4.19781, -4.07646, -3.84647, -3.80361, -3.81436, -3.65011, -3.46158, -3.36409, -3.26585, -3.08161, -2.84638, -2.74853, -2.71229, -2.76282, -2.74936, -2.64894, -2.65801, -2.66149, -2.53615, -2.36757, -2.31868, -2.28034, -2.34418, -2.32584, -2.17652, -2.08145, -2.07078, -1.91960, -1.64866, -1.49354, -1.37880, -1.26685, -1.10354, -1.04698, -1.03844, -1.14937, -1.33136, -1.47507, -1.54510, -1.55220, -1.53384, -1.57373, -1.65541, -1.72011, -1.64157, -1.55948, -1.50007, -1.39850, -1.32661, -1.23793, -1.19654, -1.17175, -1.10609, -0.89086, -0.83051, -0.86805, -0.77135, -0.61584, -0.54382, -0.45613, -0.36958, -0.40140, -0.41321, -0.46338, -0.37482, -0.25638, -0.04755, 0.10036, 0.19773, 0.48607, 0.82728, 0.98063, 0.97766, 0.92384, 0.90961, 0.83848, 0.75234, 0.59743, 0.52130, 0.51943, 0.33006, 0.10025, 0.00804, 0.00254, 0.01108, 0.13687, 0.20620, 0.20863, 0.34845, 0.43370, 0.36277, 0.36861, 0.47374, 0.48971, 0.37294, 0.24932, 0.24150, 0.17253, 0.20625, 0.32944, 0.33190, 0.33696, 0.38168, 0.43593, 0.53364, 0.63108, 0.70254, 0.68625, 0.73808, 0.74235, 0.57969, 0.42178, 0.23587, 0.15227, 0.16893, 0.18730, 0.23617, 0.42198, 0.56730, 0.56032, 0.56578, 0.56879, 0.46692, 0.37034, 0.54125, 0.80364, 0.96142, 1.02051, 1.10326, 1.22997, 1.35534, 1.43191, 1.27087, 1.25691, 1.46944, 1.67883, 1.81023, 1.89450, 2.05554, 2.13833, 2.13137, 2.14453, 2.16058, 2.24698, 2.21826, 2.14539, 2.12854, 2.03167, 1.88208, 1.69120, 1.50681, 1.26385, 1.15784, 1.14370, 1.00796, 0.95490, 1.09977, 1.17607, 1.21754, 1.31470, 1.41652, 1.36658, 1.24831, 1.25307, 1.12927, 1.08201, 1.14067, 1.13809, 1.15858, 1.10898, 0.94793, 0.73181, 0.57466, 0.54968, 0.38907, 0.21690, 0.01048, -0.12678, -0.14961, -0.20180, -0.30825, -0.35584, -0.35313, -0.49931, -0.48518, -0.35118, -0.42395, -0.68956, -0.81320, -0.86338, -1.01240, -1.30089, -1.66793, -1.90508, -2.02685, -2.01780, -2.25841, -2.53144, -2.57001, -2.65586, -2.84509, -3.02838, -3.10944, -3.14756, -3.21341, -3.14500, -3.16263, -3.22790, -3.37669, -3.57754, -3.56885, -3.40265, -3.19047, -2.98162, -2.82187, -2.81270, -2.81304, -2.77751, -2.80602, -2.86790, -2.81851, -2.80192, -2.88659, -2.91025, -2.92888, -2.86563, -2.84223, -2.69222, -2.59724, -2.57258, -2.47786, -2.39990, -2.28746, -2.17284, -2.16362, -2.26588, -2.42105, -2.42323, -2.49822, -2.63147, -2.80854, -2.95934, -2.97718, -2.98601, -2.91967, -2.80211, -2.70961, -2.88840, -3.01114, -2.87916, -2.74357, +0.48807, 0.48608, 0.52161, 0.62846, 0.64105, 0.46895, 0.40955, 0.40505, 0.45403, 0.46153, 0.47680, 0.46848, 0.39163, 0.33862, 0.29157, 0.25820, 0.15980, 0.09772, -0.09686, -0.31506, -0.49394, -0.76861, -0.89771, -0.79711, -0.71093, -0.72797, -0.75855, -0.73716, -0.70088, -0.57022, -0.46193, -0.31425, -0.14478, -0.07970, -0.03865, 0.15746, 0.41937, 0.43033, 0.44215, 0.60131, 0.84544, 1.06037, 1.08972, 1.01524, 0.88132, 0.83077, 0.75819, 0.68704, 0.60284, 0.65925, 0.61882, 0.52187, 0.63893, 0.75012, 0.80900, 0.86054, 0.84423, 0.76716, 0.81082, 0.90139, 0.87655, 0.98382, 1.11027, 1.24266, 1.39770, 1.48913, 1.65824, 1.85369, 2.12408, 2.26645, 2.40935, 2.56965, 2.63868, 2.64997, 2.56200, 2.50330, 2.38114, 2.32063, 2.26046, 2.25801, 2.13620, 2.07278, 1.99551, 1.90470, 1.91534, 1.76916, 1.51183, 1.41050, 1.37764, 1.29599, 1.21810, 1.20686, 1.09509, 0.93622, 0.67128, 0.51491, 0.43875, 0.18866, -0.10001, -0.30716, -0.37217, -0.52736, -0.74053, -0.88659, -1.00726, -1.06883, -1.24694, -1.39026, -1.51764, -1.48594, -1.50269, -1.47848, -1.41216, -1.20575, -1.06844, -1.15019, -1.20778, -1.35034, -1.52827, -1.67308, -1.85507, -2.06455, -2.28428, -2.41103, -2.71831, -3.00348, -3.23634, -3.45495, -3.54952, -3.63784, -3.71054, -3.80642, -3.88231, -4.06219, -4.23593, -4.30662, -4.35319, -4.31736, -4.32875, -4.25831, -4.34460, -4.40740, -4.46329, -4.41556, -4.46430, -4.56875, -4.68478, -4.84595, -4.71750, -4.45205, -4.29694, -4.07743, -3.86832, -3.83630, -3.89987, -3.76502, -3.65279, -3.57427, -3.46016, -3.27942, -2.94935, -2.70053, -2.63007, -2.66091, -2.58703, -2.57472, -2.63397, -2.63828, -2.55241, -2.38913, -2.43771, -2.45124, -2.46794, -2.34758, -2.28091, -2.19498, -2.14878, -2.02380, -1.75421, -1.64245, -1.47341, -1.29368, -1.26834, -1.21122, -1.23116, -1.32463, -1.46489, -1.53504, -1.61373, -1.64576, -1.62439, -1.65103, -1.64083, -1.62606, -1.59999, -1.55645, -1.42580, -1.35047, -1.33092, -1.26558, -1.24089, -1.15346, -1.11562, -0.94506, -0.87204, -0.84623, -0.87922, -0.79856, -0.64549, -0.52118, -0.39103, -0.44659, -0.41801, -0.39375, -0.47890, -0.37944, -0.16542, 0.00978, 0.17203, 0.49678, 0.80996, 0.98683, 1.03866, 0.96152, 0.95672, 0.91616, 0.78157, 0.59827, 0.59473, 0.58439, 0.36008, 0.15297, 0.08947, 0.16133, 0.14023, 0.16133, 0.14329, 0.16224, 0.23672, 0.28368, 0.33382, 0.37270, 0.45902, 0.41329, 0.32672, 0.34443, 0.27712, 0.23879, 0.32172, 0.42193, 0.44825, 0.50227, 0.53057, 0.52887, 0.62107, 0.68222, 0.78566, 0.84897, 0.85770, 0.78956, 0.69574, 0.58339, 0.38970, 0.34532, 0.38467, 0.44609, 0.44164, 0.52022, 0.65000, 0.73344, 0.74763, 0.68395, 0.65793, 0.53292, 0.58760, 0.75422, 0.90469, 1.11113, 1.18593, 1.30340, 1.51309, 1.63975, 1.54852, 1.53861, 1.66129, 1.74759, 1.88345, 1.98275, 2.20153, 2.38494, 2.38351, 2.34742, 2.43184, 2.55742, 2.44029, 2.28201, 2.14228, 2.02135, 1.89932, 1.68478, 1.52984, 1.36607, 1.27219, 1.19011, 1.17803, 1.19556, 1.32188, 1.37819, 1.41626, 1.61449, 1.69936, 1.62682, 1.59110, 1.56616, 1.47195, 1.43763, 1.47177, 1.39861, 1.40631, 1.32925, 1.19755, 1.08083, 0.93873, 0.83279, 0.67514, 0.49938, 0.15542, -0.04219, -0.07919, -0.06481, -0.05975, -0.13634, -0.15696, -0.33736, -0.42977, -0.48141, -0.53381, -0.75198, -0.89289, -0.98119, -1.12521, -1.22513, -1.51396, -1.81677, -1.91781, -1.99396, -2.21528, -2.46969, -2.52999, -2.70217, -2.89370, -3.06014, -3.08054, -3.00012, -3.02787, -3.07904, -3.18847, -3.25398, -3.47685, -3.70134, -3.71686, -3.57875, -3.35141, -3.23456, -3.11510, -3.08622, -3.05551, -3.10570, -3.07245, -3.06876, -3.02177, -2.99039, -3.08863, -3.01139, -2.96095, -2.97976, -2.89926, -2.79377, -2.70511, -2.69028, -2.59981, -2.58942, -2.49120, -2.38285, -2.37527, -2.42370, -2.56679, -2.64196, -2.70429, -2.68770, -2.80403, -2.92507, -2.93800, -3.00566, -2.95590, -2.92212, -2.87355, -3.01358, -3.06604, -3.04198, -2.84959, +0.62347, 0.53119, 0.47974, 0.50271, 0.57041, 0.50315, 0.47424, 0.50017, 0.50361, 0.44072, 0.46649, 0.49297, 0.50501, 0.48507, 0.40162, 0.36988, 0.25816, 0.18026, 0.02537, -0.19136, -0.45077, -0.74912, -0.80950, -0.69215, -0.60064, -0.58770, -0.58210, -0.51775, -0.44303, -0.29880, -0.23841, -0.12468, -0.01196, -0.01476, -0.01612, 0.11458, 0.38984, 0.50177, 0.61575, 0.81967, 0.98339, 1.08582, 1.09617, 1.02907, 0.89943, 0.82761, 0.76056, 0.79402, 0.73835, 0.71922, 0.71404, 0.72976, 0.81399, 0.82291, 0.87505, 0.91413, 0.85543, 0.78499, 0.84974, 1.00460, 1.09147, 1.23872, 1.28850, 1.30331, 1.41273, 1.47206, 1.64509, 1.88211, 2.23247, 2.46643, 2.58454, 2.72541, 2.75581, 2.65196, 2.53107, 2.49042, 2.42327, 2.45296, 2.37808, 2.34459, 2.20432, 2.11895, 2.10929, 2.08016, 2.00578, 1.71755, 1.47616, 1.40377, 1.36873, 1.34539, 1.29523, 1.29784, 1.20381, 1.10274, 0.76811, 0.46539, 0.28138, -0.04680, -0.27052, -0.42584, -0.43770, -0.44321, -0.60709, -0.72454, -0.90138, -1.13264, -1.31095, -1.35883, -1.47133, -1.46009, -1.53593, -1.49080, -1.43353, -1.31244, -1.17645, -1.21282, -1.36324, -1.67197, -1.84395, -1.91240, -2.02641, -2.18055, -2.42848, -2.63206, -2.93876, -3.13285, -3.36987, -3.61881, -3.72335, -3.90462, -4.01962, -4.10105, -4.10507, -4.13491, -4.27609, -4.31715, -4.32896, -4.35510, -4.39377, -4.34191, -4.43170, -4.39689, -4.42361, -4.38347, -4.47170, -4.66186, -4.74646, -4.80122, -4.68454, -4.55065, -4.40225, -4.14444, -3.91019, -3.75850, -3.81745, -3.77384, -3.73952, -3.60136, -3.41675, -3.26758, -2.94699, -2.72764, -2.63771, -2.63625, -2.58159, -2.52049, -2.54562, -2.51491, -2.49837, -2.56409, -2.69101, -2.63789, -2.60650, -2.37962, -2.26995, -2.16072, -2.13088, -2.08449, -1.81714, -1.60548, -1.42662, -1.44286, -1.53468, -1.54731, -1.56742, -1.53796, -1.61261, -1.64494, -1.71489, -1.72040, -1.72518, -1.80672, -1.78519, -1.80781, -1.80546, -1.74905, -1.57840, -1.37735, -1.34864, -1.35162, -1.36403, -1.35545, -1.31884, -1.10738, -1.02575, -0.91016, -0.86561, -0.74280, -0.58118, -0.51689, -0.39671, -0.37617, -0.31290, -0.37243, -0.54521, -0.50439, -0.33686, -0.04885, 0.24845, 0.57915, 0.86113, 1.07824, 1.14322, 0.99825, 0.89671, 0.75523, 0.62982, 0.52823, 0.53800, 0.57228, 0.42428, 0.26612, 0.20638, 0.19263, 0.12606, 0.15909, 0.10852, 0.16910, 0.29895, 0.40580, 0.49348, 0.42949, 0.41570, 0.35870, 0.32610, 0.29710, 0.18775, 0.19558, 0.28422, 0.40629, 0.44688, 0.48320, 0.49881, 0.52025, 0.62284, 0.64231, 0.75055, 0.82338, 0.78647, 0.69189, 0.63488, 0.67254, 0.64334, 0.63059, 0.64735, 0.63483, 0.58612, 0.69260, 0.82004, 0.93340, 0.99483, 0.92802, 0.91867, 0.76913, 0.71664, 0.82815, 0.96791, 1.15827, 1.26262, 1.43339, 1.67350, 1.85801, 1.82539, 1.77607, 1.77294, 1.80560, 2.01454, 2.14371, 2.31841, 2.43620, 2.40729, 2.39267, 2.47285, 2.63986, 2.60779, 2.40140, 2.16970, 1.97400, 1.82227, 1.73624, 1.68222, 1.55351, 1.51552, 1.41713, 1.45688, 1.47283, 1.52182, 1.59036, 1.64968, 1.74850, 1.70387, 1.65051, 1.66005, 1.67939, 1.65728, 1.62473, 1.64468, 1.59152, 1.61054, 1.46624, 1.31426, 1.24395, 1.09888, 0.96835, 0.77041, 0.62001, 0.40560, 0.20561, 0.11709, 0.07089, -0.00175, -0.05195, -0.01346, -0.15940, -0.25622, -0.42129, -0.53370, -0.72495, -0.86572, -0.94765, -1.03275, -1.14246, -1.51640, -1.82030, -1.98127, -2.08489, -2.18651, -2.39518, -2.53289, -2.77839, -2.90910, -3.06948, -3.12544, -3.02632, -3.06670, -3.14182, -3.30551, -3.35667, -3.42762, -3.57717, -3.61501, -3.60006, -3.56456, -3.51975, -3.35319, -3.30347, -3.21001, -3.27266, -3.26355, -3.30016, -3.34443, -3.30045, -3.30401, -3.21982, -3.26901, -3.27351, -3.15309, -3.03799, -2.92594, -2.95872, -2.89537, -2.85276, -2.65488, -2.55391, -2.60199, -2.61601, -2.73709, -2.78702, -2.83988, -2.77421, -2.71667, -2.78511, -2.78846, -2.88884, -3.02243, -3.09221, -3.03188, -3.07338, -2.95368, -2.91171, -2.69939, +0.80654, 0.68492, 0.64522, 0.56615, 0.57919, 0.63622, 0.68370, 0.65362, 0.63470, 0.58382, 0.58041, 0.63207, 0.63059, 0.54868, 0.42244, 0.33855, 0.29311, 0.18405, 0.05800, -0.11235, -0.44844, -0.60100, -0.51004, -0.48188, -0.49455, -0.43883, -0.39141, -0.28101, -0.13097, -0.08992, -0.10108, -0.01609, -0.03010, 0.02219, 0.18618, 0.28913, 0.41957, 0.52590, 0.70992, 0.85525, 0.95579, 1.02170, 0.94524, 0.89960, 0.78628, 0.67975, 0.69117, 0.81384, 0.89034, 0.84784, 0.83232, 0.94896, 0.88026, 0.85449, 0.97981, 0.95329, 0.84752, 0.86568, 0.97368, 1.14783, 1.36358, 1.44127, 1.42685, 1.42699, 1.45855, 1.57034, 1.83540, 2.08037, 2.34538, 2.57014, 2.71188, 2.74885, 2.71172, 2.62209, 2.45189, 2.39811, 2.35777, 2.35976, 2.29933, 2.24544, 2.17594, 2.13655, 2.12067, 2.16434, 1.94711, 1.66602, 1.59772, 1.52794, 1.41260, 1.39557, 1.31700, 1.22313, 1.18216, 1.11832, 0.82531, 0.55797, 0.20506, -0.19955, -0.33493, -0.44766, -0.52824, -0.55244, -0.66691, -0.81217, -1.03803, -1.22191, -1.33988, -1.29552, -1.35141, -1.45151, -1.56421, -1.53325, -1.50448, -1.45267, -1.42952, -1.38053, -1.60482, -1.89380, -1.90473, -1.93936, -2.09142, -2.24986, -2.49033, -2.80302, -3.02337, -3.16593, -3.44948, -3.62952, -3.81605, -4.05789, -4.11186, -4.14871, -4.19209, -4.21523, -4.28742, -4.36158, -4.41252, -4.37607, -4.41208, -4.38358, -4.43779, -4.44039, -4.46589, -4.48108, -4.59518, -4.74053, -4.83510, -4.72042, -4.65643, -4.59585, -4.36313, -4.10894, -3.92221, -3.64149, -3.53319, -3.57701, -3.58758, -3.48147, -3.35584, -3.14347, -2.88833, -2.76584, -2.63511, -2.56252, -2.58693, -2.57758, -2.50187, -2.44585, -2.52976, -2.65427, -2.78150, -2.69005, -2.61872, -2.45979, -2.34278, -2.20058, -2.11400, -1.97574, -1.80562, -1.52353, -1.42662, -1.61753, -1.66713, -1.69742, -1.75507, -1.66349, -1.63320, -1.69253, -1.75227, -1.75076, -1.86816, -1.93194, -1.93677, -2.02550, -1.98015, -1.87106, -1.75125, -1.59452, -1.52063, -1.54748, -1.64820, -1.62045, -1.53838, -1.34801, -1.22757, -1.11100, -0.99634, -0.80368, -0.62909, -0.50882, -0.49981, -0.43023, -0.34826, -0.39671, -0.37380, -0.29080, -0.26867, -0.03479, 0.34961, 0.62806, 0.86108, 1.06419, 1.00444, 0.86713, 0.72522, 0.51107, 0.51191, 0.58441, 0.58303, 0.53390, 0.47014, 0.38330, 0.21166, 0.14423, 0.12547, 0.18064, 0.21846, 0.30528, 0.42304, 0.55736, 0.61269, 0.53590, 0.38688, 0.31529, 0.35978, 0.27607, 0.28240, 0.39860, 0.39135, 0.43581, 0.49826, 0.46912, 0.43716, 0.50597, 0.51285, 0.52411, 0.68502, 0.73538, 0.77311, 0.78711, 0.74447, 0.77381, 0.84145, 0.86703, 0.77762, 0.73439, 0.77502, 0.89730, 1.03522, 1.09647, 1.05699, 0.96981, 0.97236, 1.00158, 0.97403, 1.02691, 1.14682, 1.21310, 1.44437, 1.76219, 1.92813, 2.00919, 1.99405, 1.89477, 1.77859, 1.86139, 2.06709, 2.24206, 2.46196, 2.47098, 2.48443, 2.55970, 2.55474, 2.57959, 2.56835, 2.42910, 2.16204, 1.98222, 1.94771, 1.95495, 1.97266, 1.85035, 1.75434, 1.65845, 1.73080, 1.80634, 1.79500, 1.77819, 1.85155, 1.78716, 1.74573, 1.80485, 1.77961, 1.75775, 1.77556, 1.72269, 1.67053, 1.68989, 1.65988, 1.47374, 1.40561, 1.30681, 1.18442, 1.09617, 0.85999, 0.63124, 0.47867, 0.35208, 0.16276, 0.00691, -0.06352, -0.11776, -0.01341, -0.00464, -0.10120, -0.32183, -0.52179, -0.68814, -0.79817, -0.95445, -0.98561, -1.23694, -1.61725, -1.79631, -2.02393, -2.18135, -2.18350, -2.31636, -2.55135, -2.78904, -2.92475, -3.13650, -3.17907, -3.16116, -3.17778, -3.13042, -3.22223, -3.30886, -3.34848, -3.38635, -3.50339, -3.64708, -3.65746, -3.64751, -3.43408, -3.34029, -3.33359, -3.44420, -3.51115, -3.56664, -3.61161, -3.66434, -3.55946, -3.52752, -3.60200, -3.47640, -3.34458, -3.29119, -3.18485, -3.20328, -3.21244, -3.09457, -2.86217, -2.82718, -2.79796, -2.79101, -2.84070, -2.75972, -2.75661, -2.77850, -2.76678, -2.76917, -2.76073, -2.83477, -2.91400, -3.03236, -3.01599, -2.98435, -2.85246, -2.79618, -2.60898, +0.93794, 0.83804, 0.69907, 0.54371, 0.58355, 0.70096, 0.82178, 0.82646, 0.86916, 0.87261, 0.77707, 0.75321, 0.77929, 0.71246, 0.59586, 0.49189, 0.43055, 0.33066, 0.17032, -0.00433, -0.20534, -0.22176, -0.16204, -0.22300, -0.32283, -0.30839, -0.20116, -0.01343, 0.08592, 0.03649, -0.04915, -0.05253, -0.04662, 0.11076, 0.28684, 0.32103, 0.39769, 0.43128, 0.57434, 0.70954, 0.83262, 0.93231, 0.75799, 0.62860, 0.58962, 0.60092, 0.72097, 0.91983, 1.06027, 1.08195, 1.04412, 1.07540, 0.99094, 0.98306, 1.03233, 0.93271, 0.81153, 0.82706, 1.01113, 1.30809, 1.49979, 1.48886, 1.44359, 1.38880, 1.48478, 1.73110, 1.95759, 2.08820, 2.32291, 2.52531, 2.68692, 2.74725, 2.72449, 2.69612, 2.44788, 2.23782, 2.19622, 2.25352, 2.24664, 2.27299, 2.25487, 2.25549, 2.20598, 2.13939, 1.93750, 1.77678, 1.68572, 1.52479, 1.36043, 1.27132, 1.20098, 1.19308, 1.12407, 1.01328, 0.78056, 0.48662, 0.11638, -0.24379, -0.46605, -0.71014, -0.79824, -0.82860, -0.90729, -0.98378, -1.15363, -1.19091, -1.28505, -1.34207, -1.36243, -1.39650, -1.49133, -1.44073, -1.46726, -1.48543, -1.54178, -1.60940, -1.80467, -1.92884, -1.91561, -2.01928, -2.20961, -2.43520, -2.63599, -2.80087, -2.95606, -3.14089, -3.43591, -3.66520, -3.84624, -3.95100, -3.97096, -4.09521, -4.13643, -4.15990, -4.21612, -4.26358, -4.31467, -4.18558, -4.22235, -4.31390, -4.36883, -4.33079, -4.37055, -4.39330, -4.51727, -4.64176, -4.74633, -4.71587, -4.64822, -4.45872, -4.21167, -4.03324, -3.85398, -3.55828, -3.33220, -3.22953, -3.24970, -3.30661, -3.28808, -3.15866, -2.93057, -2.70830, -2.55896, -2.59639, -2.65027, -2.64251, -2.54621, -2.45153, -2.52712, -2.55320, -2.64904, -2.66482, -2.62177, -2.43787, -2.30114, -2.09599, -1.95987, -1.79950, -1.68822, -1.57996, -1.60809, -1.74518, -1.77647, -1.86747, -1.89853, -1.81929, -1.75256, -1.67161, -1.67265, -1.74270, -1.90472, -2.03131, -2.07156, -2.06287, -1.99334, -2.03278, -2.00059, -1.88368, -1.79901, -1.75808, -1.83958, -1.73595, -1.64209, -1.59499, -1.50413, -1.32037, -1.16465, -0.90716, -0.68365, -0.52199, -0.50548, -0.51449, -0.46572, -0.33571, -0.15645, -0.11457, -0.16874, -0.08882, 0.19648, 0.52833, 0.79303, 0.90516, 0.77202, 0.57801, 0.41193, 0.33145, 0.45172, 0.48414, 0.46626, 0.43875, 0.41123, 0.39298, 0.22000, 0.19260, 0.22391, 0.19923, 0.22728, 0.38971, 0.53575, 0.67668, 0.69436, 0.58427, 0.41468, 0.28164, 0.31516, 0.34667, 0.45406, 0.53879, 0.48710, 0.46900, 0.49272, 0.51936, 0.54781, 0.55700, 0.47621, 0.42167, 0.55078, 0.71623, 0.91180, 0.93281, 0.84714, 0.87966, 0.94247, 0.99154, 0.92198, 0.91342, 0.98695, 1.00426, 1.05094, 1.13162, 1.11220, 1.05506, 1.10595, 1.24047, 1.31056, 1.31072, 1.31593, 1.36820, 1.66043, 1.95661, 2.06676, 2.07650, 1.99291, 1.92072, 1.88716, 1.95132, 2.09234, 2.24264, 2.43989, 2.52179, 2.65175, 2.66774, 2.49845, 2.44300, 2.40371, 2.32172, 2.15792, 2.08245, 2.17308, 2.14763, 2.06553, 1.98796, 1.96145, 1.92361, 2.05283, 2.11716, 2.06802, 1.96490, 1.91882, 1.86645, 1.93228, 1.98067, 1.90676, 1.86614, 1.81876, 1.76206, 1.78787, 1.78465, 1.69120, 1.50886, 1.40451, 1.33715, 1.30565, 1.15734, 0.79103, 0.51929, 0.32486, 0.20522, 0.04972, -0.09349, -0.08918, -0.18219, -0.17280, -0.04568, -0.00008, -0.18306, -0.37862, -0.61016, -0.76327, -0.96976, -1.11247, -1.36864, -1.63334, -1.82088, -2.11404, -2.27436, -2.31803, -2.40606, -2.49691, -2.71473, -2.92689, -3.17086, -3.30409, -3.29077, -3.16476, -3.07944, -3.23391, -3.31317, -3.36171, -3.39472, -3.50660, -3.67434, -3.62313, -3.62661, -3.52171, -3.43175, -3.40114, -3.52386, -3.57836, -3.63900, -3.67376, -3.74769, -3.72931, -3.68424, -3.63607, -3.51642, -3.46804, -3.44033, -3.38628, -3.37622, -3.26954, -3.13739, -2.99834, -2.98112, -2.96635, -2.92985, -2.83544, -2.71083, -2.79620, -2.84062, -2.85304, -2.84484, -2.76672, -2.74465, -2.66349, -2.77781, -2.92589, -2.95234, -2.77784, -2.67280, -2.42509, +1.06257, 0.88784, 0.73951, 0.60198, 0.69185, 0.84220, 0.92117, 0.93767, 1.00225, 0.98517, 0.89602, 0.87615, 0.90395, 0.90275, 0.78532, 0.62527, 0.48664, 0.45055, 0.43699, 0.26320, 0.08907, 0.13068, 0.12452, 0.00898, -0.10290, -0.12104, -0.03561, 0.12225, 0.12871, 0.10363, 0.07029, 0.01517, 0.01755, 0.11718, 0.31290, 0.36109, 0.41844, 0.40603, 0.43011, 0.50974, 0.63272, 0.68437, 0.53990, 0.45823, 0.47083, 0.61302, 0.79873, 0.94548, 1.04313, 1.12774, 1.24489, 1.23885, 1.09969, 1.07014, 1.01922, 0.88836, 0.83780, 0.87652, 1.07581, 1.37420, 1.48673, 1.47299, 1.49146, 1.38381, 1.54994, 1.76127, 1.95922, 2.05953, 2.27265, 2.46750, 2.59590, 2.65332, 2.69162, 2.65378, 2.42175, 2.21877, 2.15240, 2.23994, 2.26412, 2.24711, 2.23183, 2.28299, 2.35984, 2.22328, 1.93845, 1.78486, 1.63197, 1.41955, 1.29047, 1.18286, 1.13908, 1.14467, 1.00250, 0.86387, 0.74871, 0.40491, 0.06357, -0.37199, -0.66807, -0.94693, -1.04452, -1.06546, -1.12267, -1.18024, -1.25205, -1.24915, -1.31338, -1.36400, -1.40098, -1.41403, -1.46948, -1.49938, -1.55700, -1.61065, -1.58286, -1.66867, -1.90278, -1.98483, -1.99150, -2.14729, -2.30416, -2.53591, -2.70840, -2.80728, -2.92721, -3.13176, -3.33494, -3.63949, -3.78178, -3.89011, -3.89280, -3.98035, -3.97967, -3.97226, -4.02028, -4.09640, -4.11503, -4.01501, -4.06931, -4.13863, -4.17506, -4.11818, -4.15457, -4.32833, -4.51151, -4.66294, -4.64809, -4.57386, -4.56131, -4.35136, -4.06846, -3.91892, -3.69334, -3.38228, -3.11331, -2.97340, -3.02037, -3.19674, -3.16549, -3.14306, -2.93131, -2.73334, -2.57587, -2.59274, -2.62006, -2.58225, -2.49454, -2.46209, -2.50653, -2.52575, -2.60655, -2.57780, -2.49217, -2.30843, -2.15412, -2.03647, -1.92465, -1.82391, -1.66424, -1.57123, -1.75649, -1.94966, -1.98339, -2.09894, -2.02792, -1.90917, -1.83765, -1.72876, -1.71428, -1.84603, -1.91589, -2.07203, -2.10549, -2.09609, -2.05479, -2.11935, -2.12960, -2.04536, -1.97471, -1.95017, -1.95472, -1.82058, -1.77745, -1.77855, -1.68794, -1.49478, -1.28546, -1.06577, -0.85544, -0.69938, -0.51755, -0.39625, -0.42343, -0.30469, -0.07549, -0.08890, -0.13915, -0.12265, 0.03722, 0.31077, 0.53193, 0.55437, 0.51354, 0.33198, 0.18691, 0.17875, 0.30765, 0.36580, 0.36904, 0.36907, 0.37513, 0.35775, 0.26217, 0.26203, 0.24755, 0.22273, 0.29437, 0.47647, 0.65960, 0.72982, 0.64230, 0.44689, 0.35758, 0.38238, 0.39722, 0.39703, 0.51068, 0.52981, 0.50298, 0.51760, 0.51793, 0.55622, 0.60424, 0.55143, 0.52840, 0.49298, 0.57429, 0.78129, 0.97984, 1.06620, 1.03342, 1.08907, 1.11656, 1.07554, 1.01947, 1.03840, 1.05602, 1.05579, 1.10905, 1.21347, 1.29117, 1.24667, 1.22987, 1.34108, 1.52147, 1.66978, 1.60800, 1.54804, 1.77699, 1.98146, 2.06264, 2.09644, 1.99464, 1.92441, 1.92223, 1.94943, 2.10851, 2.29515, 2.42573, 2.55251, 2.65989, 2.69744, 2.54518, 2.46247, 2.38862, 2.28746, 2.20201, 2.23468, 2.32154, 2.28687, 2.19236, 2.11652, 2.15024, 2.15860, 2.21806, 2.19540, 2.12867, 2.13052, 2.04190, 1.92422, 1.99876, 2.02412, 1.97288, 2.01006, 1.95741, 1.88726, 1.89595, 1.82417, 1.72189, 1.63931, 1.48340, 1.44726, 1.31508, 1.09818, 0.72109, 0.43277, 0.20733, 0.04905, -0.10636, -0.15487, -0.12709, -0.21712, -0.21139, -0.05498, 0.07983, -0.04869, -0.33718, -0.67257, -0.89803, -1.00799, -1.18539, -1.50797, -1.75587, -1.97393, -2.27482, -2.35986, -2.41745, -2.50182, -2.56711, -2.79410, -3.01468, -3.13072, -3.30193, -3.26070, -3.18787, -3.10198, -3.20845, -3.26877, -3.33606, -3.43002, -3.61020, -3.74720, -3.72343, -3.71520, -3.59483, -3.53087, -3.50739, -3.60533, -3.74302, -3.83334, -3.87764, -3.79241, -3.70780, -3.69831, -3.63007, -3.53357, -3.54837, -3.48340, -3.43476, -3.39836, -3.25608, -3.14649, -3.11247, -3.02911, -3.04742, -2.96901, -2.89732, -2.77429, -2.82363, -2.80626, -2.76776, -2.76413, -2.72289, -2.60615, -2.47512, -2.58181, -2.73254, -2.80689, -2.66415, -2.51043, -2.33315, +1.16459, 0.94180, 0.83714, 0.74760, 0.85593, 0.98670, 1.00351, 0.97081, 0.98091, 0.94135, 0.90047, 0.90702, 0.86569, 0.84815, 0.87325, 0.83704, 0.70778, 0.66314, 0.56951, 0.34081, 0.21344, 0.30202, 0.38045, 0.29039, 0.16494, 0.14666, 0.13797, 0.17443, 0.18834, 0.21259, 0.25572, 0.25487, 0.18137, 0.15530, 0.33863, 0.42560, 0.47519, 0.50200, 0.51504, 0.51679, 0.52186, 0.48499, 0.44358, 0.48535, 0.49004, 0.58130, 0.82989, 1.04352, 1.10385, 1.15137, 1.22755, 1.18250, 1.11371, 1.09070, 1.01884, 0.90885, 0.89215, 0.98746, 1.11256, 1.25530, 1.38788, 1.45828, 1.50908, 1.46626, 1.62502, 1.73122, 1.89251, 2.00533, 2.19865, 2.40045, 2.50601, 2.53794, 2.57361, 2.52796, 2.39109, 2.30966, 2.19516, 2.15044, 2.17887, 2.23406, 2.26112, 2.36826, 2.42659, 2.16235, 1.83569, 1.66430, 1.54985, 1.43928, 1.32709, 1.24945, 1.20729, 1.06766, 0.87784, 0.74832, 0.62699, 0.33896, 0.00193, -0.44973, -0.71757, -0.96364, -1.11712, -1.14634, -1.14573, -1.16145, -1.21003, -1.26283, -1.33193, -1.33855, -1.46076, -1.64921, -1.67815, -1.57397, -1.53886, -1.56399, -1.61662, -1.84488, -2.07142, -2.12766, -2.12670, -2.19201, -2.30168, -2.46505, -2.63046, -2.83085, -2.92452, -3.06406, -3.26297, -3.52288, -3.64238, -3.79882, -3.80216, -3.81006, -3.77242, -3.71259, -3.71138, -3.76133, -3.80885, -3.81524, -3.91672, -3.93276, -3.93786, -3.96800, -4.00266, -4.12974, -4.33203, -4.47184, -4.44687, -4.44417, -4.44088, -4.21642, -3.86645, -3.60433, -3.39455, -3.11452, -2.89285, -2.90919, -2.98314, -3.04837, -2.99390, -2.97811, -2.82565, -2.71430, -2.51185, -2.40464, -2.38948, -2.35104, -2.30141, -2.31436, -2.42032, -2.54220, -2.60641, -2.44959, -2.25704, -2.19669, -2.14433, -2.00369, -1.88958, -1.79705, -1.70518, -1.76351, -1.99521, -2.19601, -2.22106, -2.20002, -2.06398, -1.92298, -1.87124, -1.90380, -1.91418, -1.96098, -1.99432, -2.10241, -2.09456, -2.12320, -2.08186, -2.06480, -2.09625, -2.06026, -2.05125, -2.04779, -2.00036, -1.87113, -1.84102, -1.82185, -1.71920, -1.62562, -1.42704, -1.08894, -0.83326, -0.62218, -0.36312, -0.31265, -0.42346, -0.37929, -0.19187, -0.13714, -0.15335, -0.09565, 0.01714, 0.07574, 0.13060, 0.18682, 0.25719, 0.17997, 0.11936, 0.08690, 0.17750, 0.30289, 0.30808, 0.29301, 0.33226, 0.37102, 0.37507, 0.32718, 0.21017, 0.18952, 0.31565, 0.41978, 0.51485, 0.64485, 0.61400, 0.44123, 0.37763, 0.37183, 0.34412, 0.29869, 0.36410, 0.43540, 0.48087, 0.53027, 0.52713, 0.46410, 0.44307, 0.46553, 0.55341, 0.58989, 0.68765, 0.82755, 0.93261, 1.08262, 1.15908, 1.26415, 1.28750, 1.18815, 1.12387, 1.12188, 1.12177, 1.18413, 1.29486, 1.38116, 1.45191, 1.48224, 1.49015, 1.55784, 1.73632, 1.83603, 1.72478, 1.68511, 1.86112, 2.03159, 2.09478, 2.13160, 2.08866, 1.97270, 1.87306, 1.91307, 2.11206, 2.31302, 2.43968, 2.51841, 2.58667, 2.72742, 2.72805, 2.62786, 2.48843, 2.34823, 2.30567, 2.35101, 2.37088, 2.35514, 2.32586, 2.20847, 2.15066, 2.22746, 2.34393, 2.26560, 2.15838, 2.10416, 1.94914, 1.82299, 1.86989, 1.93964, 2.01963, 2.12859, 2.15942, 2.06309, 1.90441, 1.80033, 1.71230, 1.66152, 1.59359, 1.56249, 1.31890, 1.05764, 0.74132, 0.46157, 0.26148, 0.10778, -0.04357, -0.04513, -0.02057, -0.10454, -0.09061, -0.01839, -0.00652, -0.09633, -0.26953, -0.57421, -0.83220, -1.04430, -1.38730, -1.72167, -1.93976, -2.11544, -2.30960, -2.39300, -2.44283, -2.56824, -2.81667, -3.04385, -3.14145, -3.12514, -3.13564, -3.11198, -3.18929, -3.13993, -3.14149, -3.19755, -3.30274, -3.43973, -3.64047, -3.79430, -3.84349, -3.81671, -3.64981, -3.64052, -3.76671, -3.84334, -3.84813, -3.91269, -3.94265, -3.84450, -3.79975, -3.75238, -3.63296, -3.50379, -3.44699, -3.40400, -3.37564, -3.33952, -3.30425, -3.19515, -3.12849, -3.06257, -3.01528, -2.90625, -2.88178, -2.75337, -2.69671, -2.58948, -2.47809, -2.48522, -2.49477, -2.40642, -2.32955, -2.42038, -2.46024, -2.48961, -2.50017, -2.40889, -2.17920, +1.22467, 0.99657, 0.84655, 0.74842, 0.85590, 0.94836, 0.91334, 0.84075, 0.83873, 0.90671, 0.85054, 0.76961, 0.73416, 0.75990, 0.86422, 0.83908, 0.76777, 0.68601, 0.50760, 0.37389, 0.33971, 0.41562, 0.48882, 0.45138, 0.40987, 0.38522, 0.33814, 0.39223, 0.44436, 0.39992, 0.32417, 0.32624, 0.28396, 0.18842, 0.26419, 0.34706, 0.39279, 0.51331, 0.58359, 0.56282, 0.46324, 0.47950, 0.49530, 0.52331, 0.57126, 0.65100, 0.87770, 1.05366, 1.12094, 1.14129, 1.12547, 1.19781, 1.21924, 1.11433, 0.90428, 0.72788, 0.75227, 0.86940, 0.93329, 1.08458, 1.31400, 1.42154, 1.38001, 1.39115, 1.59651, 1.67356, 1.70984, 1.82507, 2.02119, 2.27907, 2.34696, 2.35195, 2.32164, 2.37951, 2.32304, 2.20699, 2.09876, 2.05683, 2.06620, 2.07772, 2.12748, 2.29620, 2.30700, 2.18819, 1.94905, 1.74344, 1.58032, 1.46704, 1.39715, 1.33587, 1.20647, 1.01657, 0.81512, 0.65300, 0.39353, 0.14396, -0.12747, -0.43318, -0.69469, -0.90736, -1.11970, -1.10854, -1.10098, -1.07271, -1.18126, -1.23720, -1.32643, -1.43853, -1.59999, -1.79846, -1.81265, -1.68910, -1.63756, -1.62926, -1.84141, -2.02686, -2.16714, -2.22104, -2.29483, -2.37628, -2.37748, -2.41681, -2.59707, -2.76661, -2.82033, -2.92664, -3.24061, -3.45584, -3.48615, -3.54591, -3.65375, -3.67626, -3.68301, -3.54877, -3.55176, -3.57227, -3.69945, -3.69929, -3.78704, -3.90200, -3.89462, -3.86232, -3.82294, -3.88862, -4.11045, -4.16995, -4.22529, -4.15023, -4.05380, -3.83662, -3.58736, -3.42106, -3.23722, -2.95064, -2.81695, -2.86355, -2.91010, -2.82336, -2.80327, -2.80565, -2.66289, -2.47616, -2.32085, -2.17336, -2.19123, -2.16304, -2.20440, -2.22845, -2.41500, -2.53909, -2.51506, -2.38885, -2.19741, -2.16401, -2.18597, -2.09842, -2.06879, -1.92979, -1.98414, -2.04662, -2.13662, -2.27178, -2.35094, -2.36864, -2.22018, -2.01887, -2.00894, -2.04103, -1.98073, -1.92296, -2.04943, -2.21122, -2.17788, -2.10581, -2.13098, -2.13051, -2.21951, -2.17943, -2.24254, -2.25079, -2.20307, -2.02433, -1.83316, -1.80122, -1.72122, -1.59161, -1.35249, -0.96328, -0.74991, -0.46918, -0.31011, -0.32753, -0.38017, -0.35094, -0.27424, -0.31738, -0.34380, -0.15118, -0.03986, -0.07487, -0.07120, 0.04584, 0.09258, 0.01479, 0.01869, 0.05141, 0.06820, 0.17512, 0.16287, 0.17359, 0.23386, 0.30684, 0.31233, 0.19648, 0.10013, 0.00998, 0.07452, 0.19567, 0.28045, 0.46026, 0.46077, 0.40067, 0.31190, 0.26387, 0.32732, 0.30573, 0.28437, 0.29300, 0.36596, 0.49451, 0.46538, 0.32465, 0.31484, 0.42488, 0.49348, 0.46396, 0.58223, 0.77002, 0.79262, 0.87917, 0.99902, 1.16600, 1.27944, 1.21750, 1.16233, 1.14836, 1.27636, 1.37384, 1.43733, 1.55243, 1.62767, 1.66177, 1.61683, 1.69346, 1.84218, 1.85774, 1.88213, 1.99724, 2.14419, 2.17705, 2.14755, 2.21653, 2.20255, 2.05686, 1.95269, 1.98408, 2.12179, 2.22306, 2.37795, 2.51769, 2.60369, 2.71014, 2.75182, 2.59954, 2.44191, 2.25188, 2.22579, 2.23428, 2.31682, 2.33943, 2.28851, 2.20475, 2.15787, 2.24256, 2.30158, 2.19943, 2.08506, 1.94854, 1.93381, 1.88768, 1.86779, 1.83184, 1.89069, 2.07566, 2.16859, 2.03403, 1.86496, 1.77459, 1.63893, 1.46980, 1.46699, 1.52393, 1.36365, 1.04632, 0.76255, 0.48326, 0.37092, 0.21524, 0.08735, 0.03221, 0.09257, 0.00268, -0.10563, -0.07388, -0.06137, -0.14097, -0.28213, -0.49597, -0.68068, -1.05283, -1.36595, -1.62705, -1.84836, -2.09716, -2.36832, -2.48801, -2.52368, -2.69798, -2.95272, -3.12812, -3.14731, -3.17396, -3.11893, -3.09443, -3.17811, -3.27050, -3.25801, -3.35892, -3.44389, -3.60617, -3.75242, -3.95739, -3.97247, -3.90740, -3.84808, -3.86425, -3.95924, -3.97105, -3.90193, -3.95667, -3.92198, -3.94756, -3.82532, -3.65942, -3.51058, -3.45165, -3.46772, -3.43780, -3.40128, -3.41680, -3.36401, -3.19106, -3.01947, -3.03739, -2.97296, -2.80412, -2.66541, -2.60749, -2.51937, -2.42896, -2.27412, -2.33042, -2.34252, -2.32280, -2.21678, -2.22847, -2.27256, -2.21060, -2.16557, -2.10320, -1.89075, +1.14237, 0.91365, 0.78591, 0.69185, 0.72859, 0.75262, 0.72943, 0.68981, 0.69589, 0.76996, 0.77256, 0.72394, 0.68227, 0.72141, 0.79477, 0.71952, 0.59465, 0.48158, 0.34090, 0.27457, 0.30572, 0.41471, 0.60384, 0.72141, 0.66424, 0.58380, 0.59743, 0.72642, 0.71332, 0.55298, 0.38067, 0.30776, 0.20646, 0.07035, 0.18263, 0.30369, 0.30387, 0.39916, 0.53008, 0.55624, 0.42885, 0.43397, 0.52230, 0.64591, 0.72257, 0.78637, 0.94211, 1.05237, 1.09159, 1.07298, 1.05324, 1.12612, 1.09803, 0.90510, 0.69085, 0.58231, 0.55783, 0.59524, 0.70069, 0.97100, 1.21562, 1.27647, 1.23029, 1.24985, 1.42156, 1.44522, 1.48662, 1.66161, 1.87419, 2.10732, 2.19628, 2.23142, 2.16780, 2.22010, 2.21954, 2.16730, 2.05216, 2.01709, 1.99467, 1.94201, 1.95967, 2.05481, 2.09937, 2.08892, 1.91295, 1.72967, 1.60236, 1.58232, 1.48490, 1.29928, 1.10501, 0.95343, 0.71150, 0.47064, 0.23228, 0.02078, -0.24915, -0.53827, -0.71841, -0.84000, -1.04827, -1.08289, -1.07010, -0.99465, -1.13647, -1.26800, -1.37514, -1.41905, -1.55841, -1.71844, -1.74545, -1.70667, -1.73884, -1.86920, -2.10762, -2.24424, -2.34058, -2.36200, -2.41208, -2.36905, -2.31260, -2.39244, -2.52655, -2.53696, -2.55785, -2.72169, -3.02977, -3.18352, -3.17242, -3.26403, -3.39356, -3.41679, -3.47701, -3.41406, -3.43960, -3.44935, -3.61478, -3.64883, -3.72092, -3.74289, -3.70911, -3.64941, -3.55754, -3.60701, -3.81014, -3.92411, -3.98996, -3.87838, -3.75777, -3.56194, -3.40453, -3.22265, -3.06052, -2.88404, -2.74512, -2.66849, -2.69413, -2.64945, -2.61943, -2.60155, -2.47193, -2.34003, -2.20298, -2.01708, -2.05921, -2.13708, -2.23409, -2.21555, -2.37105, -2.47474, -2.41909, -2.21797, -2.07716, -2.12369, -2.19900, -2.21599, -2.24845, -2.21536, -2.33293, -2.36915, -2.39045, -2.46425, -2.52945, -2.45216, -2.27158, -2.15942, -2.15328, -2.02183, -1.85539, -1.83062, -1.99091, -2.16839, -2.16430, -2.14595, -2.21405, -2.21943, -2.32581, -2.33720, -2.41788, -2.36182, -2.27517, -2.09106, -1.82087, -1.63245, -1.50054, -1.36179, -1.13137, -0.82129, -0.65676, -0.48864, -0.45934, -0.51802, -0.55885, -0.49559, -0.41050, -0.40317, -0.42525, -0.32922, -0.26130, -0.22237, -0.16867, -0.10714, -0.09991, -0.14569, -0.12536, -0.13893, -0.14572, 0.01154, 0.05467, 0.06336, 0.10876, 0.20898, 0.17161, -0.03568, -0.15585, -0.18568, -0.08438, 0.03840, 0.12047, 0.27689, 0.30216, 0.23597, 0.11877, 0.08518, 0.17083, 0.16960, 0.14497, 0.23593, 0.39336, 0.45263, 0.35975, 0.26647, 0.32104, 0.38916, 0.37226, 0.29289, 0.37616, 0.50807, 0.48021, 0.58542, 0.73915, 0.89553, 1.05381, 1.10921, 1.12238, 1.10966, 1.24898, 1.42332, 1.56361, 1.67000, 1.70125, 1.68440, 1.62532, 1.71512, 1.85840, 1.89082, 1.95586, 2.13159, 2.29548, 2.34314, 2.34335, 2.32174, 2.21775, 2.11739, 2.09010, 2.04640, 2.08425, 2.17436, 2.35918, 2.49801, 2.54711, 2.64250, 2.64600, 2.40784, 2.20998, 2.06447, 2.10651, 2.11069, 2.17687, 2.26067, 2.30912, 2.23534, 2.17177, 2.19311, 2.16916, 2.02726, 1.85943, 1.76196, 1.82077, 1.80659, 1.77420, 1.72202, 1.82911, 1.97123, 1.96311, 1.84195, 1.79108, 1.70140, 1.49793, 1.32689, 1.34162, 1.40354, 1.28103, 1.04409, 0.82613, 0.54727, 0.41014, 0.28695, 0.21878, 0.10003, 0.05120, -0.05654, -0.09881, -0.04721, -0.01117, -0.11903, -0.30974, -0.49392, -0.70684, -1.08324, -1.36675, -1.61676, -1.85008, -2.12254, -2.37230, -2.57605, -2.72677, -2.86094, -2.93190, -3.03828, -3.09305, -3.13208, -3.11925, -3.15887, -3.30598, -3.41617, -3.37186, -3.49568, -3.63834, -3.77151, -3.82600, -4.03301, -4.08624, -4.01752, -3.88135, -3.87287, -3.91608, -3.86576, -3.79230, -3.82751, -3.85671, -3.92302, -3.78500, -3.59967, -3.46292, -3.44195, -3.38901, -3.36311, -3.42782, -3.43654, -3.25481, -3.04206, -2.88551, -2.89176, -2.82794, -2.67859, -2.58872, -2.53626, -2.40063, -2.35537, -2.31061, -2.38102, -2.31340, -2.24643, -2.12802, -2.11596, -2.04132, -1.89641, -1.79097, -1.71675, -1.55783, +0.97034, 0.91170, 0.81076, 0.65819, 0.59739, 0.54334, 0.48170, 0.46653, 0.60398, 0.63346, 0.52217, 0.52346, 0.52859, 0.54073, 0.57355, 0.53819, 0.38708, 0.27554, 0.24813, 0.26110, 0.41631, 0.54189, 0.67376, 0.89903, 0.90705, 0.92153, 0.95811, 0.97511, 0.89246, 0.63917, 0.49932, 0.32525, 0.06001, 0.01556, 0.20648, 0.31045, 0.32694, 0.41239, 0.51732, 0.50307, 0.46505, 0.44990, 0.45555, 0.62835, 0.76690, 0.79742, 0.88251, 1.00828, 1.06247, 1.04055, 1.07486, 1.05554, 0.95620, 0.68407, 0.39795, 0.36721, 0.39679, 0.46383, 0.57161, 0.73682, 1.01027, 1.07282, 1.15822, 1.16176, 1.12496, 1.17379, 1.30928, 1.48328, 1.77781, 2.00786, 2.11433, 2.14738, 2.21799, 2.30339, 2.20561, 2.09409, 1.98373, 1.90015, 1.88208, 1.92844, 1.97721, 1.93275, 1.99636, 2.00007, 1.92780, 1.83063, 1.65486, 1.62832, 1.53801, 1.33689, 1.12031, 0.81282, 0.55224, 0.25520, 0.17351, 0.05198, -0.31533, -0.53873, -0.59999, -0.77106, -0.93929, -1.01909, -1.01527, -1.00812, -1.07534, -1.18186, -1.41254, -1.52673, -1.59713, -1.72038, -1.74737, -1.72008, -1.79650, -2.09614, -2.26049, -2.34783, -2.35522, -2.32124, -2.45143, -2.41263, -2.25591, -2.24512, -2.25309, -2.33531, -2.37393, -2.60419, -2.78511, -2.79407, -2.86414, -2.99139, -3.04394, -3.15165, -3.20087, -3.19893, -3.25760, -3.41063, -3.55117, -3.51276, -3.59836, -3.60520, -3.50991, -3.50807, -3.43095, -3.39637, -3.44420, -3.60571, -3.62725, -3.56041, -3.45587, -3.25305, -3.24040, -3.15076, -2.96674, -2.79300, -2.52888, -2.49281, -2.50134, -2.52346, -2.46477, -2.36744, -2.37326, -2.34061, -2.11426, -1.99943, -2.02678, -2.14098, -2.25842, -2.33101, -2.38947, -2.29723, -2.25679, -2.16566, -2.10491, -2.28079, -2.39601, -2.40247, -2.34326, -2.44712, -2.59593, -2.64159, -2.60361, -2.52874, -2.60076, -2.59168, -2.41289, -2.32705, -2.20023, -2.04280, -1.83172, -1.85189, -1.97977, -2.01170, -2.08470, -2.17296, -2.16419, -2.26901, -2.38436, -2.37502, -2.35321, -2.26488, -2.13006, -1.85707, -1.61877, -1.46473, -1.26480, -1.14512, -0.99034, -0.78130, -0.58136, -0.54697, -0.60243, -0.68242, -0.73758, -0.56932, -0.46015, -0.51180, -0.50438, -0.47278, -0.39574, -0.41084, -0.40199, -0.39566, -0.38734, -0.27754, -0.28180, -0.38816, -0.29430, -0.16623, -0.09192, 0.00522, 0.08570, 0.10919, -0.03250, -0.18959, -0.31021, -0.37692, -0.22220, -0.14149, -0.13651, -0.00520, 0.18426, 0.16262, 0.04406, 0.00448, 0.00014, 0.05097, 0.03762, 0.09199, 0.31095, 0.34174, 0.30605, 0.25506, 0.27962, 0.31622, 0.21389, 0.17056, 0.15883, 0.14446, 0.24607, 0.39613, 0.49084, 0.63722, 0.82708, 0.94682, 1.00344, 1.13199, 1.26060, 1.32594, 1.48899, 1.58584, 1.54650, 1.52607, 1.60982, 1.79107, 1.97283, 2.08979, 2.14741, 2.37826, 2.51576, 2.44869, 2.44253, 2.37136, 2.28862, 2.20733, 2.12143, 2.06054, 2.00282, 2.16307, 2.36848, 2.43836, 2.55813, 2.63459, 2.45828, 2.20501, 2.06032, 2.01242, 2.07402, 2.15542, 2.18804, 2.16490, 2.24560, 2.20979, 2.06008, 1.97259, 1.93776, 1.83062, 1.63448, 1.65319, 1.71137, 1.73152, 1.71359, 1.58639, 1.70163, 1.83082, 1.79617, 1.68137, 1.56949, 1.55031, 1.37662, 1.35916, 1.38612, 1.30392, 1.26777, 1.19002, 0.95515, 0.74925, 0.60561, 0.48539, 0.35450, 0.24803, 0.13671, -0.10153, -0.17952, -0.07887, -0.06769, -0.18966, -0.30742, -0.40699, -0.69997, -1.01208, -1.32132, -1.56515, -1.79463, -2.18408, -2.46948, -2.68872, -2.87121, -2.93754, -2.99236, -2.95416, -3.03183, -3.03107, -3.07141, -3.28001, -3.40296, -3.37669, -3.41035, -3.54428, -3.73100, -3.81519, -3.85788, -3.95891, -3.97426, -4.04596, -4.00913, -3.94040, -3.96653, -3.84974, -3.69221, -3.62316, -3.72399, -3.72018, -3.60076, -3.43318, -3.32286, -3.43748, -3.41289, -3.30404, -3.29558, -3.18521, -3.09174, -2.88407, -2.78114, -2.70312, -2.57036, -2.56135, -2.55378, -2.42660, -2.37906, -2.36341, -2.37824, -2.40496, -2.35598, -2.17168, -1.91654, -1.93601, -1.88846, -1.67367, -1.59419, -1.52118, -1.34289, +0.82324, 0.89061, 0.81646, 0.64907, 0.51363, 0.39566, 0.30574, 0.30111, 0.36432, 0.25887, 0.12773, 0.19680, 0.31402, 0.37749, 0.31265, 0.21190, 0.18862, 0.21124, 0.28891, 0.38325, 0.48879, 0.55576, 0.67354, 0.91593, 0.94829, 1.01471, 1.09325, 1.05165, 0.97144, 0.76859, 0.58259, 0.35626, 0.15146, 0.18045, 0.33743, 0.43172, 0.47095, 0.55410, 0.58246, 0.51101, 0.42983, 0.33366, 0.36744, 0.60126, 0.81633, 0.94258, 0.93206, 0.88209, 0.93638, 0.99737, 1.03069, 0.93749, 0.71187, 0.39319, 0.21740, 0.30571, 0.36493, 0.35913, 0.40027, 0.46348, 0.73691, 0.93356, 1.01714, 0.93071, 0.88758, 1.03852, 1.22165, 1.43682, 1.74192, 1.95420, 2.04803, 2.12564, 2.26304, 2.28370, 2.17447, 2.08347, 2.01482, 1.98442, 1.95164, 1.91417, 1.94477, 1.89667, 1.86980, 1.83937, 1.78589, 1.68979, 1.59627, 1.60504, 1.48282, 1.24027, 1.04763, 0.73039, 0.47542, 0.26400, 0.16628, -0.01983, -0.30473, -0.36761, -0.43645, -0.63356, -0.80120, -0.89366, -0.92476, -0.96919, -1.01997, -1.17047, -1.42982, -1.57441, -1.64685, -1.68341, -1.73414, -1.87278, -1.98677, -2.16373, -2.22017, -2.20656, -2.18020, -2.27514, -2.43397, -2.39075, -2.23441, -2.19467, -2.13854, -2.22465, -2.27728, -2.36959, -2.47140, -2.52067, -2.59023, -2.63279, -2.70003, -2.80970, -2.84101, -2.87159, -2.99595, -3.22162, -3.33980, -3.36058, -3.39762, -3.32800, -3.24106, -3.23927, -3.24087, -3.32599, -3.30919, -3.31239, -3.28416, -3.25547, -3.21840, -3.15614, -3.14472, -3.00159, -2.83444, -2.73983, -2.48841, -2.45580, -2.44405, -2.36796, -2.34203, -2.37889, -2.42215, -2.28899, -2.04913, -1.96445, -1.95646, -2.01327, -2.16698, -2.34051, -2.38778, -2.30588, -2.27499, -2.20603, -2.20784, -2.33901, -2.40924, -2.48545, -2.44387, -2.53430, -2.70327, -2.77666, -2.72412, -2.67329, -2.71173, -2.66511, -2.52379, -2.48463, -2.31015, -2.12557, -1.93896, -1.87810, -1.95149, -2.00511, -2.05980, -2.04525, -2.01658, -2.13534, -2.19543, -2.11098, -1.99159, -1.88117, -1.75348, -1.59577, -1.48173, -1.33524, -1.11539, -0.95280, -0.82144, -0.82489, -0.75054, -0.67654, -0.66764, -0.69755, -0.75106, -0.69166, -0.61989, -0.62795, -0.60768, -0.68020, -0.70059, -0.76821, -0.78868, -0.69302, -0.60822, -0.54386, -0.51962, -0.46255, -0.32932, -0.28646, -0.22799, -0.07536, 0.01074, -0.04057, -0.22108, -0.37522, -0.46656, -0.43076, -0.25209, -0.22271, -0.26016, -0.27735, -0.12553, -0.00696, -0.03524, -0.08306, -0.14969, -0.18308, -0.21435, -0.12205, 0.07293, 0.01849, -0.02492, -0.00571, 0.04750, 0.13872, 0.07562, -0.04355, -0.11262, -0.04368, 0.17788, 0.30547, 0.33578, 0.43009, 0.56975, 0.68458, 0.78886, 0.94265, 1.02584, 1.07875, 1.25450, 1.39749, 1.46701, 1.45756, 1.52772, 1.80427, 2.09005, 2.26942, 2.35510, 2.49560, 2.50805, 2.43501, 2.43693, 2.31344, 2.20002, 2.12179, 2.06970, 2.09408, 2.07378, 2.10987, 2.21809, 2.37829, 2.58735, 2.59604, 2.36540, 2.18626, 2.16141, 2.21591, 2.28355, 2.27321, 2.14844, 2.04505, 2.12665, 2.10865, 1.96416, 1.75669, 1.57743, 1.55037, 1.50575, 1.58285, 1.61063, 1.54359, 1.44014, 1.37270, 1.53259, 1.60206, 1.50213, 1.41895, 1.35651, 1.45161, 1.47949, 1.46322, 1.36695, 1.27989, 1.33548, 1.30106, 1.11671, 0.99220, 0.89051, 0.73037, 0.53068, 0.37717, 0.17209, -0.08046, -0.16596, -0.11889, -0.10558, -0.24951, -0.43199, -0.48865, -0.69636, -0.96742, -1.26090, -1.54533, -1.89320, -2.30337, -2.52679, -2.75481, -3.02844, -3.12574, -3.15518, -3.01015, -2.95135, -2.99592, -3.16943, -3.31443, -3.24566, -3.14643, -3.22481, -3.42334, -3.63330, -3.74577, -3.78640, -3.84438, -3.95095, -4.08641, -4.06578, -3.96374, -3.88660, -3.74317, -3.70339, -3.62168, -3.59327, -3.50104, -3.36689, -3.27643, -3.33180, -3.45267, -3.34773, -3.18102, -3.13961, -3.01245, -2.97294, -2.82354, -2.67080, -2.59272, -2.56993, -2.56866, -2.46656, -2.37426, -2.38530, -2.36231, -2.30346, -2.28058, -2.25062, -2.07314, -1.89772, -1.90552, -1.79691, -1.59075, -1.49384, -1.40559, -1.32489, +0.69013, 0.61940, 0.54616, 0.42403, 0.30106, 0.22958, 0.07975, 0.06972, 0.11030, -0.07525, -0.19140, -0.14450, -0.08117, 0.04248, 0.03740, -0.00853, 0.03521, 0.08723, 0.22650, 0.27201, 0.31311, 0.46803, 0.62088, 0.78013, 0.82319, 0.97363, 1.18267, 1.14590, 1.00509, 0.83285, 0.62101, 0.54344, 0.47310, 0.33893, 0.35107, 0.43189, 0.44586, 0.57802, 0.55242, 0.47139, 0.43886, 0.35838, 0.46823, 0.70624, 0.85674, 1.03673, 1.04739, 0.90905, 0.84399, 0.77234, 0.77010, 0.62786, 0.39730, 0.27649, 0.25317, 0.31805, 0.33970, 0.31124, 0.35220, 0.34726, 0.46198, 0.66381, 0.67285, 0.67932, 0.82614, 0.93221, 1.06737, 1.33577, 1.56141, 1.79221, 1.86096, 1.95768, 2.18997, 2.22727, 2.16991, 2.14405, 2.05448, 2.02944, 2.01362, 1.87890, 1.79177, 1.63296, 1.55202, 1.48111, 1.41351, 1.46345, 1.53418, 1.55359, 1.41346, 1.24261, 1.16362, 0.93039, 0.57686, 0.34701, 0.09909, -0.07438, -0.17721, -0.25655, -0.41627, -0.56802, -0.79330, -0.84327, -0.89657, -0.98726, -0.97257, -1.08873, -1.32879, -1.48882, -1.69082, -1.80021, -1.83747, -2.01182, -2.11282, -2.24209, -2.21590, -2.15188, -2.17791, -2.25387, -2.34611, -2.35991, -2.29390, -2.20988, -2.09521, -2.07574, -2.15774, -2.15405, -2.26350, -2.29924, -2.25207, -2.32642, -2.52318, -2.59071, -2.67599, -2.70227, -2.84523, -3.06214, -3.06145, -3.05498, -3.08746, -3.03715, -3.06203, -3.11652, -3.11183, -3.22904, -3.22181, -3.25129, -3.18871, -3.14345, -3.19362, -3.10971, -2.97184, -2.80353, -2.71385, -2.65650, -2.47166, -2.39063, -2.46268, -2.36316, -2.38783, -2.47378, -2.38299, -2.19743, -2.07483, -1.95358, -1.94745, -1.94392, -2.10164, -2.36016, -2.40234, -2.34189, -2.33917, -2.26130, -2.30044, -2.42078, -2.41191, -2.48471, -2.50819, -2.70801, -2.88953, -2.94572, -2.95434, -2.86505, -2.78258, -2.67801, -2.55880, -2.47396, -2.26863, -2.02057, -1.96900, -1.92635, -2.00601, -2.09758, -2.00981, -1.92555, -2.01283, -2.02557, -2.00169, -1.86006, -1.70313, -1.67400, -1.52832, -1.36489, -1.33407, -1.21541, -1.07860, -1.00025, -0.82961, -0.86973, -0.88823, -0.87358, -0.80984, -0.74239, -0.83201, -0.84344, -0.76421, -0.76325, -0.81613, -0.90378, -0.93509, -0.94310, -1.02453, -0.91463, -0.79156, -0.78351, -0.60200, -0.40871, -0.43818, -0.46342, -0.47047, -0.38519, -0.29594, -0.39909, -0.47486, -0.47218, -0.51425, -0.41560, -0.31457, -0.43699, -0.47268, -0.52325, -0.44262, -0.36197, -0.39462, -0.37232, -0.43658, -0.47684, -0.42265, -0.32486, -0.27270, -0.37491, -0.38898, -0.27513, -0.24825, -0.20361, -0.21574, -0.33627, -0.25137, -0.06006, -0.00465, 0.00483, 0.01025, 0.04606, 0.17322, 0.22790, 0.37665, 0.63536, 0.76573, 0.87760, 1.03657, 1.15121, 1.36701, 1.48327, 1.56334, 1.76919, 1.97456, 2.19625, 2.28370, 2.39213, 2.48031, 2.46583, 2.41872, 2.30282, 2.24877, 2.23610, 2.20476, 2.18544, 2.16820, 2.06334, 2.17141, 2.40974, 2.48819, 2.43048, 2.31510, 2.20640, 2.29198, 2.34912, 2.38711, 2.36655, 2.16894, 1.99225, 1.97296, 1.82291, 1.66480, 1.51594, 1.36190, 1.36133, 1.32151, 1.41876, 1.38860, 1.24651, 1.20418, 1.19856, 1.28736, 1.29902, 1.27376, 1.34186, 1.38430, 1.43888, 1.50195, 1.36114, 1.28714, 1.32777, 1.28780, 1.17929, 1.09588, 1.00143, 1.00983, 0.83161, 0.58579, 0.49178, 0.31580, 0.08063, -0.05300, -0.21187, -0.30821, -0.41116, -0.56838, -0.59704, -0.80925, -1.02357, -1.27147, -1.56980, -1.84646, -2.19625, -2.44273, -2.70842, -2.96231, -3.05377, -3.07993, -3.05227, -2.96662, -3.07351, -3.17636, -3.11079, -3.05310, -3.06432, -3.13727, -3.41810, -3.59751, -3.75983, -3.85361, -3.84026, -3.93344, -4.03107, -3.95905, -3.91017, -3.84230, -3.66007, -3.65801, -3.59726, -3.60939, -3.49481, -3.35718, -3.35619, -3.35541, -3.32721, -3.19286, -3.06282, -3.00399, -2.90010, -2.81225, -2.78855, -2.66323, -2.66163, -2.67297, -2.52428, -2.39980, -2.45320, -2.43520, -2.39367, -2.20941, -2.13505, -2.15553, -1.99890, -1.87452, -1.88085, -1.72850, -1.58570, -1.53982, -1.38712, -1.27593, +0.39329, 0.23970, 0.17663, 0.10071, 0.03481, 0.00766, -0.10751, -0.13237, -0.14692, -0.34505, -0.50231, -0.52728, -0.45917, -0.29178, -0.23438, -0.18330, -0.03673, 0.06184, 0.18564, 0.15931, 0.15820, 0.33755, 0.51376, 0.68543, 0.77096, 0.97609, 1.22114, 1.20227, 1.08189, 0.93236, 0.81035, 0.84137, 0.73837, 0.49118, 0.40961, 0.44058, 0.42219, 0.55496, 0.60575, 0.57731, 0.54910, 0.50681, 0.60835, 0.78331, 0.93893, 1.13117, 1.13005, 0.97768, 0.87038, 0.72991, 0.66979, 0.52696, 0.36764, 0.36288, 0.38789, 0.42770, 0.40304, 0.34057, 0.33624, 0.23818, 0.26556, 0.40601, 0.43208, 0.55987, 0.77931, 0.86027, 0.97824, 1.21094, 1.35887, 1.54355, 1.65248, 1.77858, 1.99098, 2.06065, 2.02857, 2.00831, 1.97734, 1.98147, 1.91480, 1.68815, 1.52653, 1.36423, 1.27488, 1.21979, 1.19383, 1.31657, 1.47284, 1.55779, 1.47312, 1.38143, 1.35815, 1.10957, 0.73748, 0.45346, 0.14776, 0.03517, -0.05493, -0.18439, -0.32738, -0.48079, -0.75048, -0.84928, -0.89151, -0.94862, -0.94586, -1.05022, -1.28508, -1.50451, -1.72540, -1.84687, -1.91720, -2.07850, -2.12902, -2.15859, -2.10407, -2.04275, -2.10340, -2.18689, -2.25517, -2.27570, -2.23785, -2.13745, -2.01278, -1.98911, -1.98795, -1.92488, -2.00475, -1.95655, -1.90804, -2.04552, -2.24581, -2.33982, -2.48592, -2.57320, -2.69022, -2.78972, -2.73667, -2.71606, -2.78677, -2.88920, -2.96127, -2.96292, -2.95044, -3.05717, -3.06997, -3.08938, -3.02311, -2.97107, -3.03774, -2.94787, -2.78482, -2.62047, -2.55177, -2.51572, -2.40593, -2.40568, -2.50278, -2.39237, -2.38259, -2.37334, -2.24807, -2.11691, -2.01043, -1.88116, -1.88367, -1.92673, -2.08166, -2.28132, -2.34385, -2.33662, -2.36667, -2.37563, -2.40189, -2.42794, -2.41000, -2.50077, -2.58649, -2.78205, -2.92162, -2.94594, -2.95427, -2.84814, -2.73380, -2.57323, -2.37375, -2.22220, -2.02104, -1.86132, -1.88701, -1.86051, -1.93614, -1.98626, -1.89546, -1.88495, -1.98222, -1.90947, -1.82321, -1.70366, -1.58496, -1.56758, -1.42812, -1.26067, -1.24185, -1.22644, -1.16613, -1.07294, -0.89105, -0.93096, -0.98676, -0.94885, -0.83167, -0.72648, -0.81306, -0.87166, -0.85967, -0.89140, -0.95377, -0.98691, -0.97190, -1.00928, -1.12189, -1.00540, -0.87248, -0.80397, -0.58604, -0.47670, -0.59318, -0.65029, -0.71798, -0.74769, -0.70673, -0.75046, -0.72305, -0.63331, -0.63782, -0.61316, -0.62085, -0.75132, -0.77095, -0.83793, -0.80510, -0.72985, -0.74169, -0.65792, -0.63731, -0.63884, -0.58840, -0.54685, -0.56033, -0.65172, -0.65018, -0.59787, -0.64607, -0.61140, -0.57102, -0.54315, -0.33182, -0.18107, -0.26023, -0.34921, -0.37873, -0.38280, -0.28281, -0.18881, 0.00374, 0.29813, 0.50245, 0.62646, 0.75601, 0.94982, 1.27077, 1.44435, 1.54176, 1.71287, 1.87742, 2.09490, 2.20649, 2.37129, 2.52729, 2.54289, 2.51642, 2.45479, 2.45143, 2.42526, 2.33365, 2.28444, 2.25604, 2.17922, 2.31895, 2.46762, 2.44465, 2.39236, 2.35214, 2.27794, 2.34483, 2.40312, 2.41653, 2.34592, 2.12620, 1.85550, 1.68270, 1.49164, 1.35318, 1.26988, 1.22457, 1.28998, 1.29652, 1.37111, 1.31518, 1.18088, 1.13925, 1.08279, 1.11482, 1.13161, 1.19362, 1.35084, 1.39867, 1.44146, 1.43550, 1.24089, 1.23555, 1.27264, 1.16118, 1.05740, 1.00402, 0.93012, 0.95910, 0.82957, 0.62168, 0.52937, 0.37599, 0.11343, -0.13661, -0.38971, -0.53049, -0.63872, -0.73808, -0.67488, -0.77512, -0.94356, -1.14653, -1.40130, -1.64231, -1.98459, -2.25201, -2.51946, -2.72989, -2.81802, -2.94100, -2.99548, -2.95449, -3.05311, -3.02498, -2.93320, -2.98057, -3.05702, -3.18003, -3.48765, -3.69085, -3.85038, -3.91452, -3.89928, -3.96396, -3.99458, -3.92251, -3.85800, -3.74924, -3.59496, -3.59272, -3.51731, -3.50844, -3.43634, -3.33184, -3.33902, -3.28149, -3.17599, -3.02462, -2.90836, -2.87989, -2.83742, -2.80172, -2.78976, -2.67307, -2.67063, -2.60391, -2.43256, -2.36838, -2.44192, -2.41849, -2.34947, -2.15896, -2.05675, -2.03366, -1.94278, -1.88139, -1.90433, -1.82535, -1.67129, -1.55874, -1.40194, -1.26323, +-0.05709, -0.14570, -0.20029, -0.22058, -0.15273, -0.06532, -0.09017, -0.27939, -0.49522, -0.56636, -0.65459, -0.72121, -0.63809, -0.51640, -0.39882, -0.28993, -0.14087, -0.01364, 0.05764, 0.00875, -0.00646, 0.08583, 0.25426, 0.48309, 0.62913, 0.88970, 1.15542, 1.18033, 1.11622, 1.01791, 1.01175, 1.01848, 0.80435, 0.61491, 0.49393, 0.48819, 0.51392, 0.70487, 0.89931, 0.82793, 0.67280, 0.68910, 0.76028, 0.84668, 1.03564, 1.12814, 1.11186, 1.00744, 0.91315, 0.80595, 0.67725, 0.53638, 0.43881, 0.40433, 0.41897, 0.46256, 0.36866, 0.26642, 0.25282, 0.14603, 0.12985, 0.20966, 0.27596, 0.42196, 0.59758, 0.78449, 0.90516, 1.02605, 1.13467, 1.35776, 1.60490, 1.64726, 1.64908, 1.79058, 1.87657, 1.84102, 1.89633, 1.86872, 1.73827, 1.46845, 1.21275, 1.06283, 0.96154, 0.94230, 1.00759, 1.08982, 1.22563, 1.38881, 1.38668, 1.40520, 1.44613, 1.22167, 0.86103, 0.54366, 0.23348, 0.12095, -0.08916, -0.16301, -0.23346, -0.41268, -0.65872, -0.80057, -0.83871, -0.95535, -1.13534, -1.24893, -1.35911, -1.57678, -1.65037, -1.74893, -1.89944, -2.05926, -2.15325, -2.12539, -2.06119, -2.02030, -2.09047, -2.26796, -2.35488, -2.31160, -2.26303, -2.13333, -1.99494, -1.92748, -1.83209, -1.72270, -1.76662, -1.71815, -1.80552, -1.85579, -1.91298, -2.05906, -2.22306, -2.28534, -2.29405, -2.35416, -2.43403, -2.43470, -2.42205, -2.63994, -2.68985, -2.66813, -2.71391, -2.80393, -2.89720, -2.96217, -2.96023, -2.95160, -2.96189, -2.90927, -2.80982, -2.64258, -2.57193, -2.52130, -2.44953, -2.47118, -2.56377, -2.44550, -2.37402, -2.26291, -2.23120, -2.15225, -2.01624, -1.92162, -1.91423, -1.96238, -2.02216, -2.12610, -2.25686, -2.31357, -2.27762, -2.38401, -2.38874, -2.33982, -2.37629, -2.47579, -2.67726, -2.89205, -2.96375, -2.95888, -2.90188, -2.82379, -2.77270, -2.55198, -2.25320, -2.02171, -1.82762, -1.75329, -1.82340, -1.76881, -1.80185, -1.83351, -1.91630, -1.96278, -1.94705, -1.86553, -1.73782, -1.58471, -1.43650, -1.40428, -1.40888, -1.34307, -1.21591, -1.25595, -1.22004, -1.09859, -1.01351, -1.04397, -1.12403, -1.07876, -0.92133, -0.84193, -0.88531, -0.98916, -1.11622, -1.17123, -1.20200, -1.15267, -1.05553, -1.05704, -1.16265, -1.10713, -1.03886, -0.92180, -0.84761, -0.88007, -0.90999, -0.94514, -0.95056, -0.96336, -0.92481, -0.91456, -0.97332, -0.95415, -0.82245, -0.84087, -0.95342, -1.04286, -1.09477, -1.15034, -1.16657, -1.14787, -1.13810, -1.03534, -0.89604, -0.84734, -0.90722, -0.96736, -0.99175, -1.00454, -0.94981, -0.95949, -1.06882, -1.01848, -0.92386, -0.75841, -0.55775, -0.48593, -0.50558, -0.64150, -0.69474, -0.66542, -0.53111, -0.34969, -0.24576, -0.08475, 0.23445, 0.42567, 0.56634, 0.90015, 1.21883, 1.39505, 1.48753, 1.57918, 1.72399, 1.91138, 2.07550, 2.33125, 2.47876, 2.52364, 2.56050, 2.50092, 2.49953, 2.46892, 2.33006, 2.25332, 2.25693, 2.31117, 2.49635, 2.52379, 2.53803, 2.48245, 2.44579, 2.44669, 2.53860, 2.61742, 2.45204, 2.18650, 2.03775, 1.79261, 1.49983, 1.34057, 1.16315, 1.11398, 1.17134, 1.23576, 1.25905, 1.24289, 1.18668, 1.15494, 1.04830, 0.87778, 0.88698, 0.94991, 1.10417, 1.31111, 1.37644, 1.41867, 1.35250, 1.14282, 1.11641, 1.02581, 0.97131, 0.91348, 0.84615, 0.81937, 0.87914, 0.85566, 0.62105, 0.40122, 0.29357, 0.09591, -0.24308, -0.47843, -0.67198, -0.81195, -0.84807, -0.75687, -0.74773, -0.87796, -1.06378, -1.30048, -1.63897, -2.02861, -2.29636, -2.54531, -2.65634, -2.66653, -2.74227, -2.83292, -2.87611, -2.99927, -2.95073, -2.97524, -3.01027, -3.09651, -3.32760, -3.59037, -3.72918, -3.79705, -3.89242, -4.02586, -4.06937, -3.92834, -3.84848, -3.70399, -3.60891, -3.57299, -3.54283, -3.45881, -3.42961, -3.43975, -3.39448, -3.32252, -3.28170, -3.21287, -3.03500, -2.91142, -2.88020, -2.87467, -2.84332, -2.80982, -2.68626, -2.64693, -2.51566, -2.46976, -2.41416, -2.39864, -2.38035, -2.23018, -1.99506, -1.82188, -1.79067, -1.88930, -1.91942, -1.84504, -1.83787, -1.63010, -1.46013, -1.36484, -1.23030, +-0.28605, -0.32317, -0.35990, -0.35450, -0.36358, -0.34797, -0.36218, -0.59029, -0.78403, -0.73996, -0.70018, -0.69999, -0.71252, -0.65466, -0.48687, -0.40470, -0.32598, -0.20601, -0.14242, -0.15980, -0.05406, 0.09771, 0.26830, 0.52924, 0.63795, 0.86247, 1.15154, 1.24210, 1.27264, 1.26654, 1.22433, 1.12196, 0.91720, 0.81101, 0.74849, 0.79061, 0.77840, 0.85701, 1.02144, 0.94654, 0.83122, 0.88071, 0.92807, 1.01236, 1.08870, 1.01066, 1.01235, 0.97378, 0.95643, 0.90036, 0.72737, 0.54605, 0.48640, 0.50245, 0.49369, 0.51761, 0.34666, 0.17148, 0.19861, 0.17297, 0.18998, 0.29266, 0.32723, 0.37229, 0.49802, 0.69662, 0.78202, 0.83324, 0.87568, 1.04012, 1.34934, 1.39539, 1.38352, 1.60361, 1.75441, 1.72316, 1.67233, 1.51041, 1.40235, 1.18659, 0.94759, 0.81657, 0.73126, 0.72919, 0.89129, 1.08871, 1.19114, 1.35585, 1.37144, 1.35223, 1.41222, 1.23888, 0.92336, 0.69584, 0.43743, 0.28029, 0.05910, -0.00430, -0.12368, -0.31827, -0.58328, -0.87501, -0.97451, -1.12303, -1.33891, -1.43158, -1.46893, -1.55219, -1.54132, -1.72918, -1.92076, -2.10598, -2.26002, -2.24559, -2.17382, -2.14380, -2.15481, -2.17557, -2.21281, -2.11504, -2.05421, -2.01674, -1.86259, -1.73865, -1.65055, -1.50633, -1.54195, -1.58813, -1.65404, -1.52681, -1.45612, -1.55700, -1.72375, -1.86914, -1.87368, -1.99865, -2.14890, -2.10180, -2.03039, -2.14671, -2.17936, -2.29411, -2.36785, -2.46503, -2.61173, -2.74709, -2.85010, -2.92694, -2.91171, -2.75020, -2.70889, -2.61048, -2.56403, -2.58962, -2.47313, -2.40365, -2.47290, -2.35128, -2.29788, -2.23670, -2.20593, -2.07912, -1.94951, -1.85261, -1.86924, -2.05406, -2.09285, -2.12720, -2.17926, -2.17657, -2.16144, -2.26892, -2.32279, -2.42141, -2.49049, -2.57630, -2.77439, -2.93844, -2.93551, -2.88695, -2.77889, -2.57423, -2.50475, -2.31375, -2.06129, -1.95428, -1.79431, -1.70203, -1.72246, -1.54913, -1.50152, -1.60514, -1.77335, -1.77177, -1.73851, -1.73593, -1.66143, -1.60319, -1.45910, -1.38298, -1.38179, -1.27960, -1.11954, -1.11670, -1.07420, -1.10197, -1.13576, -1.17637, -1.24613, -1.20511, -1.08440, -1.07335, -1.12301, -1.09411, -1.15806, -1.20884, -1.24261, -1.31839, -1.26450, -1.18588, -1.23074, -1.16914, -1.13148, -1.09923, -1.16014, -1.22135, -1.19292, -1.17115, -1.08588, -1.17040, -1.23295, -1.26966, -1.38928, -1.35119, -1.16797, -1.14207, -1.22164, -1.37065, -1.45702, -1.46578, -1.48204, -1.48528, -1.46965, -1.41563, -1.32123, -1.18642, -1.21142, -1.31724, -1.31247, -1.32975, -1.27230, -1.25226, -1.33245, -1.21397, -1.07130, -0.97879, -0.85598, -0.72199, -0.62653, -0.70225, -0.73000, -0.75723, -0.69485, -0.50965, -0.41631, -0.25196, 0.08749, 0.33873, 0.56795, 0.85521, 1.04738, 1.19752, 1.28453, 1.39239, 1.59410, 1.79464, 1.95458, 2.27018, 2.49368, 2.57938, 2.66046, 2.52718, 2.43180, 2.42598, 2.29642, 2.23173, 2.33584, 2.45972, 2.67351, 2.72414, 2.76617, 2.66822, 2.58598, 2.52850, 2.51575, 2.56594, 2.36693, 2.12212, 2.04699, 1.85551, 1.59006, 1.35616, 1.05192, 0.97096, 0.99089, 1.03163, 1.05094, 0.99724, 0.96375, 1.07798, 1.11029, 0.91622, 0.91335, 0.96784, 1.03560, 1.20245, 1.29864, 1.37665, 1.38441, 1.18559, 1.07148, 0.96517, 0.97370, 0.92754, 0.86731, 0.79131, 0.70542, 0.68353, 0.46324, 0.24201, 0.14742, -0.04352, -0.32485, -0.54243, -0.80335, -0.91326, -0.93865, -0.88606, -0.86025, -0.95393, -1.13997, -1.35377, -1.60869, -1.99996, -2.30246, -2.57379, -2.71379, -2.62609, -2.56273, -2.65787, -2.72692, -2.94072, -3.04944, -3.11721, -3.08949, -3.16584, -3.37774, -3.59973, -3.79700, -3.82805, -3.92387, -4.05493, -4.03234, -3.88313, -3.78129, -3.65040, -3.69873, -3.69228, -3.60266, -3.45768, -3.38430, -3.41298, -3.40147, -3.26492, -3.12937, -3.13739, -3.00264, -2.88797, -2.92054, -2.87689, -2.76483, -2.68197, -2.47724, -2.39949, -2.32222, -2.32458, -2.24131, -2.19296, -2.14357, -1.99489, -1.91351, -1.77937, -1.75101, -1.82197, -1.76744, -1.66685, -1.65976, -1.53282, -1.53892, -1.48347, -1.36774, +-0.48732, -0.55070, -0.58222, -0.52419, -0.52755, -0.61775, -0.71132, -0.82297, -0.91723, -0.88326, -0.82516, -0.79294, -0.79554, -0.67636, -0.42585, -0.43355, -0.44572, -0.25952, -0.21736, -0.20675, -0.02755, 0.11171, 0.25164, 0.56340, 0.76208, 1.01494, 1.25842, 1.40878, 1.51623, 1.48590, 1.40768, 1.23152, 1.04853, 0.93019, 0.92033, 1.05081, 1.11222, 1.08358, 1.06813, 1.03640, 1.00812, 1.03318, 1.09459, 1.15071, 1.16444, 1.07528, 1.14906, 1.08830, 1.01910, 0.99405, 0.77140, 0.54182, 0.51036, 0.48506, 0.41933, 0.44304, 0.37831, 0.26056, 0.24578, 0.22870, 0.31025, 0.34209, 0.37670, 0.32805, 0.38560, 0.44994, 0.47630, 0.52718, 0.63998, 0.77352, 1.00258, 1.13594, 1.25357, 1.43419, 1.57450, 1.47835, 1.35254, 1.19754, 1.20101, 1.03280, 0.78354, 0.73591, 0.68816, 0.65735, 0.90144, 1.10514, 1.17659, 1.33653, 1.44294, 1.45349, 1.46047, 1.25536, 1.04476, 0.79699, 0.63177, 0.45407, 0.26639, 0.07465, -0.17730, -0.41384, -0.62194, -0.90655, -1.06369, -1.18936, -1.30629, -1.45640, -1.49289, -1.56337, -1.56738, -1.79749, -1.94725, -2.14051, -2.37529, -2.32399, -2.21186, -2.22222, -2.09530, -2.03526, -2.05755, -1.95317, -1.80254, -1.73154, -1.59157, -1.54698, -1.44974, -1.41935, -1.42338, -1.50177, -1.45312, -1.27946, -1.15249, -1.16736, -1.20736, -1.32718, -1.42418, -1.62363, -1.71038, -1.70137, -1.62077, -1.69303, -1.71031, -1.84385, -1.85752, -1.95357, -2.20404, -2.37216, -2.50452, -2.72147, -2.69419, -2.57516, -2.63302, -2.63787, -2.55128, -2.51799, -2.35279, -2.31322, -2.29331, -2.30060, -2.31653, -2.33533, -2.24677, -2.07898, -1.92195, -1.81187, -1.76785, -1.93739, -2.03873, -2.09721, -2.04611, -2.11385, -2.17925, -2.32848, -2.42236, -2.55936, -2.56298, -2.57344, -2.74360, -2.81361, -2.70123, -2.69183, -2.52842, -2.30154, -2.24640, -2.15328, -1.94505, -1.84654, -1.69419, -1.65399, -1.53905, -1.36306, -1.28805, -1.41754, -1.56436, -1.58698, -1.62955, -1.72703, -1.65279, -1.55774, -1.44649, -1.37931, -1.23910, -1.12255, -1.00771, -1.02252, -0.99431, -1.07058, -1.08700, -1.08899, -1.22135, -1.22185, -1.09063, -1.19517, -1.25262, -1.17910, -1.21470, -1.29897, -1.30336, -1.39891, -1.41090, -1.40719, -1.35073, -1.24493, -1.20604, -1.23429, -1.34764, -1.44752, -1.47264, -1.46869, -1.35555, -1.43825, -1.59594, -1.73034, -1.76782, -1.69732, -1.56337, -1.51801, -1.52798, -1.64816, -1.67772, -1.60191, -1.66220, -1.69598, -1.60343, -1.65487, -1.66219, -1.52989, -1.56841, -1.70045, -1.62542, -1.56093, -1.48078, -1.49309, -1.49872, -1.34282, -1.25166, -1.21713, -1.12326, -0.92870, -0.80347, -0.82388, -0.78567, -0.74937, -0.74444, -0.64913, -0.46528, -0.23681, 0.03600, 0.28835, 0.53577, 0.79066, 0.96793, 1.16223, 1.20280, 1.30501, 1.64315, 1.84965, 1.97181, 2.26274, 2.41828, 2.47762, 2.62533, 2.62431, 2.57169, 2.51640, 2.39736, 2.37904, 2.44544, 2.59461, 2.75641, 2.79893, 2.77799, 2.64606, 2.56783, 2.55739, 2.48230, 2.45166, 2.36827, 2.23794, 2.09625, 1.89552, 1.61306, 1.34274, 1.04051, 0.96449, 0.86220, 0.81697, 0.90725, 0.87744, 0.83317, 1.02540, 1.07369, 0.88523, 0.90839, 1.04234, 1.09220, 1.15696, 1.22279, 1.38422, 1.36101, 1.21122, 1.03053, 0.94450, 0.90177, 0.84152, 0.80900, 0.79267, 0.65659, 0.53943, 0.36171, 0.21933, 0.02297, -0.19715, -0.47376, -0.64443, -0.82488, -0.82133, -0.86622, -0.94595, -0.91327, -0.97888, -1.19415, -1.29559, -1.52360, -1.92453, -2.24075, -2.43665, -2.53957, -2.46831, -2.47234, -2.54999, -2.74545, -2.99868, -3.23415, -3.29301, -3.30363, -3.34518, -3.45396, -3.54562, -3.72547, -3.81466, -3.88879, -3.89175, -3.90729, -3.83960, -3.82809, -3.72394, -3.76404, -3.64479, -3.49388, -3.38505, -3.24214, -3.19439, -3.24387, -3.05968, -2.97477, -3.08078, -3.01510, -2.83519, -2.79515, -2.71705, -2.63841, -2.43418, -2.25491, -2.12223, -2.08293, -2.04811, -2.00538, -1.97625, -1.92107, -1.74035, -1.70359, -1.67307, -1.66661, -1.56885, -1.49119, -1.42286, -1.49838, -1.51311, -1.63963, -1.56137, -1.41362, +-0.64870, -0.68478, -0.72577, -0.68826, -0.67918, -0.76867, -0.86635, -0.92414, -0.99687, -0.99949, -0.97382, -0.94693, -0.86649, -0.67295, -0.43536, -0.47121, -0.52340, -0.35976, -0.25391, -0.15730, -0.03167, 0.04031, 0.23281, 0.62441, 0.85117, 1.10522, 1.35303, 1.52759, 1.65495, 1.62104, 1.59684, 1.49972, 1.33995, 1.23490, 1.21000, 1.30548, 1.40781, 1.37663, 1.26989, 1.21478, 1.17374, 1.20089, 1.30207, 1.31529, 1.31966, 1.28360, 1.33780, 1.21280, 1.06447, 0.95977, 0.77593, 0.63053, 0.55325, 0.42792, 0.35655, 0.39326, 0.34136, 0.22692, 0.19428, 0.17717, 0.29216, 0.31902, 0.39151, 0.37885, 0.34268, 0.31754, 0.28451, 0.28333, 0.43598, 0.59583, 0.77218, 0.92372, 1.07054, 1.19275, 1.32265, 1.20857, 1.09019, 0.99776, 1.01610, 0.84946, 0.61814, 0.56691, 0.60256, 0.70201, 0.93644, 1.04258, 1.13734, 1.34131, 1.45694, 1.44468, 1.44231, 1.25096, 1.08762, 0.85178, 0.73965, 0.66299, 0.47814, 0.20163, -0.17030, -0.52430, -0.72498, -0.88133, -0.98434, -1.10234, -1.20365, -1.38571, -1.41063, -1.50339, -1.54878, -1.76769, -1.92610, -2.15786, -2.40140, -2.37961, -2.23403, -2.13169, -1.95307, -1.94206, -1.92902, -1.75261, -1.55693, -1.50539, -1.39212, -1.42306, -1.40529, -1.43739, -1.40274, -1.31808, -1.16223, -0.94653, -0.78827, -0.78623, -0.74042, -0.76153, -0.85740, -1.07081, -1.17796, -1.27048, -1.21041, -1.26996, -1.27251, -1.34176, -1.32934, -1.46558, -1.76435, -2.01914, -2.18830, -2.36696, -2.38234, -2.43925, -2.55959, -2.55895, -2.47741, -2.47814, -2.32672, -2.30487, -2.27126, -2.34478, -2.41119, -2.34986, -2.20420, -1.95778, -1.74258, -1.68334, -1.62786, -1.69038, -1.77355, -1.85998, -1.86640, -2.08125, -2.20601, -2.37815, -2.47526, -2.54558, -2.52021, -2.55182, -2.68158, -2.73049, -2.58362, -2.45284, -2.22812, -2.10564, -2.07902, -2.00795, -1.87372, -1.83744, -1.68413, -1.60647, -1.42272, -1.25595, -1.18378, -1.19884, -1.28154, -1.33156, -1.41503, -1.60561, -1.58783, -1.45019, -1.32159, -1.24610, -1.09063, -1.04401, -0.94735, -0.94995, -0.92771, -0.95487, -0.94533, -0.99520, -1.17288, -1.24766, -1.15775, -1.20628, -1.24218, -1.28723, -1.37648, -1.43554, -1.42681, -1.59170, -1.66901, -1.69231, -1.59065, -1.40752, -1.32891, -1.30884, -1.39660, -1.51596, -1.58221, -1.66486, -1.64357, -1.71427, -1.84155, -1.96691, -1.96908, -1.94144, -1.85952, -1.81638, -1.79765, -1.84164, -1.82665, -1.75887, -1.82130, -1.87658, -1.78774, -1.82081, -1.85463, -1.83624, -1.92314, -1.98569, -1.86266, -1.84032, -1.79968, -1.80162, -1.76042, -1.59555, -1.49818, -1.38306, -1.21368, -1.00388, -0.85303, -0.86683, -0.85633, -0.77671, -0.72218, -0.63458, -0.44897, -0.25688, -0.03376, 0.22374, 0.47419, 0.76689, 0.99840, 1.18589, 1.19749, 1.27790, 1.60812, 1.88412, 2.06838, 2.23915, 2.26505, 2.34505, 2.57423, 2.66760, 2.65551, 2.59495, 2.50246, 2.51963, 2.57193, 2.74520, 2.91594, 2.91106, 2.87706, 2.73211, 2.62017, 2.63694, 2.58654, 2.52376, 2.45742, 2.30628, 2.08082, 1.88777, 1.61537, 1.36715, 1.11134, 0.94973, 0.70997, 0.60552, 0.68193, 0.74798, 0.81029, 0.94258, 0.89111, 0.76421, 0.86699, 1.01547, 1.05255, 1.10162, 1.14857, 1.30984, 1.27713, 1.17552, 1.05473, 0.94571, 0.89270, 0.82479, 0.73744, 0.73599, 0.64917, 0.50652, 0.32504, 0.16670, -0.09848, -0.30351, -0.56280, -0.68620, -0.76909, -0.74312, -0.84489, -1.00715, -1.05305, -1.08842, -1.16762, -1.19948, -1.48819, -1.86496, -2.10711, -2.26583, -2.40003, -2.37660, -2.47488, -2.61070, -2.86782, -3.13089, -3.31090, -3.38893, -3.42099, -3.44051, -3.53428, -3.55702, -3.63289, -3.67846, -3.71243, -3.69826, -3.79472, -3.81027, -3.88634, -3.78941, -3.72499, -3.52407, -3.37877, -3.29440, -3.17798, -3.06414, -2.99819, -2.83478, -2.89836, -3.05097, -2.99525, -2.83194, -2.79850, -2.69316, -2.61361, -2.35980, -2.13581, -1.93209, -1.77302, -1.70502, -1.67275, -1.65894, -1.67651, -1.52880, -1.44617, -1.42095, -1.41872, -1.30422, -1.29858, -1.25833, -1.39553, -1.51457, -1.65968, -1.60558, -1.48636, +-0.89337, -0.80935, -0.77246, -0.85280, -0.93458, -0.92982, -0.99452, -1.03155, -1.05482, -1.10294, -1.11190, -1.20758, -1.14994, -0.87093, -0.61685, -0.57239, -0.51216, -0.38247, -0.34888, -0.21351, -0.09131, 0.05592, 0.29684, 0.68719, 0.98558, 1.20341, 1.44302, 1.67869, 1.78311, 1.77558, 1.77825, 1.69116, 1.60713, 1.59162, 1.58439, 1.51674, 1.49476, 1.52178, 1.43276, 1.34053, 1.30753, 1.36588, 1.50733, 1.40050, 1.28687, 1.34690, 1.39453, 1.19337, 1.04724, 0.98644, 0.82914, 0.73727, 0.65864, 0.57100, 0.47790, 0.35368, 0.26256, 0.09083, 0.01853, 0.08173, 0.25824, 0.34538, 0.42105, 0.28268, 0.20317, 0.21982, 0.24510, 0.19211, 0.23579, 0.37995, 0.49832, 0.57559, 0.74588, 0.86849, 1.05200, 0.98845, 0.80171, 0.73575, 0.73878, 0.59911, 0.46387, 0.46746, 0.50728, 0.68731, 0.90384, 1.02859, 1.19288, 1.29513, 1.41216, 1.36838, 1.35375, 1.29287, 1.18745, 0.99190, 0.86676, 0.66953, 0.47237, 0.22620, -0.10492, -0.54198, -0.87464, -0.94782, -0.97912, -1.14889, -1.22784, -1.31821, -1.28470, -1.42689, -1.63360, -1.78325, -1.87763, -2.09630, -2.27280, -2.20296, -2.13374, -2.04493, -1.89493, -1.84308, -1.71562, -1.58597, -1.31518, -1.26349, -1.24549, -1.30414, -1.33173, -1.34918, -1.23836, -1.13759, -0.91854, -0.66088, -0.45219, -0.44505, -0.45180, -0.42155, -0.40648, -0.57295, -0.71224, -0.89390, -0.87247, -0.89553, -0.99648, -1.05056, -0.98689, -1.09588, -1.39113, -1.61565, -1.86169, -2.08441, -2.16871, -2.29285, -2.33265, -2.40088, -2.33537, -2.36759, -2.35449, -2.34706, -2.29096, -2.34604, -2.34542, -2.33813, -2.19986, -1.88225, -1.60380, -1.57914, -1.63285, -1.62607, -1.61658, -1.77138, -1.86161, -2.07299, -2.15924, -2.26691, -2.43806, -2.50738, -2.47318, -2.55251, -2.69848, -2.65828, -2.53616, -2.37479, -2.08287, -1.97436, -1.87136, -1.92425, -1.86483, -1.80681, -1.67575, -1.49364, -1.23686, -1.11396, -1.04004, -1.09804, -1.17365, -1.20386, -1.20272, -1.32661, -1.47912, -1.46756, -1.30346, -1.22910, -1.12329, -1.11965, -0.98362, -0.86748, -0.93213, -0.98391, -0.92620, -1.00243, -1.22296, -1.26533, -1.20763, -1.26325, -1.28718, -1.40557, -1.48045, -1.62328, -1.67487, -1.80675, -1.91834, -1.93363, -1.76592, -1.54289, -1.41522, -1.47438, -1.61232, -1.68110, -1.71681, -1.82374, -1.96393, -2.04987, -2.01442, -2.05629, -2.03930, -2.03704, -2.00176, -1.96069, -2.07514, -2.18099, -2.12538, -2.03041, -2.03751, -1.99847, -1.91527, -2.00966, -2.04033, -2.04458, -2.01945, -2.03574, -2.00612, -2.04829, -2.12424, -2.13916, -1.99428, -1.82007, -1.60594, -1.41899, -1.32555, -1.16063, -0.96260, -0.88868, -0.99626, -1.03250, -0.86460, -0.72283, -0.60254, -0.43791, -0.20428, 0.12393, 0.31805, 0.55800, 0.91283, 1.17164, 1.21873, 1.35371, 1.63941, 1.85601, 2.06670, 2.20832, 2.30536, 2.40112, 2.55714, 2.72709, 2.69996, 2.61319, 2.64083, 2.72656, 2.79748, 2.90047, 2.93344, 2.95898, 3.02620, 2.99721, 2.82842, 2.70575, 2.67388, 2.56566, 2.38437, 2.18379, 1.93900, 1.84812, 1.60578, 1.27152, 1.04812, 0.81974, 0.52078, 0.45411, 0.57755, 0.65615, 0.72993, 0.76184, 0.70780, 0.65566, 0.70977, 0.90864, 1.01077, 1.09343, 1.17057, 1.27134, 1.25429, 1.19227, 0.95037, 0.79474, 0.82320, 0.85563, 0.67678, 0.52618, 0.48217, 0.36677, 0.12726, -0.03535, -0.23135, -0.31292, -0.51916, -0.74153, -0.81070, -0.79423, -0.91917, -1.05094, -1.05070, -1.14019, -1.18011, -1.19016, -1.44544, -1.75663, -2.04301, -2.12801, -2.30040, -2.39783, -2.49188, -2.60165, -2.83423, -3.05663, -3.34058, -3.48777, -3.50710, -3.48370, -3.61344, -3.72347, -3.71297, -3.59987, -3.59103, -3.59551, -3.72457, -3.76842, -3.85139, -3.85838, -3.70770, -3.41251, -3.27444, -3.21290, -3.06206, -2.96628, -2.86557, -2.72945, -2.75676, -2.82169, -2.95222, -2.87485, -2.83770, -2.74123, -2.61729, -2.32327, -1.99984, -1.68205, -1.59827, -1.55434, -1.47669, -1.40645, -1.47154, -1.48668, -1.37600, -1.24027, -1.23703, -1.17764, -1.23753, -1.19906, -1.30270, -1.54128, -1.68667, -1.64010, -1.53893, +-1.14353, -1.10886, -1.00460, -1.06136, -1.09371, -0.99847, -1.04969, -1.09148, -1.12977, -1.24869, -1.33496, -1.52562, -1.49813, -1.19659, -0.86000, -0.68523, -0.62852, -0.57354, -0.54157, -0.33807, -0.19089, -0.02751, 0.30993, 0.77699, 1.11717, 1.33009, 1.54875, 1.77314, 1.82707, 1.77509, 1.84321, 1.87478, 1.80339, 1.76470, 1.80320, 1.71172, 1.61522, 1.64645, 1.60118, 1.51942, 1.49114, 1.52267, 1.59159, 1.38934, 1.20493, 1.27658, 1.34839, 1.15803, 0.96461, 0.91788, 0.85434, 0.81802, 0.73764, 0.61980, 0.53613, 0.40759, 0.28568, 0.09685, -0.02354, -0.00743, 0.13489, 0.16538, 0.26188, 0.18224, 0.14860, 0.16001, 0.24115, 0.22720, 0.18284, 0.22412, 0.25421, 0.25382, 0.40792, 0.52366, 0.71678, 0.70032, 0.50428, 0.42696, 0.46773, 0.45808, 0.36341, 0.30994, 0.36324, 0.58605, 0.76412, 0.84868, 1.09414, 1.28551, 1.40240, 1.34286, 1.30675, 1.25218, 1.17136, 0.96644, 0.87025, 0.72188, 0.50648, 0.19186, -0.06571, -0.44260, -0.81936, -0.93368, -1.00642, -1.21317, -1.27658, -1.29693, -1.24926, -1.44081, -1.70509, -1.78752, -1.78816, -1.90558, -2.06519, -2.08720, -2.05763, -1.94950, -1.80076, -1.73290, -1.52558, -1.30315, -1.02845, -1.00738, -1.06517, -1.18907, -1.16018, -1.14946, -0.98722, -0.78419, -0.57316, -0.46500, -0.28692, -0.24244, -0.25579, -0.22396, -0.15584, -0.27096, -0.44091, -0.68636, -0.70474, -0.70523, -0.82392, -0.89343, -0.80228, -0.81030, -1.10659, -1.41675, -1.66545, -1.85422, -1.98096, -2.18689, -2.20830, -2.18910, -2.12938, -2.17611, -2.24040, -2.32289, -2.27371, -2.31647, -2.23072, -2.13265, -2.00113, -1.85567, -1.67549, -1.65002, -1.73486, -1.71131, -1.68249, -1.87470, -1.98401, -2.11136, -2.13297, -2.20200, -2.36897, -2.44667, -2.41137, -2.42884, -2.56752, -2.58999, -2.50273, -2.32683, -2.04836, -2.00364, -1.89462, -1.85271, -1.70014, -1.56417, -1.43171, -1.27329, -1.05136, -1.02696, -0.99675, -1.00313, -1.02514, -1.14328, -1.13639, -1.16193, -1.37163, -1.46915, -1.33810, -1.27061, -1.20916, -1.24150, -1.09153, -0.92716, -1.01056, -1.06706, -0.95715, -0.94427, -1.17452, -1.33969, -1.35654, -1.39823, -1.41212, -1.56991, -1.65954, -1.74913, -1.78110, -1.84426, -1.91446, -1.96668, -1.82974, -1.69327, -1.63358, -1.67978, -1.79082, -1.92940, -2.03448, -2.12290, -2.24987, -2.26438, -2.12698, -2.09744, -2.04904, -2.06348, -2.06894, -2.07237, -2.25919, -2.40843, -2.36910, -2.22944, -2.20930, -2.23101, -2.18413, -2.20001, -2.08831, -2.04673, -1.98970, -1.93173, -1.94488, -2.06356, -2.22249, -2.30572, -2.16036, -2.00946, -1.76247, -1.48294, -1.39253, -1.37375, -1.27259, -1.12959, -1.23758, -1.34270, -1.17309, -1.03054, -0.95708, -0.79594, -0.50341, -0.11600, 0.07136, 0.30201, 0.72861, 1.12076, 1.28463, 1.41427, 1.63209, 1.85030, 2.10889, 2.28249, 2.41857, 2.56638, 2.72486, 2.85526, 2.78501, 2.65725, 2.69283, 2.79000, 2.80080, 2.87022, 2.92271, 2.95229, 2.97539, 3.03376, 2.92860, 2.74845, 2.68097, 2.52558, 2.28267, 2.05713, 1.81497, 1.74903, 1.49695, 1.11511, 0.88428, 0.72233, 0.55913, 0.48222, 0.52729, 0.59766, 0.64627, 0.58788, 0.46549, 0.46080, 0.59452, 0.82906, 1.01008, 1.11595, 1.12605, 1.16175, 1.11353, 1.11617, 0.90774, 0.67872, 0.60405, 0.66793, 0.50044, 0.29356, 0.25888, 0.15388, -0.11099, -0.26692, -0.37679, -0.35995, -0.50061, -0.72047, -0.79641, -0.77328, -0.83191, -0.95125, -1.00336, -1.10719, -1.13826, -1.21238, -1.53087, -1.80923, -2.00744, -2.06518, -2.26648, -2.45002, -2.58668, -2.64705, -2.90465, -3.09202, -3.32562, -3.52845, -3.67429, -3.64102, -3.69629, -3.79126, -3.74394, -3.58016, -3.58138, -3.62424, -3.75606, -3.74491, -3.74198, -3.76154, -3.60069, -3.27818, -3.09537, -3.07828, -3.04160, -2.96165, -2.81544, -2.69787, -2.72908, -2.76395, -2.90206, -2.88505, -2.82314, -2.70496, -2.63010, -2.35017, -2.04741, -1.70318, -1.58228, -1.53466, -1.52660, -1.44380, -1.48116, -1.55901, -1.45159, -1.26635, -1.23563, -1.17758, -1.23840, -1.19114, -1.25348, -1.46546, -1.58709, -1.54722, -1.41576, +-1.19399, -1.22758, -1.22870, -1.24149, -1.13651, -1.09057, -1.10649, -1.20843, -1.37340, -1.50863, -1.66209, -1.85046, -1.72931, -1.49672, -1.19169, -0.95247, -0.83765, -0.76977, -0.70975, -0.39851, -0.15440, 0.00841, 0.35841, 0.81219, 1.13262, 1.38193, 1.63966, 1.79486, 1.80411, 1.84503, 1.87799, 1.94450, 1.94475, 1.92918, 1.94389, 1.86152, 1.81612, 1.72470, 1.69499, 1.61823, 1.50048, 1.53129, 1.51829, 1.30763, 1.20390, 1.18966, 1.17070, 1.04825, 0.91839, 0.90424, 0.82800, 0.81947, 0.75383, 0.59344, 0.47975, 0.35858, 0.24460, 0.12682, 0.01872, -0.07632, -0.07941, 0.00682, 0.08266, 0.04995, 0.16040, 0.22521, 0.26270, 0.20030, 0.20614, 0.11830, 0.11101, 0.10795, 0.13048, 0.24285, 0.38259, 0.34722, 0.24602, 0.18024, 0.19839, 0.33883, 0.35238, 0.34685, 0.34591, 0.55318, 0.71190, 0.76663, 1.01485, 1.26416, 1.34213, 1.29238, 1.23695, 1.11189, 0.95018, 0.90231, 0.88535, 0.78725, 0.63856, 0.31829, 0.03408, -0.38936, -0.64952, -0.84275, -0.97104, -1.12163, -1.28399, -1.29535, -1.27387, -1.47919, -1.66338, -1.72844, -1.81919, -1.88374, -2.01359, -2.00882, -2.02442, -1.85721, -1.60047, -1.44306, -1.23568, -0.99642, -0.83596, -0.84873, -0.91361, -1.04096, -1.02443, -0.84728, -0.64631, -0.46286, -0.23440, -0.17594, -0.06332, -0.13921, -0.06479, -0.05988, -0.03986, -0.10346, -0.40393, -0.66484, -0.67350, -0.65048, -0.66347, -0.67963, -0.70270, -0.68542, -0.94004, -1.17975, -1.43023, -1.56607, -1.68059, -1.90759, -2.02627, -2.02263, -2.05263, -2.09806, -2.13197, -2.22136, -2.28169, -2.22566, -2.07255, -1.98458, -1.82599, -1.76546, -1.70165, -1.83558, -1.86706, -1.86014, -1.89621, -1.98660, -2.15574, -2.26689, -2.24875, -2.32308, -2.40020, -2.37848, -2.41966, -2.37733, -2.40283, -2.32167, -2.28524, -2.15924, -1.95283, -1.93525, -1.88092, -1.77447, -1.58363, -1.40713, -1.26423, -1.12151, -1.04026, -0.97942, -0.88145, -0.89402, -0.83528, -0.92132, -0.93844, -1.11052, -1.29141, -1.37920, -1.33767, -1.19253, -1.21640, -1.31754, -1.16778, -1.04237, -1.05867, -0.99228, -0.92662, -0.89180, -1.09994, -1.27190, -1.40966, -1.52088, -1.53876, -1.63279, -1.71232, -1.76537, -1.83095, -1.89896, -1.94544, -1.98178, -1.96178, -1.85511, -1.74614, -1.82238, -1.90148, -2.03666, -2.16840, -2.34937, -2.40895, -2.32483, -2.24690, -2.12974, -2.10478, -2.18939, -2.18769, -2.23023, -2.34517, -2.37431, -2.44579, -2.40815, -2.41656, -2.40651, -2.34953, -2.28997, -2.02664, -1.88425, -1.85091, -1.81320, -1.89375, -2.06538, -2.21620, -2.28086, -2.21783, -2.08659, -1.76477, -1.56997, -1.51933, -1.52887, -1.48276, -1.42943, -1.52687, -1.56579, -1.52640, -1.38244, -1.33135, -1.23051, -0.84056, -0.42427, -0.17664, 0.17758, 0.55737, 0.92778, 1.20188, 1.46179, 1.75326, 1.97206, 2.27328, 2.48982, 2.59163, 2.70527, 2.81380, 2.84776, 2.77568, 2.68032, 2.64201, 2.67125, 2.76831, 2.78176, 2.81228, 2.85384, 2.82428, 2.80620, 2.70305, 2.63755, 2.49722, 2.38884, 2.22755, 1.94457, 1.74234, 1.61878, 1.32974, 1.03646, 0.77888, 0.59251, 0.55952, 0.52791, 0.55515, 0.54185, 0.57846, 0.52302, 0.36728, 0.33451, 0.48368, 0.68378, 0.89257, 1.00022, 0.94244, 0.91745, 1.03373, 1.08488, 0.90123, 0.70749, 0.56408, 0.53218, 0.30009, 0.20190, 0.12793, 0.03062, -0.17409, -0.41906, -0.48139, -0.44314, -0.53070, -0.57524, -0.59667, -0.67713, -0.71221, -0.82685, -0.87044, -1.02695, -1.05279, -1.15375, -1.50308, -1.81781, -2.01583, -2.15504, -2.35078, -2.53085, -2.70857, -2.85850, -3.01586, -3.19538, -3.42887, -3.56931, -3.71905, -3.67004, -3.70528, -3.61753, -3.57407, -3.47673, -3.47243, -3.64469, -3.76092, -3.69087, -3.62810, -3.56097, -3.39424, -3.21418, -3.01186, -2.95974, -2.87610, -2.83529, -2.66169, -2.53833, -2.59852, -2.72804, -2.87377, -2.91069, -2.79155, -2.61311, -2.54468, -2.38943, -2.05237, -1.73342, -1.66144, -1.55450, -1.51655, -1.44322, -1.59159, -1.60818, -1.54194, -1.41845, -1.27787, -1.23276, -1.22790, -1.14726, -1.20972, -1.32767, -1.37815, -1.45367, -1.33893, +-1.27252, -1.31839, -1.26900, -1.20139, -1.08091, -1.08955, -1.14892, -1.34339, -1.58969, -1.74154, -1.89513, -2.02002, -1.87787, -1.71284, -1.46258, -1.27448, -1.16482, -1.05494, -0.94437, -0.58407, -0.28089, -0.07653, 0.26142, 0.67086, 0.98168, 1.25669, 1.59895, 1.82399, 1.76589, 1.77941, 1.82072, 1.89192, 1.93074, 1.93479, 2.00163, 2.01220, 1.96988, 1.80393, 1.69804, 1.55762, 1.43929, 1.51101, 1.51545, 1.36485, 1.27629, 1.14088, 1.04262, 0.95492, 0.85619, 0.82768, 0.72429, 0.70812, 0.68601, 0.56047, 0.42062, 0.26261, 0.14406, 0.06344, 0.02165, -0.00721, -0.14331, -0.14790, -0.07499, -0.08605, 0.09929, 0.22342, 0.31678, 0.31343, 0.26831, 0.10636, 0.07648, 0.06902, 0.07880, 0.18877, 0.24211, 0.12594, 0.02640, -0.03111, 0.03343, 0.23891, 0.29941, 0.30855, 0.26538, 0.40202, 0.53437, 0.59077, 0.82421, 1.06420, 1.13373, 1.10328, 1.09944, 1.08052, 0.85730, 0.74791, 0.76624, 0.70105, 0.61572, 0.33610, 0.06172, -0.25956, -0.45838, -0.66402, -0.78730, -0.92946, -1.10784, -1.13705, -1.17783, -1.37275, -1.54707, -1.68584, -1.82224, -1.87681, -1.96527, -1.94901, -1.99127, -1.83776, -1.53291, -1.29149, -1.06081, -0.85044, -0.76085, -0.78234, -0.79382, -0.73749, -0.69875, -0.55916, -0.34629, -0.23961, -0.08492, -0.05451, 0.04525, 0.06266, 0.16929, 0.12204, 0.05520, -0.12029, -0.46115, -0.63102, -0.59836, -0.55093, -0.52881, -0.56803, -0.63980, -0.64256, -0.86834, -1.08587, -1.32857, -1.45495, -1.54785, -1.73700, -1.87001, -1.92453, -2.03661, -2.13379, -2.16058, -2.10086, -2.16101, -2.18781, -2.07335, -2.03343, -1.88847, -1.84527, -1.80588, -1.87476, -1.89080, -1.96713, -2.05737, -2.12924, -2.28616, -2.31856, -2.25351, -2.27911, -2.25822, -2.21052, -2.27203, -2.22180, -2.19914, -2.08797, -2.06879, -2.00959, -1.87834, -1.85572, -1.79842, -1.68591, -1.50344, -1.33296, -1.18954, -0.97830, -0.95523, -0.97625, -0.85199, -0.81518, -0.70021, -0.75046, -0.81554, -1.00107, -1.13464, -1.19685, -1.17965, -1.08296, -1.16683, -1.23970, -1.09576, -0.99397, -0.97107, -0.90355, -0.86448, -0.83456, -1.04317, -1.24359, -1.44509, -1.63589, -1.69724, -1.76904, -1.81874, -1.86148, -1.94383, -2.04499, -2.12426, -2.05580, -2.00135, -1.96793, -1.85267, -1.90948, -1.98756, -2.14586, -2.28208, -2.37386, -2.34397, -2.24571, -2.19788, -2.08497, -2.05557, -2.10477, -2.10660, -2.19116, -2.28695, -2.31644, -2.45395, -2.49794, -2.56543, -2.55825, -2.47786, -2.36595, -2.03913, -1.82456, -1.76611, -1.79497, -1.95748, -2.13542, -2.22850, -2.12925, -1.98631, -1.96095, -1.78427, -1.74317, -1.76764, -1.78714, -1.77311, -1.72147, -1.75191, -1.76958, -1.80084, -1.71165, -1.68372, -1.54119, -1.06866, -0.61472, -0.30789, 0.09496, 0.45865, 0.82134, 1.11779, 1.40468, 1.72886, 1.96539, 2.27845, 2.49534, 2.55467, 2.61458, 2.66055, 2.65536, 2.61321, 2.63148, 2.66363, 2.55152, 2.55678, 2.53427, 2.51037, 2.52704, 2.47747, 2.49505, 2.53716, 2.54633, 2.38855, 2.28221, 2.14587, 1.92715, 1.81604, 1.66914, 1.36118, 1.09196, 0.80727, 0.62868, 0.61992, 0.58680, 0.57122, 0.45752, 0.41994, 0.37587, 0.26363, 0.25348, 0.36906, 0.50804, 0.63748, 0.73460, 0.80638, 0.77964, 0.88010, 0.94503, 0.77174, 0.61888, 0.45769, 0.40451, 0.26367, 0.20922, 0.11777, 0.01575, -0.18667, -0.38610, -0.34616, -0.29431, -0.36344, -0.37716, -0.42757, -0.54909, -0.61919, -0.79997, -0.92125, -1.11133, -1.15854, -1.24786, -1.55106, -1.85636, -2.12619, -2.37743, -2.59509, -2.73009, -2.78200, -2.98147, -3.20878, -3.36685, -3.56142, -3.63736, -3.75633, -3.68037, -3.56779, -3.36831, -3.30720, -3.26896, -3.34471, -3.53521, -3.57138, -3.46274, -3.38036, -3.30663, -3.22934, -3.17886, -3.03879, -2.96853, -2.84438, -2.76662, -2.60598, -2.51384, -2.64069, -2.84247, -2.98988, -3.01055, -2.86563, -2.65787, -2.44377, -2.33216, -2.15419, -1.92655, -1.91919, -1.80182, -1.72146, -1.62465, -1.67498, -1.61353, -1.54466, -1.45090, -1.33307, -1.27820, -1.15528, -1.02280, -1.06333, -1.17952, -1.29872, -1.42574, -1.34277, +-1.23608, -1.34675, -1.28495, -1.13769, -1.13754, -1.27202, -1.30363, -1.49271, -1.81950, -2.06392, -2.12843, -2.12415, -2.03481, -1.89095, -1.68043, -1.51902, -1.36063, -1.19858, -1.02171, -0.68673, -0.41248, -0.16708, 0.25858, 0.65920, 0.92221, 1.22071, 1.53474, 1.76873, 1.78359, 1.75570, 1.82207, 1.99253, 2.02828, 1.88613, 1.83913, 1.92947, 1.88016, 1.67247, 1.53812, 1.40122, 1.26588, 1.26542, 1.36123, 1.37513, 1.27545, 1.12840, 1.03319, 1.02000, 0.96708, 0.86457, 0.74346, 0.73273, 0.76103, 0.67709, 0.57709, 0.38946, 0.13301, 0.02303, -0.00120, 0.01629, -0.07927, -0.13880, -0.09462, 0.01291, 0.16193, 0.17599, 0.23428, 0.31127, 0.19902, -0.00994, 0.01073, 0.12375, 0.12113, 0.07652, 0.01414, -0.10655, -0.22078, -0.17614, 0.00135, 0.21845, 0.29235, 0.26503, 0.21625, 0.31333, 0.43306, 0.49284, 0.72846, 0.96843, 0.98376, 0.98465, 1.03877, 1.06293, 0.87783, 0.66301, 0.56129, 0.62485, 0.62924, 0.33599, -0.03632, -0.26313, -0.44074, -0.66614, -0.71380, -0.71392, -0.85121, -0.99769, -1.12064, -1.20828, -1.43680, -1.62607, -1.72698, -1.73833, -1.73628, -1.77099, -1.85201, -1.76141, -1.52134, -1.27262, -0.96875, -0.68588, -0.65467, -0.64611, -0.57684, -0.42856, -0.35913, -0.26070, -0.11735, 0.03207, 0.14273, 0.10615, 0.10766, 0.23327, 0.31991, 0.15338, -0.01455, -0.19112, -0.44988, -0.56737, -0.53552, -0.43420, -0.47478, -0.52354, -0.53446, -0.51424, -0.66330, -0.92341, -1.20862, -1.36007, -1.42471, -1.55120, -1.61541, -1.62625, -1.86381, -2.11010, -2.20584, -2.10649, -2.07261, -2.09448, -2.14555, -2.08926, -1.93859, -1.93866, -1.98150, -1.95409, -1.92833, -2.09781, -2.21491, -2.16489, -2.24351, -2.27508, -2.22423, -2.09349, -2.00084, -1.96373, -1.97647, -1.94204, -1.92317, -1.86560, -1.84733, -1.80459, -1.69652, -1.63994, -1.53244, -1.34725, -1.30357, -1.24060, -1.09053, -0.90289, -0.86806, -0.83862, -0.76102, -0.60295, -0.42349, -0.51628, -0.77955, -0.98783, -1.00179, -1.02410, -1.02170, -0.95343, -1.05174, -1.13011, -1.06035, -0.89185, -0.84461, -0.84299, -0.79801, -0.77544, -0.93574, -1.14915, -1.37911, -1.62131, -1.74376, -1.89144, -1.96404, -1.89212, -1.96984, -2.14415, -2.27070, -2.20090, -2.08933, -1.98518, -1.90006, -1.86543, -1.83444, -2.01422, -2.25549, -2.30507, -2.19087, -2.14168, -2.13027, -1.96457, -1.86538, -1.93273, -2.06250, -2.18389, -2.33693, -2.45945, -2.54839, -2.58622, -2.63117, -2.60318, -2.51792, -2.39175, -2.11641, -1.89675, -1.78527, -1.74749, -1.93284, -2.12440, -2.11955, -1.91626, -1.73030, -1.72498, -1.79230, -1.87913, -1.81633, -1.81519, -1.95673, -2.04646, -2.02163, -2.03557, -2.09630, -1.97093, -1.85663, -1.68951, -1.30003, -0.80808, -0.40638, -0.00522, 0.43590, 0.82093, 1.10921, 1.31750, 1.55390, 1.82428, 2.16611, 2.36325, 2.36897, 2.46617, 2.48852, 2.41504, 2.43236, 2.52996, 2.62530, 2.51007, 2.40085, 2.32889, 2.37287, 2.36006, 2.20443, 2.17983, 2.37624, 2.40440, 2.21408, 2.10208, 2.01078, 1.85611, 1.75112, 1.63324, 1.41290, 1.13162, 0.90649, 0.75879, 0.70224, 0.66776, 0.58655, 0.42298, 0.34308, 0.31841, 0.27616, 0.37055, 0.46212, 0.43664, 0.42750, 0.50327, 0.71002, 0.82923, 0.86973, 0.80772, 0.74601, 0.65834, 0.43136, 0.28800, 0.26677, 0.21416, 0.05697, -0.02887, -0.11809, -0.21451, -0.17215, -0.14467, -0.17612, -0.34506, -0.45058, -0.52695, -0.58974, -0.80705, -1.07863, -1.28909, -1.35586, -1.42280, -1.64410, -1.83695, -2.06778, -2.45762, -2.70838, -2.80813, -2.80935, -2.95521, -3.20752, -3.41270, -3.44797, -3.46412, -3.64240, -3.72367, -3.55513, -3.29971, -3.22615, -3.18729, -3.19701, -3.32054, -3.36092, -3.31276, -3.22213, -3.22876, -3.21104, -3.18627, -3.07458, -2.94450, -2.81543, -2.68850, -2.57064, -2.55151, -2.76631, -2.92163, -2.89664, -2.90370, -2.81701, -2.67025, -2.41879, -2.24905, -2.13849, -2.08000, -2.02525, -1.89796, -1.87780, -1.88561, -1.82576, -1.64880, -1.56377, -1.47930, -1.33434, -1.31196, -1.20821, -1.07080, -0.98712, -1.17076, -1.39862, -1.49142, -1.41730, +-1.25541, -1.29977, -1.28818, -1.18605, -1.25124, -1.45426, -1.55772, -1.76414, -1.97727, -2.14965, -2.25676, -2.28547, -2.15284, -1.96837, -1.86118, -1.72232, -1.35381, -1.04661, -0.84187, -0.55128, -0.32277, -0.06869, 0.30713, 0.64838, 0.98644, 1.36373, 1.55610, 1.64017, 1.72770, 1.76422, 1.78387, 1.89813, 1.97812, 1.86129, 1.70975, 1.75507, 1.74494, 1.59046, 1.40801, 1.20422, 1.10927, 1.11937, 1.16168, 1.17767, 1.22206, 1.26050, 1.15973, 1.10188, 1.15219, 1.13219, 1.00800, 1.00726, 1.02994, 0.91204, 0.73593, 0.44320, 0.18570, 0.14547, 0.06414, -0.05681, -0.12105, -0.11367, -0.09369, -0.01562, 0.10399, 0.14659, 0.16295, 0.21874, 0.16457, 0.02190, 0.01210, 0.04081, 0.00536, -0.04904, -0.20680, -0.37621, -0.34576, -0.10457, 0.07214, 0.16192, 0.27983, 0.37691, 0.34056, 0.43397, 0.55253, 0.60663, 0.76288, 0.86772, 0.90578, 1.01829, 1.02369, 0.86763, 0.70133, 0.53819, 0.38774, 0.45216, 0.54032, 0.40995, 0.03259, -0.23308, -0.39426, -0.60200, -0.67173, -0.70238, -0.75945, -0.78584, -0.92462, -1.08657, -1.28854, -1.35761, -1.47008, -1.58242, -1.55267, -1.52126, -1.64017, -1.59574, -1.40970, -1.17216, -0.87349, -0.68057, -0.63666, -0.47386, -0.35583, -0.33051, -0.29634, -0.13708, 0.00184, 0.14712, 0.30316, 0.38153, 0.33465, 0.34416, 0.33968, 0.15348, -0.06134, -0.27156, -0.40489, -0.35924, -0.32081, -0.34765, -0.40379, -0.29730, -0.27569, -0.35713, -0.46390, -0.59464, -0.90423, -1.08502, -1.13289, -1.23819, -1.32975, -1.48255, -1.77414, -1.97671, -2.10896, -2.15705, -2.11692, -2.02320, -2.10123, -2.10985, -1.99757, -1.94752, -2.02148, -2.04101, -1.97725, -2.04679, -2.12105, -2.10125, -2.13021, -2.03000, -1.93463, -1.84690, -1.75576, -1.61691, -1.60639, -1.71190, -1.72815, -1.54614, -1.48722, -1.45115, -1.35840, -1.28975, -1.17544, -1.11601, -1.20835, -1.10863, -0.93215, -0.85688, -0.81605, -0.65686, -0.55878, -0.45377, -0.33605, -0.36102, -0.63712, -0.86382, -0.80056, -0.73330, -0.73079, -0.80339, -0.94959, -0.92946, -0.84315, -0.75922, -0.73383, -0.62996, -0.57561, -0.69963, -0.89014, -0.99389, -1.22386, -1.51635, -1.66991, -1.86185, -1.95168, -1.93460, -2.02426, -2.08253, -2.15908, -2.20616, -2.17330, -2.00939, -1.88846, -1.83569, -1.73868, -1.75421, -1.92229, -2.01630, -1.92765, -1.86424, -1.85227, -1.77640, -1.76316, -1.82532, -1.98354, -2.24813, -2.50476, -2.54872, -2.55503, -2.70070, -2.81133, -2.66252, -2.49748, -2.38906, -2.18073, -1.97175, -1.80932, -1.75708, -1.90951, -1.95758, -1.83517, -1.72732, -1.69406, -1.67002, -1.75549, -1.87005, -1.78500, -1.71411, -1.86113, -2.10488, -2.14361, -2.11001, -2.12067, -2.02222, -1.91240, -1.65924, -1.24941, -0.83578, -0.47394, 0.00807, 0.51486, 0.77770, 0.94327, 1.16743, 1.44353, 1.72470, 2.08759, 2.29882, 2.29749, 2.33469, 2.25060, 2.18437, 2.28894, 2.35736, 2.38844, 2.37209, 2.33077, 2.22503, 2.23991, 2.26440, 2.17633, 2.08836, 2.21265, 2.23372, 2.08436, 1.92697, 1.78918, 1.74168, 1.75342, 1.60236, 1.32608, 1.13858, 1.06390, 0.84389, 0.62115, 0.64277, 0.68388, 0.57196, 0.54154, 0.54064, 0.50845, 0.52295, 0.44427, 0.38163, 0.42903, 0.51639, 0.66562, 0.86326, 0.94898, 0.79207, 0.70409, 0.68603, 0.57157, 0.39233, 0.33855, 0.30241, 0.16376, 0.04859, -0.07418, -0.10640, -0.00563, -0.05249, -0.20797, -0.41608, -0.43480, -0.54684, -0.72655, -0.90705, -1.09318, -1.30958, -1.41052, -1.50841, -1.70081, -1.86025, -2.11801, -2.44847, -2.56806, -2.66883, -2.81195, -2.93743, -3.09207, -3.31942, -3.40457, -3.42213, -3.50524, -3.66128, -3.57978, -3.29866, -3.15230, -3.13519, -3.21888, -3.28532, -3.21697, -3.24142, -3.33147, -3.36035, -3.21168, -3.16688, -3.15455, -2.98824, -2.73309, -2.63298, -2.57652, -2.58814, -2.78382, -2.84100, -2.80073, -2.76527, -2.60500, -2.52339, -2.43535, -2.27314, -2.09618, -2.08998, -2.08731, -1.97760, -1.88139, -1.91325, -1.89384, -1.69235, -1.55930, -1.48306, -1.42704, -1.42278, -1.21388, -1.05050, -1.03013, -1.21700, -1.33800, -1.42840, -1.53226, +-1.44744, -1.43952, -1.37094, -1.34128, -1.43808, -1.63704, -1.81495, -1.87651, -1.96053, -2.13921, -2.32473, -2.35105, -2.18527, -2.08495, -2.01192, -1.79212, -1.31751, -0.96881, -0.74047, -0.43591, -0.20518, -0.00999, 0.32428, 0.73701, 1.06117, 1.42702, 1.59797, 1.59096, 1.68598, 1.72511, 1.71378, 1.69921, 1.71439, 1.69487, 1.63299, 1.65503, 1.59815, 1.49697, 1.27193, 1.17581, 1.14000, 1.03147, 0.94885, 0.99219, 1.19690, 1.26764, 1.17316, 1.12133, 1.19763, 1.20891, 1.10977, 1.13567, 1.12699, 0.90320, 0.66422, 0.45840, 0.24314, 0.22019, 0.14757, -0.08264, -0.18980, -0.19588, -0.15726, -0.13025, -0.09725, 0.01712, 0.06746, 0.13650, 0.08031, 0.00654, -0.10818, -0.09218, -0.13293, -0.28158, -0.47802, -0.57410, -0.35002, -0.13020, -0.00551, 0.08119, 0.22660, 0.35846, 0.33952, 0.45958, 0.58296, 0.59133, 0.67595, 0.82802, 0.88040, 0.94303, 0.89924, 0.60312, 0.43735, 0.33549, 0.26790, 0.35326, 0.37416, 0.37387, 0.09791, -0.12058, -0.35610, -0.55948, -0.74825, -0.73247, -0.64804, -0.64919, -0.78052, -0.96817, -1.04105, -1.11900, -1.28993, -1.42944, -1.44381, -1.45439, -1.58886, -1.51434, -1.29561, -1.06390, -0.82893, -0.60972, -0.56194, -0.44078, -0.27412, -0.30666, -0.27079, -0.07865, 0.08334, 0.27918, 0.39981, 0.55363, 0.50553, 0.45058, 0.26225, 0.10228, -0.13753, -0.24942, -0.20260, -0.17764, -0.16872, -0.24411, -0.17795, -0.05585, -0.09706, -0.20443, -0.29397, -0.38881, -0.69045, -0.83716, -0.86355, -1.00152, -1.22472, -1.40046, -1.64850, -1.87152, -1.94177, -2.04758, -2.03901, -1.90119, -1.94508, -1.93835, -1.96803, -1.96309, -2.06633, -2.05040, -2.04653, -1.99645, -2.04358, -2.00980, -1.88324, -1.75750, -1.66221, -1.62752, -1.47098, -1.33912, -1.40277, -1.53508, -1.50867, -1.27403, -1.21145, -1.17944, -1.12976, -1.10142, -1.06607, -1.01439, -1.06420, -1.02024, -0.82612, -0.75006, -0.67825, -0.47311, -0.38589, -0.32595, -0.37571, -0.39457, -0.58117, -0.66815, -0.64760, -0.56789, -0.58448, -0.70351, -0.73585, -0.71025, -0.66935, -0.66885, -0.56187, -0.39654, -0.42983, -0.62167, -0.81782, -0.93554, -1.23443, -1.54552, -1.68200, -1.83442, -1.93233, -1.89950, -1.90014, -1.94546, -1.96510, -2.02335, -2.06176, -1.94134, -1.84833, -1.74453, -1.67935, -1.62106, -1.67845, -1.70862, -1.70064, -1.65604, -1.65016, -1.66924, -1.63296, -1.74202, -1.98042, -2.32918, -2.50398, -2.44878, -2.54254, -2.78951, -2.95218, -2.80376, -2.62603, -2.48994, -2.26028, -2.03501, -1.89710, -1.78110, -1.75335, -1.76865, -1.64540, -1.61193, -1.70498, -1.67409, -1.71287, -1.73179, -1.70836, -1.71076, -1.80841, -2.01302, -2.11500, -2.11493, -2.08714, -2.04078, -1.81153, -1.48707, -1.13370, -0.79358, -0.39744, 0.14295, 0.49080, 0.62560, 0.75659, 0.99963, 1.30630, 1.59671, 1.97251, 2.21555, 2.19219, 2.19336, 2.15265, 2.01071, 2.06354, 2.13573, 2.13284, 2.19652, 2.20342, 2.12943, 2.08871, 2.04600, 2.04246, 1.98333, 2.00983, 1.92960, 1.83822, 1.65127, 1.66177, 1.74134, 1.71364, 1.49241, 1.20423, 1.13786, 1.02499, 0.75041, 0.51805, 0.55748, 0.64244, 0.61960, 0.68375, 0.70432, 0.59505, 0.46929, 0.39628, 0.33701, 0.40484, 0.57909, 0.66468, 0.84896, 0.94555, 0.80656, 0.68264, 0.58072, 0.55729, 0.43081, 0.38394, 0.28269, 0.20624, 0.03552, -0.01121, 0.01866, -0.00621, -0.13472, -0.31254, -0.38106, -0.41919, -0.61858, -0.83951, -0.99880, -1.14478, -1.35284, -1.46492, -1.62208, -1.87034, -2.06502, -2.19470, -2.40870, -2.51917, -2.57900, -2.79288, -2.91411, -3.02818, -3.24945, -3.40414, -3.55541, -3.55498, -3.63878, -3.49256, -3.27661, -3.07503, -3.14274, -3.22490, -3.18558, -3.15719, -3.22307, -3.37146, -3.29928, -3.15425, -3.12768, -3.10894, -2.94671, -2.71550, -2.69617, -2.65653, -2.64478, -2.78503, -2.80515, -2.68367, -2.60053, -2.48128, -2.37732, -2.37647, -2.25292, -2.06711, -2.06234, -2.06282, -2.06765, -1.92181, -1.90709, -1.84107, -1.77554, -1.65418, -1.62384, -1.53750, -1.35949, -1.12511, -0.97903, -1.00463, -1.04548, -1.12105, -1.29396, -1.50127, +-1.57763, -1.59512, -1.50354, -1.47958, -1.56463, -1.77833, -2.03920, -2.08019, -2.09207, -2.24916, -2.41402, -2.45790, -2.38154, -2.31709, -2.07212, -1.65769, -1.21741, -0.95638, -0.79389, -0.51189, -0.23586, -0.06116, 0.22283, 0.65871, 0.96617, 1.28205, 1.47596, 1.52209, 1.59238, 1.59745, 1.60974, 1.58499, 1.52451, 1.49738, 1.52389, 1.56192, 1.45532, 1.32201, 1.06961, 1.01322, 1.00438, 0.84613, 0.76115, 0.88261, 1.09733, 1.11775, 1.11498, 1.18000, 1.22974, 1.20292, 1.07705, 1.04836, 1.03356, 0.83246, 0.60153, 0.44400, 0.26087, 0.20370, 0.15212, -0.01890, -0.19437, -0.28586, -0.23079, -0.13427, -0.12324, -0.08240, -0.06547, 0.01656, -0.00189, -0.05572, -0.24984, -0.34971, -0.44080, -0.60525, -0.70682, -0.63367, -0.40430, -0.31885, -0.16230, 0.09432, 0.23867, 0.28174, 0.24300, 0.34062, 0.49060, 0.51638, 0.52597, 0.64317, 0.70058, 0.73350, 0.69430, 0.47893, 0.30415, 0.18355, 0.20645, 0.38147, 0.34266, 0.27042, 0.04957, -0.07987, -0.29219, -0.50078, -0.74353, -0.73806, -0.62174, -0.65336, -0.77200, -0.89015, -0.93480, -1.09447, -1.25408, -1.27521, -1.35167, -1.45864, -1.58644, -1.53285, -1.27829, -1.01771, -0.84158, -0.66943, -0.63152, -0.53511, -0.31760, -0.15447, -0.04197, 0.07884, 0.20428, 0.49025, 0.62274, 0.68482, 0.55540, 0.39635, 0.11870, -0.01423, -0.18397, -0.22508, -0.15754, -0.21787, -0.22283, -0.19371, -0.08274, -0.06884, -0.09918, -0.01282, -0.07052, -0.25562, -0.60758, -0.81845, -0.81851, -0.89051, -1.16305, -1.39532, -1.63550, -1.85724, -1.85992, -1.83210, -1.83066, -1.79448, -1.84570, -1.73872, -1.79215, -1.91499, -2.07798, -2.03889, -2.05164, -1.98889, -2.02410, -1.99249, -1.79156, -1.65533, -1.55014, -1.45264, -1.28436, -1.23082, -1.28749, -1.23430, -1.14301, -1.00129, -0.98517, -1.03671, -1.02038, -0.94978, -0.93309, -0.87468, -0.88981, -0.93463, -0.81021, -0.60894, -0.44402, -0.30324, -0.30322, -0.26734, -0.34958, -0.39760, -0.49482, -0.45791, -0.47421, -0.46337, -0.50229, -0.62488, -0.63217, -0.65778, -0.62688, -0.53530, -0.36543, -0.28378, -0.40710, -0.49074, -0.62333, -0.82717, -1.20694, -1.59995, -1.74585, -1.78448, -1.81158, -1.78851, -1.79085, -1.88655, -1.89359, -1.81268, -1.78104, -1.75339, -1.73640, -1.55545, -1.45503, -1.44059, -1.49876, -1.48435, -1.47867, -1.46489, -1.50273, -1.62128, -1.65366, -1.81816, -2.08688, -2.37030, -2.47166, -2.49251, -2.68896, -2.86869, -2.97407, -2.89500, -2.75668, -2.60962, -2.37092, -2.12541, -1.99414, -1.83801, -1.69541, -1.70086, -1.62771, -1.58072, -1.60022, -1.56331, -1.56727, -1.48942, -1.50279, -1.65893, -1.81841, -1.96632, -2.07004, -2.10673, -2.05302, -1.99063, -1.73586, -1.43435, -1.15717, -0.79289, -0.31441, 0.17638, 0.37095, 0.51904, 0.71490, 0.91597, 1.17672, 1.39840, 1.68191, 1.91976, 1.93427, 1.93828, 1.91204, 1.71383, 1.70557, 1.84541, 1.95033, 1.99567, 1.95158, 1.93000, 1.95764, 1.85813, 1.79454, 1.72892, 1.72027, 1.62446, 1.57974, 1.43306, 1.49578, 1.58838, 1.51572, 1.31050, 1.10392, 1.04496, 0.86627, 0.71746, 0.65180, 0.63370, 0.63457, 0.64745, 0.73429, 0.77315, 0.62484, 0.37226, 0.27574, 0.23386, 0.34062, 0.59568, 0.73918, 0.83748, 0.85793, 0.77779, 0.71673, 0.55630, 0.50979, 0.44886, 0.43427, 0.29056, 0.18814, 0.00470, -0.01624, 0.02272, -0.09363, -0.23434, -0.32896, -0.34780, -0.46684, -0.68075, -0.83128, -1.05818, -1.27296, -1.47434, -1.63827, -1.81836, -2.03844, -2.23644, -2.34707, -2.53864, -2.67832, -2.69272, -2.75542, -2.86939, -3.05118, -3.27422, -3.36997, -3.53343, -3.55711, -3.57678, -3.38483, -3.22479, -3.06489, -3.18958, -3.30492, -3.24995, -3.25400, -3.26059, -3.31779, -3.27137, -3.25691, -3.18538, -2.98253, -2.85822, -2.80296, -2.88808, -2.89430, -2.80664, -2.76763, -2.73135, -2.64066, -2.58410, -2.50210, -2.35761, -2.25739, -2.16357, -2.05362, -2.04604, -1.98284, -2.05090, -2.00894, -1.97571, -1.84395, -1.81490, -1.74469, -1.73925, -1.64744, -1.37053, -1.12131, -0.97857, -0.95583, -0.96834, -1.10836, -1.28400, -1.37186, +-1.70611, -1.62957, -1.51536, -1.50091, -1.61502, -1.79081, -2.01713, -2.21793, -2.23225, -2.24013, -2.42107, -2.61063, -2.57366, -2.32453, -1.92399, -1.55466, -1.22981, -0.97958, -0.79418, -0.59025, -0.39031, -0.19908, 0.06033, 0.46183, 0.84666, 1.08250, 1.11690, 1.20305, 1.35893, 1.41137, 1.47532, 1.46417, 1.39472, 1.42755, 1.50045, 1.48530, 1.27662, 1.11513, 0.96542, 0.83462, 0.81897, 0.84385, 0.81024, 0.83598, 0.96006, 1.02210, 1.07428, 1.05493, 1.08543, 1.15844, 1.09741, 0.95855, 0.84429, 0.78810, 0.68005, 0.55040, 0.46312, 0.34408, 0.13526, -0.03426, -0.16108, -0.25817, -0.23727, -0.13381, -0.11164, -0.09561, -0.13137, -0.13386, -0.19810, -0.25817, -0.38007, -0.63408, -0.76737, -0.72444, -0.69652, -0.69558, -0.64799, -0.58147, -0.34405, -0.10251, 0.02565, 0.10465, 0.12739, 0.17426, 0.21497, 0.26413, 0.27530, 0.34853, 0.49071, 0.58680, 0.48940, 0.30884, 0.19951, 0.09489, 0.11539, 0.25546, 0.16576, 0.06944, -0.08025, -0.15231, -0.31389, -0.47583, -0.56094, -0.60911, -0.60584, -0.57874, -0.67607, -0.88126, -0.98420, -1.08047, -1.13819, -1.23389, -1.36330, -1.33317, -1.29919, -1.23431, -1.09692, -0.88152, -0.71473, -0.60670, -0.51648, -0.34854, -0.22493, -0.01108, 0.22867, 0.32860, 0.37399, 0.61215, 0.72567, 0.76032, 0.60770, 0.37774, 0.12635, 0.03057, 0.07536, 0.01724, -0.14616, -0.22597, -0.20557, -0.21899, -0.18951, -0.19871, -0.10650, 0.00382, -0.09286, -0.24256, -0.53684, -0.75345, -0.83909, -0.86945, -1.03796, -1.28755, -1.51110, -1.64710, -1.73335, -1.76356, -1.72737, -1.73157, -1.80118, -1.66476, -1.68732, -1.77468, -1.87604, -1.83868, -1.88682, -1.93446, -1.87787, -1.81720, -1.70596, -1.50036, -1.32687, -1.30568, -1.21792, -1.10120, -0.96744, -0.85555, -0.83878, -0.73478, -0.67518, -0.72185, -0.79724, -0.73981, -0.65563, -0.55769, -0.54664, -0.57923, -0.64169, -0.57557, -0.35894, -0.23140, -0.31964, -0.33484, -0.36329, -0.32861, -0.27202, -0.22199, -0.35996, -0.51095, -0.48035, -0.50779, -0.64652, -0.70175, -0.57786, -0.48069, -0.39142, -0.36521, -0.39791, -0.43418, -0.61545, -0.77968, -1.04865, -1.39442, -1.64800, -1.72034, -1.65753, -1.63820, -1.68235, -1.73417, -1.79889, -1.77525, -1.63850, -1.55248, -1.55776, -1.38483, -1.30620, -1.33358, -1.34619, -1.29795, -1.29384, -1.37215, -1.39912, -1.50502, -1.69817, -1.84467, -1.97116, -2.22988, -2.44633, -2.59271, -2.71775, -2.83076, -2.97164, -2.87790, -2.64926, -2.38917, -2.24439, -2.15164, -2.01972, -1.86203, -1.71632, -1.63933, -1.64753, -1.70726, -1.57554, -1.40597, -1.35237, -1.32490, -1.47342, -1.72616, -1.84124, -1.89185, -2.00088, -2.12570, -2.02224, -1.83043, -1.71630, -1.51536, -1.17221, -0.79276, -0.38282, 0.07129, 0.37278, 0.58161, 0.66258, 0.80264, 1.09012, 1.30702, 1.40701, 1.46010, 1.54215, 1.62014, 1.62528, 1.55114, 1.52517, 1.56805, 1.69454, 1.74290, 1.67092, 1.66069, 1.72591, 1.63107, 1.59228, 1.55223, 1.55097, 1.48438, 1.50916, 1.52119, 1.45054, 1.40274, 1.41365, 1.24837, 1.00011, 0.90065, 0.83175, 0.86819, 0.76869, 0.66483, 0.69071, 0.77852, 0.80397, 0.70924, 0.56581, 0.34684, 0.28373, 0.35172, 0.48553, 0.54727, 0.57316, 0.62220, 0.61480, 0.56957, 0.50694, 0.32481, 0.33926, 0.37680, 0.35679, 0.15674, 0.01952, -0.01756, -0.08207, -0.09516, -0.07901, -0.16953, -0.34651, -0.43697, -0.52696, -0.68512, -0.97537, -1.32856, -1.47550, -1.56065, -1.73111, -1.99038, -2.15192, -2.27840, -2.43989, -2.63399, -2.77176, -2.88899, -2.92319, -2.97281, -3.16423, -3.38940, -3.41607, -3.47553, -3.40885, -3.32748, -3.17800, -3.11638, -3.05291, -3.07088, -3.21130, -3.26463, -3.16388, -3.04197, -3.16235, -3.25673, -3.26459, -3.07309, -2.89550, -2.88220, -2.85632, -2.86901, -2.82767, -2.78583, -2.66931, -2.62149, -2.65242, -2.63242, -2.49250, -2.41226, -2.37451, -2.27031, -2.16098, -2.14675, -2.08462, -2.17352, -2.12406, -1.98888, -1.81031, -1.76094, -1.75594, -1.66222, -1.58874, -1.42577, -1.11399, -0.90450, -0.97280, -1.09238, -1.19570, -1.20373, -1.25765, +-1.83409, -1.74481, -1.62363, -1.61207, -1.70475, -1.84254, -1.98310, -2.16252, -2.24187, -2.25666, -2.35817, -2.50360, -2.47719, -2.20102, -1.79516, -1.50312, -1.29473, -1.08322, -0.83099, -0.59215, -0.38476, -0.18592, 0.03186, 0.36946, 0.69863, 0.85200, 0.85308, 0.99092, 1.17175, 1.23644, 1.34137, 1.34713, 1.25549, 1.25385, 1.29836, 1.24435, 1.04398, 0.93542, 0.89578, 0.83426, 0.78028, 0.80478, 0.86049, 0.92485, 0.97355, 0.99346, 1.03532, 0.96644, 0.97216, 1.04725, 1.04743, 0.94100, 0.84782, 0.90681, 0.87465, 0.77923, 0.69446, 0.51924, 0.27854, 0.12939, -0.00207, -0.15030, -0.18299, -0.13444, -0.18849, -0.28444, -0.37356, -0.42388, -0.49038, -0.50358, -0.56512, -0.75422, -0.88134, -0.85264, -0.75305, -0.73438, -0.82047, -0.82594, -0.58127, -0.36059, -0.24477, -0.19050, -0.13964, -0.06583, -0.04998, 0.04190, 0.08258, 0.18494, 0.34754, 0.44282, 0.37593, 0.25433, 0.15596, -0.00983, -0.05855, 0.00790, -0.12576, -0.26879, -0.36317, -0.37073, -0.45109, -0.48921, -0.46533, -0.43313, -0.46972, -0.52207, -0.58188, -0.70381, -0.82216, -0.94074, -0.97716, -1.11742, -1.23983, -1.15301, -1.01274, -0.84503, -0.72846, -0.51155, -0.36498, -0.27701, -0.19299, -0.06556, 0.01633, 0.24856, 0.49131, 0.52557, 0.52833, 0.70797, 0.77478, 0.72855, 0.56086, 0.36335, 0.20528, 0.21699, 0.34991, 0.32482, 0.03421, -0.20309, -0.21283, -0.16433, -0.17698, -0.25730, -0.16258, -0.09327, -0.20103, -0.35228, -0.57767, -0.67526, -0.75499, -0.72123, -0.82494, -1.05252, -1.27958, -1.46381, -1.61212, -1.64592, -1.58763, -1.62076, -1.68456, -1.55259, -1.56783, -1.67317, -1.74833, -1.69666, -1.72815, -1.72805, -1.60864, -1.45232, -1.35372, -1.25631, -1.11034, -1.03290, -0.94431, -0.83211, -0.64333, -0.54296, -0.56982, -0.52976, -0.46326, -0.42138, -0.48200, -0.37870, -0.26385, -0.14133, -0.14185, -0.24315, -0.39518, -0.39551, -0.20994, -0.15765, -0.30802, -0.34092, -0.33182, -0.30954, -0.23109, -0.21211, -0.40847, -0.55442, -0.47837, -0.39828, -0.54735, -0.73068, -0.65870, -0.50323, -0.41221, -0.43618, -0.42813, -0.44320, -0.63295, -0.79428, -1.00675, -1.24380, -1.48948, -1.55498, -1.48246, -1.44612, -1.47618, -1.53524, -1.61478, -1.59659, -1.42958, -1.35531, -1.39388, -1.25660, -1.19576, -1.25978, -1.26737, -1.19639, -1.18385, -1.24880, -1.25975, -1.31440, -1.50615, -1.72231, -1.86701, -2.04428, -2.25711, -2.49421, -2.62305, -2.71684, -2.84628, -2.75257, -2.51098, -2.17878, -2.06512, -2.02195, -1.89859, -1.76304, -1.63783, -1.59109, -1.63888, -1.66240, -1.41799, -1.21618, -1.19012, -1.25253, -1.49086, -1.79372, -1.90057, -1.88246, -1.95566, -2.05185, -1.91893, -1.68035, -1.59101, -1.52121, -1.24432, -0.79387, -0.33746, 0.08490, 0.40173, 0.61242, 0.62320, 0.66811, 0.86609, 1.08247, 1.15935, 1.17666, 1.31023, 1.42698, 1.47630, 1.44603, 1.40868, 1.44431, 1.60223, 1.64376, 1.54018, 1.52729, 1.60050, 1.50068, 1.44592, 1.43842, 1.48754, 1.49992, 1.59769, 1.67562, 1.59087, 1.40831, 1.32237, 1.21482, 1.05828, 0.93493, 0.85964, 0.92416, 0.77172, 0.62306, 0.62919, 0.76762, 0.83532, 0.73173, 0.65637, 0.52185, 0.52331, 0.58450, 0.62123, 0.53345, 0.47003, 0.44548, 0.36381, 0.30634, 0.22589, 0.02689, 0.00451, 0.06361, 0.05892, -0.10770, -0.16443, -0.11031, -0.11316, -0.16265, -0.19970, -0.24011, -0.34777, -0.50674, -0.67619, -0.84435, -1.20328, -1.59079, -1.73626, -1.75717, -1.83272, -2.05576, -2.12697, -2.20359, -2.34988, -2.55982, -2.75831, -2.91818, -2.93342, -2.97793, -3.20425, -3.41219, -3.38321, -3.36934, -3.29913, -3.18621, -3.05462, -3.01803, -2.93521, -2.90257, -2.96613, -3.06637, -3.05850, -2.91292, -2.97127, -3.10485, -3.15672, -2.94036, -2.80417, -2.84122, -2.85587, -2.79598, -2.63705, -2.60280, -2.46992, -2.48310, -2.57090, -2.58289, -2.48379, -2.42839, -2.40397, -2.33000, -2.29810, -2.30866, -2.25122, -2.31143, -2.24844, -2.04401, -1.82261, -1.73614, -1.69261, -1.58485, -1.47870, -1.39718, -1.21758, -0.99516, -0.95882, -1.05172, -1.15341, -1.10593, -1.16077, +-1.93468, -1.89337, -1.79212, -1.68851, -1.71313, -1.98182, -2.17170, -2.22653, -2.20397, -2.23791, -2.32549, -2.34179, -2.28253, -2.12762, -1.74912, -1.44489, -1.23273, -1.04049, -0.82121, -0.51110, -0.26908, -0.15805, 0.00204, 0.25135, 0.53324, 0.70201, 0.72293, 0.83656, 1.01578, 1.15000, 1.22696, 1.26710, 1.19362, 1.10449, 1.07199, 1.06908, 0.98882, 0.81192, 0.73699, 0.78086, 0.81175, 0.80383, 0.83077, 0.96363, 1.01217, 0.93750, 0.98673, 0.99092, 1.01975, 1.06706, 1.00466, 0.95496, 0.91033, 0.89146, 0.83637, 0.73612, 0.64744, 0.55575, 0.35491, 0.18913, 0.04053, -0.04970, -0.14650, -0.15000, -0.27546, -0.53499, -0.69030, -0.69510, -0.64661, -0.75184, -0.91369, -1.00553, -1.01349, -1.01586, -0.98381, -0.92989, -1.01208, -1.11683, -0.89522, -0.59263, -0.44625, -0.38708, -0.40340, -0.30434, -0.23222, -0.18763, -0.14157, -0.01491, 0.12343, 0.28302, 0.24067, 0.11823, -0.00444, -0.12241, -0.25728, -0.24859, -0.36032, -0.54953, -0.60346, -0.51465, -0.42583, -0.48884, -0.55910, -0.48315, -0.41321, -0.42669, -0.48975, -0.51272, -0.56448, -0.75484, -0.82192, -0.86482, -0.94791, -0.84205, -0.74403, -0.53591, -0.35180, -0.19221, -0.11258, -0.04089, -0.00859, 0.15525, 0.22603, 0.40940, 0.55540, 0.63882, 0.64266, 0.79247, 0.87718, 0.73405, 0.54574, 0.43559, 0.46683, 0.46837, 0.46200, 0.40236, 0.16582, -0.09214, -0.20431, -0.14680, -0.12761, -0.28009, -0.25788, -0.12119, -0.17973, -0.26501, -0.47928, -0.52894, -0.54195, -0.55947, -0.72970, -0.95148, -1.21412, -1.37024, -1.54315, -1.58621, -1.55256, -1.46446, -1.46122, -1.35227, -1.33490, -1.51115, -1.61940, -1.55495, -1.43526, -1.36931, -1.34216, -1.20600, -1.03370, -0.93884, -0.88546, -0.79756, -0.66141, -0.61381, -0.50708, -0.35186, -0.35564, -0.29716, -0.28968, -0.25597, -0.22857, -0.12382, -0.07164, 0.04780, -0.01166, -0.08118, -0.21532, -0.24452, -0.16101, -0.10402, -0.24377, -0.30204, -0.25201, -0.30102, -0.29003, -0.29929, -0.37441, -0.45567, -0.50898, -0.48826, -0.55508, -0.70711, -0.73325, -0.59639, -0.42789, -0.44787, -0.47532, -0.40974, -0.54721, -0.67545, -0.92098, -1.16214, -1.31512, -1.38762, -1.42223, -1.37387, -1.38906, -1.35430, -1.35948, -1.34879, -1.26812, -1.19781, -1.21782, -1.14697, -1.04858, -1.10038, -1.12946, -1.06415, -0.95119, -0.94967, -1.10318, -1.24861, -1.37903, -1.56523, -1.78262, -1.97073, -2.09534, -2.33051, -2.54505, -2.58274, -2.61602, -2.46564, -2.25920, -2.01612, -1.90458, -1.87575, -1.85646, -1.76415, -1.69372, -1.65712, -1.64924, -1.60906, -1.37578, -1.17177, -1.11413, -1.24922, -1.46255, -1.73858, -1.87190, -1.83126, -1.76515, -1.72702, -1.73041, -1.62920, -1.50870, -1.40642, -1.19170, -0.77836, -0.25562, 0.15562, 0.36204, 0.58416, 0.65797, 0.67469, 0.76198, 0.86934, 0.99418, 1.07550, 1.15010, 1.24095, 1.27967, 1.25960, 1.29082, 1.34633, 1.49063, 1.56265, 1.55471, 1.51737, 1.60719, 1.53472, 1.43032, 1.43060, 1.57235, 1.70107, 1.67911, 1.61779, 1.55484, 1.40229, 1.24210, 1.09610, 1.04863, 0.96616, 0.78749, 0.80029, 0.68477, 0.55659, 0.56196, 0.64604, 0.77001, 0.74325, 0.65749, 0.57326, 0.59861, 0.60229, 0.61551, 0.44860, 0.29823, 0.19770, 0.14823, 0.04242, -0.03498, -0.18888, -0.28973, -0.24958, -0.17244, -0.16988, -0.26249, -0.32128, -0.30929, -0.31795, -0.39673, -0.47565, -0.49350, -0.63945, -0.93831, -1.14036, -1.38391, -1.68812, -1.79820, -1.88247, -1.91646, -2.04856, -2.14169, -2.23234, -2.34138, -2.55340, -2.69794, -2.86818, -2.92410, -3.01879, -3.15295, -3.33735, -3.29461, -3.22093, -3.21258, -3.11626, -2.93665, -2.76617, -2.73104, -2.81593, -2.85531, -2.87648, -2.88708, -2.83821, -2.86145, -2.92280, -3.02009, -2.83860, -2.61640, -2.63500, -2.62761, -2.60090, -2.43395, -2.37579, -2.34860, -2.47162, -2.57403, -2.63063, -2.49088, -2.43664, -2.43647, -2.43850, -2.37093, -2.37824, -2.31198, -2.26121, -2.19417, -1.97648, -1.72609, -1.53321, -1.52991, -1.58955, -1.54568, -1.44893, -1.29907, -1.12567, -0.98038, -0.90972, -1.00305, -1.00592, -0.98403, +-2.12639, -1.98160, -1.96229, -1.90134, -1.88161, -2.15109, -2.28972, -2.25367, -2.16614, -2.17028, -2.32660, -2.31981, -2.12299, -1.97422, -1.76739, -1.58381, -1.32581, -1.07867, -0.85617, -0.54588, -0.27065, -0.13945, 0.06292, 0.32950, 0.57735, 0.74291, 0.82604, 0.92762, 0.97363, 0.97343, 0.97855, 1.06486, 1.14156, 1.14697, 0.96859, 0.84656, 0.84886, 0.75597, 0.74900, 0.85854, 0.92744, 0.95699, 0.91701, 0.93705, 1.01826, 1.00076, 0.99531, 0.92888, 0.95596, 0.98573, 0.89508, 0.85708, 0.82791, 0.74288, 0.65543, 0.57333, 0.46084, 0.40321, 0.26607, 0.16566, 0.02378, -0.11268, -0.24494, -0.30159, -0.44310, -0.67779, -0.92505, -1.05021, -0.98208, -1.08070, -1.23201, -1.18563, -1.11366, -1.14425, -1.26224, -1.37428, -1.37845, -1.36274, -1.18914, -0.99542, -0.83318, -0.71763, -0.71933, -0.58720, -0.44407, -0.32933, -0.20232, -0.03514, 0.02428, 0.09937, 0.03983, 0.01329, -0.07698, -0.27756, -0.51194, -0.57005, -0.61852, -0.62733, -0.65581, -0.65987, -0.51542, -0.50100, -0.54637, -0.41347, -0.30080, -0.24392, -0.29759, -0.40790, -0.41257, -0.49178, -0.56542, -0.66784, -0.74017, -0.66409, -0.62754, -0.45010, -0.24328, -0.04962, 0.02586, 0.16508, 0.20893, 0.35643, 0.41833, 0.60679, 0.68383, 0.66029, 0.65176, 0.76638, 0.84339, 0.79363, 0.61601, 0.48224, 0.58554, 0.58717, 0.49242, 0.44788, 0.28583, 0.08372, -0.08906, -0.22069, -0.20240, -0.21477, -0.18401, -0.11699, -0.12564, -0.10165, -0.24895, -0.32279, -0.37451, -0.45670, -0.67417, -0.77791, -0.99107, -1.18324, -1.42330, -1.44577, -1.37536, -1.28417, -1.25392, -1.18340, -1.17284, -1.22531, -1.31726, -1.39219, -1.27273, -1.12923, -1.08511, -0.90145, -0.71094, -0.60118, -0.57029, -0.61427, -0.51325, -0.42378, -0.36747, -0.35450, -0.39370, -0.31038, -0.33399, -0.30853, -0.21414, -0.04503, 0.00881, 0.19511, 0.13492, 0.04648, -0.07592, -0.09571, -0.07119, -0.13768, -0.30561, -0.33897, -0.29687, -0.31423, -0.35179, -0.48795, -0.51443, -0.49683, -0.56509, -0.53701, -0.54959, -0.63622, -0.66379, -0.64607, -0.47632, -0.32193, -0.27315, -0.32954, -0.54685, -0.71704, -0.97890, -1.16045, -1.22272, -1.26501, -1.36640, -1.25043, -1.17579, -1.07397, -1.05247, -1.04883, -1.00720, -1.02113, -1.09972, -1.10007, -1.03085, -0.96983, -0.92202, -0.95127, -0.89337, -0.84798, -0.99377, -1.09626, -1.19143, -1.39744, -1.65315, -1.97686, -2.14103, -2.25241, -2.41944, -2.50375, -2.52178, -2.31944, -2.12342, -1.94852, -1.88466, -1.85611, -1.86726, -1.77630, -1.72715, -1.74403, -1.71292, -1.56641, -1.31419, -1.23252, -1.29792, -1.46054, -1.61086, -1.74058, -1.77030, -1.78773, -1.72138, -1.56691, -1.53812, -1.41762, -1.23437, -1.06818, -0.84758, -0.60548, -0.24050, 0.15267, 0.39478, 0.61004, 0.67187, 0.66837, 0.65999, 0.70225, 0.86190, 1.03132, 1.10868, 1.19266, 1.25913, 1.23965, 1.27263, 1.33280, 1.49035, 1.53797, 1.48957, 1.43536, 1.50022, 1.50373, 1.53119, 1.51735, 1.57407, 1.69460, 1.63748, 1.53020, 1.51034, 1.38546, 1.21601, 1.01517, 0.92383, 0.92407, 0.80647, 0.70860, 0.45861, 0.32451, 0.33703, 0.37832, 0.49117, 0.51661, 0.52648, 0.57256, 0.66126, 0.56814, 0.45900, 0.26118, 0.14280, -0.01658, -0.19279, -0.35458, -0.42579, -0.48490, -0.44173, -0.40051, -0.36805, -0.24588, -0.28750, -0.42071, -0.43499, -0.51274, -0.58603, -0.65598, -0.73348, -0.85866, -1.11674, -1.34295, -1.60127, -1.80465, -1.87475, -2.00703, -2.03977, -2.09521, -2.13992, -2.22498, -2.26889, -2.47828, -2.64132, -2.82090, -2.87800, -3.00634, -3.18617, -3.33940, -3.31924, -3.25123, -3.14779, -3.07945, -2.98370, -2.75251, -2.66928, -2.72085, -2.64652, -2.60927, -2.59636, -2.62304, -2.80377, -2.82888, -2.80319, -2.66334, -2.56280, -2.59044, -2.51976, -2.46570, -2.35153, -2.36339, -2.40943, -2.55309, -2.55872, -2.61400, -2.52582, -2.49141, -2.44689, -2.45730, -2.46055, -2.44624, -2.33397, -2.16205, -1.92965, -1.73864, -1.65341, -1.52388, -1.48508, -1.52336, -1.42240, -1.35022, -1.23099, -1.06028, -0.95783, -0.77060, -0.70634, -0.72386, -0.79568, +-2.44353, -2.30285, -2.22571, -2.21943, -2.23688, -2.37056, -2.43693, -2.32297, -2.21230, -2.23769, -2.31186, -2.21586, -2.04932, -1.92958, -1.80833, -1.69477, -1.33447, -1.00550, -0.72643, -0.46213, -0.26479, -0.06472, 0.17080, 0.44795, 0.65677, 0.87158, 1.03309, 1.01115, 0.89072, 0.82105, 0.83085, 0.90605, 1.06739, 1.11881, 0.97740, 0.78979, 0.71912, 0.73194, 0.73616, 0.83858, 0.90117, 0.89009, 0.91774, 0.96758, 0.98461, 0.96195, 0.96019, 0.81985, 0.83859, 0.85798, 0.78546, 0.72837, 0.63187, 0.54432, 0.44372, 0.36028, 0.22839, 0.22503, 0.19651, 0.05856, -0.13358, -0.28537, -0.36114, -0.51755, -0.66053, -0.90651, -1.13649, -1.29579, -1.33842, -1.36088, -1.44943, -1.34042, -1.26842, -1.44823, -1.61419, -1.67740, -1.62759, -1.55984, -1.36015, -1.27451, -1.10279, -0.92213, -0.88074, -0.74921, -0.65122, -0.46967, -0.25473, -0.10421, -0.11349, -0.12005, -0.11067, -0.09926, -0.15363, -0.35264, -0.51853, -0.67260, -0.70459, -0.70061, -0.73774, -0.77185, -0.73914, -0.62750, -0.57252, -0.41345, -0.27646, -0.28678, -0.28838, -0.30600, -0.31817, -0.39818, -0.40713, -0.54857, -0.57778, -0.49017, -0.48516, -0.34630, -0.22525, -0.02540, 0.09828, 0.25200, 0.29640, 0.39478, 0.53633, 0.69678, 0.76062, 0.69325, 0.77924, 0.82257, 0.87090, 0.81012, 0.65649, 0.57876, 0.54350, 0.50436, 0.42196, 0.43014, 0.40667, 0.18001, 0.00390, -0.10037, -0.08841, -0.08834, -0.00928, -0.01658, 0.00250, 0.12533, 0.04045, -0.06347, -0.25363, -0.45120, -0.63205, -0.63005, -0.74474, -0.95970, -1.13766, -1.17728, -1.11115, -1.08600, -1.01364, -1.04134, -1.09456, -1.13932, -1.22132, -1.28431, -1.30735, -1.18051, -1.04018, -0.81964, -0.59741, -0.55495, -0.51880, -0.46567, -0.32321, -0.28230, -0.22331, -0.31777, -0.40569, -0.30536, -0.34919, -0.32965, -0.31199, -0.19512, -0.07978, 0.16670, 0.20572, 0.10748, 0.08123, 0.07887, 0.05200, -0.11836, -0.21230, -0.26618, -0.33870, -0.44363, -0.54031, -0.58079, -0.60459, -0.57799, -0.55696, -0.51996, -0.47654, -0.58330, -0.65520, -0.59404, -0.38303, -0.20732, -0.09175, -0.25327, -0.57326, -0.78571, -1.02133, -1.06950, -1.09658, -1.16553, -1.21994, -1.05138, -0.88044, -0.81899, -0.79682, -0.81547, -0.85606, -0.94908, -0.97974, -1.02069, -1.07062, -1.03063, -0.97780, -0.95016, -0.99522, -1.02345, -1.04839, -1.06028, -1.06146, -1.29842, -1.62861, -1.92265, -2.04750, -2.16915, -2.30145, -2.42436, -2.51587, -2.31137, -2.11958, -1.91469, -1.87591, -1.92179, -1.89884, -1.78585, -1.70265, -1.76752, -1.68259, -1.46080, -1.31113, -1.37424, -1.45544, -1.53444, -1.67222, -1.75117, -1.76659, -1.72755, -1.67896, -1.56421, -1.43271, -1.26243, -1.01026, -0.80558, -0.65722, -0.46638, -0.15354, 0.11572, 0.38977, 0.68851, 0.74799, 0.77626, 0.75333, 0.81711, 0.96810, 1.03738, 1.07372, 1.13531, 1.21744, 1.19190, 1.25164, 1.34485, 1.40936, 1.38937, 1.35166, 1.34688, 1.29225, 1.29213, 1.35549, 1.44642, 1.51147, 1.50893, 1.50056, 1.41987, 1.44636, 1.35210, 1.09990, 0.91658, 0.86355, 0.82647, 0.70107, 0.60165, 0.26491, 0.12546, 0.14876, 0.21612, 0.32285, 0.28863, 0.37362, 0.50724, 0.59990, 0.43537, 0.27111, 0.18529, 0.06433, -0.14289, -0.38291, -0.50583, -0.64997, -0.68572, -0.63631, -0.54705, -0.47982, -0.41090, -0.39317, -0.55422, -0.62305, -0.75940, -0.89369, -0.85824, -0.81188, -0.93196, -1.19411, -1.35728, -1.64846, -1.84547, -1.93920, -2.08586, -2.11346, -2.19883, -2.22126, -2.27564, -2.31526, -2.51841, -2.70443, -2.81208, -2.94291, -3.11059, -3.30249, -3.30544, -3.32555, -3.29102, -3.21186, -3.13244, -2.99402, -2.84471, -2.70623, -2.67691, -2.56085, -2.47352, -2.53355, -2.53737, -2.63386, -2.66199, -2.65201, -2.48090, -2.47398, -2.51965, -2.40588, -2.34430, -2.29031, -2.45539, -2.56497, -2.59976, -2.51099, -2.51877, -2.49613, -2.40152, -2.37061, -2.41338, -2.50135, -2.38824, -2.28790, -2.07788, -1.84380, -1.70219, -1.63643, -1.67206, -1.57759, -1.45116, -1.26509, -1.14180, -1.10841, -0.92113, -0.71172, -0.52037, -0.51687, -0.50926, -0.64270, +-2.57610, -2.51021, -2.40420, -2.39183, -2.40157, -2.48135, -2.61807, -2.53861, -2.29770, -2.22829, -2.31892, -2.25154, -2.12721, -2.01801, -1.78792, -1.56570, -1.18937, -0.86465, -0.56983, -0.31997, -0.11479, 0.12872, 0.23820, 0.37079, 0.55100, 0.78251, 0.93967, 0.85240, 0.72538, 0.70683, 0.77900, 0.91933, 1.08865, 1.14267, 1.06539, 0.89768, 0.78343, 0.75743, 0.61367, 0.58603, 0.71411, 0.78770, 0.80687, 0.82495, 0.82958, 0.80263, 0.89354, 0.84671, 0.82575, 0.78749, 0.69775, 0.60498, 0.52921, 0.52063, 0.35641, 0.16625, 0.04185, 0.06950, 0.07094, -0.10727, -0.33323, -0.44854, -0.48671, -0.60837, -0.73028, -0.98575, -1.19678, -1.32138, -1.36982, -1.37036, -1.50067, -1.52510, -1.44858, -1.57763, -1.77673, -1.86756, -1.79206, -1.73163, -1.46382, -1.27319, -1.12139, -0.97900, -0.96499, -0.90046, -0.82436, -0.58582, -0.40084, -0.37772, -0.39127, -0.38580, -0.32322, -0.29262, -0.30745, -0.38919, -0.46830, -0.56402, -0.59741, -0.67131, -0.76693, -0.79508, -0.78834, -0.65671, -0.60200, -0.55539, -0.37696, -0.27854, -0.26393, -0.32067, -0.33538, -0.43394, -0.38247, -0.38006, -0.36134, -0.28271, -0.29054, -0.19126, -0.10259, 0.13110, 0.23564, 0.22668, 0.20742, 0.27586, 0.44511, 0.60502, 0.72250, 0.76463, 0.89994, 1.00239, 1.07012, 0.97237, 0.80660, 0.72875, 0.61014, 0.53375, 0.44611, 0.37579, 0.43069, 0.33948, 0.19008, 0.02993, 0.03427, 0.00567, 0.07112, 0.13543, 0.15049, 0.23582, 0.16029, 0.04321, -0.17681, -0.34574, -0.49215, -0.58430, -0.68831, -0.87697, -1.00996, -1.06852, -1.01943, -0.98102, -0.93852, -0.95358, -1.01914, -1.10662, -1.20135, -1.23709, -1.30188, -1.19948, -1.04596, -0.93882, -0.71205, -0.54742, -0.46264, -0.43356, -0.23257, -0.16675, -0.08460, -0.06397, -0.15457, -0.14087, -0.23203, -0.27990, -0.36824, -0.26739, -0.13274, 0.01626, 0.10418, 0.05736, 0.07835, 0.09847, 0.09064, -0.01187, -0.06095, -0.10645, -0.22555, -0.39134, -0.49632, -0.44094, -0.43210, -0.41648, -0.37931, -0.45903, -0.44494, -0.46079, -0.55891, -0.62251, -0.45247, -0.30280, -0.17788, -0.22916, -0.52024, -0.77987, -0.98881, -0.98307, -0.99915, -1.00983, -0.99424, -0.92221, -0.78467, -0.77878, -0.81453, -0.86859, -0.94102, -0.98311, -0.95262, -0.95831, -1.01513, -1.01361, -0.97782, -0.90709, -0.96504, -1.02506, -1.02128, -1.08675, -1.05054, -1.12916, -1.39564, -1.73763, -1.89631, -2.04815, -2.19290, -2.26834, -2.39908, -2.30255, -2.16080, -1.93571, -1.87135, -1.88971, -1.82417, -1.77634, -1.71012, -1.75129, -1.64786, -1.45463, -1.37571, -1.42258, -1.42847, -1.41842, -1.50832, -1.60844, -1.65046, -1.57792, -1.51712, -1.43645, -1.33447, -1.27186, -1.07798, -0.77268, -0.55865, -0.43145, -0.19276, 0.03928, 0.33628, 0.76512, 0.92434, 0.94827, 0.91798, 0.99553, 1.11695, 1.11035, 1.09868, 1.04768, 1.02653, 0.99913, 1.06650, 1.15397, 1.17298, 1.17266, 1.20753, 1.23568, 1.18258, 1.15335, 1.19135, 1.34625, 1.50707, 1.52295, 1.53901, 1.42751, 1.38609, 1.37827, 1.21118, 0.95275, 0.77072, 0.67518, 0.51353, 0.48947, 0.26219, 0.07909, 0.04710, 0.14830, 0.27769, 0.25380, 0.38787, 0.45563, 0.42417, 0.26495, 0.13203, 0.10812, -0.01931, -0.21371, -0.38600, -0.47817, -0.59237, -0.65206, -0.69536, -0.63526, -0.53922, -0.49568, -0.48146, -0.69505, -0.89814, -0.99119, -0.99848, -0.94481, -0.93938, -1.03792, -1.28676, -1.37026, -1.54752, -1.82609, -2.03216, -2.18196, -2.20775, -2.28447, -2.25482, -2.33553, -2.50361, -2.70016, -2.87284, -2.96128, -3.12969, -3.28914, -3.38849, -3.30129, -3.20422, -3.13111, -3.08577, -2.99624, -2.81191, -2.68003, -2.53621, -2.55331, -2.61125, -2.50944, -2.46384, -2.43663, -2.56644, -2.61909, -2.65640, -2.44148, -2.30287, -2.36515, -2.32772, -2.30683, -2.29292, -2.48164, -2.52589, -2.50152, -2.50507, -2.49916, -2.47239, -2.36215, -2.36075, -2.43772, -2.52871, -2.42356, -2.28282, -2.06537, -1.87009, -1.73938, -1.62876, -1.65812, -1.50416, -1.31453, -1.21150, -1.03864, -0.87404, -0.66564, -0.54486, -0.44784, -0.53779, -0.51233, -0.50787, +-2.77347, -2.70693, -2.64082, -2.64699, -2.57188, -2.66146, -2.73516, -2.60032, -2.34170, -2.20159, -2.22289, -2.25073, -2.15471, -1.93502, -1.66484, -1.40546, -1.08902, -0.71417, -0.42463, -0.21295, 0.01318, 0.27652, 0.31253, 0.33133, 0.54041, 0.66303, 0.69517, 0.62258, 0.51965, 0.49009, 0.56042, 0.75113, 0.91366, 1.02385, 0.96628, 0.78105, 0.73391, 0.61409, 0.39489, 0.37894, 0.49816, 0.64566, 0.72273, 0.68200, 0.67694, 0.79253, 0.92550, 0.89765, 0.79193, 0.71945, 0.60907, 0.43069, 0.40789, 0.46344, 0.29769, 0.05770, 0.00533, -0.03462, -0.10689, -0.25005, -0.49480, -0.65732, -0.74241, -0.83449, -0.94944, -1.13911, -1.31594, -1.46546, -1.42502, -1.43311, -1.57549, -1.61066, -1.64733, -1.75918, -1.91792, -2.04707, -2.01852, -1.84502, -1.57421, -1.37543, -1.26249, -1.11889, -1.08904, -1.18504, -1.12538, -0.89702, -0.71841, -0.72908, -0.61653, -0.59229, -0.57366, -0.49355, -0.47811, -0.53208, -0.61935, -0.66150, -0.69407, -0.79503, -0.92574, -1.00997, -0.89543, -0.71054, -0.65773, -0.54040, -0.38783, -0.22083, -0.12808, -0.19106, -0.28778, -0.30526, -0.25132, -0.22777, -0.17971, -0.07819, -0.02174, -0.04729, 0.02666, 0.23839, 0.37516, 0.29665, 0.31347, 0.36722, 0.45202, 0.63735, 0.81002, 0.90463, 1.01195, 1.15198, 1.22441, 1.12927, 0.97478, 0.74426, 0.59044, 0.51733, 0.39445, 0.41157, 0.45160, 0.40280, 0.30392, 0.15354, 0.08981, 0.16814, 0.20981, 0.18937, 0.14145, 0.15301, 0.15263, -0.02285, -0.18121, -0.30538, -0.36647, -0.49934, -0.53993, -0.67481, -0.88991, -0.96312, -0.91092, -0.92535, -1.00928, -1.02803, -1.06971, -1.14071, -1.19803, -1.31700, -1.35843, -1.19628, -1.06553, -0.87704, -0.67928, -0.51293, -0.37761, -0.29748, -0.09973, 0.12393, 0.26297, 0.26076, 0.10680, -0.00609, -0.04757, -0.22292, -0.38358, -0.33436, -0.17355, -0.08403, 0.07503, 0.14512, 0.11017, 0.13057, 0.17642, 0.11693, 0.01566, -0.10002, -0.25810, -0.42608, -0.45460, -0.42051, -0.38089, -0.30342, -0.31723, -0.33330, -0.31685, -0.33277, -0.46216, -0.60260, -0.57692, -0.40286, -0.22795, -0.25604, -0.51631, -0.81010, -0.88841, -0.90162, -0.90936, -0.88349, -0.79283, -0.75232, -0.60832, -0.58617, -0.77665, -0.89273, -0.90784, -0.89987, -0.91285, -0.95341, -0.99749, -0.99445, -0.89156, -0.85690, -0.95229, -0.98484, -1.03291, -1.02126, -0.87679, -0.88116, -1.09293, -1.42202, -1.70546, -1.85625, -1.92590, -2.05551, -2.28374, -2.34300, -2.17807, -1.98695, -1.93409, -1.91369, -1.79337, -1.74584, -1.65144, -1.56148, -1.53150, -1.47670, -1.40576, -1.41315, -1.41846, -1.41085, -1.46443, -1.57822, -1.57143, -1.49903, -1.43818, -1.27515, -1.25678, -1.23333, -1.01627, -0.73450, -0.48830, -0.32362, -0.16693, 0.06448, 0.47476, 0.89044, 1.02994, 0.98234, 0.99820, 1.08186, 1.11395, 1.03284, 0.96149, 0.87790, 0.83562, 0.91142, 0.89465, 0.88498, 0.93870, 0.98548, 1.02587, 1.01401, 0.95231, 0.87120, 0.94622, 1.14526, 1.36395, 1.53090, 1.55241, 1.45593, 1.47114, 1.45816, 1.35270, 1.09204, 0.77146, 0.58739, 0.50810, 0.45208, 0.20844, -0.04605, -0.07407, 0.08026, 0.14778, 0.16438, 0.29275, 0.30272, 0.20109, 0.16357, 0.02825, -0.05715, -0.14674, -0.32006, -0.49293, -0.62018, -0.69314, -0.76861, -0.85391, -0.85430, -0.83781, -0.74608, -0.74366, -0.95568, -1.07603, -1.16690, -1.11023, -1.02797, -1.07524, -1.22041, -1.32370, -1.38890, -1.59135, -1.99521, -2.27264, -2.34334, -2.42126, -2.44285, -2.41253, -2.48109, -2.69747, -2.77345, -2.91737, -3.08532, -3.25468, -3.40422, -3.46864, -3.36494, -3.13501, -2.99176, -2.91358, -2.80097, -2.69312, -2.48980, -2.30804, -2.38019, -2.41563, -2.36351, -2.29164, -2.23610, -2.38104, -2.51897, -2.45595, -2.23631, -2.11530, -2.21595, -2.26397, -2.23506, -2.33885, -2.47431, -2.47600, -2.37855, -2.42350, -2.33944, -2.28262, -2.26511, -2.26709, -2.35400, -2.52549, -2.57127, -2.46059, -2.27339, -2.07953, -1.88044, -1.79234, -1.70465, -1.44619, -1.26176, -1.05861, -0.87341, -0.66090, -0.42278, -0.35271, -0.44273, -0.48659, -0.41205, -0.37783, +-2.83552, -2.78934, -2.69608, -2.70223, -2.70426, -2.82538, -2.83085, -2.66571, -2.46502, -2.33475, -2.17578, -2.13403, -2.14573, -1.93588, -1.64015, -1.39315, -1.07746, -0.65738, -0.34382, -0.11529, 0.09333, 0.34726, 0.46436, 0.49964, 0.62251, 0.62002, 0.57228, 0.54160, 0.47982, 0.47097, 0.52129, 0.66310, 0.77511, 0.84824, 0.81320, 0.66577, 0.61343, 0.41078, 0.16369, 0.16651, 0.30964, 0.50873, 0.69000, 0.72426, 0.63460, 0.71828, 0.90314, 0.90337, 0.80645, 0.71254, 0.58812, 0.43360, 0.38742, 0.37423, 0.23119, 0.02907, -0.08352, -0.21406, -0.27167, -0.32143, -0.54801, -0.73247, -0.83397, -0.95632, -1.13121, -1.32112, -1.39814, -1.49094, -1.50883, -1.60713, -1.74695, -1.84158, -1.97021, -2.08560, -2.13308, -2.13672, -2.19148, -2.09777, -1.86189, -1.69758, -1.54468, -1.30476, -1.20957, -1.30902, -1.31561, -1.19785, -1.03890, -0.94404, -0.74373, -0.70735, -0.68612, -0.57169, -0.55337, -0.61581, -0.71370, -0.74928, -0.77938, -0.93864, -1.04333, -1.03618, -0.84440, -0.65808, -0.62454, -0.54175, -0.43467, -0.25725, -0.03393, 0.10823, -0.03902, -0.20310, -0.17898, -0.14843, -0.05241, 0.11706, 0.19292, 0.15742, 0.16548, 0.28700, 0.47885, 0.52008, 0.57723, 0.58325, 0.66012, 0.88545, 1.04209, 1.16683, 1.32261, 1.45614, 1.45958, 1.28730, 1.14114, 0.86857, 0.64302, 0.50288, 0.36461, 0.35706, 0.35288, 0.29332, 0.23488, 0.26466, 0.22171, 0.24610, 0.29001, 0.19243, 0.09183, 0.11222, 0.10917, 0.01754, -0.04167, -0.16093, -0.19576, -0.27659, -0.30011, -0.49563, -0.76704, -0.80922, -0.76901, -0.84964, -0.97777, -0.98678, -0.98125, -1.05892, -1.12462, -1.23484, -1.28089, -1.14691, -0.98585, -0.76075, -0.60092, -0.51058, -0.34179, -0.04124, 0.21405, 0.36229, 0.48027, 0.41067, 0.18357, 0.08504, 0.08235, -0.05910, -0.21856, -0.26081, -0.11655, -0.00814, 0.13802, 0.20859, 0.19607, 0.26151, 0.29012, 0.23190, 0.13273, -0.05144, -0.25332, -0.44741, -0.45732, -0.40765, -0.37650, -0.35066, -0.41919, -0.42442, -0.37383, -0.36492, -0.46530, -0.50480, -0.51577, -0.50598, -0.41334, -0.42969, -0.61977, -0.79720, -0.81433, -0.80993, -0.78699, -0.81292, -0.73409, -0.61782, -0.44532, -0.49136, -0.73757, -0.78773, -0.70337, -0.66001, -0.71397, -0.80578, -0.87536, -0.89073, -0.75163, -0.66954, -0.79964, -0.94806, -1.05143, -1.00093, -0.81296, -0.81426, -1.01305, -1.23214, -1.50784, -1.74460, -1.82239, -1.95698, -2.20935, -2.26273, -2.06942, -1.91026, -1.86810, -1.84764, -1.69681, -1.59053, -1.48421, -1.38346, -1.38808, -1.37761, -1.29753, -1.27717, -1.27513, -1.30218, -1.38075, -1.53689, -1.56588, -1.44614, -1.30976, -1.11854, -1.12737, -1.13508, -0.94362, -0.72578, -0.51430, -0.19554, 0.09316, 0.27615, 0.59502, 0.92905, 1.02530, 0.98575, 1.04646, 1.15391, 1.18129, 1.01628, 0.88438, 0.87181, 0.92143, 0.99464, 0.86169, 0.79870, 0.87289, 0.94282, 1.01385, 1.00137, 0.88305, 0.71528, 0.77444, 1.04928, 1.34493, 1.51726, 1.48983, 1.37349, 1.37402, 1.37789, 1.31943, 1.18475, 0.97706, 0.71214, 0.53641, 0.36992, 0.04625, -0.16635, -0.09840, 0.05912, 0.09873, 0.10646, 0.16222, 0.13462, 0.06016, 0.05521, -0.11696, -0.22510, -0.26344, -0.43167, -0.62356, -0.74763, -0.79053, -0.85237, -0.98559, -1.02513, -1.02021, -0.99157, -1.06948, -1.21993, -1.25706, -1.31548, -1.30147, -1.20255, -1.13380, -1.34586, -1.53697, -1.61990, -1.86813, -2.28789, -2.48455, -2.46867, -2.45117, -2.45025, -2.51755, -2.59083, -2.74720, -2.76051, -2.89237, -3.04674, -3.19412, -3.36989, -3.40261, -3.24961, -2.98075, -2.84043, -2.81881, -2.73563, -2.62814, -2.39465, -2.22276, -2.26172, -2.27533, -2.23197, -2.18989, -2.15696, -2.16290, -2.28149, -2.27281, -2.11951, -2.09543, -2.17959, -2.18447, -2.18903, -2.28749, -2.37630, -2.41941, -2.30824, -2.27433, -2.16789, -2.16903, -2.16044, -2.07248, -2.12034, -2.32762, -2.47261, -2.44271, -2.34717, -2.23200, -1.95943, -1.74724, -1.57304, -1.36202, -1.19407, -0.96896, -0.79143, -0.60596, -0.35372, -0.15616, -0.29428, -0.41634, -0.30968, -0.24186, +-2.81348, -2.79663, -2.75297, -2.72425, -2.80444, -2.98912, -2.94209, -2.76476, -2.54799, -2.43539, -2.26439, -2.13867, -2.03661, -1.84836, -1.59673, -1.28597, -0.98109, -0.59543, -0.35977, -0.15302, 0.17872, 0.40003, 0.56340, 0.67438, 0.73524, 0.69354, 0.60731, 0.54782, 0.46825, 0.47825, 0.45262, 0.53940, 0.69449, 0.71496, 0.59475, 0.50268, 0.48595, 0.26767, 0.10416, 0.16394, 0.39377, 0.62592, 0.72078, 0.72905, 0.64739, 0.65080, 0.77425, 0.90127, 0.88488, 0.79157, 0.63081, 0.47617, 0.47528, 0.30480, 0.05363, -0.12405, -0.30730, -0.43976, -0.48419, -0.54318, -0.81527, -0.99303, -1.09367, -1.19590, -1.33149, -1.50613, -1.58285, -1.63748, -1.71414, -1.94169, -2.07248, -2.14308, -2.19295, -2.21737, -2.26834, -2.25999, -2.30399, -2.26100, -2.17106, -1.99118, -1.79956, -1.55350, -1.42631, -1.48446, -1.38314, -1.29046, -1.23750, -1.06290, -0.85100, -0.77379, -0.78102, -0.73010, -0.76873, -0.82887, -0.93795, -0.93889, -0.85740, -0.93569, -1.00191, -0.89566, -0.62414, -0.51567, -0.53740, -0.50306, -0.41368, -0.19550, 0.01682, 0.21661, 0.14185, -0.01691, -0.08336, 0.01799, 0.12959, 0.21103, 0.23150, 0.15830, 0.25087, 0.42588, 0.55910, 0.69229, 0.73477, 0.75432, 0.85948, 1.07548, 1.13748, 1.27576, 1.48422, 1.62251, 1.63098, 1.46732, 1.27488, 1.02053, 0.85480, 0.63926, 0.47195, 0.41218, 0.37913, 0.39514, 0.27806, 0.28273, 0.27290, 0.32424, 0.31547, 0.27445, 0.22137, 0.20835, 0.15177, 0.06081, 0.15459, 0.15045, -0.02077, -0.10455, -0.16551, -0.38957, -0.69271, -0.74879, -0.78812, -0.88111, -0.95929, -0.93304, -0.83322, -0.84427, -0.98336, -1.11037, -1.11126, -1.04984, -0.88740, -0.63245, -0.44558, -0.25714, -0.09111, 0.22108, 0.44591, 0.53268, 0.52268, 0.43759, 0.27625, 0.19718, 0.17700, -0.01196, -0.11133, -0.06359, -0.02949, 0.04400, 0.08325, 0.12145, 0.14258, 0.20973, 0.13726, 0.06304, 0.02941, -0.09490, -0.18209, -0.27645, -0.34126, -0.38127, -0.34424, -0.38813, -0.53598, -0.55928, -0.47110, -0.31300, -0.33676, -0.36260, -0.39494, -0.42479, -0.49531, -0.53316, -0.58655, -0.70685, -0.78115, -0.87074, -0.79357, -0.70554, -0.73253, -0.60660, -0.43765, -0.47831, -0.64696, -0.61696, -0.52826, -0.51723, -0.58787, -0.69817, -0.73775, -0.68670, -0.57825, -0.54310, -0.63019, -0.82860, -0.98770, -0.93884, -0.81623, -0.80830, -1.00564, -1.25220, -1.50735, -1.67600, -1.80456, -1.95594, -2.08685, -2.09440, -1.92246, -1.88283, -1.87006, -1.70198, -1.58452, -1.51570, -1.45049, -1.37502, -1.32495, -1.24399, -1.15578, -1.15055, -1.12525, -1.19151, -1.24927, -1.33304, -1.43293, -1.39620, -1.19111, -0.96339, -0.94999, -0.90517, -0.71339, -0.46098, -0.26020, 0.04365, 0.37454, 0.57625, 0.72344, 0.89234, 1.05405, 1.03292, 1.05151, 1.09782, 1.13388, 1.13396, 1.01962, 1.00536, 1.09946, 1.08829, 0.88742, 0.78354, 0.77272, 0.75996, 0.85497, 0.86106, 0.81030, 0.75587, 0.84076, 1.06233, 1.32106, 1.42171, 1.30639, 1.18900, 1.20733, 1.30925, 1.33594, 1.20549, 1.03860, 0.81562, 0.57028, 0.21919, -0.08975, -0.23927, -0.16359, -0.09638, -0.13035, -0.01312, 0.03069, -0.05416, -0.07921, -0.12356, -0.28548, -0.39979, -0.44645, -0.65305, -0.85374, -0.99022, -0.98751, -0.93844, -1.01351, -1.11004, -1.10967, -1.10076, -1.26239, -1.33899, -1.29494, -1.30510, -1.31908, -1.33919, -1.29641, -1.52332, -1.78474, -1.98862, -2.15546, -2.44574, -2.56321, -2.52795, -2.49774, -2.40587, -2.49424, -2.67628, -2.81209, -2.86181, -2.94061, -3.03377, -3.13511, -3.31950, -3.29347, -3.12509, -2.91687, -2.79110, -2.78185, -2.79922, -2.69552, -2.40109, -2.27381, -2.26590, -2.23551, -2.14475, -2.03614, -2.11408, -2.14398, -2.18317, -2.14018, -2.14417, -2.13657, -2.13790, -2.10907, -2.10707, -2.21664, -2.19004, -2.16898, -2.17218, -2.08690, -2.02048, -2.05793, -2.04987, -1.92027, -1.96733, -2.12202, -2.26563, -2.27866, -2.19470, -2.07455, -1.82788, -1.57274, -1.33949, -1.25381, -1.11913, -0.88491, -0.71687, -0.48273, -0.28704, -0.09544, -0.15839, -0.19629, -0.15341, -0.03690, +-2.91424, -2.94788, -2.91794, -2.86974, -2.85961, -2.98030, -2.91829, -2.74111, -2.60412, -2.56303, -2.36523, -2.15234, -1.88987, -1.63560, -1.40696, -1.08635, -0.84368, -0.52699, -0.29832, -0.09488, 0.17680, 0.32343, 0.49459, 0.62827, 0.73332, 0.73646, 0.64260, 0.56130, 0.50126, 0.53499, 0.41539, 0.41270, 0.53202, 0.49185, 0.34709, 0.28423, 0.38627, 0.31512, 0.22784, 0.31738, 0.48423, 0.59241, 0.62991, 0.62731, 0.58203, 0.60206, 0.68597, 0.85445, 0.86016, 0.77637, 0.66863, 0.55023, 0.46962, 0.13118, -0.17528, -0.35594, -0.50133, -0.57617, -0.66427, -0.80215, -1.11610, -1.26161, -1.37142, -1.48166, -1.58983, -1.77568, -1.84827, -1.90419, -1.95327, -2.11732, -2.25116, -2.27278, -2.29964, -2.37312, -2.38949, -2.31715, -2.29344, -2.18501, -2.16685, -2.03511, -1.90790, -1.75914, -1.61463, -1.59538, -1.47907, -1.46535, -1.43201, -1.25013, -1.01793, -0.87491, -0.91685, -0.91571, -0.94405, -0.92381, -1.02426, -1.04250, -0.90778, -0.94877, -0.95358, -0.81225, -0.50123, -0.32945, -0.39692, -0.38787, -0.36273, -0.28607, -0.09989, 0.15314, 0.17607, 0.17621, 0.11388, 0.22915, 0.30600, 0.27140, 0.29487, 0.28665, 0.41424, 0.52075, 0.62286, 0.74384, 0.76447, 0.85171, 0.97290, 1.17724, 1.23682, 1.44432, 1.65804, 1.74720, 1.76333, 1.57039, 1.37189, 1.15202, 1.05342, 0.93911, 0.75602, 0.67534, 0.60257, 0.50710, 0.34176, 0.33516, 0.32443, 0.45295, 0.42358, 0.39651, 0.34464, 0.24598, 0.17794, 0.14161, 0.27112, 0.18652, -0.04715, -0.14044, -0.18575, -0.31457, -0.60406, -0.69308, -0.77025, -0.80726, -0.86626, -0.90021, -0.80393, -0.85106, -1.00127, -1.10160, -1.05718, -0.89360, -0.71778, -0.44829, -0.24142, -0.10735, 0.03750, 0.36517, 0.56380, 0.69966, 0.67533, 0.60409, 0.49272, 0.36248, 0.30981, 0.12462, 0.00649, -0.04609, -0.07440, -0.03972, -0.06475, -0.00357, 0.00846, 0.04517, -0.04367, -0.03919, 0.00293, -0.07552, -0.08290, -0.17890, -0.28779, -0.38287, -0.36565, -0.32588, -0.47135, -0.50661, -0.40658, -0.29780, -0.31833, -0.29764, -0.33183, -0.31138, -0.42398, -0.50307, -0.54008, -0.72361, -0.84457, -0.90103, -0.77332, -0.73500, -0.81864, -0.70118, -0.54085, -0.49166, -0.58725, -0.54442, -0.46888, -0.43060, -0.47043, -0.59974, -0.64299, -0.62764, -0.58211, -0.59753, -0.67303, -0.76172, -0.88116, -0.85126, -0.78596, -0.89020, -1.13244, -1.33445, -1.52843, -1.58067, -1.66501, -1.81578, -1.90471, -1.93775, -1.79643, -1.74429, -1.71711, -1.60742, -1.57160, -1.52876, -1.48103, -1.35157, -1.22511, -1.08683, -0.97571, -0.93249, -0.85380, -0.94734, -1.01567, -1.10115, -1.26515, -1.28955, -1.09702, -0.78820, -0.66962, -0.57777, -0.36752, -0.17371, -0.05912, 0.23075, 0.55899, 0.78091, 0.89621, 0.99267, 1.16678, 1.10905, 1.06724, 1.12506, 1.20271, 1.20826, 1.05665, 1.04740, 1.13207, 1.11176, 0.91910, 0.76927, 0.67330, 0.61202, 0.72638, 0.71208, 0.69555, 0.72512, 0.81145, 1.00352, 1.19406, 1.29865, 1.25488, 1.14902, 1.19857, 1.27902, 1.23302, 1.10481, 0.96404, 0.80667, 0.63007, 0.23936, -0.06193, -0.23942, -0.24172, -0.18353, -0.19497, -0.11501, -0.17799, -0.27422, -0.30254, -0.34511, -0.43401, -0.53169, -0.57383, -0.74294, -0.87950, -1.04931, -1.10208, -1.06105, -1.17098, -1.28533, -1.30135, -1.24653, -1.28549, -1.31383, -1.22437, -1.27424, -1.43712, -1.51736, -1.48177, -1.70131, -1.90940, -2.14691, -2.26800, -2.49814, -2.63341, -2.57462, -2.50609, -2.44459, -2.64623, -2.86134, -3.01286, -3.06492, -3.04867, -3.10043, -3.14526, -3.24549, -3.10627, -2.94675, -2.85892, -2.80231, -2.87554, -2.94027, -2.85289, -2.52975, -2.29478, -2.27477, -2.22547, -2.13426, -2.11382, -2.21586, -2.20893, -2.18510, -2.01364, -2.02237, -1.99361, -1.97781, -1.99628, -1.94969, -1.99346, -1.95886, -2.02351, -2.05403, -1.95198, -1.87686, -1.85412, -1.85825, -1.74426, -1.77747, -1.82992, -1.95154, -2.03572, -1.97961, -1.92568, -1.72434, -1.49422, -1.25932, -1.09006, -0.94231, -0.69495, -0.55058, -0.43682, -0.28952, -0.06912, -0.07083, 0.03031, 0.07970, 0.20455, +-3.05993, -3.09037, -2.96206, -2.92668, -2.93852, -2.97091, -2.87727, -2.78894, -2.69917, -2.63813, -2.41537, -2.10542, -1.81390, -1.60043, -1.39889, -1.09154, -0.77759, -0.52562, -0.28291, -0.06429, 0.02652, 0.20210, 0.46301, 0.55661, 0.66047, 0.75760, 0.66321, 0.55177, 0.58444, 0.58335, 0.42830, 0.40556, 0.40289, 0.36810, 0.33199, 0.26920, 0.32373, 0.34992, 0.37541, 0.41405, 0.50323, 0.54663, 0.49876, 0.50171, 0.44408, 0.40394, 0.47052, 0.62140, 0.71440, 0.66490, 0.60603, 0.58633, 0.34699, -0.00981, -0.19932, -0.41488, -0.60896, -0.65850, -0.80811, -1.06894, -1.36012, -1.55043, -1.66293, -1.69313, -1.83288, -1.97529, -1.93525, -1.97891, -2.10323, -2.24084, -2.32658, -2.39469, -2.45490, -2.49664, -2.46885, -2.27702, -2.16923, -2.10346, -2.12368, -2.09607, -2.01899, -1.94661, -1.85873, -1.68685, -1.61942, -1.57619, -1.40896, -1.27534, -1.10313, -0.91009, -0.97292, -1.07817, -1.02795, -0.96173, -1.04955, -0.99300, -0.91208, -0.92475, -0.76316, -0.55269, -0.33333, -0.21759, -0.30676, -0.39840, -0.46832, -0.41390, -0.23982, 0.06503, 0.17316, 0.18982, 0.15084, 0.23480, 0.30518, 0.26555, 0.26860, 0.42784, 0.48846, 0.53800, 0.75039, 0.83666, 0.76050, 0.86750, 1.01413, 1.13321, 1.27502, 1.53486, 1.71075, 1.87444, 1.86559, 1.65845, 1.56928, 1.44167, 1.28872, 1.15444, 1.00768, 0.88275, 0.73890, 0.61853, 0.42909, 0.39731, 0.36226, 0.38589, 0.31071, 0.26824, 0.24047, 0.17319, 0.02400, 0.10086, 0.18728, 0.03020, -0.10403, -0.18608, -0.26369, -0.30025, -0.49935, -0.68605, -0.76421, -0.75998, -0.84853, -0.82549, -0.78652, -0.93558, -1.02427, -1.00681, -0.97252, -0.80312, -0.56844, -0.33315, -0.19884, -0.06415, 0.08514, 0.41940, 0.62235, 0.69548, 0.68044, 0.62144, 0.52890, 0.44177, 0.29935, 0.19755, 0.02213, -0.16349, -0.10303, -0.05383, -0.17555, -0.13465, -0.09335, -0.13889, -0.18658, -0.06856, -0.01675, 0.03243, 0.06143, -0.10506, -0.16999, -0.17934, -0.21122, -0.21549, -0.31869, -0.39472, -0.40374, -0.33225, -0.32457, -0.24284, -0.21491, -0.24709, -0.43325, -0.57923, -0.63639, -0.76328, -0.97193, -0.93797, -0.76802, -0.81111, -0.78631, -0.62063, -0.56028, -0.49938, -0.47514, -0.46439, -0.40391, -0.32291, -0.41985, -0.48327, -0.49000, -0.55841, -0.50898, -0.47852, -0.60059, -0.72474, -0.79890, -0.78842, -0.87020, -1.03822, -1.22900, -1.37247, -1.49092, -1.55067, -1.64740, -1.78546, -1.86348, -1.81311, -1.72666, -1.62327, -1.53823, -1.55550, -1.46753, -1.34659, -1.36835, -1.25385, -1.03473, -0.90358, -0.82103, -0.70069, -0.63936, -0.66840, -0.66799, -0.82202, -0.97801, -0.96923, -0.85513, -0.64350, -0.46667, -0.29760, -0.14877, -0.00529, 0.09731, 0.35853, 0.71658, 0.89632, 0.89949, 0.94183, 1.09287, 1.11345, 1.02545, 1.06873, 1.20374, 1.12372, 1.08701, 1.22905, 1.25634, 1.15950, 1.00221, 0.80371, 0.61548, 0.59391, 0.64403, 0.61032, 0.67919, 0.69554, 0.81677, 1.08074, 1.20101, 1.20280, 1.20513, 1.14009, 1.08418, 1.08051, 1.04239, 0.92161, 0.83847, 0.71178, 0.49892, 0.12275, -0.16543, -0.28180, -0.31891, -0.29054, -0.19750, -0.23795, -0.30843, -0.30595, -0.41501, -0.52734, -0.52804, -0.56734, -0.62972, -0.67654, -0.79776, -1.02547, -1.07368, -1.15951, -1.30098, -1.30458, -1.29005, -1.29119, -1.28526, -1.23794, -1.18852, -1.31706, -1.53055, -1.65662, -1.59524, -1.78660, -2.06737, -2.33390, -2.46724, -2.59164, -2.65939, -2.63463, -2.47023, -2.54983, -2.80081, -2.89153, -3.05575, -3.14829, -3.06320, -3.07287, -3.14235, -3.10098, -2.90483, -2.80289, -2.73390, -2.80350, -2.94668, -2.96524, -2.88633, -2.67449, -2.44427, -2.37398, -2.37946, -2.35390, -2.33572, -2.41925, -2.32216, -2.20366, -2.03701, -2.00747, -1.95847, -1.89042, -1.86421, -1.87611, -1.80585, -1.84821, -1.95712, -1.82783, -1.69107, -1.65560, -1.60118, -1.61079, -1.61312, -1.60404, -1.57723, -1.69481, -1.70999, -1.71894, -1.76892, -1.54082, -1.27266, -1.14041, -1.02589, -0.83834, -0.62470, -0.55617, -0.49000, -0.38407, -0.14472, -0.04926, 0.06232, 0.11829, 0.20947, +-3.10199, -3.04697, -2.98806, -3.03871, -3.05445, -3.03937, -2.89360, -2.81725, -2.67959, -2.53649, -2.38765, -2.17254, -1.93716, -1.75879, -1.54000, -1.20885, -0.83615, -0.56196, -0.35506, -0.18438, -0.09768, 0.10606, 0.27497, 0.31651, 0.41884, 0.54389, 0.55968, 0.55045, 0.59214, 0.55362, 0.38903, 0.33482, 0.36624, 0.45980, 0.42042, 0.23222, 0.18918, 0.17735, 0.28656, 0.37053, 0.47220, 0.53558, 0.34276, 0.20125, 0.15624, 0.18226, 0.29772, 0.46035, 0.55325, 0.51039, 0.41635, 0.34908, 0.15240, -0.04218, -0.14893, -0.36216, -0.64299, -0.84099, -0.99767, -1.17547, -1.45653, -1.72483, -1.86252, -1.90606, -1.95514, -1.90838, -1.86394, -2.02043, -2.18626, -2.32798, -2.35922, -2.43214, -2.54244, -2.50948, -2.50985, -2.38107, -2.19033, -2.06565, -2.03208, -1.99173, -2.00450, -2.02417, -2.06872, -1.94517, -1.76828, -1.53260, -1.33517, -1.29598, -1.18289, -1.04116, -1.06479, -1.06579, -0.99356, -0.93735, -0.98700, -0.97539, -0.92075, -0.80700, -0.58269, -0.45061, -0.29500, -0.26153, -0.37425, -0.46709, -0.52916, -0.34073, -0.19563, -0.04618, 0.04810, 0.08771, 0.07183, 0.19438, 0.26951, 0.30618, 0.36778, 0.51446, 0.54781, 0.64402, 0.86027, 0.89190, 0.79131, 0.81430, 0.95602, 1.16083, 1.36241, 1.59133, 1.74676, 1.88419, 1.91233, 1.89926, 1.88512, 1.62565, 1.35448, 1.14450, 0.99392, 0.90777, 0.77952, 0.76008, 0.58468, 0.38508, 0.23984, 0.18161, 0.02426, 0.03024, 0.05092, 0.02979, -0.15831, -0.20131, -0.12661, -0.13555, -0.20520, -0.32262, -0.38814, -0.38612, -0.49216, -0.60188, -0.71207, -0.81119, -0.90559, -0.90105, -0.88646, -0.93039, -0.97156, -1.02475, -0.97058, -0.76417, -0.50674, -0.26917, -0.20565, -0.03127, 0.10171, 0.27407, 0.43756, 0.59097, 0.67640, 0.72636, 0.61227, 0.48789, 0.32029, 0.15213, -0.03186, -0.11989, -0.02897, -0.06177, -0.21295, -0.23991, -0.21177, -0.17361, -0.13814, -0.00711, 0.06085, 0.07589, 0.04773, -0.01834, -0.02856, -0.11615, -0.18153, -0.20611, -0.25916, -0.30408, -0.39480, -0.32317, -0.33888, -0.35040, -0.32742, -0.33165, -0.54678, -0.70342, -0.75349, -0.82598, -1.01382, -1.03302, -0.86971, -0.73826, -0.60358, -0.53450, -0.59530, -0.62544, -0.55629, -0.43549, -0.30896, -0.27309, -0.41521, -0.47758, -0.43921, -0.36441, -0.25870, -0.36941, -0.63874, -0.84718, -0.94606, -0.92136, -1.02621, -1.07927, -1.12569, -1.31786, -1.53980, -1.63205, -1.68965, -1.71768, -1.70486, -1.60223, -1.52299, -1.49778, -1.42851, -1.34651, -1.17728, -1.10593, -1.17530, -1.09879, -0.88859, -0.75170, -0.67444, -0.59652, -0.58793, -0.58997, -0.54357, -0.57877, -0.57932, -0.65329, -0.72411, -0.65096, -0.53798, -0.28545, -0.08692, 0.11269, 0.25112, 0.37355, 0.62536, 0.80906, 0.80820, 0.86485, 1.05074, 1.15573, 1.07791, 0.98620, 0.98970, 0.97268, 1.13746, 1.33479, 1.34275, 1.20555, 1.01923, 0.86386, 0.78352, 0.76949, 0.70350, 0.58211, 0.57515, 0.62357, 0.86024, 1.07034, 1.06282, 1.06490, 1.10447, 1.07585, 0.93620, 0.86889, 0.91038, 0.77120, 0.62869, 0.52970, 0.34578, 0.02626, -0.15541, -0.21162, -0.24265, -0.28678, -0.25315, -0.23654, -0.19634, -0.27943, -0.54278, -0.72003, -0.74965, -0.69145, -0.58605, -0.55489, -0.67265, -0.94732, -1.11215, -1.27964, -1.35095, -1.32025, -1.37475, -1.38805, -1.41162, -1.34298, -1.25240, -1.36784, -1.50699, -1.70395, -1.77091, -1.90928, -2.17553, -2.47968, -2.60616, -2.67181, -2.64429, -2.64605, -2.56895, -2.64642, -2.76407, -2.82003, -2.98056, -3.04644, -3.01389, -3.02050, -3.01196, -2.94387, -2.81112, -2.76406, -2.76122, -2.81157, -2.80034, -2.83508, -2.98747, -2.90847, -2.72282, -2.59688, -2.54185, -2.52915, -2.43066, -2.51897, -2.48622, -2.30573, -2.07326, -1.99251, -1.83828, -1.70128, -1.64902, -1.77757, -1.86843, -1.92729, -1.89352, -1.68145, -1.55004, -1.48519, -1.43686, -1.46404, -1.43419, -1.45721, -1.49740, -1.56937, -1.57164, -1.58301, -1.55678, -1.34856, -1.21099, -1.14533, -1.09347, -0.91390, -0.65526, -0.56398, -0.44610, -0.43027, -0.39438, -0.28812, -0.08334, 0.00844, 0.15682, +-3.05656, -2.99780, -2.97053, -3.05799, -3.08140, -3.05923, -2.94936, -2.87602, -2.73576, -2.60823, -2.46791, -2.28589, -2.08960, -1.87688, -1.69852, -1.48583, -1.20748, -0.85649, -0.47584, -0.29407, -0.24835, -0.07738, -0.04987, -0.02769, 0.13583, 0.27726, 0.37545, 0.44894, 0.46942, 0.50519, 0.41694, 0.33075, 0.41503, 0.52180, 0.48571, 0.23552, 0.12592, 0.05648, 0.12679, 0.22973, 0.36217, 0.41518, 0.19974, -0.00110, -0.07166, 0.00757, 0.10645, 0.17401, 0.18802, 0.17856, 0.23416, 0.15383, -0.06415, -0.18065, -0.27135, -0.44266, -0.66738, -0.92644, -1.07008, -1.16767, -1.44592, -1.69622, -1.78184, -1.90794, -1.89847, -1.83309, -1.79139, -2.00064, -2.20090, -2.34138, -2.37491, -2.44494, -2.53321, -2.51181, -2.53215, -2.47272, -2.30231, -2.10491, -1.99830, -1.99667, -2.09441, -2.16453, -2.13990, -2.02450, -1.83708, -1.53052, -1.36523, -1.38750, -1.24012, -1.12009, -1.10088, -1.01646, -0.96209, -0.88967, -0.82002, -0.90523, -0.83646, -0.74528, -0.51951, -0.41312, -0.27594, -0.23565, -0.35699, -0.47639, -0.50264, -0.32920, -0.22902, -0.14435, -0.08863, -0.01630, 0.00489, 0.04233, 0.07571, 0.14826, 0.40938, 0.62524, 0.61470, 0.70133, 0.87985, 0.87459, 0.85823, 0.85477, 0.98063, 1.22001, 1.40164, 1.58351, 1.82735, 1.86377, 1.92669, 1.96812, 1.99385, 1.70931, 1.40122, 1.17115, 0.97079, 0.79665, 0.67986, 0.66412, 0.51688, 0.30642, 0.09348, -0.01124, -0.20869, -0.30369, -0.30568, -0.35039, -0.42510, -0.45120, -0.44013, -0.41344, -0.45474, -0.60521, -0.57614, -0.49393, -0.52329, -0.56558, -0.70461, -0.91211, -0.91141, -0.96984, -0.93510, -0.92538, -0.94607, -1.02330, -0.96183, -0.74858, -0.52005, -0.34836, -0.29383, -0.14812, -0.05233, 0.06648, 0.20894, 0.43880, 0.65126, 0.69787, 0.56312, 0.37390, 0.32611, 0.26719, 0.06089, -0.02424, 0.04846, -0.09776, -0.21983, -0.24437, -0.22519, -0.15032, -0.09753, -0.01311, 0.17804, 0.15764, 0.11418, 0.08630, 0.04008, -0.13008, -0.22522, -0.23099, -0.22150, -0.26536, -0.36236, -0.33904, -0.44357, -0.49574, -0.47751, -0.46415, -0.64226, -0.87906, -0.97294, -1.06938, -1.10385, -0.98009, -0.84939, -0.66747, -0.49179, -0.54296, -0.63401, -0.68899, -0.62108, -0.43696, -0.25671, -0.25252, -0.29220, -0.35906, -0.33303, -0.22326, -0.17092, -0.36006, -0.70350, -0.94690, -1.06297, -1.09018, -1.16721, -1.13296, -1.12186, -1.27882, -1.50966, -1.60325, -1.56962, -1.55591, -1.52761, -1.46334, -1.30827, -1.18334, -1.17149, -1.10425, -0.92827, -0.98057, -1.06995, -0.96429, -0.77113, -0.62789, -0.55625, -0.56749, -0.55616, -0.58375, -0.57848, -0.52278, -0.45100, -0.51523, -0.65840, -0.66163, -0.61279, -0.38593, -0.14394, 0.10571, 0.20788, 0.27010, 0.47754, 0.66197, 0.73470, 0.78587, 0.90889, 1.00055, 0.98847, 0.98224, 0.89168, 0.83388, 1.08051, 1.27355, 1.34796, 1.33513, 1.17550, 1.05404, 1.01822, 0.91665, 0.79745, 0.64435, 0.49133, 0.54433, 0.74830, 0.91322, 0.86566, 0.90281, 0.98337, 0.95051, 0.79003, 0.73186, 0.76968, 0.66814, 0.55304, 0.46821, 0.35368, 0.05351, -0.18007, -0.26180, -0.26633, -0.21366, -0.22229, -0.23048, -0.15469, -0.31500, -0.64047, -0.77673, -0.86279, -0.81602, -0.63754, -0.59306, -0.63383, -0.81262, -1.10749, -1.30051, -1.42679, -1.38955, -1.44466, -1.44478, -1.48293, -1.45790, -1.37503, -1.43162, -1.56559, -1.78490, -1.88685, -1.99677, -2.20672, -2.51158, -2.74596, -2.83797, -2.76018, -2.60736, -2.49753, -2.56999, -2.62656, -2.70349, -2.88972, -2.89993, -2.90972, -2.93377, -2.90036, -2.87327, -2.80120, -2.71182, -2.82409, -2.82218, -2.78265, -2.81979, -3.04677, -3.01755, -2.83710, -2.68735, -2.61455, -2.55808, -2.47170, -2.58824, -2.57454, -2.37674, -2.08933, -1.97602, -1.88948, -1.75146, -1.70434, -1.73504, -1.83130, -1.95569, -1.93973, -1.77502, -1.68726, -1.50961, -1.38224, -1.37826, -1.32037, -1.39730, -1.52431, -1.47000, -1.51957, -1.50134, -1.49207, -1.33314, -1.24817, -1.19362, -1.14514, -0.99567, -0.77117, -0.61545, -0.51608, -0.58137, -0.64051, -0.55489, -0.28263, -0.11420, 0.00853, +-2.98047, -2.98173, -2.90085, -2.95665, -3.02142, -3.03640, -2.96754, -2.92854, -2.87697, -2.82071, -2.62491, -2.35717, -2.19615, -2.02344, -1.79427, -1.61423, -1.42278, -1.06700, -0.69688, -0.54142, -0.50869, -0.36066, -0.27586, -0.18285, 0.00913, 0.17151, 0.22669, 0.24696, 0.34546, 0.49328, 0.48904, 0.46416, 0.52494, 0.56145, 0.55836, 0.34303, 0.19762, 0.09443, 0.11567, 0.18506, 0.26855, 0.27041, 0.10918, -0.05247, -0.23840, -0.31906, -0.22219, -0.11034, -0.09298, -0.04641, 0.03466, -0.09888, -0.35057, -0.49877, -0.52867, -0.57710, -0.69806, -0.86930, -1.03075, -1.21603, -1.43971, -1.59365, -1.62107, -1.70375, -1.74492, -1.78592, -1.71753, -1.87324, -2.10748, -2.25695, -2.29274, -2.31746, -2.35260, -2.37542, -2.38629, -2.33938, -2.29502, -2.21825, -2.05441, -1.95622, -2.05188, -2.11730, -2.08890, -2.04159, -1.87060, -1.58177, -1.38029, -1.30336, -1.13335, -1.00093, -1.01318, -1.05528, -0.98615, -0.82917, -0.69858, -0.71998, -0.64842, -0.64768, -0.41695, -0.24395, -0.11778, -0.05719, -0.17067, -0.32214, -0.39810, -0.38138, -0.32779, -0.18146, -0.14448, -0.15676, -0.08660, 0.02116, 0.01624, 0.05186, 0.30964, 0.45833, 0.47565, 0.58221, 0.78754, 0.89510, 0.91503, 0.93153, 1.03496, 1.11352, 1.24869, 1.47602, 1.76419, 1.83864, 1.89076, 1.85174, 1.90715, 1.78385, 1.55394, 1.34390, 1.10442, 0.81614, 0.62547, 0.51169, 0.36789, 0.25334, 0.02201, -0.23438, -0.44690, -0.48632, -0.50835, -0.57522, -0.64076, -0.74719, -0.77274, -0.77468, -0.79442, -0.81144, -0.70923, -0.55044, -0.53163, -0.66870, -0.80598, -0.93868, -0.88188, -0.88200, -0.82906, -0.88321, -0.91506, -0.92706, -0.89498, -0.75599, -0.58148, -0.44982, -0.38359, -0.28619, -0.19799, -0.01266, 0.10585, 0.18434, 0.39168, 0.55269, 0.50378, 0.36032, 0.34901, 0.23780, 0.00210, -0.11460, -0.04481, -0.10379, -0.20497, -0.20207, -0.16568, -0.22841, -0.24184, -0.10623, 0.16443, 0.27677, 0.32935, 0.25257, 0.14458, -0.02384, -0.13954, -0.14550, -0.11823, -0.16773, -0.27361, -0.34456, -0.51208, -0.52103, -0.50040, -0.62050, -0.83690, -0.99806, -1.06304, -1.15259, -1.13190, -1.02679, -0.92190, -0.75404, -0.57074, -0.52242, -0.55523, -0.58272, -0.51008, -0.43565, -0.30734, -0.21631, -0.16465, -0.17815, -0.16613, -0.19658, -0.25001, -0.38656, -0.67069, -0.88060, -0.98578, -1.04673, -1.15241, -1.18476, -1.20494, -1.25489, -1.36285, -1.49854, -1.49283, -1.38561, -1.30455, -1.24459, -1.06226, -0.98828, -1.06557, -1.04471, -0.89197, -0.90512, -0.96317, -0.84314, -0.63096, -0.52207, -0.50214, -0.48726, -0.46135, -0.52257, -0.52359, -0.50669, -0.47174, -0.45145, -0.53312, -0.54498, -0.50617, -0.31067, -0.08137, 0.12610, 0.16726, 0.26461, 0.50680, 0.59327, 0.58581, 0.69355, 0.85982, 0.94190, 0.95409, 0.93700, 0.78679, 0.71303, 0.97217, 1.26811, 1.49696, 1.60256, 1.51135, 1.33308, 1.13374, 0.96500, 0.84574, 0.69021, 0.54643, 0.54873, 0.63562, 0.79420, 0.76584, 0.77302, 0.85242, 0.83678, 0.73187, 0.69057, 0.67599, 0.63125, 0.60315, 0.47485, 0.28290, 0.02394, -0.17177, -0.26888, -0.26574, -0.24797, -0.36095, -0.39861, -0.30731, -0.33427, -0.49250, -0.58173, -0.69367, -0.77169, -0.75921, -0.69662, -0.62985, -0.72641, -0.96413, -1.17274, -1.39202, -1.33551, -1.31053, -1.31293, -1.36082, -1.37149, -1.32994, -1.41548, -1.63154, -1.83686, -1.87273, -2.02118, -2.33230, -2.58275, -2.72495, -2.80129, -2.69688, -2.51831, -2.44827, -2.48929, -2.53442, -2.57450, -2.69040, -2.73173, -2.74847, -2.80031, -2.88987, -2.85603, -2.73915, -2.65573, -2.78488, -2.83164, -2.90079, -2.90278, -2.98427, -2.92416, -2.74148, -2.59725, -2.54363, -2.49009, -2.48410, -2.62472, -2.56896, -2.40542, -2.25753, -2.16064, -2.02167, -1.88365, -1.79670, -1.73312, -1.85694, -2.00612, -2.06637, -1.95093, -1.76068, -1.51812, -1.31050, -1.26745, -1.32932, -1.41479, -1.47361, -1.36930, -1.36435, -1.33964, -1.43052, -1.30244, -1.14956, -1.09730, -1.06059, -0.93741, -0.76143, -0.62045, -0.61167, -0.70035, -0.69125, -0.60874, -0.45787, -0.27447, -0.03008, +-2.87143, -2.91221, -2.87304, -2.93739, -3.02778, -3.11302, -3.11975, -3.13362, -3.08982, -2.92501, -2.74675, -2.52114, -2.31549, -2.10764, -1.81804, -1.69583, -1.51071, -1.19578, -0.93770, -0.75049, -0.67042, -0.54901, -0.49531, -0.42090, -0.19550, -0.02878, 0.03500, 0.12858, 0.32819, 0.45902, 0.39754, 0.46450, 0.61185, 0.61853, 0.53186, 0.31630, 0.16509, 0.10620, 0.09429, 0.09258, 0.06931, 0.12884, -0.00030, -0.23330, -0.43128, -0.52954, -0.41839, -0.32733, -0.27565, -0.18178, -0.16026, -0.19901, -0.37922, -0.58628, -0.69533, -0.74901, -0.74199, -0.80987, -0.99737, -1.17697, -1.30026, -1.40161, -1.49770, -1.51631, -1.54616, -1.64967, -1.70483, -1.84742, -2.04832, -2.11426, -2.17419, -2.17289, -2.20956, -2.13547, -2.12390, -2.21496, -2.24071, -2.18632, -2.02962, -1.96365, -2.04302, -2.02791, -2.06692, -1.96509, -1.76347, -1.52609, -1.35512, -1.27411, -1.09068, -0.95764, -1.03893, -1.08994, -0.96622, -0.77404, -0.73747, -0.68187, -0.53248, -0.44731, -0.30446, -0.16007, -0.10927, 0.00944, -0.10193, -0.25051, -0.39446, -0.35296, -0.29634, -0.25951, -0.22927, -0.20643, -0.08793, 0.05143, 0.02147, 0.07434, 0.16969, 0.33634, 0.46226, 0.58310, 0.70473, 0.76337, 0.81989, 0.91301, 0.96929, 0.99981, 1.11227, 1.33632, 1.48719, 1.60208, 1.75259, 1.81893, 1.80189, 1.74522, 1.55044, 1.44041, 1.16876, 0.82827, 0.52431, 0.42126, 0.27951, 0.03218, -0.21681, -0.44893, -0.63705, -0.67760, -0.78338, -0.79854, -0.93653, -1.01114, -0.99841, -1.04505, -1.14046, -1.16853, -1.01267, -0.74393, -0.71994, -0.84133, -0.89647, -0.87239, -0.88681, -0.90412, -0.85060, -0.82717, -0.93249, -0.95734, -0.97281, -0.80359, -0.69098, -0.58452, -0.56297, -0.42064, -0.24622, -0.12308, -0.03672, 0.01662, 0.20587, 0.42743, 0.41153, 0.39570, 0.28636, 0.14977, 0.00508, -0.08144, -0.07797, -0.19138, -0.31612, -0.26214, -0.26282, -0.35496, -0.30182, -0.05096, 0.14993, 0.29315, 0.44713, 0.49412, 0.31137, 0.08661, -0.08652, -0.05157, -0.08815, -0.19001, -0.33550, -0.39951, -0.49685, -0.60652, -0.67856, -0.80996, -0.98382, -1.07111, -1.19402, -1.22988, -1.26114, -1.16628, -0.96009, -0.75809, -0.63147, -0.61123, -0.59560, -0.47734, -0.41417, -0.43889, -0.33632, -0.12609, -0.08764, -0.13672, -0.08770, -0.06610, -0.21757, -0.40361, -0.67309, -0.80231, -0.88125, -0.94418, -1.07827, -1.15476, -1.11452, -1.16697, -1.25107, -1.33611, -1.33529, -1.18123, -1.11245, -0.98039, -0.83616, -0.84759, -0.89307, -0.88196, -0.83038, -0.90136, -0.91924, -0.71035, -0.49854, -0.42803, -0.38073, -0.27565, -0.30709, -0.49587, -0.48827, -0.41265, -0.46449, -0.52667, -0.57265, -0.52585, -0.44765, -0.30647, -0.12612, 0.04801, 0.20797, 0.29904, 0.42084, 0.45364, 0.42802, 0.58410, 0.73380, 0.84417, 0.85348, 0.77435, 0.75917, 0.80907, 1.03103, 1.25875, 1.50605, 1.76076, 1.76165, 1.54578, 1.32723, 1.18936, 1.00700, 0.70865, 0.58134, 0.62232, 0.66209, 0.71817, 0.68163, 0.65092, 0.74384, 0.72507, 0.68481, 0.63164, 0.68060, 0.65522, 0.57818, 0.47567, 0.29942, 0.06890, -0.17235, -0.30149, -0.30664, -0.37798, -0.36956, -0.32759, -0.25775, -0.28093, -0.37779, -0.36805, -0.45146, -0.64952, -0.70345, -0.60959, -0.57180, -0.78423, -0.93361, -1.04597, -1.22970, -1.29303, -1.26960, -1.27718, -1.23776, -1.30074, -1.32346, -1.51927, -1.69283, -1.86600, -1.99619, -2.16435, -2.46645, -2.65490, -2.71086, -2.72415, -2.56776, -2.52845, -2.40136, -2.31542, -2.33540, -2.42332, -2.55415, -2.57044, -2.55659, -2.67962, -2.79581, -2.71676, -2.57613, -2.63065, -2.76633, -2.82751, -2.88715, -2.95990, -2.95415, -2.89716, -2.67054, -2.56641, -2.49608, -2.49070, -2.44807, -2.57389, -2.67408, -2.59197, -2.49477, -2.37745, -2.16672, -2.04381, -1.86852, -1.86134, -1.89986, -1.94467, -2.03013, -2.02871, -1.88256, -1.60509, -1.35062, -1.34338, -1.39301, -1.39741, -1.36852, -1.39490, -1.38941, -1.30652, -1.29019, -1.27154, -1.15670, -1.17150, -1.08032, -0.99316, -0.83762, -0.77917, -0.76257, -0.78388, -0.81010, -0.71368, -0.58460, -0.42879, -0.13427, +-3.00944, -3.06565, -3.00917, -3.03240, -3.13118, -3.29592, -3.35637, -3.38718, -3.31432, -3.07570, -2.83111, -2.60163, -2.39654, -2.14165, -1.85859, -1.76314, -1.61398, -1.36278, -1.17176, -1.04818, -0.96301, -0.79570, -0.64400, -0.54435, -0.44978, -0.36320, -0.14925, 0.14585, 0.33000, 0.37110, 0.30718, 0.44824, 0.61456, 0.57248, 0.46483, 0.28043, 0.10611, 0.04946, 0.03840, -0.02928, -0.19035, -0.19611, -0.25441, -0.42183, -0.56825, -0.56417, -0.45864, -0.46090, -0.46400, -0.41370, -0.37874, -0.35466, -0.47118, -0.66761, -0.78129, -0.80732, -0.84444, -0.97664, -1.11344, -1.14761, -1.22456, -1.32831, -1.42616, -1.39386, -1.39586, -1.58241, -1.72545, -1.85271, -2.00213, -2.04367, -2.09672, -2.09473, -2.18588, -2.09396, -1.99337, -1.99022, -2.00195, -1.92660, -1.86292, -1.96125, -2.05390, -2.01441, -2.01441, -1.90487, -1.76414, -1.57351, -1.35541, -1.19126, -1.10110, -1.12208, -1.16807, -1.01146, -0.85612, -0.74238, -0.74913, -0.66132, -0.47380, -0.36025, -0.25901, -0.17310, -0.23857, -0.19609, -0.26928, -0.34828, -0.47997, -0.38937, -0.28206, -0.20606, -0.18718, -0.12372, -0.00027, 0.07097, 0.04673, 0.03934, 0.03466, 0.17290, 0.28101, 0.36680, 0.43749, 0.52723, 0.57495, 0.59613, 0.65989, 0.87121, 1.02529, 1.13198, 1.17174, 1.28861, 1.53996, 1.65047, 1.61502, 1.56992, 1.35633, 1.24665, 1.01717, 0.76773, 0.45505, 0.32914, 0.14579, -0.10597, -0.32345, -0.45973, -0.61932, -0.80945, -1.03914, -1.14396, -1.28246, -1.31195, -1.34532, -1.45585, -1.55634, -1.45950, -1.26777, -1.07124, -1.01521, -0.91390, -0.83702, -0.76485, -0.81829, -0.90817, -0.92714, -0.95917, -1.08476, -1.09407, -1.10370, -0.93479, -0.85048, -0.73930, -0.75747, -0.63811, -0.42349, -0.19955, -0.04293, 0.05650, 0.21458, 0.33453, 0.28396, 0.21156, 0.01789, -0.12559, -0.23398, -0.29588, -0.31397, -0.32314, -0.39743, -0.45915, -0.52039, -0.44682, -0.22580, 0.02592, 0.15836, 0.24010, 0.38526, 0.44972, 0.27680, 0.10956, -0.05972, -0.07360, -0.21881, -0.34355, -0.45082, -0.47589, -0.52644, -0.62842, -0.74766, -0.86184, -0.96975, -1.11523, -1.34789, -1.48026, -1.53901, -1.38031, -1.13071, -0.93222, -0.82165, -0.69957, -0.57086, -0.43306, -0.41507, -0.40467, -0.29236, -0.12568, -0.11129, -0.18485, -0.10295, -0.05428, -0.25658, -0.45655, -0.72071, -0.86038, -0.94141, -0.92984, -0.98447, -1.07266, -1.04740, -1.04276, -1.07740, -1.13328, -1.14480, -1.07164, -1.04921, -0.94911, -0.86352, -0.83370, -0.82782, -0.85933, -0.89529, -0.90866, -0.79403, -0.62168, -0.49687, -0.40810, -0.27918, -0.17376, -0.23673, -0.43830, -0.43680, -0.39117, -0.57224, -0.68365, -0.65324, -0.55460, -0.46388, -0.33909, -0.16518, -0.00432, 0.21938, 0.35638, 0.43265, 0.41107, 0.40355, 0.53003, 0.59681, 0.64353, 0.60203, 0.55853, 0.66654, 0.81876, 1.01372, 1.22449, 1.50837, 1.76852, 1.78126, 1.65530, 1.61840, 1.51710, 1.23658, 0.83563, 0.63941, 0.62375, 0.57749, 0.61040, 0.62407, 0.54614, 0.55848, 0.54355, 0.56249, 0.48528, 0.51201, 0.53683, 0.55672, 0.50719, 0.38254, 0.17623, -0.13627, -0.36343, -0.48989, -0.55368, -0.41078, -0.32553, -0.28572, -0.31481, -0.31082, -0.26350, -0.36722, -0.51604, -0.44819, -0.38760, -0.52315, -0.82232, -0.91844, -0.95984, -1.15802, -1.30206, -1.28628, -1.29849, -1.23897, -1.31084, -1.36087, -1.63542, -1.80492, -1.91847, -1.99898, -2.18560, -2.45649, -2.62922, -2.69068, -2.66616, -2.60269, -2.66403, -2.53746, -2.39295, -2.34998, -2.39172, -2.36146, -2.32727, -2.41524, -2.56852, -2.57567, -2.50599, -2.47184, -2.58574, -2.72211, -2.81975, -2.95863, -3.07065, -3.01630, -2.98688, -2.82742, -2.72654, -2.56285, -2.55499, -2.52086, -2.57640, -2.62706, -2.62749, -2.58679, -2.47148, -2.28197, -2.18530, -2.09608, -2.16315, -2.14248, -2.10982, -2.14144, -2.12397, -1.89548, -1.62687, -1.53490, -1.53630, -1.35502, -1.23156, -1.23911, -1.37127, -1.41005, -1.29838, -1.25449, -1.29465, -1.21432, -1.26928, -1.17874, -1.07625, -0.88065, -0.87264, -0.89785, -0.88187, -0.77872, -0.63937, -0.54940, -0.48442, -0.32143, +-3.32794, -3.28773, -3.21481, -3.22915, -3.24639, -3.37084, -3.47986, -3.55743, -3.41368, -3.18949, -3.00341, -2.74690, -2.55965, -2.33353, -2.04161, -1.81639, -1.68015, -1.50437, -1.32488, -1.25263, -1.08336, -0.88851, -0.78195, -0.65202, -0.60917, -0.48385, -0.21360, 0.07069, 0.24192, 0.24907, 0.36531, 0.55188, 0.59480, 0.62309, 0.56053, 0.34319, 0.17283, 0.08660, 0.01375, -0.15366, -0.29932, -0.37327, -0.51745, -0.64213, -0.73571, -0.72596, -0.61343, -0.53999, -0.55132, -0.58998, -0.51186, -0.51139, -0.54773, -0.71022, -0.92259, -0.95116, -1.02501, -1.14635, -1.22754, -1.28285, -1.30588, -1.42020, -1.38035, -1.28492, -1.33900, -1.46735, -1.58758, -1.81924, -1.97188, -2.03483, -2.07758, -2.14549, -2.19050, -2.07216, -2.00300, -1.92581, -1.86816, -1.83941, -1.80689, -1.83353, -1.85059, -1.88335, -1.82961, -1.79487, -1.68134, -1.49865, -1.38419, -1.24439, -1.18838, -1.21178, -1.13001, -0.94196, -0.73472, -0.70045, -0.62446, -0.49150, -0.44414, -0.35534, -0.23236, -0.28015, -0.37413, -0.38526, -0.41152, -0.50488, -0.53516, -0.36977, -0.31875, -0.25415, -0.20211, -0.19228, -0.07711, 0.05587, 0.12452, -0.00490, -0.03366, -0.00178, 0.05220, 0.13626, 0.09851, 0.15415, 0.22565, 0.24703, 0.38922, 0.60557, 0.87161, 0.90966, 0.97848, 1.13510, 1.25901, 1.34045, 1.41476, 1.28557, 1.07626, 0.95693, 0.80236, 0.57392, 0.36400, 0.32178, 0.08716, -0.16615, -0.29543, -0.45639, -0.63668, -0.85492, -1.06792, -1.33772, -1.48314, -1.57134, -1.64604, -1.70685, -1.82810, -1.70345, -1.44430, -1.24332, -1.06283, -0.93424, -0.77539, -0.74655, -0.77528, -0.79293, -0.95157, -1.09454, -1.11889, -1.19827, -1.21328, -1.08408, -0.99910, -0.96534, -0.97576, -0.78771, -0.60753, -0.39191, -0.12451, -0.03540, 0.08184, 0.18954, 0.21561, 0.01530, -0.20686, -0.39574, -0.52989, -0.52392, -0.60428, -0.60581, -0.53285, -0.58373, -0.56717, -0.50975, -0.26351, -0.07538, 0.05366, 0.19991, 0.21613, 0.16703, 0.13067, -0.01846, -0.16971, -0.20960, -0.34142, -0.46932, -0.49839, -0.38373, -0.44795, -0.63351, -0.73294, -0.88649, -1.03332, -1.21206, -1.38535, -1.61742, -1.66673, -1.47586, -1.25126, -0.98823, -0.90337, -0.80477, -0.56215, -0.40043, -0.32101, -0.33167, -0.26924, -0.18272, -0.18627, -0.15669, -0.15284, -0.24085, -0.35652, -0.56013, -0.83889, -0.97499, -1.01957, -0.98571, -0.97091, -0.92910, -0.93279, -1.00254, -0.99792, -1.06389, -1.12621, -1.08817, -0.97810, -0.94183, -0.92500, -0.82097, -0.76003, -0.71587, -0.80462, -0.92512, -0.76447, -0.60837, -0.45685, -0.39661, -0.32851, -0.24654, -0.31798, -0.36388, -0.39918, -0.51228, -0.62892, -0.68870, -0.64625, -0.50034, -0.37528, -0.25238, -0.07886, 0.18792, 0.39767, 0.42170, 0.47285, 0.42571, 0.38089, 0.48841, 0.61808, 0.62909, 0.51005, 0.51640, 0.62530, 0.85268, 1.02885, 1.14444, 1.46445, 1.74926, 1.85890, 1.80622, 1.76481, 1.68559, 1.34021, 1.02107, 0.75633, 0.53131, 0.47432, 0.52863, 0.49360, 0.41196, 0.37731, 0.35932, 0.35852, 0.38296, 0.42755, 0.39293, 0.46416, 0.46888, 0.32036, 0.18719, 0.02722, -0.19604, -0.48440, -0.56551, -0.47520, -0.35477, -0.31080, -0.44680, -0.40140, -0.28934, -0.30511, -0.35327, -0.33578, -0.28458, -0.52014, -0.71279, -0.76275, -0.92585, -1.11396, -1.22029, -1.28739, -1.28020, -1.24028, -1.30031, -1.40158, -1.58942, -1.68857, -1.85510, -1.94522, -2.11660, -2.45358, -2.64441, -2.64037, -2.57760, -2.68646, -2.75883, -2.69820, -2.50737, -2.36185, -2.42210, -2.31349, -2.20556, -2.29134, -2.39994, -2.50183, -2.45895, -2.56092, -2.62497, -2.70463, -2.94930, -3.13925, -3.17308, -3.19064, -3.14469, -3.01976, -2.87626, -2.71798, -2.62500, -2.52204, -2.55636, -2.56226, -2.55594, -2.65134, -2.63398, -2.44731, -2.29568, -2.36269, -2.44796, -2.45823, -2.37899, -2.29213, -2.29191, -2.05434, -1.73174, -1.62948, -1.49057, -1.28449, -1.08002, -1.15472, -1.25984, -1.22905, -1.24195, -1.27733, -1.24254, -1.23597, -1.24304, -1.11119, -0.93579, -0.77844, -0.74689, -0.72763, -0.78262, -0.72293, -0.56994, -0.59975, -0.61957, -0.48186, +-3.46266, -3.32843, -3.26896, -3.28065, -3.21096, -3.25916, -3.38483, -3.51378, -3.49455, -3.38308, -3.18752, -2.87541, -2.61749, -2.35373, -2.14107, -1.96311, -1.76980, -1.56792, -1.38606, -1.27108, -1.12137, -0.99621, -0.90252, -0.75801, -0.74399, -0.62127, -0.37756, -0.15140, 0.09138, 0.21324, 0.34894, 0.48466, 0.58208, 0.76003, 0.74450, 0.53153, 0.36764, 0.23629, 0.06614, -0.17703, -0.38197, -0.55970, -0.71938, -0.80194, -0.84228, -0.81398, -0.77387, -0.74529, -0.67502, -0.62723, -0.51947, -0.51884, -0.60639, -0.86314, -1.10743, -1.13100, -1.22751, -1.35704, -1.42848, -1.50940, -1.45029, -1.42853, -1.37721, -1.33851, -1.28920, -1.22712, -1.33418, -1.64678, -1.87711, -1.98009, -2.03822, -2.13416, -2.18193, -2.13523, -2.06187, -1.93939, -1.84255, -1.77849, -1.76115, -1.78075, -1.68721, -1.64412, -1.60081, -1.61632, -1.58430, -1.53890, -1.49972, -1.39473, -1.36949, -1.39187, -1.23965, -1.04454, -0.77340, -0.61225, -0.52702, -0.50629, -0.49670, -0.34238, -0.26288, -0.36723, -0.43958, -0.41281, -0.40516, -0.50401, -0.53265, -0.48827, -0.48315, -0.38947, -0.29960, -0.23741, -0.13322, -0.07070, 0.04893, -0.00611, -0.05567, -0.07965, -0.08875, -0.13014, -0.21268, -0.16283, -0.11255, -0.12844, 0.02738, 0.23173, 0.60267, 0.80879, 0.89806, 0.91095, 0.93643, 1.12076, 1.24871, 1.10711, 0.93163, 0.84405, 0.71341, 0.46625, 0.27974, 0.18045, -0.01820, -0.15697, -0.21864, -0.35552, -0.57897, -0.92971, -1.14739, -1.35802, -1.52908, -1.66229, -1.76674, -1.91476, -2.03209, -1.87158, -1.59798, -1.40821, -1.17394, -1.05794, -0.87564, -0.74924, -0.76320, -0.85117, -1.01893, -1.01690, -0.97013, -1.09575, -1.16571, -1.11466, -1.08602, -1.12158, -1.14773, -1.03300, -0.86760, -0.60578, -0.28536, -0.14351, -0.02774, -0.00751, 0.05732, -0.03269, -0.23611, -0.46069, -0.65080, -0.77618, -0.92530, -0.89907, -0.73434, -0.76277, -0.70599, -0.70898, -0.53163, -0.26745, -0.09522, -0.02317, -0.06650, -0.02577, 0.01049, -0.16840, -0.33545, -0.36794, -0.43832, -0.50276, -0.47515, -0.40139, -0.49986, -0.67229, -0.74505, -0.86765, -1.03451, -1.33274, -1.51933, -1.65475, -1.65265, -1.46579, -1.26943, -1.09268, -1.04384, -0.92119, -0.63236, -0.50102, -0.41179, -0.43186, -0.38938, -0.21779, -0.16771, -0.21781, -0.33670, -0.41054, -0.44609, -0.63802, -0.89939, -0.99368, -0.99733, -0.96419, -0.93759, -0.92809, -0.97925, -1.02661, -0.96315, -0.96318, -0.99864, -1.05429, -0.99089, -0.89639, -0.85273, -0.70710, -0.57621, -0.56623, -0.72554, -0.91142, -0.80212, -0.69474, -0.54266, -0.48819, -0.44630, -0.28888, -0.28153, -0.37433, -0.50970, -0.57964, -0.53092, -0.51065, -0.45535, -0.29119, -0.13571, -0.00333, 0.18407, 0.42581, 0.53483, 0.51333, 0.56177, 0.53551, 0.50889, 0.52657, 0.59008, 0.67667, 0.63121, 0.64933, 0.73322, 0.85934, 0.92520, 1.03123, 1.38815, 1.67888, 1.81732, 1.78743, 1.69420, 1.64576, 1.39899, 1.07666, 0.71185, 0.48502, 0.50914, 0.52455, 0.42094, 0.31746, 0.27525, 0.26005, 0.27369, 0.32506, 0.32332, 0.29497, 0.40141, 0.45603, 0.36999, 0.26822, 0.13889, 0.00260, -0.24659, -0.41398, -0.43828, -0.41005, -0.47332, -0.61078, -0.51088, -0.37699, -0.37977, -0.42018, -0.46631, -0.38118, -0.46580, -0.60422, -0.75200, -0.93049, -1.00334, -1.10163, -1.20512, -1.19459, -1.15529, -1.21102, -1.31943, -1.47745, -1.63140, -1.81318, -1.88844, -2.03143, -2.33512, -2.58088, -2.69881, -2.65307, -2.72619, -2.79705, -2.74676, -2.56387, -2.46968, -2.49831, -2.35461, -2.26415, -2.37730, -2.47711, -2.64684, -2.60768, -2.63133, -2.70981, -2.89987, -3.15644, -3.20059, -3.17416, -3.19715, -3.12499, -2.97984, -2.82809, -2.70060, -2.59960, -2.56548, -2.54999, -2.45588, -2.41668, -2.52199, -2.63831, -2.65023, -2.50075, -2.48450, -2.54242, -2.54936, -2.48375, -2.48699, -2.50640, -2.24564, -1.88938, -1.72224, -1.46076, -1.25754, -1.02038, -0.96926, -1.03977, -1.09771, -1.16018, -1.10318, -1.03154, -1.04202, -0.99612, -0.79716, -0.58644, -0.46233, -0.43278, -0.51275, -0.63403, -0.61570, -0.51811, -0.55737, -0.59616, -0.55462, +-3.41349, -3.40726, -3.37060, -3.35037, -3.22676, -3.15993, -3.30256, -3.39394, -3.39456, -3.39015, -3.18617, -2.87871, -2.62363, -2.28079, -2.05160, -1.92793, -1.83163, -1.73218, -1.56597, -1.43041, -1.25832, -1.06404, -0.93272, -0.88073, -0.91262, -0.77327, -0.45597, -0.24354, -0.05575, 0.09276, 0.11012, 0.27045, 0.49120, 0.63444, 0.69895, 0.60805, 0.42087, 0.26088, -0.03735, -0.30471, -0.47677, -0.68052, -0.77817, -0.82219, -0.90783, -0.88413, -0.85927, -0.86394, -0.80227, -0.75602, -0.59394, -0.59056, -0.73032, -0.94420, -1.14657, -1.22775, -1.31562, -1.39352, -1.43971, -1.55391, -1.58933, -1.50937, -1.53308, -1.43904, -1.17154, -1.08515, -1.22226, -1.46372, -1.77899, -1.91486, -2.06429, -2.17887, -2.12439, -2.07634, -1.95682, -1.81797, -1.84663, -1.82771, -1.78828, -1.77255, -1.62653, -1.61374, -1.58492, -1.66379, -1.74437, -1.69581, -1.59607, -1.52783, -1.56163, -1.55995, -1.37681, -1.16891, -0.99437, -0.74803, -0.67433, -0.64802, -0.54970, -0.50633, -0.56953, -0.58675, -0.62980, -0.47928, -0.42463, -0.49783, -0.46249, -0.51032, -0.55414, -0.43795, -0.41674, -0.35138, -0.18043, -0.12952, -0.01296, -0.09898, -0.15212, -0.17801, -0.21547, -0.22896, -0.28789, -0.32543, -0.39240, -0.41205, -0.23792, 0.04408, 0.39411, 0.72008, 0.78478, 0.77421, 0.87931, 1.01776, 1.00382, 0.94258, 0.81740, 0.81488, 0.70157, 0.40858, 0.22979, 0.07528, -0.10860, -0.11909, -0.18843, -0.37172, -0.58333, -1.00448, -1.26704, -1.51452, -1.65116, -1.73500, -1.89141, -2.03880, -2.11010, -1.99489, -1.82121, -1.59844, -1.28300, -1.07722, -1.01781, -0.91740, -0.98855, -1.09508, -1.06389, -0.91792, -0.92540, -0.98201, -1.10695, -1.13525, -1.19220, -1.32057, -1.32643, -1.22217, -1.04601, -0.70332, -0.41020, -0.30709, -0.13525, -0.08412, 0.05405, -0.01833, -0.24486, -0.50830, -0.82685, -1.01884, -1.13638, -1.10129, -0.95757, -0.93438, -0.82785, -0.72717, -0.68779, -0.47959, -0.36449, -0.36055, -0.23558, -0.08188, -0.15706, -0.34076, -0.57738, -0.64549, -0.68278, -0.70900, -0.57794, -0.48392, -0.60515, -0.73411, -0.84536, -1.01789, -1.09236, -1.35336, -1.55744, -1.72961, -1.77738, -1.61947, -1.50996, -1.33706, -1.15203, -0.97450, -0.77433, -0.70671, -0.61181, -0.51654, -0.50838, -0.32038, -0.23946, -0.37412, -0.42674, -0.44398, -0.60862, -0.76835, -0.98113, -1.04023, -0.98298, -0.99227, -0.94199, -0.91645, -0.99079, -0.93801, -0.81067, -0.84139, -0.84147, -0.92106, -0.92624, -0.87592, -0.86248, -0.66636, -0.50482, -0.49149, -0.55966, -0.69614, -0.72251, -0.70547, -0.56689, -0.40308, -0.33196, -0.19003, -0.14216, -0.36569, -0.49858, -0.48363, -0.50731, -0.42583, -0.29202, -0.13984, 0.05318, 0.13255, 0.33739, 0.62537, 0.73236, 0.76077, 0.77468, 0.63555, 0.58575, 0.56971, 0.57156, 0.68861, 0.69527, 0.74000, 0.73965, 0.71620, 0.79217, 0.95406, 1.25750, 1.53058, 1.72480, 1.79212, 1.67962, 1.51932, 1.31851, 0.94418, 0.65096, 0.57380, 0.51166, 0.43697, 0.34071, 0.17808, 0.16729, 0.15571, 0.24640, 0.38324, 0.35420, 0.33513, 0.42675, 0.41786, 0.38829, 0.39899, 0.33529, 0.23581, -0.02500, -0.20774, -0.36043, -0.50209, -0.58651, -0.63588, -0.52384, -0.41178, -0.36839, -0.39756, -0.49505, -0.54226, -0.55484, -0.70344, -0.82215, -0.87834, -1.02014, -1.22618, -1.28304, -1.28564, -1.14235, -1.18465, -1.30126, -1.41117, -1.62628, -1.82796, -1.89977, -2.06244, -2.30589, -2.52502, -2.75193, -2.82271, -2.96435, -3.00824, -2.93894, -2.78378, -2.60705, -2.51369, -2.40932, -2.43233, -2.54692, -2.61848, -2.74927, -2.80718, -2.78095, -2.92040, -3.11389, -3.20316, -3.20922, -3.20564, -3.09253, -3.03982, -2.87770, -2.79353, -2.74408, -2.60215, -2.58217, -2.50210, -2.28857, -2.27314, -2.37770, -2.47943, -2.62249, -2.57160, -2.62176, -2.62566, -2.56895, -2.55796, -2.54303, -2.52834, -2.33412, -2.06310, -1.81504, -1.41780, -1.09708, -0.93736, -0.84719, -0.96770, -1.07161, -0.97812, -0.83157, -0.84756, -0.80087, -0.77268, -0.55113, -0.36552, -0.30449, -0.18181, -0.24182, -0.40626, -0.42840, -0.48323, -0.57972, -0.53303, -0.46909, +-3.26959, -3.33107, -3.29792, -3.29901, -3.27909, -3.24924, -3.32835, -3.29433, -3.20290, -3.22399, -3.13239, -2.91091, -2.60682, -2.20599, -1.94410, -1.78088, -1.70905, -1.68412, -1.58858, -1.48587, -1.27324, -1.02798, -0.89245, -0.87980, -0.91568, -0.77307, -0.48782, -0.35407, -0.24761, -0.15260, -0.13431, 0.07890, 0.25496, 0.32238, 0.45640, 0.43992, 0.22305, 0.02396, -0.22947, -0.41657, -0.55151, -0.76336, -0.91641, -0.99504, -1.02423, -0.92398, -0.86568, -0.84953, -0.77461, -0.69491, -0.48979, -0.45536, -0.57004, -0.73976, -0.94236, -1.05834, -1.13084, -1.20392, -1.31455, -1.52966, -1.60538, -1.51420, -1.51075, -1.34267, -1.12220, -1.13540, -1.24348, -1.36439, -1.65122, -1.86782, -2.07776, -2.17571, -2.05627, -1.96539, -1.85032, -1.74451, -1.81160, -1.83040, -1.84691, -1.83913, -1.67439, -1.64862, -1.62049, -1.71641, -1.82455, -1.76220, -1.65594, -1.61807, -1.67674, -1.65860, -1.49820, -1.38531, -1.29598, -1.07959, -0.98117, -0.86951, -0.79672, -0.87539, -0.91041, -0.81410, -0.80125, -0.65314, -0.56502, -0.53419, -0.42415, -0.43629, -0.51605, -0.48990, -0.49211, -0.38365, -0.17566, -0.08344, 0.04987, -0.00876, -0.05016, -0.06467, -0.09478, -0.09760, -0.19863, -0.31286, -0.40743, -0.39046, -0.22573, -0.03442, 0.21226, 0.51089, 0.61366, 0.79381, 0.97868, 0.97468, 0.85967, 0.81688, 0.74549, 0.73995, 0.67398, 0.47953, 0.30023, 0.10539, -0.15434, -0.26003, -0.34472, -0.50423, -0.70700, -1.11145, -1.37683, -1.59625, -1.68455, -1.71958, -1.87027, -1.97651, -2.03768, -1.98690, -1.89219, -1.67282, -1.35960, -1.22946, -1.26967, -1.21528, -1.24231, -1.19040, -1.04021, -0.93635, -0.96569, -0.96126, -1.06686, -1.15685, -1.25945, -1.37591, -1.38133, -1.25896, -1.07478, -0.78463, -0.50988, -0.37174, -0.17319, -0.05924, 0.13681, 0.09724, -0.14136, -0.42505, -0.76566, -0.94202, -1.06855, -1.12924, -1.10229, -1.08143, -0.93580, -0.77409, -0.75977, -0.64782, -0.61570, -0.54502, -0.29641, -0.17901, -0.27992, -0.41888, -0.69572, -0.87958, -0.99071, -0.98106, -0.79883, -0.67118, -0.78145, -0.96567, -1.11312, -1.24900, -1.25619, -1.44644, -1.62770, -1.77251, -1.82573, -1.70440, -1.64945, -1.45411, -1.21211, -1.05330, -0.91858, -0.84534, -0.68919, -0.57158, -0.60359, -0.47656, -0.42021, -0.46666, -0.38971, -0.40795, -0.61811, -0.73506, -0.90975, -0.98440, -0.92762, -0.90707, -0.84000, -0.80638, -0.88121, -0.85456, -0.73957, -0.75555, -0.74128, -0.79396, -0.76306, -0.67873, -0.66230, -0.51571, -0.42197, -0.39224, -0.37312, -0.41038, -0.45085, -0.48545, -0.38450, -0.22007, -0.13845, -0.01034, 0.06961, -0.08855, -0.17885, -0.25528, -0.42512, -0.34662, -0.18058, -0.06253, 0.11011, 0.20997, 0.44408, 0.75174, 0.88382, 0.87295, 0.80561, 0.65315, 0.60644, 0.57277, 0.56135, 0.71170, 0.76519, 0.79658, 0.73753, 0.69353, 0.82566, 0.99029, 1.22124, 1.42981, 1.62187, 1.71044, 1.58759, 1.41285, 1.22831, 0.92886, 0.77854, 0.72760, 0.57100, 0.46229, 0.35347, 0.13219, 0.07244, 0.09404, 0.25522, 0.41345, 0.38916, 0.34057, 0.39102, 0.41346, 0.45264, 0.47662, 0.42359, 0.36308, 0.17582, 0.07563, -0.10928, -0.35666, -0.49542, -0.54349, -0.42494, -0.31065, -0.19389, -0.21368, -0.42370, -0.59149, -0.68448, -0.82388, -0.83594, -0.88451, -1.13420, -1.37522, -1.42026, -1.43765, -1.29740, -1.30865, -1.37700, -1.46290, -1.68030, -1.94358, -2.11791, -2.26528, -2.43485, -2.64890, -2.89579, -2.97610, -3.06462, -3.07405, -3.00911, -2.88832, -2.66639, -2.51530, -2.40262, -2.43477, -2.52467, -2.59597, -2.77030, -2.85687, -2.82707, -2.92960, -2.98069, -2.99350, -3.05613, -3.03696, -2.87400, -2.86521, -2.79351, -2.74188, -2.64981, -2.48871, -2.45666, -2.44017, -2.33177, -2.30283, -2.28608, -2.27090, -2.40187, -2.43023, -2.52394, -2.49881, -2.39096, -2.37988, -2.28200, -2.23671, -2.11833, -1.92836, -1.68443, -1.25481, -0.94595, -0.81242, -0.73419, -0.85261, -0.85998, -0.69787, -0.59913, -0.64470, -0.57865, -0.55853, -0.40977, -0.27719, -0.21101, -0.05745, -0.08492, -0.29413, -0.43706, -0.51272, -0.50795, -0.37902, -0.26563, +-3.26913, -3.20045, -3.16504, -3.19414, -3.23955, -3.24042, -3.22939, -3.23135, -3.19476, -3.09995, -3.04668, -2.91806, -2.56341, -2.21583, -1.95101, -1.73266, -1.63896, -1.59818, -1.56222, -1.46302, -1.24050, -1.07114, -0.93676, -0.87238, -0.86512, -0.71859, -0.53495, -0.53338, -0.52256, -0.48556, -0.37524, -0.15491, -0.09550, 0.01522, 0.13355, 0.11022, -0.03804, -0.13848, -0.20628, -0.41351, -0.68666, -0.87937, -1.07831, -1.22873, -1.12893, -0.95504, -0.84527, -0.80983, -0.76270, -0.63160, -0.41582, -0.31735, -0.36571, -0.60737, -0.83890, -0.93792, -1.03526, -1.14020, -1.30617, -1.55244, -1.58383, -1.46266, -1.39088, -1.24536, -1.23405, -1.24814, -1.30473, -1.36815, -1.53033, -1.70375, -1.85668, -2.04415, -2.09518, -1.97237, -1.80467, -1.72783, -1.69110, -1.73385, -1.83305, -1.87044, -1.77547, -1.71444, -1.67511, -1.72176, -1.77511, -1.82143, -1.82492, -1.82846, -1.90221, -1.84362, -1.66686, -1.58046, -1.53417, -1.39939, -1.33124, -1.22646, -1.27682, -1.26577, -1.13211, -0.96479, -0.85301, -0.69494, -0.55617, -0.51938, -0.49593, -0.41963, -0.39027, -0.46958, -0.42194, -0.28637, -0.10941, 0.01942, 0.12204, 0.11003, 0.07783, 0.06001, 0.02602, -0.12641, -0.32622, -0.41717, -0.44332, -0.33605, -0.18265, -0.08146, 0.04971, 0.26576, 0.40388, 0.71217, 0.84981, 0.84420, 0.76467, 0.66759, 0.63835, 0.67231, 0.72167, 0.62815, 0.35329, 0.10305, -0.12520, -0.38883, -0.46209, -0.57337, -0.80017, -1.13918, -1.42333, -1.60989, -1.71292, -1.77703, -1.86421, -1.99975, -2.07082, -1.98131, -1.90704, -1.71151, -1.50062, -1.47571, -1.55395, -1.47990, -1.40806, -1.22312, -1.15034, -1.11233, -1.09392, -1.09305, -1.11045, -1.10517, -1.12303, -1.21464, -1.36537, -1.32299, -1.03613, -0.81821, -0.52088, -0.31047, -0.16046, -0.02375, 0.10434, 0.05153, -0.16447, -0.42864, -0.64727, -0.83544, -1.06052, -1.20356, -1.29566, -1.29301, -1.14414, -0.95807, -0.90852, -0.83272, -0.83751, -0.70791, -0.54171, -0.47524, -0.44869, -0.51899, -0.73224, -0.90644, -1.01978, -1.00095, -0.95846, -0.93644, -0.91631, -1.12245, -1.26385, -1.32149, -1.41003, -1.59754, -1.78196, -1.87240, -1.82756, -1.70014, -1.60983, -1.47759, -1.38262, -1.27015, -1.13154, -0.96462, -0.72422, -0.61337, -0.68551, -0.65678, -0.65912, -0.59270, -0.48472, -0.46441, -0.51542, -0.60110, -0.73659, -0.76131, -0.65781, -0.57078, -0.63121, -0.74822, -0.73884, -0.76185, -0.73280, -0.69930, -0.72003, -0.70684, -0.59217, -0.46914, -0.42104, -0.37599, -0.35185, -0.35558, -0.40588, -0.38732, -0.34974, -0.34467, -0.23908, -0.11464, -0.05049, 0.07294, 0.19417, 0.20124, 0.11093, -0.08664, -0.23567, -0.19513, -0.03512, 0.12831, 0.35876, 0.55337, 0.68139, 0.80275, 0.94705, 0.88860, 0.74878, 0.70968, 0.69373, 0.67913, 0.66648, 0.75408, 0.78816, 0.76020, 0.72035, 0.74980, 0.83336, 0.94010, 1.11224, 1.22376, 1.37318, 1.44631, 1.36389, 1.26790, 1.12318, 0.93489, 0.82726, 0.69896, 0.61375, 0.52287, 0.38890, 0.19640, 0.15058, 0.21800, 0.24818, 0.22093, 0.26008, 0.30210, 0.36059, 0.51608, 0.57882, 0.54877, 0.45764, 0.36691, 0.25542, 0.20450, 0.06515, -0.17787, -0.46705, -0.61095, -0.49100, -0.36105, -0.14865, -0.10699, -0.33452, -0.54514, -0.72134, -0.85458, -0.84688, -1.00311, -1.19057, -1.37817, -1.45074, -1.45633, -1.35441, -1.33370, -1.45335, -1.65612, -1.79864, -1.98936, -2.26951, -2.38579, -2.57151, -2.82037, -3.01577, -3.06022, -3.04741, -3.05960, -3.03401, -2.95332, -2.86588, -2.76604, -2.57481, -2.52198, -2.53375, -2.59980, -2.78753, -2.85190, -2.80349, -2.81724, -2.75673, -2.83268, -2.85562, -2.80048, -2.72311, -2.71992, -2.65241, -2.51080, -2.38257, -2.35921, -2.35738, -2.34147, -2.40795, -2.32264, -2.20405, -2.13507, -2.18791, -2.27743, -2.38621, -2.39793, -2.30636, -2.23657, -2.14463, -2.08793, -1.93651, -1.75432, -1.49976, -1.09434, -0.80591, -0.65294, -0.55607, -0.62347, -0.54722, -0.50969, -0.47866, -0.48514, -0.44945, -0.35725, -0.15567, 0.01870, 0.06473, 0.01608, -0.11857, -0.24587, -0.44505, -0.39131, -0.22662, -0.10265, 0.02120, +-3.15949, -2.97415, -2.92960, -2.97608, -3.17274, -3.30218, -3.28940, -3.30173, -3.21065, -3.02851, -2.94121, -2.83229, -2.62605, -2.42896, -2.17927, -1.90372, -1.74959, -1.68078, -1.64384, -1.53387, -1.22275, -1.01024, -0.86867, -0.75983, -0.81286, -0.76367, -0.64497, -0.69723, -0.71273, -0.65627, -0.53612, -0.35304, -0.28636, -0.14284, -0.09918, -0.14245, -0.28644, -0.36133, -0.31788, -0.52382, -0.81269, -1.00815, -1.23722, -1.37512, -1.30686, -1.16602, -0.99361, -0.94497, -0.90847, -0.74790, -0.50433, -0.36213, -0.29326, -0.45215, -0.69083, -0.79565, -0.99958, -1.22582, -1.37586, -1.54433, -1.49688, -1.28737, -1.21368, -1.15796, -1.23562, -1.22243, -1.25502, -1.27358, -1.39625, -1.62217, -1.76448, -2.01538, -2.14402, -2.00983, -1.82927, -1.67756, -1.63171, -1.80961, -1.93879, -2.00533, -1.96686, -1.91547, -1.84573, -1.82922, -1.78879, -1.77436, -1.86884, -1.93141, -2.06142, -2.08875, -1.87357, -1.72305, -1.68978, -1.58296, -1.61932, -1.62219, -1.65927, -1.46358, -1.19442, -0.96440, -0.83611, -0.81442, -0.71095, -0.68956, -0.65120, -0.43839, -0.32501, -0.37724, -0.35638, -0.34711, -0.18215, -0.04028, 0.04823, 0.03870, 0.01330, -0.02114, -0.06274, -0.17115, -0.40269, -0.47744, -0.48011, -0.44049, -0.28695, -0.16284, -0.11288, 0.08929, 0.23013, 0.50572, 0.66244, 0.75847, 0.71135, 0.59000, 0.53125, 0.45740, 0.53751, 0.51852, 0.27888, 0.07095, -0.14284, -0.40858, -0.52446, -0.77839, -1.00585, -1.27627, -1.54465, -1.73237, -1.86479, -1.95051, -1.97292, -1.95426, -1.96477, -1.84231, -1.79907, -1.79780, -1.72458, -1.69602, -1.74867, -1.55752, -1.40694, -1.26611, -1.25295, -1.21480, -1.20251, -1.19842, -1.15985, -1.16368, -1.14465, -1.24825, -1.44125, -1.36626, -1.04103, -0.78522, -0.48859, -0.41219, -0.32065, -0.19549, -0.12437, -0.19495, -0.37173, -0.58796, -0.70586, -0.74752, -0.97269, -1.17891, -1.39196, -1.56393, -1.45840, -1.19500, -1.08230, -0.95097, -0.94477, -0.89089, -0.80726, -0.69503, -0.57863, -0.55112, -0.68068, -0.92747, -1.07457, -1.09372, -1.13631, -1.12509, -1.04062, -1.16307, -1.27790, -1.46117, -1.66725, -1.85472, -2.00145, -2.02178, -1.87091, -1.70249, -1.58890, -1.41462, -1.39023, -1.31619, -1.16702, -1.04008, -0.80433, -0.65855, -0.73934, -0.75921, -0.78679, -0.73667, -0.60080, -0.41457, -0.31662, -0.36900, -0.47071, -0.54242, -0.47806, -0.40078, -0.53321, -0.68353, -0.64867, -0.66867, -0.67720, -0.75484, -0.84244, -0.76182, -0.56417, -0.40364, -0.33498, -0.35863, -0.42986, -0.38487, -0.39893, -0.34935, -0.25709, -0.30984, -0.25624, -0.11734, -0.03754, 0.11096, 0.30788, 0.38996, 0.30438, 0.13798, 0.05818, 0.07707, 0.22078, 0.32698, 0.51917, 0.73713, 0.79293, 0.83590, 0.94913, 0.89291, 0.78944, 0.73211, 0.68307, 0.70896, 0.70348, 0.70902, 0.67005, 0.61346, 0.60239, 0.78415, 0.94554, 0.99563, 1.07673, 0.98757, 0.98138, 1.06848, 1.09587, 1.11776, 1.06651, 0.89214, 0.75754, 0.67243, 0.69035, 0.61648, 0.47690, 0.23765, 0.09456, 0.11988, 0.04023, -0.03481, 0.07871, 0.21918, 0.38638, 0.54514, 0.51970, 0.46050, 0.32130, 0.21126, 0.13285, 0.12427, 0.02585, -0.14187, -0.38086, -0.59298, -0.52205, -0.46544, -0.30159, -0.15136, -0.26879, -0.45713, -0.59911, -0.76541, -0.84274, -1.00719, -1.07105, -1.21038, -1.29375, -1.37018, -1.44528, -1.46354, -1.62275, -1.81769, -1.84844, -1.97732, -2.22947, -2.43904, -2.80107, -3.03375, -3.14621, -3.10796, -3.04377, -3.06629, -3.10547, -3.07253, -2.96488, -2.90328, -2.67115, -2.58055, -2.65467, -2.69383, -2.77966, -2.77496, -2.62148, -2.57383, -2.52888, -2.59531, -2.52105, -2.47475, -2.45867, -2.48888, -2.52930, -2.36146, -2.22449, -2.23094, -2.19083, -2.21061, -2.32437, -2.26124, -2.23896, -2.12605, -2.11281, -2.21086, -2.34408, -2.40388, -2.36331, -2.26451, -2.01984, -1.87964, -1.68165, -1.50990, -1.36371, -0.98366, -0.63867, -0.44996, -0.24955, -0.26504, -0.24844, -0.28974, -0.24549, -0.23193, -0.19141, -0.05907, 0.07031, 0.22098, 0.20257, 0.01628, -0.14383, -0.21682, -0.30148, -0.13267, -0.02165, 0.08585, 0.17971, +-3.01401, -2.86906, -2.81743, -2.80477, -3.03072, -3.31069, -3.39348, -3.29761, -3.10779, -2.95431, -2.88188, -2.77635, -2.67088, -2.55433, -2.30697, -2.06374, -1.86705, -1.68955, -1.64853, -1.50119, -1.12959, -0.96004, -0.88543, -0.72410, -0.72980, -0.75411, -0.77238, -0.79578, -0.74391, -0.70968, -0.63972, -0.57123, -0.49414, -0.43248, -0.46060, -0.42569, -0.42763, -0.46958, -0.48493, -0.64840, -0.87851, -1.15962, -1.41766, -1.56439, -1.54059, -1.38189, -1.11575, -1.09617, -1.09026, -0.81630, -0.55020, -0.41575, -0.23061, -0.35930, -0.65562, -0.78826, -0.94645, -1.13071, -1.27819, -1.41633, -1.32894, -1.17697, -1.08061, -1.08298, -1.17391, -1.23908, -1.26822, -1.21279, -1.23526, -1.50486, -1.73045, -1.91840, -1.99346, -1.99784, -1.92121, -1.78960, -1.74502, -1.95276, -1.98758, -2.04394, -2.10162, -2.04330, -1.96362, -1.94917, -1.81971, -1.82333, -1.99845, -2.04467, -2.06299, -2.06860, -1.93114, -1.87759, -1.80972, -1.83606, -1.92854, -1.98867, -1.89190, -1.61060, -1.30998, -1.05134, -0.86236, -0.91347, -0.89753, -0.84096, -0.67577, -0.46630, -0.36178, -0.44020, -0.45133, -0.46165, -0.21677, -0.06491, -0.02212, 0.01422, -0.00206, -0.14211, -0.12584, -0.16143, -0.39462, -0.51312, -0.50140, -0.47456, -0.32838, -0.24115, -0.16992, -0.07635, 0.08061, 0.28505, 0.51056, 0.60483, 0.56068, 0.48426, 0.46038, 0.29092, 0.24993, 0.26188, 0.20077, -0.02061, -0.23211, -0.49372, -0.68220, -1.04556, -1.20551, -1.38563, -1.68930, -1.85757, -1.93977, -2.02979, -1.91050, -1.78519, -1.81952, -1.79040, -1.72539, -1.81127, -1.84876, -1.86955, -1.77507, -1.56147, -1.41142, -1.40204, -1.39865, -1.40120, -1.40321, -1.37334, -1.24579, -1.22417, -1.26551, -1.41183, -1.48396, -1.38771, -1.09749, -0.86168, -0.58895, -0.60622, -0.51193, -0.37803, -0.34883, -0.32538, -0.36718, -0.63810, -0.73624, -0.71972, -0.93250, -1.21090, -1.46747, -1.68713, -1.61280, -1.40382, -1.18602, -1.07094, -1.05023, -1.04957, -0.98915, -0.92347, -0.84817, -0.75549, -0.75066, -0.97418, -1.15594, -1.23264, -1.24065, -1.28064, -1.24096, -1.32862, -1.45385, -1.73459, -1.91124, -1.94563, -2.03180, -1.96462, -1.71995, -1.64036, -1.51858, -1.35075, -1.37512, -1.33213, -1.10059, -0.91795, -0.75130, -0.73324, -0.79324, -0.85413, -0.89662, -0.87369, -0.69251, -0.40675, -0.27474, -0.30209, -0.31593, -0.32927, -0.33871, -0.35563, -0.42208, -0.57921, -0.64785, -0.72114, -0.72572, -0.80421, -0.82789, -0.65894, -0.50503, -0.33394, -0.14615, -0.24123, -0.41160, -0.34988, -0.35807, -0.33501, -0.18811, -0.18616, -0.11799, -0.01179, 0.08535, 0.20520, 0.35355, 0.47156, 0.42028, 0.30639, 0.25485, 0.27960, 0.41720, 0.50526, 0.62329, 0.76989, 0.85445, 0.88535, 0.91849, 0.91476, 0.87464, 0.80813, 0.74297, 0.82097, 0.78014, 0.68517, 0.69155, 0.64617, 0.66305, 0.95187, 1.06499, 0.98400, 0.96931, 0.82791, 0.75969, 0.78157, 0.85932, 0.97537, 0.90919, 0.75192, 0.60751, 0.61609, 0.63337, 0.56796, 0.46869, 0.24613, -0.01356, -0.12559, -0.14575, -0.08968, 0.00786, 0.13827, 0.28633, 0.43190, 0.44223, 0.46924, 0.27534, 0.12327, 0.15017, 0.17197, 0.04068, -0.05325, -0.25624, -0.50593, -0.51029, -0.48330, -0.35707, -0.18286, -0.24535, -0.34703, -0.48993, -0.64378, -0.85234, -1.01590, -1.07930, -1.19374, -1.27729, -1.36750, -1.53053, -1.59508, -1.68220, -1.75976, -1.86583, -2.03315, -2.30359, -2.60550, -2.99114, -3.05948, -3.05802, -3.00732, -2.91016, -2.95625, -3.13139, -3.09577, -2.99905, -2.99734, -2.79706, -2.63622, -2.69805, -2.74038, -2.79356, -2.63445, -2.47266, -2.34156, -2.33674, -2.35499, -2.31395, -2.29733, -2.23314, -2.16438, -2.24652, -2.20843, -2.12150, -2.02056, -1.99268, -2.07174, -2.26909, -2.24460, -2.23773, -2.00988, -1.93930, -2.08679, -2.15669, -2.18460, -2.29631, -2.21381, -1.93864, -1.74227, -1.53492, -1.28787, -1.08349, -0.72636, -0.47957, -0.23007, -0.03344, 0.00952, -0.08911, -0.14861, -0.10294, -0.02485, 0.08505, 0.28319, 0.31904, 0.32964, 0.23005, 0.07065, -0.10000, -0.12659, -0.11635, 0.09721, 0.13998, 0.28730, 0.37844, +-2.83360, -2.77015, -2.75372, -2.71700, -2.81624, -3.04825, -3.16665, -3.06720, -2.94852, -2.88123, -2.83262, -2.69118, -2.51109, -2.38829, -2.22989, -2.09468, -1.95079, -1.76521, -1.61332, -1.33166, -1.02962, -0.98858, -0.92568, -0.72115, -0.73180, -0.82111, -0.92645, -0.94606, -0.87416, -0.87904, -0.83984, -0.81247, -0.76569, -0.73461, -0.75541, -0.64950, -0.49324, -0.44582, -0.55133, -0.75904, -1.00745, -1.28950, -1.46192, -1.59742, -1.57035, -1.42516, -1.23229, -1.28436, -1.33542, -1.08157, -0.74785, -0.50713, -0.29912, -0.46832, -0.74514, -0.85960, -0.98795, -1.10761, -1.21824, -1.36688, -1.34550, -1.27892, -1.12561, -0.99755, -1.01840, -1.07348, -1.10842, -1.08661, -1.07469, -1.29447, -1.54057, -1.65995, -1.72530, -1.89209, -1.94715, -1.93512, -1.90348, -2.04859, -2.03677, -2.08357, -2.19231, -2.20832, -2.10366, -1.99412, -1.89695, -2.05612, -2.24366, -2.19073, -2.13555, -2.15389, -2.13831, -2.23660, -2.19506, -2.27327, -2.28887, -2.16805, -1.96331, -1.65950, -1.42232, -1.24032, -0.99739, -0.89688, -0.80455, -0.71244, -0.55868, -0.50918, -0.49136, -0.62553, -0.65326, -0.60742, -0.35467, -0.24421, -0.19509, -0.16066, -0.14615, -0.21973, -0.18702, -0.28824, -0.49951, -0.61638, -0.68305, -0.71639, -0.56141, -0.44152, -0.27944, -0.19395, -0.01422, 0.26209, 0.47724, 0.53438, 0.49399, 0.43883, 0.46015, 0.31449, 0.18299, 0.13340, 0.08644, -0.21664, -0.39989, -0.62795, -0.83164, -1.16687, -1.31057, -1.49998, -1.82212, -2.04119, -2.07798, -1.99300, -1.77444, -1.74017, -1.85573, -1.87396, -1.82015, -1.96306, -2.01918, -2.04762, -1.90331, -1.74407, -1.68693, -1.64743, -1.60388, -1.53154, -1.43419, -1.41295, -1.28216, -1.23024, -1.31135, -1.47430, -1.52770, -1.52182, -1.28502, -1.09050, -0.82103, -0.79001, -0.71503, -0.65787, -0.62771, -0.55331, -0.50387, -0.69059, -0.82530, -0.95511, -1.17578, -1.36180, -1.53757, -1.75466, -1.70518, -1.57636, -1.38989, -1.32493, -1.29241, -1.13313, -1.00519, -0.98967, -0.97900, -0.95947, -0.94126, -1.07347, -1.19213, -1.25691, -1.28831, -1.45841, -1.47685, -1.55630, -1.68325, -1.91506, -2.01430, -1.95906, -1.96799, -1.89184, -1.68890, -1.59469, -1.43516, -1.37366, -1.40370, -1.28605, -1.01264, -0.90414, -0.88912, -0.98319, -1.02811, -1.01291, -0.96869, -0.82183, -0.57289, -0.31290, -0.19587, -0.24863, -0.27170, -0.21375, -0.21521, -0.27321, -0.32002, -0.55563, -0.73498, -0.86212, -0.84520, -0.80329, -0.73374, -0.59999, -0.53846, -0.40074, -0.16354, -0.12397, -0.19624, -0.21472, -0.29725, -0.27516, -0.11837, -0.11063, -0.00722, 0.15297, 0.26786, 0.33351, 0.39500, 0.54812, 0.57649, 0.47627, 0.47175, 0.49841, 0.57090, 0.66219, 0.78864, 0.89850, 0.96270, 0.91460, 0.89095, 0.95455, 0.96698, 0.94484, 0.85883, 0.87073, 0.78525, 0.65538, 0.70924, 0.78689, 0.90263, 1.07942, 0.97134, 0.81001, 0.77664, 0.65919, 0.59485, 0.56968, 0.59913, 0.66757, 0.56447, 0.48738, 0.44815, 0.48794, 0.50558, 0.44171, 0.34315, 0.17124, -0.07467, -0.24381, -0.22048, -0.12455, -0.09227, -0.03533, 0.00757, 0.17215, 0.29950, 0.43000, 0.28637, 0.15643, 0.19512, 0.24713, 0.15709, 0.02091, -0.24006, -0.40518, -0.38385, -0.42138, -0.39955, -0.28968, -0.37422, -0.45260, -0.55897, -0.63418, -0.78977, -0.98324, -1.07270, -1.20289, -1.36519, -1.47148, -1.57316, -1.60510, -1.63695, -1.71589, -1.98171, -2.19841, -2.47418, -2.72538, -2.94128, -2.89486, -2.86918, -2.88420, -2.90900, -2.95699, -3.04298, -2.96234, -2.96649, -3.00513, -2.84536, -2.74327, -2.82952, -2.85930, -2.90583, -2.67771, -2.48878, -2.24969, -2.07754, -2.05402, -2.05161, -2.05383, -1.98761, -1.84578, -1.86547, -1.94217, -1.96323, -1.86237, -1.88989, -1.92357, -2.09905, -2.05144, -1.95937, -1.72497, -1.71226, -1.88763, -1.94419, -1.88589, -1.94081, -1.92313, -1.84198, -1.66949, -1.41135, -1.12184, -0.86197, -0.49957, -0.33964, -0.11545, 0.04746, 0.11198, 0.07088, -0.00036, 0.05650, 0.20392, 0.31084, 0.48936, 0.49389, 0.43682, 0.31643, 0.20156, 0.03277, 0.06322, 0.10324, 0.26880, 0.29783, 0.44730, 0.52977, +-2.74438, -2.63753, -2.58578, -2.63758, -2.72767, -2.82780, -2.93692, -2.90053, -2.85135, -2.83407, -2.74422, -2.62875, -2.43145, -2.23274, -2.11083, -2.03818, -1.86187, -1.67646, -1.53922, -1.22272, -0.97059, -0.88026, -0.81630, -0.68682, -0.68577, -0.82534, -0.99437, -1.03118, -1.02182, -1.03791, -1.04806, -1.12040, -1.07878, -0.97007, -0.88482, -0.82027, -0.70610, -0.57417, -0.68488, -0.93620, -1.16974, -1.36984, -1.38983, -1.53178, -1.58257, -1.44770, -1.35095, -1.47325, -1.51860, -1.29842, -1.01240, -0.71581, -0.47558, -0.51963, -0.72161, -0.92409, -1.04655, -1.18530, -1.28458, -1.36024, -1.35563, -1.27293, -1.10943, -1.02196, -0.96573, -0.90086, -0.85919, -0.92293, -1.02591, -1.18352, -1.39365, -1.52366, -1.59047, -1.81440, -1.90193, -1.98682, -2.07255, -2.15166, -2.13355, -2.19475, -2.25540, -2.23678, -2.17851, -2.05718, -2.01218, -2.17640, -2.33956, -2.39922, -2.33887, -2.40333, -2.47421, -2.57239, -2.54996, -2.57440, -2.48499, -2.35928, -2.10908, -1.73061, -1.44935, -1.33267, -1.17307, -0.93787, -0.71267, -0.62712, -0.51085, -0.54820, -0.56619, -0.72051, -0.86698, -0.80439, -0.57248, -0.49855, -0.38347, -0.24526, -0.24956, -0.30456, -0.31430, -0.43768, -0.58875, -0.82421, -0.92291, -0.98001, -0.85425, -0.63211, -0.36641, -0.20526, 0.02112, 0.21467, 0.37469, 0.46176, 0.48439, 0.42375, 0.35420, 0.22138, 0.11072, -0.01816, -0.11629, -0.43698, -0.58085, -0.74401, -1.00843, -1.28017, -1.39430, -1.60651, -1.90251, -2.05655, -2.15091, -2.05921, -1.83247, -1.80767, -1.85552, -1.97391, -1.95260, -2.10852, -2.20742, -2.21725, -2.08943, -1.97366, -1.92691, -1.94779, -1.88798, -1.66128, -1.39131, -1.33756, -1.32356, -1.30817, -1.34333, -1.51097, -1.59832, -1.64805, -1.44042, -1.23122, -1.05723, -1.01179, -0.95115, -0.98462, -0.99064, -0.83942, -0.78650, -0.94401, -1.07185, -1.24171, -1.36994, -1.55571, -1.66099, -1.81598, -1.81228, -1.70865, -1.56377, -1.53922, -1.47028, -1.30677, -1.17270, -1.11144, -1.04143, -1.03382, -1.14808, -1.30826, -1.34399, -1.40835, -1.47780, -1.67337, -1.68199, -1.67490, -1.84132, -2.04197, -2.08298, -2.03156, -2.00702, -1.83670, -1.66819, -1.60110, -1.42784, -1.38334, -1.29365, -1.21769, -1.04267, -1.00797, -1.11789, -1.22932, -1.19620, -1.06981, -0.87352, -0.69011, -0.46968, -0.21050, -0.04197, -0.06320, -0.22881, -0.25852, -0.20110, -0.25972, -0.32592, -0.57402, -0.78240, -0.88137, -0.95390, -0.93789, -0.80412, -0.69739, -0.65417, -0.43085, -0.17374, -0.08478, -0.05187, -0.08797, -0.10591, -0.11870, -0.06044, -0.03122, 0.06826, 0.28187, 0.47946, 0.53906, 0.62069, 0.73717, 0.69941, 0.61581, 0.68786, 0.76598, 0.72106, 0.71974, 0.90838, 1.02814, 1.05507, 0.98387, 0.93569, 1.05344, 1.03368, 0.96592, 0.91548, 0.87643, 0.75278, 0.70071, 0.80530, 0.87350, 1.00283, 1.08280, 0.95490, 0.76234, 0.62191, 0.55171, 0.46468, 0.39962, 0.44213, 0.45675, 0.38645, 0.34629, 0.24851, 0.29122, 0.38678, 0.40375, 0.25489, 0.02475, -0.14333, -0.29554, -0.33195, -0.26877, -0.27359, -0.21754, -0.24858, -0.17005, 0.03543, 0.24048, 0.18991, 0.18410, 0.28418, 0.27944, 0.18207, 0.01249, -0.17395, -0.22087, -0.26145, -0.30115, -0.36007, -0.34748, -0.42098, -0.51883, -0.58296, -0.61119, -0.81847, -1.00915, -1.04243, -1.12933, -1.39261, -1.64799, -1.74152, -1.75156, -1.80111, -1.87572, -2.14865, -2.31518, -2.55706, -2.81551, -2.88872, -2.80857, -2.81961, -2.84895, -2.87203, -2.96154, -2.97905, -2.85186, -2.83175, -2.84363, -2.84472, -2.78758, -2.88122, -2.91375, -2.89488, -2.63788, -2.37360, -2.03200, -1.85132, -1.80260, -1.74719, -1.70449, -1.71259, -1.70043, -1.70133, -1.76460, -1.84655, -1.76825, -1.79950, -1.74344, -1.82532, -1.84167, -1.69930, -1.49247, -1.55137, -1.71159, -1.68403, -1.62216, -1.64277, -1.64682, -1.60799, -1.38865, -1.22728, -0.94000, -0.67519, -0.35497, -0.16864, 0.05008, 0.21438, 0.31175, 0.20008, 0.07666, 0.14666, 0.34924, 0.43267, 0.48020, 0.47917, 0.49147, 0.38894, 0.32464, 0.20520, 0.27484, 0.34403, 0.36221, 0.37133, 0.52081, 0.60076, +-2.67289, -2.60367, -2.49526, -2.58060, -2.70664, -2.74320, -2.84075, -2.83453, -2.80726, -2.81090, -2.70246, -2.58984, -2.37776, -2.12570, -1.93271, -1.82236, -1.67229, -1.52527, -1.40269, -1.10163, -0.90820, -0.80516, -0.70680, -0.58690, -0.54253, -0.64701, -0.86771, -1.01415, -1.13290, -1.23545, -1.22129, -1.24271, -1.24748, -1.18639, -1.03208, -0.97207, -0.92444, -0.79726, -0.89044, -1.11543, -1.28092, -1.37044, -1.30132, -1.44845, -1.56028, -1.45294, -1.34606, -1.44106, -1.54249, -1.45114, -1.25559, -0.97355, -0.74460, -0.70612, -0.78470, -0.94558, -1.05205, -1.18855, -1.29008, -1.33551, -1.30369, -1.25775, -1.10467, -1.04344, -1.01965, -0.98343, -0.85273, -0.86012, -1.01953, -1.17301, -1.37318, -1.52426, -1.59710, -1.83966, -1.95517, -2.08701, -2.21939, -2.25685, -2.17885, -2.16785, -2.23902, -2.28176, -2.29603, -2.22284, -2.21544, -2.36528, -2.48241, -2.57477, -2.54763, -2.63197, -2.72263, -2.80528, -2.77056, -2.79683, -2.65135, -2.48768, -2.24759, -1.95881, -1.61935, -1.42650, -1.30190, -1.02609, -0.76304, -0.70912, -0.62367, -0.66319, -0.65804, -0.78777, -0.97418, -0.94719, -0.74541, -0.63410, -0.53355, -0.42279, -0.42726, -0.47247, -0.53000, -0.70140, -0.81355, -1.00050, -1.06182, -1.10134, -1.02244, -0.84288, -0.53947, -0.36703, -0.09494, 0.13302, 0.25995, 0.23724, 0.28497, 0.30140, 0.18290, 0.01528, -0.09958, -0.27342, -0.38251, -0.65392, -0.74312, -0.85070, -1.12225, -1.36363, -1.46441, -1.60407, -1.86562, -2.05288, -2.21158, -2.19600, -2.01945, -2.01259, -1.96652, -1.97652, -1.93193, -2.06072, -2.22123, -2.32952, -2.26229, -2.25014, -2.18958, -2.13972, -2.02355, -1.80923, -1.48301, -1.33724, -1.36989, -1.38384, -1.36900, -1.51086, -1.59105, -1.65753, -1.49769, -1.32653, -1.25227, -1.24282, -1.19914, -1.21085, -1.26722, -1.20908, -1.18486, -1.29114, -1.36592, -1.55723, -1.65525, -1.77292, -1.79348, -1.83576, -1.81996, -1.77181, -1.68480, -1.75836, -1.71223, -1.50831, -1.35342, -1.36905, -1.29750, -1.20135, -1.33629, -1.52851, -1.53889, -1.62231, -1.71579, -1.88521, -1.88264, -1.80932, -1.93249, -2.07650, -2.07974, -1.99148, -1.95750, -1.84066, -1.68931, -1.59723, -1.40833, -1.37531, -1.26795, -1.18397, -1.06804, -1.06457, -1.19165, -1.30791, -1.21136, -1.04050, -0.79778, -0.55609, -0.33045, -0.16110, -0.02031, 0.04010, -0.16039, -0.29924, -0.27341, -0.36613, -0.45699, -0.65701, -0.82833, -0.89444, -1.02973, -1.07250, -0.92188, -0.72232, -0.60786, -0.42527, -0.23463, -0.15442, -0.05818, -0.07438, -0.04118, 0.01221, 0.06700, 0.13086, 0.24459, 0.45001, 0.65559, 0.68209, 0.74437, 0.89239, 0.87973, 0.74509, 0.77235, 0.91059, 0.85325, 0.77078, 0.92866, 1.04478, 1.09444, 1.08086, 1.04051, 1.13541, 1.06749, 0.95710, 0.95399, 0.97857, 0.88596, 0.78871, 0.80344, 0.82785, 0.93573, 0.96202, 0.86597, 0.75318, 0.65296, 0.62995, 0.52004, 0.38108, 0.36910, 0.34733, 0.27412, 0.29703, 0.21706, 0.16612, 0.16344, 0.22540, 0.10497, -0.14271, -0.26436, -0.38859, -0.47075, -0.43642, -0.44674, -0.36998, -0.42753, -0.44498, -0.26994, -0.02219, 0.06714, 0.12206, 0.21170, 0.19692, 0.09873, -0.07715, -0.20269, -0.11911, -0.09202, -0.10567, -0.18402, -0.24753, -0.37477, -0.50485, -0.61070, -0.61055, -0.78489, -1.01579, -1.17083, -1.22881, -1.44687, -1.77518, -1.93794, -2.00403, -2.08533, -2.11998, -2.27509, -2.33953, -2.52321, -2.78450, -2.84705, -2.75896, -2.74349, -2.82058, -2.88852, -2.95722, -2.89579, -2.74004, -2.73517, -2.72292, -2.71939, -2.63184, -2.65221, -2.65683, -2.64631, -2.41468, -2.19884, -1.84100, -1.62804, -1.58185, -1.61309, -1.54424, -1.53195, -1.60328, -1.61076, -1.60894, -1.67408, -1.60908, -1.63272, -1.55058, -1.56874, -1.60721, -1.46441, -1.26182, -1.28074, -1.45336, -1.47667, -1.41962, -1.41612, -1.42272, -1.39730, -1.12553, -0.91047, -0.60510, -0.32276, -0.05429, 0.07436, 0.25017, 0.31414, 0.41484, 0.34650, 0.20469, 0.11025, 0.25618, 0.37676, 0.38467, 0.43229, 0.54370, 0.49500, 0.46751, 0.37358, 0.44621, 0.49640, 0.41725, 0.39687, 0.55447, 0.73828, +-2.39764, -2.38211, -2.42048, -2.57252, -2.69572, -2.78898, -2.80904, -2.80113, -2.84543, -2.84435, -2.76955, -2.62186, -2.29226, -2.06974, -1.88156, -1.69701, -1.47519, -1.31723, -1.19936, -0.91006, -0.76484, -0.73227, -0.67582, -0.58375, -0.51404, -0.49577, -0.62779, -0.91759, -1.17435, -1.27195, -1.27672, -1.17837, -1.12391, -1.09760, -1.07412, -1.10571, -1.03082, -1.03522, -1.06655, -1.18195, -1.33541, -1.33691, -1.32219, -1.47797, -1.51488, -1.44958, -1.36215, -1.38481, -1.43703, -1.39269, -1.33235, -1.11501, -0.95074, -0.91894, -0.91935, -1.00292, -1.10954, -1.20249, -1.25604, -1.30028, -1.23447, -1.10825, -1.03807, -1.06968, -1.09078, -1.07753, -0.96298, -0.94589, -0.98229, -1.19829, -1.40212, -1.55017, -1.75792, -2.01985, -2.19001, -2.32198, -2.31924, -2.30638, -2.25142, -2.17331, -2.23941, -2.30434, -2.44889, -2.42489, -2.40135, -2.51511, -2.58513, -2.69056, -2.78776, -2.90925, -2.95932, -2.99148, -2.94984, -2.82005, -2.68522, -2.54058, -2.27900, -2.07349, -1.75085, -1.56094, -1.30949, -1.10010, -0.95097, -0.90789, -0.95361, -0.95131, -0.86195, -0.91101, -0.91805, -0.85543, -0.81012, -0.72190, -0.67840, -0.55422, -0.56625, -0.56271, -0.61840, -0.83558, -0.98908, -1.08573, -1.13635, -1.18901, -1.16441, -1.13230, -0.95306, -0.64401, -0.31009, -0.02623, 0.15868, 0.08758, 0.09119, 0.00348, -0.05566, -0.27215, -0.45602, -0.56715, -0.72708, -0.93981, -0.95922, -1.03778, -1.20526, -1.36727, -1.59034, -1.68813, -1.86084, -1.95436, -2.13222, -2.18891, -2.09818, -2.14838, -2.10032, -1.94700, -1.88183, -1.97268, -2.17833, -2.39742, -2.48932, -2.46295, -2.31899, -2.17130, -1.92452, -1.72914, -1.50595, -1.49654, -1.47101, -1.44170, -1.40992, -1.40818, -1.47104, -1.54866, -1.45189, -1.40562, -1.38330, -1.32894, -1.38332, -1.39130, -1.46115, -1.43045, -1.46268, -1.48980, -1.48489, -1.70220, -1.89778, -2.03373, -2.06331, -2.01216, -1.92019, -1.85653, -1.89614, -1.97460, -1.91727, -1.75265, -1.57041, -1.60504, -1.56008, -1.54012, -1.56911, -1.69378, -1.76543, -1.80312, -1.96832, -2.17130, -2.17111, -2.07781, -2.02750, -1.93339, -1.93196, -1.88923, -1.88742, -1.80837, -1.67367, -1.50904, -1.26821, -1.21608, -1.22791, -1.18911, -1.15841, -1.20496, -1.24540, -1.26139, -1.17250, -0.97665, -0.72189, -0.51838, -0.27964, -0.10744, 0.02262, 0.00386, -0.11307, -0.22641, -0.36365, -0.47400, -0.63081, -0.82107, -0.88612, -0.92222, -1.01183, -0.97090, -0.88554, -0.64744, -0.44731, -0.29200, -0.20408, -0.22404, -0.10506, -0.05115, -0.01655, 0.10095, 0.15872, 0.20040, 0.33197, 0.52884, 0.62660, 0.63335, 0.78371, 0.95262, 1.03739, 0.95840, 0.95717, 0.98213, 0.91156, 0.86832, 0.86816, 1.02168, 1.15711, 1.19391, 1.23621, 1.23519, 1.12175, 1.06693, 1.05969, 1.09508, 1.05805, 0.94826, 0.84510, 0.78099, 0.86651, 0.88782, 0.83672, 0.82910, 0.81686, 0.73863, 0.55878, 0.36900, 0.23405, 0.20360, 0.28484, 0.34816, 0.35217, 0.27875, 0.13817, 0.03990, -0.14518, -0.25284, -0.37824, -0.42440, -0.46629, -0.53275, -0.52500, -0.43286, -0.48077, -0.49685, -0.44566, -0.36504, -0.20315, -0.05546, 0.08890, 0.09045, 0.03814, -0.10559, -0.22209, -0.10743, -0.01861, -0.05634, -0.12350, -0.18347, -0.37239, -0.55452, -0.56124, -0.58568, -0.73662, -0.95930, -1.24037, -1.36644, -1.58332, -1.75445, -1.99462, -2.17063, -2.26461, -2.38659, -2.40028, -2.35117, -2.45210, -2.60240, -2.72247, -2.77675, -2.77129, -2.85686, -2.84419, -2.85062, -2.67509, -2.53912, -2.63482, -2.67975, -2.62896, -2.49903, -2.39645, -2.29817, -2.26374, -2.13823, -1.90486, -1.64367, -1.48143, -1.37978, -1.43560, -1.38496, -1.45040, -1.43149, -1.42973, -1.34699, -1.28163, -1.33586, -1.40527, -1.40247, -1.41889, -1.34972, -1.15922, -1.04977, -1.04647, -1.21782, -1.24148, -1.24022, -1.21022, -1.20240, -1.18500, -0.92285, -0.61789, -0.32741, -0.03926, 0.19019, 0.24846, 0.27450, 0.33778, 0.46888, 0.47235, 0.45030, 0.28798, 0.28687, 0.23580, 0.31570, 0.46959, 0.65161, 0.76739, 0.68468, 0.52738, 0.56631, 0.53027, 0.47153, 0.53812, 0.62666, 0.85766, +-2.21283, -2.22311, -2.28611, -2.43266, -2.56763, -2.69153, -2.71231, -2.74639, -2.80605, -2.78473, -2.73105, -2.57755, -2.24618, -2.07397, -1.90505, -1.70761, -1.45513, -1.29371, -1.20796, -0.96083, -0.83938, -0.83645, -0.83547, -0.76180, -0.65351, -0.54371, -0.47470, -0.65547, -1.00307, -1.17074, -1.27079, -1.19829, -1.08775, -1.02270, -0.99303, -1.00543, -0.94153, -1.04622, -1.09593, -1.19267, -1.30023, -1.23275, -1.27542, -1.43304, -1.45843, -1.46427, -1.40707, -1.41812, -1.42316, -1.36758, -1.39876, -1.27211, -1.14713, -1.09332, -1.07585, -1.15260, -1.23532, -1.27951, -1.22822, -1.12751, -1.08874, -1.02362, -1.03772, -1.19439, -1.23708, -1.18840, -1.04520, -0.93823, -0.92074, -1.17651, -1.40993, -1.63004, -1.91451, -2.15302, -2.36516, -2.51502, -2.47661, -2.48872, -2.45616, -2.37492, -2.44904, -2.53892, -2.77039, -2.79411, -2.74890, -2.80606, -2.81827, -2.93424, -3.08448, -3.23516, -3.25778, -3.12102, -3.06083, -2.89097, -2.73187, -2.63416, -2.35556, -2.16386, -1.85800, -1.60709, -1.31621, -1.20015, -1.18463, -1.22674, -1.33365, -1.24273, -1.07278, -1.03287, -0.89089, -0.79676, -0.82074, -0.78087, -0.77349, -0.64129, -0.67352, -0.68476, -0.72853, -0.93265, -1.12022, -1.23766, -1.31674, -1.41077, -1.41087, -1.32493, -1.22033, -0.92955, -0.57780, -0.32808, -0.11959, -0.15606, -0.15689, -0.22631, -0.26922, -0.52570, -0.76849, -0.92420, -1.11300, -1.22336, -1.18051, -1.22387, -1.32892, -1.49241, -1.75893, -1.82533, -1.93383, -1.96107, -2.10962, -2.21170, -2.17658, -2.26251, -2.28278, -2.13599, -2.05381, -2.07621, -2.23104, -2.32204, -2.46232, -2.53118, -2.37533, -2.22933, -1.92762, -1.72519, -1.58777, -1.57722, -1.51354, -1.46953, -1.42758, -1.39310, -1.39862, -1.35822, -1.26091, -1.28466, -1.29999, -1.28384, -1.41403, -1.46153, -1.55332, -1.55421, -1.64119, -1.68266, -1.67335, -1.89549, -2.14320, -2.35477, -2.39781, -2.28052, -2.13063, -1.92041, -1.98878, -2.16421, -2.14985, -2.09008, -1.93889, -1.93645, -1.89217, -1.84215, -1.78709, -1.87238, -1.97370, -2.04182, -2.26122, -2.41589, -2.36330, -2.20952, -2.03195, -1.82180, -1.76426, -1.72989, -1.75953, -1.74727, -1.69402, -1.55631, -1.29846, -1.17815, -1.20890, -1.24042, -1.27928, -1.35855, -1.34366, -1.16853, -1.00683, -0.90847, -0.73804, -0.62454, -0.44190, -0.25666, -0.12635, -0.12199, -0.10659, -0.15870, -0.36767, -0.52087, -0.70520, -0.79213, -0.73308, -0.71836, -0.75466, -0.70293, -0.68092, -0.46419, -0.27492, -0.17002, -0.15658, -0.27381, -0.16439, -0.04397, 0.00721, 0.09633, 0.10037, 0.11239, 0.23463, 0.49421, 0.61596, 0.55206, 0.68225, 0.81918, 0.92344, 0.92556, 0.95595, 0.97500, 0.95240, 0.92780, 0.86094, 1.02434, 1.18406, 1.32260, 1.50845, 1.48848, 1.34668, 1.23818, 1.12425, 1.11387, 1.07792, 0.98110, 0.83933, 0.70994, 0.74941, 0.77109, 0.77181, 0.81063, 0.82022, 0.69174, 0.45260, 0.30331, 0.21296, 0.12483, 0.20567, 0.25958, 0.29154, 0.25991, 0.08245, -0.07418, -0.21758, -0.23647, -0.34865, -0.35263, -0.38607, -0.45800, -0.39198, -0.31054, -0.38945, -0.46574, -0.55531, -0.61121, -0.45863, -0.26891, -0.09745, -0.10787, -0.16955, -0.27812, -0.36062, -0.26302, -0.19204, -0.23585, -0.30262, -0.32080, -0.39881, -0.62456, -0.66057, -0.72216, -0.91622, -1.11120, -1.38192, -1.49096, -1.61513, -1.67361, -1.90867, -2.14615, -2.31225, -2.50488, -2.43603, -2.32946, -2.36067, -2.42515, -2.59707, -2.73589, -2.77958, -2.88646, -2.82596, -2.78943, -2.58587, -2.48528, -2.62149, -2.70078, -2.67136, -2.50867, -2.32735, -2.12086, -1.86559, -1.76853, -1.63819, -1.48338, -1.42901, -1.29802, -1.30877, -1.22956, -1.21833, -1.11649, -1.07704, -0.93795, -0.85156, -0.94910, -0.97885, -1.02293, -1.04069, -0.93363, -0.79820, -0.78026, -0.82795, -1.01695, -1.05691, -1.11338, -1.11591, -1.10475, -1.07969, -0.85383, -0.57602, -0.30932, -0.03376, 0.17246, 0.33503, 0.30061, 0.29439, 0.44472, 0.43872, 0.51556, 0.42836, 0.38134, 0.31714, 0.40108, 0.56647, 0.78300, 0.95559, 0.89284, 0.79754, 0.82954, 0.72837, 0.63925, 0.66272, 0.68192, 0.86539, +-2.04149, -2.18606, -2.25992, -2.31739, -2.44617, -2.56623, -2.55792, -2.59296, -2.70953, -2.77972, -2.68810, -2.51153, -2.28529, -2.09968, -1.89063, -1.68431, -1.50098, -1.42211, -1.34985, -1.12095, -1.01543, -1.01960, -0.92607, -0.80053, -0.73570, -0.61837, -0.46296, -0.48382, -0.74167, -1.01424, -1.22227, -1.14339, -1.04606, -1.05361, -1.00235, -0.89916, -0.88227, -1.06252, -1.13960, -1.21813, -1.32604, -1.30262, -1.29727, -1.37405, -1.48489, -1.52696, -1.45968, -1.45098, -1.46744, -1.48216, -1.52650, -1.43263, -1.31181, -1.23719, -1.14886, -1.18888, -1.32316, -1.36668, -1.27197, -1.06919, -0.99093, -1.04129, -1.13211, -1.21011, -1.21859, -1.22576, -1.13591, -0.93524, -0.95049, -1.24288, -1.45773, -1.64427, -1.94769, -2.26192, -2.50498, -2.64190, -2.73935, -2.80069, -2.73271, -2.62357, -2.70176, -2.90397, -3.14328, -3.16533, -3.13253, -3.19477, -3.12258, -3.13741, -3.31951, -3.49326, -3.53946, -3.32950, -3.17414, -3.00853, -2.83887, -2.61007, -2.31352, -2.22682, -2.07280, -1.77995, -1.53634, -1.49105, -1.49079, -1.49891, -1.61186, -1.57169, -1.39097, -1.20626, -1.05917, -0.94746, -0.89429, -0.81103, -0.76013, -0.70996, -0.76410, -0.79991, -0.86139, -1.07469, -1.23574, -1.30495, -1.48331, -1.65564, -1.67184, -1.51054, -1.31793, -1.05569, -0.80189, -0.50399, -0.29473, -0.37559, -0.46508, -0.45031, -0.49033, -0.79459, -1.06127, -1.21510, -1.42790, -1.56871, -1.53665, -1.45323, -1.57078, -1.77116, -1.93534, -1.90849, -1.95878, -2.07001, -2.20619, -2.28539, -2.25371, -2.37551, -2.46180, -2.28850, -2.24345, -2.24266, -2.28505, -2.24217, -2.30056, -2.42211, -2.41749, -2.23527, -1.89865, -1.72403, -1.69635, -1.62119, -1.53809, -1.55359, -1.52709, -1.43028, -1.37676, -1.30503, -1.22868, -1.16088, -1.19492, -1.27020, -1.38891, -1.43945, -1.53367, -1.66087, -1.81396, -1.89302, -1.92382, -2.16295, -2.39615, -2.49231, -2.51539, -2.41658, -2.25705, -2.01001, -2.04110, -2.23634, -2.35767, -2.29671, -2.11147, -2.12076, -2.19653, -2.14243, -2.05648, -2.16921, -2.27641, -2.29349, -2.48638, -2.64178, -2.59321, -2.29950, -2.08141, -1.92248, -1.75866, -1.62909, -1.59926, -1.69176, -1.77048, -1.68775, -1.43521, -1.26624, -1.22611, -1.15113, -1.21508, -1.38592, -1.39827, -1.17585, -0.93146, -0.81386, -0.77310, -0.68732, -0.49474, -0.37746, -0.39764, -0.39814, -0.28094, -0.31305, -0.51242, -0.58834, -0.67037, -0.68753, -0.63497, -0.52648, -0.52436, -0.56443, -0.52237, -0.29019, -0.10381, -0.07480, -0.13485, -0.23653, -0.08988, 0.04901, 0.09085, 0.21678, 0.17079, 0.08759, 0.17889, 0.45301, 0.64926, 0.62168, 0.62247, 0.69821, 0.87116, 0.90061, 0.85212, 0.85972, 0.92713, 0.88535, 0.81981, 1.03566, 1.23110, 1.38006, 1.55330, 1.60393, 1.51085, 1.25988, 1.06155, 1.04072, 1.03129, 0.95262, 0.79195, 0.67616, 0.69683, 0.67575, 0.65300, 0.77590, 0.83603, 0.66670, 0.42290, 0.29234, 0.25664, 0.17415, 0.12272, 0.10343, 0.22293, 0.21511, -0.05679, -0.26297, -0.28246, -0.29089, -0.41615, -0.37588, -0.34624, -0.40711, -0.39834, -0.33484, -0.39642, -0.59610, -0.73068, -0.74579, -0.54221, -0.35161, -0.27744, -0.31033, -0.39032, -0.49145, -0.55686, -0.39007, -0.26130, -0.35521, -0.46345, -0.50483, -0.50824, -0.66705, -0.77631, -0.90032, -1.00079, -1.16061, -1.46331, -1.61987, -1.64754, -1.70891, -1.95371, -2.17023, -2.30096, -2.54228, -2.58696, -2.49979, -2.41459, -2.46996, -2.60254, -2.67207, -2.68876, -2.81154, -2.86228, -2.81023, -2.58622, -2.47015, -2.58852, -2.60763, -2.51546, -2.41805, -2.26477, -2.03368, -1.65518, -1.47047, -1.42288, -1.38886, -1.27074, -1.12373, -1.19139, -1.19161, -1.06738, -0.92260, -0.86544, -0.68006, -0.51323, -0.57134, -0.61644, -0.65168, -0.54355, -0.50014, -0.46569, -0.46338, -0.52908, -0.71092, -0.85901, -0.93380, -0.94196, -0.94182, -0.96051, -0.77333, -0.46155, -0.27152, -0.06561, 0.11892, 0.33699, 0.37294, 0.36215, 0.43010, 0.48402, 0.61521, 0.53755, 0.41340, 0.42394, 0.47995, 0.55065, 0.76150, 1.02441, 1.06199, 1.01103, 1.01509, 0.97692, 0.77729, 0.64776, 0.66369, 0.84387, +-1.88007, -1.99485, -2.15499, -2.23241, -2.31759, -2.42412, -2.49048, -2.57458, -2.60862, -2.64129, -2.62782, -2.54031, -2.28247, -2.00132, -1.85791, -1.76544, -1.57734, -1.47067, -1.40498, -1.15685, -0.99515, -0.94444, -0.83565, -0.77422, -0.71646, -0.57715, -0.52366, -0.57998, -0.67797, -0.87525, -1.15434, -1.14730, -1.02622, -0.99766, -0.96524, -0.84145, -0.80121, -0.98957, -1.19523, -1.38787, -1.46892, -1.37254, -1.34739, -1.44951, -1.50991, -1.44436, -1.44767, -1.54180, -1.51212, -1.45510, -1.47942, -1.38186, -1.25754, -1.20966, -1.19126, -1.32050, -1.42401, -1.38689, -1.36492, -1.28575, -1.11954, -1.08969, -1.23442, -1.31668, -1.26408, -1.21574, -1.21982, -1.06210, -1.01160, -1.22816, -1.46294, -1.71694, -1.99089, -2.24944, -2.55950, -2.86333, -3.05510, -3.04556, -3.02844, -3.00179, -2.98199, -3.06716, -3.26852, -3.32010, -3.35568, -3.46879, -3.44139, -3.48847, -3.59834, -3.63327, -3.71273, -3.66061, -3.45396, -3.17317, -2.95853, -2.66778, -2.31867, -2.18886, -2.21201, -2.07768, -1.87434, -1.77356, -1.74756, -1.81395, -1.90020, -1.78310, -1.62600, -1.49620, -1.33100, -1.05176, -0.94574, -0.92742, -0.80848, -0.68387, -0.77443, -0.84008, -0.91618, -1.14014, -1.33466, -1.50071, -1.68017, -1.75121, -1.80023, -1.78866, -1.56733, -1.22188, -1.03299, -0.75207, -0.47394, -0.42236, -0.56190, -0.63861, -0.67824, -0.92315, -1.20475, -1.49804, -1.77549, -1.85505, -1.84464, -1.79296, -1.85183, -1.86074, -1.92616, -2.00545, -2.06960, -2.10978, -2.24700, -2.28330, -2.21759, -2.33126, -2.47158, -2.44426, -2.44349, -2.30159, -2.21606, -2.22095, -2.23937, -2.27990, -2.39502, -2.29867, -1.95973, -1.63263, -1.58488, -1.58496, -1.50235, -1.47838, -1.46785, -1.45368, -1.41322, -1.23190, -1.12615, -1.10737, -1.16502, -1.17913, -1.30506, -1.50177, -1.62872, -1.68973, -1.87161, -1.97974, -2.00180, -2.21954, -2.44503, -2.59131, -2.63451, -2.45626, -2.29092, -2.16857, -2.18242, -2.24902, -2.40223, -2.40764, -2.21734, -2.10149, -2.20381, -2.31510, -2.30266, -2.37607, -2.46210, -2.49451, -2.64748, -2.67799, -2.58456, -2.38880, -2.25408, -2.03784, -1.79775, -1.69560, -1.63154, -1.59659, -1.67797, -1.64722, -1.42018, -1.22150, -1.09159, -1.02334, -1.12138, -1.25639, -1.31038, -1.25672, -1.07732, -0.81455, -0.73958, -0.72089, -0.55181, -0.37707, -0.43398, -0.55550, -0.46841, -0.42436, -0.54913, -0.61666, -0.67554, -0.61325, -0.54103, -0.48915, -0.52910, -0.50379, -0.39035, -0.23808, -0.07478, 0.06273, 0.05040, -0.03193, 0.12546, 0.24844, 0.26422, 0.33780, 0.24926, 0.21275, 0.32795, 0.47239, 0.58915, 0.67414, 0.67585, 0.62329, 0.75201, 0.87237, 0.87112, 0.84081, 0.93008, 0.96704, 0.95551, 1.07026, 1.14718, 1.27915, 1.46031, 1.49219, 1.37244, 1.17342, 1.03105, 0.90597, 0.81870, 0.86968, 0.87019, 0.80641, 0.83124, 0.75226, 0.64894, 0.70928, 0.72779, 0.67892, 0.56867, 0.36861, 0.22123, 0.19391, 0.14439, 0.02052, 0.09982, 0.16593, -0.03547, -0.30539, -0.37144, -0.39411, -0.50974, -0.50649, -0.52205, -0.54615, -0.51194, -0.50603, -0.61849, -0.78720, -0.81587, -0.86172, -0.75029, -0.52050, -0.38725, -0.39200, -0.42339, -0.50744, -0.57772, -0.44547, -0.37356, -0.41405, -0.45303, -0.61232, -0.76733, -0.84222, -0.85179, -0.96288, -1.00534, -1.04934, -1.23810, -1.51312, -1.65976, -1.76987, -1.99306, -2.21102, -2.39674, -2.62955, -2.67613, -2.67431, -2.66376, -2.64101, -2.53432, -2.54556, -2.62826, -2.73280, -2.74757, -2.70415, -2.45122, -2.25785, -2.31568, -2.32873, -2.29696, -2.20192, -1.98041, -1.81009, -1.58526, -1.34041, -1.19873, -1.21713, -1.14566, -1.01633, -1.01700, -1.08233, -1.02036, -0.85371, -0.72778, -0.50233, -0.32855, -0.32423, -0.27366, -0.30996, -0.27054, -0.26176, -0.13295, -0.10666, -0.25298, -0.40384, -0.46617, -0.54542, -0.54304, -0.53509, -0.61155, -0.54510, -0.38056, -0.23454, 0.05223, 0.25311, 0.35624, 0.45482, 0.56405, 0.53778, 0.50981, 0.61600, 0.65638, 0.53713, 0.49244, 0.53570, 0.59026, 0.75388, 0.94566, 1.05488, 1.18173, 1.20679, 1.08513, 0.77831, 0.65866, 0.65405, 0.71844, +-1.88398, -1.87892, -1.99490, -2.13644, -2.23400, -2.35162, -2.53420, -2.54853, -2.47694, -2.50834, -2.60968, -2.54849, -2.21144, -1.96314, -1.88352, -1.82516, -1.63118, -1.50349, -1.43867, -1.18916, -0.96637, -0.87488, -0.72550, -0.64022, -0.67881, -0.60415, -0.63783, -0.74746, -0.73913, -0.82517, -1.01040, -1.08573, -1.04655, -0.99257, -0.96823, -0.88200, -0.85627, -0.97963, -1.29029, -1.47494, -1.52130, -1.45302, -1.45580, -1.53478, -1.44731, -1.36124, -1.44402, -1.62146, -1.62665, -1.56280, -1.55052, -1.40669, -1.26946, -1.31910, -1.41339, -1.51596, -1.57609, -1.50496, -1.50681, -1.54913, -1.32812, -1.20878, -1.32706, -1.46050, -1.47277, -1.36003, -1.36752, -1.23159, -1.16359, -1.26627, -1.56187, -1.78166, -1.96123, -2.22103, -2.57970, -2.95415, -3.09623, -3.14160, -3.26216, -3.33116, -3.25543, -3.22516, -3.35271, -3.43291, -3.57015, -3.79984, -3.88802, -3.85505, -3.86093, -3.80460, -3.78604, -3.83443, -3.64927, -3.37497, -3.16126, -2.87401, -2.56798, -2.31553, -2.35571, -2.31084, -2.23981, -2.08430, -2.09055, -2.13243, -2.09252, -1.93387, -1.79719, -1.73627, -1.48880, -1.19154, -1.10770, -1.10829, -0.95750, -0.82940, -0.96924, -1.03050, -1.08229, -1.31827, -1.59232, -1.74264, -1.84093, -1.87666, -1.91273, -2.02040, -1.83605, -1.49008, -1.32230, -1.05148, -0.79784, -0.61483, -0.71995, -0.80480, -0.91936, -1.06811, -1.36292, -1.66697, -1.86977, -1.96099, -2.02132, -2.05910, -1.94081, -1.80339, -1.84854, -2.04608, -2.18638, -2.23139, -2.39770, -2.35324, -2.22722, -2.30135, -2.45837, -2.45578, -2.45125, -2.35779, -2.22994, -2.26543, -2.25078, -2.20350, -2.33060, -2.28447, -2.06971, -1.65232, -1.51703, -1.47968, -1.45307, -1.33995, -1.36255, -1.42020, -1.33138, -1.13863, -1.02094, -1.06552, -1.04071, -1.06205, -1.32242, -1.64444, -1.78186, -1.80390, -2.02213, -2.11750, -2.08289, -2.26161, -2.52693, -2.66434, -2.65937, -2.51911, -2.35754, -2.29745, -2.29683, -2.29564, -2.44625, -2.47366, -2.37834, -2.18907, -2.20970, -2.29472, -2.38841, -2.43102, -2.54675, -2.62220, -2.60585, -2.52141, -2.41533, -2.41077, -2.31159, -2.08310, -1.93080, -1.85204, -1.73185, -1.55521, -1.55545, -1.51158, -1.31588, -1.18341, -1.11679, -1.03983, -1.03823, -1.14442, -1.21457, -1.27642, -1.20632, -0.89985, -0.78046, -0.76106, -0.67250, -0.47122, -0.48262, -0.60778, -0.64338, -0.58069, -0.62702, -0.69014, -0.62091, -0.53156, -0.51386, -0.55924, -0.53323, -0.39305, -0.35338, -0.28329, -0.08882, 0.13425, 0.16145, 0.12037, 0.28405, 0.37297, 0.30413, 0.34892, 0.35880, 0.32566, 0.41741, 0.48535, 0.51601, 0.65593, 0.70530, 0.65734, 0.68977, 0.79728, 0.85887, 0.88569, 0.99075, 1.09237, 1.14294, 1.07222, 1.10419, 1.19001, 1.28243, 1.27129, 1.20968, 1.20180, 1.06728, 0.83949, 0.68086, 0.72157, 0.76899, 0.76370, 0.84833, 0.78759, 0.59498, 0.56974, 0.64036, 0.66404, 0.62409, 0.41910, 0.20021, 0.21101, 0.15997, -0.01305, -0.07719, -0.06832, -0.14633, -0.35470, -0.47709, -0.61395, -0.72493, -0.79960, -0.72771, -0.66565, -0.69318, -0.75230, -0.83439, -0.85791, -0.90843, -1.03489, -1.00395, -0.79527, -0.64075, -0.59060, -0.52428, -0.57858, -0.70091, -0.63876, -0.49754, -0.46306, -0.45885, -0.61346, -0.87477, -0.92328, -0.90211, -0.95027, -0.94416, -0.94685, -0.99502, -1.32793, -1.58101, -1.85039, -2.05343, -2.30990, -2.44276, -2.53714, -2.60125, -2.69462, -2.78215, -2.68363, -2.54210, -2.55884, -2.62482, -2.66598, -2.64400, -2.61184, -2.32649, -2.07273, -2.11151, -2.15870, -2.04321, -1.88647, -1.69652, -1.57127, -1.52449, -1.29184, -1.09267, -1.08609, -1.08257, -1.11221, -1.05702, -1.08357, -0.98061, -0.86979, -0.67113, -0.43890, -0.16005, 0.00048, 0.06306, 0.00203, -0.05463, 0.02178, 0.15365, 0.14654, -0.01687, -0.15080, -0.17353, -0.25642, -0.19999, -0.15507, -0.25672, -0.29892, -0.16781, -0.02130, 0.20220, 0.43420, 0.48911, 0.64101, 0.79710, 0.68100, 0.56011, 0.49232, 0.60798, 0.59140, 0.61944, 0.64287, 0.75732, 0.83736, 0.95170, 1.12043, 1.27581, 1.30857, 1.13291, 0.91719, 0.78962, 0.65918, 0.61003, +-1.79266, -1.83769, -1.93305, -2.09979, -2.21279, -2.33320, -2.56520, -2.56804, -2.54430, -2.64508, -2.72537, -2.61516, -2.33504, -2.18774, -2.00875, -1.79876, -1.61681, -1.52619, -1.51037, -1.34293, -1.08564, -0.94282, -0.76861, -0.65587, -0.77237, -0.77233, -0.74215, -0.73175, -0.71207, -0.79611, -0.85449, -0.87835, -0.93916, -0.99209, -1.04153, -1.01358, -1.02088, -1.09344, -1.38353, -1.53167, -1.60472, -1.65363, -1.67134, -1.66666, -1.56636, -1.54985, -1.56552, -1.65044, -1.74496, -1.78183, -1.79727, -1.67912, -1.48865, -1.51372, -1.64470, -1.71573, -1.74928, -1.67048, -1.60157, -1.55472, -1.36737, -1.30707, -1.38487, -1.46088, -1.53822, -1.49484, -1.50763, -1.40104, -1.39879, -1.48975, -1.79661, -1.97362, -2.10671, -2.40481, -2.71986, -2.96366, -3.08640, -3.28716, -3.46351, -3.51121, -3.51635, -3.55015, -3.65225, -3.76001, -3.88897, -4.09552, -4.20531, -4.10361, -4.07031, -4.01434, -3.88465, -3.80083, -3.65279, -3.52858, -3.39776, -3.08545, -2.84105, -2.60475, -2.58420, -2.52829, -2.53980, -2.44088, -2.51968, -2.55460, -2.45209, -2.30844, -2.13620, -1.98903, -1.73239, -1.56182, -1.46178, -1.29995, -1.14212, -1.10536, -1.27457, -1.36859, -1.34871, -1.48798, -1.77800, -1.91362, -1.99775, -2.08610, -2.09809, -2.08741, -1.90953, -1.65633, -1.50975, -1.20349, -1.04453, -0.95254, -1.05140, -1.10019, -1.24215, -1.36282, -1.63117, -1.85084, -1.95556, -2.10371, -2.22235, -2.25245, -2.08503, -1.99456, -1.99539, -2.02843, -2.16600, -2.30011, -2.46136, -2.41198, -2.25843, -2.25945, -2.40633, -2.41632, -2.43627, -2.49384, -2.43370, -2.34159, -2.25758, -2.18452, -2.24833, -2.10547, -1.95143, -1.66650, -1.56358, -1.48409, -1.47981, -1.34425, -1.38302, -1.47498, -1.37129, -1.24453, -1.13340, -1.09256, -0.99295, -1.12021, -1.46076, -1.65997, -1.74346, -1.84206, -2.10137, -2.25174, -2.21135, -2.31170, -2.56981, -2.67711, -2.61972, -2.54298, -2.39929, -2.25347, -2.24407, -2.31007, -2.49070, -2.45474, -2.39756, -2.30121, -2.30134, -2.26437, -2.33969, -2.37791, -2.54074, -2.68674, -2.60937, -2.52762, -2.43406, -2.41404, -2.29837, -2.17145, -2.08514, -1.83971, -1.61966, -1.45220, -1.40650, -1.37092, -1.20178, -1.10680, -1.14030, -1.09808, -1.04609, -1.14394, -1.19502, -1.17889, -1.11386, -0.93764, -0.90783, -0.83929, -0.75486, -0.62732, -0.65960, -0.74480, -0.81768, -0.76669, -0.77598, -0.81382, -0.64565, -0.56323, -0.60099, -0.59579, -0.45011, -0.32698, -0.38487, -0.22813, 0.05425, 0.22749, 0.23133, 0.19479, 0.36485, 0.50270, 0.42265, 0.40799, 0.40644, 0.29568, 0.31959, 0.43763, 0.52201, 0.61161, 0.64199, 0.71528, 0.79328, 0.81418, 0.78861, 0.80479, 0.91411, 1.02979, 1.10829, 0.96340, 0.97209, 0.99749, 1.01826, 1.06743, 1.11459, 1.14498, 0.97239, 0.84077, 0.77805, 0.68051, 0.58302, 0.53124, 0.61242, 0.65218, 0.50293, 0.43312, 0.49757, 0.45554, 0.37480, 0.25692, 0.15689, 0.15822, 0.04081, -0.11423, -0.18852, -0.28360, -0.40919, -0.57419, -0.68402, -0.87689, -1.00591, -1.10061, -0.94861, -0.84961, -0.95479, -1.00707, -1.00101, -1.01612, -1.17580, -1.24289, -1.07905, -0.92051, -0.85462, -0.84674, -0.82254, -0.83671, -0.92934, -0.89797, -0.72180, -0.67687, -0.65134, -0.65490, -0.74951, -0.80425, -0.90045, -0.95391, -0.85746, -0.86476, -0.91604, -1.22638, -1.47630, -1.80429, -1.99417, -2.26556, -2.39055, -2.44961, -2.58239, -2.69410, -2.74424, -2.72454, -2.75728, -2.72584, -2.56144, -2.49677, -2.48389, -2.45711, -2.23737, -2.00103, -2.01349, -2.08599, -1.93659, -1.77673, -1.67238, -1.55024, -1.43765, -1.24485, -1.12890, -1.10167, -1.01698, -1.11512, -1.13293, -1.10790, -0.90176, -0.78478, -0.56057, -0.33256, -0.01973, 0.19893, 0.20793, 0.17099, 0.20776, 0.31396, 0.31548, 0.27226, 0.25073, 0.12525, 0.01419, -0.08187, -0.05160, 0.02563, 0.02191, -0.00465, 0.11885, 0.21795, 0.26933, 0.44781, 0.62074, 0.80423, 0.90255, 0.75623, 0.69545, 0.56950, 0.63283, 0.66620, 0.76649, 0.79394, 0.92309, 0.95671, 1.00659, 1.11367, 1.14243, 1.16600, 1.12117, 1.05033, 0.85988, 0.66832, 0.69460, +-1.64361, -1.72264, -1.83851, -2.04235, -2.21057, -2.26641, -2.42409, -2.60026, -2.68501, -2.71140, -2.77771, -2.76487, -2.57879, -2.36675, -2.10168, -1.89650, -1.68528, -1.50402, -1.44004, -1.41749, -1.27788, -1.07739, -0.89073, -0.79292, -0.81886, -0.87355, -0.91651, -0.80972, -0.73094, -0.81145, -0.85460, -0.87050, -0.94171, -0.98189, -1.05880, -1.09836, -1.17772, -1.20362, -1.34937, -1.59807, -1.73738, -1.74442, -1.82538, -1.92914, -1.89533, -1.79442, -1.70754, -1.84861, -1.99138, -1.97585, -1.95000, -1.93657, -1.82161, -1.74431, -1.81707, -1.89374, -1.80276, -1.67884, -1.67348, -1.58368, -1.40030, -1.38804, -1.46710, -1.51465, -1.57937, -1.51744, -1.52347, -1.51874, -1.65379, -1.76575, -1.92813, -2.17126, -2.34436, -2.49117, -2.73150, -3.00156, -3.18054, -3.37309, -3.52559, -3.72770, -3.87727, -3.89737, -3.92525, -4.05162, -4.22396, -4.33787, -4.34871, -4.22652, -4.11463, -4.03672, -4.01509, -3.92751, -3.75870, -3.70256, -3.65569, -3.38279, -3.16940, -2.89699, -2.78140, -2.72505, -2.77922, -2.77995, -2.82330, -2.94398, -2.90940, -2.63017, -2.38708, -2.31390, -2.14435, -1.95652, -1.75956, -1.62522, -1.51482, -1.40949, -1.48731, -1.59890, -1.61063, -1.65217, -1.85875, -2.02175, -2.09130, -2.14458, -2.24163, -2.21472, -1.97422, -1.73467, -1.62259, -1.39335, -1.35291, -1.30170, -1.34883, -1.40234, -1.55877, -1.71421, -1.83410, -2.00620, -2.14383, -2.18934, -2.26714, -2.42122, -2.36826, -2.26532, -2.11349, -2.06593, -2.20184, -2.25333, -2.27009, -2.19988, -2.15962, -2.18952, -2.31335, -2.40394, -2.45563, -2.52053, -2.61540, -2.55306, -2.36941, -2.20705, -2.19262, -1.99674, -1.84645, -1.63483, -1.55041, -1.48768, -1.50602, -1.43993, -1.38949, -1.50005, -1.52206, -1.34503, -1.15943, -1.16230, -1.12741, -1.25399, -1.48256, -1.63850, -1.75105, -1.81297, -1.99128, -2.15452, -2.24956, -2.36714, -2.52722, -2.60324, -2.50201, -2.33253, -2.27617, -2.24964, -2.25272, -2.31559, -2.50457, -2.48245, -2.46754, -2.41515, -2.35552, -2.23505, -2.26046, -2.34483, -2.43936, -2.59822, -2.66473, -2.56364, -2.37067, -2.36331, -2.34291, -2.25974, -2.03728, -1.69881, -1.52208, -1.33637, -1.19078, -1.10576, -1.03218, -1.02816, -1.05273, -1.04550, -1.01800, -1.00367, -1.08671, -1.15913, -1.08162, -0.99150, -1.07403, -1.03679, -0.96520, -0.84549, -0.81258, -0.84914, -0.90830, -0.90367, -0.82994, -0.78117, -0.70193, -0.59876, -0.53354, -0.52357, -0.42653, -0.33377, -0.29533, -0.08518, 0.10225, 0.26007, 0.37128, 0.43149, 0.54495, 0.63735, 0.63041, 0.55807, 0.44736, 0.37862, 0.32662, 0.31019, 0.41414, 0.50043, 0.51205, 0.63240, 0.74172, 0.74680, 0.72451, 0.71076, 0.77151, 0.82241, 0.95901, 0.92088, 0.79589, 0.78178, 0.94829, 1.04305, 1.01414, 0.98753, 0.91593, 0.90902, 0.81369, 0.64195, 0.54004, 0.49474, 0.46862, 0.44970, 0.38642, 0.31434, 0.29105, 0.23160, 0.08115, -0.10685, -0.13212, -0.07443, -0.19731, -0.34612, -0.41368, -0.53356, -0.64917, -0.78833, -0.90791, -1.13708, -1.26007, -1.23854, -1.15619, -1.09005, -1.07341, -1.12354, -1.24061, -1.33305, -1.41451, -1.34377, -1.18829, -1.05660, -0.93582, -0.93077, -1.04554, -1.14654, -1.16885, -1.11107, -0.98533, -0.88344, -0.80596, -0.80245, -0.78676, -0.77765, -0.93001, -1.04938, -0.95900, -0.95145, -0.91277, -1.10031, -1.32333, -1.63512, -1.77929, -1.92195, -2.16801, -2.36567, -2.45017, -2.55906, -2.72367, -2.84942, -2.88981, -2.73224, -2.52187, -2.38488, -2.22370, -2.09757, -1.97347, -1.92337, -1.95042, -1.99855, -1.91122, -1.74108, -1.64157, -1.63629, -1.52732, -1.31555, -1.23816, -1.22108, -1.08702, -1.14049, -1.10843, -0.97450, -0.70183, -0.55155, -0.34437, -0.03560, 0.16960, 0.27198, 0.38127, 0.43821, 0.43882, 0.47731, 0.48016, 0.48655, 0.43001, 0.27463, 0.22001, 0.19688, 0.18980, 0.17482, 0.23768, 0.31725, 0.39659, 0.45899, 0.45835, 0.44103, 0.54664, 0.76048, 0.87882, 0.76123, 0.74018, 0.66322, 0.79380, 0.91746, 1.02180, 1.01845, 1.05675, 1.16329, 1.15153, 1.07387, 1.11567, 1.20762, 1.15989, 1.10811, 0.97856, 0.90312, 0.87754, +-1.55368, -1.69312, -1.80953, -2.00523, -2.17852, -2.20964, -2.26442, -2.50321, -2.75482, -2.77452, -2.70747, -2.67897, -2.62034, -2.43278, -2.17507, -2.02653, -1.83675, -1.62078, -1.42088, -1.35406, -1.26153, -1.07862, -0.93908, -0.84727, -0.83097, -0.94666, -1.04050, -0.89623, -0.79217, -0.87698, -0.96347, -1.04765, -1.14342, -1.16147, -1.17603, -1.19867, -1.27797, -1.26804, -1.31955, -1.54129, -1.75928, -1.85628, -1.97641, -2.09441, -2.11347, -1.97707, -1.85678, -2.06947, -2.23770, -2.20551, -2.12745, -2.13028, -2.08500, -1.94210, -1.93045, -1.94839, -1.79624, -1.66617, -1.66498, -1.55703, -1.42624, -1.46287, -1.52279, -1.54382, -1.64122, -1.65783, -1.68875, -1.78831, -1.99521, -2.01359, -1.98581, -2.15286, -2.41711, -2.58178, -2.72512, -2.93432, -3.17711, -3.41914, -3.57410, -3.88846, -4.17101, -4.28969, -4.30819, -4.34281, -4.46044, -4.45568, -4.37353, -4.19110, -4.03132, -3.98487, -4.07897, -4.06699, -3.92662, -3.92083, -3.87631, -3.63032, -3.46125, -3.24886, -3.11347, -3.03069, -3.05050, -3.04622, -3.07313, -3.14469, -3.14816, -2.88989, -2.59011, -2.49059, -2.38203, -2.23062, -2.03528, -2.02022, -2.00824, -1.91069, -1.88394, -1.86983, -1.84330, -1.76613, -1.87735, -2.01115, -2.09013, -2.13989, -2.22598, -2.15537, -1.92703, -1.78369, -1.72518, -1.63257, -1.70349, -1.67774, -1.65264, -1.70269, -1.89333, -2.00236, -2.00968, -2.05986, -2.21209, -2.30845, -2.31251, -2.39330, -2.41868, -2.39819, -2.22425, -2.16006, -2.23984, -2.22831, -2.12762, -1.93358, -1.91983, -1.95129, -2.12011, -2.29788, -2.40444, -2.52240, -2.65643, -2.58413, -2.34907, -2.18923, -2.14750, -1.92216, -1.75294, -1.62912, -1.60122, -1.55465, -1.57231, -1.46338, -1.33718, -1.36874, -1.43104, -1.35039, -1.18073, -1.16456, -1.20395, -1.36979, -1.52510, -1.69420, -1.81958, -1.86578, -1.96524, -2.03934, -2.18929, -2.24577, -2.28845, -2.27308, -2.17188, -2.04943, -2.06742, -2.15850, -2.18703, -2.22796, -2.38661, -2.43024, -2.52683, -2.55681, -2.49103, -2.33718, -2.32763, -2.35517, -2.31739, -2.33584, -2.45350, -2.49960, -2.34417, -2.25025, -2.22881, -2.19129, -1.91509, -1.58387, -1.43497, -1.26544, -1.11878, -0.95054, -0.87615, -0.84005, -0.77905, -0.73464, -0.72509, -0.75744, -0.91257, -1.03322, -0.95659, -0.98177, -1.19504, -1.22125, -1.16813, -1.04801, -0.96623, -0.94713, -0.95288, -0.90133, -0.76154, -0.63110, -0.60944, -0.61221, -0.55792, -0.47989, -0.36235, -0.29873, -0.21214, -0.04399, 0.04472, 0.21718, 0.43219, 0.65572, 0.76133, 0.83283, 0.88439, 0.78246, 0.64267, 0.60100, 0.50701, 0.36827, 0.39652, 0.42601, 0.36974, 0.44898, 0.52793, 0.51104, 0.53050, 0.53812, 0.54121, 0.54121, 0.71944, 0.83606, 0.74392, 0.65700, 0.83099, 1.02230, 1.04013, 0.95965, 0.87279, 0.87234, 0.74025, 0.56589, 0.49421, 0.50787, 0.46106, 0.37154, 0.33363, 0.27281, 0.20970, 0.05767, -0.20134, -0.41787, -0.38208, -0.27546, -0.40261, -0.54732, -0.60999, -0.75688, -0.92090, -1.09507, -1.26633, -1.48008, -1.52681, -1.38643, -1.25653, -1.24668, -1.24700, -1.27762, -1.40104, -1.50858, -1.53192, -1.39840, -1.33217, -1.24299, -1.12208, -1.11001, -1.20409, -1.27055, -1.18882, -1.13642, -1.06896, -0.97613, -0.93105, -0.93527, -0.86136, -0.81088, -0.96422, -1.11293, -1.09451, -1.13513, -1.07635, -1.12610, -1.26454, -1.48768, -1.50242, -1.50644, -1.70450, -2.04596, -2.30871, -2.45022, -2.60443, -2.78115, -2.81294, -2.59964, -2.42756, -2.27816, -2.05089, -1.80845, -1.63606, -1.70487, -1.74647, -1.78191, -1.70100, -1.54512, -1.51649, -1.58135, -1.47390, -1.28373, -1.29603, -1.34342, -1.24285, -1.24637, -1.16568, -0.93467, -0.58878, -0.37065, -0.09395, 0.23581, 0.43581, 0.47743, 0.54101, 0.65353, 0.67422, 0.65580, 0.60999, 0.59891, 0.49829, 0.39449, 0.38560, 0.38520, 0.41984, 0.39129, 0.52471, 0.65670, 0.72901, 0.76157, 0.70877, 0.57192, 0.56512, 0.70472, 0.77534, 0.71139, 0.72572, 0.70463, 0.86759, 1.06354, 1.20218, 1.17007, 1.15891, 1.29238, 1.34907, 1.23278, 1.20934, 1.33204, 1.36118, 1.31344, 1.19849, 1.19785, 1.06805, +-1.48445, -1.72362, -1.84392, -1.92208, -2.05345, -2.26458, -2.39791, -2.57097, -2.76497, -2.76977, -2.60303, -2.43130, -2.42464, -2.37775, -2.11562, -1.95746, -1.79927, -1.61890, -1.38533, -1.14520, -1.00680, -0.97105, -0.95963, -0.93552, -0.89423, -0.99088, -1.15514, -1.13767, -1.04878, -1.03558, -1.12773, -1.20116, -1.30232, -1.36907, -1.33140, -1.22633, -1.20857, -1.36749, -1.58552, -1.74894, -1.89067, -2.01030, -2.12383, -2.14158, -2.16381, -2.14376, -2.02755, -2.16735, -2.30156, -2.28707, -2.28220, -2.26828, -2.22710, -2.13697, -2.09423, -2.08780, -1.98031, -1.83837, -1.80080, -1.71514, -1.63966, -1.59731, -1.63513, -1.60612, -1.74736, -1.95080, -2.03430, -2.09141, -2.15453, -2.15308, -2.11362, -2.16030, -2.36330, -2.54815, -2.67542, -2.79649, -3.06676, -3.45788, -3.61475, -3.80201, -4.12094, -4.37341, -4.54668, -4.53282, -4.52930, -4.52972, -4.50881, -4.37680, -4.22537, -4.10178, -4.19688, -4.24823, -4.17641, -4.10461, -4.04142, -3.79117, -3.63316, -3.61169, -3.56557, -3.40791, -3.24481, -3.21485, -3.30572, -3.32511, -3.25016, -3.03321, -2.79278, -2.62621, -2.50104, -2.47388, -2.36055, -2.31945, -2.36168, -2.28158, -2.26009, -2.17123, -2.09912, -2.06344, -2.16763, -2.27580, -2.36930, -2.30083, -2.29236, -2.18270, -2.06143, -1.94096, -1.91563, -1.88325, -1.91778, -1.93065, -1.85726, -1.82531, -1.90665, -2.01459, -2.11872, -2.17908, -2.26790, -2.36300, -2.32642, -2.22006, -2.19749, -2.32766, -2.26785, -2.08582, -2.05694, -1.99323, -1.96971, -1.80010, -1.72274, -1.77736, -2.02183, -2.26734, -2.46340, -2.56019, -2.65510, -2.55681, -2.36134, -2.18801, -2.15709, -1.91595, -1.64451, -1.54457, -1.53121, -1.46753, -1.38385, -1.27251, -1.27646, -1.34121, -1.32602, -1.26675, -1.20470, -1.17573, -1.20516, -1.43451, -1.62492, -1.72048, -1.86872, -1.93238, -2.04099, -2.09862, -2.17434, -2.16587, -2.18675, -2.12165, -2.10189, -2.00712, -2.02352, -2.13000, -2.16999, -2.09330, -2.15540, -2.23765, -2.37259, -2.50630, -2.51470, -2.39043, -2.27686, -2.21747, -2.17956, -2.12398, -2.15147, -2.24198, -2.22158, -2.07887, -1.95487, -1.97970, -1.87191, -1.55554, -1.35979, -1.15109, -1.04202, -0.88628, -0.72533, -0.62929, -0.57214, -0.50910, -0.55274, -0.66106, -0.86324, -0.98345, -0.93179, -0.91251, -1.09548, -1.18084, -1.11459, -1.03701, -0.99079, -0.93130, -0.77352, -0.61280, -0.59413, -0.57192, -0.54254, -0.54848, -0.57758, -0.51932, -0.38233, -0.37706, -0.37522, -0.19640, -0.06312, 0.19074, 0.44821, 0.68774, 0.81304, 0.88673, 0.89869, 0.81406, 0.72707, 0.76571, 0.74440, 0.57583, 0.47559, 0.45609, 0.38339, 0.34255, 0.39365, 0.36478, 0.40939, 0.48692, 0.55203, 0.57314, 0.59428, 0.66305, 0.68159, 0.62587, 0.66940, 0.83233, 0.98865, 0.94037, 0.75792, 0.77848, 0.73824, 0.61960, 0.54289, 0.49435, 0.46007, 0.30081, 0.11707, 0.01218, -0.05609, -0.19196, -0.39400, -0.58097, -0.56063, -0.45193, -0.49654, -0.64342, -0.66299, -0.81616, -1.11094, -1.35761, -1.49682, -1.59006, -1.70346, -1.68442, -1.57020, -1.54121, -1.58396, -1.64705, -1.66114, -1.69429, -1.77048, -1.63031, -1.54370, -1.46140, -1.35438, -1.37524, -1.33879, -1.25939, -1.16153, -1.14828, -1.14426, -1.09012, -1.03097, -1.06021, -1.00631, -0.94682, -0.92868, -1.03287, -1.04154, -1.11108, -1.14445, -1.11259, -1.08732, -1.14283, -1.22585, -1.32058, -1.44595, -1.74272, -2.11887, -2.35088, -2.42686, -2.56728, -2.68837, -2.50214, -2.26299, -2.14185, -1.92596, -1.68790, -1.40800, -1.36811, -1.44047, -1.52296, -1.47400, -1.38637, -1.34643, -1.41582, -1.32245, -1.20948, -1.21221, -1.32264, -1.24877, -1.16209, -1.10467, -0.87702, -0.50327, -0.15300, 0.10902, 0.27543, 0.44200, 0.55753, 0.60558, 0.65849, 0.69975, 0.69823, 0.55578, 0.52390, 0.60474, 0.63084, 0.69525, 0.63846, 0.68476, 0.75089, 0.85500, 0.90314, 0.94153, 0.93336, 0.98001, 0.85768, 0.75392, 0.73223, 0.81241, 0.81225, 0.87156, 0.90112, 0.93775, 1.10714, 1.32143, 1.42401, 1.38713, 1.37812, 1.42025, 1.40340, 1.39249, 1.46055, 1.54611, 1.51464, 1.32303, 1.28900, 1.26157, +-1.44111, -1.65125, -1.87576, -1.98007, -2.06578, -2.33388, -2.47669, -2.56795, -2.64537, -2.59592, -2.51591, -2.35531, -2.22251, -2.13933, -1.96182, -1.87213, -1.71036, -1.53290, -1.31586, -1.02291, -0.84537, -0.86432, -0.87246, -0.86245, -0.85171, -0.98114, -1.22610, -1.32259, -1.32092, -1.31449, -1.34368, -1.34530, -1.35155, -1.35858, -1.42862, -1.39346, -1.31687, -1.53928, -1.82676, -1.94384, -2.01089, -2.04510, -2.18927, -2.27513, -2.23271, -2.19831, -2.17954, -2.37578, -2.48007, -2.45723, -2.50569, -2.49857, -2.41329, -2.29860, -2.20258, -2.15319, -2.13719, -2.06501, -2.01622, -1.91967, -1.90211, -1.90465, -1.94895, -1.91290, -2.01707, -2.17456, -2.32616, -2.43087, -2.35997, -2.30483, -2.24638, -2.17011, -2.25641, -2.35931, -2.52336, -2.73658, -2.95151, -3.28394, -3.50056, -3.74548, -4.07487, -4.36963, -4.64331, -4.66206, -4.61992, -4.62750, -4.67592, -4.58015, -4.46752, -4.31365, -4.32843, -4.32051, -4.29638, -4.31430, -4.31850, -4.11002, -3.92612, -3.85722, -3.88574, -3.81655, -3.55043, -3.41216, -3.45342, -3.39527, -3.27198, -3.05561, -2.92582, -2.92147, -2.78151, -2.68609, -2.63764, -2.69309, -2.73216, -2.60866, -2.60144, -2.52769, -2.48358, -2.49070, -2.58603, -2.61212, -2.69198, -2.57469, -2.50618, -2.34431, -2.27623, -2.24862, -2.24983, -2.21759, -2.17284, -2.04452, -1.94204, -1.94409, -1.91518, -1.96058, -2.08871, -2.10636, -2.13194, -2.14995, -2.11037, -2.09049, -2.02751, -2.06125, -2.04423, -1.93256, -1.87218, -1.77183, -1.85095, -1.78727, -1.70178, -1.72482, -1.92632, -2.09764, -2.34094, -2.50424, -2.65157, -2.54009, -2.35886, -2.25664, -2.24568, -2.00238, -1.65832, -1.36016, -1.27594, -1.32295, -1.23755, -1.13731, -1.22451, -1.28313, -1.22874, -1.12974, -1.12304, -1.25717, -1.27800, -1.36614, -1.55030, -1.75436, -2.00169, -2.09223, -2.21310, -2.28571, -2.31328, -2.24298, -2.24830, -2.10226, -2.10158, -2.03982, -2.05614, -2.10776, -2.11332, -2.06300, -2.11312, -2.18370, -2.29127, -2.32496, -2.31109, -2.29962, -2.16375, -2.02523, -1.97660, -1.84311, -1.77686, -1.79646, -1.80467, -1.80863, -1.70922, -1.66042, -1.65921, -1.53023, -1.39103, -1.12937, -0.97457, -0.81787, -0.62798, -0.52320, -0.52010, -0.40740, -0.44113, -0.59600, -0.82363, -0.92452, -0.85584, -0.81942, -0.98129, -1.10020, -1.05444, -0.91951, -0.83337, -0.84427, -0.66338, -0.41922, -0.43768, -0.43304, -0.35731, -0.31335, -0.37961, -0.51874, -0.53375, -0.49159, -0.47695, -0.39169, -0.29834, 0.00677, 0.28504, 0.49874, 0.62733, 0.73471, 0.76007, 0.79048, 0.81216, 0.87649, 0.88090, 0.74835, 0.63183, 0.52690, 0.37880, 0.27093, 0.30653, 0.36834, 0.51907, 0.55827, 0.59030, 0.65902, 0.62921, 0.68199, 0.76801, 0.73907, 0.69279, 0.67944, 0.77368, 0.86823, 0.80732, 0.79603, 0.70666, 0.57190, 0.43610, 0.30658, 0.25538, 0.07552, -0.17574, -0.28203, -0.29401, -0.36919, -0.50884, -0.65983, -0.64275, -0.60640, -0.69335, -0.84390, -0.85113, -0.93958, -1.17406, -1.49317, -1.67524, -1.67657, -1.80947, -1.87893, -1.81644, -1.79216, -1.81860, -1.97501, -2.07186, -2.00781, -2.00268, -1.92495, -1.92072, -1.82320, -1.68503, -1.69216, -1.58445, -1.42339, -1.29007, -1.22792, -1.17072, -1.14520, -1.09954, -1.12492, -1.04529, -1.00145, -0.97695, -1.04271, -1.02940, -1.02242, -0.93366, -0.88823, -0.88452, -0.85964, -0.98627, -1.13237, -1.17963, -1.38133, -1.68721, -1.99850, -2.22690, -2.38572, -2.50035, -2.40548, -2.26700, -2.16497, -1.93635, -1.71934, -1.38072, -1.19617, -1.20228, -1.27581, -1.20108, -1.18442, -1.17738, -1.24818, -1.14315, -1.09122, -1.17816, -1.30791, -1.21105, -1.02903, -0.83380, -0.65263, -0.44244, -0.06392, 0.20525, 0.29028, 0.45767, 0.59879, 0.67827, 0.66109, 0.53697, 0.55787, 0.52911, 0.51694, 0.59035, 0.66980, 0.81292, 0.76894, 0.83138, 0.96800, 1.10640, 1.14437, 1.23900, 1.21051, 1.26706, 1.15451, 1.04637, 0.95737, 0.96070, 0.97306, 1.05363, 1.09455, 1.15883, 1.29079, 1.41897, 1.62117, 1.67174, 1.62000, 1.66550, 1.64362, 1.63682, 1.65302, 1.58296, 1.54263, 1.45201, 1.39744, 1.32460, +-1.46045, -1.67067, -1.88606, -2.08800, -2.23903, -2.40613, -2.48617, -2.50022, -2.56299, -2.56117, -2.45960, -2.25700, -2.09331, -1.95207, -1.82309, -1.81261, -1.62059, -1.41807, -1.18419, -0.95574, -0.87149, -0.86140, -0.81939, -0.76392, -0.81128, -0.95174, -1.18857, -1.38266, -1.48295, -1.46919, -1.38437, -1.39289, -1.36915, -1.38463, -1.51102, -1.61578, -1.65310, -1.79761, -2.00366, -2.04860, -2.10985, -2.16455, -2.22989, -2.27717, -2.27179, -2.26316, -2.29686, -2.57240, -2.65769, -2.64212, -2.69200, -2.70336, -2.66030, -2.47823, -2.30863, -2.21131, -2.29070, -2.29368, -2.18514, -2.11201, -2.14182, -2.19578, -2.20178, -2.27721, -2.38985, -2.52312, -2.64250, -2.74971, -2.71243, -2.54964, -2.41959, -2.24566, -2.25019, -2.38475, -2.49594, -2.63831, -2.82949, -3.11670, -3.34357, -3.73142, -4.08101, -4.36981, -4.64406, -4.70132, -4.76581, -4.79610, -4.85123, -4.76235, -4.67871, -4.53103, -4.38916, -4.34209, -4.35167, -4.46966, -4.49095, -4.43514, -4.28692, -4.19817, -4.18193, -4.12381, -3.94403, -3.68195, -3.59642, -3.46659, -3.33791, -3.27005, -3.17473, -3.13792, -3.02720, -2.95224, -2.90215, -3.06392, -3.08076, -2.89980, -2.86828, -2.81036, -2.91062, -2.98406, -3.02292, -2.96294, -2.98524, -2.89011, -2.72834, -2.58472, -2.55334, -2.60832, -2.53130, -2.53694, -2.46542, -2.28724, -2.14255, -2.07888, -2.07123, -2.03608, -2.06631, -1.99555, -1.93860, -2.00122, -1.95830, -1.90944, -1.84461, -1.84575, -1.76594, -1.74978, -1.70962, -1.59695, -1.71402, -1.68943, -1.68875, -1.71923, -1.79873, -1.87470, -2.09434, -2.36275, -2.52199, -2.45865, -2.31632, -2.28985, -2.15828, -1.94264, -1.61405, -1.23606, -1.10133, -1.14458, -1.20910, -1.17507, -1.21417, -1.21333, -1.12989, -1.13973, -1.17461, -1.26423, -1.24895, -1.29627, -1.41882, -1.74341, -2.11399, -2.24182, -2.35071, -2.37250, -2.42381, -2.38884, -2.34553, -2.16060, -2.11831, -2.11276, -2.06382, -2.06365, -2.07235, -2.12701, -2.11812, -2.17522, -2.28641, -2.27642, -2.23311, -2.16629, -2.08858, -1.94749, -1.81027, -1.62060, -1.47488, -1.50401, -1.51053, -1.46867, -1.37127, -1.35610, -1.37017, -1.38894, -1.35295, -1.07595, -0.86653, -0.65579, -0.51672, -0.51429, -0.54527, -0.41863, -0.39581, -0.56529, -0.69027, -0.72973, -0.67671, -0.68068, -0.76692, -0.89235, -0.96421, -0.87648, -0.78998, -0.74624, -0.64760, -0.47018, -0.40142, -0.33040, -0.17887, -0.15431, -0.28463, -0.44623, -0.54611, -0.57635, -0.52383, -0.48522, -0.46602, -0.16620, 0.10230, 0.31934, 0.41096, 0.46771, 0.56121, 0.70360, 0.83478, 0.86989, 0.90915, 0.86509, 0.72693, 0.52392, 0.37331, 0.30025, 0.27934, 0.37503, 0.54077, 0.59733, 0.56217, 0.57584, 0.65158, 0.75845, 0.88361, 0.81352, 0.64693, 0.61535, 0.71787, 0.83296, 0.88221, 0.87054, 0.67348, 0.48116, 0.25739, 0.09049, -0.00642, -0.23823, -0.42802, -0.48574, -0.42020, -0.45264, -0.52630, -0.60556, -0.67133, -0.75530, -0.86590, -0.95087, -1.06196, -1.17582, -1.39697, -1.67062, -1.86317, -1.91601, -1.96012, -2.02300, -2.00790, -2.02940, -2.12700, -2.23746, -2.29100, -2.25265, -2.23432, -2.19104, -2.29916, -2.19063, -2.01735, -1.96179, -1.83352, -1.73379, -1.56328, -1.40896, -1.26881, -1.24963, -1.20649, -1.13187, -1.05550, -1.03510, -1.04603, -1.02377, -1.04592, -0.97297, -0.79607, -0.68850, -0.69263, -0.75287, -0.81870, -0.90246, -0.87907, -1.00645, -1.32717, -1.61169, -1.83618, -2.10344, -2.32493, -2.30563, -2.32950, -2.22131, -1.94143, -1.70577, -1.32984, -1.12488, -1.05981, -1.05978, -0.96466, -0.98103, -1.00558, -0.98814, -0.93531, -0.96611, -1.14324, -1.18507, -1.12463, -0.91534, -0.67340, -0.51183, -0.39276, -0.14827, 0.17307, 0.33219, 0.53485, 0.67172, 0.63787, 0.59523, 0.50289, 0.51412, 0.50670, 0.55661, 0.53954, 0.60974, 0.80118, 0.81671, 0.93075, 1.03518, 1.19767, 1.32602, 1.50092, 1.50603, 1.49398, 1.43923, 1.32863, 1.22934, 1.17063, 1.27847, 1.31311, 1.31560, 1.36433, 1.47898, 1.60705, 1.75232, 1.88790, 1.92195, 1.99159, 1.92762, 1.74724, 1.70120, 1.65361, 1.63540, 1.56830, 1.53814, 1.37988, +-1.27350, -1.53810, -1.74311, -2.00658, -2.21618, -2.31345, -2.45973, -2.51646, -2.49664, -2.48459, -2.45183, -2.29547, -2.16516, -2.02554, -1.79992, -1.73317, -1.55340, -1.34906, -1.11457, -0.97636, -0.95473, -0.89397, -0.88867, -0.88273, -0.96831, -1.11283, -1.29982, -1.47810, -1.54844, -1.46920, -1.32529, -1.30323, -1.29907, -1.33711, -1.43221, -1.60514, -1.78700, -1.93179, -2.11335, -2.18246, -2.17574, -2.17881, -2.26629, -2.34237, -2.40869, -2.49378, -2.43138, -2.55149, -2.64306, -2.73337, -2.82315, -2.83272, -2.81649, -2.61400, -2.48692, -2.45778, -2.57240, -2.59501, -2.44703, -2.35654, -2.31440, -2.32450, -2.33713, -2.47773, -2.62615, -2.76690, -2.83046, -2.86385, -2.85196, -2.68351, -2.60517, -2.53596, -2.44832, -2.48245, -2.58553, -2.73650, -2.90507, -3.17825, -3.33252, -3.67121, -4.06589, -4.38163, -4.62661, -4.72163, -4.88901, -4.94423, -5.01632, -5.00793, -4.94205, -4.80594, -4.61349, -4.56609, -4.54291, -4.54356, -4.51923, -4.52036, -4.46395, -4.43129, -4.31763, -4.17909, -4.06871, -3.81601, -3.74391, -3.73443, -3.61005, -3.53347, -3.42973, -3.36568, -3.27408, -3.31928, -3.24356, -3.25688, -3.28337, -3.16244, -3.11840, -3.06145, -3.24304, -3.32810, -3.35173, -3.33662, -3.29086, -3.21822, -3.05649, -2.99963, -2.96188, -2.89702, -2.74529, -2.69066, -2.60310, -2.47262, -2.31383, -2.15459, -2.13256, -2.06735, -2.06764, -2.09417, -1.96019, -1.88440, -1.83468, -1.86862, -1.82332, -1.83048, -1.64838, -1.49480, -1.49118, -1.45220, -1.53707, -1.47638, -1.53006, -1.56972, -1.63130, -1.80919, -2.01304, -2.24510, -2.37080, -2.39562, -2.32114, -2.20014, -1.90294, -1.61507, -1.30512, -0.99646, -0.88943, -0.88810, -1.06095, -1.12594, -1.12480, -1.18704, -1.11792, -1.12252, -1.16650, -1.26840, -1.26924, -1.37536, -1.44741, -1.63484, -2.04044, -2.25200, -2.34743, -2.28630, -2.32316, -2.32913, -2.31400, -2.31103, -2.27139, -2.23602, -2.14263, -2.13585, -2.16901, -2.19703, -2.14408, -2.15044, -2.22439, -2.22959, -2.18550, -2.02345, -1.92357, -1.78051, -1.62913, -1.59126, -1.45448, -1.33564, -1.24577, -1.22918, -1.18326, -1.23900, -1.20544, -1.08986, -1.08343, -0.92243, -0.76271, -0.55159, -0.44743, -0.43476, -0.46516, -0.51275, -0.55048, -0.65405, -0.61799, -0.61042, -0.58528, -0.54762, -0.55912, -0.64807, -0.79554, -0.81426, -0.72819, -0.56307, -0.49518, -0.43777, -0.34639, -0.33971, -0.24057, -0.13999, -0.21029, -0.40557, -0.58175, -0.68947, -0.61776, -0.40283, -0.32604, -0.15118, 0.01424, 0.17462, 0.25295, 0.32435, 0.46789, 0.55486, 0.65020, 0.66966, 0.71765, 0.68921, 0.53049, 0.35946, 0.28672, 0.28431, 0.31382, 0.42100, 0.53415, 0.59465, 0.56600, 0.56712, 0.71125, 0.73409, 0.74004, 0.72924, 0.65537, 0.62105, 0.65952, 0.70143, 0.73370, 0.82174, 0.68748, 0.46284, 0.15459, -0.08461, -0.25128, -0.45494, -0.50905, -0.60483, -0.60130, -0.61519, -0.64900, -0.70903, -0.88268, -0.98580, -0.96394, -0.94191, -1.08765, -1.30659, -1.56899, -1.77587, -1.94434, -2.04588, -2.04022, -2.15303, -2.28541, -2.25972, -2.25424, -2.29659, -2.36700, -2.43128, -2.50922, -2.44658, -2.45509, -2.36226, -2.22586, -2.13954, -2.02587, -1.97708, -1.79438, -1.67221, -1.60212, -1.56544, -1.49992, -1.36690, -1.27983, -1.19241, -1.11056, -1.02904, -0.97427, -0.81997, -0.60283, -0.45239, -0.43005, -0.51756, -0.49408, -0.55017, -0.64785, -0.73088, -0.95702, -1.23859, -1.50385, -1.81265, -2.16906, -2.21746, -2.22650, -2.11629, -1.81762, -1.57473, -1.20663, -1.01679, -0.89431, -0.89132, -0.95014, -0.96705, -0.91673, -0.81156, -0.84763, -0.95383, -1.04889, -1.02443, -0.95992, -0.76256, -0.53911, -0.37489, -0.24968, -0.06196, 0.29995, 0.53807, 0.61377, 0.70500, 0.69000, 0.60380, 0.49185, 0.49034, 0.42782, 0.52793, 0.60938, 0.63439, 0.75196, 0.78176, 0.92736, 1.01945, 1.21801, 1.38452, 1.48890, 1.53415, 1.49661, 1.44726, 1.33616, 1.30412, 1.38841, 1.56656, 1.61756, 1.63686, 1.69307, 1.81431, 1.96337, 2.03773, 2.16038, 2.20990, 2.15147, 2.08937, 1.92335, 1.79293, 1.65139, 1.66160, 1.59268, 1.57376, 1.52450, +-1.09299, -1.35457, -1.62973, -1.94396, -2.05822, -2.13219, -2.25968, -2.32035, -2.32505, -2.31542, -2.33485, -2.33073, -2.21569, -1.99473, -1.76771, -1.72595, -1.64799, -1.39958, -1.17216, -1.10258, -1.07197, -0.96691, -0.98823, -1.03412, -1.07366, -1.30084, -1.51189, -1.58869, -1.61833, -1.58034, -1.50774, -1.47424, -1.47935, -1.41490, -1.41476, -1.60468, -1.77483, -1.98990, -2.16585, -2.19445, -2.20243, -2.19712, -2.33501, -2.52740, -2.62974, -2.61332, -2.48303, -2.51732, -2.64885, -2.76625, -2.86778, -2.94170, -2.95759, -2.81629, -2.73364, -2.73095, -2.71479, -2.74121, -2.64070, -2.47920, -2.39151, -2.45292, -2.54939, -2.69837, -2.82867, -2.87629, -2.91222, -2.97362, -2.89524, -2.75572, -2.71858, -2.64746, -2.58027, -2.54298, -2.63350, -2.88749, -3.08683, -3.20485, -3.32398, -3.64712, -4.09571, -4.42336, -4.62891, -4.86214, -5.08330, -5.17258, -5.22635, -5.25440, -5.12435, -5.04116, -4.96298, -4.89142, -4.81601, -4.70633, -4.61145, -4.57240, -4.58557, -4.58477, -4.46067, -4.38926, -4.25109, -4.04788, -4.05575, -4.02311, -3.94017, -3.80120, -3.62267, -3.56850, -3.51939, -3.47726, -3.39056, -3.35937, -3.47232, -3.47372, -3.38041, -3.38875, -3.51187, -3.54898, -3.53330, -3.55904, -3.43139, -3.39556, -3.35705, -3.32234, -3.21779, -3.06967, -2.94993, -2.85286, -2.76114, -2.61645, -2.42022, -2.31655, -2.21611, -2.08636, -2.11345, -2.10784, -1.97898, -1.80990, -1.72108, -1.82190, -1.85366, -1.72660, -1.48950, -1.33507, -1.39954, -1.45376, -1.42046, -1.39363, -1.44256, -1.51047, -1.59109, -1.87052, -2.00601, -2.09086, -2.18767, -2.22402, -2.17874, -2.05718, -1.78497, -1.46615, -1.16620, -0.90938, -0.81298, -0.88934, -1.05382, -1.06710, -1.05557, -1.02956, -0.97736, -0.98143, -1.00819, -1.14448, -1.29949, -1.38198, -1.39992, -1.52863, -1.91017, -2.19103, -2.20518, -2.18001, -2.21742, -2.27227, -2.27034, -2.38543, -2.27740, -2.12843, -2.11031, -2.13535, -2.16083, -2.17802, -2.18532, -2.19387, -2.22490, -2.20029, -2.10626, -2.00826, -1.87836, -1.64283, -1.52840, -1.47069, -1.33111, -1.14467, -0.99078, -1.02437, -1.12382, -1.13721, -0.99384, -0.83426, -0.88390, -0.91553, -0.78982, -0.67716, -0.59527, -0.47834, -0.38692, -0.51394, -0.57533, -0.57891, -0.55413, -0.56192, -0.51243, -0.48545, -0.56236, -0.67056, -0.82192, -0.84764, -0.67216, -0.49969, -0.43152, -0.33450, -0.27444, -0.23817, -0.19377, -0.12543, -0.13322, -0.30473, -0.55123, -0.60798, -0.43730, -0.17351, -0.12214, -0.13494, -0.00282, 0.09192, 0.17054, 0.29178, 0.46820, 0.50273, 0.56677, 0.66520, 0.63190, 0.51486, 0.38775, 0.25045, 0.14188, 0.10367, 0.18868, 0.32376, 0.48275, 0.50785, 0.46330, 0.56020, 0.68000, 0.65872, 0.62273, 0.59930, 0.62525, 0.61244, 0.50740, 0.47735, 0.54969, 0.62974, 0.51538, 0.30339, 0.08281, -0.18267, -0.46119, -0.65845, -0.65487, -0.76615, -0.81331, -0.76980, -0.87819, -1.00826, -1.16448, -1.21046, -1.12516, -1.07685, -1.18194, -1.43366, -1.64174, -1.84328, -2.10631, -2.17447, -2.15992, -2.24741, -2.31839, -2.27543, -2.18251, -2.17639, -2.36788, -2.54455, -2.57377, -2.53555, -2.50175, -2.47189, -2.36300, -2.25429, -2.23780, -2.18477, -2.00845, -1.91221, -1.89163, -1.74906, -1.71841, -1.66513, -1.51404, -1.34025, -1.20554, -1.11963, -0.96100, -0.73612, -0.44807, -0.29890, -0.34720, -0.33921, -0.22647, -0.25541, -0.32931, -0.47173, -0.67067, -0.94999, -1.28581, -1.57040, -1.78777, -1.91173, -2.01000, -2.01143, -1.76206, -1.47937, -1.23011, -1.05422, -0.91621, -0.87538, -0.98848, -0.86506, -0.73433, -0.66156, -0.69412, -0.81188, -0.88340, -0.92675, -0.91232, -0.76163, -0.49537, -0.26361, -0.15595, 0.12487, 0.55189, 0.80529, 0.89323, 0.88840, 0.87906, 0.79730, 0.65758, 0.58218, 0.61029, 0.70447, 0.76204, 0.70981, 0.71853, 0.79389, 0.85961, 0.98270, 1.18081, 1.36636, 1.42011, 1.56748, 1.56887, 1.43855, 1.36120, 1.41210, 1.55818, 1.67637, 1.73680, 1.79459, 1.92954, 2.10080, 2.14111, 2.18822, 2.30169, 2.28831, 2.28525, 2.28866, 2.19845, 2.02129, 1.74549, 1.62207, 1.64183, 1.63558, 1.56294, +-0.98080, -1.27796, -1.52586, -1.80123, -1.88793, -1.99058, -2.12198, -2.19860, -2.26716, -2.29226, -2.20551, -2.16992, -2.15255, -1.96952, -1.79784, -1.83419, -1.78457, -1.48553, -1.21767, -1.10826, -1.10450, -1.03295, -1.01217, -1.04841, -1.11287, -1.41577, -1.64568, -1.68003, -1.71833, -1.71709, -1.69001, -1.67449, -1.72295, -1.64273, -1.51666, -1.60791, -1.75596, -2.05229, -2.27664, -2.30754, -2.34580, -2.36333, -2.41166, -2.52465, -2.69463, -2.67492, -2.52906, -2.57737, -2.67053, -2.69527, -2.76282, -2.86297, -2.98841, -2.98908, -2.89602, -2.83089, -2.76732, -2.82696, -2.73561, -2.51203, -2.44557, -2.55174, -2.67457, -2.81356, -2.91951, -2.95229, -2.94425, -2.97278, -2.89310, -2.83009, -2.81758, -2.74244, -2.71746, -2.70709, -2.72842, -2.89227, -3.16767, -3.31032, -3.41343, -3.73113, -4.13971, -4.39533, -4.58861, -4.87803, -5.17465, -5.37715, -5.43715, -5.44076, -5.31569, -5.30182, -5.24399, -5.07799, -4.95936, -4.79540, -4.62768, -4.55382, -4.60071, -4.71905, -4.67076, -4.63240, -4.51449, -4.40063, -4.44473, -4.39532, -4.32373, -4.15955, -3.86919, -3.63643, -3.59844, -3.57328, -3.48312, -3.49995, -3.64772, -3.63459, -3.50891, -3.50124, -3.60015, -3.69399, -3.65315, -3.62934, -3.52393, -3.57846, -3.58550, -3.46656, -3.29314, -3.12228, -3.02296, -2.93077, -2.83483, -2.72336, -2.49007, -2.34354, -2.20202, -2.09649, -2.13981, -2.12716, -2.02577, -1.87211, -1.71936, -1.62429, -1.67374, -1.61621, -1.41625, -1.35406, -1.44323, -1.44979, -1.37453, -1.34137, -1.38568, -1.54195, -1.61235, -1.81533, -1.90711, -1.96251, -2.00824, -1.95608, -1.90735, -1.86873, -1.70064, -1.42618, -1.13557, -0.93831, -0.82493, -0.85851, -0.97006, -0.97569, -0.97035, -0.91738, -0.86692, -0.89240, -0.90207, -0.88729, -1.09888, -1.29670, -1.32654, -1.48690, -1.85056, -2.08281, -2.06825, -2.06817, -2.15356, -2.32626, -2.33057, -2.35721, -2.16999, -2.01552, -2.03836, -2.00961, -1.98609, -1.99688, -2.01526, -2.02102, -2.02038, -2.02295, -1.93044, -1.84584, -1.71765, -1.50955, -1.42507, -1.32803, -1.18848, -1.04504, -0.91088, -0.81949, -0.91878, -1.02520, -0.92368, -0.84284, -0.94657, -0.99606, -0.86422, -0.77089, -0.70053, -0.60805, -0.45041, -0.46865, -0.47288, -0.50377, -0.54610, -0.50495, -0.38970, -0.36622, -0.47174, -0.60900, -0.75791, -0.81784, -0.64984, -0.46129, -0.34777, -0.23640, -0.21263, -0.15939, -0.13479, -0.11837, -0.11246, -0.11115, -0.27311, -0.38668, -0.24259, -0.04858, -0.08164, -0.12392, 0.03993, 0.16062, 0.27164, 0.33485, 0.46573, 0.55612, 0.67156, 0.78073, 0.69601, 0.58676, 0.52004, 0.38388, 0.23114, 0.12860, 0.19082, 0.28083, 0.43097, 0.49755, 0.47859, 0.55556, 0.57312, 0.50306, 0.44728, 0.35931, 0.33359, 0.40082, 0.34013, 0.20630, 0.22620, 0.26592, 0.12911, 0.01100, -0.05125, -0.25662, -0.54803, -0.85400, -0.94752, -1.00189, -0.98670, -0.93713, -1.11700, -1.25281, -1.31998, -1.31728, -1.22098, -1.16849, -1.22223, -1.44674, -1.64739, -1.81622, -2.08636, -2.17778, -2.22446, -2.29752, -2.31355, -2.28208, -2.20727, -2.13209, -2.26235, -2.54091, -2.63565, -2.63061, -2.63838, -2.62820, -2.48242, -2.34562, -2.32363, -2.29707, -2.18485, -2.03382, -1.92557, -1.73503, -1.75831, -1.72997, -1.48732, -1.25371, -1.06173, -0.92552, -0.73029, -0.51357, -0.28944, -0.14281, -0.16653, -0.15360, -0.11654, -0.16320, -0.20429, -0.36335, -0.57695, -0.78521, -0.97604, -1.25173, -1.46778, -1.63565, -1.85948, -1.97987, -1.75649, -1.45977, -1.22388, -1.07168, -0.99495, -0.87577, -0.84300, -0.61287, -0.49262, -0.42957, -0.35956, -0.44220, -0.53929, -0.65322, -0.72829, -0.64764, -0.44137, -0.16349, 0.01785, 0.34999, 0.74320, 0.97453, 1.06888, 1.03280, 0.99092, 0.97207, 1.01405, 0.89095, 0.83823, 0.89840, 0.87901, 0.79754, 0.83924, 0.94757, 1.01486, 1.12872, 1.21542, 1.39770, 1.53481, 1.74169, 1.74609, 1.62112, 1.63534, 1.72368, 1.84036, 1.90730, 1.94401, 1.97628, 2.02699, 2.18650, 2.23215, 2.27686, 2.32337, 2.25755, 2.27767, 2.32292, 2.23960, 2.05887, 1.87814, 1.62993, 1.51527, 1.48596, 1.35049, +-0.78653, -1.13642, -1.41229, -1.60990, -1.70701, -1.88929, -2.07464, -2.20649, -2.23913, -2.27413, -2.22434, -2.17345, -2.13600, -2.03399, -1.92677, -1.89757, -1.83801, -1.57742, -1.36972, -1.21975, -1.05560, -1.00507, -1.01552, -1.10851, -1.27961, -1.59332, -1.81379, -1.88630, -1.98794, -1.98132, -1.92507, -1.85164, -1.86036, -1.81646, -1.68430, -1.65065, -1.76071, -2.11628, -2.37485, -2.44935, -2.45005, -2.45192, -2.50795, -2.57036, -2.69566, -2.70717, -2.61272, -2.57500, -2.61088, -2.63532, -2.74713, -2.86231, -2.89122, -2.95605, -2.95993, -2.89177, -2.86668, -2.90217, -2.80113, -2.60687, -2.62334, -2.72946, -2.83378, -2.89543, -2.87433, -2.88770, -2.93225, -2.94182, -2.89349, -2.96380, -2.99067, -2.94288, -2.87271, -2.81074, -2.86020, -2.98773, -3.24571, -3.44554, -3.62766, -3.83804, -4.12495, -4.32813, -4.57423, -4.95843, -5.21986, -5.45489, -5.62308, -5.62556, -5.58964, -5.58682, -5.45788, -5.23084, -5.14787, -4.96129, -4.74261, -4.60434, -4.58592, -4.74603, -4.84888, -4.87140, -4.80418, -4.83488, -4.87304, -4.81304, -4.66987, -4.36955, -4.06025, -3.76579, -3.68492, -3.69187, -3.68673, -3.63598, -3.67306, -3.62638, -3.55081, -3.58969, -3.58342, -3.62106, -3.68365, -3.66157, -3.67931, -3.80048, -3.80852, -3.63684, -3.46317, -3.28839, -3.19712, -3.09430, -2.93054, -2.78652, -2.60270, -2.43218, -2.22427, -2.18151, -2.20416, -2.18139, -2.06358, -1.82659, -1.69827, -1.55085, -1.54352, -1.51063, -1.47009, -1.47567, -1.52702, -1.49841, -1.44323, -1.44751, -1.41573, -1.47949, -1.57967, -1.70268, -1.84003, -1.91188, -1.90698, -1.80104, -1.81164, -1.84975, -1.76503, -1.54154, -1.22814, -0.98833, -0.86590, -0.83947, -0.83282, -0.86487, -0.86924, -0.83324, -0.79550, -0.74574, -0.77700, -0.73370, -0.88109, -1.08617, -1.24587, -1.42593, -1.68948, -1.87567, -1.92440, -2.04545, -2.15240, -2.26785, -2.36429, -2.32915, -2.13741, -2.02120, -2.04545, -1.97354, -1.96258, -1.97295, -1.94835, -1.89644, -1.77705, -1.68730, -1.62840, -1.58434, -1.44501, -1.33989, -1.32435, -1.23448, -1.08603, -0.86136, -0.79172, -0.76960, -0.85890, -0.97102, -0.99888, -0.97924, -1.02197, -1.02127, -0.88088, -0.85955, -0.80294, -0.61754, -0.51147, -0.48297, -0.47401, -0.55503, -0.61907, -0.54226, -0.45844, -0.45824, -0.50491, -0.61067, -0.67729, -0.66093, -0.55639, -0.42992, -0.27784, -0.21334, -0.23256, -0.14310, -0.05402, 0.07248, 0.08177, 0.08241, -0.00582, -0.08185, -0.05476, 0.03309, 0.02623, 0.00349, 0.14151, 0.21699, 0.35085, 0.49063, 0.50859, 0.55944, 0.67909, 0.74395, 0.67435, 0.62471, 0.57751, 0.42497, 0.30511, 0.19327, 0.26263, 0.37062, 0.44849, 0.47513, 0.52165, 0.55707, 0.41949, 0.25471, 0.16421, 0.12219, 0.07474, 0.07594, 0.01780, -0.08430, -0.11233, -0.14047, -0.20249, -0.22597, -0.22327, -0.44186, -0.72894, -0.97254, -1.17472, -1.29026, -1.27404, -1.28213, -1.43895, -1.52887, -1.55823, -1.55959, -1.43228, -1.35354, -1.32763, -1.42879, -1.59413, -1.75374, -1.92743, -2.03387, -2.21488, -2.30791, -2.29472, -2.18826, -2.09019, -2.08803, -2.22575, -2.49832, -2.67890, -2.76526, -2.72194, -2.70869, -2.60946, -2.53965, -2.52719, -2.40071, -2.30286, -2.17797, -1.97435, -1.78404, -1.75475, -1.66732, -1.39040, -1.16598, -0.91497, -0.70199, -0.42778, -0.15421, -0.02034, -0.00496, -0.00750, -0.00350, -0.10724, -0.18114, -0.21388, -0.26199, -0.33542, -0.55547, -0.71845, -0.93827, -1.16664, -1.43708, -1.65068, -1.80760, -1.68228, -1.48959, -1.33640, -1.10806, -0.97995, -0.88190, -0.71191, -0.46152, -0.32479, -0.23490, -0.13340, -0.24575, -0.33819, -0.43372, -0.48206, -0.38703, -0.22685, -0.00813, 0.24211, 0.63377, 0.92539, 1.12931, 1.21040, 1.21564, 1.26373, 1.23870, 1.32028, 1.20375, 1.08510, 1.01066, 0.99972, 0.95734, 0.99663, 1.07312, 1.10558, 1.28642, 1.42029, 1.50788, 1.69200, 1.85972, 1.86678, 1.81314, 1.91370, 1.97254, 2.01211, 2.01650, 2.04804, 2.10656, 2.13713, 2.20524, 2.24363, 2.36508, 2.34972, 2.24123, 2.21961, 2.28065, 2.29240, 2.05477, 1.84211, 1.53848, 1.32902, 1.15727, 1.00054, +-0.76476, -1.10962, -1.40485, -1.57675, -1.59119, -1.77631, -2.01921, -2.20175, -2.31042, -2.41392, -2.38752, -2.34154, -2.20278, -2.04581, -1.93751, -1.83229, -1.83999, -1.69263, -1.54397, -1.38814, -1.17947, -1.14990, -1.16572, -1.30776, -1.48393, -1.74877, -1.96257, -2.05617, -2.15530, -2.09995, -2.04039, -1.98632, -2.02637, -2.07428, -2.00022, -1.92277, -1.89512, -2.06818, -2.23576, -2.31596, -2.41342, -2.52607, -2.54604, -2.53751, -2.55263, -2.50819, -2.47192, -2.39051, -2.47286, -2.60845, -2.72859, -2.79643, -2.75242, -2.89569, -3.02389, -3.03951, -3.00735, -2.96395, -2.90675, -2.78802, -2.80317, -2.81457, -2.91413, -2.96922, -2.88935, -2.93476, -3.04236, -3.10030, -3.02926, -3.05619, -3.12120, -3.09685, -3.06510, -3.07507, -3.11089, -3.16960, -3.35862, -3.49123, -3.74279, -3.91431, -4.13210, -4.32699, -4.53499, -4.91887, -5.19424, -5.52136, -5.74317, -5.75994, -5.74948, -5.68220, -5.51875, -5.31240, -5.27115, -5.06563, -4.88082, -4.77892, -4.72049, -4.84627, -4.97438, -5.09022, -5.08173, -5.07515, -5.05292, -4.91787, -4.75028, -4.51594, -4.22623, -3.89232, -3.78332, -3.72650, -3.75510, -3.62715, -3.53837, -3.52597, -3.51096, -3.58581, -3.55451, -3.64898, -3.81401, -3.85660, -3.91529, -3.97554, -4.00165, -3.84348, -3.67893, -3.46994, -3.41131, -3.37660, -3.17475, -3.03192, -2.89233, -2.76472, -2.50408, -2.31276, -2.24753, -2.13212, -2.01284, -1.86769, -1.80013, -1.64040, -1.55667, -1.38452, -1.39598, -1.44607, -1.49625, -1.52566, -1.44840, -1.40192, -1.32583, -1.41096, -1.51202, -1.62971, -1.81205, -1.85386, -1.86552, -1.78619, -1.82699, -1.77708, -1.69206, -1.60164, -1.35414, -1.13029, -0.94090, -0.85150, -0.75001, -0.66606, -0.66737, -0.61847, -0.63984, -0.72018, -0.78680, -0.68303, -0.70182, -0.77140, -1.01764, -1.24733, -1.46172, -1.70396, -1.83451, -2.00657, -2.10232, -2.25789, -2.43040, -2.40456, -2.24762, -2.10902, -2.14878, -2.09411, -2.07226, -1.99612, -1.91198, -1.86818, -1.67063, -1.51967, -1.44340, -1.42359, -1.31809, -1.17580, -1.20941, -1.13809, -0.97443, -0.80124, -0.79154, -0.80690, -0.88686, -0.88201, -0.90589, -0.88923, -0.88808, -0.91447, -0.77837, -0.78803, -0.77814, -0.69832, -0.71097, -0.71410, -0.70377, -0.65488, -0.66169, -0.62794, -0.62397, -0.58062, -0.49494, -0.57395, -0.60276, -0.59451, -0.56516, -0.50726, -0.40247, -0.28411, -0.23595, -0.04616, 0.17984, 0.28494, 0.19549, 0.16563, 0.12467, 0.17085, 0.17712, 0.21335, 0.26198, 0.20516, 0.27721, 0.33958, 0.46147, 0.51580, 0.37736, 0.34939, 0.45308, 0.56704, 0.54604, 0.50221, 0.46692, 0.38228, 0.37884, 0.25953, 0.26432, 0.30633, 0.24929, 0.20085, 0.27234, 0.39768, 0.28854, 0.08469, -0.00602, -0.08702, -0.20093, -0.22337, -0.28848, -0.28054, -0.23131, -0.30270, -0.34742, -0.41774, -0.46796, -0.67433, -0.90597, -1.08863, -1.38040, -1.59504, -1.66033, -1.64475, -1.67747, -1.72918, -1.76227, -1.76732, -1.58578, -1.51062, -1.51116, -1.56118, -1.68615, -1.77743, -1.84460, -1.89909, -2.08967, -2.22293, -2.16973, -2.08054, -2.09239, -2.12331, -2.22261, -2.40955, -2.52983, -2.66215, -2.62039, -2.69005, -2.72743, -2.69337, -2.64684, -2.51014, -2.51549, -2.43737, -2.19335, -1.92024, -1.71247, -1.55087, -1.28276, -1.05136, -0.73765, -0.49476, -0.20983, 0.09282, 0.14282, 0.05569, 0.02129, 0.06450, 0.04075, -0.02229, -0.01145, 0.00859, -0.06062, -0.28785, -0.45568, -0.64134, -0.77177, -1.07813, -1.24179, -1.37273, -1.39072, -1.32354, -1.26601, -1.04506, -0.95146, -0.87186, -0.67802, -0.43119, -0.21477, -0.12211, -0.07592, -0.19917, -0.18656, -0.19859, -0.22056, -0.15330, -0.11227, 0.02902, 0.28691, 0.72846, 1.09240, 1.31494, 1.46778, 1.49731, 1.47595, 1.43523, 1.51321, 1.39875, 1.34981, 1.21553, 1.22083, 1.17239, 1.08669, 1.11623, 1.15842, 1.36570, 1.46618, 1.49841, 1.64653, 1.77207, 1.83158, 1.82956, 1.98405, 2.06782, 2.14001, 2.09718, 2.05113, 2.11046, 2.11606, 2.13169, 2.13378, 2.33347, 2.45604, 2.33451, 2.27731, 2.27043, 2.16196, 1.85491, 1.66217, 1.41851, 1.28997, 1.01675, 0.80584, +-0.84109, -1.10356, -1.28095, -1.46513, -1.53257, -1.70326, -1.97671, -2.26107, -2.42349, -2.52319, -2.47244, -2.37763, -2.25027, -2.11667, -2.01349, -1.92746, -1.93487, -1.89974, -1.75812, -1.56693, -1.47529, -1.37885, -1.24341, -1.38779, -1.56458, -1.75354, -1.98145, -2.10888, -2.12959, -2.10495, -2.08638, -2.07144, -2.25043, -2.34432, -2.19143, -2.08570, -2.04777, -2.03132, -2.03491, -2.15643, -2.34313, -2.48885, -2.45631, -2.33654, -2.32478, -2.36257, -2.38929, -2.33028, -2.37836, -2.56579, -2.66534, -2.61797, -2.68452, -2.87409, -2.97265, -3.09278, -3.11977, -3.01868, -3.02455, -3.01336, -2.91997, -2.87196, -2.96027, -2.95712, -2.95014, -3.02925, -3.06464, -3.11555, -3.09876, -3.09708, -3.16872, -3.27490, -3.36074, -3.41406, -3.42830, -3.39068, -3.54316, -3.70853, -3.97996, -4.18003, -4.31575, -4.46063, -4.58578, -4.75698, -5.10125, -5.46168, -5.56724, -5.61459, -5.67529, -5.58906, -5.49976, -5.46706, -5.41449, -5.22056, -5.07822, -4.92882, -4.92131, -5.00135, -4.96392, -5.04438, -5.13997, -5.11744, -5.01192, -4.89710, -4.79070, -4.63411, -4.37144, -3.95287, -3.80075, -3.78641, -3.81313, -3.68799, -3.54037, -3.54315, -3.61251, -3.58765, -3.64778, -3.82491, -3.92514, -4.00866, -4.10876, -4.10551, -4.13574, -4.09068, -3.89802, -3.66891, -3.66334, -3.56747, -3.37691, -3.28523, -3.09690, -2.95311, -2.76969, -2.52945, -2.36260, -2.24967, -2.18877, -2.07620, -2.00979, -1.78135, -1.61647, -1.45114, -1.42431, -1.45868, -1.48180, -1.47899, -1.42975, -1.21590, -1.17258, -1.36513, -1.39927, -1.54256, -1.80553, -1.82555, -1.81032, -1.83329, -1.84856, -1.66740, -1.57168, -1.46896, -1.30993, -1.18036, -0.87765, -0.64855, -0.57095, -0.51496, -0.48933, -0.46407, -0.58118, -0.73501, -0.79487, -0.60842, -0.54169, -0.66264, -0.96782, -1.25164, -1.45733, -1.65852, -1.89149, -1.95384, -2.02404, -2.28262, -2.38222, -2.34151, -2.30096, -2.19358, -2.21282, -2.22606, -2.14401, -1.94657, -1.87265, -1.77592, -1.56492, -1.47151, -1.33480, -1.24103, -1.22332, -1.13273, -1.16363, -1.14286, -1.06309, -0.93661, -0.86700, -0.77474, -0.76517, -0.76410, -0.78816, -0.77065, -0.76105, -0.75063, -0.73892, -0.72214, -0.74533, -0.85794, -0.84185, -0.81084, -0.87387, -0.74145, -0.62620, -0.66854, -0.70936, -0.56732, -0.44027, -0.42817, -0.43664, -0.56775, -0.55301, -0.41141, -0.35532, -0.26904, -0.13718, 0.10189, 0.27984, 0.29754, 0.17141, 0.15992, 0.19912, 0.25221, 0.21447, 0.25410, 0.35570, 0.37552, 0.36229, 0.45181, 0.57196, 0.42227, 0.26905, 0.30286, 0.35582, 0.46364, 0.50395, 0.39509, 0.31856, 0.34509, 0.36008, 0.25344, 0.22836, 0.11107, -0.03029, -0.03756, 0.01831, 0.12198, 0.13328, 0.00611, -0.14248, -0.27179, -0.37789, -0.37215, -0.38037, -0.38636, -0.42095, -0.54438, -0.61839, -0.65120, -0.74877, -0.92456, -1.04218, -1.25894, -1.48525, -1.63036, -1.79461, -1.80415, -1.71878, -1.77187, -1.88557, -1.86323, -1.69735, -1.60126, -1.54928, -1.64569, -1.73340, -1.68323, -1.72190, -1.86799, -2.05553, -2.19240, -2.21543, -2.19432, -2.24296, -2.22849, -2.18319, -2.30761, -2.45944, -2.60262, -2.60895, -2.67860, -2.77985, -2.74760, -2.56207, -2.54377, -2.61102, -2.48371, -2.29555, -2.02677, -1.68496, -1.48789, -1.28729, -0.96568, -0.63036, -0.38520, -0.03811, 0.20133, 0.24371, 0.25635, 0.24518, 0.23062, 0.26558, 0.26448, 0.23771, 0.21827, 0.12384, -0.09145, -0.17528, -0.30809, -0.44631, -0.73431, -0.87837, -0.90087, -0.93289, -0.98730, -0.89590, -0.81633, -0.79536, -0.63682, -0.52350, -0.39558, -0.13227, -0.01651, -0.05920, -0.09131, 0.01590, 0.03567, 0.07705, 0.03073, -0.04922, 0.12398, 0.42684, 0.80208, 1.18049, 1.49353, 1.67281, 1.66953, 1.61430, 1.57497, 1.70460, 1.62450, 1.53809, 1.42080, 1.42090, 1.37201, 1.23370, 1.12770, 1.25361, 1.37094, 1.36602, 1.46723, 1.57886, 1.62159, 1.70689, 1.75326, 1.85696, 2.03869, 2.23663, 2.18233, 2.16860, 2.17340, 2.09969, 2.16266, 2.22061, 2.34949, 2.45318, 2.36167, 2.24505, 2.12704, 1.93395, 1.59882, 1.49602, 1.39456, 1.26185, 0.93929, 0.66584, +-0.85394, -0.96873, -1.15973, -1.41467, -1.55452, -1.74678, -1.98223, -2.26259, -2.34276, -2.36198, -2.40408, -2.37235, -2.24093, -2.11433, -1.99617, -1.94171, -1.96422, -1.97066, -1.92435, -1.78922, -1.64090, -1.42135, -1.24159, -1.38064, -1.59550, -1.79885, -1.97403, -2.04147, -2.07536, -2.15017, -2.22701, -2.29812, -2.46308, -2.44075, -2.26550, -2.20864, -2.19881, -2.13910, -2.02305, -2.09530, -2.22829, -2.28278, -2.31998, -2.27001, -2.24024, -2.31055, -2.34538, -2.25977, -2.24841, -2.38145, -2.51678, -2.52081, -2.60123, -2.73412, -2.84605, -3.04409, -3.14701, -3.10280, -3.11290, -3.06589, -2.95965, -2.96958, -3.07076, -3.06843, -3.04350, -2.99807, -3.02706, -3.15770, -3.17947, -3.22507, -3.29372, -3.43678, -3.56332, -3.55352, -3.64087, -3.72963, -3.86498, -3.99789, -4.21952, -4.35230, -4.42228, -4.50315, -4.59656, -4.71377, -4.97661, -5.17568, -5.24167, -5.36966, -5.51703, -5.54825, -5.56271, -5.57679, -5.56135, -5.44896, -5.29852, -5.13198, -5.10811, -5.01397, -4.89495, -5.03536, -5.16762, -5.18045, -5.03441, -4.88479, -4.78918, -4.57277, -4.37626, -4.07942, -3.88666, -3.82175, -3.81858, -3.66237, -3.54704, -3.57941, -3.71136, -3.74805, -3.80500, -3.85132, -3.92260, -4.08251, -4.22783, -4.28919, -4.32301, -4.23110, -4.03681, -3.89028, -3.91806, -3.79695, -3.57128, -3.34664, -3.13391, -3.11412, -3.01334, -2.82336, -2.62694, -2.49309, -2.43777, -2.18368, -2.07705, -1.93043, -1.73230, -1.54373, -1.45682, -1.37398, -1.35049, -1.30043, -1.29434, -1.16002, -1.13223, -1.22362, -1.26877, -1.51711, -1.82856, -1.88639, -1.80414, -1.73399, -1.71554, -1.57368, -1.49739, -1.40443, -1.27448, -1.05067, -0.69576, -0.53703, -0.52081, -0.55272, -0.52750, -0.45667, -0.56806, -0.59260, -0.62659, -0.57991, -0.58378, -0.75416, -1.06484, -1.28822, -1.45202, -1.58313, -1.84320, -1.96597, -2.02349, -2.15021, -2.17970, -2.21129, -2.27640, -2.29397, -2.32985, -2.25518, -2.08716, -1.90625, -1.86511, -1.76742, -1.56079, -1.35905, -1.16337, -1.18207, -1.26397, -1.24231, -1.26580, -1.20430, -1.15386, -0.94752, -0.77535, -0.71608, -0.69812, -0.67882, -0.70786, -0.65061, -0.61628, -0.58856, -0.69005, -0.81819, -0.89725, -0.90371, -0.76547, -0.77096, -0.92392, -0.87216, -0.74582, -0.72334, -0.70519, -0.57767, -0.48404, -0.43888, -0.43542, -0.50062, -0.39922, -0.29266, -0.27641, -0.20740, -0.06021, 0.20808, 0.29799, 0.31054, 0.23640, 0.13596, 0.14721, 0.22772, 0.19590, 0.30427, 0.48360, 0.57630, 0.53477, 0.51245, 0.54697, 0.43444, 0.37368, 0.40981, 0.41367, 0.44018, 0.45675, 0.37335, 0.33303, 0.34188, 0.26689, 0.10333, 0.03345, -0.05948, -0.12357, -0.18079, -0.23131, -0.18823, -0.12176, -0.11943, -0.23699, -0.30784, -0.33672, -0.42370, -0.51260, -0.55189, -0.67403, -0.81029, -0.84814, -0.79854, -0.85346, -1.09068, -1.25276, -1.38468, -1.44456, -1.56375, -1.79239, -1.86642, -1.79449, -1.79555, -1.85726, -1.86418, -1.78094, -1.68249, -1.58441, -1.59200, -1.53704, -1.50920, -1.71176, -1.97033, -2.18810, -2.28235, -2.29771, -2.25894, -2.21911, -2.23642, -2.22643, -2.29620, -2.42555, -2.53032, -2.48908, -2.51302, -2.59009, -2.59311, -2.44241, -2.40788, -2.37685, -2.28836, -2.22238, -2.03162, -1.74623, -1.53486, -1.25814, -0.89479, -0.60056, -0.35208, -0.00967, 0.24343, 0.45996, 0.53354, 0.43187, 0.36207, 0.36146, 0.40938, 0.42723, 0.40151, 0.37138, 0.12254, -0.02423, -0.05672, -0.10601, -0.33400, -0.40637, -0.36829, -0.37439, -0.52674, -0.55593, -0.53199, -0.43662, -0.30530, -0.34337, -0.34421, -0.16035, -0.00519, 0.08105, 0.14437, 0.23298, 0.23937, 0.23242, 0.14938, 0.19112, 0.38995, 0.59022, 0.89267, 1.20498, 1.56640, 1.81523, 1.81931, 1.86755, 1.80567, 1.81447, 1.76203, 1.71235, 1.65071, 1.71898, 1.67276, 1.52144, 1.28896, 1.27172, 1.32837, 1.38811, 1.47322, 1.48969, 1.47467, 1.50100, 1.57798, 1.76544, 2.01552, 2.23236, 2.19820, 2.17917, 2.16101, 2.18240, 2.26947, 2.22416, 2.24173, 2.22576, 2.14554, 2.08400, 1.97883, 1.89894, 1.55428, 1.32686, 1.25732, 1.15536, 0.83369, 0.59849, +-0.84745, -0.87739, -1.06616, -1.34260, -1.54091, -1.77965, -2.01566, -2.20915, -2.19571, -2.22153, -2.32246, -2.30120, -2.10145, -1.89995, -1.84205, -1.93672, -2.06841, -2.01610, -1.84226, -1.71964, -1.58426, -1.36558, -1.29033, -1.41748, -1.57664, -1.78818, -1.90147, -1.93371, -2.07055, -2.17246, -2.29255, -2.46584, -2.57181, -2.51942, -2.32707, -2.26228, -2.22742, -2.15522, -2.06449, -2.10520, -2.16778, -2.22379, -2.31166, -2.30868, -2.24577, -2.22485, -2.29157, -2.32465, -2.35021, -2.33635, -2.28981, -2.34472, -2.52664, -2.67883, -2.82990, -3.01049, -3.05024, -3.08368, -3.12999, -3.06591, -3.02394, -3.02537, -3.07683, -3.17522, -3.16467, -3.13323, -3.16186, -3.29196, -3.28806, -3.36852, -3.49707, -3.62673, -3.68906, -3.68617, -3.84476, -4.05534, -4.18829, -4.19756, -4.32056, -4.44657, -4.53001, -4.58692, -4.53712, -4.59755, -4.80578, -4.90041, -4.99461, -5.21879, -5.38255, -5.52921, -5.63217, -5.64341, -5.71297, -5.66183, -5.40785, -5.28844, -5.18487, -5.03152, -4.92121, -5.10179, -5.21629, -5.23679, -5.11601, -4.95485, -4.78740, -4.54983, -4.42701, -4.26168, -4.05908, -3.82984, -3.75212, -3.71082, -3.73937, -3.83722, -3.81438, -3.78161, -3.82995, -3.84977, -3.98872, -4.25577, -4.34785, -4.41075, -4.43808, -4.29532, -4.20544, -4.17843, -4.11904, -4.03752, -3.74361, -3.48658, -3.29458, -3.30874, -3.18545, -3.00161, -2.85536, -2.78206, -2.66466, -2.31465, -2.11673, -1.94351, -1.73261, -1.49376, -1.35552, -1.28876, -1.25247, -1.20662, -1.10230, -0.99746, -1.05827, -1.15024, -1.25825, -1.61900, -1.88693, -1.93468, -1.77716, -1.55319, -1.49723, -1.44515, -1.32739, -1.33445, -1.21367, -0.98335, -0.67393, -0.59317, -0.57965, -0.60615, -0.62484, -0.60939, -0.63638, -0.52334, -0.53834, -0.60639, -0.74484, -0.91723, -1.13043, -1.33380, -1.46975, -1.63797, -1.80082, -1.86390, -1.92672, -1.96892, -1.98284, -2.16777, -2.32232, -2.43021, -2.49027, -2.29915, -2.08695, -2.01492, -1.91209, -1.82520, -1.57796, -1.30613, -1.14698, -1.28264, -1.39131, -1.33669, -1.29557, -1.20251, -1.11679, -0.88773, -0.70879, -0.64795, -0.61238, -0.53429, -0.51813, -0.55533, -0.59411, -0.66725, -0.74183, -0.82211, -0.96326, -0.91920, -0.69711, -0.77222, -0.92408, -0.91996, -0.87051, -0.79655, -0.73853, -0.71441, -0.57644, -0.52859, -0.49333, -0.45153, -0.35319, -0.31477, -0.26726, -0.09241, 0.07219, 0.25244, 0.24629, 0.24873, 0.20805, 0.12498, 0.14076, 0.23155, 0.25173, 0.34185, 0.53028, 0.62420, 0.66055, 0.67713, 0.56563, 0.42806, 0.42375, 0.41703, 0.42267, 0.42309, 0.39462, 0.39060, 0.42244, 0.32547, 0.19919, -0.03710, -0.17019, -0.17080, -0.16355, -0.23102, -0.35073, -0.34312, -0.26824, -0.21940, -0.25306, -0.23207, -0.26549, -0.43936, -0.60746, -0.68348, -0.79176, -0.95827, -1.06031, -1.02835, -0.97007, -1.06145, -1.25083, -1.39512, -1.42682, -1.61029, -1.86122, -1.92460, -1.88697, -1.82697, -1.77597, -1.83533, -1.80152, -1.71086, -1.62922, -1.47979, -1.39579, -1.46320, -1.82668, -2.11476, -2.28724, -2.33727, -2.31438, -2.25792, -2.23756, -2.28270, -2.26628, -2.26548, -2.28419, -2.38984, -2.45004, -2.49237, -2.48234, -2.30915, -2.18059, -2.20003, -2.14832, -2.12301, -2.13328, -1.96873, -1.81022, -1.63715, -1.27048, -0.90664, -0.56807, -0.22361, 0.01791, 0.30544, 0.57008, 0.68181, 0.56328, 0.52133, 0.51396, 0.52670, 0.55917, 0.57233, 0.55005, 0.30407, 0.14007, 0.19195, 0.31851, 0.18510, 0.07456, 0.06650, 0.02810, -0.03818, -0.12792, -0.21183, -0.14065, -0.10974, -0.25616, -0.27760, -0.20421, -0.06605, 0.19635, 0.35629, 0.42559, 0.46873, 0.30420, 0.27974, 0.42969, 0.68378, 0.82767, 1.06665, 1.31881, 1.64532, 1.93013, 2.01913, 2.09863, 1.97330, 1.86271, 1.81938, 1.89097, 1.93072, 1.92970, 1.81286, 1.62215, 1.50140, 1.46806, 1.41471, 1.41121, 1.38939, 1.30225, 1.34519, 1.39311, 1.48867, 1.74556, 1.97980, 2.14987, 2.25153, 2.18281, 2.20613, 2.24303, 2.26900, 2.12667, 2.08079, 2.03022, 1.94579, 1.89238, 1.88091, 1.88813, 1.55465, 1.26537, 1.15344, 1.07074, 0.78324, 0.45728, +-0.80989, -0.86744, -0.94273, -1.13110, -1.34978, -1.59758, -1.82443, -1.97345, -2.00905, -2.13903, -2.20235, -2.08725, -1.91033, -1.75340, -1.68345, -1.78865, -1.92134, -1.80802, -1.59506, -1.53114, -1.50171, -1.36753, -1.31841, -1.41899, -1.52993, -1.70026, -1.84871, -1.99715, -2.15465, -2.19885, -2.22123, -2.29982, -2.42240, -2.47530, -2.27203, -2.14248, -2.08938, -2.02551, -2.00868, -2.07718, -2.14767, -2.26157, -2.30090, -2.22991, -2.20596, -2.19102, -2.22273, -2.30167, -2.39283, -2.31763, -2.21003, -2.34265, -2.58823, -2.70465, -2.70868, -2.71426, -2.68244, -2.77955, -2.96755, -3.11736, -3.14346, -3.07925, -3.06526, -3.13360, -3.19293, -3.28006, -3.24334, -3.25720, -3.27785, -3.42557, -3.62236, -3.75256, -3.78262, -3.86598, -4.02663, -4.16034, -4.28004, -4.31479, -4.32103, -4.36648, -4.48653, -4.55526, -4.51621, -4.64119, -4.82617, -4.87498, -4.88120, -5.02010, -5.19517, -5.37201, -5.50866, -5.64233, -5.74853, -5.68971, -5.41760, -5.24936, -5.11290, -5.05306, -4.95272, -5.04122, -5.12638, -5.13526, -5.02614, -4.88571, -4.67459, -4.46632, -4.37346, -4.22644, -4.10878, -3.96612, -3.85037, -3.80746, -3.89239, -3.93977, -3.77701, -3.70984, -3.75607, -3.86399, -4.03385, -4.25508, -4.34374, -4.36962, -4.40459, -4.41887, -4.40800, -4.35369, -4.21174, -4.06352, -3.79131, -3.68675, -3.51230, -3.37874, -3.18524, -3.00971, -2.90721, -2.86066, -2.65874, -2.30506, -2.01283, -1.70150, -1.51719, -1.43059, -1.33686, -1.23274, -1.16996, -1.10124, -0.93951, -0.93394, -1.08951, -1.23601, -1.28589, -1.48537, -1.69605, -1.73645, -1.58807, -1.45796, -1.38821, -1.30028, -1.17437, -1.16205, -1.04568, -0.94928, -0.70471, -0.56591, -0.50362, -0.47977, -0.53712, -0.63309, -0.66974, -0.58888, -0.62248, -0.65738, -0.83101, -1.07007, -1.19522, -1.24735, -1.33532, -1.55372, -1.68415, -1.80761, -1.91904, -1.96692, -1.96182, -2.07772, -2.26273, -2.39442, -2.46152, -2.39973, -2.28994, -2.23961, -2.08433, -1.88200, -1.54560, -1.35033, -1.24775, -1.28018, -1.29073, -1.18279, -1.08225, -1.01308, -0.95059, -0.82231, -0.74051, -0.61222, -0.52048, -0.52622, -0.52798, -0.56451, -0.64692, -0.76358, -0.75166, -0.80244, -0.99355, -1.01950, -0.81492, -0.78554, -0.86875, -0.88681, -0.91622, -0.97823, -0.99150, -0.94285, -0.73017, -0.60028, -0.44341, -0.37573, -0.34299, -0.28264, -0.18524, 0.03963, 0.19873, 0.28155, 0.23063, 0.23346, 0.21823, 0.28216, 0.35998, 0.29599, 0.24169, 0.34235, 0.55011, 0.66097, 0.75695, 0.75484, 0.53396, 0.34858, 0.36708, 0.44801, 0.48062, 0.45395, 0.41113, 0.36796, 0.33763, 0.21895, 0.11477, -0.05823, -0.10263, -0.09475, -0.10653, -0.12348, -0.23496, -0.28742, -0.28102, -0.25645, -0.24261, -0.19032, -0.26468, -0.42802, -0.57924, -0.74267, -0.86788, -0.95577, -1.05108, -1.08946, -1.02113, -1.06444, -1.28752, -1.49532, -1.58556, -1.70641, -1.85123, -1.86521, -1.80424, -1.78059, -1.75677, -1.74904, -1.69162, -1.62059, -1.52021, -1.37042, -1.40069, -1.48450, -1.78890, -1.99778, -2.08437, -2.08083, -2.07707, -2.10464, -2.20153, -2.26118, -2.16973, -2.18086, -2.23790, -2.28306, -2.30746, -2.32476, -2.23314, -2.00384, -1.98519, -2.09725, -2.09211, -2.00195, -1.92609, -1.79890, -1.70134, -1.57448, -1.29502, -0.89272, -0.44001, -0.04401, 0.19877, 0.42694, 0.53384, 0.67862, 0.69052, 0.71179, 0.72871, 0.70561, 0.71142, 0.76397, 0.75690, 0.60143, 0.54281, 0.55037, 0.59713, 0.55457, 0.52251, 0.46642, 0.37579, 0.32756, 0.14994, -0.01676, -0.03146, -0.02158, -0.04968, -0.05048, -0.04938, -0.01300, 0.12598, 0.33514, 0.47899, 0.57132, 0.48871, 0.58614, 0.73663, 1.07673, 1.29056, 1.44769, 1.61556, 1.83875, 2.06983, 2.18981, 2.20730, 2.06851, 2.01646, 1.97701, 1.97803, 2.05219, 2.04748, 1.86643, 1.66051, 1.62538, 1.53617, 1.38155, 1.27853, 1.26798, 1.31348, 1.42039, 1.50909, 1.55321, 1.61936, 1.76870, 1.93992, 2.12781, 2.15838, 2.24701, 2.17695, 2.13530, 2.05054, 2.04023, 2.06080, 2.00834, 1.91561, 1.88562, 1.81733, 1.50463, 1.31037, 1.14133, 0.86863, 0.56542, 0.27583, +-0.69783, -0.82151, -0.90872, -1.04904, -1.17575, -1.35150, -1.56592, -1.73796, -1.85488, -1.96174, -2.04281, -1.96887, -1.79615, -1.65267, -1.51325, -1.55933, -1.56429, -1.44988, -1.35475, -1.31683, -1.33308, -1.29931, -1.35045, -1.48985, -1.53443, -1.67204, -1.84973, -2.00582, -2.08829, -2.12619, -2.13502, -2.07974, -2.12947, -2.25414, -2.20683, -2.12967, -2.08359, -1.99113, -1.99687, -2.07160, -2.16739, -2.18685, -2.19195, -2.18110, -2.16691, -2.14876, -2.13284, -2.22223, -2.33779, -2.30967, -2.32076, -2.38529, -2.50470, -2.54096, -2.51399, -2.48794, -2.40906, -2.53563, -2.84176, -3.11396, -3.17776, -3.14470, -3.22036, -3.21529, -3.19537, -3.25747, -3.27833, -3.27908, -3.36239, -3.51669, -3.77716, -3.94382, -4.04132, -4.08874, -4.21828, -4.33858, -4.36698, -4.37457, -4.32766, -4.36997, -4.51534, -4.54739, -4.63466, -4.73410, -4.83281, -4.86727, -4.85938, -4.96168, -5.09004, -5.21317, -5.36184, -5.52652, -5.61428, -5.57575, -5.48538, -5.30323, -5.11702, -5.00895, -4.96227, -4.99620, -5.06779, -4.97589, -4.86456, -4.71859, -4.54429, -4.28834, -4.20067, -4.19942, -4.18832, -4.15793, -4.05685, -3.96460, -4.00090, -3.87705, -3.74195, -3.61947, -3.60660, -3.77289, -4.01758, -4.29057, -4.40232, -4.38046, -4.46557, -4.53969, -4.47586, -4.32991, -4.27520, -4.11360, -3.87260, -3.76721, -3.68886, -3.52695, -3.34893, -3.11647, -3.02803, -2.89877, -2.64256, -2.21014, -1.84647, -1.62930, -1.48720, -1.43164, -1.35342, -1.19667, -1.14604, -0.98851, -0.89108, -0.89184, -0.99545, -1.11858, -1.14480, -1.29454, -1.46434, -1.46373, -1.42161, -1.38960, -1.29518, -1.10473, -1.05750, -1.03236, -0.90014, -0.75821, -0.61826, -0.49988, -0.45637, -0.34972, -0.43705, -0.57157, -0.71568, -0.70324, -0.72504, -0.83737, -0.99148, -1.16353, -1.23572, -1.17723, -1.28586, -1.43889, -1.62993, -1.80459, -1.88255, -1.91988, -1.96656, -2.09070, -2.23733, -2.28467, -2.40297, -2.48502, -2.46529, -2.36686, -2.29356, -2.08943, -1.70235, -1.43089, -1.36028, -1.29298, -1.22682, -1.04356, -0.96960, -0.96642, -0.97242, -0.86747, -0.75603, -0.68726, -0.62587, -0.63923, -0.62032, -0.58030, -0.70346, -0.73510, -0.71230, -0.77756, -0.89972, -0.94936, -0.87643, -0.90413, -0.97582, -0.91283, -0.96792, -1.12609, -1.15170, -0.97911, -0.78129, -0.65211, -0.39034, -0.19598, -0.20462, -0.17968, -0.13212, 0.07645, 0.21305, 0.26464, 0.22644, 0.26693, 0.33672, 0.38501, 0.39273, 0.27324, 0.19939, 0.33951, 0.51426, 0.69673, 0.78728, 0.74677, 0.64091, 0.52798, 0.50049, 0.50778, 0.48690, 0.50269, 0.44655, 0.30757, 0.22639, 0.16137, 0.05148, -0.09012, -0.01061, 0.07623, 0.00272, -0.12128, -0.26335, -0.32426, -0.33439, -0.33572, -0.31138, -0.24913, -0.21186, -0.36787, -0.58776, -0.73896, -0.81781, -0.81980, -0.92902, -1.01171, -1.02703, -1.17111, -1.31366, -1.44577, -1.56922, -1.71888, -1.82655, -1.72298, -1.60504, -1.63236, -1.61017, -1.50233, -1.45648, -1.50841, -1.43776, -1.31889, -1.40140, -1.53925, -1.73442, -1.83836, -1.84142, -1.85580, -1.90815, -2.03846, -2.11036, -2.21295, -2.22868, -2.24148, -2.28104, -2.19829, -2.09527, -2.02716, -1.87542, -1.77121, -1.75829, -1.84047, -1.89944, -1.88866, -1.85395, -1.72223, -1.58557, -1.46400, -1.21250, -0.77559, -0.33574, -0.09009, 0.18112, 0.42967, 0.51048, 0.57380, 0.63530, 0.69568, 0.82737, 0.80955, 0.83581, 0.91506, 1.06440, 1.00582, 0.89326, 0.83930, 0.81129, 0.81117, 0.85215, 0.80555, 0.75882, 0.59641, 0.44623, 0.34534, 0.28394, 0.20245, 0.15848, 0.18267, 0.20080, 0.12946, 0.12873, 0.32776, 0.54065, 0.60010, 0.69364, 0.95053, 1.19055, 1.46561, 1.66430, 1.73613, 1.89663, 1.98297, 2.12982, 2.17950, 2.23782, 2.19317, 2.12933, 2.10999, 2.09752, 2.16119, 2.17373, 1.95447, 1.79969, 1.65131, 1.54194, 1.42482, 1.33302, 1.32971, 1.38345, 1.49708, 1.59202, 1.49875, 1.43359, 1.55149, 1.75950, 1.86093, 1.94995, 2.11603, 2.13125, 2.00367, 1.93745, 1.96600, 2.13990, 2.10547, 2.00114, 1.85055, 1.73126, 1.47189, 1.22132, 1.02037, 0.69354, 0.37611, 0.16942, +-0.66065, -0.86347, -0.95571, -1.04891, -1.11113, -1.23026, -1.38800, -1.55439, -1.75165, -1.84776, -1.84999, -1.76178, -1.58881, -1.41906, -1.30006, -1.33787, -1.29250, -1.22414, -1.19063, -1.20334, -1.28741, -1.30954, -1.35305, -1.45217, -1.54295, -1.72904, -1.80938, -1.81099, -1.88973, -1.98852, -2.00434, -1.90547, -1.93570, -2.14068, -2.21536, -2.19939, -2.21737, -2.14173, -2.07311, -2.06480, -2.16718, -2.14456, -2.08721, -2.05623, -2.04685, -2.03026, -2.06906, -2.23221, -2.38397, -2.45098, -2.51186, -2.48489, -2.50115, -2.46109, -2.38490, -2.31833, -2.31832, -2.55959, -2.83438, -2.99558, -3.12709, -3.22792, -3.39162, -3.37653, -3.28616, -3.34025, -3.40094, -3.40698, -3.56913, -3.76743, -4.02531, -4.19793, -4.39423, -4.45217, -4.50036, -4.48207, -4.40109, -4.33018, -4.31933, -4.50354, -4.69790, -4.75298, -4.86459, -4.88684, -4.94630, -4.97774, -4.92441, -4.91719, -5.03014, -5.19621, -5.27582, -5.26318, -5.34397, -5.41723, -5.47183, -5.34163, -5.15040, -5.02532, -4.95461, -4.90840, -4.97775, -4.88397, -4.75598, -4.54640, -4.41540, -4.20248, -4.11780, -4.11225, -4.15619, -4.16958, -4.13273, -4.12889, -4.12879, -3.94408, -3.80355, -3.60320, -3.58620, -3.78796, -4.03979, -4.26910, -4.42441, -4.50857, -4.60248, -4.49982, -4.34377, -4.22116, -4.24971, -4.15928, -3.98517, -3.91835, -3.89409, -3.73448, -3.61708, -3.41207, -3.29495, -3.01038, -2.69162, -2.23586, -1.84331, -1.61853, -1.47763, -1.35132, -1.25642, -1.17385, -1.15895, -1.03187, -0.96401, -0.87838, -0.91797, -0.99160, -0.97421, -1.02007, -1.16139, -1.27093, -1.32477, -1.19480, -1.06645, -0.89096, -0.86086, -0.84769, -0.73429, -0.62802, -0.57913, -0.46549, -0.45691, -0.38636, -0.47989, -0.54288, -0.73042, -0.82316, -0.87920, -0.96144, -1.06895, -1.13367, -1.18280, -1.21450, -1.40226, -1.58401, -1.79267, -1.91367, -1.96558, -2.00972, -2.08053, -2.11267, -2.15853, -2.24543, -2.42594, -2.45904, -2.45670, -2.42163, -2.43739, -2.32192, -1.97769, -1.69438, -1.61056, -1.41126, -1.27227, -1.10933, -1.10680, -1.12794, -1.15405, -1.06624, -0.91637, -0.78108, -0.70228, -0.66541, -0.60229, -0.60914, -0.79130, -0.83593, -0.83885, -0.86749, -0.93349, -1.01029, -1.03575, -1.05176, -1.08515, -1.03721, -1.08574, -1.12327, -1.05405, -0.88723, -0.74924, -0.64966, -0.37648, -0.16215, -0.19083, -0.13136, -0.09140, 0.03720, 0.12048, 0.20593, 0.21885, 0.25042, 0.31889, 0.38117, 0.35793, 0.25842, 0.23070, 0.31819, 0.41732, 0.58976, 0.65943, 0.69822, 0.75542, 0.70860, 0.64828, 0.63261, 0.60397, 0.56415, 0.43431, 0.30200, 0.26333, 0.16274, 0.00553, -0.11639, 0.00342, 0.09402, -0.07436, -0.27711, -0.41913, -0.50258, -0.52974, -0.48555, -0.40847, -0.34820, -0.24461, -0.30570, -0.47734, -0.56326, -0.57647, -0.62315, -0.83531, -1.01149, -1.14667, -1.30918, -1.35380, -1.38706, -1.46361, -1.56799, -1.60829, -1.51902, -1.45921, -1.43310, -1.28726, -1.18712, -1.21928, -1.34908, -1.34978, -1.31136, -1.45901, -1.58897, -1.65699, -1.70785, -1.72175, -1.75910, -1.84554, -2.06392, -2.14692, -2.23393, -2.24815, -2.24132, -2.21053, -2.05785, -1.91044, -1.79908, -1.67551, -1.63644, -1.58007, -1.62191, -1.71110, -1.76114, -1.73480, -1.65417, -1.57651, -1.38713, -1.00359, -0.61907, -0.34980, -0.25657, -0.00973, 0.25464, 0.32244, 0.36302, 0.47405, 0.54219, 0.70863, 0.75448, 0.88160, 1.00282, 1.23238, 1.26993, 1.22687, 1.14819, 1.10461, 1.06683, 1.02519, 0.99134, 0.94528, 0.75149, 0.67979, 0.61855, 0.53744, 0.42907, 0.41090, 0.40393, 0.33857, 0.26277, 0.35507, 0.50857, 0.65271, 0.69845, 0.88979, 1.23509, 1.48411, 1.69494, 1.88005, 1.88808, 1.97471, 1.96636, 2.08035, 2.05969, 2.11125, 2.18714, 2.27386, 2.30757, 2.34469, 2.36698, 2.27389, 2.03782, 1.83555, 1.57993, 1.49394, 1.41799, 1.37344, 1.41372, 1.52080, 1.58640, 1.49590, 1.28141, 1.30770, 1.42259, 1.55752, 1.58843, 1.66940, 1.86923, 1.92387, 1.78179, 1.77890, 1.85274, 2.06244, 2.04623, 2.00317, 1.77745, 1.57864, 1.34584, 1.16448, 1.00525, 0.74007, 0.41412, 0.13296, +-0.65397, -0.83829, -0.92989, -1.02879, -1.04556, -1.10493, -1.23542, -1.42430, -1.58786, -1.67286, -1.65396, -1.52065, -1.41776, -1.29760, -1.14991, -1.05388, -1.03170, -1.04183, -1.03145, -1.14588, -1.22034, -1.25274, -1.34295, -1.37449, -1.48639, -1.62429, -1.66254, -1.67386, -1.77218, -1.92088, -1.81065, -1.73142, -1.91250, -2.11227, -2.21163, -2.28156, -2.32741, -2.26005, -2.11108, -2.02116, -1.98756, -1.98404, -2.04814, -2.01603, -2.05369, -2.16875, -2.23218, -2.26347, -2.33797, -2.46502, -2.53204, -2.55830, -2.51213, -2.39861, -2.34637, -2.24510, -2.32057, -2.57448, -2.74950, -2.89107, -3.05240, -3.29276, -3.40038, -3.38935, -3.42095, -3.47176, -3.50403, -3.62423, -3.83274, -4.02731, -4.20815, -4.42763, -4.63389, -4.69213, -4.75803, -4.66245, -4.52940, -4.49230, -4.49284, -4.63021, -4.79720, -4.95291, -5.02802, -5.08230, -5.10338, -5.08493, -5.08510, -5.01063, -5.05742, -5.15858, -5.10740, -5.08435, -5.14135, -5.32736, -5.34334, -5.19565, -5.15007, -5.05600, -4.86597, -4.81548, -4.84299, -4.82065, -4.71874, -4.53017, -4.36520, -4.18111, -4.16234, -4.11899, -4.08276, -4.15547, -4.19015, -4.17923, -4.11831, -4.00807, -3.79600, -3.61783, -3.62870, -3.78679, -4.05550, -4.23621, -4.37306, -4.49650, -4.51431, -4.40381, -4.18335, -4.15244, -4.15768, -4.09097, -4.12287, -4.12713, -3.98979, -3.91134, -3.84171, -3.66334, -3.46178, -3.13995, -2.73833, -2.21212, -1.87141, -1.66337, -1.46970, -1.36516, -1.26516, -1.14390, -1.05470, -1.07104, -1.00738, -0.92144, -0.89633, -0.81224, -0.78443, -0.78924, -0.86272, -1.01923, -1.04496, -0.95882, -0.83424, -0.75349, -0.64464, -0.50429, -0.51545, -0.61434, -0.58374, -0.53403, -0.55361, -0.54856, -0.56332, -0.55676, -0.62147, -0.65945, -0.84556, -1.02038, -1.10492, -1.18615, -1.24886, -1.30205, -1.47060, -1.78047, -1.94434, -2.03742, -2.10042, -2.07378, -2.16968, -2.16725, -2.07504, -2.15499, -2.27960, -2.39206, -2.44353, -2.48787, -2.49634, -2.35379, -2.18541, -2.03039, -1.80626, -1.55558, -1.38344, -1.24741, -1.24870, -1.31459, -1.32312, -1.15482, -1.04112, -0.93608, -0.79709, -0.78765, -0.76322, -0.76149, -0.83059, -0.94614, -0.97476, -1.01433, -1.09672, -1.10499, -1.17355, -1.21792, -1.16986, -1.10781, -1.02302, -0.97296, -0.88288, -0.83950, -0.79311, -0.59673, -0.43769, -0.40563, -0.32148, -0.16692, -0.04251, 0.07823, 0.13203, 0.18519, 0.20792, 0.32723, 0.34748, 0.30782, 0.26575, 0.15065, 0.13674, 0.25096, 0.44921, 0.57687, 0.62504, 0.74315, 0.85749, 0.92308, 0.85332, 0.72576, 0.72931, 0.70599, 0.63136, 0.46278, 0.33079, 0.17638, -0.02476, -0.03680, 0.02753, -0.04726, -0.19532, -0.39260, -0.55752, -0.63797, -0.66536, -0.59855, -0.50118, -0.35623, -0.26606, -0.34445, -0.41849, -0.44832, -0.49663, -0.58379, -0.74018, -0.97694, -1.22080, -1.34102, -1.38527, -1.28424, -1.25030, -1.34778, -1.33329, -1.32989, -1.31114, -1.25248, -1.16552, -1.10707, -1.18621, -1.17064, -1.13737, -1.27774, -1.44760, -1.52585, -1.57585, -1.55617, -1.57164, -1.64146, -1.82840, -2.01382, -2.09181, -2.23600, -2.23148, -2.20768, -2.20642, -2.00197, -1.70053, -1.53732, -1.53189, -1.52744, -1.50779, -1.42907, -1.43561, -1.59174, -1.57426, -1.48514, -1.39426, -1.16416, -0.85612, -0.54095, -0.45586, -0.34935, -0.09827, 0.03186, 0.09437, 0.21692, 0.30174, 0.38755, 0.53021, 0.65061, 0.82817, 1.09033, 1.39044, 1.40622, 1.41944, 1.36913, 1.24607, 1.17421, 1.17103, 1.20003, 1.07862, 0.95385, 0.85115, 0.76442, 0.70361, 0.54031, 0.50875, 0.51104, 0.48054, 0.54581, 0.67215, 0.80258, 0.78690, 0.87207, 1.14796, 1.40868, 1.61574, 1.86633, 1.95162, 1.96414, 2.00769, 1.98982, 2.01896, 2.01846, 2.11311, 2.19757, 2.36995, 2.48515, 2.46012, 2.41174, 2.36480, 2.26708, 1.94985, 1.64448, 1.49307, 1.46700, 1.53823, 1.53999, 1.63248, 1.68897, 1.49366, 1.27638, 1.23745, 1.32191, 1.31253, 1.36434, 1.53012, 1.61261, 1.58171, 1.56859, 1.58865, 1.73425, 1.92740, 1.95148, 1.90038, 1.70422, 1.54719, 1.27007, 1.08464, 1.00303, 0.72959, 0.40094, 0.12496, +-0.43017, -0.51443, -0.64065, -0.80043, -0.86802, -0.94773, -1.08580, -1.28707, -1.45088, -1.52914, -1.47065, -1.29185, -1.17639, -1.04413, -0.94690, -0.89468, -0.85580, -0.84039, -0.82276, -0.92490, -1.02998, -1.13094, -1.23806, -1.22182, -1.33702, -1.43962, -1.51939, -1.62071, -1.66008, -1.74291, -1.69465, -1.77286, -1.95782, -2.01240, -2.06674, -2.15372, -2.18974, -2.14168, -2.02313, -1.91409, -1.82583, -1.87636, -2.00634, -1.98485, -2.04276, -2.22174, -2.34688, -2.34383, -2.25229, -2.28531, -2.38377, -2.47313, -2.52131, -2.51388, -2.48945, -2.35849, -2.41512, -2.58825, -2.67346, -2.80344, -2.87566, -3.04493, -3.18371, -3.33916, -3.49685, -3.50825, -3.56784, -3.78304, -3.96872, -4.08043, -4.19200, -4.42636, -4.65130, -4.78127, -4.87901, -4.83569, -4.74101, -4.68478, -4.68114, -4.77768, -4.80845, -4.86956, -4.91557, -4.98396, -5.03120, -5.09584, -5.15568, -5.06336, -5.05023, -5.09268, -5.01031, -5.06434, -5.05744, -5.10056, -5.03547, -4.95193, -4.96218, -4.81637, -4.65910, -4.67088, -4.66989, -4.65216, -4.57586, -4.42964, -4.28022, -4.20864, -4.20725, -4.10750, -3.97072, -4.00621, -4.12092, -4.21881, -4.14511, -3.97167, -3.71962, -3.53543, -3.53375, -3.71848, -3.96995, -4.09394, -4.18474, -4.30693, -4.28764, -4.28182, -4.11843, -4.05136, -4.06063, -4.13596, -4.24783, -4.11049, -3.88035, -3.84655, -3.77754, -3.55801, -3.31826, -3.08502, -2.73135, -2.27623, -1.94525, -1.67738, -1.40611, -1.24211, -1.13062, -1.06935, -0.92682, -0.87689, -0.83119, -0.75747, -0.68763, -0.62289, -0.63890, -0.64454, -0.66835, -0.79765, -0.74556, -0.72922, -0.64161, -0.53663, -0.42958, -0.35347, -0.44044, -0.50019, -0.45952, -0.47362, -0.52295, -0.52775, -0.46824, -0.41313, -0.37986, -0.47457, -0.78543, -1.05645, -1.19693, -1.27768, -1.34758, -1.48609, -1.60531, -1.78606, -1.87766, -1.93350, -1.98607, -2.02838, -2.15685, -2.17309, -2.07660, -2.16600, -2.23880, -2.42745, -2.48981, -2.41199, -2.35330, -2.30206, -2.27263, -2.05035, -1.72829, -1.56129, -1.44057, -1.29087, -1.23566, -1.28501, -1.27967, -1.17022, -1.12733, -1.05309, -0.88496, -0.84565, -0.85310, -0.93704, -0.95786, -0.98612, -1.03241, -1.11827, -1.20816, -1.22988, -1.27920, -1.29868, -1.20745, -1.18609, -1.07002, -1.00729, -0.91774, -0.81853, -0.76177, -0.63314, -0.64265, -0.62684, -0.40509, -0.19520, 0.00252, 0.15512, 0.20207, 0.20056, 0.17412, 0.24680, 0.20135, 0.13226, 0.14352, 0.12557, 0.17982, 0.27779, 0.51713, 0.75383, 0.87266, 0.97791, 1.03135, 1.02739, 0.89947, 0.73566, 0.80568, 0.83473, 0.82194, 0.61807, 0.40163, 0.31383, 0.14022, 0.00216, -0.11250, -0.18073, -0.15953, -0.28822, -0.44932, -0.50144, -0.50902, -0.46041, -0.38803, -0.28444, -0.30468, -0.40143, -0.40087, -0.37384, -0.45586, -0.65522, -0.83554, -0.94497, -1.05763, -1.11300, -1.16531, -1.12039, -1.14161, -1.22382, -1.17538, -1.23062, -1.25670, -1.22427, -1.24411, -1.14873, -1.10991, -1.04074, -1.04664, -1.20149, -1.26299, -1.34092, -1.44315, -1.38603, -1.36285, -1.43491, -1.64557, -1.81878, -1.95656, -2.10576, -2.06744, -1.99917, -1.97290, -1.85871, -1.65231, -1.43364, -1.37183, -1.36436, -1.31316, -1.17515, -1.17404, -1.32613, -1.27378, -1.15626, -1.10251, -0.98219, -0.84879, -0.55245, -0.39782, -0.27520, -0.12956, -0.02695, 0.17726, 0.34046, 0.38392, 0.46296, 0.57555, 0.70281, 0.87453, 1.14906, 1.34788, 1.33361, 1.40155, 1.46578, 1.43707, 1.34156, 1.24430, 1.27195, 1.20717, 1.13528, 1.03324, 0.90197, 0.74694, 0.56384, 0.51518, 0.52959, 0.55162, 0.71672, 0.82587, 0.94196, 0.94618, 0.97446, 1.09571, 1.29242, 1.62822, 1.94083, 2.01329, 2.08675, 2.17224, 2.18375, 2.15857, 2.15384, 2.17151, 2.17759, 2.30924, 2.46167, 2.47323, 2.40894, 2.35302, 2.39403, 2.20918, 1.92228, 1.75685, 1.75002, 1.71987, 1.60413, 1.64279, 1.69628, 1.50203, 1.32983, 1.18697, 1.23492, 1.28184, 1.34583, 1.43205, 1.42929, 1.48024, 1.56227, 1.57763, 1.72227, 1.87005, 1.88449, 1.80934, 1.69191, 1.54725, 1.25616, 1.03732, 0.92659, 0.67334, 0.36301, 0.02454, +-0.05018, -0.21461, -0.37487, -0.55698, -0.71515, -0.81322, -0.98942, -1.14478, -1.25148, -1.32996, -1.20994, -1.03004, -0.97593, -0.81335, -0.73050, -0.76500, -0.78146, -0.78798, -0.74242, -0.83940, -0.98671, -1.05007, -1.08841, -1.09631, -1.23569, -1.30540, -1.32842, -1.47055, -1.56043, -1.63156, -1.76400, -1.87567, -1.92602, -2.00673, -2.04642, -2.06052, -2.09729, -2.03178, -2.01075, -1.91006, -1.76840, -1.79501, -1.81769, -1.77576, -1.92468, -2.10745, -2.23069, -2.26501, -2.18789, -2.28573, -2.42147, -2.55986, -2.71124, -2.70275, -2.61702, -2.49566, -2.50547, -2.54982, -2.50887, -2.56829, -2.64883, -2.74750, -3.01039, -3.24962, -3.40557, -3.54731, -3.71485, -3.89507, -4.07114, -4.09152, -4.21082, -4.43293, -4.60660, -4.79575, -4.89925, -4.91306, -4.95969, -4.90048, -4.82927, -4.89292, -4.86339, -4.89959, -4.90600, -4.96664, -5.06933, -5.11338, -5.10543, -5.02096, -5.02040, -5.02257, -4.91134, -4.93264, -4.96483, -4.88427, -4.83223, -4.75780, -4.65805, -4.59151, -4.63493, -4.65961, -4.69555, -4.58023, -4.47339, -4.34871, -4.16200, -4.13339, -4.08919, -3.91785, -3.85430, -3.94840, -4.07085, -4.23479, -4.18871, -4.03254, -3.76411, -3.54883, -3.52715, -3.63588, -3.79190, -3.89530, -4.00820, -4.10102, -4.04669, -4.02648, -4.04365, -3.97837, -4.06480, -4.21749, -4.20382, -4.01297, -3.87334, -3.76377, -3.68324, -3.39106, -3.15383, -3.01679, -2.68274, -2.29719, -1.95558, -1.58690, -1.33621, -1.16996, -0.98665, -0.95069, -0.81217, -0.76790, -0.72047, -0.62233, -0.57338, -0.50272, -0.47488, -0.46140, -0.51069, -0.59935, -0.49138, -0.40784, -0.43873, -0.36230, -0.36819, -0.41648, -0.40097, -0.33377, -0.35387, -0.32552, -0.39101, -0.35484, -0.26455, -0.23943, -0.18976, -0.38528, -0.76484, -1.01106, -1.23704, -1.37546, -1.39752, -1.54660, -1.61662, -1.74793, -1.83091, -1.85791, -1.94719, -2.01761, -2.07502, -2.07994, -2.08145, -2.17269, -2.19337, -2.26312, -2.36180, -2.24471, -2.20290, -2.27301, -2.18070, -1.86610, -1.66712, -1.54239, -1.46369, -1.29188, -1.17990, -1.24594, -1.22121, -1.17395, -1.19490, -1.08013, -0.94513, -0.95089, -0.90960, -1.00316, -1.03217, -1.07357, -1.16625, -1.25443, -1.37732, -1.40534, -1.33783, -1.27398, -1.22937, -1.27891, -1.20071, -1.05214, -0.98102, -0.80946, -0.70711, -0.72591, -0.73254, -0.63530, -0.51550, -0.31240, -0.12752, -0.01084, 0.06760, 0.03391, 0.03962, 0.12464, 0.06471, 0.10273, 0.19532, 0.19256, 0.32227, 0.44347, 0.67239, 0.92399, 1.05342, 1.13946, 1.07927, 0.98162, 0.91056, 0.84112, 0.91411, 0.93885, 0.95392, 0.83843, 0.59835, 0.48303, 0.29637, -0.05007, -0.19219, -0.12697, -0.12005, -0.20772, -0.30970, -0.35964, -0.32796, -0.34605, -0.30168, -0.22291, -0.31506, -0.35622, -0.32575, -0.36921, -0.46224, -0.68476, -0.90740, -0.96847, -1.00869, -0.99046, -1.06621, -1.13597, -1.16316, -1.17748, -1.14777, -1.20451, -1.20929, -1.13563, -1.17093, -1.11826, -1.01473, -1.04851, -1.07876, -1.13334, -1.22072, -1.32750, -1.37631, -1.31541, -1.21096, -1.26828, -1.41599, -1.53237, -1.72264, -1.81999, -1.73909, -1.72249, -1.67415, -1.60992, -1.55347, -1.37911, -1.32112, -1.26051, -1.17394, -1.06277, -0.97860, -0.98252, -0.89677, -0.80113, -0.77846, -0.71714, -0.64303, -0.45960, -0.25048, -0.21295, -0.10743, 0.12158, 0.33085, 0.43098, 0.52469, 0.56404, 0.69948, 0.77505, 0.89562, 1.15848, 1.26062, 1.27556, 1.42249, 1.50349, 1.56081, 1.52703, 1.35416, 1.29289, 1.16637, 1.11423, 1.05086, 0.92020, 0.80940, 0.70797, 0.65261, 0.62859, 0.67618, 0.87082, 0.97482, 0.93328, 0.94854, 0.85065, 0.86040, 1.15314, 1.52701, 1.80906, 2.02348, 2.13380, 2.30219, 2.33385, 2.28566, 2.32485, 2.28871, 2.24031, 2.35266, 2.43979, 2.46417, 2.48973, 2.43810, 2.49940, 2.34436, 2.10795, 1.97732, 1.92150, 1.84433, 1.72748, 1.73235, 1.72205, 1.55470, 1.42189, 1.31859, 1.25009, 1.33170, 1.33799, 1.33880, 1.44453, 1.56927, 1.57120, 1.63044, 1.70486, 1.81936, 1.79582, 1.66980, 1.64669, 1.53206, 1.26699, 1.08497, 0.84276, 0.51243, 0.26253, -0.05612, +0.30171, 0.04973, -0.12789, -0.33850, -0.62166, -0.78140, -0.92814, -0.98853, -0.98056, -1.03450, -0.99734, -0.90455, -0.86331, -0.67793, -0.56847, -0.58860, -0.62816, -0.67188, -0.63596, -0.73533, -0.86160, -0.88182, -0.89863, -0.91241, -1.03792, -1.08395, -1.11597, -1.33342, -1.50847, -1.64822, -1.81695, -1.83696, -1.86866, -2.05396, -2.11116, -2.10189, -2.15945, -2.12714, -2.13918, -2.01302, -1.80879, -1.72841, -1.69374, -1.70247, -1.87131, -1.99249, -2.06831, -2.10554, -2.09078, -2.26243, -2.41383, -2.56427, -2.71609, -2.65927, -2.56908, -2.48231, -2.44994, -2.39082, -2.29475, -2.34345, -2.40878, -2.50426, -2.79254, -3.00068, -3.25470, -3.60510, -3.83867, -3.97218, -4.13548, -4.17497, -4.30854, -4.47604, -4.57474, -4.74424, -4.90179, -5.02491, -5.15101, -5.09904, -4.98639, -4.97085, -4.89835, -4.91596, -4.86545, -4.87010, -4.95113, -4.92368, -4.88058, -4.82204, -4.82438, -4.79187, -4.68153, -4.72577, -4.78629, -4.71016, -4.66917, -4.50108, -4.37473, -4.49210, -4.68130, -4.73914, -4.81423, -4.66319, -4.49113, -4.32727, -4.08834, -3.96905, -3.89517, -3.78719, -3.79638, -3.91490, -4.01319, -4.13400, -4.08237, -3.94491, -3.69008, -3.47716, -3.43797, -3.44486, -3.55241, -3.65373, -3.73107, -3.75808, -3.69861, -3.76428, -3.94062, -3.96546, -4.08188, -4.11262, -4.00796, -3.93200, -3.88246, -3.72646, -3.61525, -3.33572, -3.08579, -2.91388, -2.58683, -2.22208, -1.92248, -1.61465, -1.39305, -1.20396, -0.94791, -0.82910, -0.67843, -0.64051, -0.58117, -0.46330, -0.42093, -0.28972, -0.22158, -0.19646, -0.23870, -0.28225, -0.18490, -0.15329, -0.27280, -0.29307, -0.38691, -0.38856, -0.28588, -0.21493, -0.24792, -0.19615, -0.25625, -0.22494, -0.13648, -0.10855, -0.08813, -0.29564, -0.68361, -0.98375, -1.25024, -1.39164, -1.39111, -1.49464, -1.53228, -1.64267, -1.72511, -1.71605, -1.78023, -1.78700, -1.79607, -1.84891, -1.93484, -1.99476, -1.96109, -1.97260, -2.08525, -2.03155, -2.05362, -2.07751, -1.89708, -1.65842, -1.56636, -1.44874, -1.40606, -1.31076, -1.21375, -1.25080, -1.22547, -1.19706, -1.24358, -1.19209, -1.12208, -1.13427, -1.05089, -1.08454, -1.09141, -1.13345, -1.22038, -1.26952, -1.38679, -1.37351, -1.26044, -1.20274, -1.20558, -1.28965, -1.25003, -1.11841, -1.07217, -0.85855, -0.73697, -0.75419, -0.69207, -0.63121, -0.64789, -0.49614, -0.37514, -0.33977, -0.24812, -0.20732, -0.10351, 0.06358, 0.04244, 0.07073, 0.16310, 0.19689, 0.38370, 0.59001, 0.87680, 1.13636, 1.25804, 1.29799, 1.14177, 1.03360, 1.03690, 1.03865, 1.11786, 1.13870, 1.15720, 1.05952, 0.79142, 0.61985, 0.40078, 0.04923, -0.02925, 0.00860, -0.08000, -0.13830, -0.21097, -0.30219, -0.27730, -0.29130, -0.25477, -0.18135, -0.28259, -0.36151, -0.38986, -0.46010, -0.52323, -0.69121, -0.87886, -0.92939, -0.96322, -0.91316, -1.00032, -1.10307, -1.10750, -1.11109, -1.08945, -1.07373, -1.02332, -0.96700, -1.03568, -1.00593, -0.93064, -0.99415, -0.97609, -1.03266, -1.20405, -1.29692, -1.29652, -1.26398, -1.16921, -1.19125, -1.25100, -1.30060, -1.45973, -1.53910, -1.47387, -1.46379, -1.39028, -1.36405, -1.37704, -1.24188, -1.17521, -1.04105, -0.91981, -0.81766, -0.65295, -0.56416, -0.44937, -0.34334, -0.28856, -0.26196, -0.29795, -0.23668, -0.08559, -0.06828, 0.10929, 0.35279, 0.46484, 0.53993, 0.64539, 0.62792, 0.70050, 0.73091, 0.83333, 1.07666, 1.19038, 1.21563, 1.32970, 1.41514, 1.52902, 1.56196, 1.42582, 1.31698, 1.14744, 1.10435, 1.09316, 1.03616, 1.01931, 0.93661, 0.86950, 0.85452, 0.92391, 1.07564, 1.06139, 0.90209, 0.86156, 0.72353, 0.79772, 1.10447, 1.35478, 1.59673, 1.88587, 2.01797, 2.19703, 2.30470, 2.35855, 2.45184, 2.44215, 2.31426, 2.28974, 2.33325, 2.41150, 2.54016, 2.55991, 2.60527, 2.44750, 2.26139, 2.17454, 2.10780, 2.09402, 1.99631, 1.93690, 1.87030, 1.73954, 1.62371, 1.46851, 1.32048, 1.38270, 1.37982, 1.45614, 1.62752, 1.67101, 1.60255, 1.66130, 1.66738, 1.69875, 1.64891, 1.54625, 1.55801, 1.49343, 1.24536, 0.98939, 0.65340, 0.30397, 0.10188, -0.09872, +0.40718, 0.24128, 0.04942, -0.18112, -0.44565, -0.55105, -0.59324, -0.66488, -0.71887, -0.72908, -0.81068, -0.84316, -0.70935, -0.53916, -0.42587, -0.38401, -0.42685, -0.51309, -0.56964, -0.64591, -0.76433, -0.91168, -0.94243, -0.88267, -0.96247, -1.00756, -1.07594, -1.33444, -1.56678, -1.78473, -1.89407, -1.86430, -1.95771, -2.09376, -2.19439, -2.23545, -2.24516, -2.16274, -2.07330, -1.99934, -1.91683, -1.73241, -1.66928, -1.76858, -1.83221, -1.86385, -1.92613, -2.02106, -2.09930, -2.21714, -2.31885, -2.40759, -2.49641, -2.54155, -2.51963, -2.43789, -2.41034, -2.30743, -2.20806, -2.24454, -2.24354, -2.34808, -2.61307, -2.85275, -3.25973, -3.60244, -3.82511, -3.93306, -4.02597, -4.09417, -4.23028, -4.46709, -4.66526, -4.79753, -4.92426, -5.10158, -5.17690, -5.17820, -5.13254, -5.07307, -5.00053, -4.97636, -4.87884, -4.77636, -4.78282, -4.84283, -4.81724, -4.71136, -4.70264, -4.64889, -4.54773, -4.58491, -4.62039, -4.57978, -4.56456, -4.39374, -4.38218, -4.50548, -4.66870, -4.76977, -4.81280, -4.61791, -4.38099, -4.26425, -4.13590, -3.91881, -3.74373, -3.77201, -3.75744, -3.78174, -3.84002, -3.89804, -3.85287, -3.71232, -3.52392, -3.36875, -3.34156, -3.44086, -3.58476, -3.60945, -3.58881, -3.53395, -3.49955, -3.65578, -3.87178, -3.93388, -4.02976, -3.93089, -3.89757, -3.90176, -3.87467, -3.75994, -3.55947, -3.23602, -2.88258, -2.62017, -2.44285, -2.21296, -1.90894, -1.70728, -1.45060, -1.21037, -0.94743, -0.73712, -0.61883, -0.56673, -0.48894, -0.36840, -0.29546, -0.24527, -0.20235, -0.07765, -0.04823, -0.03064, -0.00071, -0.06708, -0.20786, -0.25893, -0.34431, -0.26247, -0.23465, -0.18276, -0.16182, -0.17116, -0.18242, -0.07091, 0.04854, 0.04092, -0.10592, -0.32887, -0.54487, -0.87517, -1.08858, -1.16728, -1.24444, -1.36631, -1.48069, -1.58060, -1.64209, -1.59589, -1.53879, -1.57522, -1.66589, -1.73586, -1.80163, -1.77166, -1.69428, -1.67200, -1.77880, -1.82238, -1.93604, -1.89636, -1.75895, -1.60831, -1.43343, -1.29084, -1.26654, -1.23901, -1.15400, -1.13621, -1.25595, -1.39898, -1.36147, -1.36114, -1.33487, -1.27519, -1.20950, -1.20451, -1.23205, -1.25821, -1.25977, -1.24065, -1.26284, -1.28635, -1.32404, -1.31657, -1.31906, -1.36029, -1.31170, -1.22816, -1.19213, -0.97390, -0.88545, -0.86399, -0.83415, -0.82531, -0.82662, -0.77649, -0.69682, -0.57959, -0.37158, -0.17133, -0.07367, -0.00182, 0.06911, 0.04262, 0.07097, 0.20883, 0.39609, 0.67248, 1.00900, 1.25730, 1.38213, 1.36057, 1.23264, 1.13160, 1.07243, 1.12911, 1.24292, 1.24460, 1.22268, 1.08898, 0.83098, 0.64322, 0.45544, 0.24336, 0.12065, -0.00947, -0.07022, -0.09730, -0.17626, -0.25646, -0.17500, -0.09528, -0.18583, -0.29257, -0.33366, -0.42510, -0.54030, -0.53266, -0.55469, -0.65760, -0.80522, -0.89316, -0.95483, -0.94644, -0.99810, -1.06699, -1.14503, -1.16752, -1.09484, -1.01046, -0.93514, -0.93468, -0.99842, -0.92490, -0.90456, -0.97555, -0.96932, -1.05759, -1.12264, -1.14358, -1.12819, -1.08901, -0.99337, -0.96754, -1.09440, -1.26377, -1.34729, -1.32721, -1.27451, -1.17378, -1.09592, -1.11600, -1.12175, -1.00891, -0.87561, -0.69027, -0.55081, -0.48333, -0.46122, -0.38308, -0.18229, -0.03186, 0.13286, 0.17787, 0.03107, -0.02209, 0.04548, 0.09835, 0.26930, 0.36356, 0.51459, 0.63836, 0.68175, 0.66563, 0.73539, 0.78920, 0.79296, 0.85249, 1.01793, 1.16218, 1.22661, 1.37660, 1.50111, 1.53034, 1.46089, 1.35777, 1.25160, 1.20360, 1.22362, 1.22260, 1.08276, 0.90454, 0.89376, 0.93647, 1.01363, 1.07213, 0.97781, 0.85945, 0.81865, 0.73243, 0.86064, 1.00206, 1.18427, 1.40519, 1.63055, 1.81397, 2.05912, 2.33698, 2.48221, 2.45763, 2.41778, 2.33691, 2.21819, 2.32556, 2.50405, 2.66316, 2.69982, 2.63793, 2.46274, 2.29656, 2.24749, 2.23724, 2.22047, 2.10723, 2.01171, 1.88776, 1.80041, 1.69634, 1.46412, 1.29309, 1.37433, 1.41659, 1.55209, 1.62449, 1.63830, 1.60743, 1.58919, 1.58491, 1.64860, 1.67685, 1.61256, 1.46294, 1.29398, 1.13897, 0.81340, 0.53076, 0.28424, 0.06035, -0.06840, +0.47436, 0.37111, 0.17520, -0.02310, -0.22300, -0.25056, -0.24012, -0.34666, -0.43352, -0.42773, -0.53518, -0.61820, -0.57314, -0.51414, -0.40392, -0.32677, -0.40350, -0.54885, -0.66643, -0.72284, -0.74504, -0.90158, -0.96410, -0.89629, -1.05719, -1.18448, -1.20406, -1.38711, -1.61189, -1.83728, -1.97494, -1.98416, -2.05225, -2.07526, -2.16640, -2.21564, -2.24468, -2.17497, -2.00836, -1.97274, -1.93814, -1.71595, -1.65753, -1.75621, -1.84627, -1.94855, -2.01778, -2.15792, -2.29431, -2.35209, -2.37920, -2.41656, -2.38608, -2.38873, -2.40526, -2.32587, -2.35436, -2.30306, -2.16498, -2.13492, -2.12645, -2.22802, -2.52379, -2.82512, -3.16623, -3.34005, -3.54323, -3.65540, -3.79555, -4.00114, -4.18087, -4.51468, -4.76365, -4.83769, -4.92259, -5.05676, -5.18360, -5.36924, -5.36719, -5.26832, -5.19292, -5.16594, -5.03900, -4.87605, -4.78264, -4.76372, -4.70475, -4.53442, -4.56077, -4.61861, -4.52338, -4.48043, -4.48848, -4.39641, -4.38862, -4.29415, -4.31807, -4.31644, -4.40964, -4.51321, -4.57495, -4.51148, -4.33070, -4.30113, -4.23262, -3.92257, -3.68415, -3.70569, -3.69571, -3.76566, -3.77636, -3.79605, -3.76153, -3.66212, -3.52841, -3.41582, -3.35622, -3.36857, -3.51431, -3.51129, -3.51466, -3.56975, -3.54818, -3.61716, -3.72741, -3.68210, -3.77271, -3.72386, -3.76853, -3.74648, -3.73076, -3.65438, -3.42791, -3.17479, -2.78247, -2.50562, -2.42312, -2.23576, -1.92933, -1.69210, -1.43127, -1.33129, -1.10189, -0.86211, -0.77477, -0.73997, -0.61994, -0.46768, -0.35956, -0.23781, -0.19445, -0.00815, 0.05531, 0.01193, 0.03090, 0.01855, -0.09896, -0.06843, -0.10000, -0.05805, -0.10396, -0.03948, -0.03639, -0.10087, -0.11130, -0.07482, 0.00595, -0.07407, -0.29328, -0.40312, -0.46417, -0.69821, -0.85750, -1.05569, -1.21428, -1.34267, -1.48199, -1.58273, -1.62495, -1.57256, -1.48534, -1.44402, -1.54921, -1.57428, -1.53077, -1.51971, -1.45059, -1.35839, -1.47692, -1.54699, -1.71173, -1.74996, -1.67987, -1.50185, -1.25742, -1.11292, -1.12737, -1.24787, -1.21775, -1.20232, -1.42211, -1.63001, -1.56180, -1.54036, -1.52860, -1.56903, -1.53306, -1.47118, -1.49527, -1.52853, -1.47551, -1.39497, -1.34393, -1.24734, -1.29761, -1.32201, -1.34048, -1.45195, -1.42336, -1.30147, -1.25648, -1.06369, -1.02627, -1.07391, -1.11983, -1.08684, -1.05754, -1.07818, -1.00088, -0.85865, -0.60574, -0.32831, -0.22769, -0.14872, 0.00841, 0.03265, 0.09014, 0.18085, 0.29588, 0.58238, 0.89105, 1.07738, 1.18915, 1.20202, 1.20366, 1.25415, 1.22163, 1.27365, 1.35446, 1.22440, 1.09727, 0.98008, 0.78305, 0.62881, 0.51224, 0.33154, 0.12584, -0.03717, -0.01214, -0.00236, -0.07995, -0.21979, -0.19262, -0.11306, -0.31356, -0.48051, -0.42306, -0.44409, -0.54866, -0.60445, -0.70511, -0.76042, -0.87264, -0.97204, -1.04432, -1.05567, -1.07902, -1.01203, -1.00979, -1.03537, -0.96046, -0.97924, -1.01777, -1.01374, -1.01326, -0.90882, -0.88918, -1.01547, -1.05805, -1.06353, -0.97556, -0.95089, -0.92610, -0.93526, -0.91826, -0.87705, -1.04181, -1.22335, -1.20926, -1.12006, -1.04773, -0.98930, -1.02153, -0.98093, -0.86499, -0.73190, -0.58715, -0.40708, -0.30445, -0.22299, -0.20425, -0.16045, 0.07213, 0.18539, 0.31349, 0.39307, 0.25266, 0.13948, 0.21255, 0.25865, 0.32320, 0.33648, 0.55531, 0.67446, 0.66349, 0.61858, 0.62318, 0.67692, 0.57505, 0.53168, 0.77252, 1.01845, 1.15687, 1.33296, 1.36095, 1.41250, 1.41846, 1.37420, 1.31979, 1.27474, 1.27231, 1.25596, 1.09872, 0.83840, 0.81966, 0.81641, 0.75563, 0.76699, 0.75497, 0.73209, 0.77088, 0.71046, 0.77651, 0.82869, 1.05169, 1.26222, 1.46193, 1.66506, 1.85787, 2.18320, 2.30402, 2.21366, 2.23164, 2.28651, 2.31650, 2.46604, 2.53471, 2.65802, 2.65862, 2.51394, 2.27957, 2.10622, 2.07218, 2.11558, 2.22518, 2.11126, 1.98041, 1.79121, 1.61510, 1.53235, 1.35455, 1.19133, 1.33355, 1.39365, 1.46593, 1.49933, 1.62569, 1.64415, 1.57331, 1.53484, 1.51444, 1.56282, 1.49478, 1.29111, 1.15455, 1.07912, 0.83854, 0.64230, 0.33557, 0.08055, -0.04840, +0.54667, 0.38687, 0.20294, 0.10611, 0.02300, 0.00421, -0.02819, -0.05521, -0.10106, -0.14925, -0.27636, -0.39188, -0.45808, -0.44126, -0.29035, -0.28346, -0.41988, -0.50404, -0.65909, -0.71181, -0.62663, -0.76574, -0.91536, -0.89433, -1.06647, -1.23485, -1.28282, -1.39560, -1.57641, -1.84312, -2.05141, -2.15363, -2.18864, -2.19639, -2.21663, -2.16849, -2.16358, -2.17678, -2.08612, -1.99449, -1.89150, -1.73018, -1.70205, -1.78880, -1.92723, -2.07234, -2.09135, -2.25746, -2.42931, -2.40493, -2.44226, -2.52001, -2.38891, -2.33184, -2.37548, -2.27727, -2.20290, -2.10572, -1.98404, -1.95364, -1.96026, -2.15256, -2.46707, -2.82110, -3.02736, -3.14475, -3.34120, -3.43773, -3.59427, -3.92737, -4.20932, -4.52339, -4.69780, -4.81213, -4.93295, -5.11510, -5.33572, -5.58583, -5.50280, -5.36720, -5.30013, -5.18473, -5.04372, -4.94060, -4.74135, -4.62334, -4.53379, -4.32705, -4.29452, -4.39127, -4.37172, -4.37160, -4.33191, -4.25919, -4.18774, -4.16231, -4.14631, -4.14546, -4.23163, -4.29546, -4.31734, -4.37498, -4.32461, -4.30529, -4.15822, -3.88228, -3.66204, -3.66343, -3.67314, -3.79559, -3.74554, -3.76315, -3.79328, -3.66779, -3.54240, -3.51921, -3.33815, -3.21014, -3.34081, -3.37998, -3.39907, -3.51554, -3.51949, -3.57165, -3.52066, -3.46001, -3.53904, -3.62459, -3.67564, -3.66473, -3.64831, -3.54037, -3.25448, -3.06201, -2.75896, -2.53413, -2.40129, -2.24630, -1.97604, -1.72612, -1.48383, -1.46633, -1.20712, -0.96008, -0.91929, -0.82148, -0.60673, -0.50126, -0.33816, -0.14541, -0.12948, -0.00074, 0.11142, 0.10138, 0.17665, 0.16829, 0.14108, 0.15461, 0.13639, 0.06662, 0.02041, 0.04954, 0.00330, -0.06380, -0.05261, -0.11666, -0.15939, -0.29309, -0.40782, -0.46148, -0.50859, -0.70497, -0.84997, -1.12013, -1.23824, -1.29074, -1.40265, -1.41655, -1.37719, -1.43115, -1.37508, -1.27176, -1.36033, -1.38322, -1.21425, -1.16468, -1.11763, -1.10041, -1.18118, -1.27669, -1.44502, -1.58680, -1.53257, -1.35722, -1.16446, -1.08033, -1.09979, -1.27963, -1.33864, -1.37302, -1.51232, -1.70923, -1.72019, -1.74429, -1.75605, -1.87218, -1.77389, -1.60083, -1.63269, -1.63888, -1.50591, -1.48347, -1.40656, -1.16612, -1.13948, -1.21252, -1.23727, -1.37929, -1.40746, -1.36309, -1.28426, -1.13657, -1.15423, -1.29204, -1.39335, -1.37351, -1.38308, -1.41302, -1.29004, -1.14560, -0.96438, -0.72907, -0.49887, -0.31284, -0.14440, -0.06072, 0.08569, 0.16134, 0.28783, 0.59353, 0.78132, 0.90915, 1.09788, 1.11860, 1.20510, 1.39859, 1.39446, 1.35831, 1.40236, 1.26168, 1.09690, 0.93223, 0.79560, 0.68122, 0.54065, 0.29620, 0.03720, -0.07051, -0.01911, 0.03657, 0.02567, -0.10522, -0.21191, -0.26847, -0.44115, -0.54706, -0.49097, -0.47840, -0.56519, -0.69109, -0.82225, -0.80222, -0.92107, -0.99233, -0.92990, -0.96555, -1.03412, -0.88181, -0.84408, -0.91762, -0.85974, -0.89052, -0.97765, -1.01326, -1.00028, -0.88199, -0.90767, -1.05244, -1.15342, -1.09364, -1.00627, -0.98157, -0.91377, -0.89529, -0.96056, -0.94969, -0.97029, -0.99696, -0.98142, -0.92422, -0.90358, -0.91020, -0.95844, -0.76927, -0.56725, -0.43203, -0.21504, -0.07679, -0.07196, 0.07934, 0.14080, 0.14010, 0.35056, 0.48685, 0.56031, 0.56472, 0.40611, 0.34278, 0.38655, 0.43838, 0.38651, 0.39685, 0.53694, 0.59087, 0.58092, 0.56834, 0.50427, 0.47668, 0.37300, 0.38382, 0.57661, 0.81416, 0.98356, 1.20342, 1.27316, 1.45068, 1.50871, 1.46125, 1.49146, 1.46209, 1.35245, 1.34320, 1.19149, 0.85916, 0.74111, 0.70385, 0.57952, 0.55048, 0.52850, 0.59076, 0.59852, 0.55417, 0.52194, 0.60659, 0.81404, 1.04062, 1.32567, 1.61537, 1.74829, 1.96293, 2.03881, 2.04727, 2.09218, 2.22091, 2.35192, 2.50068, 2.48230, 2.61679, 2.60142, 2.40363, 2.22354, 2.09472, 1.97587, 2.06488, 2.21539, 2.04064, 1.84133, 1.69143, 1.53116, 1.46852, 1.28261, 1.20500, 1.30212, 1.36524, 1.34034, 1.42780, 1.60323, 1.63345, 1.56201, 1.52082, 1.37946, 1.30696, 1.20903, 1.17089, 1.13062, 1.07640, 0.87998, 0.71009, 0.35355, 0.15768, 0.04786, +0.65277, 0.46695, 0.29387, 0.26214, 0.32202, 0.36653, 0.33754, 0.34467, 0.20863, 0.06333, -0.07347, -0.16755, -0.18943, -0.16937, -0.09922, -0.24012, -0.44967, -0.47391, -0.52552, -0.51193, -0.49990, -0.72062, -0.90171, -0.92096, -1.10692, -1.29778, -1.40647, -1.53445, -1.70698, -1.98579, -2.10630, -2.15050, -2.21176, -2.26954, -2.29645, -2.21560, -2.11055, -2.09445, -2.09209, -2.00454, -1.92372, -1.85699, -1.82049, -1.86922, -1.94601, -2.08187, -2.15532, -2.35820, -2.55990, -2.54172, -2.54422, -2.55829, -2.41231, -2.38733, -2.40286, -2.26918, -2.15037, -2.01158, -1.89695, -1.90427, -1.95943, -2.21885, -2.45287, -2.67745, -2.82104, -2.93099, -3.11016, -3.26214, -3.44571, -3.77005, -4.08461, -4.32946, -4.47868, -4.72414, -4.93844, -5.24317, -5.45964, -5.59194, -5.45954, -5.37069, -5.34420, -5.20802, -5.01766, -4.86139, -4.64820, -4.59148, -4.46251, -4.19012, -4.09687, -4.15869, -4.14048, -4.20014, -4.18598, -4.20844, -4.09958, -3.97354, -3.92837, -3.96645, -4.08507, -4.17103, -4.12188, -4.10648, -4.07474, -4.02089, -3.85794, -3.76156, -3.62512, -3.63834, -3.62631, -3.68789, -3.63932, -3.71338, -3.76639, -3.65856, -3.53860, -3.49687, -3.30507, -3.23581, -3.30602, -3.29325, -3.31579, -3.43782, -3.44176, -3.51476, -3.42108, -3.40242, -3.44094, -3.49130, -3.59231, -3.62373, -3.57382, -3.42306, -3.06592, -2.81595, -2.60961, -2.48450, -2.34083, -2.26555, -2.03569, -1.85234, -1.62689, -1.51904, -1.24150, -1.05020, -1.01690, -0.89929, -0.61774, -0.43402, -0.24172, -0.14747, -0.11414, 0.02676, 0.13873, 0.11718, 0.21276, 0.20034, 0.23335, 0.19168, 0.14023, 0.12969, 0.10845, 0.10326, 0.06905, -0.00900, -0.00200, -0.08792, -0.22095, -0.36759, -0.42228, -0.54013, -0.60366, -0.78706, -0.85916, -1.00339, -1.07785, -1.16289, -1.28781, -1.28337, -1.17307, -1.17113, -1.11845, -1.11581, -1.19088, -1.14374, -0.92678, -0.87057, -0.83922, -0.94850, -1.08517, -1.22336, -1.35369, -1.34961, -1.24050, -1.13622, -1.07009, -1.15009, -1.19363, -1.27675, -1.34345, -1.43196, -1.52939, -1.76956, -1.85552, -1.94417, -1.96553, -2.00834, -1.85081, -1.66929, -1.69829, -1.67826, -1.46443, -1.37137, -1.26694, -1.13628, -1.13268, -1.16625, -1.17195, -1.36015, -1.47917, -1.53943, -1.48775, -1.39353, -1.42541, -1.46878, -1.54140, -1.61340, -1.67305, -1.71250, -1.58208, -1.36815, -1.17911, -0.94882, -0.59063, -0.37222, -0.24556, -0.17826, -0.00962, 0.16991, 0.37694, 0.63079, 0.70435, 0.77977, 1.01892, 1.15222, 1.33565, 1.49137, 1.43461, 1.33569, 1.31351, 1.15900, 1.01385, 0.86873, 0.75530, 0.61204, 0.36769, 0.12834, -0.03532, -0.08018, -0.01525, 0.02329, 0.02904, 0.00048, -0.11665, -0.27175, -0.43074, -0.56137, -0.57975, -0.56590, -0.62942, -0.65357, -0.66299, -0.62101, -0.78908, -0.90698, -0.81653, -0.79534, -0.81823, -0.76861, -0.88066, -0.96971, -0.89523, -0.90074, -0.94947, -0.97770, -1.01067, -0.97928, -1.07413, -1.13506, -1.14566, -1.08121, -1.02918, -1.01300, -0.91440, -0.80337, -0.83496, -0.86640, -0.81383, -0.76762, -0.79342, -0.77448, -0.81117, -0.76688, -0.69795, -0.44413, -0.25698, -0.13457, 0.09136, 0.20919, 0.20864, 0.33728, 0.33809, 0.38811, 0.60939, 0.70540, 0.66734, 0.57367, 0.40612, 0.39956, 0.40336, 0.47681, 0.48566, 0.48045, 0.50632, 0.47189, 0.41098, 0.44762, 0.44351, 0.38688, 0.31704, 0.38816, 0.50766, 0.71009, 0.83296, 1.08220, 1.29438, 1.55918, 1.61794, 1.53513, 1.53545, 1.54406, 1.47603, 1.44914, 1.18975, 0.85430, 0.67564, 0.52484, 0.34080, 0.28786, 0.21311, 0.28472, 0.24463, 0.27883, 0.41075, 0.55840, 0.71219, 0.89793, 1.16242, 1.53195, 1.75960, 1.90872, 1.95677, 2.03410, 2.03689, 2.19410, 2.32145, 2.48552, 2.52056, 2.59229, 2.47544, 2.26694, 2.14846, 2.13963, 2.08178, 2.12063, 2.02341, 1.75487, 1.59055, 1.50127, 1.36655, 1.30378, 1.10427, 1.08014, 1.10767, 1.17769, 1.26323, 1.40915, 1.57339, 1.60966, 1.51046, 1.50991, 1.42607, 1.27365, 1.11979, 1.13783, 1.08762, 1.06906, 0.89707, 0.74728, 0.47618, 0.33510, 0.18019, +0.69268, 0.62526, 0.54894, 0.47472, 0.44945, 0.52266, 0.55555, 0.56818, 0.39465, 0.24000, 0.18843, 0.11783, 0.07277, 0.05674, -0.01639, -0.26230, -0.35933, -0.26900, -0.24767, -0.22678, -0.31865, -0.49789, -0.69838, -0.83878, -1.03858, -1.28355, -1.46562, -1.62178, -1.79568, -1.97840, -2.00699, -2.08488, -2.18109, -2.25133, -2.30200, -2.30011, -2.21701, -2.12158, -2.14669, -2.12782, -2.08796, -2.07059, -1.95382, -1.94307, -1.98897, -2.08243, -2.22379, -2.43527, -2.56634, -2.54938, -2.58965, -2.55630, -2.40012, -2.30484, -2.28879, -2.26132, -2.19697, -2.10030, -1.97577, -1.94140, -2.02472, -2.21754, -2.35436, -2.55732, -2.73107, -2.79873, -2.87480, -3.10288, -3.40307, -3.67311, -3.92969, -4.13583, -4.31467, -4.66610, -4.94120, -5.30577, -5.48979, -5.45384, -5.30916, -5.33400, -5.32275, -5.12818, -4.94422, -4.73802, -4.51506, -4.40686, -4.23713, -4.05882, -3.91939, -3.92528, -3.85411, -3.87730, -3.92575, -4.02602, -3.96414, -3.87533, -3.81107, -3.78356, -3.86600, -4.00149, -4.00529, -3.92040, -3.79809, -3.69811, -3.52433, -3.52469, -3.43424, -3.43363, -3.48503, -3.52178, -3.52291, -3.66802, -3.69016, -3.55873, -3.52897, -3.52101, -3.40837, -3.32779, -3.24748, -3.25154, -3.25347, -3.35112, -3.34904, -3.38957, -3.39078, -3.40683, -3.36743, -3.44799, -3.59054, -3.55833, -3.39470, -3.20093, -2.93421, -2.70661, -2.53599, -2.47120, -2.27714, -2.17607, -1.95470, -1.84472, -1.73736, -1.54431, -1.24850, -1.10176, -0.99926, -0.77037, -0.52865, -0.33980, -0.14247, -0.04125, 0.11903, 0.16480, 0.20181, 0.07842, 0.09861, 0.16013, 0.25518, 0.22851, 0.17234, 0.12035, 0.06809, 0.09577, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.33666, -0.38497, -0.53972, -0.60047, -0.71020, -0.77775, -0.84558, -0.91448, -1.10913, -1.29577, -1.21670, -1.07793, -1.02414, -0.94254, -0.92467, -0.86184, -0.85127, -0.75691, -0.76935, -0.77334, -0.90048, -1.05794, -1.17090, -1.18599, -1.10037, -1.02817, -0.97818, -0.98620, -1.14561, -1.25084, -1.29965, -1.31765, -1.47974, -1.60129, -1.81192, -1.88611, -1.92848, -1.98889, -2.00889, -1.86299, -1.75940, -1.76564, -1.60170, -1.33670, -1.23283, -1.14918, -1.16279, -1.13763, -1.16682, -1.18998, -1.40963, -1.64288, -1.74969, -1.72966, -1.68038, -1.64373, -1.62337, -1.69860, -1.78102, -1.77467, -1.73984, -1.69179, -1.53427, -1.28331, -1.01743, -0.61713, -0.39539, -0.30678, -0.25653, -0.19055, 0.00617, 0.29563, 0.48539, 0.51575, 0.69248, 0.99172, 1.15382, 1.32626, 1.43776, 1.47195, 1.33589, 1.19259, 1.02340, 0.88515, 0.80351, 0.71153, 0.50461, 0.21103, -0.01887, -0.11109, -0.05144, 0.08497, 0.10605, 0.03140, 0.00548, -0.03531, -0.18770, -0.35883, -0.51602, -0.60148, -0.55389, -0.59566, -0.53999, -0.40215, -0.37995, -0.61009, -0.76286, -0.71393, -0.70211, -0.68032, -0.73256, -0.89315, -0.99407, -1.01510, -1.00308, -1.00420, -0.95709, -0.93751, -0.97339, -1.03792, -1.02359, -1.04125, -0.98379, -0.88079, -0.80825, -0.75507, -0.70704, -0.70271, -0.77407, -0.78168, -0.70814, -0.70453, -0.64497, -0.68966, -0.62683, -0.44125, -0.23044, -0.16572, -0.00607, 0.27838, 0.36052, 0.38853, 0.51329, 0.59597, 0.72938, 0.80569, 0.80038, 0.61470, 0.49999, 0.47420, 0.53582, 0.55324, 0.58311, 0.53918, 0.52324, 0.54978, 0.51194, 0.36823, 0.30904, 0.32819, 0.31568, 0.28613, 0.43710, 0.56584, 0.75409, 0.80905, 0.91800, 1.18916, 1.49235, 1.54721, 1.49076, 1.50051, 1.48091, 1.43511, 1.39763, 1.19807, 0.98174, 0.69669, 0.44667, 0.19599, 0.11898, 0.06664, 0.10042, 0.08335, 0.21365, 0.40669, 0.58002, 0.75107, 0.89491, 1.04267, 1.33645, 1.63156, 1.80915, 1.84713, 1.97561, 1.99499, 2.13812, 2.19719, 2.27860, 2.37070, 2.39651, 2.21016, 2.07900, 2.13369, 2.18839, 2.13833, 2.07253, 1.81640, 1.59531, 1.42898, 1.38592, 1.22063, 1.08669, 0.96197, 0.98355, 1.02145, 1.13716, 1.24156, 1.37948, 1.55739, 1.65316, 1.56121, 1.52238, 1.46221, 1.30514, 1.07020, 1.01390, 0.96012, 1.02348, 0.95920, 0.77196, 0.55633, 0.44399, 0.20182, +0.62741, 0.57721, 0.63503, 0.55220, 0.39478, 0.44998, 0.52167, 0.58325, 0.51821, 0.44630, 0.46597, 0.35938, 0.20774, 0.14893, 0.09174, -0.07439, -0.06398, 0.07578, 0.11765, 0.12568, -0.02210, -0.15921, -0.33180, -0.52324, -0.70001, -0.98015, -1.26500, -1.48865, -1.70071, -1.87033, -1.87740, -2.01496, -2.20532, -2.35513, -2.34833, -2.34257, -2.32681, -2.19395, -2.20372, -2.22241, -2.19373, -2.21877, -2.09974, -2.08154, -2.12414, -2.12879, -2.18551, -2.31943, -2.43589, -2.46952, -2.56357, -2.53581, -2.41889, -2.31734, -2.25830, -2.25249, -2.17917, -2.07448, -1.97775, -1.96703, -2.09902, -2.29901, -2.35849, -2.54138, -2.78447, -2.91375, -2.86141, -3.00294, -3.32504, -3.55775, -3.79180, -4.04845, -4.29586, -4.67755, -4.93411, -5.23233, -5.34672, -5.22055, -5.03732, -5.05972, -5.09021, -4.93039, -4.77879, -4.56541, -4.33204, -4.16250, -3.93497, -3.77587, -3.57734, -3.50526, -3.44502, -3.50323, -3.59439, -3.78600, -3.74710, -3.68656, -3.65649, -3.67801, -3.66760, -3.71813, -3.77724, -3.72114, -3.58470, -3.48183, -3.27585, -3.22790, -3.12445, -3.14034, -3.28630, -3.35906, -3.37659, -3.48893, -3.56992, -3.56080, -3.62947, -3.66199, -3.57012, -3.42478, -3.19967, -3.14631, -3.11015, -3.15138, -3.16988, -3.26647, -3.37106, -3.47970, -3.38192, -3.40787, -3.51174, -3.53064, -3.31342, -3.06798, -2.93542, -2.76518, -2.56522, -2.44904, -2.15889, -1.99151, -1.77030, -1.70456, -1.69636, -1.49129, -1.16044, -0.91963, -0.75558, -0.51328, -0.32626, -0.18635, -0.00623, 0.09106, 0.29975, 0.29827, 0.29555, 0.16649, 0.14867, 0.21374, 0.34266, 0.29767, 0.26815, 0.21134, 0.11590, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.44004, -0.48065, -0.54145, -0.67884, -0.79507, -0.86331, -1.01824, -1.21623, -1.15065, -1.02802, -0.98347, -0.89425, -0.84535, -0.67403, -0.64749, -0.64418, -0.67025, -0.69726, -0.82481, -0.92961, -1.05411, -1.02731, -0.94326, -0.94884, -1.04338, -1.09429, -1.13668, -1.23849, -1.33163, -1.33839, -1.54786, -1.67258, -1.79875, -1.81038, -1.78149, -1.87466, -1.93053, -1.81386, -1.68809, -1.66612, -1.51156, -1.31675, -1.27960, -1.22383, -1.30055, -1.22685, -1.18452, -1.17704, -1.31749, -1.56533, -1.73960, -1.79352, -1.89086, -1.89645, -1.84676, -1.88359, -1.97016, -1.91643, -1.73888, -1.70619, -1.62636, -1.34644, -1.08204, -0.74143, -0.55766, -0.49082, -0.44051, -0.44215, -0.27411, 0.04641, 0.26629, 0.31462, 0.51105, 0.81739, 0.96506, 1.11320, 1.22213, 1.36392, 1.33157, 1.20755, 1.07574, 0.92371, 0.77201, 0.62397, 0.35273, 0.05276, -0.07825, -0.09512, -0.05874, 0.04275, 0.12733, 0.06225, 0.00967, 0.02970, -0.08571, -0.25229, -0.38707, -0.47798, -0.39394, -0.42427, -0.37943, -0.20886, -0.14568, -0.33910, -0.54354, -0.57637, -0.62110, -0.59871, -0.68664, -0.82819, -0.89184, -0.96075, -0.94986, -0.92562, -0.86238, -0.79652, -0.81559, -0.86412, -0.79059, -0.80521, -0.80532, -0.75659, -0.61529, -0.59272, -0.67737, -0.68436, -0.77170, -0.81703, -0.70755, -0.65346, -0.56500, -0.62914, -0.60422, -0.39218, -0.19494, -0.15648, -0.01197, 0.27123, 0.38900, 0.49013, 0.63955, 0.77781, 0.92855, 0.91089, 0.87368, 0.69246, 0.62858, 0.68010, 0.75988, 0.72999, 0.73362, 0.65057, 0.57262, 0.49453, 0.49036, 0.36499, 0.20545, 0.20694, 0.24142, 0.24577, 0.43255, 0.55795, 0.72146, 0.72936, 0.71916, 0.98284, 1.32153, 1.46155, 1.43507, 1.41853, 1.36198, 1.27789, 1.20080, 1.06553, 0.98690, 0.76652, 0.56791, 0.34138, 0.21821, 0.11797, 0.10506, 0.04433, 0.21518, 0.39459, 0.52156, 0.59510, 0.73967, 0.91058, 1.11825, 1.38772, 1.55976, 1.55761, 1.69988, 1.75727, 1.87628, 1.87480, 1.86929, 1.98253, 2.08826, 2.04225, 1.98498, 2.06867, 2.08900, 1.99042, 1.87743, 1.61909, 1.53073, 1.43343, 1.42791, 1.29399, 1.11646, 0.99221, 1.03010, 1.02378, 1.16699, 1.28500, 1.39699, 1.46746, 1.60262, 1.61636, 1.50800, 1.37565, 1.21936, 0.95117, 0.87492, 0.88125, 1.01844, 1.06094, 0.88652, 0.70357, 0.61710, 0.38115, +0.68768, 0.57741, 0.56302, 0.49817, 0.38543, 0.36498, 0.48486, 0.59319, 0.57897, 0.60285, 0.61956, 0.49972, 0.37275, 0.25879, 0.22160, 0.20079, 0.30077, 0.43599, 0.49957, 0.55678, 0.40548, 0.19885, 0.02898, -0.16884, -0.38353, -0.68410, -1.01752, -1.36013, -1.60067, -1.70337, -1.76236, -1.91746, -2.13723, -2.34268, -2.36405, -2.34190, -2.27351, -2.20513, -2.17061, -2.17134, -2.22599, -2.29748, -2.27222, -2.25278, -2.18252, -2.13578, -2.16117, -2.21368, -2.31459, -2.38251, -2.50332, -2.45807, -2.40431, -2.41701, -2.35941, -2.29396, -2.20821, -2.05320, -1.96371, -2.06830, -2.28984, -2.43004, -2.46259, -2.56546, -2.75814, -2.92176, -2.89097, -2.99392, -3.15893, -3.42001, -3.67407, -3.98039, -4.38838, -4.76277, -4.98004, -5.15384, -5.09551, -4.94952, -4.81830, -4.77829, -4.80962, -4.69378, -4.57955, -4.32554, -4.08357, -3.93839, -3.70475, -3.47678, -3.27648, -3.14947, -3.09952, -3.24749, -3.38680, -3.48545, -3.41876, -3.31931, -3.29171, -3.37985, -3.37278, -3.43207, -3.39906, -3.43057, -3.37206, -3.23791, -3.10334, -3.01548, -2.91884, -2.98433, -3.10853, -3.20020, -3.31389, -3.40081, -3.56187, -3.66908, -3.80049, -3.77015, -3.60840, -3.42094, -3.16489, -3.01650, -3.01772, -3.04988, -3.07144, -3.24772, -3.44407, -3.49631, -3.37505, -3.30078, -3.29294, -3.36422, -3.21729, -3.12048, -2.98449, -2.82936, -2.60882, -2.32878, -2.04315, -1.87336, -1.64973, -1.59132, -1.52519, -1.28057, -1.01719, -0.70255, -0.49230, -0.24280, -0.09533, 0.06573, 0.23715, 0.27220, 0.37839, 0.38466, 0.34256, 0.25311, 0.29879, 0.34922, 0.40594, 0.43510, 0.45740, 0.43657, 0.35749, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.59980, -0.70151, -0.84093, -0.93765, -1.07452, -0.99812, -0.92495, -0.87632, -0.80586, -0.78050, -0.64348, -0.54182, -0.56176, -0.60257, -0.62975, -0.74294, -0.86539, -0.93643, -0.88779, -0.85637, -0.88364, -1.04910, -1.12934, -1.20544, -1.24388, -1.33901, -1.42413, -1.56081, -1.69958, -1.82267, -1.77294, -1.72967, -1.77375, -1.76032, -1.72921, -1.60626, -1.56303, -1.46051, -1.40184, -1.40757, -1.34377, -1.41104, -1.34437, -1.20542, -1.16006, -1.24354, -1.42799, -1.62501, -1.83510, -2.04787, -2.09621, -2.06326, -2.02185, -2.06163, -2.00124, -1.87698, -1.79494, -1.66271, -1.45086, -1.16367, -0.93560, -0.88723, -0.82636, -0.78980, -0.72611, -0.45238, -0.19433, -0.01285, 0.05034, 0.25160, 0.54845, 0.74410, 0.96265, 1.10163, 1.23026, 1.31681, 1.27325, 1.12534, 0.94673, 0.69989, 0.41036, 0.13615, -0.04395, -0.08798, -0.02867, -0.02212, 0.01787, 0.05436, 0.03086, 0.06941, 0.05892, 0.01691, -0.11840, -0.29280, -0.34285, -0.25513, -0.23680, -0.11828, -0.02792, -0.00215, -0.12218, -0.30097, -0.36113, -0.44127, -0.39896, -0.48861, -0.66769, -0.70808, -0.76816, -0.83876, -0.82090, -0.75084, -0.73200, -0.71962, -0.65732, -0.56554, -0.51696, -0.51052, -0.53033, -0.47056, -0.53082, -0.60006, -0.67511, -0.72961, -0.71602, -0.65975, -0.58819, -0.54534, -0.63891, -0.55930, -0.38671, -0.25411, -0.16877, -0.03337, 0.23238, 0.41357, 0.64508, 0.82793, 0.90618, 0.98016, 0.96075, 0.89671, 0.79775, 0.82387, 0.82894, 0.85125, 0.89596, 0.89674, 0.83260, 0.72861, 0.53933, 0.46002, 0.27422, 0.17786, 0.13918, 0.20014, 0.28124, 0.36596, 0.43111, 0.54014, 0.53782, 0.61366, 0.89519, 1.15818, 1.35720, 1.36561, 1.35392, 1.27564, 1.20462, 1.08578, 0.93015, 0.90159, 0.83954, 0.69299, 0.50220, 0.36229, 0.16752, 0.06008, 0.05491, 0.20792, 0.36688, 0.48421, 0.48358, 0.60172, 0.73449, 1.00126, 1.19429, 1.26695, 1.25154, 1.28079, 1.32432, 1.44069, 1.42776, 1.47334, 1.63767, 1.76722, 1.88030, 1.88995, 1.96085, 1.90345, 1.83196, 1.74753, 1.52656, 1.48391, 1.47918, 1.44937, 1.35830, 1.22205, 1.05776, 1.01132, 1.05186, 1.20344, 1.34470, 1.48835, 1.49682, 1.61043, 1.56527, 1.48662, 1.28723, 1.07994, 0.90921, 0.82865, 0.88163, 1.06119, 1.14295, 1.09613, 1.02005, 0.86545, 0.61176, +0.65211, 0.57706, 0.55094, 0.56176, 0.53788, 0.44951, 0.51319, 0.58220, 0.64357, 0.78000, 0.77136, 0.61210, 0.49438, 0.36888, 0.37843, 0.48386, 0.62914, 0.70919, 0.71014, 0.79166, 0.69230, 0.43627, 0.19926, -0.02070, -0.23646, -0.55029, -0.85505, -1.18708, -1.46982, -1.53581, -1.66623, -1.90495, -2.09730, -2.26327, -2.25569, -2.18383, -2.10390, -2.14761, -2.13978, -2.14819, -2.20368, -2.22721, -2.26098, -2.23786, -2.12145, -2.13213, -2.20452, -2.23088, -2.28050, -2.33585, -2.52803, -2.54194, -2.53322, -2.57436, -2.53980, -2.48116, -2.38390, -2.22398, -2.10115, -2.15783, -2.44685, -2.55695, -2.59876, -2.69056, -2.74730, -2.86085, -2.87553, -2.92383, -2.95612, -3.24113, -3.55703, -3.98258, -4.46771, -4.72030, -4.84508, -4.89798, -4.78828, -4.74623, -4.70513, -4.62344, -4.61576, -4.52098, -4.45802, -4.18224, -3.89772, -3.74297, -3.58509, -3.41086, -3.19450, -2.98580, -2.86007, -2.89440, -3.06681, -3.12105, -3.03388, -3.00850, -2.99304, -3.10463, -3.12151, -3.12122, -2.99176, -3.07142, -3.08213, -2.97809, -2.91270, -2.78968, -2.73716, -2.84997, -2.95845, -3.11971, -3.35360, -3.49719, -3.71527, -3.82396, -3.96805, -3.90097, -3.66803, -3.44197, -3.22736, -3.11981, -3.13671, -3.12774, -3.11084, -3.12665, -3.33060, -3.41855, -3.35624, -3.33725, -3.23685, -3.26230, -3.19094, -3.18393, -3.00355, -2.80248, -2.51202, -2.14060, -1.92089, -1.73841, -1.51349, -1.42090, -1.29854, -1.10932, -0.92047, -0.56919, -0.31905, -0.05072, 0.01078, 0.11920, 0.30743, 0.38131, 0.42418, 0.34818, 0.27202, 0.24783, 0.38192, 0.57776, 0.57088, 0.53383, 0.55565, 0.48420, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.81262, -0.91290, -0.83677, -0.84456, -0.86797, -0.81020, -0.74398, -0.63943, -0.53533, -0.55112, -0.61903, -0.68327, -0.64683, -0.72350, -0.82984, -0.83327, -0.97538, -1.02438, -1.10800, -1.11885, -1.15970, -1.18689, -1.33246, -1.49019, -1.58323, -1.75139, -1.84931, -1.72447, -1.63635, -1.62622, -1.62062, -1.71857, -1.65136, -1.58686, -1.46271, -1.49000, -1.58518, -1.53872, -1.53668, -1.45491, -1.34714, -1.33876, -1.41933, -1.54811, -1.59169, -1.80404, -2.13064, -2.23901, -2.30575, -2.29358, -2.28938, -2.21755, -2.09072, -1.91254, -1.72799, -1.59235, -1.35426, -1.23835, -1.20437, -1.08240, -1.03103, -0.92230, -0.65013, -0.50313, -0.39115, -0.30315, -0.03930, 0.27476, 0.51545, 0.79561, 0.96004, 1.04924, 1.13982, 1.12679, 0.96426, 0.73576, 0.50321, 0.25367, -0.01020, -0.07751, -0.12680, -0.14938, -0.16112, -0.11362, -0.04105, 0.01623, 0.11193, 0.09784, 0.13027, 0.00609, -0.17093, -0.17294, -0.08187, 0.00251, 0.17694, 0.17283, 0.12577, 0.02955, -0.08122, -0.12688, -0.28476, -0.29880, -0.40749, -0.58371, -0.63426, -0.71366, -0.82312, -0.80746, -0.65689, -0.57804, -0.62939, -0.55448, -0.49168, -0.45267, -0.39051, -0.40334, -0.39468, -0.44289, -0.43761, -0.53270, -0.56010, -0.56039, -0.56700, -0.46313, -0.46322, -0.55573, -0.44845, -0.36054, -0.26456, -0.16532, -0.06980, 0.15344, 0.33697, 0.63339, 0.84880, 0.88414, 0.84746, 0.81071, 0.79573, 0.83320, 0.97287, 1.02644, 0.93319, 0.97610, 0.96997, 0.81874, 0.70539, 0.54283, 0.46763, 0.30597, 0.24016, 0.12505, 0.17792, 0.28055, 0.32022, 0.40501, 0.47086, 0.46756, 0.62126, 0.86203, 1.01395, 1.16154, 1.15197, 1.17693, 1.08813, 1.01491, 0.90269, 0.78825, 0.77959, 0.73043, 0.58655, 0.42220, 0.32235, 0.24780, 0.05859, -0.00230, 0.07214, 0.11724, 0.27663, 0.33963, 0.47958, 0.62773, 0.90675, 1.00695, 0.98528, 0.92653, 0.87441, 0.97367, 1.14537, 1.14499, 1.18693, 1.29710, 1.42656, 1.62884, 1.67539, 1.72907, 1.58958, 1.54336, 1.55296, 1.47948, 1.44345, 1.35804, 1.26562, 1.22665, 1.18111, 1.14756, 1.03785, 1.07271, 1.24030, 1.29687, 1.42861, 1.45180, 1.57407, 1.57720, 1.57691, 1.34823, 1.10309, 0.97160, 0.90909, 1.05877, 1.25323, 1.30700, 1.30012, 1.24536, 1.03772, 0.75353, +0.72722, 0.61935, 0.62228, 0.73804, 0.72723, 0.58736, 0.60068, 0.64306, 0.70595, 0.80936, 0.83057, 0.69232, 0.54932, 0.53155, 0.67498, 0.85110, 0.85247, 0.76141, 0.71007, 0.81219, 0.73221, 0.43139, 0.22653, 0.03096, -0.22878, -0.57156, -0.86382, -1.09844, -1.32539, -1.45752, -1.57944, -1.74998, -1.95445, -2.20427, -2.21797, -2.08756, -2.07932, -2.21722, -2.21220, -2.15526, -2.15970, -2.16591, -2.14012, -2.05141, -2.02917, -2.10408, -2.16568, -2.14832, -2.19407, -2.32423, -2.55591, -2.63336, -2.66488, -2.67338, -2.54416, -2.43184, -2.39560, -2.31772, -2.21040, -2.16993, -2.37949, -2.53361, -2.59946, -2.57052, -2.55320, -2.75073, -2.85975, -2.83322, -2.87175, -3.18568, -3.51946, -3.93082, -4.34016, -4.53120, -4.56158, -4.53101, -4.60662, -4.70150, -4.65227, -4.48681, -4.45221, -4.49113, -4.45230, -4.15826, -3.85774, -3.71287, -3.54559, -3.32309, -3.11608, -2.86272, -2.63218, -2.50171, -2.59573, -2.71684, -2.70526, -2.65350, -2.68184, -2.93187, -3.03679, -2.89939, -2.73631, -2.80282, -2.78811, -2.64991, -2.60853, -2.58629, -2.60536, -2.66749, -2.84692, -3.09383, -3.34055, -3.50560, -3.73009, -3.88706, -3.98037, -3.86884, -3.62556, -3.44960, -3.24983, -3.08861, -3.10707, -3.08445, -3.03768, -2.89390, -3.00050, -3.20686, -3.30786, -3.27586, -3.16007, -3.25074, -3.30735, -3.21911, -2.95049, -2.68521, -2.30520, -1.89548, -1.77397, -1.69062, -1.50788, -1.27866, -1.18390, -1.12794, -0.92988, -0.52640, -0.24861, -0.11187, -0.11464, -0.01869, 0.19440, 0.31557, 0.42021, 0.43106, 0.32763, 0.28132, 0.42852, 0.70052, 0.00000, 0.56798, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.53211, -0.62876, -0.73919, -0.80552, -0.73686, -0.65907, -0.56204, -0.34483, -0.36170, -0.53247, -0.66266, -0.57014, -0.56434, -0.72139, -0.89003, -1.04047, -0.99261, -1.03360, -1.08341, -1.10424, -1.20482, -1.46327, -1.64715, -1.65765, -1.79957, -1.94154, -1.86444, -1.67093, -1.64313, -1.75309, -1.86068, -1.74846, -1.62007, -1.54045, -1.60236, -1.71934, -1.69932, -1.71459, -1.66373, -1.51405, -1.54583, -1.71188, -1.81495, -1.73853, -1.82224, -2.12709, -2.35733, -2.44865, -2.43778, -2.51147, -2.56468, -2.39451, -2.10055, -1.92304, -1.82465, -1.58964, -1.44209, -1.34565, -1.22307, -1.08032, -0.96465, -0.85942, -0.75264, -0.60340, -0.42440, -0.17451, 0.09287, 0.39140, 0.69433, 0.80354, 0.82737, 0.96995, 0.97993, 0.74714, 0.46858, 0.29518, 0.23510, 0.07269, -0.04153, -0.16400, -0.25624, -0.35223, -0.39844, -0.26275, -0.09387, -0.03491, -0.04776, 0.06712, 0.01031, -0.15414, -0.19674, -0.03271, 0.14977, 0.29062, 0.30891, 0.30373, 0.24262, 0.09536, -0.06239, -0.27138, -0.34595, -0.51565, -0.68259, -0.62981, -0.62727, -0.74637, -0.73483, -0.54705, -0.39761, -0.47374, -0.52758, -0.49299, -0.34615, -0.26600, -0.37171, -0.40048, -0.29892, -0.22215, -0.29087, -0.26508, -0.25653, -0.32278, -0.30132, -0.29285, -0.29259, -0.26886, -0.24128, -0.08714, 0.02392, 0.01097, 0.04715, 0.19610, 0.49881, 0.69818, 0.70389, 0.74037, 0.85589, 0.88743, 0.97909, 1.09806, 1.15401, 1.03194, 0.96957, 0.93422, 0.82316, 0.66402, 0.42301, 0.31981, 0.27114, 0.16720, -0.01084, 0.06038, 0.22367, 0.30503, 0.37048, 0.42587, 0.49404, 0.57219, 0.71654, 0.85444, 0.97097, 0.91176, 0.84474, 0.78587, 0.76234, 0.70026, 0.62401, 0.68878, 0.70263, 0.49134, 0.29242, 0.22770, 0.29366, 0.14118, -0.05863, -0.11678, 0.00109, 0.23156, 0.27464, 0.36948, 0.58673, 0.79358, 0.80018, 0.76159, 0.75716, 0.70443, 0.76891, 0.96308, 1.04357, 0.96782, 0.94638, 1.11847, 1.38948, 1.44885, 1.36648, 1.24912, 1.30828, 1.41256, 1.41027, 1.34385, 1.24011, 1.06684, 1.02151, 1.05574, 1.12788, 1.05470, 1.03006, 1.12235, 1.22114, 1.34735, 1.31760, 1.38582, 1.53695, 1.62438, 1.40332, 1.17531, 1.10388, 1.06915, 1.18240, 1.31654, 1.40906, 1.33632, 1.21083, 1.06921, 0.86555, +0.94704, 0.86319, 0.77345, 0.86227, 0.84953, 0.68670, 0.64039, 0.63614, 0.73140, 0.83501, 0.81646, 0.67810, 0.65666, 0.79918, 0.91921, 1.02733, 1.03336, 0.93392, 0.85581, 0.95419, 0.87211, 0.55156, 0.28885, 0.00782, -0.22767, -0.51018, -0.86591, -1.13953, -1.23274, -1.32124, -1.48019, -1.63318, -1.78168, -2.03909, -2.20402, -2.15505, -2.15304, -2.27518, -2.27090, -2.21344, -2.15313, -2.10162, -2.08147, -2.01744, -1.96465, -1.92177, -2.00336, -2.03285, -1.99149, -2.06600, -2.31965, -2.43353, -2.48862, -2.49290, -2.38424, -2.34543, -2.31485, -2.20016, -2.16957, -2.22291, -2.30441, -2.36424, -2.47162, -2.42368, -2.35395, -2.52502, -2.74287, -2.77885, -2.81156, -3.09149, -3.42792, -3.82011, -4.11337, -4.22051, -4.27432, -4.33721, -4.49659, -4.52086, -4.49114, -4.37908, -4.26702, -4.24807, -4.23457, -3.96646, -3.67520, -3.53193, -3.36461, -3.18171, -2.95477, -2.58562, -2.33789, -2.28399, -2.28168, -2.32702, -2.42407, -2.41091, -2.42307, -2.62321, -2.81297, -2.73555, -2.56283, -2.57179, -2.54237, -2.43572, -2.37848, -2.32285, -2.39048, -2.51673, -2.72458, -2.88038, -3.14607, -3.42646, -3.60487, -3.65401, -3.72212, -3.59973, -3.36469, -3.21938, -3.05095, -2.95886, -2.97028, -2.83498, -2.78969, -2.77118, -2.84871, -2.98883, -3.18400, -3.19201, -3.06714, -3.08549, -3.22376, -3.17381, -2.83133, -2.48678, -2.09370, -1.76984, -1.71057, -1.60400, -1.45589, -1.25938, -1.19220, -1.06579, -0.88142, -0.61098, -0.32960, -0.12773, -0.12550, -0.01635, 0.20548, 0.35019, 0.48516, 0.45769, 0.33592, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.24980, -0.39268, -0.49333, -0.43656, -0.37147, -0.29985, -0.15494, -0.24361, -0.37131, -0.49519, -0.54919, -0.56398, -0.61184, -0.83132, -0.99462, -0.88628, -0.82074, -0.92514, -1.11123, -1.29602, -1.54930, -1.72151, -1.74958, -1.90415, -2.01779, -1.99523, -1.87522, -1.88860, -1.92217, -1.93114, -1.86569, -1.73370, -1.55125, -1.58346, -1.71524, -1.72669, -1.79891, -1.81874, -1.74716, -1.83092, -1.91274, -1.93246, -1.94273, -2.04229, -2.19962, -2.43792, -2.59017, -2.58376, -2.58548, -2.66412, -2.58634, -2.28583, -2.06428, -1.94645, -1.74112, -1.58867, -1.40355, -1.26438, -1.15776, -1.09859, -0.97874, -0.80133, -0.70803, -0.52873, -0.17398, 0.12820, 0.41711, 0.68422, 0.75300, 0.75062, 0.84671, 0.80316, 0.61947, 0.40577, 0.19367, 0.14010, 0.12561, 0.01715, 0.00000, 0.00000, 0.00000, 0.00000, -0.42131, -0.26881, -0.19510, -0.19782, -0.10166, -0.15729, -0.24518, -0.22963, -0.06293, 0.10514, 0.30585, 0.45301, 0.40980, 0.28915, 0.18016, 0.01440, -0.22442, -0.31336, -0.47942, -0.61916, -0.56672, -0.59183, -0.64921, -0.55619, -0.44183, -0.38653, -0.36505, -0.37854, -0.39907, -0.22175, -0.06626, -0.13180, -0.24341, -0.14232, -0.00281, -0.02046, -0.00075, -0.03567, -0.09326, -0.06669, -0.10387, -0.14230, -0.12422, -0.01983, 0.06987, 0.04648, 0.03397, 0.07711, 0.19022, 0.47863, 0.67464, 0.70204, 0.79411, 0.93348, 1.02488, 1.20359, 1.21702, 1.10774, 1.04628, 1.04725, 0.95038, 0.82535, 0.67843, 0.45668, 0.24607, 0.14003, 0.04459, -0.09232, -0.02729, 0.09131, 0.20203, 0.31138, 0.32483, 0.33058, 0.35549, 0.55471, 0.66156, 0.67749, 0.67547, 0.69839, 0.64858, 0.64624, 0.62056, 0.57799, 0.66666, 0.65322, 0.46561, 0.37181, 0.29919, 0.25619, 0.15809, 0.02268, -0.12896, -0.01780, 0.25848, 0.38123, 0.39495, 0.51600, 0.68875, 0.70030, 0.64788, 0.60933, 0.55856, 0.64966, 0.78444, 0.77627, 0.64807, 0.71587, 0.90692, 1.09570, 1.19790, 1.21485, 1.16376, 1.29000, 1.43135, 1.43080, 1.30946, 1.11508, 0.92329, 0.98935, 1.05627, 1.00476, 0.95180, 1.01081, 1.02797, 1.10308, 1.25986, 1.34923, 1.37805, 1.46869, 1.59338, 1.44220, 1.23587, 1.13096, 1.07098, 1.19809, 1.29089, 1.32837, 1.23435, 1.22079, 1.13098, 0.85878, +1.00338, 1.04007, 0.99284, 1.01576, 0.96760, 0.79594, 0.65983, 0.69709, 0.84577, 0.93212, 0.82445, 0.74908, 0.91661, 1.06777, 1.07295, 1.08441, 1.11468, 1.05623, 0.98672, 1.07947, 0.98067, 0.61727, 0.29260, 0.02728, -0.17667, -0.40657, -0.75101, -1.08714, -1.14521, -1.21081, -1.39167, -1.62815, -1.78371, -1.96683, -2.18370, -2.24189, -2.26324, -2.29856, -2.31502, -2.20080, -2.05850, -1.99760, -2.04269, -1.99754, -1.80792, -1.71189, -1.83402, -1.90990, -1.81739, -1.82844, -2.06378, -2.16195, -2.24525, -2.34314, -2.33928, -2.31273, -2.27033, -2.13167, -2.12014, -2.27687, -2.29344, -2.25919, -2.32899, -2.34631, -2.33550, -2.41035, -2.60707, -2.69057, -2.77372, -2.98924, -3.36538, -3.66200, -3.79793, -3.88569, -4.02549, -4.19666, -4.27053, -4.26611, -4.30847, -4.27623, -4.12474, -4.01262, -3.98101, -3.69276, -3.39509, -3.27216, -3.12831, -2.92364, -2.67580, -2.29507, -2.04972, -2.09535, -2.04911, -2.04339, -2.18486, -2.25697, -2.31814, -2.36132, -2.49416, -2.45178, -2.36027, -2.30908, -2.33471, -2.24397, -2.10147, -2.00702, -2.10222, -2.32150, -2.44227, -2.56360, -2.90317, -3.28252, -3.45878, -3.45346, -3.52472, -3.38048, -3.14632, -3.03331, -2.92981, -2.84297, -2.79788, -2.62022, -2.55591, -2.68554, -2.81769, -2.92632, -3.11091, -3.15849, -3.10392, -3.00103, -3.08447, -2.98162, -2.66479, -2.26354, -1.94740, -1.70678, -1.57893, -1.43037, -1.30345, -1.21386, -1.06526, -0.87760, -0.78215, -0.65745, -0.40050, -0.12298, -0.08723, 0.05629, 0.26291, 0.36175, 0.43222, 0.40315, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.04223, -0.10209, -0.19214, -0.13832, -0.10606, -0.11226, -0.05043, -0.15589, -0.27647, -0.35918, -0.50928, -0.57876, -0.57578, -0.76104, -0.89297, -0.85930, -0.76759, -0.88066, -1.11881, -1.40073, -1.60489, -1.76829, -1.86642, -1.94915, -2.01141, -2.02871, -2.05134, -2.02442, -1.92627, -1.92430, -1.94681, -1.85012, -1.61891, -1.64408, -1.75514, -1.77328, -1.91906, -2.07195, -2.07889, -2.10080, -2.08016, -2.00656, -2.08134, -2.25665, -2.36184, -2.56747, -2.72996, -2.80271, -2.73968, -2.72730, -2.62830, -2.39379, -2.14642, -1.99428, -1.85694, -1.65457, -1.42284, -1.29873, -1.30038, -1.22418, -0.98693, -0.83060, -0.82289, -0.65563, -0.22277, 0.11732, 0.39115, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.32272, -0.29008, -0.26275, -0.23605, -0.18756, -0.10967, -0.00840, 0.13779, 0.43444, 0.56481, 0.43506, 0.25823, 0.15450, -0.01674, -0.25041, -0.29517, -0.40176, -0.53835, -0.53363, -0.52074, -0.52699, -0.39543, -0.32160, -0.37081, -0.28972, -0.24131, -0.25615, -0.15045, -0.00528, 0.06082, -0.01164, 0.03906, 0.13214, 0.16282, 0.10854, 0.10927, 0.14451, 0.17224, 0.07177, -0.00182, 0.12344, 0.21632, 0.16343, -0.00817, -0.03007, 0.05167, 0.15137, 0.44789, 0.64672, 0.67443, 0.77940, 0.98081, 1.12035, 1.31404, 1.29924, 1.07434, 1.04531, 1.09629, 0.99144, 0.79292, 0.58502, 0.45406, 0.25283, 0.12283, 0.00396, -0.04267, -0.05412, 0.02880, 0.17954, 0.27578, 0.23870, 0.16464, 0.24661, 0.42765, 0.45747, 0.41493, 0.49292, 0.61797, 0.56293, 0.57901, 0.56533, 0.50562, 0.55763, 0.59792, 0.51645, 0.49022, 0.44266, 0.27873, 0.18672, 0.10961, -0.04808, -0.02612, 0.13709, 0.34537, 0.36648, 0.45866, 0.55114, 0.61172, 0.51536, 0.46919, 0.50301, 0.59658, 0.64145, 0.48336, 0.43834, 0.57219, 0.70555, 0.79875, 0.91976, 1.05668, 1.07516, 1.25240, 1.38386, 1.32097, 1.12134, 0.93036, 0.80955, 0.92717, 1.03985, 0.89944, 0.85356, 0.97473, 1.00694, 1.06281, 1.17334, 1.39585, 1.45560, 1.52636, 1.56154, 1.48546, 1.28785, 1.15963, 1.14565, 1.25924, 1.32328, 1.27419, 1.30368, 1.38698, 1.22957, 0.84406, +0.99375, 1.08149, 1.13655, 1.16343, 1.07801, 0.88279, 0.69314, 0.76590, 0.85257, 0.84047, 0.76931, 0.87306, 1.09053, 1.10989, 1.11861, 1.15461, 1.13599, 1.05359, 0.95557, 0.98731, 0.91318, 0.58021, 0.27335, 0.08994, -0.12185, -0.32951, -0.50690, -0.76730, -0.92404, -1.12865, -1.33031, -1.52519, -1.72244, -1.93890, -2.20002, -2.33573, -2.38450, -2.34948, -2.36268, -2.20493, -2.07535, -2.07514, -2.07324, -1.94149, -1.75414, -1.75236, -1.78075, -1.72242, -1.68198, -1.75878, -1.97752, -2.06371, -2.12134, -2.29822, -2.41368, -2.39983, -2.41579, -2.32460, -2.24354, -2.28685, -2.25506, -2.20734, -2.18992, -2.15104, -2.23530, -2.36130, -2.52498, -2.62175, -2.79390, -3.01347, -3.39844, -3.53793, -3.57968, -3.78430, -3.98236, -4.10274, -4.10261, -4.17432, -4.18518, -4.04650, -3.92053, -3.83359, -3.76082, -3.45410, -3.08692, -2.89447, -2.73906, -2.53818, -2.39322, -2.18709, -1.95134, -1.83194, -1.71481, -1.75248, -1.93234, -1.97880, -2.08339, -2.10549, -2.17950, -2.14387, -2.15368, -2.09519, -2.15722, -2.07165, -1.92748, -1.93154, -2.01365, -2.14332, -2.22447, -2.46920, -2.79215, -3.00043, -3.19388, -3.34508, -3.48809, -3.41376, -3.17548, -3.01735, -2.95400, -2.82192, -2.73205, -2.61586, -2.52385, -2.55978, -2.72177, -2.90766, -3.07328, -3.03856, -3.04779, -2.98664, -3.00187, -2.76150, -2.48669, -2.15716, -1.97770, -1.77818, -1.55073, -1.43602, -1.30811, -1.15925, -0.93996, -0.84016, -0.77813, -0.51907, -0.25333, -0.04458, 0.00600, 0.06532, 0.19733, 0.24020, 0.23223, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.24821, 0.21902, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.01584, -0.10616, -0.03586, 0.03830, -0.02526, 0.00233, -0.11641, -0.33695, -0.40714, -0.44319, -0.49210, -0.54517, -0.71567, -0.68636, -0.70489, -0.80373, -1.04499, -1.28020, -1.57399, -1.75169, -1.92619, -2.06515, -2.06491, -2.14418, -2.18805, -2.14400, -1.99787, -1.90068, -1.93464, -1.88129, -1.78846, -1.72866, -1.82070, -1.90779, -1.90143, -2.05048, -2.33121, -2.37918, -2.31584, -2.28486, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.76118, -2.86182, -2.87470, -2.86028, -2.71116, -2.53745, -2.32364, -2.15897, -2.03335, -1.78408, -1.64304, -1.60881, -1.58363, -1.39533, -1.16052, -1.09564, -0.96297, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.42804, -0.39574, -0.23474, -0.08867, -0.02085, 0.06149, 0.22855, 0.42036, 0.41185, 0.40876, 0.38797, 0.19985, -0.10572, -0.36130, -0.37086, -0.36237, -0.47500, -0.51299, -0.44533, -0.45330, -0.36161, -0.25382, -0.25270, -0.19559, -0.19467, -0.17015, -0.06374, -0.00767, 0.06030, 0.06627, 0.09580, 0.06643, 0.05817, -0.06039, 0.01723, 0.10662, 0.06298, 0.01605, 0.08627, 0.25087, 0.21762, 0.17105, 0.07866, -0.01802, -0.04382, -0.00649, 0.22526, 0.44164, 0.52972, 0.67644, 0.92757, 1.00767, 1.09579, 1.17061, 1.12419, 1.12822, 1.11138, 1.01260, 0.86480, 0.58058, 0.41118, 0.26948, 0.20162, 0.08952, 0.06595, -0.06116, -0.02917, 0.04935, 0.04012, 0.07135, 0.13036, 0.21936, 0.21790, 0.27499, 0.44115, 0.56568, 0.59374, 0.47053, 0.43215, 0.45370, 0.41847, 0.41084, 0.49455, 0.45670, 0.39237, 0.40039, 0.34258, 0.26910, 0.17145, 0.05622, 0.09479, 0.07885, 0.15359, 0.14843, 0.26686, 0.28737, 0.33606, 0.23728, 0.27191, 0.38599, 0.39135, 0.39850, 0.29238, 0.30637, 0.32703, 0.42109, 0.63909, 0.75631, 0.85344, 0.91794, 1.03181, 1.09095, 0.98285, 0.75367, 0.65330, 0.59661, 0.64569, 0.80528, 0.85298, 0.89987, 1.02849, 1.12190, 1.31067, 1.41361, 1.55302, 1.53453, 1.56541, 1.45273, 1.40614, 1.28450, 1.23097, 1.24750, 1.21459, 1.26215, 1.33501, 1.48975, 1.45821, 1.21110, 0.96160, +0.90940, 1.04909, 1.17356, 1.24313, 1.15774, 1.02325, 0.85303, 0.77253, 0.81697, 0.88202, 0.81976, 0.88815, 1.04563, 1.08995, 1.13750, 1.12948, 1.13984, 1.14174, 1.06421, 0.96636, 0.82888, 0.59766, 0.31112, 0.08913, -0.03921, -0.22177, -0.39817, -0.61036, -0.81200, -1.12063, -1.36730, -1.50014, -1.66495, -1.84307, -2.10598, -2.29101, -2.38088, -2.33193, -2.34064, -2.36543, -2.30164, -2.18459, -2.13884, -2.08793, -1.98744, -1.93486, -1.84018, -1.78031, -1.77834, -1.80092, -1.93945, -2.06870, -2.15320, -2.29057, -2.45891, -2.54724, -2.54273, -2.46709, -2.46020, -2.44579, -2.38026, -2.33284, -2.27242, -2.16875, -2.20352, -2.27572, -2.39924, -2.51767, -2.73099, -2.95570, -3.24078, -3.43580, -3.53134, -3.66649, -3.86328, -4.01197, -3.97476, -3.94807, -3.84427, -3.73024, -3.64177, -3.46801, -3.32026, -3.08636, -2.77681, -2.50538, -2.31966, -2.24496, -2.16589, -2.05443, -1.93636, -1.69811, -1.46832, -1.47818, -1.65858, -1.68107, -1.75443, -1.75031, -1.82692, -1.86050, -1.93496, -1.91369, -1.90456, -1.95806, -1.95763, -1.91188, -1.95202, -2.12141, -2.26161, -2.47768, -2.66701, -2.81299, -3.00304, -3.13629, -3.27597, -3.31677, -3.19087, -3.00025, -2.91259, -2.85058, -2.77812, -2.66854, -2.67613, -2.67706, -2.75609, -2.92309, -3.07623, -2.98417, -2.94309, -2.83204, -2.75929, -2.50127, -2.30040, -2.12077, -1.95423, -1.82402, -1.61857, -1.38115, -1.17864, -1.08030, -0.91891, -0.81180, -0.68139, -0.42353, -0.21449, 0.02544, 0.13999, 0.08978, 0.05237, 0.02587, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.25315, 0.16002, 0.16333, 0.08895, 0.08664, 0.14254, 0.14083, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.02080, -0.05692, -0.03828, -0.08062, -0.10045, -0.22261, -0.37684, -0.50328, -0.52887, -0.48170, -0.50857, -0.66639, -0.59747, -0.66326, -0.87183, -1.16071, -1.38228, -1.62104, -1.82848, -1.94255, -2.10240, -2.20570, -2.22876, -2.19310, -2.16642, -2.06243, -1.96556, -1.90125, -1.82365, -1.82871, -1.85250, -1.89037, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.04061, -2.98074, -2.82581, -2.70545, -2.57950, -2.37072, -2.19853, -2.04093, -1.90594, -1.78388, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.34545, -0.14622, 0.05554, 0.09582, 0.12250, 0.17317, 0.23964, 0.42003, 0.44229, 0.25151, -0.00679, -0.21173, -0.28811, -0.36238, -0.47527, -0.54097, -0.51346, -0.43790, -0.37385, -0.37337, -0.35650, -0.30157, -0.33733, -0.32665, -0.23252, -0.19170, -0.07492, 0.00890, 0.05002, -0.05454, -0.10676, -0.18655, -0.20948, -0.13916, -0.06482, -0.08221, -0.08413, 0.02265, 0.05611, 0.14943, 0.07898, -0.06583, -0.07702, -0.01968, 0.10728, 0.22788, 0.36791, 0.52164, 0.67800, 0.76106, 0.84797, 0.95042, 1.07795, 1.17933, 1.14864, 1.03478, 0.91612, 0.62632, 0.44475, 0.33725, 0.28238, 0.17990, 0.12312, -0.00603, -0.15058, -0.21616, -0.10240, 0.04570, 0.09957, 0.14803, 0.18026, 0.37588, 0.58647, 0.63388, 0.60337, 0.45887, 0.31299, 0.24775, 0.22848, 0.20403, 0.20690, 0.20290, 0.18067, 0.12383, 0.11157, 0.12415, 0.07881, 0.03419, 0.12832, 0.06215, 0.07049, 0.05000, 0.12849, 0.09893, 0.07572, 0.04101, 0.00221, 0.04996, 0.16146, 0.25457, 0.13948, 0.10351, 0.13211, 0.32644, 0.56851, 0.62756, 0.75186, 0.85653, 0.84173, 0.72100, 0.58291, 0.44501, 0.37181, 0.37202, 0.47812, 0.58669, 0.73563, 0.92344, 1.09543, 1.22118, 1.47545, 1.60602, 1.69001, 1.60287, 1.53193, 1.33358, 1.28556, 1.34844, 1.32741, 1.26485, 1.28015, 1.40378, 1.45606, 1.50600, 1.38870, 1.20549, 1.01760, +0.78194, 0.91774, 1.10043, 1.21460, 1.18539, 1.14317, 1.06111, 0.91938, 0.86267, 0.93081, 0.91153, 0.94185, 1.01350, 1.10070, 1.15577, 1.08308, 1.09085, 1.13404, 1.15488, 1.04451, 0.88401, 0.74131, 0.47672, 0.19789, 0.06082, -0.16016, -0.38646, -0.56721, -0.76661, -1.11659, -1.37656, -1.51445, -1.70548, -1.87504, -2.10081, -2.29690, -2.40518, -2.35110, -2.33546, -2.42945, -2.47744, -2.36889, -2.27395, -2.24103, -2.20671, -2.11041, -1.97219, -1.98678, -2.00720, -1.97449, -1.98864, -2.08336, -2.16311, -2.18927, -2.32383, -2.43974, -2.44794, -2.45081, -2.53842, -2.54144, -2.51582, -2.52106, -2.44725, -2.32339, -2.29911, -2.31056, -2.38018, -2.47965, -2.65640, -2.80545, -2.96168, -3.14562, -3.34556, -3.48637, -3.59566, -3.66678, -3.61470, -3.53261, -3.37458, -3.35542, -3.30344, -3.08977, -2.88745, -2.68556, -2.46832, -2.15973, -1.95865, -1.92140, -1.87989, -1.85083, -1.80749, -1.54670, -1.28086, -1.29031, -1.44636, -1.47738, -1.54559, -1.56529, -1.65349, -1.71000, -1.79330, -1.75284, -1.66766, -1.72279, -1.85446, -1.87797, -1.87454, -2.00385, -2.16965, -2.35339, -2.46384, -2.67004, -2.84043, -2.90407, -2.98127, -3.00657, -2.98040, -2.77566, -2.65975, -2.63570, -2.65620, -2.65715, -2.76929, -2.78172, -2.78232, -2.93086, -3.07623, -2.96328, -2.85205, -2.69297, -2.56060, -2.33918, -2.21409, -2.07551, -1.85570, -1.65789, -1.51229, -1.32489, -1.06926, -0.92872, -0.81236, -0.73479, -0.61382, -0.51835, -0.39897, -0.15786, 0.02412, 0.04537, -0.06272, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.01971, -0.07913, -0.07646, -0.15995, -0.15637, -0.01468, 0.06947, 0.01865, 0.04124, 0.18963, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.04883, -0.10098, -0.12132, -0.12653, -0.23710, -0.39696, -0.59078, -0.62759, -0.48426, -0.48424, -0.64669, -0.62393, -0.73417, -0.98461, -1.24802, -1.42968, -1.64477, -1.84502, -1.88148, -1.93788, 0.00000, -2.19636, -2.17901, -2.15522, -2.09302, -2.03736, -1.90989, -1.86783, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.13168, -2.96103, -2.87428, -2.78316, -2.53398, -2.25546, -2.08476, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.00457, -0.00506, -0.00993, 0.14628, 0.39118, 0.36081, 0.19266, 0.02567, -0.05873, -0.15340, -0.34927, -0.47352, -0.51556, -0.48911, -0.40532, -0.41697, -0.51585, -0.50669, -0.46200, -0.54694, -0.57165, -0.51602, -0.49434, -0.36404, -0.22590, -0.13406, -0.21106, -0.22944, -0.21839, -0.25349, -0.27485, -0.20546, -0.20590, -0.26626, -0.22574, -0.13097, 0.05576, -0.05721, -0.23828, -0.23736, -0.08595, 0.06585, 0.10731, 0.26091, 0.39338, 0.51223, 0.60936, 0.69447, 0.81126, 1.02089, 1.19378, 1.16978, 1.06264, 0.93096, 0.61776, 0.37215, 0.24729, 0.17912, 0.07605, 0.05563, 0.02042, -0.10959, -0.25443, -0.12945, 0.09391, 0.17250, 0.20264, 0.29072, 0.55784, 0.65615, 0.56598, 0.45881, 0.34574, 0.20935, 0.05004, 0.04138, 0.02796, 0.01843, 0.01952, -0.03140, -0.14981, -0.14835, -0.05725, -0.06197, -0.03237, 0.13444, 0.09927, 0.07143, 0.04552, 0.07461, -0.00168, -0.03348, -0.02921, -0.06569, -0.09471, -0.00374, 0.18421, 0.14745, 0.07150, 0.09375, 0.36410, 0.52924, 0.51871, 0.62046, 0.74355, 0.74603, 0.52437, 0.40881, 0.34856, 0.31473, 0.33961, 0.44595, 0.51529, 0.69635, 0.96589, 1.11080, 1.20686, 1.43292, 1.53757, 1.56659, 1.46413, 1.35409, 1.15415, 1.16939, 1.36515, 1.45513, 1.35700, 1.32775, 1.49093, 1.55324, 1.48319, 1.29527, 1.19156, 0.96359, +0.80709, 0.85506, 1.06619, 1.29040, 1.35463, 1.24068, 1.10001, 1.01060, 0.93303, 0.90316, 0.91529, 0.99943, 0.97290, 0.95187, 1.05428, 1.05847, 1.07448, 1.07691, 1.08804, 1.07254, 1.00425, 0.86658, 0.58522, 0.21784, 0.01713, -0.19101, -0.41843, -0.60768, -0.78563, -1.06214, -1.31561, -1.44070, -1.67621, -1.94098, -2.15566, -2.26106, -2.28551, -2.36997, -2.51442, -2.58491, -2.61119, -2.56895, -2.47302, -2.35390, -2.35127, -2.35293, -2.16752, -2.08129, -2.09539, -2.12503, -2.16688, -2.16786, -2.12747, -2.11727, -2.26317, -2.41914, -2.49503, -2.51086, -2.59795, -2.62866, -2.66282, -2.63941, -2.56061, -2.40812, -2.34662, -2.38803, -2.39334, -2.35777, -2.39291, -2.56280, -2.76587, -2.93165, -3.14650, -3.33929, -3.39505, -3.27436, -3.16688, -3.17267, -3.01568, -2.90521, -2.82228, -2.62086, -2.49040, -2.32966, -2.13648, -1.90697, -1.78819, -1.77818, -1.76421, -1.70116, -1.63390, -1.38439, -1.15961, -1.10688, -1.24376, -1.26230, -1.30611, -1.45834, -1.58807, -1.55964, -1.50210, -1.47272, -1.49498, -1.56016, -1.69350, -1.79343, -1.78647, -1.75557, -1.88431, -2.19640, -2.33510, -2.42669, -2.50454, -2.52277, -2.64865, -2.67929, -2.66601, -2.51833, -2.44040, -2.44717, -2.57069, -2.61301, -2.74341, -2.76794, -2.78877, -2.84458, -2.94379, -2.79924, -2.62607, -2.53589, -2.41463, -2.22847, -2.10600, -2.01609, -1.90370, -1.69921, -1.51600, -1.39405, -1.17781, -0.90199, -0.71603, -0.73318, -0.71868, -0.64536, -0.55560, -0.34088, -0.20280, -0.11185, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.03642, -0.22679, -0.31126, -0.28398, -0.27231, -0.22714, -0.15268, -0.07072, -0.10321, -0.18090, -0.10194, 0.12244, 0.40566, 0.46360, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.08184, -0.17136, -0.21489, -0.37070, -0.51020, -0.67212, -0.66718, -0.53930, -0.48688, -0.61467, -0.66498, -0.78331, -1.08631, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.87843, -2.78541, -2.65931, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.13305, -0.03017, 0.26272, 0.33457, 0.23238, 0.08815, 0.00276, -0.05162, -0.28756, -0.51373, -0.57172, -0.54268, -0.47024, -0.48556, -0.61040, -0.64811, -0.61831, -0.64625, -0.69633, -0.67338, -0.70786, -0.66954, -0.49820, -0.24855, -0.18266, -0.28336, -0.39011, -0.41709, -0.42599, -0.42131, -0.43024, -0.40256, -0.36168, -0.35375, -0.14829, -0.15425, -0.30019, -0.31769, -0.19947, -0.00085, 0.07835, 0.14771, 0.15131, 0.19674, 0.28387, 0.44231, 0.62175, 0.86087, 1.04817, 1.12572, 1.06834, 0.99312, 0.70965, 0.31296, 0.10992, 0.08338, 0.05485, -0.01570, -0.09843, -0.14482, -0.20131, -0.11744, 0.08910, 0.29252, 0.36389, 0.36352, 0.60419, 0.72907, 0.53443, 0.32013, 0.15042, 0.06578, -0.05340, -0.12597, -0.21133, -0.24862, -0.25841, -0.25597, -0.35517, -0.37596, -0.31142, -0.19747, -0.05828, 0.23802, 0.29262, 0.15093, 0.06174, 0.08663, 0.08107, 0.02091, -0.09141, -0.13455, -0.10957, -0.06432, 0.10322, 0.22277, 0.21484, 0.14372, 0.36056, 0.57729, 0.56702, 0.60709, 0.60277, 0.59244, 0.42227, 0.30392, 0.21407, 0.17577, 0.17666, 0.32821, 0.44981, 0.69325, 0.96053, 1.11205, 1.15441, 1.33272, 1.41421, 1.31435, 1.19227, 1.13558, 1.07485, 1.13179, 1.24756, 1.35645, 1.34250, 1.28424, 1.39589, 1.53052, 1.44909, 1.15914, 1.04682, 0.95067, +0.96930, 1.07227, 1.20556, 1.39944, 1.46291, 1.26961, 1.12750, 1.09655, 1.01788, 0.93312, 0.83540, 0.84366, 0.85602, 0.85667, 0.93007, 0.90608, 0.92261, 0.91447, 0.88017, 0.91401, 0.95195, 0.85656, 0.67368, 0.33189, 0.07300, -0.16039, -0.42910, -0.60822, -0.75231, -0.97579, -1.24464, -1.41512, -1.60378, -1.83105, -2.12985, -2.26235, -2.20580, -2.37600, -2.59573, -2.59590, -2.52094, -2.43580, -2.48211, -2.49488, -2.46624, -2.44496, -2.26360, -2.15848, -2.14577, -2.22909, -2.34052, -2.29128, -2.18031, -2.20697, -2.35903, -2.50468, -2.65707, -2.68266, -2.73512, -2.73057, -2.77431, -2.75525, -2.67550, -2.53839, -2.44093, -2.35056, -2.28626, -2.22724, -2.18459, -2.37437, -2.58292, -2.71218, -2.88975, -3.01418, -3.09585, -3.04010, -2.86648, -2.80483, -2.70465, -2.63071, -2.49124, -2.23840, -2.13701, -2.02129, -1.86818, -1.74164, -1.71112, -1.64757, -1.60022, -1.47320, -1.40696, -1.20795, -1.04064, -1.01820, -1.17762, -1.20604, -1.18555, -1.25495, -1.38312, -1.35319, -1.14058, -1.07823, -1.19823, -1.28368, -1.41190, -1.47372, -1.48183, -1.51007, -1.58815, -1.87764, -2.06761, -2.16557, -2.20205, -2.21109, -2.42227, -2.52216, -2.54408, -2.43462, -2.34900, -2.26957, -2.40579, -2.45040, -2.58281, -2.64254, -2.74399, -2.78397, -2.81154, -2.66594, -2.50126, -2.33728, -2.22558, -2.20153, -2.09366, -2.01227, -1.97298, -1.78474, -1.59390, -1.43126, -1.28652, -1.13312, -0.87305, -0.75976, -0.75245, -0.76404, -0.71015, -0.49514, -0.42600, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.10033, -0.14557, -0.23585, -0.33268, -0.29527, -0.20706, -0.15613, -0.04635, -0.06935, -0.16577, -0.14335, -0.02098, 0.31435, 0.48296, 0.49733, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.08449, 0.14013, 0.22173, 0.18710, 0.06723, -0.05922, -0.10471, -0.32572, -0.57443, -0.57714, -0.47282, -0.40467, -0.45451, -0.62295, -0.71811, -0.71994, -0.71753, -0.76695, -0.78757, -0.81147, -0.69913, -0.55445, -0.33121, -0.20648, -0.38448, -0.61067, -0.64782, -0.59403, -0.53846, -0.60061, -0.62641, -0.49603, -0.43922, -0.34453, -0.40622, -0.47177, -0.42954, -0.40313, -0.26187, -0.13372, -0.10501, -0.17266, -0.12705, -0.03202, 0.17064, 0.35480, 0.59450, 0.76931, 0.86568, 0.87172, 0.89095, 0.75758, 0.48335, 0.21116, 0.08656, 0.07537, -0.04623, -0.12216, -0.03989, 0.01624, 0.10365, 0.19028, 0.28136, 0.39644, 0.43306, 0.58780, 0.61130, 0.37389, 0.16970, -0.03008, -0.08068, -0.15217, -0.29022, -0.43601, -0.45679, -0.45586, -0.38189, -0.44913, -0.50468, -0.49892, -0.33706, -0.11036, 0.23929, 0.35791, 0.29605, 0.13478, 0.03278, 0.10504, 0.06885, -0.07361, -0.06493, 0.03172, 0.12236, 0.16966, 0.16054, 0.25525, 0.29575, 0.40006, 0.47969, 0.48069, 0.53579, 0.42318, 0.36840, 0.27199, 0.16087, 0.02221, 0.02422, 0.00447, 0.16882, 0.33589, 0.65186, 0.94268, 1.07873, 1.06165, 1.16402, 1.19829, 1.16300, 1.09980, 1.02080, 1.05771, 1.09763, 1.11486, 1.23811, 1.27733, 1.27435, 1.33771, 1.32791, 1.27551, 1.13757, 1.07140, 1.00158, +1.03844, 1.17914, 1.30509, 1.36812, 1.30399, 1.15496, 1.09372, 1.11159, 0.93987, 0.75651, 0.68031, 0.72569, 0.79341, 0.87938, 0.90759, 0.77758, 0.77675, 0.78353, 0.77073, 0.77300, 0.79524, 0.79507, 0.76275, 0.56022, 0.27135, 0.02400, -0.22307, -0.40896, -0.58188, -0.80003, -1.07799, -1.39512, -1.57794, -1.77986, -2.09251, -2.30627, -2.29851, -2.35804, -2.46305, -2.36605, -2.28817, -2.28273, -2.38595, -2.45731, -2.48254, -2.45871, -2.31140, -2.28780, -2.23449, -2.27774, -2.35426, -2.31180, -2.31120, -2.41785, -2.56489, -2.65377, -2.83268, -2.84825, -2.80951, -2.79189, -2.86979, -2.89905, -2.76179, -2.71918, -2.64257, -2.46971, -2.30105, -2.24723, -2.27650, -2.36664, -2.45895, -2.45654, -2.55565, -2.69852, -2.73645, -2.67465, -2.51797, -2.40041, -2.32911, -2.40793, -2.26175, -1.97014, -1.80824, -1.67506, -1.61224, -1.52609, -1.50389, -1.36937, -1.28552, -1.16502, -1.07851, -0.95798, -0.84730, -0.92429, -1.05371, -1.16940, -1.13599, -1.10323, -1.12865, -1.07240, -0.89052, -0.75150, -0.85302, -0.90751, -1.05481, -1.22566, -1.22053, -1.21002, -1.26009, -1.47954, -1.63703, -1.85214, -1.96129, -2.06152, -2.32219, -2.45183, -2.54620, -2.42023, -2.26719, -2.09644, -2.20099, -2.28988, -2.34970, -2.44052, -2.62091, -2.75205, -2.67333, -2.60228, -2.52120, -2.34606, -2.22913, -2.23209, -2.19631, -2.06148, -1.96168, -1.74592, -1.56875, -1.49708, -1.39688, -1.26864, -1.00502, -0.82041, -0.71170, -0.79822, -0.76302, -0.54060, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.02641, -0.08065, -0.05983, -0.15927, -0.29169, -0.37433, -0.29030, -0.15766, 0.03688, 0.06450, -0.09754, -0.09221, 0.03688, 0.29805, 0.40372, 0.43587, 0.30387, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.75994, -0.85924, -0.93777, -0.96256, -1.01746, -1.05540, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.07240, 0.08358, 0.07846, -0.02198, -0.12216, -0.17202, -0.38622, -0.52992, -0.44237, -0.25902, -0.24547, -0.34609, -0.49704, -0.67102, -0.77414, -0.80154, -0.78680, -0.85650, -0.83612, -0.65873, -0.51750, -0.46063, -0.49938, -0.63159, -0.83234, -0.82538, -0.76620, -0.76975, -0.79897, -0.80010, -0.66197, -0.56395, -0.55785, -0.78114, -0.81283, -0.72159, -0.72001, -0.64532, -0.55974, -0.47224, -0.44551, -0.30237, -0.19799, -0.01291, 0.20857, 0.41930, 0.55593, 0.58715, 0.68515, 0.70805, 0.68614, 0.57757, 0.36469, 0.17333, 0.04600, -0.02064, 0.00601, 0.20415, 0.26989, 0.20176, 0.23865, 0.32267, 0.39708, 0.42569, 0.52861, 0.38833, 0.17021, 0.03278, -0.13401, -0.17216, -0.31439, -0.47306, -0.59079, -0.57942, -0.57468, -0.51028, -0.47936, -0.51066, -0.50398, -0.38244, -0.07270, 0.15160, 0.21368, 0.20713, 0.05598, -0.07325, -0.05638, -0.01114, -0.05986, 0.03354, 0.16162, 0.16077, 0.14065, 0.11031, 0.22990, 0.31889, 0.37041, 0.24322, 0.23390, 0.34863, 0.29153, 0.28479, 0.17533, 0.07624, -0.03622, 0.02608, 0.02620, 0.10656, 0.32938, 0.67311, 0.97769, 1.05798, 1.09419, 1.09882, 1.05763, 1.06675, 1.07098, 1.01887, 0.95955, 0.96085, 1.01298, 1.20255, 1.26104, 1.16680, 1.21300, 1.24072, 1.26740, 1.25403, 1.27918, 1.12324, +1.16121, 1.24214, 1.42182, 1.44049, 1.26353, 1.11839, 0.96741, 0.92342, 0.80394, 0.63368, 0.55034, 0.62626, 0.68723, 0.77761, 0.90717, 0.82933, 0.80150, 0.79399, 0.80272, 0.77508, 0.76990, 0.83218, 0.76770, 0.55978, 0.29556, 0.09382, -0.12675, -0.36433, -0.51170, -0.63631, -0.88110, -1.24134, -1.46218, -1.70491, -1.94723, -2.13649, -2.19432, -2.19891, -2.32056, -2.29599, -2.17720, -2.18309, -2.34479, -2.45996, -2.56890, -2.62204, -2.41509, -2.32147, -2.25960, -2.27664, -2.31505, -2.30235, -2.39622, -2.54126, -2.76016, -2.91569, -3.05872, -3.01187, -2.92445, -2.96934, -3.05650, -3.00741, -2.79968, -2.76148, -2.70508, -2.56079, -2.30098, -2.15924, -2.22156, -2.25113, -2.32474, -2.34657, -2.31148, -2.37057, -2.38883, -2.31992, -2.18983, -2.10932, -1.97098, -1.98600, -1.87481, -1.63076, -1.46449, -1.34146, -1.34136, -1.25565, -1.27393, -1.24453, -1.15059, -1.01564, -0.90641, -0.86209, -0.74633, -0.73459, -0.79408, -0.91578, -0.89781, -0.88933, -0.83394, -0.68537, -0.56784, -0.44187, -0.56706, -0.73893, -0.85666, -1.00575, -1.01961, -1.01760, -1.06050, -1.28297, -1.35301, -1.46897, -1.64176, -1.85473, -2.14887, -2.29275, -2.42112, -2.26748, -2.11886, -2.07513, -2.18914, -2.27488, -2.26589, -2.39484, -2.57959, -2.63136, -2.47077, -2.39931, -2.36307, -2.28726, -2.18952, -2.10381, -2.11076, -1.99344, -1.88139, -1.79318, -1.60005, -1.47783, -1.39893, -1.31739, -1.09093, -0.97621, -0.80139, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.19292, 0.09893, 0.04119, -0.00260, -0.11119, -0.14775, -0.29499, -0.27810, -0.13569, -0.06259, -0.00467, -0.06489, -0.04693, 0.05020, 0.23864, 0.20816, 0.25222, 0.24348, 0.13894, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.70527, -0.76973, -0.83967, -0.83891, -0.83998, -0.95263, -1.06967, -1.26045, -1.32296, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.09004, 0.08793, -0.01673, -0.08732, -0.13878, -0.34929, -0.42162, -0.38732, -0.28353, -0.30295, -0.39591, -0.53324, -0.79937, -0.92871, -0.87729, -0.78801, -0.81897, -0.77369, -0.63369, -0.46524, -0.45783, -0.63968, -0.77169, -1.01518, -1.09144, -0.97959, -0.95966, -1.01371, -1.04674, -0.96113, -0.91060, -0.84125, -1.00233, -1.06314, -1.00807, -1.00006, -0.94092, -0.89239, -0.74733, -0.69186, -0.59578, -0.47856, -0.26999, -0.00939, 0.14265, 0.29659, 0.42709, 0.61799, 0.68360, 0.70022, 0.60659, 0.47931, 0.35126, 0.14943, 0.09419, 0.11360, 0.20619, 0.29538, 0.23381, 0.24824, 0.31338, 0.33307, 0.26888, 0.39212, 0.31586, 0.08580, -0.07827, -0.24003, -0.29713, -0.50514, -0.64671, -0.76302, -0.86362, -0.85928, -0.77986, -0.67963, -0.70644, -0.64022, -0.40368, -0.01298, 0.17738, 0.19730, 0.14161, 0.03595, 0.01038, -0.02646, 0.01290, -0.04222, -0.08857, 0.06431, 0.11379, 0.08516, 0.03548, 0.12407, 0.13014, 0.20674, 0.16855, 0.14875, 0.25492, 0.26323, 0.30551, 0.17704, 0.11278, 0.03234, -0.00126, 0.01834, 0.08173, 0.33474, 0.62107, 0.89956, 1.05070, 1.16065, 1.15932, 1.09076, 1.04481, 1.06742, 1.11032, 0.97656, 0.92632, 0.99969, 1.07417, 1.14724, 1.11167, 1.16302, 1.20276, 1.26834, 1.22964, 1.31541, 1.28270, +1.23421, 1.31410, 1.41691, 1.36609, 1.22529, 1.04957, 0.87830, 0.81952, 0.73879, 0.64733, 0.54969, 0.53151, 0.60332, 0.75617, 0.91189, 0.87637, 0.79386, 0.82114, 0.83998, 0.76462, 0.75968, 0.84678, 0.72523, 0.52414, 0.39900, 0.18049, -0.09424, -0.32878, -0.46056, -0.59835, -0.88434, -1.22355, -1.44267, -1.61623, -1.83150, -2.04610, -2.05859, -2.07368, -2.17523, -2.14802, -2.05195, -2.05609, -2.30471, -2.56343, -2.69184, -2.64356, -2.41239, -2.30161, -2.31037, -2.31016, -2.32489, -2.39335, -2.51855, -2.67813, -2.91715, -3.09788, -3.14747, -3.14218, -3.10720, -3.11765, -3.18250, -3.14052, -2.97051, -2.89188, -2.81550, -2.60317, -2.31272, -2.17615, -2.12206, -2.09011, -2.13695, -2.11549, -2.05595, -2.02090, -2.02705, -2.03431, -1.90341, -1.70257, -1.53278, -1.53930, -1.54921, -1.40141, -1.24312, -1.17839, -1.13144, -1.01446, -1.05588, -1.13328, -0.97343, -0.84683, -0.81936, -0.76719, -0.61025, -0.53695, -0.60588, -0.70354, -0.71430, -0.66749, -0.54198, -0.41816, -0.25780, -0.16062, -0.35859, -0.53754, -0.66533, -0.72868, -0.75198, -0.88049, -0.98009, -1.06229, -1.08314, -1.15719, -1.42055, -1.74006, -1.97926, -2.18452, -2.31106, -2.17482, -2.04687, -2.12140, -2.19114, -2.26142, -2.30120, -2.39923, -2.51202, -2.49413, -2.36756, -2.26966, -2.24764, -2.18360, -2.09327, -2.08922, -2.07674, -1.93756, -1.85274, -1.72895, -1.51925, -1.30614, -1.21527, -1.28045, -1.20502, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.18260, 0.11600, 0.09471, 0.06748, 0.02330, -0.05966, -0.13990, -0.24603, -0.17728, -0.09136, -0.04741, -0.01265, 0.02175, 0.07672, 0.07463, 0.10556, 0.10666, 0.20281, 0.25472, 0.11114, 0.03067, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.69805, -0.73062, -0.76519, -0.80213, -0.81896, -0.83718, -0.93205, -1.07932, -1.26445, -1.40815, -1.47926, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.04799, -0.02358, -0.09798, -0.20382, -0.33988, -0.32615, -0.34426, -0.33888, -0.34595, -0.52556, -0.73423, -0.96679, -1.05344, -0.99628, -0.92515, -0.87646, -0.78584, -0.60403, -0.48052, -0.58783, -0.74445, -0.86983, -1.12879, -1.24409, -1.16923, -1.09036, -1.17392, -1.35030, -1.32351, -1.20525, -1.12726, -1.24253, -1.37228, -1.35398, -1.31497, -1.29306, -1.18168, -0.96891, -0.90703, -0.87832, -0.68105, -0.48158, -0.26114, -0.07116, 0.12820, 0.29112, 0.43697, 0.54519, 0.57964, 0.57192, 0.53295, 0.39947, 0.27734, 0.22968, 0.20848, 0.28881, 0.33087, 0.29963, 0.28711, 0.23653, 0.20407, 0.19978, 0.26973, 0.18121, -0.09312, -0.28293, -0.40414, -0.56060, -0.77780, -0.89376, -0.98816, -1.13879, -1.03103, -0.93927, -0.90720, -0.88676, -0.73995, -0.44399, -0.09904, 0.08911, 0.11128, 0.11704, 0.05449, -0.04859, -0.06423, -0.00809, -0.11397, -0.19166, -0.09028, 0.01608, 0.00173, -0.12190, -0.09848, -0.00487, 0.09229, 0.11357, 0.07305, 0.11603, 0.18498, 0.16097, 0.08412, 0.10985, 0.12421, 0.05172, 0.16069, 0.24514, 0.36395, 0.57307, 0.80644, 0.97391, 1.06270, 1.09425, 1.04334, 1.02075, 1.08748, 1.09506, 0.99470, 0.97012, 1.00399, 1.08714, 1.14670, 1.15754, 1.18468, 1.12229, 1.14681, 1.25329, 1.40206, 1.42161, +1.32658, 1.38096, 1.43224, 1.32530, 1.17537, 0.96769, 0.83041, 0.79029, 0.67895, 0.62976, 0.71364, 0.71075, 0.61440, 0.69899, 0.78278, 0.69755, 0.64325, 0.77691, 0.88770, 0.85592, 0.75725, 0.75496, 0.64185, 0.52529, 0.50735, 0.26752, -0.01639, -0.23170, -0.40306, -0.59319, -0.91307, -1.23556, -1.46890, -1.58915, -1.70814, -1.91525, -1.96910, -2.09104, -2.17121, -2.10876, -2.09136, -2.14479, -2.30676, -2.49940, -2.67286, -2.56100, -2.33988, -2.31712, -2.38734, -2.36701, -2.36775, -2.46980, -2.66501, -2.84867, -2.93730, -2.96672, -2.98325, -3.11133, -3.09942, -2.99038, -3.00114, -2.99944, -2.90875, -2.86743, -2.80471, -2.58836, -2.26879, -2.11521, -1.99993, -1.95202, -1.94078, -1.89039, -1.93001, -1.92770, -1.83935, -1.72854, -1.63831, -1.42554, -1.22128, -1.26661, -1.36394, -1.25216, -1.13429, -1.07176, -0.98728, -0.90857, -0.89716, -0.93655, -0.74850, -0.67203, -0.66470, -0.51617, -0.32311, -0.21169, -0.27787, -0.43094, -0.53445, -0.56646, -0.38867, -0.23725, -0.06464, -0.03480, -0.26418, -0.40414, -0.54330, -0.58700, -0.55692, -0.61003, -0.84060, -0.98642, -1.02154, -1.15822, -1.44305, -1.66126, -1.75289, -1.90998, -2.09823, -2.16312, -2.04369, -2.04082, -2.03136, -2.12675, -2.19970, -2.20429, -2.23010, -2.18390, -2.10572, -2.06213, -2.08503, -2.08720, -1.99874, -2.06076, -2.10710, -2.01889, -1.95344, -1.74971, -1.50637, -1.28261, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.15447, 0.05336, 0.01520, 0.02902, 0.03932, -0.01956, -0.05643, -0.11108, -0.14907, -0.05405, -0.02789, -0.00036, -0.04225, -0.07868, -0.00282, 0.14414, 0.11320, 0.08528, 0.24051, 0.25542, 0.00193, -0.17561, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.96971, -2.03854, -1.98192, -2.02544, -2.13212, -2.17466, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.68090, -0.65779, -0.63025, -0.50945, -0.54444, -0.62392, -0.66807, -0.72455, -0.81275, -0.89617, -0.99990, -1.17791, -1.32142, -1.45872, -1.57787, -1.54558, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.00511, -0.07589, -0.23314, -0.40025, -0.38149, -0.34847, -0.32074, -0.33901, -0.62337, -0.86033, -0.96549, -0.98337, -0.95449, -0.94909, -0.93860, -0.89407, -0.74590, -0.64194, -0.76942, -0.86538, -0.97703, -1.20431, -1.35943, -1.40026, -1.34230, -1.30280, -1.38325, -1.47484, -1.42481, -1.40584, -1.55494, -1.68122, -1.60388, -1.51806, -1.46628, -1.32070, -1.13907, -1.06069, -1.01339, -0.78291, -0.66253, -0.47338, -0.18962, 0.05072, 0.23951, 0.32498, 0.36779, 0.33408, 0.30187, 0.37959, 0.33639, 0.29376, 0.19599, 0.13689, 0.24079, 0.22340, 0.14632, 0.18687, 0.25335, 0.17648, 0.10758, 0.05649, -0.18334, -0.48306, -0.57652, -0.63592, -0.80429, -1.03126, -1.21285, -1.23025, -1.21648, -0.98298, -0.93583, -0.98269, -0.92450, -0.76063, -0.48120, -0.20015, -0.03712, 0.02955, 0.07230, 0.05635, -0.11760, -0.17101, -0.15981, -0.26696, -0.30007, -0.27504, -0.24222, -0.21190, -0.14729, -0.16012, -0.10276, -0.01653, -0.03274, -0.05819, 0.01381, 0.06005, -0.02568, -0.07471, -0.08145, 0.05890, 0.15938, 0.39901, 0.50635, 0.51067, 0.65567, 0.77525, 0.84958, 0.92132, 0.96337, 0.94240, 0.88496, 0.98858, 1.04990, 1.02746, 1.00760, 1.01019, 1.14704, 1.20920, 1.13067, 1.08169, 1.09323, 1.07451, 1.18893, 1.36928, 1.36079, +1.55587, 1.55738, 1.53472, 1.42454, 1.19689, 0.93133, 0.80805, 0.76659, 0.72550, 0.72739, 0.86150, 0.90500, 0.75333, 0.69067, 0.66282, 0.55531, 0.49881, 0.63393, 0.75482, 0.80434, 0.79265, 0.71326, 0.56761, 0.48956, 0.45948, 0.24728, 0.00489, -0.23958, -0.48639, -0.68817, -0.98729, -1.23197, -1.38757, -1.48551, -1.57461, -1.72513, -1.84507, -2.10919, -2.22888, -2.19992, -2.14946, -2.15071, -2.28139, -2.40935, -2.56616, -2.53430, -2.40516, -2.36429, -2.42977, -2.43767, -2.48963, -2.59953, -2.72319, -2.89238, -2.91634, -2.81604, -2.83481, -2.96471, -2.89614, -2.72265, -2.72859, -2.73582, -2.68784, -2.65351, -2.58269, -2.42130, -2.16888, -2.00575, -1.91808, -1.94420, -1.89713, -1.84211, -1.83421, -1.76108, -1.68719, -1.57998, -1.52328, -1.39204, -1.21564, -1.15561, -1.22043, -1.13903, -1.09881, -1.03322, -0.82827, -0.71818, -0.73490, -0.73152, -0.60728, -0.55610, -0.50504, -0.30046, -0.13186, 0.01282, -0.02231, -0.16938, -0.27037, -0.36185, -0.24421, -0.06805, 0.09999, 0.04355, -0.16908, -0.33119, -0.44660, -0.44038, -0.47394, -0.52780, -0.79778, -1.04630, -1.17202, -1.27457, -1.49660, -1.62475, -1.65527, -1.76620, -1.88598, -1.97931, -1.95386, -1.88558, -1.88277, -1.98612, -2.01836, -1.96057, -2.00138, -1.96072, -1.89722, -1.88876, -1.93118, -1.96767, -1.93822, -1.98499, -2.01134, -2.01232, -1.96765, -1.81779, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.12421, -0.01128, -0.15188, -0.14364, -0.06178, 0.05744, 0.10123, 0.07775, 0.04382, 0.04043, 0.01054, -0.04962, -0.09988, -0.17930, -0.14449, -0.07234, 0.10821, 0.08364, 0.02008, 0.10532, 0.12531, -0.09545, -0.27402, -0.30341, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.24416, -1.36572, -1.54320, -1.74148, -1.92647, -2.02780, -2.19198, -2.14944, -2.17646, -2.32651, -2.49848, -2.59912, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.85504, -3.86226, -3.79701, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.12700, -1.10159, -1.04692, -0.88134, -0.77939, -0.74759, -0.66487, -0.52522, -0.50321, -0.52887, -0.59648, -0.70752, -0.85849, -1.03392, -1.13729, -1.25025, -1.34567, -1.44867, -1.52078, -1.55350, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.31285, -0.39567, -0.39414, -0.38056, -0.32538, -0.39008, -0.68504, -0.89322, -0.97156, -1.02892, -1.01142, -1.02401, -1.00821, -0.94437, -0.85754, -0.83477, -0.94330, -1.03525, -1.19584, -1.38270, -1.53959, -1.53266, -1.41762, -1.35856, -1.37520, -1.49279, -1.57499, -1.67964, -1.79312, -1.86142, -1.76207, -1.71974, -1.66395, -1.40255, -1.19661, -1.12961, -1.03655, -0.87631, -0.84758, -0.71804, -0.44489, -0.24405, -0.01446, 0.08009, 0.11821, 0.09875, 0.04301, 0.13642, 0.20148, 0.21512, 0.02769, -0.05476, 0.01288, 0.02313, 0.00566, 0.01575, 0.12060, 0.06583, -0.10214, -0.28970, -0.53673, -0.79672, -0.84040, -0.91294, -1.06414, -1.17588, -1.32100, -1.37281, -1.27001, -1.07350, -1.06306, -1.10462, -1.02459, -0.90057, -0.63896, -0.38614, -0.21715, -0.07414, 0.00899, -0.01067, -0.15470, -0.20506, -0.30045, -0.39671, -0.44102, -0.41813, -0.33870, -0.35776, -0.24532, -0.22046, -0.21719, -0.23508, -0.23040, -0.19069, -0.08803, -0.09355, -0.22260, -0.19978, -0.17467, -0.08398, 0.13902, 0.41464, 0.56055, 0.57750, 0.68902, 0.66776, 0.64815, 0.72945, 0.82608, 0.89975, 0.88149, 0.96754, 1.10200, 1.18428, 1.11406, 1.09405, 1.19179, 1.25941, 1.21747, 1.06695, 1.03263, 0.99574, 1.07224, 1.18447, 1.24362, +1.58791, 1.53413, 1.43832, 1.33264, 1.17120, 0.95556, 0.90002, 0.90481, 0.84333, 0.80782, 0.94280, 1.04323, 1.03993, 0.97272, 0.83654, 0.67959, 0.49487, 0.52728, 0.60927, 0.68819, 0.71424, 0.56161, 0.39727, 0.33228, 0.34348, 0.20672, -0.02089, -0.29820, -0.55471, -0.71510, -1.03698, -1.26531, -1.35385, -1.45420, -1.56813, -1.69373, -1.74559, -1.97788, -2.10890, -2.08794, -2.07986, -2.12477, -2.24592, -2.34420, -2.41588, -2.39555, -2.38444, -2.31883, -2.40220, -2.45930, -2.51398, -2.60131, -2.68882, -2.92520, -2.96186, -2.80923, -2.71868, -2.68637, -2.57672, -2.42401, -2.45018, -2.43329, -2.44436, -2.46590, -2.42959, -2.37345, -2.22988, -2.12885, -2.02765, -2.00010, -1.91708, -1.75868, -1.66623, -1.60043, -1.55122, -1.50239, -1.44486, -1.26212, -1.14491, -1.01335, -1.05571, -1.03836, -0.99037, -0.88359, -0.60463, -0.52968, -0.58447, -0.57240, -0.46188, -0.35864, -0.32525, -0.16129, -0.02255, 0.17526, 0.13478, -0.03979, -0.10235, -0.22152, -0.17789, -0.05251, 0.14162, 0.17311, -0.00397, -0.13733, -0.29238, -0.42722, -0.56210, -0.63871, -0.85331, -0.97634, -1.15119, -1.22238, -1.42975, -1.63219, -1.65352, -1.72666, -1.74251, -1.84901, -1.91031, -1.86087, -1.87551, -1.88933, -1.88838, -1.83873, -1.92892, -1.86580, -1.82214, -1.90227, -1.96859, -2.04191, -2.04857, -2.04138, -1.92230, -1.78941, -1.73392, -1.60425, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.02916, -0.03334, -0.19518, -0.26684, -0.20561, -0.12776, 0.07289, 0.19583, 0.17420, 0.09589, 0.07679, 0.03754, -0.08321, -0.13366, -0.19504, -0.16854, -0.11320, 0.05389, 0.01302, 0.01858, 0.02427, 0.03260, -0.09625, -0.29792, -0.33510, -0.45325, -0.49586, -0.53041, -0.60852, -0.64047, -0.65225, -0.56225, -0.55628, -0.58251, -0.72151, -0.73654, -0.68555, -0.75282, -0.78380, -0.87748, -1.07827, -1.34962, -1.43472, -1.47426, -1.61248, -1.75098, -1.91592, -2.07412, -2.32071, -2.34158, -2.39809, -2.45825, -2.67934, -2.82066, -2.84577, -3.01362, -3.18179, -3.37378, -3.43781, -3.50128, -3.79050, -3.97046, -4.01819, -3.95987, -3.84000, -3.64071, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.28270, -1.26553, -1.14546, -1.17121, -1.15046, -1.00185, -0.99688, -1.00936, -0.93278, -0.72340, -0.59666, -0.53365, -0.57801, -0.68110, -0.84191, -1.14491, -1.29251, -1.34659, -1.41871, -1.50705, -1.52473, -1.45415, -1.48564, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.40344, -0.46655, -0.49984, -0.44623, -0.46765, -0.68378, -0.88833, -1.03021, -1.15315, -1.10864, -1.14765, -1.13716, -1.03608, -1.01628, -1.10036, -1.27186, -1.34372, -1.45150, -1.57169, -1.60618, -1.55101, -1.48354, -1.45493, -1.47253, -1.52301, -1.56161, -1.76248, -1.85969, -1.92788, -1.88751, -1.87453, -1.82341, -1.51769, -1.34009, -1.23409, -1.09246, -0.95244, -0.93928, -0.92706, -0.75724, -0.61555, -0.35563, -0.28651, -0.28644, -0.26189, -0.31922, -0.24772, -0.15774, -0.04586, -0.12805, -0.18498, -0.09568, -0.11072, -0.20794, -0.24834, -0.15801, -0.16204, -0.23842, -0.47420, -0.65705, -0.87841, -0.98708, -1.07584, -1.20784, -1.24967, -1.44406, -1.57350, -1.51938, -1.39378, -1.31961, -1.33424, -1.23195, -1.09776, -0.78950, -0.57833, -0.50852, -0.37291, -0.30931, -0.33023, -0.41892, -0.38384, -0.39822, -0.48318, -0.49687, -0.47862, -0.46697, -0.55971, -0.48152, -0.40016, -0.26303, -0.34395, -0.32685, -0.26749, -0.22721, -0.20122, -0.30479, -0.24056, -0.28666, -0.30735, -0.07412, 0.21409, 0.46765, 0.51482, 0.59453, 0.51600, 0.52680, 0.62581, 0.71231, 0.86539, 0.89438, 0.97639, 1.12188, 1.28693, 1.32444, 1.30492, 1.39699, 1.42764, 1.29644, 1.06505, 0.97679, 0.93051, 1.10979, 1.17446, 1.28628, +1.46612, 1.41768, 1.41591, 1.32877, 1.18248, 1.03697, 1.00917, 0.98279, 0.93075, 0.94663, 1.14334, 1.32536, 1.34355, 1.24481, 1.05878, 0.81941, 0.57816, 0.49687, 0.55066, 0.59652, 0.45168, 0.33561, 0.29965, 0.18979, 0.16822, 0.11355, -0.07709, -0.33968, -0.52405, -0.70768, -1.03360, -1.21065, -1.35793, -1.47154, -1.50212, -1.60465, -1.65785, -1.77636, -1.87984, -1.98105, -2.10857, -2.20125, -2.24044, -2.22699, -2.25873, -2.25539, -2.28507, -2.28185, -2.36348, -2.44779, -2.44691, -2.40536, -2.56761, -2.79892, -2.73124, -2.59451, -2.44514, -2.26534, -2.17411, -2.12538, -2.10977, -2.09276, -2.15161, -2.17152, -2.28962, -2.40144, -2.29305, -2.22640, -2.12981, -1.99715, -1.87212, -1.74169, -1.65399, -1.57342, -1.45841, -1.33697, -1.28589, -1.13740, -1.07555, -1.02895, -1.03852, -0.98592, -0.86992, -0.61774, -0.43744, -0.40480, -0.30369, -0.27643, -0.23725, -0.13647, -0.15930, -0.10145, 0.06902, 0.27984, 0.20658, 0.07820, -0.01947, -0.15409, -0.05086, 0.04835, 0.13775, 0.22640, 0.13203, -0.04210, -0.26067, -0.46331, -0.61088, -0.62785, -0.80486, -0.91878, -1.08119, -1.17598, -1.34816, -1.55753, -1.61458, -1.54715, -1.58589, -1.76243, -1.77202, -1.76573, -1.82533, -1.75867, -1.73278, -1.77194, -1.86624, -1.82051, -1.86290, -1.92607, -1.98983, -2.10526, -2.03184, -1.90283, -1.73637, -1.48626, -1.35421, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.30821, -0.11134, -0.13433, -0.24373, -0.32318, -0.22788, -0.14763, -0.04512, 0.11988, 0.18590, 0.25435, 0.24697, 0.17822, 0.15157, 0.04260, -0.07319, -0.20432, -0.22360, -0.14984, 0.09187, 0.09912, 0.05208, -0.01013, -0.05346, -0.13508, -0.27826, -0.36868, -0.34040, -0.33400, -0.45517, -0.42949, -0.39312, -0.47868, -0.40289, -0.39846, -0.51387, -0.61274, -0.53652, -0.52659, -0.58307, -0.63862, -0.85495, -1.07344, -1.33722, -1.50854, -1.54716, -1.68215, -1.87190, -2.07526, -2.26713, -2.51382, -2.53296, -2.59277, -2.67687, -2.88063, -3.03467, -3.09430, -3.25345, -3.45484, -3.49139, -3.49889, -3.70558, -3.93811, -4.03435, -4.09921, -3.96331, -3.78264, -3.67699, -3.58625, -3.40053, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.64279, -1.50121, -1.34916, -1.26552, -1.19732, -1.17164, -1.16429, -1.24079, -1.27269, -1.20002, -1.10752, -0.85786, -0.64531, -0.58375, -0.62003, -0.60731, -0.76356, -1.09212, -1.23495, -1.34518, -1.44008, -1.44726, -1.41329, -1.28327, -1.20341, -1.05993, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.56700, -0.55387, -0.56316, -0.55171, -0.63419, -0.84505, -1.02750, -1.07523, -1.03791, -1.11650, -1.10704, -1.09885, -1.15109, -1.19670, -1.38546, -1.52546, -1.59040, -1.65498, -1.67364, -1.64878, -1.63884, -1.59278, -1.51235, -1.52133, -1.57568, -1.78707, -1.94105, -2.01548, -2.02885, -1.97856, -1.75770, -1.55286, -1.42777, -1.20958, -1.08482, -0.98339, -0.94821, -1.03650, -1.01499, -0.86996, -0.69062, -0.71542, -0.68477, -0.68668, -0.77419, -0.65359, -0.53142, -0.39629, -0.31710, -0.30699, -0.30752, -0.42928, -0.58946, -0.60813, -0.44186, -0.42072, -0.49609, -0.68295, -0.80323, -0.92115, -1.05907, -1.22498, -1.26340, -1.37711, -1.64803, -1.71980, -1.70128, -1.63281, -1.50698, -1.51562, -1.47262, -1.25150, -0.89125, -0.71698, -0.64516, -0.61086, -0.65841, -0.59814, -0.57054, -0.54968, -0.51781, -0.55312, -0.58374, -0.61253, -0.66698, -0.77460, -0.66713, -0.57232, -0.45024, -0.47546, -0.41122, -0.32956, -0.30636, -0.31557, -0.26528, -0.24809, -0.42720, -0.41262, -0.19007, 0.04589, 0.30344, 0.35483, 0.38229, 0.38848, 0.49155, 0.55723, 0.69651, 0.88413, 0.91047, 1.06315, 1.26229, 1.38149, 1.47775, 1.50618, 1.52840, 1.44496, 1.21327, 0.97407, 0.97777, 0.99172, 1.10524, 1.10165, 1.18051, +1.20891, 1.28806, 1.30396, 1.21636, 1.10965, 1.01276, 1.02797, 0.99071, 1.08457, 1.26163, 1.37447, 1.45367, 1.41569, 1.28301, 1.13096, 0.92821, 0.73317, 0.59649, 0.48447, 0.36272, 0.22387, 0.29286, 0.34807, 0.15083, -0.00925, -0.06895, -0.13701, -0.27163, -0.45409, -0.74426, -1.05397, -1.15365, -1.24845, -1.25802, -1.29764, -1.46550, -1.55980, -1.62959, -1.68110, -1.87543, -2.06213, -2.11374, -2.19575, -2.22518, -2.20888, -2.15453, -2.14817, -2.16307, -2.23982, -2.32956, -2.36809, -2.32092, -2.37364, -2.38694, -2.26207, -2.21410, -2.13932, -1.98835, -1.91358, -1.88650, -1.89398, -1.97422, -2.08017, -2.06380, -2.16340, -2.23773, -2.23093, -2.31250, -2.23729, -2.08783, -1.92338, -1.84326, -1.77210, -1.54349, -1.39983, -1.28777, -1.17962, -1.03370, -1.00989, -1.00736, -0.94959, -0.77838, -0.63445, -0.41789, -0.26554, -0.08276, 0.14358, 0.12922, 0.03041, -0.00354, -0.04344, 0.05730, 0.22099, 0.31005, 0.18441, 0.09182, 0.02467, 0.07032, 0.19309, 0.12163, 0.05652, 0.05900, 0.03511, -0.11707, -0.31370, -0.33943, -0.49117, -0.63138, -0.80933, -0.93362, -1.07699, -1.12794, -1.21698, -1.35344, -1.49390, -1.50435, -1.56960, -1.63251, -1.61300, -1.70724, -1.83331, -1.80738, -1.76480, -1.72984, -1.76501, -1.83407, -1.99159, -2.04616, -2.03348, -1.96696, -1.82008, -1.77557, -1.66492, -1.42665, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.58918, -0.51863, -0.37797, -0.34733, -0.34075, -0.29328, -0.14014, -0.09033, -0.01597, 0.08469, 0.23541, 0.40567, 0.34560, 0.24529, 0.20631, 0.12307, -0.00499, -0.21185, -0.15036, -0.05960, 0.07055, 0.11641, 0.06316, -0.05762, -0.11164, -0.18333, -0.26033, -0.40584, -0.42726, -0.39575, -0.36277, -0.20248, -0.12254, -0.23521, -0.29500, -0.36262, -0.45607, -0.44782, -0.37479, -0.45653, -0.58413, -0.70984, -0.86285, -0.99323, -1.29363, -1.55423, -1.69428, -1.90033, -2.10745, -2.29917, -2.32886, -2.49032, -2.67677, -2.81944, -2.91794, -3.08676, -3.20040, -3.29388, -3.41222, -3.59998, -3.62728, -3.63864, -3.77199, -3.87580, -3.94106, -4.02733, -3.92012, -3.76466, -3.69334, -3.61431, -3.43283, -3.36187, -3.29467, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.34002, -2.18293, -2.00929, -1.90063, -1.73973, -1.52990, -1.34255, -1.28396, -1.27521, -1.28390, -1.36910, -1.34644, -1.25223, -1.15896, -0.96866, -0.78399, -0.73372, -0.72671, -0.66014, -0.81529, -1.07567, -1.16401, -1.20162, -1.22963, -1.26423, -1.25028, -1.10942, -1.00208, -0.87905, -0.84703, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.51676, -0.52291, -0.64599, -0.68088, -0.70731, -0.85493, -0.92345, -0.89491, -0.94904, -1.09699, -1.13769, -1.15436, -1.13056, -1.17634, -1.42677, -1.65094, -1.78275, -1.82406, -1.85770, -1.83784, -1.76958, -1.79492, -1.75533, -1.70885, -1.74490, -1.84962, -1.92394, -1.97905, -2.02386, -2.01687, -1.76334, -1.54580, -1.33943, -1.15629, -1.15772, -1.14139, -1.13170, -1.20310, -1.17171, -1.06154, -1.08755, -1.20935, -1.13303, -1.06843, -1.01540, -0.92013, -0.90877, -0.79253, -0.65944, -0.58417, -0.62697, -0.78118, -0.79977, -0.82063, -0.74745, -0.71260, -0.77112, -0.87571, -0.85848, -0.86165, -1.01113, -1.33518, -1.49895, -1.63777, -1.77326, -1.81389, -1.84018, -1.81033, -1.74994, -1.76458, -1.69342, -1.43143, -1.13654, -0.97341, -0.85135, -0.84566, -0.83038, -0.75490, -0.80958, -0.86623, -0.90831, -0.89399, -0.85941, -0.87959, -0.80935, -0.87485, -0.86203, -0.79101, -0.70680, -0.66113, -0.45889, -0.32985, -0.30421, -0.44471, -0.46366, -0.44399, -0.46801, -0.37106, -0.21547, -0.07049, 0.04441, 0.10177, 0.24935, 0.39260, 0.48674, 0.48638, 0.64759, 0.88141, 1.07920, 1.28023, 1.35827, 1.38912, 1.45371, 1.52486, 1.54425, 1.38251, 1.23872, 1.02453, 0.96121, 1.00091, 1.02541, 0.92563, 0.98705, +0.88368, 1.01691, 1.00728, 0.95569, 1.00552, 1.01761, 1.05202, 1.04251, 1.18753, 1.38642, 1.43244, 1.40733, 1.34447, 1.26042, 1.10278, 0.88251, 0.65624, 0.55226, 0.47569, 0.28226, 0.17425, 0.30726, 0.29885, 0.06656, -0.11589, -0.20361, -0.17228, -0.18236, -0.40554, -0.67404, -0.91689, -1.01174, -1.00536, -0.96898, -1.05827, -1.28260, -1.36797, -1.43375, -1.52371, -1.73025, -1.89705, -1.96013, -2.09830, -2.20293, -2.16809, -2.02873, -2.02505, -2.11018, -2.24771, -2.30698, -2.23897, -2.19489, -2.16879, -2.05531, -1.97644, -1.98618, -1.92467, -1.85596, -1.78750, -1.71981, -1.82676, -1.97528, -2.08448, -2.11400, -2.06889, -2.07350, -2.15296, -2.37684, -2.34967, -2.21832, -2.07651, -2.01309, -1.91975, -1.64085, -1.47706, -1.36884, -1.19129, -0.93506, -0.87705, -0.89415, -0.81211, -0.56894, -0.28370, -0.08873, 0.05207, 0.31001, 0.49192, 0.38818, 0.26461, 0.13538, 0.11110, 0.32100, 0.41778, 0.40778, 0.30335, 0.11583, 0.11029, 0.22673, 0.29628, 0.09711, -0.01194, -0.04077, -0.07700, -0.21456, -0.35445, -0.32135, -0.48630, -0.71326, -0.89568, -0.94320, -1.05427, -1.15281, -1.23892, -1.35657, -1.41575, -1.46700, -1.58219, -1.59659, -1.61978, -1.81489, -1.92113, -1.94931, -1.91723, -1.73398, -1.69840, -1.82394, -1.95799, -2.14213, -2.09689, -1.92374, -1.75584, -1.80704, -1.71932, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.94748, -1.00160, -1.00094, -0.89614, -0.82097, -0.70160, -0.57142, -0.49782, -0.31364, -0.19088, -0.09225, 0.00141, -0.02381, 0.07632, 0.30399, 0.49329, 0.35577, 0.25086, 0.22967, 0.13698, -0.01241, -0.21506, -0.13908, -0.07888, -0.05072, -0.01325, 0.00197, -0.09207, -0.21404, -0.32769, -0.43847, -0.48921, -0.46870, -0.45178, -0.33019, -0.13541, -0.08821, -0.10114, -0.19689, -0.34204, -0.39820, -0.38456, -0.40982, -0.46309, -0.70952, -0.88768, -0.96357, -1.06830, -1.42870, -1.72468, -1.88502, -2.10870, -2.29404, -2.40288, -2.33613, -2.46819, -2.75164, -2.95569, -3.01672, -3.13742, -3.29941, -3.44116, -3.58572, -3.63423, -3.55411, -3.59369, -3.66807, -3.72196, -3.86829, -3.94183, -3.86992, -3.79224, -3.67427, -3.56140, -3.46939, -3.35053, -3.31166, -3.13624, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.61269, -2.53448, -2.52511, -2.45004, -2.26438, -2.10869, -1.97041, -1.78347, -1.62047, -1.48765, -1.33403, -1.29982, -1.33587, -1.30285, -1.35125, -1.31047, -1.14716, -1.02435, -0.94335, -0.86351, -0.83148, -0.91185, -1.09774, -1.17432, -1.08306, -1.03257, -1.06960, -1.07071, -0.90420, -0.79977, -0.73436, -0.72193, -0.66309, -0.67674, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.50608, -0.59357, -0.74961, -0.75035, -0.77485, -0.84749, -0.79814, -0.81548, -0.90991, -1.08281, -1.25019, -1.23615, -1.19207, -1.28464, -1.58812, -1.81739, -1.98057, -2.06829, -2.11618, -2.07776, -2.00845, -2.07787, -2.08908, -1.99588, -1.90922, -1.88021, -1.88428, -1.94258, -1.98646, -1.93885, -1.75649, -1.56565, -1.35362, -1.31304, -1.44449, -1.44970, -1.49526, -1.53119, -1.41043, -1.36981, -1.46256, -1.53366, -1.52218, -1.36916, -1.24278, -1.19158, -1.26672, -1.14193, -0.99281, -0.92120, -0.94272, -1.01831, -0.94109, -0.95177, -0.95228, -0.90276, -0.85365, -0.89155, -0.88580, -0.91112, -1.09653, -1.37493, -1.61237, -1.79739, -1.88571, -2.00132, -2.12927, -2.09414, -2.10514, -2.12443, -1.96021, -1.72234, -1.49287, -1.25844, -1.19798, -1.14335, -1.07613, -1.03907, -1.20240, -1.27750, -1.31888, -1.29347, -1.21114, -1.16334, -1.02988, -1.02165, -1.01687, -0.94663, -0.80891, -0.74776, -0.59159, -0.47595, -0.48315, -0.57709, -0.62412, -0.63298, -0.57388, -0.48749, -0.43835, -0.27686, -0.19004, -0.08044, 0.23802, 0.44745, 0.49830, 0.56303, 0.64918, 0.91902, 1.19259, 1.37055, 1.33701, 1.35940, 1.46062, 1.53288, 1.53903, 1.39668, 1.29373, 1.07710, 0.92872, 0.92200, 0.95561, 0.85712, 0.84324, +0.58891, 0.65594, 0.73917, 0.81060, 0.99910, 1.13665, 1.18791, 1.17963, 1.23585, 1.33290, 1.42561, 1.43590, 1.27736, 1.14432, 1.01436, 0.78659, 0.50387, 0.41777, 0.38516, 0.18842, 0.06480, 0.16844, 0.19625, 0.03586, -0.10340, -0.16866, -0.17770, -0.23931, -0.40082, -0.52799, -0.63975, -0.66717, -0.67248, -0.70514, -0.72223, -0.87261, -0.97153, -1.08024, -1.25314, -1.47833, -1.64775, -1.77025, -1.86351, -1.91795, -1.98859, -1.97811, -1.98941, -2.07726, -2.24691, -2.26442, -2.10869, -2.07915, -2.06207, -1.93726, -1.80352, -1.72035, -1.60925, -1.54702, -1.56989, -1.67200, -1.84817, -1.97947, -2.04963, -2.02725, -1.91625, -1.97089, -2.02439, -2.22428, -2.29505, -2.22885, -2.13403, -2.09435, -1.98291, -1.75771, -1.53509, -1.32260, -1.17907, -0.98813, -0.84439, -0.74949, -0.62110, -0.34090, 0.03090, 0.19514, 0.30419, 0.54140, 0.73431, 0.69871, 0.59693, 0.45313, 0.37698, 0.43216, 0.47385, 0.49839, 0.46914, 0.30600, 0.29163, 0.25965, 0.30265, 0.18742, 0.09125, 0.06718, 0.01168, -0.16272, -0.31173, -0.40793, -0.58989, -0.72457, -0.93027, -1.06996, -1.14447, -1.22154, -1.32745, -1.45072, -1.44175, -1.52529, -1.67106, -1.70939, -1.71391, -1.82251, -1.90173, -1.93847, -1.94792, -1.87470, -1.78390, -1.81181, -1.86263, -2.05196, -2.05102, -1.99369, -1.80181, -1.72576, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.17113, -1.23156, -1.11693, -1.12021, -1.25239, -1.29951, -1.16717, -0.98499, -0.79498, -0.59304, -0.45671, -0.33770, -0.21350, -0.09918, 0.05121, 0.08050, 0.22826, 0.38344, 0.56759, 0.53241, 0.43515, 0.36779, 0.23911, 0.03677, -0.16490, -0.18516, -0.17461, -0.08649, -0.06004, -0.17049, -0.26500, -0.35194, -0.44403, -0.55342, -0.51381, -0.47937, -0.51019, -0.43456, -0.22944, -0.05504, 0.06247, 0.01247, -0.17006, -0.42170, -0.54796, -0.59196, -0.57308, -0.76870, -0.91161, -1.06888, -1.22505, -1.52253, -1.81619, -2.00090, -2.19746, -2.34928, -2.40143, -2.38149, -2.54382, -2.74476, -2.92256, -3.10066, -3.25181, -3.38826, -3.51949, -3.66475, -3.60449, -3.47002, -3.54562, -3.64025, -3.66155, -3.72855, -3.76055, -3.72436, -3.70479, -3.69415, -3.62890, -3.50496, -3.28753, -3.18226, -2.99997, -2.84723, -2.77805, 0.00000, 0.00000, 0.00000, 0.00000, -2.87323, -2.84400, -2.78110, -2.75522, -2.67465, -2.54982, -2.46265, -2.34813, -2.18712, -2.01160, -1.88514, -1.69055, -1.42929, -1.34718, -1.38018, -1.35752, -1.41640, -1.39954, -1.25129, -1.14852, -1.13384, -1.10338, -1.03634, -1.00076, -1.08442, -1.09541, -0.99529, -0.93333, -0.81150, -0.72008, -0.56620, -0.49121, -0.50184, -0.53074, -0.53742, -0.66395, -0.85799, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.69215, -0.70285, -0.72576, -0.63450, -0.61421, -0.72391, -0.80043, -0.87403, -0.93218, -1.06139, -1.23257, -1.26264, -1.33226, -1.39576, -1.63200, -1.86923, -2.04840, -2.17801, -2.24992, -2.23362, -2.25291, -2.29365, -2.23417, -2.18735, -2.13506, -1.96372, -1.83096, -1.85584, -1.87667, -1.83755, -1.79992, -1.70987, -1.57049, -1.53101, -1.61319, -1.62912, -1.71289, -1.82988, -1.86309, -1.85125, -1.83777, -1.76810, -1.71276, -1.56314, -1.54231, -1.46443, -1.44526, -1.31264, -1.16498, -1.10318, -1.12412, -1.14998, -1.10837, -1.07746, -0.98459, -0.94512, -0.94893, -0.92730, -0.90872, -0.99838, -1.21001, -1.42122, -1.70224, -1.94519, -2.09252, -2.22726, -2.33879, -2.34552, -2.38401, -2.43780, -2.40446, -2.17968, -1.89148, -1.57066, -1.46854, -1.39420, -1.43010, -1.37571, -1.42904, -1.48501, -1.52006, -1.50706, -1.45821, -1.38775, -1.31696, -1.22858, -1.04687, -0.96655, -0.94324, -0.91521, -0.79588, -0.70347, -0.71341, -0.71298, -0.77255, -0.83775, -0.84213, -0.77883, -0.67089, -0.46614, -0.29144, -0.10794, 0.11905, 0.33024, 0.44854, 0.62258, 0.77265, 1.06722, 1.22455, 1.38089, 1.43901, 1.48620, 1.59151, 1.63782, 1.58342, 1.46641, 1.30167, 1.06952, 0.97656, 0.90480, 0.78658, 0.70213, 0.72744, +0.38370, 0.38771, 0.47340, 0.60471, 0.91902, 1.18882, 1.30439, 1.33815, 1.34938, 1.41258, 1.42068, 1.35361, 1.19071, 1.04135, 0.98743, 0.78259, 0.49505, 0.32793, 0.15481, 0.02732, -0.00065, 0.05230, 0.03528, -0.13135, -0.20482, -0.22288, -0.23254, -0.24512, -0.24822, -0.29810, -0.41627, -0.39674, -0.38031, -0.42020, -0.39982, -0.50178, -0.63666, -0.79964, -1.04530, -1.25795, -1.42166, -1.46937, -1.54188, -1.64369, -1.77149, -1.89421, -1.92986, -1.98506, -2.11888, -2.10432, -2.01488, -1.92617, -1.82727, -1.71328, -1.59802, -1.48224, -1.25712, -1.14427, -1.29938, -1.57719, -1.79991, -1.95226, -2.09988, -2.00017, -1.80899, -1.82013, -1.89833, -2.04637, -2.17336, -2.16148, -2.16279, -2.13808, -2.00304, -1.70563, -1.44030, -1.26621, -1.18091, -1.08126, -0.89782, -0.65471, -0.42428, -0.07813, 0.20632, 0.37316, 0.53899, 0.76519, 0.96215, 0.97786, 0.91167, 0.78324, 0.57851, 0.44551, 0.44424, 0.52559, 0.49990, 0.42113, 0.39567, 0.29606, 0.24244, 0.19825, 0.13630, 0.19879, 0.14061, -0.01771, -0.21714, -0.37144, -0.60207, -0.80975, -1.04445, -1.24146, -1.28642, -1.27920, -1.39177, -1.47022, -1.56039, -1.63869, -1.65605, -1.66024, -1.71257, -1.84088, -1.92130, -1.90143, -1.96224, -1.98819, -1.83745, -1.73080, -1.81108, -1.91682, -1.92240, -1.89806, -1.79936, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.99835, -1.06363, -1.14614, -1.31715, -1.32616, -1.27980, -1.31167, -1.40624, -1.46586, -1.40643, -1.25710, -1.04756, -0.68711, -0.44521, -0.35931, -0.23827, -0.08540, -0.01262, 0.09356, 0.31323, 0.53614, 0.67911, 0.70213, 0.59999, 0.53157, 0.34477, 0.13589, -0.11605, -0.17662, -0.16235, -0.15309, -0.17405, -0.34912, -0.45155, -0.40596, -0.42019, -0.40990, -0.43726, -0.49474, -0.50945, -0.42734, -0.26655, -0.08119, 0.09466, 0.15050, -0.05069, -0.42036, -0.64464, -0.67826, -0.75616, -0.91233, -0.94642, -1.04077, -1.25444, -1.56931, -1.94400, -2.15753, -2.37850, -2.47083, -2.50453, -2.50529, -2.63536, -2.88021, -3.08762, -3.29879, -3.41914, -3.41048, -3.51656, -3.57482, -3.56379, -3.53026, -3.56833, -3.57152, -3.54599, -3.61351, -3.69134, -3.67997, -3.71368, -3.78890, -3.72585, -3.47433, -3.24369, -3.10286, -2.87210, -2.73784, -2.76667, -2.82129, -2.98510, -2.98222, -2.95378, -2.93696, -2.95559, -2.94670, -2.89554, -2.80941, -2.66524, -2.61165, -2.57019, -2.38806, -2.24664, -2.07293, -1.88713, -1.66856, -1.45801, -1.37243, -1.33385, -1.38412, -1.41759, -1.28439, -1.22743, -1.27437, -1.22041, -1.04334, -0.96819, -1.06050, -1.02925, -0.89554, -0.82678, -0.62944, -0.47304, -0.31681, -0.27231, -0.37098, -0.47296, -0.54752, -0.61913, -0.80149, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.85261, -0.82168, -0.74680, -0.51630, -0.40404, -0.54179, -0.70821, -0.80311, -0.89663, -1.10137, -1.24108, -1.26185, -1.36617, -1.47430, -1.67584, -1.90738, -2.06083, -2.19744, -2.25137, -2.30265, -2.34078, -2.42444, -2.44184, -2.40898, -2.37070, -2.07675, -1.78478, -1.71386, -1.66128, -1.72126, -1.75857, -1.71868, -1.68858, -1.68057, -1.73520, -1.74476, -1.81780, -2.06046, -2.27027, -2.28880, -2.22127, -2.13308, -1.98159, -1.80640, -1.80684, -1.79942, -1.73951, -1.58332, -1.32977, -1.25211, -1.26174, -1.32103, -1.27318, -1.24731, -1.21114, -1.11172, -1.07619, -1.00328, -0.95101, -1.10411, -1.27936, -1.55866, -1.82178, -2.00381, -2.17380, -2.36043, -2.53362, -2.61817, -2.65246, -2.76848, -2.83959, -2.58793, -2.21537, -1.93717, -1.75340, -1.63093, -1.63574, -1.58891, -1.53810, -1.60188, -1.62062, -1.69256, -1.68978, -1.67302, -1.58862, -1.42891, -1.23387, -1.13158, -1.13015, -1.08618, -0.94502, -0.91326, -0.87013, -0.88280, -0.89221, -0.88556, -0.88776, -0.91443, -0.88197, -0.71359, -0.44191, -0.21168, -0.05722, 0.17046, 0.38092, 0.50970, 0.73495, 1.10477, 1.34805, 1.46089, 1.53868, 1.53684, 1.62418, 1.57553, 1.48394, 1.38817, 1.28631, 1.08444, 0.88008, 0.71072, 0.52581, 0.46949, 0.62460, +0.18885, 0.16750, 0.25472, 0.39200, 0.64585, 0.90128, 1.11196, 1.27863, 1.34539, 1.41242, 1.37523, 1.25019, 1.13817, 1.03522, 0.95218, 0.73755, 0.45802, 0.19289, -0.06201, -0.14719, -0.14039, -0.13048, -0.15611, -0.28765, -0.37006, -0.41374, -0.30775, -0.12478, -0.05385, -0.11032, -0.23979, -0.20366, -0.17694, -0.25570, -0.25161, -0.34633, -0.55570, -0.76187, -0.93905, -1.03362, -1.18077, -1.20313, -1.26942, -1.37521, -1.47499, -1.56594, -1.65579, -1.79225, -1.92224, -1.92212, -1.83728, -1.63080, -1.47565, -1.38605, -1.28914, -1.14611, -0.92946, -0.90874, -1.10406, -1.32231, -1.57124, -1.79469, -2.02487, -1.95254, -1.81713, -1.87435, -1.96515, -1.98956, -2.09037, -2.14601, -2.22171, -2.17944, -2.04065, -1.69578, -1.35939, -1.11097, -1.00302, -0.90031, -0.79376, -0.64892, -0.39829, -0.04644, 0.21764, 0.49758, 0.71642, 0.92301, 1.11094, 1.16762, 1.08057, 0.86871, 0.63358, 0.57020, 0.51117, 0.50738, 0.42099, 0.33538, 0.28975, 0.17319, 0.12322, 0.19122, 0.14632, 0.18437, 0.09682, 0.01493, -0.18817, -0.32779, -0.54765, -0.76855, -1.01621, -1.17169, -1.22936, -1.31042, -1.46082, -1.57074, -1.73280, -1.71766, -1.65388, -1.66013, -1.75005, -1.84605, -1.88004, -1.86457, -1.91942, -1.85155, -1.76107, -1.72576, -1.84977, -1.86823, -1.80734, -1.81180, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.08567, -1.10274, -1.12380, -1.18176, -1.34201, -1.55298, -1.57407, -1.58845, -1.55085, -1.60071, -1.65881, -1.63752, -1.49183, -1.28895, -0.94458, -0.65692, -0.40306, -0.24480, -0.11452, -0.05611, 0.09030, 0.33890, 0.54686, 0.60200, 0.68627, 0.63311, 0.60317, 0.42088, 0.28387, 0.00893, -0.09609, -0.08372, -0.08396, -0.12668, -0.25028, -0.33977, -0.35057, -0.38451, -0.37952, -0.49710, -0.52604, -0.46296, -0.35251, -0.23719, -0.10115, -0.00229, -0.02704, -0.24642, -0.42519, -0.57193, -0.68823, -0.91076, -1.10308, -1.06911, -1.11312, -1.34581, -1.60424, -2.01747, -2.32185, -2.64724, -2.72041, -2.75634, -2.78689, -2.87397, -3.06986, -3.26273, -3.40281, -3.46911, -3.48898, -3.63152, -3.65876, -3.69520, -3.65631, -3.63880, -3.59795, -3.57587, -3.64901, -3.75384, -3.80170, -3.83821, -3.78283, -3.62377, -3.40616, -3.26073, -3.12758, -2.82964, -2.63342, -2.70547, -2.75768, -2.91802, -2.94590, -2.95848, -2.93359, -2.97883, -3.04411, -2.99548, -2.88172, -2.73617, -2.66913, -2.65473, -2.56749, -2.49723, -2.30945, -2.16578, -1.97659, -1.70931, -1.54917, -1.44940, -1.36095, -1.32620, -1.28076, -1.34328, -1.33117, -1.12545, -0.93191, -0.87281, -0.95931, -0.91677, -0.78602, -0.79106, -0.60386, -0.40963, -0.28481, -0.29040, -0.41577, -0.54662, -0.69652, -0.74132, -0.87584, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.96082, -0.86519, -0.71607, -0.49714, -0.41898, -0.46652, -0.47049, -0.55720, -0.74939, -1.05508, -1.21759, -1.23462, -1.36689, -1.49503, -1.64322, -1.88332, -2.05647, -2.19358, -2.23874, -2.39585, -2.47008, -2.52783, -2.49797, -2.40426, -2.30563, -2.08114, -1.91305, -1.83325, -1.74550, -1.75221, -1.69835, -1.70047, -1.78202, -1.80945, -1.82575, -1.87528, -1.99114, -2.21038, -2.34808, -2.44418, -2.50978, -2.49964, -2.33026, -2.12907, -2.13102, -2.16192, -2.05742, -1.91342, -1.65154, -1.56432, -1.51590, -1.59212, -1.52694, -1.47892, -1.43647, -1.28515, -1.15835, -1.10984, -1.17246, -1.33443, -1.46949, -1.76337, -1.93965, -2.12069, -2.33262, -2.54049, -2.68138, -2.79051, -2.90805, -3.03721, -2.97555, -2.70698, -2.37608, -2.15411, -1.94748, -1.78280, -1.76277, -1.73999, -1.63548, -1.75154, -1.83358, -1.95607, -1.90264, -1.92890, -1.86553, -1.73568, -1.57603, -1.46286, -1.34951, -1.22534, -1.16890, -1.21401, -1.19593, -1.20934, -1.05322, -0.94199, -0.86938, -0.89993, -0.90412, -0.82380, -0.67939, -0.47489, -0.17982, 0.08629, 0.27765, 0.35414, 0.59065, 1.00634, 1.29941, 1.36474, 1.46415, 1.42237, 1.43900, 1.29582, 1.21696, 1.11491, 1.03151, 0.86037, 0.66617, 0.52700, 0.46171, 0.44386, 0.51258, +-0.09289, -0.03541, 0.07976, 0.18274, 0.32905, 0.52325, 0.77363, 1.02676, 1.24054, 1.30696, 1.21814, 1.10047, 0.94789, 0.80109, 0.72952, 0.67867, 0.43510, 0.12142, -0.13421, -0.28475, -0.23979, -0.21754, -0.23994, -0.26371, -0.34785, -0.36007, -0.20976, -0.03145, 0.02016, -0.05374, 0.00317, 0.09875, 0.00210, -0.09715, -0.12581, -0.29251, -0.52806, -0.70779, -0.74982, -0.74401, -0.79140, -0.86361, -1.03444, -1.12199, -1.21747, -1.30700, -1.37259, -1.43823, -1.57105, -1.65206, -1.53544, -1.35375, -1.15817, -1.05525, -1.00658, -0.83183, -0.70584, -0.76990, -0.94493, -1.15266, -1.36650, -1.63835, -1.78661, -1.73741, -1.83524, -1.97949, -2.01121, -2.00199, -2.03939, -2.12416, -2.19421, -2.17373, -1.99467, -1.65584, -1.34216, -0.97121, -0.78470, -0.72464, -0.65559, -0.49894, -0.23819, 0.01748, 0.34272, 0.63571, 0.89925, 1.13401, 1.22612, 1.26925, 1.15203, 0.91964, 0.79407, 0.76768, 0.68887, 0.52862, 0.43611, 0.34862, 0.16989, 0.03882, 0.13691, 0.23418, 0.20518, 0.13961, 0.02267, -0.05322, -0.16504, -0.22385, -0.46647, -0.68380, -0.93381, -1.15691, -1.23516, -1.28992, -1.41829, -1.68120, -1.84046, -1.86439, -1.82191, -1.79646, -1.90731, -1.90074, -1.79897, -1.73124, -1.68913, -1.64661, -1.65560, -1.80526, -1.88983, -1.79542, -1.79210, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.09314, -1.22656, -1.22940, -1.28568, -1.32489, -1.42576, -1.55936, -1.71975, -1.78056, -1.81715, -1.87496, -1.83332, -1.77950, -1.56882, -1.33260, -1.07025, -0.76718, -0.50307, -0.31213, -0.22636, -0.05734, 0.21577, 0.35680, 0.36436, 0.42450, 0.51996, 0.56153, 0.60746, 0.53274, 0.43448, 0.20689, 0.13249, 0.07158, 0.04713, 0.03501, -0.12303, -0.22503, -0.24960, -0.27679, -0.45440, -0.61124, -0.63983, -0.52720, -0.30969, -0.22870, -0.15020, -0.11466, -0.25198, -0.41457, -0.50391, -0.58258, -0.80119, -1.05636, -1.17598, -1.21666, -1.38660, -1.51214, -1.67305, -2.03339, -2.39219, -2.75748, -2.88313, -2.92195, -2.90454, -3.00387, -3.16498, -3.27988, -3.44162, -3.57233, -3.63023, -3.69146, -3.77345, -3.77566, -3.70543, -3.70651, -3.62459, -3.66407, -3.76141, -3.80043, -3.83598, -3.75115, -3.61651, -3.45367, -3.38646, -3.32825, -3.08957, -2.78517, -2.64940, -2.63354, -2.65552, -2.81017, -2.86928, -2.89442, -2.87931, -2.93846, -2.98639, -3.01130, -2.97327, -2.85437, -2.85983, -2.91363, -2.83676, -2.65023, -2.50237, -2.40832, -2.24409, -2.05248, -1.81033, -1.63046, -1.43937, -1.25916, -1.25065, -1.32817, -1.30410, -1.10495, -0.96713, -0.91984, -0.81946, -0.75455, -0.76495, -0.77726, -0.58509, -0.40369, -0.29412, -0.31080, -0.42373, -0.56926, -0.70447, -0.83643, -1.03776, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.91893, -0.81807, -0.62568, -0.50113, -0.45261, -0.42968, -0.36385, -0.40916, -0.67727, -0.92539, -1.11229, -1.27560, -1.40454, -1.45496, -1.58300, -1.79839, -1.99732, -2.15642, -2.29005, -2.46515, -2.57302, -2.62286, -2.45466, -2.30351, -2.25246, -2.12244, -2.00620, -1.96668, -1.97711, -1.90184, -1.83821, -1.81273, -1.89173, -1.99187, -1.97698, -2.04887, -2.13808, -2.22633, -2.33929, -2.47306, -2.69427, -2.65123, -2.45555, -2.36351, -2.36444, -2.29781, -2.19974, -2.07721, -1.92928, -1.86284, -1.81167, -1.77996, -1.63117, -1.59127, -1.50682, -1.37011, -1.34250, -1.33345, -1.35386, -1.42564, -1.62425, -1.87978, -2.11706, -2.34915, -2.54679, -2.78515, -2.82517, -2.86335, -3.00168, -3.07299, -3.00487, -2.73938, -2.52548, -2.24554, -1.96819, -1.89584, -1.93187, -1.86037, -1.82603, -1.96873, -2.12229, -2.19873, -2.10724, -2.08981, -2.02833, -2.02970, -1.93998, -1.83147, -1.76177, -1.60316, -1.48631, -1.46851, -1.57191, -1.55125, -1.36766, -1.17582, -0.92493, -0.89359, -0.85416, -0.79350, -0.77086, -0.55709, -0.25997, 0.02515, 0.13625, 0.27616, 0.60740, 0.90928, 1.04837, 1.15712, 1.24465, 1.24659, 1.24223, 1.11201, 1.01035, 0.90368, 0.82883, 0.62370, 0.49295, 0.49783, 0.46734, 0.44364, 0.47554, +-0.32243, -0.11083, -0.01655, 0.01677, 0.07842, 0.21204, 0.43905, 0.71731, 1.00323, 1.04864, 0.91639, 0.81259, 0.67050, 0.51142, 0.39650, 0.46113, 0.41420, 0.19348, -0.02061, -0.18518, -0.18617, -0.23447, -0.28144, -0.21346, -0.25570, -0.23010, -0.13418, -0.05752, 0.06730, 0.10255, 0.25106, 0.30523, 0.20288, 0.19841, 0.08114, -0.17721, -0.36169, -0.42967, -0.37227, -0.33793, -0.35396, -0.54095, -0.83604, -0.93740, -0.98860, -1.01312, -1.07578, -1.12562, -1.16006, -1.17727, -1.04339, -0.91003, -0.77661, -0.78834, -0.83545, -0.68630, -0.62472, -0.70425, -0.86328, -1.11663, -1.21339, -1.36252, -1.46931, -1.53835, -1.78325, -1.87137, -1.87843, -1.89916, -1.86234, -1.90775, -1.97087, -2.00372, -1.84223, -1.60334, -1.35663, -0.91912, -0.61243, -0.51865, -0.47715, -0.34472, -0.02287, 0.26943, 0.63259, 0.93538, 1.17576, 1.29975, 1.26223, 1.25939, 1.15971, 0.98301, 0.95559, 0.88240, 0.85105, 0.71202, 0.55824, 0.35394, 0.12420, 0.16756, 0.36225, 0.38633, 0.34317, 0.20422, 0.03465, -0.09117, -0.14088, -0.17776, -0.43609, -0.68617, -0.91311, -1.11955, -1.22161, -1.31948, -1.39334, -1.63763, -1.80235, -1.87635, -1.88799, -1.93037, -2.05283, -1.98614, -1.75880, -1.60141, -1.47866, -1.55906, -1.65845, -1.81693, -1.87804, -1.83072, -1.87912, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.85455, -1.17328, -1.35442, -1.34304, -1.38419, -1.40594, -1.50143, -1.54220, -1.65582, -1.74322, -1.82454, -1.87692, -1.84708, -1.77812, -1.56013, -1.30528, -1.12453, -0.87830, -0.73277, -0.51399, -0.27581, 0.00324, 0.23721, 0.24666, 0.22967, 0.32167, 0.37795, 0.50302, 0.68664, 0.73018, 0.62347, 0.44229, 0.35594, 0.23299, 0.15607, 0.16854, 0.03077, -0.08429, -0.20716, -0.24916, -0.41654, -0.57553, -0.62055, -0.49750, -0.31651, -0.29190, -0.30072, -0.33184, -0.52271, -0.61750, -0.72398, -0.76672, -0.89887, -1.10714, -1.27272, -1.44560, -1.59166, -1.57714, -1.67668, -1.96501, -2.29610, -2.63854, -2.84007, -2.92311, -2.95219, -3.08847, -3.24366, -3.30525, -3.44548, -3.62494, -3.76682, -3.76460, -3.73370, -3.65612, -3.57201, -3.59610, -3.62307, -3.78924, -3.92373, -3.86574, -3.79977, -3.58775, -3.47703, -3.38284, -3.33831, -3.29001, -3.07563, -2.84388, -2.63202, -2.45886, -2.49995, -2.66168, -2.68638, -2.68460, -2.71126, -2.80814, -2.90391, -3.03717, -3.11219, -3.03670, -3.03528, -3.10050, -3.08344, -2.84224, -2.59792, -2.45290, -2.30843, -2.20020, -1.99652, -1.81608, -1.58148, -1.29100, -1.26398, -1.31790, -1.35812, -1.27166, -1.10731, -0.98239, -0.78982, -0.76796, -0.78853, -0.66917, -0.49872, -0.38324, -0.26971, -0.24449, -0.34562, -0.52226, -0.68647, -0.93537, -1.19471, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.78709, -0.75704, -0.61459, -0.60253, -0.58831, -0.57319, -0.53176, -0.44611, -0.62813, -0.87077, -1.15115, -1.33223, -1.30081, -1.29688, -1.44975, -1.62734, -1.80828, -2.01160, -2.24588, -2.43296, -2.59906, -2.65527, -2.41022, -2.18336, -2.13032, -2.13736, -2.16958, -2.12656, -2.10971, -1.98248, -1.90318, -1.88582, -2.02804, -2.19829, -2.20018, -2.27276, -2.29687, -2.26896, -2.41826, -2.50399, -2.65828, -2.60856, -2.51922, -2.48241, -2.30900, -2.15304, -2.11694, -2.02405, -1.94425, -1.90257, -1.88451, -1.77348, -1.61791, -1.60078, -1.52540, -1.42864, -1.46574, -1.50731, -1.53679, -1.47482, -1.59654, -1.83864, -2.15426, -2.48422, -2.77645, -3.04253, -3.00903, -2.94170, -3.04221, -3.07868, -3.09909, -2.80955, -2.54181, -2.24492, -2.05614, -2.06852, -1.99760, -1.89226, -1.96081, -2.09300, -2.23417, -2.27045, -2.20337, -2.16063, -2.16242, -2.29712, -2.33711, -2.24476, -2.17214, -2.00920, -1.90250, -1.78490, -1.80204, -1.74646, -1.56838, -1.34862, -1.06668, -0.96867, -0.90593, -0.83684, -0.84433, -0.63056, -0.46634, -0.18988, 0.02307, 0.23270, 0.50306, 0.67545, 0.84815, 1.04068, 1.09477, 1.16031, 1.21161, 1.12119, 0.95919, 0.80580, 0.65964, 0.44047, 0.36648, 0.51821, 0.56517, 0.52590, 0.43388, +-0.46649, -0.33618, -0.26224, -0.22072, -0.21597, -0.11225, 0.06548, 0.37073, 0.67319, 0.69808, 0.66003, 0.63418, 0.48200, 0.33665, 0.17217, 0.22029, 0.28440, 0.12851, -0.00076, -0.11566, -0.19974, -0.28682, -0.27977, -0.17336, -0.21082, -0.20559, -0.09507, 0.00501, 0.19609, 0.34908, 0.38345, 0.38197, 0.41244, 0.35950, 0.15937, -0.03300, -0.12912, -0.04442, 0.00415, 0.00615, -0.02779, -0.29655, -0.54027, -0.60668, -0.70008, -0.67519, -0.72650, -0.82919, -0.83366, -0.81662, -0.67653, -0.60095, -0.58583, -0.66603, -0.72702, -0.65253, -0.64886, -0.66933, -0.72024, -0.92299, -1.05185, -1.11195, -1.28192, -1.37777, -1.54877, -1.67702, -1.73762, -1.70591, -1.66015, -1.63906, -1.71057, -1.71928, -1.56074, -1.46718, -1.25897, -0.77323, -0.45277, -0.31402, -0.21011, -0.09306, 0.20534, 0.44189, 0.78554, 1.09518, 1.23949, 1.26944, 1.23552, 1.27333, 1.21324, 1.10673, 1.12021, 1.05177, 0.98434, 0.89522, 0.61758, 0.37273, 0.31527, 0.44380, 0.51560, 0.48634, 0.35336, 0.21340, 0.02315, -0.12390, -0.13693, -0.22053, -0.44625, -0.64197, -0.90726, -1.08165, -1.14626, -1.31218, -1.39099, -1.65439, -1.86333, -1.97887, -2.04150, -2.04275, -2.04349, -1.93455, -1.75459, -1.58651, -1.40614, -1.43207, -1.65837, -1.79227, -1.91441, -1.96349, -1.91620, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.82025, -0.98563, -1.23948, -1.29874, -1.35414, -1.45405, -1.43735, -1.54112, -1.57878, -1.70487, -1.80027, -1.79971, -1.81758, -1.78049, -1.68079, -1.49262, -1.31072, -1.23693, -1.06398, -0.84846, -0.63746, -0.26713, -0.03742, 0.02766, 0.06826, 0.12382, 0.15381, 0.26905, 0.42736, 0.70504, 0.80678, 0.68592, 0.57152, 0.46580, 0.34301, 0.34538, 0.33891, 0.16672, 0.06141, -0.16172, -0.24129, -0.37202, -0.53964, -0.62540, -0.62417, -0.53476, -0.45876, -0.43190, -0.55132, -0.78204, -0.84019, -0.83678, -0.90103, -0.96331, -1.14409, -1.39951, -1.54547, -1.62779, -1.71337, -1.74696, -1.96360, -2.24538, -2.50651, -2.73723, -2.86792, -3.02220, -3.19469, -3.22848, -3.30143, -3.50383, -3.64157, -3.75063, -3.71150, -3.63360, -3.60443, -3.56925, -3.64806, -3.81010, -3.96725, -3.97463, -3.83469, -3.70039, -3.48187, -3.32609, -3.30345, -3.25541, -3.18551, -3.11956, -2.88235, -2.55268, -2.44542, -2.50161, -2.63509, -2.61983, -2.57239, -2.63891, -2.72776, -2.89231, -3.12532, -3.18179, -3.09596, -3.07889, -3.08233, -3.12740, -2.99185, -2.73788, -2.55374, -2.37984, -2.33785, -2.22014, -1.98407, -1.64167, -1.34258, -1.34251, -1.38110, -1.35087, -1.33632, -1.24359, -1.11443, -1.00749, -0.93892, -0.82043, -0.67663, -0.51376, -0.43423, -0.38220, -0.29922, -0.38849, -0.56891, -0.77741, -1.06895, -1.17583, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.70549, -0.69648, -0.66693, -0.76980, -0.78784, -0.73839, -0.68596, -0.59844, -0.70286, -1.04839, -1.32800, -1.33829, -1.27266, -1.27280, -1.36558, -1.56259, -1.71434, -1.96726, -2.18372, -2.30551, -2.50401, -2.52693, -2.27204, -2.08139, -1.99299, -2.05011, -2.26240, -2.28851, -2.28564, -2.13883, -2.05636, -2.10085, -2.20765, -2.26957, -2.29869, -2.45645, -2.49153, -2.36253, -2.43299, -2.53349, -2.53628, -2.55729, -2.57797, -2.46600, -2.22850, -2.08228, -2.02831, -2.01648, -1.89945, -1.81609, -1.76567, -1.61375, -1.57241, -1.55744, -1.44410, -1.46708, -1.51541, -1.50610, -1.56024, -1.49567, -1.66918, -1.95039, -2.31520, -2.72624, -3.02198, -3.19764, -3.11570, -3.05176, -3.14262, -3.15123, -3.11548, -2.88219, -2.55604, -2.35048, -2.27969, -2.23680, -2.13850, -2.11718, -2.10131, -2.18736, -2.24959, -2.31845, -2.32986, -2.25693, -2.31574, -2.47100, -2.52436, -2.52061, -2.46263, -2.26439, -2.21085, -2.07859, -2.01710, -1.90942, -1.74525, -1.61772, -1.37515, -1.15702, -1.04243, -1.01357, -0.99057, -0.77721, -0.63705, -0.48555, -0.17731, 0.01893, 0.14458, 0.34983, 0.63743, 0.84902, 1.01509, 1.09826, 1.16058, 1.07333, 0.87000, 0.70401, 0.51880, 0.38702, 0.49744, 0.66464, 0.66848, 0.64128, 0.44901, +-0.72617, -0.79610, -0.74157, -0.65547, -0.62642, -0.48853, -0.29957, 0.03479, 0.36738, 0.40835, 0.38987, 0.42417, 0.34547, 0.25548, 0.11647, 0.13767, 0.18658, 0.04174, -0.00850, -0.05752, -0.11715, -0.16640, -0.15667, -0.07167, -0.07863, -0.05555, 0.04682, 0.12932, 0.31078, 0.46539, 0.44090, 0.47379, 0.52575, 0.35373, 0.18036, 0.11088, 0.06403, 0.18295, 0.16951, 0.14627, 0.16191, -0.00825, -0.15805, -0.24015, -0.37845, -0.37518, -0.42162, -0.50604, -0.53136, -0.55849, -0.43847, -0.41559, -0.42543, -0.45422, -0.54105, -0.56584, -0.56999, -0.48870, -0.46875, -0.69725, -0.94249, -1.05133, -1.21763, -1.15103, -1.20386, -1.42929, -1.53322, -1.49109, -1.52126, -1.52362, -1.57416, -1.46535, -1.20937, -1.12459, -1.00290, -0.64771, -0.38373, -0.21253, -0.00911, 0.20344, 0.47746, 0.62392, 0.92799, 1.21132, 1.30016, 1.34505, 1.31243, 1.35180, 1.34483, 1.32785, 1.31693, 1.16253, 1.03335, 0.93386, 0.67450, 0.60024, 0.64814, 0.62000, 0.48744, 0.37437, 0.16106, 0.05840, -0.04075, -0.12945, -0.10760, -0.19900, -0.45631, -0.69610, -0.99793, -1.15920, -1.17712, -1.29508, -1.35287, -1.63588, -1.86829, -2.01299, -2.08292, -1.94634, -1.86186, -1.80513, -1.72683, -1.55633, -1.35854, -1.35986, -1.60447, -1.74803, -1.90567, -1.90443, -1.83067, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.16499, -0.98378, -1.07252, -1.24557, -1.27687, -1.38160, -1.52362, -1.48005, -1.51734, -1.55780, -1.73490, -1.82500, -1.74046, -1.71361, -1.58697, -1.50417, -1.42789, -1.31413, -1.23722, -1.05253, -0.81407, -0.65487, -0.35057, -0.25534, -0.19136, -0.05881, 0.01634, 0.05627, 0.23729, 0.37625, 0.58088, 0.66156, 0.57512, 0.51592, 0.46952, 0.36035, 0.33581, 0.32085, 0.15594, 0.07168, -0.13338, -0.21459, -0.35276, -0.54264, -0.69159, -0.83899, -0.75486, -0.61634, -0.54693, -0.63018, -0.78071, -0.79836, -0.79843, -0.96111, -1.07626, -1.25341, -1.38341, -1.39895, -1.56015, -1.81838, -1.87591, -2.08469, -2.37722, -2.56938, -2.73883, -2.86314, -3.02161, -3.20620, -3.26074, -3.39027, -3.63416, -3.71669, -3.69893, -3.60094, -3.55466, -3.63492, -3.66966, -3.79008, -3.91348, -3.94284, -3.85839, -3.68174, -3.51300, -3.33811, -3.20105, -3.22604, -3.13980, -3.01900, -2.94894, -2.67916, -2.47134, -2.55804, -2.64040, -2.78040, -2.81277, -2.76391, -2.79985, -2.80162, -2.89178, -3.13032, -3.23520, -3.17680, -3.13155, -3.07656, -3.11863, -3.06444, -2.85755, -2.66204, -2.39474, -2.30094, -2.13848, -1.82927, -1.50912, -1.30825, -1.32288, -1.31393, -1.20728, -1.24478, -1.26750, -1.23883, -1.18528, -1.01405, -0.87756, -0.80731, -0.62888, -0.56930, -0.60828, -0.53020, -0.58256, -0.71437, -0.87430, -1.11035, -1.14888, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.59945, -0.65715, -0.71833, -0.78122, -0.72751, -0.67972, -0.72158, -0.76392, -0.91230, -1.26275, -1.42390, -1.38575, -1.43126, -1.43175, -1.44882, -1.67000, -1.83902, -2.08864, -2.21158, -2.20818, -2.34619, -2.42571, -2.30576, -2.16748, -2.03849, -2.00735, -2.17481, -2.24012, -2.29619, -2.18506, -2.14997, -2.20839, -2.17578, -2.10789, -2.15815, -2.35793, -2.40542, -2.29353, -2.39183, -2.53819, -2.48836, -2.49563, -2.44613, -2.31913, -2.20389, -2.09362, -2.02502, -2.08869, -1.97271, -1.82457, -1.69306, -1.50600, -1.51666, -1.55920, -1.51031, -1.56966, -1.55137, -1.45576, -1.46816, -1.49577, -1.81396, -2.13272, -2.47511, -2.80302, -2.93920, -3.05140, -3.03652, -3.04140, -3.10283, -3.10561, -3.11409, -2.99009, -2.73262, -2.58279, -2.43116, -2.34778, -2.39500, -2.45472, -2.35246, -2.39936, -2.44465, -2.55189, -2.59530, -2.47080, -2.45546, -2.54636, -2.61206, -2.65876, -2.61752, -2.42227, -2.35931, -2.22792, -2.12688, -1.93131, -1.75841, -1.71344, -1.48167, -1.26610, -1.20336, -1.20238, -1.07798, -0.83844, -0.76444, -0.74202, -0.47741, -0.31007, -0.14191, 0.11562, 0.35299, 0.55732, 0.81848, 0.88497, 0.86767, 0.78074, 0.63233, 0.55836, 0.51182, 0.46553, 0.57783, 0.65219, 0.57433, 0.57364, 0.47719, +-1.20203, -1.26119, -1.21877, -1.10787, -0.97918, -0.75101, -0.46869, -0.19860, 0.00444, 0.11400, 0.11119, 0.18358, 0.30623, 0.28147, 0.16426, 0.15779, 0.18633, 0.08647, 0.03836, 0.04218, -0.00114, -0.11608, -0.10856, 0.01666, 0.07536, 0.14309, 0.18621, 0.18575, 0.32741, 0.44562, 0.47663, 0.51519, 0.47707, 0.35544, 0.25347, 0.23813, 0.25048, 0.38789, 0.41653, 0.33971, 0.26137, 0.22143, 0.16596, 0.04934, 0.00248, -0.00303, -0.08999, -0.17657, -0.23698, -0.27523, -0.22076, -0.21268, -0.21678, -0.31933, -0.44105, -0.46632, -0.47302, -0.36850, -0.36500, -0.63239, -0.88930, -1.02475, -1.13452, -1.00030, -1.07310, -1.24390, -1.32752, -1.32438, -1.36562, -1.36839, -1.33460, -1.19090, -0.99336, -0.86877, -0.73731, -0.51390, -0.20384, 0.01315, 0.20847, 0.44569, 0.69454, 0.86609, 1.12944, 1.39314, 1.48072, 1.41822, 1.31394, 1.34671, 1.36509, 1.41328, 1.39295, 1.18782, 1.06080, 0.95878, 0.77957, 0.79270, 0.73586, 0.62659, 0.42878, 0.22939, 0.02738, -0.00359, 0.03464, -0.02328, -0.10962, -0.21987, -0.42547, -0.72851, -0.96195, -1.07433, -1.12715, -1.21675, -1.26792, -1.47186, -1.70711, -1.87142, -1.94478, -1.91015, -1.87434, -1.81252, -1.74836, -1.55565, -1.39662, -1.44734, -1.64026, -1.77435, -1.91322, -1.86035, -1.91489, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.15366, -1.07871, -1.16551, -1.22756, -1.31394, -1.36365, -1.41984, -1.40752, -1.42071, -1.48615, -1.62889, -1.74102, -1.68331, -1.61530, -1.54987, -1.52924, -1.45769, -1.35041, -1.22433, -1.03712, -0.87430, -0.76131, -0.54066, -0.49938, -0.36379, -0.27242, -0.16569, 0.00457, 0.19264, 0.35058, 0.52934, 0.63191, 0.60824, 0.45383, 0.33271, 0.30393, 0.21576, 0.25679, 0.22823, 0.12301, -0.08461, -0.24187, -0.39867, -0.61351, -0.82205, -0.97726, -0.96929, -0.90290, -0.78669, -0.76573, -0.80037, -0.79194, -0.86559, -1.08565, -1.24285, -1.41364, -1.39719, -1.41601, -1.64520, -1.87238, -1.97321, -2.16897, -2.42642, -2.55757, -2.63379, -2.82539, -3.06237, -3.16610, -3.27898, -3.41480, -3.55713, -3.68018, -3.66743, -3.59828, -3.55314, -3.64446, -3.72628, -3.81982, -3.94660, -3.99536, -3.87781, -3.66221, -3.44830, -3.27294, -3.17709, -3.19230, -3.04021, -2.87310, -2.72740, -2.54217, -2.51281, -2.61982, -2.73360, -2.89807, -2.94842, -2.87756, -2.80803, -2.80563, -2.92948, -3.06809, -3.21694, -3.22513, -3.09388, -3.04453, -3.09177, -3.06810, -2.86464, -2.63636, -2.33598, -2.13154, -1.94774, -1.73046, -1.48104, -1.33101, -1.33968, -1.30849, -1.20542, -1.25217, -1.29787, -1.31859, -1.23360, -1.08447, -1.04537, -0.93971, -0.75227, -0.69755, -0.71858, -0.61028, -0.55996, -0.70601, -0.95597, -1.14170, -1.19912, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.64707, -0.76909, -0.81501, -0.79229, -0.67218, -0.66627, -0.79019, -0.89426, -1.07986, -1.35920, -1.50792, -1.58643, -1.61706, -1.58425, -1.56954, -1.72913, -1.86846, -2.04306, -2.19623, -2.29278, -2.37685, -2.44738, -2.42307, -2.20924, -2.04787, -1.98828, -2.09039, -2.17003, -2.20811, -2.16058, -2.15338, -2.19730, -2.21505, -2.10929, -2.08935, -2.24689, -2.26358, -2.20757, -2.37176, -2.52079, -2.48168, -2.43122, -2.32926, -2.30028, -2.19403, -2.05792, -2.00810, -2.06021, -1.96279, -1.76085, -1.62636, -1.55050, -1.56096, -1.57366, -1.61592, -1.57971, -1.47583, -1.40690, -1.43236, -1.54865, -1.87300, -2.21168, -2.50626, -2.70828, -2.85962, -2.99158, -2.97357, -2.99182, -3.00783, -3.03164, -3.14262, -3.08824, -2.90757, -2.76032, -2.53944, -2.54980, -2.64506, -2.69727, -2.64118, -2.64918, -2.65229, -2.67712, -2.68017, -2.64173, -2.62561, -2.59444, -2.69069, -2.67978, -2.58298, -2.46464, -2.42040, -2.32518, -2.15680, -1.91498, -1.73222, -1.67806, -1.57979, -1.48345, -1.44400, -1.43738, -1.24261, -0.99667, -0.98457, -0.98095, -0.74951, -0.56885, -0.31387, -0.14957, 0.00770, 0.24723, 0.50526, 0.62296, 0.64324, 0.64117, 0.58452, 0.48097, 0.44583, 0.49792, 0.51659, 0.57832, 0.56796, 0.54831, 0.53516, +-1.57461, -1.54267, -1.53467, -1.45616, -1.34006, -1.07312, -0.72879, -0.51833, -0.36066, -0.15030, -0.06129, 0.09788, 0.26320, 0.19840, 0.11123, 0.10345, 0.11084, 0.04720, 0.01858, 0.06501, 0.11463, 0.02043, -0.00231, 0.12224, 0.16868, 0.24480, 0.31930, 0.27543, 0.34616, 0.43669, 0.48343, 0.52238, 0.50203, 0.51229, 0.42811, 0.40232, 0.40265, 0.48932, 0.56186, 0.45485, 0.36222, 0.48062, 0.51703, 0.41745, 0.34521, 0.23096, 0.15775, 0.09307, -0.00182, -0.09241, -0.13482, -0.17693, -0.15678, -0.24031, -0.36617, -0.37135, -0.44374, -0.42866, -0.40559, -0.58341, -0.77067, -0.87141, -1.00712, -0.97480, -1.07085, -1.08896, -1.13064, -1.12798, -1.17906, -1.23642, -1.15530, -1.04484, -0.89004, -0.67816, -0.48593, -0.25807, 0.05393, 0.17730, 0.36679, 0.60695, 0.79729, 0.94372, 1.13646, 1.35742, 1.52002, 1.52361, 1.38681, 1.36814, 1.30871, 1.28032, 1.32090, 1.25552, 1.17770, 1.12726, 0.93615, 0.85595, 0.70275, 0.62043, 0.41615, 0.19828, 0.02614, -0.01209, 0.07691, -0.03625, -0.20913, -0.23783, -0.30583, -0.51736, -0.69339, -0.93689, -1.07235, -1.17987, -1.28473, -1.46841, -1.67843, -1.83784, -1.88683, -1.85074, -1.86876, -1.78232, -1.72269, -1.64299, -1.54904, -1.59402, -1.75925, -1.80980, -1.91678, -1.89862, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.17536, -1.15718, -1.15786, -1.09062, -1.12349, -1.14408, -1.29927, -1.37159, -1.38453, -1.44613, -1.55885, -1.67801, -1.69888, -1.63319, -1.52648, -1.49946, -1.36615, -1.26831, -1.24291, -1.13362, -0.99168, -0.92687, -0.73317, -0.68857, -0.55286, -0.47952, -0.24285, 0.01207, 0.17478, 0.33177, 0.44705, 0.58762, 0.58431, 0.36143, 0.21861, 0.23972, 0.16618, 0.22558, 0.14871, 0.01154, -0.17642, -0.40155, -0.63851, -0.88520, -1.10391, -1.20922, -1.16087, -1.16870, -1.08034, -1.01586, -1.05945, -1.03457, -1.04021, -1.25259, -1.39123, -1.54406, -1.51645, -1.57784, -1.75049, -1.89006, -1.99318, -2.14158, -2.40448, -2.49909, -2.55158, -2.81925, -3.06766, -3.11353, -3.19082, -3.26388, -3.42910, -3.64747, -3.70363, -3.71444, -3.73431, -3.79337, -3.84622, -3.89371, -3.93136, -4.02149, -3.93223, -3.72096, -3.58617, -3.40532, -3.20985, -3.12708, -2.88617, -2.69911, -2.59747, -2.54071, -2.53567, -2.55631, -2.66913, -2.82781, -2.96494, -2.94775, -2.86588, -2.91736, -3.00431, -2.99139, -3.06885, -3.08494, -3.03202, -3.07330, -3.07363, -3.02417, -2.87301, -2.67514, -2.41065, -2.14182, -1.83599, -1.62449, -1.41704, -1.30481, -1.40697, -1.42665, -1.27186, -1.25896, -1.28143, -1.29147, -1.22075, -1.13520, -1.09246, -0.88338, -0.70737, -0.66335, -0.72132, -0.67643, -0.58484, -0.74579, -0.99420, -1.10434, -1.17548, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.70515, -0.84092, -0.85041, -0.85838, -0.81699, -0.81864, -0.92126, -1.00583, -1.13006, -1.36791, -1.57084, -1.72246, -1.69205, -1.68209, -1.68222, -1.81076, -1.95776, -2.07641, -2.30544, -2.47413, -2.45509, -2.41321, -2.34012, -2.15865, -2.14050, -2.10985, -2.16475, -2.25502, -2.29178, -2.26859, -2.27330, -2.25062, -2.22419, -2.10229, -2.02721, -2.19815, -2.27311, -2.20265, -2.29341, -2.40504, -2.32077, -2.26885, -2.22532, -2.25989, -2.10006, -1.94670, -1.87953, -1.90328, -1.90347, -1.74156, -1.70072, -1.70477, -1.58793, -1.48066, -1.48184, -1.44094, -1.48860, -1.48286, -1.53684, -1.72267, -2.03125, -2.33542, -2.55846, -2.64431, -2.74940, -2.92210, -2.90297, -2.93281, -2.99038, -2.99123, -3.06672, -3.08713, -2.95943, -2.88711, -2.75414, -2.81848, -2.82054, -2.84416, -2.83960, -2.83760, -2.85598, -2.76175, -2.74127, -2.79326, -2.75707, -2.65723, -2.68375, -2.62823, -2.63070, -2.56376, -2.52619, -2.47806, -2.32083, -2.06568, -1.88599, -1.80317, -1.69278, -1.66568, -1.62186, -1.61659, -1.48402, -1.24389, -1.16599, -1.16381, -0.93459, -0.73733, -0.47660, -0.35913, -0.18182, 0.04191, 0.25479, 0.42006, 0.48124, 0.58710, 0.57072, 0.40514, 0.37307, 0.49510, 0.52228, 0.59785, 0.53481, 0.51385, 0.59170, +-1.68424, -1.66633, -1.71294, -1.69039, -1.66346, -1.46543, -1.14540, -0.83017, -0.57746, -0.37230, -0.24891, -0.05831, 0.04425, -0.01929, -0.02267, -0.03649, 0.00469, 0.07222, 0.06653, 0.11861, 0.28140, 0.25939, 0.15695, 0.25233, 0.35744, 0.48492, 0.59640, 0.52507, 0.50751, 0.48779, 0.48017, 0.54318, 0.63006, 0.68722, 0.59687, 0.57143, 0.55556, 0.50924, 0.54937, 0.57728, 0.63072, 0.76250, 0.73294, 0.59456, 0.43284, 0.29259, 0.35115, 0.31588, 0.25517, 0.24049, 0.09749, -0.08400, -0.06749, -0.09402, -0.21822, -0.21053, -0.26861, -0.31655, -0.32041, -0.41252, -0.46825, -0.59798, -0.81668, -0.98765, -1.10510, -1.08183, -1.07371, -0.98058, -0.98972, -1.14813, -1.13333, -1.00493, -0.78373, -0.57525, -0.38476, -0.13738, 0.15392, 0.24165, 0.50643, 0.72172, 0.83702, 1.01398, 1.12478, 1.23678, 1.53295, 1.71960, 1.64109, 1.55620, 1.43658, 1.30247, 1.34249, 1.38766, 1.42235, 1.37538, 1.13218, 0.86707, 0.69202, 0.54721, 0.35022, 0.22110, 0.12863, -0.01023, -0.07371, -0.22973, -0.33173, -0.28784, -0.23670, -0.32673, -0.42836, -0.73344, -0.89286, -1.06993, -1.28111, -1.38314, -1.50933, -1.70411, -1.68755, -1.59556, -1.66512, -1.60048, -1.50079, -1.53927, -1.55666, -1.71470, -1.84713, -1.85493, -1.90042, -1.94702, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.31961, -1.16637, -1.07880, -0.96785, -0.96954, -1.01472, -1.27079, -1.36546, -1.35977, -1.37631, -1.33039, -1.33201, -1.49425, -1.47741, -1.34335, -1.30495, -1.14772, -1.01748, -1.06946, -1.09310, -1.08861, -1.03811, -0.91602, -0.82445, -0.71979, -0.55705, -0.28321, -0.10428, 0.02758, 0.18948, 0.24550, 0.36487, 0.37107, 0.30602, 0.21677, 0.17352, 0.06268, 0.06762, -0.07358, -0.13594, -0.24024, -0.49248, -0.72797, -0.93875, -1.20520, -1.26987, -1.18544, -1.27611, -1.35875, -1.30406, -1.32728, -1.27107, -1.25296, -1.38814, -1.53132, -1.68367, -1.76139, -1.82555, -1.93954, -2.05394, -2.10324, -2.13925, -2.39080, -2.52445, -2.62434, -2.81575, -3.00781, -3.12073, -3.17867, -3.17330, -3.33659, -3.50964, -3.60363, -3.75147, -3.83884, -3.80472, -3.84097, -3.84657, -3.76479, -3.89232, -3.92212, -3.74494, -3.66805, -3.45422, -3.19925, -2.97574, -2.72066, -2.61683, -2.65023, -2.67240, -2.61506, -2.58538, -2.64745, -2.68911, -2.86678, -3.00210, -3.03524, -3.03217, -2.97017, -2.88712, -2.89609, -2.89892, -2.95787, -3.01026, -2.87591, -2.79818, -2.69165, -2.49124, -2.38396, -2.16606, -1.72693, -1.46257, -1.30333, -1.21121, -1.34604, -1.41069, -1.29556, -1.23291, -1.21470, -1.22961, -1.19418, -1.12453, -1.00862, -0.79413, -0.65128, -0.59141, -0.69160, -0.81667, -0.78984, -0.81381, -0.87750, -0.95754, -1.10083, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.65854, -0.79194, -0.78760, -0.86337, -0.98168, -1.06787, -1.15619, -1.14226, -1.19520, -1.37753, -1.56638, -1.68388, -1.72605, -1.81437, -1.83910, -1.92677, -2.13249, -2.27324, -2.43915, -2.51559, -2.46498, -2.33556, -2.20975, -2.13858, -2.23592, -2.22570, -2.28130, -2.35417, -2.29786, -2.27241, -2.35407, -2.26346, -2.17132, -2.08591, -2.01990, -2.15953, -2.27279, -2.20170, -2.22394, -2.23056, -2.13668, -2.10264, -2.15466, -2.16919, -2.06822, -1.91580, -1.75330, -1.66870, -1.76962, -1.77726, -1.80366, -1.76946, -1.57950, -1.39058, -1.33334, -1.34390, -1.54703, -1.54360, -1.63758, -1.85991, -2.01980, -2.21968, -2.44810, -2.50394, -2.60984, -2.85678, -2.89922, -2.86970, -2.92148, -2.88912, -2.90938, -2.92496, -2.92514, -2.97785, -3.02469, -3.03090, -2.98809, -2.98764, -2.95612, -2.91184, -2.96964, -2.82979, -2.75683, -2.77031, -2.78557, -2.78704, -2.79109, -2.71541, -2.76694, -2.62684, -2.57503, -2.58432, -2.41379, -2.17030, -2.10840, -2.00736, -1.83076, -1.80984, -1.76896, -1.69352, -1.58328, -1.37116, -1.28920, -1.23331, -1.05789, -0.81986, -0.58946, -0.35927, -0.16890, -0.04817, 0.10490, 0.28825, 0.36425, 0.49815, 0.52186, 0.44846, 0.39251, 0.46881, 0.48410, 0.57123, 0.51550, 0.62343, 0.79307, +-1.63231, -1.67409, -1.78967, -1.81778, -1.73817, -1.52670, -1.25559, -0.88226, -0.65750, -0.54251, -0.44568, -0.28631, -0.15179, -0.13380, -0.10964, -0.17511, -0.16563, -0.02333, 0.07893, 0.22309, 0.35173, 0.27372, 0.17718, 0.32122, 0.50748, 0.67630, 0.79732, 0.72296, 0.64676, 0.50451, 0.48486, 0.60954, 0.73295, 0.80771, 0.74985, 0.74617, 0.82459, 0.78316, 0.75756, 0.85259, 0.92841, 0.93999, 0.80492, 0.59979, 0.45635, 0.39994, 0.51230, 0.44265, 0.38267, 0.44511, 0.34736, 0.17989, 0.12625, 0.00565, -0.10126, -0.05861, -0.08072, -0.13842, -0.18637, -0.27458, -0.28809, -0.50671, -0.72082, -0.89947, -1.04470, -1.04363, -1.02308, -0.91454, -0.83603, -0.94257, -0.98964, -0.86527, -0.65112, -0.55322, -0.39343, -0.19455, 0.11413, 0.29328, 0.58615, 0.72206, 0.74664, 0.89905, 1.02801, 1.20442, 1.55009, 1.70272, 1.73190, 1.71825, 1.61592, 1.43351, 1.38237, 1.37834, 1.45720, 1.37010, 1.18540, 0.97658, 0.79735, 0.55908, 0.33474, 0.20595, 0.20307, 0.10940, -0.07881, -0.25784, -0.31853, -0.33810, -0.23437, -0.28699, -0.28234, -0.43970, -0.58259, -0.85033, -1.12968, -1.19256, -1.21468, -1.32400, -1.28858, -1.35546, -1.48166, -1.42700, -1.34100, -1.45045, -1.54218, -1.80075, -1.88296, -1.90359, -1.88154, -1.82742, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.41017, -1.28770, -1.07056, -1.04854, -0.94399, -0.97705, -1.02227, -1.19216, -1.24438, -1.23122, -1.21612, -1.09021, -0.93735, -1.03354, -1.04400, -1.12717, -1.18404, -1.03623, -0.89320, -0.94866, -1.02166, -1.14400, -1.10752, -1.10474, -1.01199, -0.80444, -0.56239, -0.33830, -0.24362, -0.19352, -0.04169, 0.08174, 0.17119, 0.15669, 0.22045, 0.11346, 0.03049, -0.12888, -0.12936, -0.15466, -0.12762, -0.21041, -0.46819, -0.71653, -0.87941, -1.09748, -1.16692, -1.28733, -1.49376, -1.65247, -1.59315, -1.57347, -1.49826, -1.53396, -1.64363, -1.85054, -2.02842, -2.05780, -2.07128, -2.17299, -2.27824, -2.34452, -2.31915, -2.42721, -2.54532, -2.67912, -2.79593, -3.02365, -3.18194, -3.23296, -3.18651, -3.21881, -3.26496, -3.38269, -3.63692, -3.83971, -3.80790, -3.77640, -3.71143, -3.69002, -3.85868, -3.90717, -3.74102, -3.69789, -3.49522, -3.27650, -2.99675, -2.79740, -2.78334, -2.77927, -2.76963, -2.71602, -2.67959, -2.73984, -2.68159, -2.70734, -2.84745, -2.94600, -2.86235, -2.75825, -2.68988, -2.69215, -2.70061, -2.71827, -2.69517, -2.51393, -2.46750, -2.42811, -2.22716, -2.14109, -1.91754, -1.56467, -1.39481, -1.26194, -1.16621, -1.27761, -1.34045, -1.28995, -1.22230, -1.19992, -1.25579, -1.16383, -1.02051, -0.89346, -0.72527, -0.65200, -0.62027, -0.65162, -0.78274, -0.80319, -0.74453, -0.74365, -0.83977, -1.01947, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.75894, -0.88691, -0.86437, -0.98795, -1.20055, -1.36881, -1.48905, -1.44066, -1.49104, -1.54305, -1.55125, -1.60491, -1.72245, -1.90320, -1.97987, -1.97220, -2.12314, -2.29358, -2.38993, -2.41898, -2.42836, -2.28624, -2.19540, -2.12969, -2.15377, -2.13279, -2.21200, -2.29779, -2.22232, -2.17442, -2.25475, -2.22107, -2.26808, -2.20724, -2.11159, -2.20262, -2.32043, -2.29384, -2.33360, -2.28269, -2.22969, -2.14229, -2.10751, -2.09266, -2.04206, -1.89585, -1.73311, -1.51795, -1.51154, -1.60375, -1.66588, -1.66772, -1.60818, -1.42514, -1.37515, -1.33680, -1.44972, -1.41918, -1.56977, -1.83290, -1.93463, -2.02287, -2.17386, -2.28957, -2.60495, -2.91250, -2.98232, -2.93397, -2.97089, -2.92947, -2.92690, -2.89337, -3.01497, -3.10073, -3.09639, -3.04333, -3.02191, -3.01474, -2.99801, -2.87492, -2.81127, -2.66806, -2.59274, -2.59272, -2.75152, -2.84354, -2.88728, -2.77615, -2.71285, -2.52012, -2.52255, -2.60497, -2.50128, -2.27931, -2.22446, -2.14703, -2.13845, -2.13692, -2.03678, -1.87748, -1.73066, -1.52902, -1.48395, -1.36230, -1.22915, -0.92851, -0.57951, -0.23500, -0.03843, 0.02862, 0.07925, 0.22791, 0.37615, 0.50534, 0.55673, 0.60116, 0.47942, 0.51713, 0.48511, 0.58271, 0.67006, 0.88822, 1.03893, +-1.59896, -1.60677, -1.71164, -1.81796, -1.74239, -1.46508, -1.20968, -0.89223, -0.73541, -0.67191, -0.55903, -0.45164, -0.32509, -0.24705, -0.25396, -0.37450, -0.35231, -0.18954, -0.02638, 0.21066, 0.33104, 0.30219, 0.25047, 0.37865, 0.56909, 0.68721, 0.81509, 0.80193, 0.73430, 0.61126, 0.55401, 0.60851, 0.73822, 0.91500, 0.98799, 0.98746, 1.05241, 1.05373, 0.98065, 1.00384, 1.02431, 0.98161, 0.85615, 0.61854, 0.44920, 0.43014, 0.48852, 0.36299, 0.34059, 0.46021, 0.41682, 0.32965, 0.26999, 0.17685, 0.08685, 0.04706, -0.00757, -0.12214, -0.18833, -0.24266, -0.27776, -0.48586, -0.68467, -0.88375, -1.00700, -0.93385, -0.87395, -0.84058, -0.82002, -0.86396, -0.89491, -0.81216, -0.63361, -0.57595, -0.40879, -0.26711, -0.03982, 0.18230, 0.43364, 0.49630, 0.52182, 0.67691, 0.82028, 1.09628, 1.45005, 1.62553, 1.76315, 1.76608, 1.69986, 1.47435, 1.32563, 1.28178, 1.32809, 1.28753, 1.21348, 1.04943, 0.87826, 0.66620, 0.43702, 0.22923, 0.17081, 0.14405, -0.00387, -0.19282, -0.26322, -0.32675, -0.20989, -0.24455, -0.25811, -0.31543, -0.45151, -0.77364, -0.99838, -0.97383, -0.97125, -1.01189, -1.00560, -1.14784, -1.28028, -1.34851, -1.35070, -1.54076, -1.65886, -1.83740, -1.83917, -1.78651, -1.71068, -1.65643, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.27485, -1.21843, -1.06042, -1.08831, -0.98322, -0.99311, -1.07678, -1.17387, -1.17747, -1.16834, -1.10577, -0.89881, -0.69895, -0.69808, -0.71569, -0.90988, -1.02164, -1.01542, -0.93503, -1.01041, -1.06232, -1.13803, -1.11084, -1.15141, -1.09370, -0.91432, -0.67934, -0.40514, -0.26600, -0.26919, -0.24401, -0.17003, -0.09096, -0.14347, -0.08554, -0.18654, -0.23902, -0.33884, -0.34042, -0.28424, -0.22589, -0.34493, -0.57099, -0.74023, -0.89788, -1.09171, -1.20972, -1.45364, -1.66124, -1.87385, -1.82877, -1.82265, -1.78308, -1.81888, -1.94420, -2.17231, -2.33679, -2.36176, -2.36610, -2.39820, -2.43508, -2.52966, -2.59528, -2.68578, -2.73134, -2.83788, -2.93644, -3.15755, -3.27144, -3.24569, -3.23960, -3.24344, -3.22896, -3.37761, -3.64858, -3.83938, -3.87984, -3.84124, -3.73785, -3.71993, -3.76611, -3.80519, -3.69927, -3.74177, -3.65014, -3.45869, -3.15998, -2.94790, -2.88504, -2.84809, -2.84417, -2.77367, -2.67934, -2.71476, -2.69287, -2.67501, -2.71688, -2.77584, -2.65847, -2.54529, -2.49335, -2.47388, -2.54038, -2.56714, -2.49652, -2.35279, -2.32797, -2.23375, -2.02793, -1.91488, -1.65887, -1.39680, -1.24976, -1.16683, -1.14102, -1.24696, -1.31352, -1.24102, -1.12915, -1.09838, -1.13178, -1.05652, -0.95180, -0.82312, -0.62566, -0.55979, -0.62767, -0.69751, -0.75392, -0.76314, -0.74744, -0.77489, -0.86560, -0.98768, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.03343, -1.07382, -1.20191, -1.44785, -1.62127, -1.72433, -1.70363, -1.71277, -1.69628, -1.64943, -1.63822, -1.69971, -1.87229, -2.03229, -2.07881, -2.18739, -2.34890, -2.45723, -2.48323, -2.50018, -2.34115, -2.29232, -2.25051, -2.17159, -2.10303, -2.15511, -2.18506, -2.10937, -2.11498, -2.20106, -2.24307, -2.32249, -2.23309, -2.18147, -2.26127, -2.43462, -2.47672, -2.51059, -2.46307, -2.36901, -2.22224, -2.16442, -2.11402, -1.97920, -1.80016, -1.73612, -1.58196, -1.48475, -1.52541, -1.60669, -1.67440, -1.73035, -1.57253, -1.52557, -1.46662, -1.43495, -1.37532, -1.55245, -1.79243, -1.86221, -1.93469, -2.00760, -2.13884, -2.49612, -2.79270, -2.98156, -3.00826, -3.11349, -3.09869, -3.03036, -2.96366, -3.05743, -3.09491, -3.05772, -2.97971, -2.90716, -2.86388, -2.90217, -2.83198, -2.70407, -2.53598, -2.50236, -2.53391, -2.74402, -2.82573, -2.84579, -2.77723, -2.65123, -2.47436, -2.55915, -2.65987, -2.56858, -2.41184, -2.34556, -2.30881, -2.38231, -2.35483, -2.28180, -2.09252, -1.94425, -1.74205, -1.63005, -1.45363, -1.24975, -0.88824, -0.54288, -0.19296, 0.07988, 0.20330, 0.19145, 0.19166, 0.28809, 0.43657, 0.50564, 0.62828, 0.55813, 0.62345, 0.61635, 0.63740, 0.75932, 0.99132, 1.07153, +-1.69883, -1.67052, -1.65694, -1.79946, -1.81562, -1.53395, -1.31989, -1.05250, -0.84640, -0.74526, -0.60302, -0.57734, -0.51642, -0.38156, -0.32019, -0.44717, -0.47064, -0.33300, -0.18878, 0.09945, 0.28946, 0.40859, 0.46590, 0.53658, 0.69411, 0.73531, 0.77968, 0.80972, 0.77563, 0.70702, 0.67572, 0.64539, 0.69396, 0.86687, 1.13591, 1.22127, 1.22696, 1.24407, 1.09375, 0.99392, 0.97631, 0.95828, 0.91321, 0.64810, 0.41033, 0.42262, 0.49016, 0.36674, 0.32409, 0.44248, 0.42007, 0.38710, 0.35259, 0.30362, 0.21980, 0.09140, 0.04117, -0.09019, -0.21963, -0.28000, -0.31430, -0.50280, -0.68063, -0.93351, -1.10623, -1.09121, -0.96356, -0.90384, -0.92144, -0.90495, -0.91637, -0.89945, -0.73114, -0.63311, -0.42679, -0.36280, -0.29381, -0.07692, 0.17159, 0.28150, 0.35642, 0.53365, 0.68025, 0.93466, 1.23326, 1.44168, 1.65402, 1.68708, 1.72006, 1.56025, 1.35909, 1.25039, 1.23198, 1.16624, 1.20984, 1.09260, 0.93167, 0.67089, 0.45869, 0.25273, 0.09924, 0.13439, 0.09913, -0.08971, -0.14150, -0.16935, -0.04996, -0.11356, -0.24582, -0.28208, -0.36215, -0.60149, -0.77905, -0.76133, -0.81820, -0.88766, -0.90976, -1.05896, -1.17994, -1.34190, -1.35158, -1.49861, -1.63590, -1.77037, -1.72620, -1.69157, -1.58430, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.17188, -1.10002, -1.11667, -1.00070, -0.95033, -1.04429, -1.07057, -0.98844, -0.93720, -0.90317, -0.72712, -0.58877, -0.57923, -0.58476, -0.77161, -0.85251, -0.96112, -0.94593, -0.97813, -0.97726, -0.99240, -0.94218, -1.06915, -1.09118, -1.01700, -0.83163, -0.58599, -0.36708, -0.30867, -0.40411, -0.41780, -0.35030, -0.47202, -0.46840, -0.52152, -0.51100, -0.52398, -0.57085, -0.55289, -0.50194, -0.56193, -0.73472, -0.86053, -1.05570, -1.29046, -1.40932, -1.66450, -1.82254, -2.05946, -2.05210, -2.02868, -2.04043, -2.08250, -2.15972, -2.43185, -2.60059, -2.66881, -2.68634, -2.73713, -2.73377, -2.78372, -2.96872, -3.11864, -3.10164, -3.14533, -3.16494, -3.26063, -3.28419, -3.23595, -3.35987, -3.46008, -3.44995, -3.51307, -3.72669, -3.87349, -3.96257, -3.99469, -3.90172, -3.85468, -3.71398, -3.67067, -3.58551, -3.63893, -3.67902, -3.58859, -3.29458, -3.06536, -2.91489, -2.84714, -2.82937, -2.78212, -2.66514, -2.59172, -2.61380, -2.62498, -2.56070, -2.56783, -2.46331, -2.37453, -2.36184, -2.33472, -2.48169, -2.58406, -2.50828, -2.30464, -2.19434, -2.03815, -1.85624, -1.79110, -1.57040, -1.38672, -1.21442, -1.08617, -1.03323, -1.04231, -1.08791, -1.04265, -0.90552, -0.88418, -0.92238, -0.91467, -0.90827, -0.85375, -0.69020, -0.50538, -0.55997, -0.67626, -0.67686, -0.74629, -0.84528, -0.92891, -1.02068, -1.05593, -1.23900, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.29855, -1.29870, -1.46918, -1.65834, -1.74418, -1.75404, -1.77617, -1.74128, -1.72826, -1.71999, -1.78395, -1.85896, -2.04865, -2.26089, -2.39755, -2.56343, -2.70337, -2.71810, -2.71707, -2.51276, -2.45437, -2.45462, -2.30916, -2.15165, -2.12129, -2.13996, -2.10377, -2.14921, -2.22256, -2.29679, -2.34755, -2.20635, -2.17028, -2.18014, -2.36022, -2.53230, -2.62571, -2.61008, -2.52642, -2.28859, -2.19605, -2.10708, -1.99426, -1.81787, -1.81956, -1.83991, -1.73619, -1.68856, -1.75586, -1.80442, -1.87922, -1.75099, -1.73657, -1.71661, -1.56321, -1.40697, -1.47977, -1.71178, -1.82980, -1.95348, -2.00687, -2.07574, -2.35000, -2.58330, -2.82789, -2.87611, -3.00228, -3.06757, -3.01775, -2.92342, -3.00129, -2.95729, -2.94019, -2.91223, -2.91462, -2.81669, -2.80454, -2.84399, -2.74757, -2.54358, -2.51947, -2.56046, -2.75850, -2.82996, -2.85919, -2.90373, -2.77826, -2.54155, -2.53087, -2.63636, -2.60252, -2.54781, -2.52295, -2.48904, -2.56209, -2.49757, -2.43845, -2.20531, -1.98680, -1.75173, -1.56943, -1.30809, -1.11132, -0.77897, -0.53156, -0.26914, -0.05768, 0.15774, 0.24125, 0.14282, 0.15522, 0.31286, 0.36969, 0.56134, 0.63537, 0.77116, 0.81158, 0.69288, 0.72146, 0.92411, 1.04731, +-1.73326, -1.71152, -1.73177, -1.84709, -1.83948, -1.66926, -1.48460, -1.25671, -1.06511, -0.91712, -0.79822, -0.77651, -0.64213, -0.49272, -0.37252, -0.41282, -0.45202, -0.34991, -0.20562, 0.09889, 0.32521, 0.48061, 0.66565, 0.73619, 0.76564, 0.73188, 0.69154, 0.67728, 0.70997, 0.78692, 0.87822, 0.92481, 0.91144, 0.95202, 1.14228, 1.26217, 1.35180, 1.35277, 1.20278, 1.04692, 0.91563, 0.88691, 0.84135, 0.58806, 0.42806, 0.46281, 0.51172, 0.40341, 0.28132, 0.32843, 0.35455, 0.42283, 0.41562, 0.28141, 0.16237, 0.05054, -0.01804, -0.12195, -0.28529, -0.44468, -0.47360, -0.55832, -0.71626, -0.90850, -1.10925, -1.22574, -1.17391, -1.12261, -1.02855, -1.02055, -1.04114, -1.03933, -0.94766, -0.81299, -0.57807, -0.49280, -0.37972, -0.17744, -0.01336, 0.11677, 0.21413, 0.40541, 0.60336, 0.86366, 1.07432, 1.18939, 1.38163, 1.55136, 1.64546, 1.59370, 1.47184, 1.28315, 1.17444, 1.09285, 1.12154, 1.10994, 1.01551, 0.73519, 0.51301, 0.26756, 0.16502, 0.19175, 0.19187, 0.06414, -0.01945, -0.00723, 0.09058, -0.03234, -0.18929, -0.23691, -0.32736, -0.45724, -0.60394, -0.66345, -0.78261, -0.82043, -0.83068, -1.02587, -1.21120, -1.33189, -1.34686, -1.43943, -1.55255, -1.71784, -1.70896, -1.64510, -1.54161, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.01610, -1.02049, -1.04690, -0.95759, -0.91602, -0.89054, -0.78248, -0.67573, -0.61320, -0.65565, -0.59803, -0.55113, -0.47254, -0.44409, -0.62533, -0.69769, -0.76447, -0.82931, -0.91953, -0.92648, -0.95432, -0.92670, -0.99628, -1.04297, -0.98597, -0.82246, -0.67782, -0.49394, -0.51738, -0.57225, -0.57842, -0.58601, -0.71678, -0.83672, -0.92829, -0.87061, -0.84699, -0.83603, -0.81282, -0.85900, -0.86941, -0.96203, -1.07717, -1.31562, -1.51150, -1.57978, -1.84285, -2.05485, -2.21771, -2.24433, -2.26200, -2.29800, -2.37647, -2.48739, -2.74373, -2.91811, -2.97812, -2.94676, -3.02900, -3.03040, -3.12474, -3.27887, -3.40844, -3.46912, -3.44414, -3.39897, -3.40204, -3.32670, -3.34470, -3.52331, -3.64237, -3.72540, -3.71392, -3.83921, -3.93086, -3.99484, -3.99871, -3.91143, -3.94036, -3.84735, -3.68340, -3.53933, -3.56004, -3.61996, -3.62008, -3.44620, -3.20420, -2.97101, -2.83198, -2.68431, -2.60731, -2.51596, -2.50203, -2.52502, -2.48429, -2.42016, -2.34719, -2.27492, -2.31698, -2.36988, -2.39648, -2.51080, -2.54858, -2.54220, -2.31499, -2.08848, -1.90318, -1.76098, -1.68149, -1.46851, -1.36406, -1.28499, -1.07924, -0.92480, -0.89676, -0.91153, -0.89883, -0.84065, -0.81133, -0.77843, -0.75020, -0.70838, -0.71246, -0.68132, -0.55983, -0.54355, -0.53961, -0.56621, -0.70609, -0.90507, -1.13064, -1.24208, -1.24075, -1.36249, -1.41433, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.46289, -1.41246, -1.49602, -1.67322, -1.80599, -1.81321, -1.79416, -1.77232, -1.74120, -1.74601, -1.86429, -1.95731, -2.17124, -2.41179, -2.66066, -2.83596, -2.93708, -3.00902, -3.01963, -2.81556, -2.69035, -2.58516, -2.41781, -2.24525, -2.14088, -2.19107, -2.22847, -2.26254, -2.24839, -2.32818, -2.44415, -2.29518, -2.15833, -2.13785, -2.26572, -2.45979, -2.66832, -2.72196, -2.63712, -2.37222, -2.14013, -1.96729, -1.93289, -1.90584, -2.03329, -2.09314, -2.04596, -1.93531, -1.90550, -1.93194, -1.96948, -1.88714, -1.92725, -1.91541, -1.74893, -1.57726, -1.50099, -1.66842, -1.83030, -1.98277, -1.98050, -2.00353, -2.27520, -2.49379, -2.61770, -2.67446, -2.82129, -2.95094, -3.04017, -2.99107, -2.97262, -2.85616, -2.76539, -2.76579, -2.88943, -2.81726, -2.80860, -2.80057, -2.77244, -2.59702, -2.49806, -2.59977, -2.81489, -2.89982, -2.97271, -3.01403, -2.88544, -2.66867, -2.55302, -2.66466, -2.72332, -2.74054, -2.66455, -2.59101, -2.65572, -2.57971, -2.40205, -2.17389, -1.97218, -1.70888, -1.51319, -1.22547, -0.98228, -0.73398, -0.51395, -0.30894, -0.19131, 0.05316, 0.14655, 0.18368, 0.22515, 0.33573, 0.41892, 0.52451, 0.60837, 0.79542, 0.87473, 0.80199, 0.80855, 0.87773, 0.99694, +-1.79359, -1.76329, -1.82738, -1.88497, -1.80963, -1.72350, -1.56093, -1.42685, -1.31048, -1.12602, -1.02053, -0.95791, -0.74248, -0.63427, -0.51880, -0.44194, -0.35023, -0.22866, -0.16083, 0.05939, 0.28506, 0.44567, 0.62535, 0.66435, 0.64459, 0.60435, 0.65534, 0.72566, 0.76581, 0.94447, 1.04511, 1.08279, 1.11518, 1.11420, 1.15790, 1.26015, 1.42190, 1.40635, 1.32060, 1.14525, 0.94078, 0.91061, 0.78419, 0.52693, 0.42629, 0.40549, 0.38174, 0.27304, 0.15708, 0.19143, 0.17521, 0.25527, 0.30625, 0.18067, 0.00173, -0.15773, -0.21884, -0.25589, -0.34349, -0.44844, -0.54332, -0.58149, -0.78083, -1.01965, -1.15127, -1.24498, -1.25015, -1.22290, -1.09649, -1.17069, -1.21672, -1.24695, -1.22501, -1.01343, -0.75484, -0.57820, -0.34396, -0.19259, -0.16367, -0.10693, -0.01602, 0.21467, 0.39375, 0.64811, 0.86124, 0.98128, 1.14538, 1.33042, 1.44324, 1.47934, 1.48271, 1.42017, 1.24799, 1.14452, 1.05840, 0.95068, 0.93702, 0.78579, 0.63148, 0.41902, 0.39511, 0.33428, 0.26831, 0.14218, 0.00183, 0.09360, 0.17796, 0.02211, -0.11647, -0.21858, -0.38409, -0.47930, -0.56560, -0.57076, -0.74672, -0.79940, -0.75787, -0.89765, -1.14371, -1.33299, -1.40581, -1.47654, -1.54599, -1.57505, -1.59703, -1.50086, -1.41210, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.89937, -0.84871, -0.77015, -0.78271, -0.69215, -0.54531, -0.47643, -0.40591, -0.45389, -0.37865, -0.39117, -0.32222, -0.28344, -0.41472, -0.51309, -0.64197, -0.78231, -0.93288, -1.00105, -0.92583, -0.93072, -0.93773, -0.93805, -0.99679, -0.87348, -0.77658, -0.68604, -0.78758, -0.77972, -0.78058, -0.85778, -0.99491, -1.22319, -1.29895, -1.20783, -1.18070, -1.09360, -1.05009, -1.19722, -1.20774, -1.21821, -1.22638, -1.49408, -1.72813, -1.79756, -2.01599, -2.26990, -2.46372, -2.51633, -2.52723, -2.55892, -2.55663, -2.75251, -3.05073, -3.22498, -3.39759, -3.37129, -3.39906, -3.37018, -3.43435, -3.47309, -3.56997, -3.74410, -3.74704, -3.73909, -3.65798, -3.46802, -3.48355, -3.63211, -3.72929, -3.88673, -3.86765, -3.94343, -3.93301, -3.97428, -4.00082, -3.92135, -3.97831, -3.99572, -3.87901, -3.73085, -3.65604, -3.62552, -3.51147, -3.39173, -3.24746, -3.01187, -2.93596, -2.75024, -2.56006, -2.43089, -2.45043, -2.41896, -2.32223, -2.30961, -2.20809, -2.18326, -2.26560, -2.30804, -2.36518, -2.41039, -2.37571, -2.46419, -2.29935, -2.04993, -1.80430, -1.67059, -1.61759, -1.39162, -1.25471, -1.21999, -1.10111, -1.01685, -0.99980, -0.99048, -0.89462, -0.83603, -0.86188, -0.75476, -0.72794, -0.68610, -0.65173, -0.68349, -0.68024, -0.62183, -0.51833, -0.57529, -0.70996, -0.95923, -1.22445, -1.25059, -1.22834, -1.30907, -1.27382, -1.26826, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.69997, -1.75585, -1.83892, -1.90713, -1.95317, -1.89256, -1.93482, -1.97472, -1.93278, -2.02012, -2.13116, -2.29564, -2.46770, -2.80149, -2.97757, -3.05901, -3.16564, -3.11957, -2.94429, -2.80591, -2.63012, -2.51031, -2.38005, -2.22534, -2.23715, -2.27269, -2.39690, -2.41737, -2.47079, -2.57623, -2.46636, -2.34662, -2.32517, -2.36245, -2.42659, -2.54218, -2.68778, -2.64866, -2.48794, -2.32025, -2.06972, -1.98299, -2.01316, -2.16984, -2.16948, -2.14871, -2.01076, -1.95051, -1.99313, -1.93256, -1.86609, -1.93746, -1.96382, -1.92035, -1.83376, -1.68632, -1.72017, -1.77953, -1.96888, -2.00019, -2.03698, -2.28390, -2.52025, -2.64390, -2.71194, -2.84475, -2.96660, -2.99983, -3.03171, -2.97213, -2.83786, -2.78949, -2.74076, -2.82561, -2.74696, -2.69815, -2.59446, -2.62549, -2.52280, -2.43969, -2.62918, -2.78964, -2.85410, -2.92570, -2.92647, -2.85614, -2.78846, -2.71176, -2.81907, -2.85151, -2.93153, -2.87082, -2.76008, -2.71212, -2.58744, -2.40855, -2.23086, -2.08876, -1.86006, -1.54595, -1.28832, -1.01154, -0.78234, -0.67336, -0.44921, -0.25054, 0.02864, 0.13771, 0.32803, 0.42416, 0.51662, 0.61570, 0.57447, 0.64643, 0.85707, 0.96066, 0.99223, 0.99077, 0.89776, 0.90770, +-1.85550, -1.93400, -1.95871, -1.91665, -1.84197, -1.77050, -1.61122, -1.52921, -1.50516, -1.38260, -1.20011, -1.07102, -0.92388, -0.80426, -0.60932, -0.41493, -0.29654, -0.22710, -0.18852, -0.05042, 0.09577, 0.22139, 0.45650, 0.55013, 0.50983, 0.46880, 0.63183, 0.88496, 0.96883, 1.05884, 1.13202, 1.20366, 1.22519, 1.12716, 1.11900, 1.27818, 1.40702, 1.39886, 1.38767, 1.26308, 1.06180, 0.93493, 0.74287, 0.50297, 0.31485, 0.25607, 0.26422, 0.18055, 0.02595, -0.03679, -0.07621, -0.02220, 0.02182, -0.08567, -0.20386, -0.31511, -0.37259, -0.37340, -0.38532, -0.36154, -0.47256, -0.64118, -0.87161, -1.03171, -1.13297, -1.28215, -1.31629, -1.24152, -1.22948, -1.37158, -1.40786, -1.43167, -1.42677, -1.24197, -0.94965, -0.63596, -0.40660, -0.30371, -0.27169, -0.25385, -0.23962, -0.13963, 0.02899, 0.30693, 0.53544, 0.66633, 0.91314, 1.20037, 1.30751, 1.34855, 1.40361, 1.49345, 1.38220, 1.16563, 0.98105, 0.90615, 0.91104, 0.76359, 0.65225, 0.60498, 0.57644, 0.41128, 0.26744, 0.14494, 0.01468, 0.09714, 0.17474, 0.08242, -0.10935, -0.28252, -0.41295, -0.46665, -0.52976, -0.61089, -0.78340, -0.82469, -0.73992, -0.83668, -1.04447, -1.19382, -1.34916, -1.47703, -1.52089, -1.39492, -1.34054, -1.32664, -1.31411, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.71347, -0.63848, -0.60201, -0.56331, -0.50144, -0.37743, -0.21911, -0.23150, -0.26189, -0.27209, -0.18776, -0.15908, -0.31179, -0.43875, -0.54415, -0.73060, -0.95906, -1.06786, -0.89264, -0.83517, -0.88496, -0.93081, -0.96399, -0.87701, -0.94063, -1.03703, -1.08126, -1.06038, -1.09378, -1.17629, -1.29686, -1.51403, -1.58950, -1.52770, -1.43100, -1.34252, -1.36478, -1.47249, -1.41402, -1.34116, -1.40040, -1.68517, -1.94005, -2.05104, -2.27888, -2.51257, -2.60538, -2.63938, -2.68002, -2.71322, -2.67359, -2.87907, -3.25690, -3.53422, -3.71946, -3.70963, -3.79180, -3.83242, -3.75951, -3.70508, -3.82609, -4.03892, -4.07676, -4.07608, -3.96998, -3.75274, -3.63115, -3.73246, -3.89168, -3.97602, -3.86460, -3.88799, -3.95858, -4.06420, -4.10456, -4.02533, -4.11534, -4.17701, -3.99754, -3.81888, -3.70699, -3.59117, -3.35421, -3.16994, -3.15454, -3.09887, -3.02838, -2.79071, -2.59208, -2.51901, -2.46937, -2.34449, -2.26093, -2.26610, -2.16094, -2.12343, -2.19205, -2.26712, -2.25682, -2.22853, -2.24935, -2.33584, -2.16173, -1.92490, -1.75490, -1.67428, -1.59206, -1.33693, -1.19344, -1.17788, -1.08447, -1.07460, -1.12387, -1.12800, -0.99109, -0.86652, -0.93071, -0.92193, -0.85914, -0.74446, -0.73135, -0.88550, -0.93106, -0.81583, -0.73796, -0.77569, -0.83180, -1.02146, -1.22735, -1.20825, -1.10481, -1.13766, -1.20537, -1.27399, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.08256, -2.10500, -2.04434, -2.06995, -2.11771, -2.19052, -2.17228, -2.13177, -2.28817, -2.39349, -2.41342, -2.56607, -2.91086, -3.05162, -3.06931, -3.13955, -3.11050, -2.94833, -2.79300, -2.69423, -2.60798, -2.41295, -2.19895, -2.22757, -2.37645, -2.58117, -2.66370, -2.71066, -2.79773, -2.64614, -2.48764, -2.49589, -2.50511, -2.45868, -2.41544, -2.55098, -2.68439, -2.65709, -2.48393, -2.25098, -2.20282, -2.22303, -2.24502, -2.22190, -2.17004, -1.98223, -1.88480, -1.92138, -1.89615, -1.83850, -1.85075, -1.98615, -2.06342, -1.96076, -1.75862, -1.72607, -1.82379, -1.99494, -2.05896, -2.17185, -2.44274, -2.61780, -2.65245, -2.73310, -2.89321, -3.00104, -2.91343, -2.92150, -2.97855, -2.91040, -2.78758, -2.70013, -2.81649, -2.74352, -2.51588, -2.38009, -2.45004, -2.39823, -2.34912, -2.53862, -2.69264, -2.72962, -2.70082, -2.74745, -2.80397, -2.81147, -2.77292, -2.87398, -3.01224, -3.12101, -3.07687, -2.96235, -2.86318, -2.64998, -2.38843, -2.26498, -2.23341, -2.07864, -1.68692, -1.39638, -1.18390, -0.99906, -0.83699, -0.55910, -0.33508, -0.07069, 0.18527, 0.42791, 0.52066, 0.65178, 0.79978, 0.74412, 0.78038, 0.96550, 1.15575, 1.19453, 1.09657, 0.97708, 0.92260, +-1.84690, -1.96731, -2.05110, -1.95888, -1.87187, -1.83944, -1.71091, -1.70513, -1.72649, -1.60187, -1.36334, -1.22000, -1.08654, -0.87705, -0.68593, -0.48404, -0.26997, -0.17317, -0.12031, 0.02583, 0.11353, 0.15620, 0.32194, 0.39326, 0.43353, 0.48443, 0.61679, 0.86419, 1.12255, 1.25525, 1.22438, 1.25947, 1.32769, 1.23435, 1.14581, 1.29018, 1.40482, 1.37897, 1.35609, 1.25709, 1.11555, 0.94704, 0.65353, 0.37038, 0.18659, 0.24613, 0.24766, 0.11385, 0.03076, -0.00772, -0.09781, -0.11325, -0.14708, -0.27490, -0.36146, -0.47932, -0.49581, -0.39117, -0.41011, -0.45784, -0.50372, -0.62514, -0.88270, -0.95819, -1.01796, -1.19598, -1.36007, -1.39835, -1.45648, -1.56220, -1.54466, -1.57833, -1.61985, -1.45997, -1.19224, -0.88161, -0.65725, -0.45194, -0.38873, -0.40821, -0.38169, -0.31764, -0.21491, 0.08211, 0.35978, 0.51749, 0.79520, 1.07349, 1.20882, 1.35016, 1.34841, 1.30781, 1.30532, 1.20594, 0.99675, 0.97502, 1.02646, 0.91619, 0.71348, 0.65384, 0.65030, 0.45412, 0.23289, 0.08470, -0.01833, 0.10372, 0.16059, 0.05251, -0.14280, -0.20202, -0.31895, -0.46623, -0.52381, -0.55805, -0.70699, -0.72753, -0.61608, -0.67518, -0.83639, -1.02570, -1.25059, -1.29838, -1.30825, -1.25220, -1.15805, -1.08822, -1.16896, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.60011, -0.52784, -0.54446, -0.45464, -0.32039, -0.18378, -0.10587, -0.05917, -0.05962, 0.03312, 0.07815, -0.08021, -0.28065, -0.49087, -0.72756, -0.87007, -0.92880, -0.85617, -0.77550, -0.73684, -0.86890, -0.91027, -0.82383, -0.91659, -1.21525, -1.39044, -1.38175, -1.37884, -1.44313, -1.56702, -1.74891, -1.77395, -1.76596, -1.72725, -1.72466, -1.67777, -1.68584, -1.66055, -1.53668, -1.50082, -1.75342, -2.02810, -2.17715, -2.37160, -2.54244, -2.60334, -2.69656, -2.71309, -2.73455, -2.88739, -3.13053, -3.33804, -3.63015, -3.88740, -3.95388, -4.00656, -4.13911, -4.17116, -4.12500, -4.22580, -4.38961, -4.41701, -4.45130, -4.35348, -4.17389, -3.99494, -4.05299, -4.11287, -4.06261, -3.95259, -3.91636, -3.90134, -4.05082, -4.13601, -4.05034, -4.10486, -4.11791, -3.92483, -3.77903, -3.61602, -3.42685, -3.24590, -3.07265, -2.99627, -3.04937, -3.03700, -2.76083, -2.45853, -2.41408, -2.45723, -2.31043, -2.20361, -2.22694, -2.18328, -2.20530, -2.23673, -2.30408, -2.28244, -2.24321, -2.19713, -2.15928, -2.06166, -1.89174, -1.63491, -1.49743, -1.38184, -1.15368, -1.03887, -1.04402, -1.04479, -1.12554, -1.11341, -1.03866, -1.03968, -1.05002, -1.02276, -1.03430, -1.03428, -0.89175, -0.80835, -0.94658, -1.10311, -1.06778, -1.05111, -1.09368, -1.07945, -1.19961, -1.31234, -1.25103, -1.13038, -1.15492, -1.23552, -1.29814, -1.34463, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.20813, -2.28803, -2.27420, -2.15302, -2.16469, -2.30749, -2.24532, -2.15671, -2.33616, -2.58723, -2.65797, -2.77022, -3.05028, -3.15183, -3.13691, -3.14388, -3.08966, -2.99752, -2.90245, -2.78399, -2.56016, -2.35818, -2.24404, -2.24185, -2.37987, -2.65741, -2.74879, -2.72719, -2.75840, -2.63497, -2.57263, -2.58606, -2.51816, -2.50220, -2.54619, -2.58052, -2.63052, -2.70971, -2.59486, -2.40371, -2.34596, -2.40881, -2.42263, -2.35605, -2.24418, -2.01565, -1.88712, -1.91633, -1.94858, -1.96271, -1.98726, -2.11160, -2.05572, -1.93380, -1.80768, -1.72882, -1.75515, -1.88867, -1.95923, -2.13733, -2.43915, -2.58281, -2.60972, -2.66694, -2.74610, -2.87530, -2.88573, -2.83951, -2.85403, -2.92827, -2.83312, -2.68995, -2.71236, -2.69719, -2.48722, -2.31582, -2.35067, -2.34913, -2.34295, -2.46932, -2.54048, -2.57728, -2.59624, -2.69947, -2.71947, -2.79315, -2.85131, -2.85483, -2.90104, -3.05475, -3.06693, -2.95455, -2.84947, -2.62996, -2.41171, -2.32530, -2.21384, -2.10500, -1.92071, -1.66823, -1.35873, -1.18756, -0.98631, -0.64444, -0.30928, -0.08670, 0.14796, 0.39791, 0.48187, 0.63218, 0.81947, 0.83656, 0.95340, 1.11379, 1.26196, 1.22500, 1.17823, 1.09603, 0.91081, +-2.09440, -2.10638, -2.12424, -2.02287, -1.93374, -1.93036, -1.90148, -1.89388, -1.82029, -1.61786, -1.41704, -1.25022, -1.00996, -0.78907, -0.68544, -0.56879, -0.31278, -0.16058, -0.04831, 0.19031, 0.27123, 0.21150, 0.24659, 0.33436, 0.48603, 0.62837, 0.68359, 0.77294, 1.08168, 1.30090, 1.27792, 1.22758, 1.30907, 1.33398, 1.27014, 1.34962, 1.41601, 1.35348, 1.18060, 1.09785, 1.09462, 1.03557, 0.72810, 0.43053, 0.37462, 0.45961, 0.35055, 0.11308, 0.07610, 0.08687, -0.06027, -0.14138, -0.25948, -0.43582, -0.53821, -0.62717, -0.62915, -0.50869, -0.53210, -0.69744, -0.73833, -0.77895, -0.98648, -1.07933, -1.18523, -1.31024, -1.48825, -1.59873, -1.65993, -1.63589, -1.61394, -1.62735, -1.62061, -1.44626, -1.25313, -1.07061, -0.78866, -0.53582, -0.48573, -0.51130, -0.44258, -0.34684, -0.29784, 0.02704, 0.34982, 0.48853, 0.65059, 0.84364, 1.02682, 1.25634, 1.26411, 1.08832, 1.11880, 1.13131, 0.98893, 0.94745, 0.97194, 0.93289, 0.68429, 0.58987, 0.58082, 0.50924, 0.27229, 0.09713, 0.06942, 0.23229, 0.24778, 0.05151, -0.01473, 0.03763, -0.13636, -0.41444, -0.49600, -0.44482, -0.57355, -0.58679, -0.54567, -0.67068, -0.83952, -1.03842, -1.22345, -1.17162, -1.11895, -1.17209, -1.14157, -1.06878, -1.14888, -1.26465, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.47428, -0.41660, -0.35746, -0.22674, -0.19090, -0.15701, -0.03348, 0.11460, 0.05842, 0.11673, 0.18348, 0.04308, -0.20118, -0.47199, -0.67461, -0.73450, -0.73243, -0.78250, -0.75569, -0.73078, -0.91187, -0.99776, -0.96832, -0.94709, -1.23879, -1.47551, -1.56091, -1.51357, -1.58939, -1.76418, -1.83446, -1.75190, -1.75824, -1.88313, -1.89316, -1.74440, -1.75887, -1.87702, -1.85993, -1.78975, -2.00918, -2.25721, -2.39370, -2.53748, -2.67394, -2.74578, -2.85694, -2.86516, -2.86367, -3.13899, -3.38700, -3.45821, -3.66884, -3.96188, -4.17594, -4.19522, -4.33192, -4.45090, -4.51903, -4.57408, -4.64806, -4.67295, -4.67422, -4.56057, -4.42591, -4.33156, -4.30201, -4.21104, -4.19987, -4.21222, -4.14190, -3.96716, -4.05295, -4.11231, -4.00660, -4.03538, -4.04292, -3.89631, -3.74108, -3.57879, -3.37605, -3.24737, -3.09107, -2.90039, -2.89791, -2.90865, -2.72588, -2.39011, -2.29002, -2.33985, -2.23681, -2.10258, -2.13297, -2.22264, -2.25863, -2.19234, -2.20104, -2.27977, -2.28933, -2.13174, -2.05415, -2.08807, -2.00849, -1.66468, -1.45530, -1.31388, -1.12834, -1.05337, -1.09417, -1.15957, -1.17892, -1.05293, -0.89282, -0.97721, -1.14919, -1.10470, -1.10514, -1.16315, -1.11415, -0.98228, -0.93537, -1.03111, -1.10451, -1.17393, -1.23949, -1.27472, -1.32663, -1.34339, -1.30839, -1.30217, -1.32626, -1.26364, -1.32346, -1.50771, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.26905, -2.36523, -2.20341, -2.16279, -2.31685, -2.32599, -2.25897, -2.36322, -2.64731, -2.78910, -2.87373, -3.03183, -3.18401, -3.20918, -3.14188, -3.03553, -3.04331, -3.03465, -2.78455, -2.50830, -2.42336, -2.49707, -2.49671, -2.55053, -2.78997, -2.77452, -2.65951, -2.65247, -2.58963, -2.58068, -2.55671, -2.46422, -2.51255, -2.70623, -2.70109, -2.60461, -2.64613, -2.65862, -2.58225, -2.44850, -2.45675, -2.46139, -2.43156, -2.31483, -2.16678, -2.03007, -1.95550, -1.95349, -2.02875, -2.13360, -2.11666, -1.94423, -1.86828, -1.87422, -1.83950, -1.80105, -1.89869, -1.89250, -2.01928, -2.32920, -2.51249, -2.55177, -2.55507, -2.56720, -2.68186, -2.81081, -2.77639, -2.76955, -2.90652, -2.91756, -2.80606, -2.67346, -2.66040, -2.54274, -2.43300, -2.37804, -2.43069, -2.45419, -2.42901, -2.37349, -2.41789, -2.59961, -2.65573, -2.62112, -2.76769, -2.90809, -2.84291, -2.73263, -2.87868, -2.89448, -2.78019, -2.73620, -2.62619, -2.48585, -2.35845, -2.11691, -1.97321, -1.99377, -1.84356, -1.49675, -1.26153, -1.06189, -0.80066, -0.41946, -0.18400, 0.06787, 0.29020, 0.44666, 0.59404, 0.76080, 0.90985, 1.14634, 1.30751, 1.28476, 1.20795, 1.21329, 1.09782, 0.82711, +-2.33448, -2.33917, -2.25461, -2.14750, -2.07903, -2.08147, -2.09502, -1.98582, -1.88962, -1.75016, -1.54027, -1.25279, -0.98140, -0.85635, -0.67543, -0.46776, -0.26944, -0.16245, -0.05618, 0.18950, 0.31588, 0.24236, 0.27256, 0.46174, 0.59304, 0.72651, 0.81430, 0.87275, 1.11551, 1.30055, 1.40484, 1.41680, 1.41126, 1.39234, 1.30758, 1.29910, 1.26462, 1.16004, 0.90979, 0.92572, 0.98546, 0.94717, 0.77699, 0.64412, 0.63279, 0.55252, 0.42152, 0.24891, 0.12881, 0.02255, -0.20457, -0.35882, -0.45709, -0.59864, -0.68292, -0.68050, -0.75904, -0.75381, -0.71567, -0.81925, -0.89926, -0.99334, -1.13694, -1.17806, -1.38846, -1.55789, -1.70017, -1.78823, -1.87367, -1.80211, -1.80119, -1.68774, -1.59554, -1.51457, -1.33272, -1.08718, -0.77564, -0.65650, -0.57872, -0.44697, -0.38548, -0.35168, -0.30399, 0.01341, 0.36842, 0.49742, 0.52983, 0.68815, 0.82576, 0.98489, 1.10520, 1.06274, 1.10118, 1.05678, 0.92039, 0.92981, 0.87050, 0.77565, 0.53457, 0.46046, 0.38729, 0.40278, 0.19567, 0.09699, 0.12356, 0.14877, 0.13820, 0.04289, 0.08980, 0.06303, -0.09987, -0.22528, -0.29376, -0.31031, -0.46529, -0.55162, -0.59539, -0.75980, -0.94389, -1.05014, -1.19246, -1.20279, -1.09052, -1.04908, -1.04409, -1.04830, -1.11299, -1.11881, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.16952, -0.13656, -0.14789, 0.01873, 0.15643, 0.19504, 0.03964, 0.00477, 0.08791, 0.04100, -0.16166, -0.32524, -0.48452, -0.67884, -0.72445, -0.72611, -0.71682, -0.77776, -0.98020, -0.98452, -1.02964, -1.04713, -1.31529, -1.52181, -1.72171, -1.71515, -1.83039, -1.96869, -1.89429, -1.83785, -1.85746, -1.93350, -1.84849, -1.77499, -1.87820, -1.94784, -2.03633, -2.15484, -2.41182, -2.66532, -2.76529, -2.81852, -2.94481, -2.96066, -3.02775, -3.14563, -3.14744, -3.30231, -3.48142, -3.56678, -3.76709, -3.93969, -4.21396, -4.35339, -4.53049, -4.62086, -4.77392, -4.84132, -4.90494, -4.91423, -4.81616, -4.76848, -4.70241, -4.56578, -4.40531, -4.34948, -4.47623, -4.40767, -4.22706, -4.03687, -4.04556, -4.06785, -3.96309, -3.98572, -4.08217, -3.96135, -3.76272, -3.70492, -3.51942, -3.27319, -3.02966, -2.78119, -2.73962, -2.66177, -2.55357, -2.38183, -2.33694, -2.33938, -2.28810, -2.18892, -2.23926, -2.36811, -2.28326, -2.19377, -2.23385, -2.29010, -2.24795, -2.12539, -2.14009, -2.11393, -1.99277, -1.75129, -1.61417, -1.50494, -1.33847, -1.21804, -1.26097, -1.29334, -1.19699, -1.12034, -0.98387, -0.96132, -1.08037, -1.07793, -1.11884, -1.09972, -1.04651, -0.99721, -0.93560, -0.95848, -1.08044, -1.23630, -1.34206, -1.44108, -1.40464, -1.44113, -1.56856, -1.59512, -1.49986, -1.36441, -1.48269, -1.60584, -1.66561, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.25751, -2.29291, -2.17089, -2.18498, -2.29037, -2.30291, -2.36436, -2.50790, -2.73027, -2.82565, -2.90927, -3.00134, -3.19108, -3.18245, -3.11141, -3.11028, -3.14196, -3.06669, -2.80475, -2.70603, -2.66034, -2.67317, -2.72464, -2.82006, -2.99790, -2.91874, -2.72715, -2.67744, -2.61690, -2.53745, -2.54459, -2.53330, -2.52406, -2.62855, -2.62133, -2.54831, -2.53515, -2.52015, -2.56783, -2.47955, -2.42974, -2.38583, -2.45313, -2.41374, -2.37395, -2.17338, -1.99546, -2.02853, -2.07772, -2.09454, -2.03805, -2.01389, -1.93527, -1.81574, -1.83007, -1.89745, -2.01363, -1.99161, -2.02816, -2.29238, -2.52333, -2.52229, -2.54161, -2.63028, -2.67682, -2.70099, -2.67321, -2.73760, -2.86817, -2.81128, -2.78667, -2.70787, -2.71733, -2.64382, -2.65157, -2.58196, -2.66753, -2.61442, -2.46017, -2.45016, -2.47187, -2.56759, -2.54221, -2.63051, -2.80521, -2.80549, -2.73977, -2.68118, -2.78899, -2.80010, -2.66736, -2.60926, -2.57095, -2.40735, -2.27076, -2.11497, -1.93823, -1.87843, -1.73630, -1.44093, -1.17850, -0.88390, -0.75841, -0.55025, -0.35640, -0.04746, 0.14126, 0.35970, 0.50011, 0.69767, 0.91618, 1.04879, 1.19108, 1.21622, 1.19930, 1.08979, 0.91310, 0.82670, +-2.40727, -2.39584, -2.29726, -2.20779, -2.18506, -2.15099, -2.15332, -2.14415, -2.03768, -1.83857, -1.65829, -1.43014, -1.18928, -0.99643, -0.70070, -0.47053, -0.27265, -0.11142, -0.00344, 0.12584, 0.20912, 0.22619, 0.30711, 0.51954, 0.71933, 0.85096, 0.89307, 0.97881, 1.17734, 1.30118, 1.45965, 1.56130, 1.55649, 1.51565, 1.35167, 1.22054, 1.08056, 0.96720, 0.79739, 0.75181, 0.82175, 0.96227, 0.92725, 0.81052, 0.73748, 0.61403, 0.51660, 0.33436, 0.13275, -0.04235, -0.33134, -0.59722, -0.71696, -0.74207, -0.76665, -0.77976, -0.86383, -0.92908, -0.94032, -0.96096, -1.02196, -1.17676, -1.33188, -1.35446, -1.57768, -1.73808, -1.85525, -1.93907, -2.02642, -1.95703, -1.90143, -1.84447, -1.73567, -1.54958, -1.34675, -1.14959, -0.88963, -0.74245, -0.56934, -0.42062, -0.38635, -0.29166, -0.16178, 0.10054, 0.38124, 0.51798, 0.49902, 0.54212, 0.65492, 0.79123, 0.89200, 0.96116, 1.04009, 0.95518, 0.76442, 0.76459, 0.68948, 0.60619, 0.43998, 0.36304, 0.26106, 0.29412, 0.19936, 0.02854, -0.03484, 0.00423, 0.01874, -0.05899, -0.02708, -0.04455, -0.09445, -0.11961, -0.17325, -0.15184, -0.27444, -0.46891, -0.67372, -0.86021, -0.98725, -1.07637, -1.14239, -1.11823, -1.07352, -1.00750, -0.98093, -1.00728, -1.07158, -1.00614, -0.99154, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.24958, -0.13629, 0.11760, 0.20992, 0.21988, 0.06987, -0.03929, -0.01857, 0.00750, -0.07572, -0.20689, -0.35149, -0.56249, -0.78685, -0.85772, -0.85243, -0.92040, -1.07453, -1.02249, -1.06124, -1.07340, -1.30035, -1.53311, -1.79829, -1.90238, -1.96235, -2.09109, -2.06343, -1.95030, -1.89910, -1.97073, -1.92697, -1.88925, -1.94202, -1.99793, -2.25480, -2.48905, -2.70480, -2.93201, -3.04101, -3.06053, -3.12556, -3.18400, -3.26293, -3.33760, -3.40687, -3.53102, -3.62215, -3.70640, -3.91518, -4.02579, -4.26721, -4.44971, -4.63079, -4.72692, -4.88210, -4.98914, -5.01550, -5.07330, -5.08554, -5.00796, -4.85817, -4.71194, -4.59285, -4.57244, -4.63085, -4.44502, -4.23959, -4.00406, -3.87516, -3.85887, -3.83770, -3.92525, -4.07493, -4.07099, -3.94633, -3.82596, -3.62874, -3.35767, -3.00298, -2.67699, -2.60228, -2.49685, -2.43417, -2.37896, -2.36023, -2.35911, -2.35272, -2.35369, -2.39179, -2.50962, -2.49447, -2.35196, -2.26686, -2.29838, -2.34947, -2.29604, -2.22347, -2.06409, -1.95916, -1.80951, -1.69539, -1.62877, -1.54283, -1.42811, -1.39488, -1.40498, -1.31971, -1.20923, -1.11522, -1.09624, -1.11172, -1.10016, -1.15627, -1.08432, -0.96846, -0.92006, -0.86970, -0.92058, -1.08440, -1.29986, -1.40674, -1.51994, -1.63498, -1.72169, -1.79478, -1.81174, -1.75402, -1.63028, -1.63427, -1.62328, -1.68484, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.30659, -2.36185, -2.34184, -2.23101, -2.25661, -2.32570, -2.33685, -2.46050, -2.60253, -2.76433, -2.81240, -2.86829, -2.90059, -3.03685, -3.18949, -3.18970, -3.10541, -3.10621, -3.09699, -2.96211, -2.91879, -2.85187, -2.86478, -2.93719, -2.96794, -3.04778, -2.99640, -2.84044, -2.73153, -2.64655, -2.61386, -2.60755, -2.60099, -2.60606, -2.58948, -2.52626, -2.48886, -2.48898, -2.43610, -2.47081, -2.35333, -2.25731, -2.22194, -2.33477, -2.36043, -2.31440, -2.24046, -2.09041, -1.97023, -1.94322, -1.98839, -2.02440, -2.05329, -1.91119, -1.76062, -1.78967, -1.82572, -1.92928, -1.97773, -2.04613, -2.26797, -2.51283, -2.62771, -2.66376, -2.70507, -2.76183, -2.72514, -2.68440, -2.77222, -2.89274, -2.78350, -2.75505, -2.68990, -2.72295, -2.75948, -2.83677, -2.79305, -2.77712, -2.76753, -2.66020, -2.54843, -2.49754, -2.57266, -2.57135, -2.65897, -2.73406, -2.67940, -2.66969, -2.59694, -2.61471, -2.64836, -2.57739, -2.49066, -2.42400, -2.31652, -2.18659, -2.03720, -1.95239, -1.84511, -1.62986, -1.32265, -1.06454, -0.75451, -0.67341, -0.54791, -0.37786, -0.11743, 0.05907, 0.26787, 0.47754, 0.61437, 0.70642, 0.83610, 1.01432, 1.03136, 1.01081, 0.91750, 0.83034, 0.87897, +-2.35329, -2.33632, -2.26756, -2.26074, -2.28118, -2.14959, -2.03095, -2.08484, -2.08018, -1.89309, -1.73774, -1.60680, -1.43048, -1.14589, -0.82671, -0.69168, -0.48728, -0.22294, -0.00018, 0.04310, 0.04584, 0.18668, 0.40591, 0.67842, 0.89781, 0.96947, 0.95896, 1.10921, 1.28478, 1.30698, 1.40424, 1.49499, 1.49025, 1.50469, 1.37614, 1.15646, 0.90799, 0.83369, 0.88349, 0.87107, 0.86243, 1.05712, 1.10100, 0.97153, 0.80142, 0.65516, 0.57458, 0.31272, 0.05034, -0.18518, -0.44701, -0.70979, -0.88876, -0.82944, -0.74772, -0.70602, -0.76735, -0.90703, -1.00245, -0.96775, -0.96820, -1.20954, -1.44408, -1.55073, -1.77944, -1.87750, -1.94774, -2.03205, -2.13307, -2.04681, -1.88378, -1.83293, -1.79000, -1.57234, -1.33231, -1.18165, -0.97723, -0.75133, -0.51015, -0.50719, -0.51805, -0.31907, -0.01994, 0.26657, 0.40256, 0.53060, 0.57369, 0.64199, 0.72202, 0.73979, 0.69660, 0.75304, 0.87774, 0.82347, 0.64443, 0.57232, 0.43619, 0.37696, 0.34559, 0.29512, 0.16430, 0.20004, 0.21661, 0.06562, -0.14765, -0.18173, -0.08964, -0.09073, -0.08706, -0.11412, -0.07687, -0.13575, -0.22118, -0.16623, -0.17772, -0.31143, -0.63394, -0.79639, -0.80810, -0.77449, -0.74554, -0.77216, -0.87265, -0.90545, -0.83915, -0.84310, -0.91516, -0.86243, -0.85437, -0.72341, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.14563, 0.04029, 0.02769, 0.03659, 0.02237, 0.04866, -0.01100, 0.02419, 0.01600, -0.05026, -0.17604, -0.38251, -0.74737, -0.99229, -1.04128, -1.10438, -1.17056, -1.10519, -1.15490, -1.19028, -1.38913, -1.63170, -1.95652, -2.11659, -2.02920, -1.98190, -2.02154, -2.00800, -1.91371, -1.95261, -2.00743, -2.03996, -2.01065, -2.14863, -2.55597, -2.82289, -2.91797, -2.92935, -3.02828, -3.08214, -3.11033, -3.18153, -3.25010, -3.29889, -3.47212, -3.67192, -3.72223, -3.81691, -4.06153, -4.20473, -4.44309, -4.64592, -4.81202, -4.91184, -5.05321, -5.14545, -5.09992, -5.10961, -5.22515, -5.19579, -4.95684, -4.78515, -4.74561, -4.75003, -4.62241, -4.37538, -4.24020, -4.01718, -3.80544, -3.66393, -3.70444, -3.80506, -3.91962, -3.98187, -3.95648, -3.80697, -3.59581, -3.37538, -2.96317, -2.61464, -2.55636, -2.48089, -2.50259, -2.53050, -2.46215, -2.40510, -2.45224, -2.56678, -2.55308, -2.54373, -2.62145, -2.56801, -2.38450, -2.32990, -2.42732, -2.40598, -2.18096, -1.91970, -1.89238, -1.85082, -1.75173, -1.63485, -1.57152, -1.47415, -1.35638, -1.30049, -1.23167, -1.14000, -1.15733, -1.25014, -1.21116, -1.17007, -1.25054, -1.18680, -1.05273, -0.99354, -0.95539, -1.05408, -1.25760, -1.48354, -1.52251, -1.56731, -1.81233, -2.01462, -1.98641, -1.90370, -1.89740, -1.85018, -1.76852, -1.70625, -1.85934, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.39486, -2.55238, -2.54560, -2.40647, -2.37354, -2.37894, -2.42980, -2.62324, -2.72058, -2.80475, -2.86150, -2.91506, -2.83423, -2.81094, -3.01587, -3.13283, -3.00791, -2.90599, -2.95062, -2.99613, -2.99958, -2.95382, -3.05164, -3.11503, -3.04588, -2.96995, -2.90345, -2.84935, -2.71944, -2.60653, -2.58515, -2.58238, -2.64271, -2.71797, -2.63173, -2.47611, -2.46957, -2.51712, -2.46983, -2.45150, -2.25952, -2.12395, -2.12894, -2.24852, -2.19441, -2.02606, -2.00999, -2.00938, -1.87999, -1.77591, -1.81297, -1.87242, -1.88597, -1.74395, -1.75952, -1.81241, -1.75542, -1.78433, -1.83961, -2.04631, -2.27448, -2.50830, -2.69427, -2.73045, -2.72217, -2.79553, -2.79558, -2.75953, -2.83568, -2.95406, -2.90273, -2.89460, -2.80077, -2.80303, -2.90425, -3.01587, -2.92973, -2.72192, -2.66363, -2.70068, -2.62021, -2.50252, -2.50158, -2.50887, -2.55312, -2.51970, -2.57239, -2.65683, -2.57755, -2.49288, -2.43796, -2.45285, -2.36331, -2.24065, -2.10152, -1.95979, -1.87718, -1.93914, -1.86457, -1.55415, -1.22060, -1.01628, -0.80054, -0.73966, -0.58228, -0.38240, -0.20443, -0.11038, 0.06549, 0.37103, 0.59367, 0.62655, 0.69676, 0.87876, 0.88988, 0.88476, 0.87126, 0.90180, 0.90305, +-2.16867, -2.27030, -2.24734, -2.22402, -2.17272, -2.06956, -1.99543, -2.00581, -2.05138, -1.99281, -1.83005, -1.64310, -1.52508, -1.32572, -0.98267, -0.82206, -0.62729, -0.37429, -0.13676, -0.03847, 0.01632, 0.17496, 0.42976, 0.69647, 0.87162, 0.95320, 0.99777, 1.17179, 1.29440, 1.26863, 1.27459, 1.34687, 1.31464, 1.31661, 1.31833, 1.20984, 1.00550, 0.85011, 0.86400, 0.93483, 0.92794, 1.01060, 1.05295, 1.03262, 0.81894, 0.54893, 0.49611, 0.32059, 0.05895, -0.25204, -0.54259, -0.71412, -0.85470, -0.83799, -0.74869, -0.67236, -0.70148, -0.78651, -0.85137, -0.80242, -0.84101, -1.12815, -1.42501, -1.55508, -1.75710, -1.89485, -1.95433, -1.96989, -2.00028, -1.96704, -1.87273, -1.78190, -1.72200, -1.58650, -1.35586, -1.11937, -0.93352, -0.79251, -0.53723, -0.46191, -0.45350, -0.25656, 0.03908, 0.33820, 0.44381, 0.50782, 0.53793, 0.61393, 0.62289, 0.57063, 0.45749, 0.48534, 0.58651, 0.65231, 0.59725, 0.55705, 0.39140, 0.20035, 0.17546, 0.19851, 0.14328, 0.12196, 0.03379, -0.08482, -0.29223, -0.41711, -0.29531, -0.10798, -0.05060, -0.17874, -0.14114, -0.08882, -0.18473, -0.19273, -0.20033, -0.22255, -0.42679, -0.51808, -0.49672, -0.40292, -0.37688, -0.44315, -0.57524, -0.62510, -0.55743, -0.49458, -0.56504, -0.52590, -0.53450, -0.56109, -0.52906, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.08023, -0.12059, -0.14982, -0.14178, -0.01552, -0.02087, 0.00973, -0.05837, -0.12925, -0.27710, -0.41975, -0.71339, -0.98010, -1.14308, -1.23989, -1.28911, -1.21874, -1.24583, -1.40754, -1.65624, -1.85594, -2.09546, -2.19359, -2.10714, -1.98715, -1.95417, -2.02791, -1.99872, -1.94004, -2.02284, -2.22493, -2.26690, -2.33490, -2.68312, -2.91609, -2.97904, -2.86951, -2.87854, -2.94076, -3.02136, -3.11410, -3.17279, -3.20688, -3.39654, -3.59189, -3.69364, -3.79913, -4.04925, -4.23059, -4.45039, -4.73963, -4.97910, -5.09968, -5.16750, -5.18383, -5.19807, -5.23047, -5.29607, -5.30515, -5.13022, -4.90114, -4.80976, -4.86197, -4.72232, -4.36195, -4.19010, -4.01383, -3.87835, -3.73478, -3.71167, -3.68032, -3.73456, -3.83435, -3.90995, -3.82521, -3.60227, -3.34276, -2.95600, -2.64899, -2.60230, -2.54797, -2.56278, -2.64001, -2.58903, -2.48846, -2.46688, -2.55060, -2.61183, -2.64896, -2.75232, -2.79359, -2.66724, -2.48730, -2.41196, -2.36871, -2.16753, -1.80845, -1.73260, -1.75018, -1.72154, -1.61091, -1.43751, -1.25979, -1.16153, -1.12036, -1.10221, -1.07055, -1.12296, -1.22723, -1.20361, -1.17335, -1.25780, -1.25120, -1.11253, -1.09372, -1.15368, -1.27675, -1.41603, -1.56266, -1.67975, -1.83690, -2.08778, -2.31341, -2.31034, -2.13853, -2.02628, -2.04018, -2.08654, -2.01258, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.68269, -2.83067, -2.81583, -2.63642, -2.48190, -2.41511, -2.41181, -2.60929, -2.75359, -2.81275, -2.84653, -2.84500, -2.76878, -2.75125, -2.86278, -2.96280, -2.92520, -2.79361, -2.75933, -2.90340, -3.06874, -3.03139, -2.99425, -2.99274, -2.91782, -2.83484, -2.71890, -2.64074, -2.56198, -2.50992, -2.52925, -2.57991, -2.67030, -2.74910, -2.62379, -2.44515, -2.38725, -2.43044, -2.34715, -2.28678, -2.17731, -2.07072, -2.03687, -2.06007, -1.98026, -1.86741, -1.85558, -1.90448, -1.90727, -1.80865, -1.67942, -1.61380, -1.66454, -1.58483, -1.61824, -1.72845, -1.72316, -1.79513, -1.84461, -2.08566, -2.37352, -2.65491, -2.86510, -2.89007, -2.80315, -2.80661, -2.77662, -2.76991, -2.78879, -2.91196, -2.93028, -2.95036, -2.94115, -2.91891, -2.93537, -2.95144, -2.85973, -2.70476, -2.65245, -2.70957, -2.72089, -2.58799, -2.35761, -2.26915, -2.37118, -2.34097, -2.32918, -2.41519, -2.38270, -2.33204, -2.22015, -2.19024, -2.13125, -2.07112, -1.94311, -1.82872, -1.76353, -1.83852, -1.74430, -1.45923, -1.14037, -1.01262, -0.87666, -0.81109, -0.72092, -0.55054, -0.39675, -0.30620, -0.16964, 0.04865, 0.32466, 0.52717, 0.60576, 0.72809, 0.82465, 0.86108, 0.78436, 0.78684, 0.84099, +-2.00838, -2.12833, -2.20857, -2.17709, -2.04066, -2.03380, -2.04474, -2.00257, -1.96837, -1.92919, -1.89193, -1.72361, -1.50631, -1.30226, -1.00805, -0.87881, -0.66755, -0.42860, -0.24907, -0.09416, 0.01994, 0.13304, 0.39751, 0.64532, 0.79438, 0.90853, 0.94538, 1.05511, 1.11371, 1.07998, 1.04661, 1.12763, 1.16231, 1.23910, 1.28020, 1.25588, 1.17345, 0.90840, 0.78682, 0.89459, 0.97572, 1.05871, 0.97794, 0.89544, 0.75129, 0.50169, 0.40723, 0.21828, 0.00540, -0.26569, -0.58772, -0.71240, -0.80058, -0.84166, -0.74596, -0.63524, -0.64893, -0.66803, -0.72171, -0.71542, -0.84487, -1.16018, -1.48121, -1.58859, -1.67983, -1.73839, -1.83891, -1.87116, -1.79665, -1.82619, -1.81235, -1.66403, -1.51439, -1.34693, -1.21961, -1.08713, -0.85636, -0.68482, -0.46167, -0.35935, -0.29592, -0.08652, 0.09538, 0.31582, 0.40531, 0.38438, 0.34949, 0.41117, 0.36048, 0.32012, 0.20435, 0.22251, 0.28959, 0.42292, 0.45863, 0.47379, 0.37662, 0.20409, 0.09498, 0.06477, 0.12049, 0.05685, -0.12918, -0.21661, -0.34502, -0.40740, -0.36053, -0.27719, -0.14390, -0.18315, -0.16826, -0.12475, -0.20463, -0.18113, -0.21403, -0.19394, -0.26746, -0.31771, -0.29047, -0.14458, -0.17065, -0.22362, -0.34508, -0.37815, -0.31640, -0.22894, -0.30517, -0.28918, -0.27157, -0.27526, -0.31170, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.23811, -0.28837, -0.28893, -0.36090, -0.28899, -0.24250, -0.21197, -0.30886, -0.32015, -0.49245, -0.56750, -0.78275, -1.02774, -1.26381, -1.43687, -1.55221, -1.51517, -1.48130, -1.54952, -1.76989, -2.01508, -2.13311, -2.15847, -2.14411, -2.03214, -1.91702, -1.90488, -1.94355, -2.04542, -2.15672, -2.32639, -2.42534, -2.52008, -2.80604, -2.92510, -2.98159, -2.89368, -2.86494, -2.93378, -3.05776, -3.08092, -3.12334, -3.12824, -3.31407, -3.50493, -3.65177, -3.77063, -4.00952, -4.21561, -4.39957, -4.61911, -4.87273, -5.12337, -5.16043, -5.13229, -5.23285, -5.27274, -5.25892, -5.19019, -5.08376, -5.02166, -4.92112, -4.87377, -4.77196, -4.46970, -4.30007, -4.08094, -3.98259, -3.90127, -3.82741, -3.70571, -3.72217, -3.75145, -3.85301, -3.82532, -3.64045, -3.37164, -3.02003, -2.74420, -2.68937, -2.65876, -2.62281, -2.58806, -2.50216, -2.48753, -2.41499, -2.41142, -2.58295, -2.71411, -2.82029, -2.83678, -2.75225, -2.68075, -2.55767, -2.37463, -2.16286, -1.84462, -1.77549, -1.73345, -1.69460, -1.60918, -1.35435, -1.12391, -1.07864, -1.01410, -1.00191, -0.98654, -1.02386, -1.12092, -1.12967, -1.13623, -1.23961, -1.32039, -1.21511, -1.15902, -1.19751, -1.37778, -1.49996, -1.57682, -1.83570, -2.11700, -2.32240, -2.47396, -2.49776, -2.45539, -2.37023, -2.29061, -2.33462, -2.31627, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.97715, -3.10600, -3.07311, -2.86777, -2.64437, -2.54132, -2.44493, -2.49503, -2.55116, -2.65013, -2.71639, -2.64104, -2.64852, -2.70882, -2.74726, -2.77100, -2.74621, -2.76075, -2.83303, -2.92298, -3.06309, -3.03411, -2.93748, -2.85334, -2.73662, -2.70662, -2.57731, -2.45078, -2.42033, -2.38200, -2.38155, -2.46779, -2.55025, -2.64815, -2.53795, -2.38098, -2.26861, -2.27593, -2.16337, -2.03461, -1.90146, -1.86183, -1.86221, -1.79651, -1.80550, -1.81330, -1.77559, -1.76000, -1.73597, -1.72959, -1.67240, -1.47642, -1.43603, -1.43411, -1.55899, -1.75730, -1.80535, -1.96014, -2.02940, -2.23281, -2.55613, -2.84668, -2.97772, -2.98189, -2.83503, -2.81031, -2.74528, -2.74271, -2.73378, -2.86296, -2.91956, -2.90881, -2.84206, -2.82205, -2.86084, -2.78196, -2.75318, -2.76044, -2.75158, -2.75883, -2.70274, -2.58856, -2.38824, -2.18791, -2.17586, -2.14740, -2.12507, -2.16851, -2.08364, -2.08052, -1.98663, -1.90832, -1.89911, -1.91596, -1.76566, -1.69050, -1.58373, -1.63446, -1.55381, -1.36463, -1.13870, -1.09711, -1.03114, -0.96931, -0.86271, -0.73407, -0.67109, -0.50905, -0.37649, -0.26277, 0.03484, 0.39549, 0.62624, 0.71261, 0.66624, 0.67460, 0.63516, 0.59662, 0.62014, +-1.95086, -2.05767, -2.18098, -2.24686, -2.12621, -2.06704, -2.05295, -1.98548, -1.99133, -1.99416, -1.96152, -1.78866, -1.49945, -1.19431, -0.94614, -0.88943, -0.68025, -0.46008, -0.29824, -0.16644, -0.05157, 0.11217, 0.40684, 0.63125, 0.68849, 0.79822, 0.87336, 0.95412, 0.91699, 0.84681, 0.89043, 0.94634, 1.00282, 1.13210, 1.20988, 1.16776, 1.09188, 0.91796, 0.81437, 0.93180, 0.96053, 0.95401, 0.87218, 0.77765, 0.65909, 0.49308, 0.35246, 0.04707, -0.16178, -0.41164, -0.68283, -0.76195, -0.79352, -0.76080, -0.64276, -0.50837, -0.53295, -0.53254, -0.54157, -0.57497, -0.81462, -1.22623, -1.50750, -1.65187, -1.67358, -1.65319, -1.77167, -1.89881, -1.87546, -1.82230, -1.74897, -1.51915, -1.33630, -1.20194, -1.05369, -0.92256, -0.69431, -0.47574, -0.29421, -0.30246, -0.19676, 0.03375, 0.15128, 0.23310, 0.19932, 0.16357, 0.12900, 0.21727, 0.13388, 0.07321, 0.08009, 0.14797, 0.16933, 0.21273, 0.33679, 0.33481, 0.26967, 0.17287, 0.02841, -0.10718, -0.13612, -0.14462, -0.24376, -0.22756, -0.31680, -0.43117, -0.41313, -0.38625, -0.28368, -0.27161, -0.24434, -0.30611, -0.31319, -0.21779, -0.23527, -0.19248, -0.22338, -0.17832, -0.09761, 0.09971, 0.04892, -0.06542, -0.12734, -0.11659, -0.05158, -0.08597, -0.14597, -0.21444, -0.23365, -0.19879, -0.27575, -0.45956, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.57926, -0.57394, -0.67439, -0.62444, -0.61491, -0.53617, -0.52058, -0.42574, -0.58864, -0.72289, -0.85686, -1.05211, -1.31150, -1.64328, -1.79477, -1.84619, -1.85405, -1.82613, -1.94966, -2.17442, -2.29936, -2.23747, -2.14798, -1.96727, -1.84872, -1.93159, -2.01337, -2.13582, -2.21616, -2.33050, -2.43740, -2.67872, -2.93938, -2.96107, -2.99095, -2.90301, -2.93071, -3.01151, -3.09672, -3.02160, -3.00011, -3.07640, -3.25053, -3.42353, -3.58849, -3.82893, -4.05180, -4.26870, -4.45803, -4.58543, -4.78673, -5.07018, -5.21328, -5.19884, -5.24900, -5.18841, -5.08775, -5.04925, -5.02211, -5.05532, -4.97981, -4.87873, -4.74339, -4.57829, -4.48131, -4.22118, -4.07058, -3.96557, -3.93089, -3.79975, -3.72475, -3.64704, -3.68532, -3.73206, -3.57892, -3.30318, -3.00508, -2.85518, -2.77654, -2.72429, -2.69258, -2.56341, -2.43517, -2.46062, -2.50018, -2.52322, -2.62830, -2.68510, -2.72069, -2.81043, -2.83916, -2.81309, -2.65671, -2.39451, -2.12950, -1.91681, -1.92703, -1.83477, -1.74782, -1.59768, -1.32995, -1.12588, -1.06517, -0.96192, -0.90556, -0.94542, -0.98577, -1.02071, -1.01416, -1.09871, -1.22847, -1.32333, -1.33588, -1.29577, -1.32321, -1.50475, -1.68022, -1.78161, -2.02834, -2.32288, -2.47603, -2.64382, -2.73791, -2.72479, -2.65512, -2.50642, -2.43760, -2.48793, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.24828, -3.28679, -3.20304, -3.01817, -2.81888, -2.64194, -2.56212, -2.52264, -2.45474, -2.49157, -2.57273, -2.54534, -2.53133, -2.56739, -2.52010, -2.55090, -2.63416, -2.71629, -2.84701, -2.92558, -2.98166, -2.93610, -2.90963, -2.79881, -2.66833, -2.64329, -2.52672, -2.42786, -2.36104, -2.25826, -2.16131, -2.23925, -2.31924, -2.35628, -2.26075, -2.17112, -2.14334, -2.06353, -1.96446, -1.80454, -1.66093, -1.68880, -1.76902, -1.76220, -1.72328, -1.69315, -1.57806, -1.50587, -1.50164, -1.51302, -1.50858, -1.31286, -1.20860, -1.26157, -1.58246, -1.86134, -1.97723, -2.17926, -2.29134, -2.50918, -2.74595, -2.93869, -2.93146, -2.88966, -2.77533, -2.69932, -2.63560, -2.66144, -2.73413, -2.76097, -2.81720, -2.81550, -2.71707, -2.69387, -2.75589, -2.74261, -2.71665, -2.75766, -2.73740, -2.74493, -2.74897, -2.60152, -2.38013, -2.15218, -2.04864, -1.98206, -2.06350, -2.08682, -1.96285, -1.93392, -1.80821, -1.74173, -1.69498, -1.68189, -1.49286, -1.43872, -1.40555, -1.38554, -1.28042, -1.16893, -1.19876, -1.24506, -1.27876, -1.27383, -1.13438, -1.01616, -1.00342, -0.85641, -0.62536, -0.45095, -0.08276, 0.33792, 0.54708, 0.62922, 0.55613, 0.51456, 0.46693, 0.40579, 0.25353, +-1.91599, -2.04027, -2.08759, -2.19082, -2.17760, -2.11720, -2.21164, -2.21580, -2.16587, -2.13815, -2.07741, -1.89247, -1.65087, -1.31202, -0.91691, -0.76547, -0.58569, -0.43298, -0.32214, -0.27162, -0.19542, 0.03517, 0.28175, 0.43500, 0.45795, 0.61513, 0.74028, 0.77557, 0.75570, 0.80395, 0.96201, 0.99122, 0.96842, 1.00090, 1.13577, 1.13546, 1.01341, 0.98170, 0.90944, 0.92385, 0.92360, 0.86710, 0.82366, 0.76897, 0.59350, 0.36862, 0.27599, 0.02314, -0.22318, -0.51609, -0.72795, -0.74068, -0.69710, -0.58436, -0.57031, -0.58246, -0.61983, -0.56273, -0.55077, -0.68841, -0.91398, -1.19714, -1.38653, -1.54809, -1.58565, -1.64174, -1.72905, -1.83011, -1.88372, -1.77408, -1.70544, -1.56935, -1.32293, -1.13821, -0.93210, -0.73456, -0.56575, -0.43891, -0.23682, -0.19627, -0.06702, 0.16138, 0.26650, 0.25685, 0.09032, 0.03377, -0.02876, -0.03014, -0.10995, -0.12566, 0.00577, 0.03060, 0.02912, 0.11910, 0.31124, 0.29797, 0.23545, 0.16205, 0.10655, 0.00255, -0.18700, -0.21401, -0.23819, -0.26619, -0.29656, -0.42851, -0.47384, -0.47326, -0.47096, -0.58341, -0.48322, -0.40265, -0.29556, -0.17238, -0.21183, -0.18887, -0.23136, -0.12432, -0.04394, 0.04124, 0.03242, -0.03928, -0.02434, -0.05853, -0.01247, -0.02031, -0.03025, -0.14438, -0.19978, -0.25356, -0.36150, -0.51017, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.77612, -0.87466, -0.80898, -0.84711, -0.74039, -0.63780, -0.63401, -0.80540, -0.98035, -1.06188, -1.29563, -1.57007, -1.78941, -1.82753, -1.93258, -2.02608, -2.05151, -2.06561, -2.09566, -2.23503, -2.21444, -2.10454, -2.03940, -1.97941, -2.10243, -2.20629, -2.27848, -2.27772, -2.46857, -2.61139, -2.79224, -2.99736, -2.97964, -3.01109, -2.91148, -2.96472, -3.05717, -3.11584, -3.13661, -3.11681, -3.23861, -3.38145, -3.59153, -3.78197, -3.97611, -4.10259, -4.30067, -4.48755, -4.62378, -4.77026, -4.89836, -5.11184, -5.19666, -5.24782, -5.28080, -5.14354, -5.02463, -4.99434, -5.04174, -4.97038, -4.93649, -4.76252, -4.48736, -4.38202, -4.12989, -3.96149, -3.85222, -3.89313, -3.83828, -3.72758, -3.71488, -3.71200, -3.67122, -3.43030, -3.20596, -3.04373, -2.89375, -2.65384, -2.52114, -2.50726, -2.45817, -2.39702, -2.34736, -2.48177, -2.63113, -2.67851, -2.76191, -2.76432, -2.84929, -2.98177, -3.00501, -2.81900, -2.60569, -2.36390, -2.04844, -1.96867, -1.83725, -1.73033, -1.52454, -1.28844, -1.16701, -1.10032, -1.08453, -1.04344, -1.08574, -1.09555, -1.12016, -1.16024, -1.20202, -1.18576, -1.21840, -1.33166, -1.41224, -1.56309, -1.67309, -1.81155, -1.97031, -2.17179, -2.54031, -2.74653, -2.85112, -2.92328, -2.89279, -2.81623, -2.70068, -2.62664, -2.61776, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.48307, -3.48059, -3.43145, -3.39580, -3.21907, -2.91707, -2.63268, -2.57904, -2.53939, -2.44948, -2.31434, -2.26615, -2.35435, -2.39801, -2.52523, -2.55724, -2.55336, -2.67993, -2.77503, -2.86484, -2.96967, -3.04469, -2.87527, -2.76763, -2.68322, -2.59991, -2.57331, -2.45684, -2.40662, -2.31965, -2.24197, -2.18030, -2.19362, -2.16957, -2.12093, -2.12717, -2.08137, -2.01143, -1.82660, -1.69531, -1.51558, -1.43435, -1.44656, -1.47606, -1.55696, -1.48512, -1.44578, -1.41819, -1.25762, -1.20501, -1.23934, -1.27619, -1.19224, -1.20684, -1.24331, -1.50076, -1.75986, -1.93440, -2.20426, -2.38778, -2.62733, -2.74801, -2.86538, -2.90602, -2.85509, -2.73775, -2.61628, -2.67840, -2.74106, -2.71097, -2.55871, -2.54748, -2.59950, -2.64522, -2.63065, -2.59000, -2.68097, -2.72831, -2.79539, -2.88269, -2.85870, -2.83492, -2.66328, -2.42194, -2.22562, -2.19435, -2.04246, -1.98135, -1.97783, -1.88189, -1.84765, -1.68318, -1.62514, -1.51567, -1.47106, -1.42781, -1.41725, -1.44596, -1.35702, -1.28920, -1.21829, -1.26272, -1.29897, -1.37916, -1.41522, -1.34017, -1.21613, -1.10088, -0.97952, -0.73817, -0.54260, -0.32038, 0.07662, 0.30584, 0.39088, 0.38422, 0.39255, 0.23474, 0.13646, 0.02114, +-1.95319, -2.00651, -2.09166, -2.23261, -2.19770, -2.18517, -2.32554, -2.34794, -2.20964, -2.07673, -2.05558, -1.99810, -1.76859, -1.36593, -0.90832, -0.71691, -0.65405, -0.54706, -0.49921, -0.52776, -0.41973, -0.13851, 0.07880, 0.23636, 0.34745, 0.48012, 0.59151, 0.68658, 0.72923, 0.79453, 0.91064, 0.91678, 0.84597, 0.87779, 1.00020, 1.00670, 0.98039, 1.04707, 1.04858, 1.03856, 1.01434, 0.98618, 0.89194, 0.70682, 0.49442, 0.28530, 0.19199, 0.00797, -0.28409, -0.56555, -0.70647, -0.70144, -0.58618, -0.47185, -0.58545, -0.74641, -0.76016, -0.73556, -0.78889, -0.90369, -1.02994, -1.21622, -1.39530, -1.51134, -1.55694, -1.59719, -1.68192, -1.78735, -1.73039, -1.57220, -1.52781, -1.45409, -1.23306, -0.97084, -0.78875, -0.72735, -0.62487, -0.44392, -0.23872, -0.14872, -0.05539, 0.13515, 0.29191, 0.24786, 0.08816, 0.03635, -0.06596, -0.17044, -0.19598, -0.21174, -0.14963, -0.13936, -0.11655, 0.00903, 0.18532, 0.23244, 0.18591, 0.21788, 0.25631, 0.11231, -0.06567, -0.08550, -0.10591, -0.13672, -0.18815, -0.30765, -0.44417, -0.60799, -0.69273, -0.74083, -0.60040, -0.42267, -0.32929, -0.30113, -0.33761, -0.38767, -0.39208, -0.22066, -0.15021, -0.16455, -0.06158, -0.05901, -0.08728, -0.12576, -0.07994, -0.07434, -0.13164, -0.20302, -0.23764, -0.28185, -0.40152, -0.64935, -0.86243, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.05442, -1.03075, -1.04192, -0.89163, -0.80828, -0.95571, -1.09408, -1.22033, -1.33580, -1.57172, -1.81744, -1.91545, -1.92180, -2.01257, -2.12388, -2.11992, -2.02989, -2.03851, -2.13996, -2.13041, -2.09792, -2.08616, -2.09969, -2.18963, -2.29436, -2.46598, -2.54115, -2.69934, -2.83659, -2.94323, -3.10498, -3.13660, -3.12535, -3.06341, -3.07479, -3.11543, -3.17896, -3.34271, -3.34278, -3.43162, -3.62696, -3.83770, -3.96665, -4.09272, -4.24306, -4.44154, -4.60723, -4.69625, -4.75731, -4.89475, -5.10695, -5.15800, -5.26526, -5.34749, -5.23299, -5.03025, -4.90193, -4.97615, -4.97856, -4.88211, -4.63189, -4.27040, -4.15110, -4.02704, -3.89977, -3.88282, -3.95352, -3.86568, -3.71170, -3.77686, -3.73761, -3.51072, -3.22938, -3.05623, -2.92289, -2.74445, -2.49258, -2.34490, -2.34108, -2.36807, -2.32550, -2.31924, -2.48126, -2.58894, -2.65016, -2.75930, -2.81838, -2.93198, -3.08426, -3.21965, -3.14544, -2.90512, -2.61397, -2.20574, -2.01136, -1.91434, -1.78204, -1.58517, -1.38290, -1.23928, -1.14253, -1.18889, -1.15073, -1.11528, -1.18112, -1.30201, -1.35045, -1.34731, -1.32050, -1.37848, -1.50568, -1.62959, -1.79418, -1.93427, -2.07239, -2.14474, -2.28127, -2.61855, -2.84267, -2.91358, -2.91237, -2.93610, -2.99737, -2.92285, -2.84961, -2.85239, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.60343, -3.58293, -3.56377, -3.54308, -3.39375, -3.08229, -2.76687, -2.62230, -2.52193, -2.33850, -2.16052, -2.14251, -2.24001, -2.35571, -2.57785, -2.67468, -2.68001, -2.74728, -2.84111, -2.98234, -3.06291, -3.02581, -2.78635, -2.60893, -2.59574, -2.56915, -2.51811, -2.42884, -2.33887, -2.22199, -2.21073, -2.22866, -2.13609, -2.08289, -2.08711, -2.11091, -2.06105, -1.98419, -1.80377, -1.58301, -1.34636, -1.15615, -1.11055, -1.17361, -1.20683, -1.11561, -1.10752, -1.12127, -0.99256, -0.90664, -0.99896, -1.19048, -1.18550, -1.15413, -1.20435, -1.39725, -1.63863, -1.85296, -2.12509, -2.39243, -2.56526, -2.56430, -2.63731, -2.78133, -2.71643, -2.60968, -2.55488, -2.64268, -2.69854, -2.62584, -2.48497, -2.44635, -2.54986, -2.61750, -2.60946, -2.61428, -2.68448, -2.74675, -2.84399, -2.93388, -2.92463, -2.81773, -2.64833, -2.53864, -2.40892, -2.28887, -2.06553, -1.87729, -1.87860, -1.88005, -1.84258, -1.73956, -1.63367, -1.45574, -1.41945, -1.52943, -1.52111, -1.57247, -1.55957, -1.51342, -1.42334, -1.38958, -1.43921, -1.49661, -1.52482, -1.42050, -1.26358, -1.19394, -1.06887, -0.84237, -0.71557, -0.55817, -0.21763, 0.08077, 0.17313, 0.10091, 0.12508, 0.06901, -0.02318, -0.07802, +-2.05388, -2.07218, -2.15768, -2.29502, -2.24403, -2.28500, -2.36288, -2.31378, -2.17252, -2.00951, -1.84774, -1.79065, -1.66467, -1.27726, -0.90562, -0.82375, -0.83639, -0.67670, -0.61243, -0.64942, -0.58855, -0.34106, -0.03624, 0.24314, 0.43948, 0.50163, 0.60299, 0.78926, 0.85571, 0.86562, 0.84804, 0.76031, 0.61270, 0.64040, 0.82347, 0.88893, 0.93582, 0.99704, 1.06171, 1.09830, 0.99682, 0.91286, 0.87647, 0.70286, 0.39121, 0.17796, 0.04835, -0.15536, -0.39757, -0.50064, -0.51406, -0.50275, -0.47975, -0.52983, -0.66222, -0.80386, -0.78980, -0.86158, -0.96733, -0.98354, -1.02858, -1.18321, -1.38579, -1.51814, -1.60294, -1.65341, -1.68587, -1.72635, -1.54847, -1.39682, -1.34809, -1.24563, -1.12183, -0.92750, -0.71852, -0.65519, -0.69176, -0.50723, -0.30713, -0.24665, -0.15283, 0.09906, 0.34722, 0.32897, 0.16279, 0.01517, -0.06574, -0.13690, -0.11214, -0.19839, -0.25089, -0.20860, -0.15875, -0.02618, 0.15351, 0.22163, 0.16082, 0.18443, 0.27653, 0.14006, 0.01340, -0.03842, -0.07447, -0.03772, -0.15217, -0.35871, -0.49426, -0.58091, -0.74400, -0.75205, -0.60098, -0.49900, -0.49604, -0.50739, -0.49378, -0.56286, -0.55432, -0.45938, -0.34722, -0.28008, -0.06094, -0.04499, -0.13081, -0.12027, -0.07774, -0.11394, -0.22974, -0.30169, -0.32058, -0.39946, -0.49386, -0.75846, -0.93547, -1.00642, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.19702, -1.18908, -1.14456, -1.09781, -1.21603, -1.26076, -1.32418, -1.43354, -1.59252, -1.80649, -1.91156, -1.96762, -2.10228, -2.22458, -2.25388, -2.10782, -2.09083, -2.15170, -2.18682, -2.24497, -2.19935, -2.24648, -2.38093, -2.47697, -2.52042, -2.70840, -2.93934, -3.04557, -3.16246, -3.28947, -3.27751, -3.18030, -3.13864, -3.13949, -3.28045, -3.36841, -3.51105, -3.48325, -3.55492, -3.80285, -3.93951, -3.97638, -4.10061, -4.31240, -4.56611, -4.73501, -4.84120, -4.85768, -5.00279, -5.18184, -5.20343, -5.34448, -5.36139, -5.26534, -5.13381, -4.95585, -4.81109, -4.81127, -4.74268, -4.46453, -4.16036, -4.07219, -3.99911, -3.87832, -3.91464, -3.98027, -3.92506, -3.71096, -3.67127, -3.53702, -3.21624, -2.97154, -2.79931, -2.62705, -2.47254, -2.29859, -2.22924, -2.27849, -2.41376, -2.39635, -2.39410, -2.50238, -2.53806, -2.64347, -2.73645, -2.87487, -3.13341, -3.31668, -3.32093, -3.24675, -3.06912, -2.76010, -2.37806, -2.17150, -2.05802, -1.83755, -1.62550, -1.43486, -1.34297, -1.24469, -1.18243, -1.04472, -0.95609, -1.12074, -1.31507, -1.34022, -1.35647, -1.42119, -1.59075, -1.74857, -1.90182, -2.03483, -2.13701, -2.25232, -2.27154, -2.38954, -2.62389, -2.80508, -2.95532, -3.00704, -2.96124, -3.03370, -3.11403, -3.13034, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.48881, -3.54460, -3.57794, -3.52997, -3.42801, -3.17673, -2.88596, -2.66413, -2.49938, -2.27601, -2.09080, -2.15364, -2.28329, -2.48100, -2.71861, -2.78487, -2.85515, -2.93380, -2.88705, -2.89416, -3.00584, -2.91448, -2.68067, -2.55833, -2.57623, -2.50063, -2.38583, -2.30708, -2.24085, -2.18951, -2.14266, -2.09153, -1.90876, -1.92872, -2.03009, -2.00917, -1.94663, -1.88338, -1.72803, -1.49377, -1.24082, -0.98634, -0.84555, -0.89753, -0.89416, -0.86857, -0.89767, -0.87326, -0.86127, -0.89099, -0.94868, -1.03824, -1.08711, -1.02321, -1.10101, -1.36615, -1.61059, -1.75910, -1.95770, -2.23790, -2.38369, -2.41439, -2.40049, -2.47573, -2.37129, -2.32976, -2.35196, -2.35995, -2.38909, -2.37229, -2.35188, -2.43523, -2.61048, -2.70468, -2.65198, -2.65282, -2.68258, -2.78172, -2.89140, -2.88853, -2.92256, -2.86845, -2.67098, -2.45220, -2.40700, -2.28420, -2.03111, -1.88378, -1.90496, -1.88874, -1.80407, -1.73957, -1.62285, -1.55559, -1.52596, -1.59389, -1.53238, -1.60863, -1.68293, -1.61946, -1.51077, -1.44255, -1.49326, -1.56473, -1.59379, -1.53289, -1.35061, -1.29249, -1.18792, -1.05980, -1.01997, -0.81544, -0.49728, -0.23675, -0.13076, -0.05328, -0.06006, -0.10430, -0.16542, -0.25851, +-2.01454, -2.02651, -2.09412, -2.17174, -2.21971, -2.34369, -2.38595, -2.26783, -2.00153, -1.81302, -1.63719, -1.51721, -1.41227, -1.15995, -0.91825, -0.90558, -0.92523, -0.74649, -0.65400, -0.60981, -0.48667, -0.31062, -0.01735, 0.31238, 0.48782, 0.56179, 0.73293, 0.92447, 0.93377, 0.90288, 0.81402, 0.70013, 0.54166, 0.51446, 0.71810, 0.89805, 0.95577, 0.94995, 0.96729, 0.94332, 0.86265, 0.75650, 0.67356, 0.53254, 0.22484, -0.02665, -0.19181, -0.35917, -0.49014, -0.40882, -0.33425, -0.33160, -0.39128, -0.60125, -0.76895, -0.84388, -0.87116, -1.01763, -1.13060, -1.11479, -1.12800, -1.19126, -1.34619, -1.47027, -1.59883, -1.71549, -1.72516, -1.62137, -1.38590, -1.32623, -1.30786, -1.22053, -1.04659, -0.84961, -0.73274, -0.72314, -0.81796, -0.70794, -0.49612, -0.31880, -0.15748, 0.11821, 0.34480, 0.36650, 0.28426, 0.13229, 0.01330, -0.05548, -0.12204, -0.27949, -0.34522, -0.26664, -0.23798, -0.09393, 0.14289, 0.29231, 0.28771, 0.27448, 0.29263, 0.18469, 0.06887, -0.09895, -0.16603, -0.16527, -0.23274, -0.36249, -0.54929, -0.63832, -0.79224, -0.79711, -0.67165, -0.59081, -0.66440, -0.70734, -0.68341, -0.69910, -0.61322, -0.54882, -0.51349, -0.39514, -0.16897, -0.12688, -0.16733, -0.12845, -0.20034, -0.30389, -0.40488, -0.41014, -0.37006, -0.47556, -0.59668, -0.75248, -0.82955, -0.98498, -1.21023, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.32057, -1.28566, -1.32465, -1.37004, -1.39656, -1.44472, -1.45369, -1.49320, -1.71059, -1.86883, -1.99124, -2.15903, -2.27320, -2.33501, -2.24246, -2.18970, -2.18366, -2.30978, -2.46191, -2.53385, -2.57946, -2.56199, -2.63633, -2.65233, -2.89551, -3.20244, -3.30348, -3.30995, -3.31236, -3.26007, -3.21681, -3.25020, -3.24141, -3.34461, -3.51668, -3.66622, -3.73658, -3.87951, -4.06877, -4.06275, -4.07537, -4.25333, -4.48334, -4.69304, -4.78235, -4.86630, -4.94560, -5.10756, -5.21190, -5.25758, -5.35758, -5.35874, -5.29548, -5.13970, -4.97639, -4.73888, -4.65281, -4.59816, -4.40006, -4.15672, -4.04686, -3.95718, -3.87461, -3.94023, -3.97935, -3.84621, -3.61839, -3.46919, -3.28015, -3.01276, -2.80655, -2.60264, -2.45556, -2.37737, -2.25229, -2.21954, -2.24636, -2.38430, -2.46913, -2.51517, -2.51615, -2.50402, -2.64092, -2.81205, -3.07197, -3.29834, -3.42262, -3.32870, -3.18589, -3.08775, -2.90663, -2.58291, -2.29569, -2.08317, -1.83850, -1.68153, -1.54038, -1.40176, -1.30120, -1.13799, -0.94739, -0.94399, -1.14445, -1.27894, -1.28902, -1.37960, -1.53103, -1.77371, -1.88778, -1.95292, -2.02050, -2.06573, -2.12817, -2.20631, -2.39049, -2.59711, -2.77702, -2.88154, -2.96925, -3.00497, -3.10257, -3.29942, -3.48154, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.47289, -3.57274, -3.59070, -3.51747, -3.47419, -3.29478, -3.04466, -2.71317, -2.39368, -2.17821, -2.07673, -2.20048, -2.38135, -2.63461, -2.83299, -2.90550, -2.95086, -2.98518, -2.90302, -2.76913, -2.81670, -2.77832, -2.63580, -2.55769, -2.56858, -2.46488, -2.34217, -2.26769, -2.18801, -2.15534, -2.07074, -1.91048, -1.76561, -1.86978, -2.00477, -1.94935, -1.88594, -1.75964, -1.56587, -1.31216, -1.03964, -0.79737, -0.63235, -0.59865, -0.58047, -0.69411, -0.80590, -0.85879, -0.87138, -0.88322, -0.94937, -0.96697, -0.98215, -0.94818, -1.04950, -1.26425, -1.47942, -1.61191, -1.81261, -2.07940, -2.17233, -2.18656, -2.16772, -2.12524, -2.06275, -2.12558, -2.18092, -2.09572, -2.10180, -2.14905, -2.25116, -2.44313, -2.59758, -2.64943, -2.55552, -2.49363, -2.53331, -2.75510, -2.87754, -2.85974, -2.84003, -2.72403, -2.60367, -2.40244, -2.37074, -2.31704, -2.10939, -1.96747, -1.98741, -1.92555, -1.81139, -1.73250, -1.59732, -1.58760, -1.65453, -1.64468, -1.57802, -1.64610, -1.70244, -1.62845, -1.58266, -1.52035, -1.50373, -1.50337, -1.45863, -1.42822, -1.33304, -1.27438, -1.19301, -1.21651, -1.24201, -1.11346, -0.79368, -0.43511, -0.32757, -0.18616, -0.19392, -0.32171, -0.42739, -0.49481, +-2.00635, -2.04978, -2.15031, -2.16223, -2.13024, -2.20107, -2.14321, -1.93646, -1.67024, -1.56897, -1.46268, -1.32177, -1.07861, -0.86886, -0.76909, -0.73590, -0.75684, -0.60762, -0.51299, -0.43325, -0.28916, -0.23583, -0.06063, 0.20538, 0.40602, 0.57254, 0.79808, 0.94531, 0.90238, 0.88223, 0.77807, 0.69836, 0.57419, 0.45542, 0.52954, 0.71845, 0.87149, 0.89428, 0.87349, 0.82469, 0.71919, 0.53949, 0.39009, 0.24911, 0.09762, -0.00266, -0.19411, -0.31793, -0.44684, -0.36668, -0.28645, -0.32719, -0.41050, -0.70381, -0.89446, -0.92826, -0.94813, -1.10216, -1.25790, -1.30380, -1.34145, -1.29938, -1.42607, -1.55917, -1.66391, -1.80746, -1.83535, -1.67717, -1.38456, -1.32616, -1.32100, -1.17877, -0.97134, -0.85716, -0.86144, -0.89485, -0.88118, -0.66214, -0.47304, -0.21242, -0.05864, 0.12161, 0.26492, 0.25323, 0.25737, 0.09011, -0.07473, -0.16875, -0.29373, -0.39276, -0.39884, -0.28397, -0.28073, -0.12601, 0.06429, 0.20502, 0.28235, 0.24574, 0.14461, -0.00211, -0.04984, -0.15589, -0.20930, -0.17484, -0.19052, -0.28499, -0.53252, -0.70824, -0.84580, -0.73546, -0.68972, -0.61658, -0.70241, -0.78052, -0.71697, -0.69682, -0.54760, -0.58369, -0.68396, -0.61194, -0.43137, -0.27624, -0.27068, -0.24723, -0.40186, -0.48669, -0.56525, -0.58386, -0.52505, -0.65322, -0.80949, -0.89433, -0.81245, -0.88080, -1.11009, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.46560, -1.43399, -1.49735, -1.46052, -1.47405, -1.45121, -1.44829, -1.47567, -1.71943, -1.88769, -2.08150, -2.34343, -2.44805, -2.51108, -2.48948, -2.49055, -2.39666, -2.41251, -2.60852, -2.74420, -2.82497, -2.80153, -2.90439, -2.95413, -3.15171, -3.21863, -3.25685, -3.15604, -3.06166, -3.14027, -3.21579, -3.40432, -3.44469, -3.54819, -3.82944, -4.01483, -4.15152, -4.22181, -4.32220, -4.27139, -4.35725, -4.57095, -4.79724, -4.99678, -5.00120, -5.04602, -5.17896, -5.34985, -5.32176, -5.22553, -5.24613, -5.21271, -5.18020, -5.08950, -5.04753, -4.86007, -4.71911, -4.48208, -4.29488, -4.11093, -3.96337, -3.91334, -3.80744, -3.86211, -3.87605, -3.74571, -3.63446, -3.47387, -3.26640, -2.97451, -2.79139, -2.61591, -2.52938, -2.46453, -2.33281, -2.36782, -2.34541, -2.40335, -2.57620, -2.75007, -2.72459, -2.59947, -2.71109, -2.88065, -3.11199, -3.24839, -3.32528, -3.19537, -3.04458, -2.89568, -2.77875, -2.57902, -2.25529, -2.05356, -1.84692, -1.73973, -1.60824, -1.40479, -1.34130, -1.17951, -1.03153, -1.04864, -1.21638, -1.30703, -1.33814, -1.47793, -1.63238, -1.88441, -1.90806, -1.83946, -1.85976, -1.95330, -2.02282, -2.07467, -2.29849, -2.50056, -2.64408, -2.74335, -2.91330, -3.08610, -3.26532, -3.39423, -3.52318, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.59216, -3.62083, -3.54911, -3.51230, -3.36311, -3.22345, -2.90967, -2.50197, -2.32627, -2.33819, -2.45978, -2.49545, -2.63323, -2.73452, -2.75974, -2.82725, -2.90295, -2.88780, -2.74023, -2.64556, -2.52076, -2.47967, -2.40675, -2.45191, -2.43464, -2.36835, -2.36586, -2.28006, -2.29796, -2.20316, -1.97187, -1.82481, -1.86652, -1.96265, -1.88747, -1.81829, -1.61520, -1.46300, -1.27070, -0.99995, -0.84199, -0.74638, -0.68545, -0.56513, -0.63380, -0.78381, -0.83977, -0.82953, -0.80688, -0.87889, -0.91417, -0.90040, -0.78439, -0.92234, -1.05105, -1.25989, -1.49887, -1.71320, -1.97104, -1.98260, -2.01377, -2.04196, -1.91079, -1.83541, -1.88695, -2.00854, -1.96762, -2.01777, -2.08662, -2.27791, -2.51058, -2.53335, -2.50451, -2.40110, -2.37264, -2.40216, -2.59005, -2.74262, -2.68310, -2.62124, -2.52841, -2.49078, -2.35844, -2.29465, -2.13269, -2.04359, -1.96209, -2.00958, -2.02497, -1.88297, -1.80662, -1.64684, -1.67332, -1.78690, -1.71285, -1.62811, -1.59344, -1.66646, -1.65367, -1.70791, -1.65711, -1.59812, -1.56410, -1.40972, -1.36210, -1.37251, -1.38767, -1.24430, -1.15969, -1.18935, -1.09246, -0.85253, -0.56109, -0.49474, -0.37591, -0.38623, -0.40624, -0.54548, -0.56753, +-2.01155, -2.10358, -2.12249, -2.08778, -1.93965, -1.84193, -1.71831, -1.54298, -1.39152, -1.36124, -1.21399, -1.01856, -0.78533, -0.62582, -0.57601, -0.52377, -0.48094, -0.38235, -0.25790, -0.18148, -0.24069, -0.23603, -0.04071, 0.14568, 0.34487, 0.58960, 0.82473, 0.95473, 0.97300, 0.96285, 0.88542, 0.84146, 0.62196, 0.40171, 0.42921, 0.56147, 0.71232, 0.82186, 0.81700, 0.70170, 0.50521, 0.27905, 0.19526, 0.16221, 0.08882, 0.05817, -0.09703, -0.22493, -0.36323, -0.38289, -0.31612, -0.30180, -0.50733, -0.81615, -0.92717, -0.99853, -1.05612, -1.18860, -1.37270, -1.48578, -1.48331, -1.39698, -1.51095, -1.61519, -1.72692, -1.87814, -1.82959, -1.65455, -1.41431, -1.30409, -1.28867, -1.21419, -1.10006, -1.09073, -1.08407, -0.97491, -0.85655, -0.61690, -0.44639, -0.26523, -0.14641, -0.01132, 0.11238, 0.19425, 0.10871, -0.13010, -0.19101, -0.27938, -0.42151, -0.43078, -0.37435, -0.27774, -0.22438, -0.06837, 0.01909, 0.13548, 0.16963, 0.07646, 0.03910, -0.05619, -0.10105, -0.08137, -0.06783, -0.06810, -0.12397, -0.27055, -0.49896, -0.60424, -0.75674, -0.71734, -0.71661, -0.67812, -0.71166, -0.74085, -0.67157, -0.53761, -0.50035, -0.71587, -0.78305, -0.75504, -0.65022, -0.43364, -0.39951, -0.41668, -0.48367, -0.47072, -0.56568, -0.59506, -0.61857, -0.84000, -0.92306, -0.90665, -0.80072, -0.76029, -0.90460, -1.03733, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.58882, -1.52584, -1.40973, -1.43293, -1.38001, -1.42062, -1.55297, -1.78238, -1.87760, -2.10251, -2.38194, -2.53714, -2.69722, -2.65237, -2.60835, -2.53818, -2.48547, -2.65566, -2.85324, -3.04802, -3.17463, -3.28543, -3.21062, -3.24822, -3.17483, -3.14825, -3.03898, -2.97064, -3.12511, -3.31990, -3.49502, -3.64551, -3.95283, -4.21696, -4.35280, -4.47327, -4.44393, -4.47106, -4.48768, -4.61547, -4.77362, -5.01951, -5.21784, -5.24267, -5.38476, -5.46856, -5.46402, -5.35710, -5.17207, -5.13611, -5.16200, -5.20805, -5.21787, -5.21943, -4.96899, -4.74983, -4.46972, -4.24799, -4.07035, -3.93391, -3.85982, -3.74965, -3.67578, -3.67946, -3.77784, -3.73981, -3.56041, -3.38779, -3.05307, -2.82274, -2.71128, -2.64228, -2.47094, -2.32542, -2.36751, -2.34256, -2.47510, -2.65904, -2.77992, -2.81406, -2.71107, -2.76136, -2.89859, -3.08197, -3.19168, -3.25090, -3.04819, -2.85813, -2.73098, -2.64056, -2.51276, -2.25832, -2.07070, -1.92282, -1.71107, -1.46896, -1.37879, -1.31416, -1.11522, -1.04936, -1.06643, -1.18352, -1.32305, -1.40615, -1.48513, -1.59591, -1.75719, -1.69873, -1.67557, -1.72764, -1.80458, -1.89864, -1.95144, -2.12910, -2.34083, -2.54561, -2.72961, -2.94961, -3.10606, -3.24906, -3.35342, -3.44279, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.48482, -3.54936, -3.52753, -3.42823, -3.28872, -3.21640, -2.98514, -2.72668, -2.62890, -2.57431, -2.60198, -2.54774, -2.55580, -2.60285, -2.67157, -2.79991, -2.91363, -2.88498, -2.67809, -2.54605, -2.41629, -2.36231, -2.29504, -2.35629, -2.43004, -2.41559, -2.37465, -2.42005, -2.51015, -2.34419, -2.11616, -1.95048, -1.85339, -1.85962, -1.79683, -1.67302, -1.48142, -1.43318, -1.28230, -1.11006, -1.06527, -0.93755, -0.83764, -0.69897, -0.63871, -0.73935, -0.82937, -0.82745, -0.80217, -0.81715, -0.77123, -0.78795, -0.72836, -0.85797, -0.97178, -1.13444, -1.38650, -1.59605, -1.70011, -1.74364, -1.85012, -1.80287, -1.65566, -1.58618, -1.57795, -1.72843, -1.83974, -1.92547, -1.97801, -2.19216, -2.34475, -2.34112, -2.37264, -2.23101, -2.19271, -2.26359, -2.36858, -2.51493, -2.51934, -2.51163, -2.50259, -2.42268, -2.16619, -2.06417, -1.93158, -1.91948, -1.94204, -2.02441, -2.09171, -2.00458, -1.82012, -1.71976, -1.83013, -1.79577, -1.66658, -1.60514, -1.54295, -1.65309, -1.73039, -1.76769, -1.65431, -1.59191, -1.50929, -1.34336, -1.35814, -1.34291, -1.31317, -1.16361, -0.96490, -0.95808, -0.94761, -0.87708, -0.77525, -0.73316, -0.52072, -0.45760, -0.44153, -0.54981, -0.54108, +-1.90800, -1.93922, -1.94176, -1.93506, -1.76208, -1.55462, -1.34181, -1.21820, -1.06970, -0.97589, -0.89037, -0.74841, -0.57509, -0.47881, -0.41024, -0.29081, -0.13095, -0.07063, -0.06021, -0.10677, -0.23158, -0.11361, 0.11027, 0.19580, 0.29774, 0.54469, 0.81344, 0.98700, 1.02599, 0.93763, 0.88788, 0.88017, 0.64973, 0.48139, 0.43898, 0.42967, 0.47833, 0.59533, 0.68934, 0.56228, 0.37805, 0.23993, 0.10204, 0.04868, 0.02010, -0.02017, -0.12751, -0.19924, -0.26563, -0.33676, -0.39713, -0.43780, -0.64348, -0.77467, -0.81488, -0.99156, -1.19062, -1.37215, -1.52064, -1.59931, -1.58014, -1.57947, -1.69027, -1.73029, -1.75651, -1.73684, -1.64665, -1.58413, -1.48325, -1.41687, -1.34158, -1.33052, -1.29094, -1.20926, -1.22735, -1.10326, -0.89429, -0.67574, -0.53183, -0.41254, -0.29554, -0.14556, -0.09842, -0.03883, -0.14821, -0.25196, -0.20902, -0.33468, -0.53092, -0.53346, -0.40302, -0.26320, -0.17366, -0.12706, -0.14319, -0.02653, -0.00517, 0.04666, 0.13253, 0.02534, -0.06595, -0.07244, -0.00163, -0.00638, -0.09643, -0.15480, -0.40178, -0.56735, -0.69884, -0.74235, -0.78042, -0.72548, -0.67588, -0.59842, -0.59303, -0.51273, -0.58002, -0.73606, -0.72287, -0.77426, -0.78782, -0.63911, -0.57287, -0.52877, -0.46126, -0.44765, -0.58634, -0.61497, -0.70104, -0.81812, -0.79698, -0.82654, -0.80298, -0.79731, -0.83140, -0.84891, -0.88648, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.58405, -1.36628, -1.25520, -1.34413, -1.39083, -1.48235, -1.64435, -1.84074, -1.94444, -2.18083, -2.41513, -2.60338, -2.71480, -2.62427, -2.63573, -2.66903, -2.72522, -2.86432, -3.02427, -3.27479, -3.34941, -3.44517, -3.42750, -3.35628, -3.20839, -3.16175, -3.04505, -3.02856, -3.17129, -3.46561, -3.73062, -3.98309, -4.25984, -4.41825, -4.52217, -4.62325, -4.60730, -4.59615, -4.62828, -4.75558, -4.92309, -5.22343, -5.43119, -5.51385, -5.60742, -5.55929, -5.46998, -5.36444, -5.24267, -5.20617, -5.24701, -5.34826, -5.26324, -5.20019, -5.02533, -4.78935, -4.50980, -4.28588, -4.06842, -3.91797, -3.75177, -3.67212, -3.64756, -3.70353, -3.82784, -3.75671, -3.60954, -3.52474, -3.24078, -2.94793, -2.80397, -2.69478, -2.51304, -2.43555, -2.44853, -2.42310, -2.52077, -2.58384, -2.66654, -2.78264, -2.81403, -2.86639, -2.92841, -3.07281, -3.05263, -3.02719, -2.92981, -2.80803, -2.70630, -2.63206, -2.49988, -2.26748, -2.02241, -1.90941, -1.69859, -1.39118, -1.24330, -1.05530, -0.86916, -0.92464, -1.01488, -1.11676, -1.27954, -1.37787, -1.43507, -1.56785, -1.62967, -1.50446, -1.46567, -1.46590, -1.59519, -1.78846, -1.92870, -2.10791, -2.26959, -2.51850, -2.68302, -2.81540, -3.03522, -3.21617, -3.29223, -3.38534, -3.55640, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.44756, -3.49975, -3.48018, -3.37594, -3.32088, -3.26312, -3.05694, -2.88216, -2.72149, -2.62729, -2.65883, -2.61949, -2.61878, -2.61085, -2.72414, -2.83403, -2.81939, -2.84834, -2.72474, -2.58425, -2.49041, -2.38084, -2.23603, -2.24657, -2.35688, -2.48574, -2.50377, -2.55184, -2.50118, -2.31132, -2.18316, -2.06235, -1.89912, -1.78378, -1.66223, -1.51629, -1.47836, -1.55112, -1.41603, -1.29027, -1.16740, -1.00743, -0.97506, -0.89517, -0.82353, -0.81694, -0.87387, -0.82605, -0.64269, -0.66968, -0.69820, -0.74341, -0.77442, -0.89772, -0.95493, -1.00492, -1.16231, -1.42013, -1.52080, -1.57534, -1.55116, -1.42090, -1.35783, -1.36570, -1.36589, -1.46878, -1.59628, -1.70021, -1.83897, -2.07227, -2.12037, -2.09671, -2.04820, -1.90469, -1.98646, -2.14734, -2.29551, -2.40867, -2.44008, -2.47727, -2.36387, -2.23500, -1.99120, -1.85004, -1.78055, -1.84021, -1.88537, -1.94136, -1.98878, -2.05346, -1.94275, -1.87095, -1.81509, -1.60534, -1.49505, -1.51285, -1.55493, -1.68775, -1.74618, -1.72485, -1.63874, -1.60789, -1.47452, -1.31808, -1.23636, -1.14417, -1.15177, -1.04927, -0.90204, -0.86335, -0.87082, -0.93659, -0.82583, -0.79682, -0.65970, -0.50830, -0.45207, -0.53254, -0.46452, +-1.70372, -1.70998, -1.78290, -1.80987, -1.57430, -1.31253, -1.07512, -0.95480, -0.79888, -0.65017, -0.57256, -0.50433, -0.36365, -0.21799, -0.12141, -0.00941, 0.10355, 0.18089, 0.19177, 0.03596, -0.09108, 0.06356, 0.18595, 0.21699, 0.28982, 0.47879, 0.77628, 1.02183, 1.00466, 0.91274, 0.86639, 0.78218, 0.62241, 0.49750, 0.36334, 0.24865, 0.28119, 0.39041, 0.51479, 0.45776, 0.33908, 0.19066, -0.07193, -0.21285, -0.21336, -0.19890, -0.25408, -0.27084, -0.26394, -0.26945, -0.33528, -0.49124, -0.70926, -0.75942, -0.85466, -1.10658, -1.37469, -1.63709, -1.70084, -1.62337, -1.64227, -1.69546, -1.78059, -1.87861, -1.77277, -1.63240, -1.58253, -1.67908, -1.64368, -1.55425, -1.42812, -1.41633, -1.41364, -1.30401, -1.32721, -1.26497, -1.03198, -0.72923, -0.58018, -0.52437, -0.45307, -0.29769, -0.20223, -0.20224, -0.30876, -0.33345, -0.35434, -0.54413, -0.69196, -0.70261, -0.51775, -0.25865, -0.19996, -0.23134, -0.24092, -0.22159, -0.13597, 0.04042, 0.17797, 0.04441, -0.01033, -0.04989, -0.04918, -0.04552, -0.13234, -0.19247, -0.44246, -0.64286, -0.67689, -0.60747, -0.66059, -0.67328, -0.65125, -0.54677, -0.46309, -0.45105, -0.60786, -0.71973, -0.71927, -0.85125, -0.87542, -0.81091, -0.73577, -0.53461, -0.41418, -0.44614, -0.54984, -0.72892, -0.81282, -0.76630, -0.66952, -0.80825, -0.83765, -0.79777, -0.76998, -0.71840, -0.70826, -0.60041, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.67128, -1.50976, -1.27442, -1.26792, -1.34770, -1.46678, -1.59876, -1.65722, -1.84310, -2.02509, -2.17987, -2.46230, -2.63999, -2.71875, -2.70760, -2.85936, -2.97984, -3.09490, -3.21396, -3.28594, -3.40443, -3.38853, -3.50734, -3.60320, -3.53902, -3.27531, -3.16272, -3.09454, -3.17299, -3.37835, -3.59899, -3.86834, -4.18702, -4.40837, -4.54987, -4.72672, -4.76565, -4.75847, -4.76619, -4.74146, -4.84823, -5.04287, -5.25609, -5.56755, -5.72491, -5.70185, -5.58579, -5.56072, -5.48134, -5.34459, -5.30755, -5.33900, -5.38793, -5.21568, -5.12013, -5.02508, -4.82057, -4.49395, -4.24637, -4.04744, -3.90322, -3.75550, -3.63322, -3.63432, -3.76654, -3.86198, -3.79870, -3.78027, -3.72386, -3.46944, -3.16636, -2.88619, -2.70024, -2.64884, -2.60737, -2.65268, -2.67785, -2.67576, -2.62204, -2.68114, -2.74696, -2.76346, -2.85183, -2.92672, -3.02484, -2.91134, -2.85566, -2.87545, -2.87502, -2.73467, -2.55501, -2.39680, -2.19159, -1.98549, -1.81737, -1.54541, -1.24480, -1.02892, -0.80964, -0.78614, -0.88969, -0.93927, -1.03382, -1.16402, -1.22796, -1.32485, -1.42055, -1.47870, -1.40950, -1.28563, -1.24983, -1.47015, -1.74218, -1.88645, -2.07032, -2.23104, -2.44761, -2.57968, -2.71413, -2.99503, -3.22359, -3.23708, -3.25633, -3.43960, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.57653, -3.50877, -3.49165, -3.43344, -3.31026, -3.11715, -2.89351, -2.72042, -2.70885, -2.81819, -2.74477, -2.72208, -2.72890, -2.84133, -2.87932, -2.77704, -2.83301, -2.81669, -2.67068, -2.50325, -2.35865, -2.21277, -2.24975, -2.37736, -2.52998, -2.60909, -2.57121, -2.39937, -2.32315, -2.30029, -2.13080, -1.96301, -1.78161, -1.53676, -1.43242, -1.48796, -1.59109, -1.57976, -1.42299, -1.23711, -1.11673, -1.18169, -1.11501, -1.03887, -0.98193, -0.93812, -0.78434, -0.53359, -0.59145, -0.71448, -0.76074, -0.71984, -0.81178, -0.88115, -0.90371, -0.98422, -1.12657, -1.26585, -1.38057, -1.31560, -1.23474, -1.31089, -1.31607, -1.30224, -1.28807, -1.20497, -1.33117, -1.57661, -1.79550, -1.92192, -1.83604, -1.70434, -1.64119, -1.89915, -2.07389, -2.19177, -2.29940, -2.33013, -2.34627, -2.18605, -2.04727, -1.87200, -1.72590, -1.60948, -1.71079, -1.78815, -1.80515, -1.85915, -1.94434, -1.92376, -1.84948, -1.67540, -1.47411, -1.46465, -1.46630, -1.57021, -1.70446, -1.61926, -1.57419, -1.56310, -1.48881, -1.44496, -1.29693, -1.13845, -1.03230, -1.12027, -1.01682, -0.88040, -0.86275, -0.86637, -0.93261, -0.79968, -0.78822, -0.75334, -0.57583, -0.37474, -0.36211, -0.31265, +-1.35858, -1.42624, -1.43419, -1.43083, -1.26645, -1.06379, -0.88145, -0.76844, -0.62017, -0.46242, -0.26183, -0.11340, -0.05938, 0.07441, 0.20785, 0.24247, 0.21572, 0.31374, 0.41486, 0.25731, 0.10395, 0.23747, 0.37566, 0.46142, 0.56223, 0.72582, 0.90006, 1.01245, 0.97533, 0.95507, 0.92558, 0.79030, 0.59792, 0.40835, 0.37498, 0.34849, 0.35972, 0.39540, 0.40280, 0.32156, 0.21229, -0.00599, -0.24411, -0.31563, -0.37849, -0.42381, -0.41129, -0.37396, -0.32728, -0.27787, -0.31241, -0.57554, -0.92584, -1.04377, -1.12461, -1.29750, -1.49431, -1.70340, -1.76158, -1.73115, -1.73026, -1.70944, -1.70409, -1.81333, -1.76357, -1.75980, -1.67976, -1.72157, -1.67471, -1.52920, -1.37766, -1.36846, -1.36836, -1.31578, -1.29081, -1.20974, -1.09684, -0.87225, -0.66684, -0.57148, -0.50793, -0.35140, -0.17542, -0.21741, -0.38092, -0.43613, -0.47396, -0.59567, -0.65851, -0.64596, -0.53628, -0.44517, -0.42165, -0.37659, -0.23201, -0.15609, -0.03993, 0.00921, 0.14885, 0.14234, 0.14265, 0.10691, 0.05269, 0.00400, -0.09758, -0.27352, -0.48312, -0.53775, -0.52165, -0.51357, -0.57551, -0.64147, -0.70126, -0.63092, -0.44910, -0.44797, -0.64396, -0.75934, -0.72852, -0.76831, -0.73566, -0.67476, -0.62489, -0.56693, -0.53587, -0.57343, -0.58387, -0.75462, -0.77809, -0.75150, -0.58390, -0.60074, -0.61218, -0.53518, -0.49730, -0.54470, -0.56922, -0.53553, -0.65251, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.60242, -1.48224, -1.28847, -1.26493, -1.29737, -1.37210, -1.46696, -1.62003, -1.85625, -2.08837, -2.19931, -2.45264, -2.59739, -2.79995, -2.87263, -2.97950, -3.14669, -3.32021, -3.43106, -3.49580, -3.50213, -3.51646, -3.66867, -3.69736, -3.66365, -3.51666, -3.38292, -3.31121, -3.39174, -3.60122, -3.71014, -3.91670, -4.27654, -4.55032, -4.68688, -4.84211, -4.89188, -4.89165, -4.90842, -4.99135, -5.09571, -5.20655, -5.25521, -5.50353, -5.63610, -5.65573, -5.57680, -5.53631, -5.47501, -5.32457, -5.23025, -5.22590, -5.19479, -5.04038, -4.95852, -4.78041, -4.55392, -4.35334, -4.16505, -3.99384, -3.87021, -3.79566, -3.67201, -3.68106, -3.88591, -4.00857, -3.89942, -3.83126, -3.75424, -3.55911, -3.32519, -3.12402, -2.96889, -2.92540, -2.80340, -2.77108, -2.77218, -2.79673, -2.72046, -2.61206, -2.54476, -2.55283, -2.67495, -2.83218, -2.96081, -2.89040, -2.87688, -2.82510, -2.75449, -2.65359, -2.44616, -2.22379, -2.00950, -1.84335, -1.60881, -1.31195, -1.14749, -1.03162, -0.83831, -0.79993, -0.80171, -0.74355, -0.78388, -0.96227, -1.09133, -1.16151, -1.17859, -1.24912, -1.22473, -1.13352, -1.13727, -1.24706, -1.44379, -1.59301, -1.78185, -1.99043, -2.21064, -2.38157, -2.62477, -2.86655, -3.02100, -3.11621, -3.22051, -3.40935, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.58988, -3.66463, -3.69391, -3.53993, -3.29870, -3.05610, -2.87660, -2.85564, -2.85986, -2.95328, -2.89090, -2.84607, -2.84702, -2.90394, -2.86105, -2.77599, -2.75850, -2.67206, -2.59802, -2.50810, -2.40744, -2.37053, -2.48402, -2.60160, -2.66796, -2.73676, -2.68241, -2.47867, -2.38214, -2.28412, -2.03104, -1.86996, -1.79121, -1.68228, -1.58236, -1.53732, -1.51342, -1.49222, -1.34064, -1.26431, -1.12223, -1.10300, -1.04707, -0.98662, -0.92182, -0.85023, -0.66934, -0.53680, -0.59833, -0.63033, -0.65754, -0.62551, -0.65764, -0.75087, -0.84388, -0.91430, -0.90653, -1.03553, -1.22345, -1.22472, -1.15790, -1.22319, -1.19453, -1.11581, -1.03679, -0.98620, -1.12956, -1.34945, -1.50456, -1.65126, -1.55729, -1.53462, -1.47085, -1.61693, -1.74443, -1.82876, -1.92294, -1.99334, -1.99644, -1.93292, -1.86686, -1.69309, -1.59553, -1.58210, -1.65549, -1.69188, -1.67154, -1.70782, -1.71045, -1.70790, -1.67972, -1.59212, -1.47346, -1.43389, -1.36237, -1.38162, -1.45439, -1.44755, -1.41521, -1.37850, -1.21826, -1.16821, -1.04352, -1.03190, -0.94468, -0.93237, -0.84238, -0.77099, -0.79450, -0.84028, -0.82752, -0.71293, -0.70612, -0.61641, -0.48824, -0.37393, -0.28049, -0.19584, +-0.96863, -1.06093, -1.06381, -1.07367, -0.98982, -0.86615, -0.72654, -0.62423, -0.47802, -0.26614, -0.05467, 0.10027, 0.13881, 0.24618, 0.46082, 0.48384, 0.43434, 0.51036, 0.53599, 0.44305, 0.36599, 0.47392, 0.61010, 0.71457, 0.85997, 1.02411, 1.07970, 1.07890, 1.08087, 1.05353, 0.94906, 0.82687, 0.64823, 0.44042, 0.42577, 0.43963, 0.43222, 0.40791, 0.28425, 0.13234, -0.02112, -0.16326, -0.31308, -0.36980, -0.45104, -0.54278, -0.45456, -0.35334, -0.31626, -0.33949, -0.54115, -0.84536, -1.18352, -1.33723, -1.41570, -1.52686, -1.59664, -1.69339, -1.79721, -1.85375, -1.79244, -1.71265, -1.72211, -1.78269, -1.77993, -1.83943, -1.78202, -1.75443, -1.65861, -1.44410, -1.29786, -1.26535, -1.26539, -1.17442, -1.12557, -1.11888, -1.09212, -0.96276, -0.70911, -0.50189, -0.42536, -0.27262, -0.21405, -0.29352, -0.40871, -0.46004, -0.49173, -0.55210, -0.55475, -0.50511, -0.51251, -0.59838, -0.57468, -0.44705, -0.28568, -0.09869, 0.06181, 0.08326, 0.14348, 0.19260, 0.22541, 0.29745, 0.26741, 0.20750, 0.05600, -0.12422, -0.30019, -0.37193, -0.40350, -0.53816, -0.61922, -0.60347, -0.68293, -0.58080, -0.47634, -0.49717, -0.58179, -0.64547, -0.63378, -0.64303, -0.59198, -0.48761, -0.48971, -0.59681, -0.63885, -0.63330, -0.67121, -0.73989, -0.68156, -0.61617, -0.48678, -0.43524, -0.42768, -0.29189, -0.27991, -0.38485, -0.48494, -0.46343, -0.52037, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.43111, -1.32625, -1.21008, -1.19082, -1.21154, -1.20693, -1.29885, -1.57467, -1.84661, -2.06314, -2.29577, -2.53169, -2.64624, -2.79989, -2.91434, -3.02010, -3.23328, -3.39567, -3.53628, -3.61065, -3.66327, -3.73127, -3.85229, -3.88751, -3.88103, -3.82894, -3.71773, -3.52489, -3.54807, -3.65234, -3.79920, -4.06377, -4.36484, -4.60367, -4.75631, -4.92265, -5.03933, -5.01639, -5.04766, -5.22094, -5.30178, -5.27796, -5.31456, -5.47635, -5.52327, -5.49568, -5.47276, -5.45016, -5.40713, -5.20241, -5.05784, -4.98295, -4.92022, -4.77022, -4.64666, -4.48969, -4.30378, -4.20551, -4.08865, -3.86329, -3.77317, -3.70127, -3.67492, -3.80645, -3.98318, -4.04481, -3.92020, -3.83184, -3.78168, -3.63777, -3.51907, -3.46616, -3.33493, -3.12288, -2.93353, -2.83658, -2.73637, -2.68016, -2.60011, -2.45357, -2.39935, -2.43648, -2.57250, -2.74178, -2.89202, -2.85328, -2.80227, -2.72022, -2.60025, -2.51370, -2.34286, -2.01859, -1.76204, -1.54159, -1.31686, -1.17313, -1.09307, -0.99484, -0.84203, -0.77646, -0.71827, -0.58102, -0.58351, -0.80660, -0.95890, -0.93070, -0.94450, -1.07610, -1.03839, -0.94194, -0.96975, -1.05652, -1.22048, -1.36337, -1.54060, -1.77207, -2.00923, -2.22226, -2.44933, -2.69074, -2.87589, -3.04588, -3.24196, -3.36069, -3.47561, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.50407, -3.68952, -3.68299, -3.51192, -3.32617, -3.09691, -2.98824, -3.03961, -3.09245, -3.17028, -3.10287, -2.99759, -2.93764, -2.88491, -2.80473, -2.68687, -2.65663, -2.61548, -2.60477, -2.61946, -2.55864, -2.55547, -2.68638, -2.76629, -2.87701, -2.90953, -2.79089, -2.58468, -2.46738, -2.31229, -2.01220, -1.83442, -1.86001, -1.86777, -1.71063, -1.55825, -1.51811, -1.41285, -1.23621, -1.16616, -1.05197, -0.97641, -0.90274, -0.77544, -0.70089, -0.61749, -0.49962, -0.41421, -0.48389, -0.55008, -0.57723, -0.58695, -0.57187, -0.58332, -0.72049, -0.76930, -0.80786, -0.90419, -0.97714, -0.97303, -0.95362, -1.01976, -0.98059, -0.84193, -0.79733, -0.89074, -1.03769, -1.15503, -1.32388, -1.39697, -1.28134, -1.26544, -1.21928, -1.25555, -1.35300, -1.38227, -1.48474, -1.55991, -1.60738, -1.57842, -1.58404, -1.54746, -1.51021, -1.57360, -1.59260, -1.48148, -1.45018, -1.41859, -1.46630, -1.51112, -1.46160, -1.43018, -1.40251, -1.35064, -1.23718, -1.13405, -1.17543, -1.26637, -1.22897, -1.11218, -1.01467, -0.94086, -0.82356, -0.82839, -0.81119, -0.77688, -0.73712, -0.67018, -0.72484, -0.76609, -0.73881, -0.59933, -0.55388, -0.51344, -0.46383, -0.44607, -0.31336, -0.03927, +-0.70025, -0.78961, -0.80804, -0.85225, -0.89115, -0.87801, -0.75224, -0.61614, -0.45399, -0.19168, 0.00883, 0.15329, 0.28848, 0.46482, 0.65051, 0.60581, 0.54557, 0.54253, 0.54004, 0.59057, 0.59315, 0.65211, 0.76608, 0.90662, 1.04577, 1.13680, 1.20390, 1.27961, 1.26084, 1.11897, 0.90763, 0.80956, 0.69218, 0.45739, 0.37340, 0.36999, 0.31277, 0.21364, 0.01033, -0.16595, -0.36429, -0.37951, -0.40100, -0.43978, -0.46119, -0.46043, -0.39411, -0.42398, -0.47372, -0.61262, -0.89085, -1.08082, -1.34453, -1.52162, -1.63115, -1.72144, -1.75849, -1.86312, -1.94295, -1.86550, -1.74337, -1.69882, -1.78342, -1.85312, -1.88047, -1.97962, -1.96133, -1.83693, -1.69249, -1.46860, -1.34910, -1.25897, -1.24160, -1.06741, -0.95150, -0.94450, -0.93070, -0.81458, -0.62839, -0.51351, -0.47489, -0.39474, -0.42010, -0.36727, -0.40247, -0.45670, -0.49399, -0.51388, -0.49927, -0.51006, -0.55859, -0.54086, -0.51067, -0.43848, -0.37649, -0.17733, 0.03908, 0.07399, 0.04762, 0.13689, 0.17068, 0.31956, 0.32170, 0.29074, 0.09799, -0.00924, -0.11891, -0.22166, -0.29993, -0.42994, -0.53263, -0.59711, -0.70077, -0.61289, -0.60278, -0.53004, -0.53148, -0.58544, -0.62208, -0.61508, -0.52792, -0.46181, -0.50847, -0.54967, -0.64602, -0.69927, -0.80331, -0.79532, -0.63525, -0.53492, -0.51469, -0.43403, -0.42255, -0.27862, -0.28630, -0.33868, -0.50079, -0.49818, -0.50437, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.26210, -1.18225, -1.13380, -1.11154, -1.11589, -1.14975, -1.30772, -1.49843, -1.74856, -2.03166, -2.41836, -2.70085, -2.78598, -2.83630, -3.00269, -3.13042, -3.37952, -3.52418, -3.70985, -3.77751, -3.90483, -3.98840, -4.02245, -4.02157, -4.01381, -3.93418, -3.85547, -3.76274, -3.84220, -3.90629, -4.10554, -4.24984, -4.38161, -4.55861, -4.74766, -4.97374, -5.16845, -5.21104, -5.28138, -5.29866, -5.26287, -5.23138, -5.35880, -5.51109, -5.46912, -5.35893, -5.37659, -5.32764, -5.29994, -5.11113, -4.97105, -4.79505, -4.70356, -4.56347, -4.36508, -4.19259, -4.05955, -3.95848, -3.87562, -3.77703, -3.82699, -3.79633, -3.85290, -3.93022, -3.97715, -3.99082, -3.92507, -3.87847, -3.85872, -3.82425, -3.84660, -3.76270, -3.52458, -3.19890, -3.01253, -2.92650, -2.72540, -2.52499, -2.47084, -2.36114, -2.36668, -2.44776, -2.59199, -2.70317, -2.82353, -2.81286, -2.71394, -2.61259, -2.49450, -2.35301, -2.16286, -1.85905, -1.63612, -1.39262, -1.23125, -1.16449, -1.07758, -0.98122, -0.87721, -0.79256, -0.69284, -0.58449, -0.64308, -0.77198, -0.76248, -0.69003, -0.74829, -0.93560, -0.91002, -0.81842, -0.90868, -1.01961, -1.17619, -1.35392, -1.52692, -1.72450, -1.94973, -2.20638, -2.37892, -2.59668, -2.81676, -2.97273, -3.12333, -3.23588, -3.38747, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.51605, -3.47807, -3.41072, -3.37844, -3.22991, -3.14061, -3.22142, -3.31680, -3.36341, -3.32706, -3.21479, -3.11485, -2.96827, -2.89292, -2.72884, -2.64545, -2.61003, -2.60805, -2.63233, -2.70205, -2.87596, -3.02584, -3.08013, -3.15482, -3.02185, -2.86335, -2.70724, -2.60636, -2.41334, -2.11219, -1.96061, -1.96652, -1.85994, -1.69419, -1.56973, -1.57036, -1.43638, -1.21323, -1.09107, -0.99671, -0.87342, -0.80078, -0.63712, -0.55570, -0.43928, -0.40439, -0.31176, -0.34400, -0.43123, -0.47780, -0.47911, -0.49338, -0.58782, -0.75736, -0.79839, -0.86119, -0.76202, -0.67452, -0.67147, -0.73493, -0.80045, -0.74783, -0.66368, -0.66117, -0.66838, -0.77487, -0.87115, -1.07424, -1.12093, -0.99719, -0.98665, -1.02780, -1.01822, -1.12680, -1.13797, -1.21110, -1.19702, -1.29605, -1.29139, -1.36119, -1.43956, -1.43638, -1.42469, -1.38415, -1.32464, -1.35500, -1.32796, -1.42169, -1.35323, -1.25466, -1.23738, -1.27502, -1.25777, -1.15551, -1.05608, -1.07769, -1.03850, -0.96196, -0.84769, -0.85347, -0.84197, -0.74532, -0.73755, -0.82526, -0.80111, -0.81697, -0.74545, -0.80085, -0.77001, -0.77571, -0.64964, -0.55298, -0.52190, -0.50630, -0.42966, -0.25393, 0.03727, +-0.68901, -0.71595, -0.69797, -0.76210, -0.85657, -0.87211, -0.74254, -0.55144, -0.31845, -0.13552, -0.01841, 0.14477, 0.31429, 0.49965, 0.69129, 0.76673, 0.65854, 0.51606, 0.46874, 0.51326, 0.59106, 0.63646, 0.76383, 1.01236, 1.09896, 1.14192, 1.26416, 1.37875, 1.28537, 1.02577, 0.88653, 0.84265, 0.65078, 0.40767, 0.29758, 0.22591, 0.12906, -0.01148, -0.18914, -0.35098, -0.51114, -0.51352, -0.52729, -0.51791, -0.52588, -0.50023, -0.46065, -0.55168, -0.72536, -0.95837, -1.15751, -1.31768, -1.46829, -1.59220, -1.71964, -1.76467, -1.87344, -2.02151, -2.04434, -1.90526, -1.75226, -1.78624, -1.81502, -1.88088, -2.00602, -2.11055, -2.02110, -1.82750, -1.64196, -1.50285, -1.42141, -1.32803, -1.20857, -0.99068, -0.84197, -0.69553, -0.69158, -0.73072, -0.66030, -0.55251, -0.55221, -0.66554, -0.68747, -0.60511, -0.57970, -0.57249, -0.57358, -0.47947, -0.47491, -0.55982, -0.55037, -0.44766, -0.40123, -0.44731, -0.39328, -0.18849, -0.04676, -0.03733, 0.02776, 0.13161, 0.17022, 0.27383, 0.27708, 0.21666, 0.07144, 0.04610, -0.06843, -0.17060, -0.27701, -0.41327, -0.47088, -0.49995, -0.56147, -0.63355, -0.66291, -0.65475, -0.68949, -0.70905, -0.76982, -0.67229, -0.53506, -0.54521, -0.57698, -0.60498, -0.68643, -0.81808, -0.85692, -0.70084, -0.56883, -0.60084, -0.60184, -0.55141, -0.50498, -0.41546, -0.37265, -0.34104, -0.48277, -0.53800, -0.60835, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.35117, -1.24363, -1.20047, -1.06410, -1.00476, -1.12227, -1.30461, -1.48456, -1.71241, -2.09030, -2.45317, -2.66227, -2.81307, -2.96968, -3.12303, -3.29792, -3.53431, -3.68590, -3.88488, -4.01102, -4.14182, -4.12400, -4.09985, -4.01781, -3.95135, -3.96141, -3.97665, -3.97471, -4.07521, -4.26241, -4.43461, -4.48406, -4.50406, -4.57231, -4.77148, -4.97185, -5.12417, -5.23679, -5.27041, -5.16553, -5.07444, -5.18109, -5.37307, -5.43550, -5.38321, -5.37465, -5.29739, -5.14977, -5.11940, -5.04034, -4.91634, -4.67222, -4.52711, -4.37100, -4.18444, -3.98310, -3.86033, -3.85029, -3.83271, -3.81650, -3.90315, -4.02873, -4.08420, -4.06560, -4.05092, -3.99011, -3.98224, -3.94568, -3.88905, -3.94222, -3.96684, -3.83762, -3.55124, -3.26283, -3.10232, -2.92686, -2.68628, -2.52325, -2.45764, -2.39509, -2.43362, -2.49016, -2.57535, -2.60522, -2.65299, -2.61895, -2.57861, -2.52155, -2.40803, -2.31163, -2.16820, -1.85763, -1.54963, -1.39349, -1.31963, -1.27933, -1.21297, -1.05520, -0.94110, -0.79964, -0.64812, -0.67064, -0.79275, -0.83966, -0.72535, -0.67045, -0.70323, -0.72707, -0.74276, -0.86242, -1.00148, -1.07137, -1.24311, -1.47878, -1.64732, -1.78471, -2.00242, -2.22489, -2.39437, -2.61284, -2.80492, -2.98833, -3.12945, -3.18606, -3.24634, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.39399, -3.34853, -3.41929, -3.41840, -3.31645, -3.29306, -3.35319, -3.36412, -3.38944, -3.39750, -3.34472, -3.24390, -3.09852, -2.98685, -2.84463, -2.75029, -2.64051, -2.68537, -2.81538, -2.95490, -3.08919, -3.21424, -3.31115, -3.27619, -3.14982, -3.01540, -2.89113, -2.81012, -2.52225, -2.24400, -2.06183, -1.93943, -1.81221, -1.71227, -1.69168, -1.59675, -1.43345, -1.31224, -1.17644, -0.97218, -0.84271, -0.74600, -0.58162, -0.45945, -0.36034, -0.33110, -0.22831, -0.24894, -0.27176, -0.36982, -0.51616, -0.57967, -0.62790, -0.71671, -0.80491, -0.79683, -0.65186, -0.50065, -0.47270, -0.60091, -0.57499, -0.49202, -0.50436, -0.50374, -0.45260, -0.44355, -0.56089, -0.65638, -0.63903, -0.66262, -0.79305, -0.85549, -0.89477, -1.00319, -1.05116, -1.03125, -0.95132, -1.03967, -1.07403, -1.22472, -1.26943, -1.25463, -1.27095, -1.19963, -1.15781, -1.23365, -1.39647, -1.47137, -1.38802, -1.28499, -1.15609, -1.18565, -1.16812, -1.11482, -1.08610, -1.02160, -0.93536, -0.84079, -0.79391, -0.77520, -0.75751, -0.77629, -0.88214, -0.94929, -0.96767, -0.99456, -0.92559, -0.89335, -0.80149, -0.80295, -0.71874, -0.66187, -0.56708, -0.47456, -0.39855, -0.21559, 0.11115, +-0.79938, -0.69850, -0.67948, -0.74778, -0.72359, -0.62962, -0.52611, -0.35678, -0.12663, -0.06747, -0.08472, 0.06006, 0.27098, 0.46699, 0.61889, 0.77389, 0.72084, 0.54643, 0.47203, 0.49737, 0.57518, 0.53972, 0.57559, 0.84158, 0.91377, 0.98825, 1.13234, 1.21757, 1.17764, 0.94574, 0.84227, 0.73303, 0.51048, 0.42633, 0.33860, 0.20037, 0.12184, 0.02025, -0.12805, -0.31056, -0.44314, -0.53802, -0.68628, -0.70465, -0.68995, -0.67760, -0.72625, -0.86357, -1.01151, -1.18466, -1.28824, -1.42579, -1.51337, -1.64873, -1.83895, -1.87388, -1.96683, -2.05520, -2.05846, -2.02509, -1.85912, -1.88289, -1.86953, -1.97737, -2.06303, -1.94859, -1.80598, -1.68024, -1.50037, -1.40620, -1.36396, -1.33823, -1.14838, -0.94045, -0.83250, -0.66287, -0.65472, -0.78829, -0.82500, -0.72837, -0.67258, -0.82270, -0.84424, -0.78125, -0.73815, -0.74328, -0.73890, -0.57968, -0.53576, -0.60270, -0.55790, -0.53682, -0.43528, -0.41316, -0.29600, -0.14605, -0.08109, 0.07691, 0.24890, 0.27112, 0.29924, 0.33708, 0.27459, 0.11298, 0.00430, -0.02907, -0.21561, -0.37652, -0.44810, -0.52490, -0.55739, -0.59259, -0.56465, -0.64134, -0.67803, -0.72121, -0.76904, -0.81766, -0.94059, -0.87550, -0.74913, -0.79489, -0.79822, -0.90378, -0.84860, -0.84009, -0.79891, -0.64880, -0.61988, -0.60200, -0.54880, -0.60355, -0.53594, -0.44513, -0.36596, -0.36980, -0.49887, -0.61609, -0.76233, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.40539, -1.35989, -1.38159, -1.25339, -1.12635, -1.20355, -1.30299, -1.56925, -1.77552, -2.05957, -2.32608, -2.53719, -2.80961, -2.98009, -3.09890, -3.38246, -3.62639, -3.77557, -3.98359, -4.21822, -4.32616, -4.22655, -4.20107, -4.15951, -4.05305, -4.09342, -4.17652, -4.26593, -4.29827, -4.40924, -4.49621, -4.49483, -4.49627, -4.58112, -4.82097, -5.01790, -5.02014, -5.07443, -5.04226, -5.00892, -4.96362, -5.05818, -5.23447, -5.30200, -5.34209, -5.32421, -5.10491, -4.97954, -4.98047, -4.93437, -4.78330, -4.54262, -4.36681, -4.21535, -4.11287, -4.01937, -3.92117, -3.93324, -3.93260, -3.99740, -4.07391, -4.18943, -4.19747, -4.11048, -4.05394, -3.96438, -3.99116, -4.01832, -3.92141, -3.94745, -3.88477, -3.80291, -3.57070, -3.27519, -3.11066, -2.91693, -2.76705, -2.61920, -2.46172, -2.48086, -2.54963, -2.51467, -2.51549, -2.53899, -2.55865, -2.50094, -2.53400, -2.57194, -2.44620, -2.32788, -2.21517, -1.99543, -1.68824, -1.52144, -1.44439, -1.34974, -1.20667, -1.01566, -0.96220, -0.90992, -0.78555, -0.86531, -0.97819, -1.04326, -0.95741, -0.82273, -0.74420, -0.66878, -0.78711, -0.99318, -1.00661, -1.05444, -1.28154, -1.52636, -1.68499, -1.84613, -2.09958, -2.27204, -2.44112, -2.70485, -2.89911, -3.07140, -3.21247, -3.28805, -3.28791, -3.24865, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.49393, -3.50542, -3.48941, -3.46405, -3.35250, -3.31034, -3.38875, -3.39429, -3.34285, -3.25271, -3.14275, -2.98886, -2.91606, -2.93481, -2.89023, -2.95974, -3.13048, -3.25930, -3.25400, -3.22384, -3.25461, -3.17153, -3.10615, -3.02186, -2.99855, -3.01537, -2.72423, -2.43526, -2.18240, -1.99816, -1.98793, -1.87624, -1.79993, -1.62145, -1.52854, -1.50153, -1.23480, -0.95856, -0.89604, -0.73345, -0.48805, -0.32390, -0.30427, -0.27799, -0.22424, -0.30171, -0.33493, -0.39802, -0.57126, -0.67212, -0.68294, -0.59133, -0.56549, -0.47790, -0.34692, -0.23625, -0.29466, -0.51282, -0.49989, -0.39666, -0.41846, -0.39367, -0.40269, -0.25985, -0.27522, -0.29341, -0.33455, -0.50696, -0.59085, -0.60872, -0.73314, -0.81067, -0.84560, -0.80842, -0.81745, -0.90171, -0.97747, -1.14544, -1.14539, -1.07921, -1.10840, -1.08943, -1.13655, -1.18845, -1.37509, -1.43197, -1.36502, -1.27938, -1.16831, -1.25998, -1.31923, -1.27504, -1.22551, -1.06406, -1.07353, -0.96381, -0.85868, -0.79842, -0.83873, -0.96741, -0.98673, -0.95788, -1.08221, -1.12020, -1.02025, -0.91149, -0.83381, -0.77464, -0.69162, -0.69177, -0.62005, -0.42927, -0.30670, -0.13871, 0.11796, +-0.81975, -0.75994, -0.72298, -0.71640, -0.57859, -0.37221, -0.29147, -0.14472, -0.01004, -0.04748, -0.01230, 0.15268, 0.34510, 0.58125, 0.68053, 0.73388, 0.67018, 0.49978, 0.42780, 0.43795, 0.42686, 0.35777, 0.41411, 0.62454, 0.63491, 0.70824, 0.93683, 1.07201, 1.08195, 0.93606, 0.70784, 0.53770, 0.43295, 0.39532, 0.35737, 0.29193, 0.21771, 0.15440, -0.02815, -0.22933, -0.40003, -0.60921, -0.75216, -0.75493, -0.79655, -0.80882, -0.93385, -1.16386, -1.29687, -1.43482, -1.51082, -1.63195, -1.74868, -1.86433, -1.96867, -1.97582, -2.03569, -2.06243, -2.01300, -1.99423, -1.91027, -1.89076, -1.95920, -2.08449, -1.96786, -1.75203, -1.65366, -1.54463, -1.44364, -1.34453, -1.32589, -1.30827, -1.11133, -0.97866, -0.84612, -0.67318, -0.74940, -0.88565, -0.93910, -0.91358, -0.84247, -0.96989, -1.00910, -0.97461, -0.98137, -0.98877, -0.87067, -0.63965, -0.60175, -0.67291, -0.61741, -0.58119, -0.50335, -0.33983, -0.21339, -0.11089, 0.04848, 0.26745, 0.36467, 0.37830, 0.34450, 0.36205, 0.24331, 0.04325, -0.07246, -0.23019, -0.42086, -0.51298, -0.61009, -0.66362, -0.69177, -0.82509, -0.79841, -0.83835, -0.87759, -0.91245, -0.95586, -1.00734, -1.07631, -1.02054, -1.01158, -1.13199, -1.12318, -1.14258, -1.03387, -0.85613, -0.83479, -0.80549, -0.71754, -0.58360, -0.54876, -0.55181, -0.49040, -0.36789, -0.31449, -0.40260, -0.55097, -0.75758, -0.87954, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.54365, -1.58933, -1.60842, -1.46261, -1.35850, -1.40279, -1.39940, -1.55617, -1.78647, -1.96407, -2.23896, -2.57766, -2.80872, -2.89466, -3.08892, -3.35693, -3.63627, -3.80830, -4.04603, -4.33093, -4.42584, -4.40674, -4.40820, -4.30494, -4.22660, -4.27845, -4.34107, -4.49252, -4.46613, -4.44063, -4.45510, -4.42068, -4.48250, -4.65426, -4.84096, -4.92370, -4.86243, -4.90418, -4.87052, -4.80915, -4.83854, -4.85495, -5.00119, -5.19512, -5.21976, -5.10003, -4.96572, -4.89630, -4.93826, -4.87508, -4.68049, -4.44047, -4.23137, -4.15638, -4.13868, -4.03484, -3.97843, -4.01618, -3.96783, -4.09651, -4.22355, -4.31011, -4.31414, -4.20537, -4.15417, -4.09252, -4.02763, -3.96394, -3.88269, -3.94235, -3.88332, -3.74914, -3.55878, -3.23809, -3.04971, -2.98323, -2.86481, -2.64936, -2.55961, -2.60063, -2.66456, -2.60917, -2.57429, -2.62332, -2.61780, -2.59491, -2.67472, -2.62005, -2.42152, -2.28737, -2.14992, -2.04704, -1.88814, -1.73450, -1.64121, -1.48695, -1.29381, -1.16246, -1.12660, -1.06345, -1.00450, -1.13450, -1.24345, -1.24071, -1.15025, -0.96827, -0.81576, -0.85532, -0.97992, -1.02873, -0.99675, -1.02445, -1.22447, -1.48016, -1.63976, -1.86619, -2.12255, -2.30252, -2.49015, -2.66565, -2.82682, -3.04311, -3.18442, -3.32202, -3.40144, -3.29629, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.66481, -3.70205, -3.55739, -3.41540, -3.40500, -3.45595, -3.46894, -3.37801, -3.28262, -3.12531, -2.96085, -2.99070, -3.04112, -3.04414, -3.18500, -3.31944, -3.39119, -3.36033, -3.24728, -3.21648, -3.14491, -3.12360, -3.11798, -3.13483, -3.10343, -2.81626, -2.57799, -2.36559, -2.18363, -2.15715, -2.05108, -1.84982, -1.72457, -1.71226, -1.59841, -1.30193, -1.08185, -0.97290, -0.78348, -0.43711, -0.25594, -0.26350, -0.26944, -0.34692, -0.41974, -0.39110, -0.43328, -0.51510, -0.58074, -0.64543, -0.50018, -0.39161, -0.26707, -0.13816, -0.10836, -0.22428, -0.38617, -0.37794, -0.34872, -0.39601, -0.33789, -0.29288, -0.17135, -0.08800, -0.17555, -0.34351, -0.45839, -0.47064, -0.50469, -0.53464, -0.59356, -0.59124, -0.61505, -0.72541, -0.82084, -0.98312, -1.08993, -0.96139, -0.92056, -0.96159, -0.98293, -1.16779, -1.23480, -1.37843, -1.42846, -1.36782, -1.35411, -1.35880, -1.46262, -1.51178, -1.49925, -1.44371, -1.23621, -1.17773, -1.10046, -0.90794, -0.88059, -1.03568, -1.08308, -0.95993, -0.96640, -1.07325, -1.14766, -1.03582, -0.91964, -0.85067, -0.69839, -0.62864, -0.61878, -0.46942, -0.30779, -0.19499, -0.01632, 0.12039, +-0.78298, -0.86162, -0.77381, -0.66148, -0.49520, -0.24187, -0.13399, 0.02168, 0.12348, 0.05331, 0.09725, 0.27935, 0.45988, 0.70000, 0.78550, 0.74299, 0.61591, 0.44604, 0.40118, 0.34272, 0.28399, 0.28688, 0.33450, 0.43254, 0.43613, 0.57385, 0.85064, 0.95505, 0.93339, 0.82367, 0.62682, 0.58068, 0.50162, 0.29631, 0.24075, 0.25573, 0.17702, 0.12230, -0.11170, -0.31436, -0.44063, -0.65149, -0.79090, -0.81784, -0.91969, -0.99875, -1.14969, -1.34665, -1.48211, -1.65011, -1.70137, -1.80541, -1.85010, -1.79133, -1.84178, -1.92570, -1.99325, -1.93035, -1.81840, -1.83773, -1.87835, -1.87955, -1.94482, -1.90509, -1.69820, -1.62635, -1.59090, -1.51783, -1.58309, -1.53277, -1.49650, -1.37137, -1.07997, -0.95257, -0.90435, -0.89134, -1.04456, -1.12436, -1.09623, -1.05427, -1.01244, -1.15718, -1.18679, -1.17845, -1.18813, -1.06398, -0.88287, -0.69482, -0.64736, -0.60999, -0.47475, -0.44293, -0.46471, -0.33990, -0.24173, -0.00849, 0.24775, 0.31059, 0.25269, 0.24936, 0.13547, 0.12649, 0.03289, -0.09581, -0.14959, -0.35441, -0.61338, -0.73580, -0.87437, -0.93451, -0.92365, -1.01267, -0.94633, -0.98504, -1.02720, -1.08914, -1.17131, -1.10657, -1.09503, -1.10062, -1.17434, -1.24143, -1.17693, -1.14776, -1.10352, -0.93330, -0.92472, -0.85761, -0.73177, -0.67375, -0.65594, -0.50515, -0.43292, -0.35632, -0.39277, -0.56918, -0.66670, -0.77580, -0.86720, -0.80879, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.72891, -1.66827, -1.59093, -1.48566, -1.44444, -1.44470, -1.38245, -1.46311, -1.74267, -1.95893, -2.30776, -2.60853, -2.73177, -2.87001, -3.13187, -3.31073, -3.61768, -3.90722, -4.20682, -4.47603, -4.51905, -4.46903, -4.49397, -4.42531, -4.35318, -4.38857, -4.40678, -4.51508, -4.46092, -4.40202, -4.35039, -4.27274, -4.38127, -4.46681, -4.52782, -4.57059, -4.54081, -4.52699, -4.45367, -4.42103, -4.60847, -4.66992, -4.79212, -4.88960, -4.81072, -4.80042, -4.93493, -4.97466, -5.03615, -4.96384, -4.74837, -4.53190, -4.28282, -4.13904, -4.15380, -4.12600, -4.13291, -4.20433, -4.11599, -4.18328, -4.27935, -4.34792, -4.31677, -4.18306, -4.18577, -4.10937, -3.94158, -3.83616, -3.79074, -3.83679, -3.78544, -3.63007, -3.52337, -3.25630, -3.05118, -2.94474, -2.75149, -2.65437, -2.77919, -2.81389, -2.85720, -2.83948, -2.79813, -2.82855, -2.71345, -2.58436, -2.66444, -2.65139, -2.50506, -2.38748, -2.19417, -2.07202, -1.96018, -1.84023, -1.74524, -1.54336, -1.38022, -1.23384, -1.11316, -1.10833, -1.19507, -1.31047, -1.31936, -1.19712, -1.15094, -1.06945, -1.00835, -1.10176, -1.04137, -0.96657, -1.03511, -1.08786, -1.25373, -1.53266, -1.71182, -1.97508, -2.17587, -2.27066, -2.43052, -2.60378, -2.79210, -3.01498, -3.10302, -3.21850, -3.33509, -3.29705, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.73340, -3.54519, -3.55595, -3.57066, -3.52614, -3.55253, -3.47818, -3.42235, -3.23383, -2.98313, -2.97724, -3.07343, -3.17052, -3.34166, -3.40185, -3.36194, -3.27282, -3.14359, -3.13214, -3.11737, -3.18438, -3.19808, -3.07030, -2.93590, -2.72437, -2.56228, -2.40563, -2.26345, -2.22989, -2.16213, -1.97988, -1.92970, -1.82728, -1.64333, -1.51643, -1.38105, -1.19873, -1.02131, -0.65856, -0.46490, -0.41922, -0.31676, -0.33358, -0.42361, -0.46638, -0.56314, -0.57881, -0.52708, -0.51316, -0.38187, -0.32955, -0.18791, -0.06705, -0.04824, -0.01836, -0.07857, -0.16106, -0.25230, -0.26204, -0.15462, -0.10869, -0.09544, -0.05773, -0.18196, -0.22875, -0.24696, -0.39440, -0.53606, -0.50333, -0.55873, -0.54497, -0.61133, -0.74121, -0.75462, -0.83936, -0.92411, -0.84306, -0.85231, -0.91206, -0.97036, -1.18180, -1.24898, -1.37251, -1.35860, -1.31377, -1.40589, -1.45311, -1.56417, -1.62765, -1.62053, -1.51408, -1.30790, -1.22115, -1.20988, -1.05759, -1.06181, -1.11366, -1.03408, -0.98432, -1.08665, -1.12621, -1.17348, -1.05041, -0.94419, -0.88453, -0.67327, -0.50180, -0.45097, -0.33511, -0.27924, -0.24302, -0.04180, 0.11698, +-0.90830, -0.91896, -0.74178, -0.53937, -0.38572, -0.15586, 0.06680, 0.19956, 0.18296, 0.15387, 0.19678, 0.40269, 0.67832, 0.85554, 0.84302, 0.72380, 0.66352, 0.60449, 0.55050, 0.41519, 0.25610, 0.18954, 0.21662, 0.31278, 0.36687, 0.56799, 0.78916, 0.81348, 0.80606, 0.74724, 0.69066, 0.66927, 0.46366, 0.19084, 0.08953, 0.12549, 0.10862, 0.07855, -0.12076, -0.37262, -0.60506, -0.81655, -0.94869, -0.98750, -0.97105, -1.05070, -1.24880, -1.40560, -1.50076, -1.61937, -1.68374, -1.74101, -1.70790, -1.66222, -1.73611, -1.84584, -1.95139, -1.85316, -1.72563, -1.78328, -1.83732, -1.82004, -1.77834, -1.65658, -1.61524, -1.64363, -1.60339, -1.58631, -1.70690, -1.67922, -1.54490, -1.33510, -1.13252, -1.06476, -1.10397, -1.23299, -1.24449, -1.17887, -1.13589, -1.14596, -1.15263, -1.20655, -1.22144, -1.19597, -1.15030, -1.05206, -0.92277, -0.75431, -0.65794, -0.49908, -0.30556, -0.33412, -0.39983, -0.37634, -0.30552, 0.00449, 0.20166, 0.20324, 0.08996, 0.00870, -0.12765, -0.16923, -0.16178, -0.17799, -0.25988, -0.49754, -0.75616, -0.93962, -1.00339, -1.00580, -1.03535, -1.10318, -1.01134, -0.97969, -1.05530, -1.17949, -1.31149, -1.31259, -1.29303, -1.27015, -1.32382, -1.28557, -1.16569, -1.18185, -1.22681, -1.12927, -1.06641, -0.91265, -0.85891, -0.80975, -0.67216, -0.42843, -0.33134, -0.33188, -0.42867, -0.60465, -0.69487, -0.74748, -0.77629, -0.87939, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.74600, -1.67719, -1.58526, -1.48637, -1.46904, -1.47768, -1.44050, -1.54292, -1.79005, -2.02382, -2.40179, -2.62214, -2.79997, -3.00561, -3.16888, -3.26943, -3.51268, -3.84245, -4.13605, -4.31173, -4.40603, -4.43649, -4.43771, -4.45547, -4.33722, -4.25415, -4.30670, -4.44672, -4.45193, -4.31275, -4.17256, -4.06682, -4.11515, -4.16710, -4.20025, -4.21946, -4.25247, -4.21112, -4.08833, -4.12128, -4.35331, -4.41587, -4.47964, -4.42519, -4.43667, -4.63485, -4.89671, -5.01784, -5.00795, -4.87704, -4.65219, -4.45348, -4.28954, -4.18987, -4.15582, -4.21501, -4.22194, -4.18599, -4.15037, -4.23132, -4.29747, -4.24857, -4.13042, -4.02363, -4.04072, -4.07110, -3.99097, -3.85352, -3.75301, -3.74400, -3.70415, -3.61146, -3.56101, -3.32506, -3.07916, -2.82625, -2.64512, -2.71257, -2.86363, -2.87703, -2.89515, -2.88528, -2.83521, -2.76878, -2.64110, -2.57525, -2.63275, -2.73805, -2.69672, -2.47684, -2.24729, -2.13168, -2.03344, -1.85134, -1.68294, -1.52188, -1.43644, -1.33481, -1.24968, -1.27277, -1.36690, -1.40889, -1.31172, -1.15541, -1.18329, -1.19044, -1.22479, -1.21867, -1.01036, -0.91436, -0.95930, -1.06903, -1.24035, -1.47646, -1.64552, -1.83701, -2.02303, -2.18877, -2.34669, -2.56105, -2.76776, -2.83030, -2.86351, -3.03482, -3.23130, -3.29489, -3.23551, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.59537, -3.58480, -3.50816, -3.51894, -3.48278, -3.44468, -3.32510, -3.14786, -3.08199, -3.17311, -3.32429, -3.34133, -3.28403, -3.25723, -3.22888, -3.10228, -3.01313, -3.03955, -3.12799, -3.11240, -2.98776, -2.82578, -2.65368, -2.55628, -2.45678, -2.32777, -2.26089, -2.14595, -2.03178, -2.04165, -1.91100, -1.80517, -1.72335, -1.56768, -1.35722, -1.15283, -0.83167, -0.58765, -0.47613, -0.37285, -0.34171, -0.42956, -0.60307, -0.69668, -0.63177, -0.52915, -0.44416, -0.32124, -0.24239, -0.11404, -0.01726, 0.03428, 0.07854, 0.07558, 0.02422, -0.09058, -0.04317, 0.09271, 0.07757, 0.04211, 0.02175, -0.07933, -0.03356, -0.14190, -0.37860, -0.57110, -0.59708, -0.60427, -0.56051, -0.58372, -0.65900, -0.68257, -0.73993, -0.82683, -0.93310, -0.90552, -0.86359, -0.96949, -1.18077, -1.23477, -1.23072, -1.17830, -1.20357, -1.36436, -1.57028, -1.69917, -1.66324, -1.59291, -1.47497, -1.34828, -1.31649, -1.28456, -1.14508, -1.10797, -1.01534, -0.99054, -1.05232, -1.13399, -1.14161, -1.09172, -0.94491, -0.82866, -0.76231, -0.67913, -0.53516, -0.38106, -0.33344, -0.29654, -0.22261, -0.07138, 0.05976, +-1.11008, -0.98321, -0.74182, -0.46929, -0.32647, -0.10835, 0.18526, 0.26567, 0.23218, 0.33925, 0.42851, 0.61290, 0.79467, 0.80889, 0.76635, 0.68047, 0.67324, 0.66194, 0.57529, 0.40047, 0.25016, 0.14375, 0.14534, 0.26339, 0.29636, 0.48201, 0.71242, 0.75061, 0.76895, 0.75222, 0.70135, 0.57167, 0.30734, 0.12743, 0.03109, 0.08214, 0.08819, 0.06765, -0.06524, -0.40408, -0.74366, -0.92950, -1.06094, -1.10419, -1.06479, -1.19625, -1.35978, -1.47626, -1.58618, -1.68581, -1.75150, -1.76131, -1.65370, -1.64549, -1.76242, -1.85587, -1.99793, -1.92053, -1.74990, -1.75478, -1.80843, -1.75959, -1.67907, -1.60610, -1.68963, -1.67706, -1.63998, -1.64132, -1.73235, -1.73017, -1.54859, -1.43333, -1.40193, -1.31600, -1.31049, -1.38599, -1.27725, -1.25259, -1.21493, -1.23969, -1.30644, -1.33250, -1.32985, -1.26708, -1.12141, -0.99405, -0.91765, -0.74935, -0.65709, -0.51758, -0.32852, -0.34276, -0.41845, -0.40338, -0.34173, -0.07671, 0.03528, 0.11670, 0.00946, -0.13820, -0.30196, -0.44821, -0.41356, -0.44076, -0.56185, -0.66563, -0.78486, -0.93516, -0.96015, -1.06545, -1.14561, -1.20113, -1.19345, -1.23000, -1.34519, -1.48774, -1.56820, -1.52728, -1.52134, -1.47110, -1.54247, -1.53819, -1.39821, -1.37271, -1.46923, -1.38019, -1.27904, -1.08876, -1.02902, -0.83299, -0.58766, -0.36192, -0.29093, -0.37707, -0.45532, -0.60576, -0.72017, -0.71867, -0.65977, -0.79516, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.68706, -1.66865, -1.60127, -1.60444, -1.67892, -1.64250, -1.66215, -1.86136, -2.03192, -2.37261, -2.59145, -2.86684, -3.06699, -3.16367, -3.24378, -3.39627, -3.68605, -3.89792, -4.04888, -4.24867, -4.31692, -4.24762, -4.27241, -4.17523, -4.20369, -4.33617, -4.45901, -4.48928, -4.33696, -4.14988, -4.03928, -4.02722, -3.98592, -4.01955, -4.02913, -4.10089, -4.11620, -3.96879, -3.88523, -4.02144, -4.02162, -4.05814, -4.04391, -4.24259, -4.51316, -4.75357, -4.87617, -4.79770, -4.68742, -4.47597, -4.32687, -4.30518, -4.24788, -4.10676, -4.13234, -4.10600, -4.11017, -4.17925, -4.25175, -4.30755, -4.26715, -4.16258, -4.10699, -4.09621, -4.07915, -4.03310, -3.87557, -3.73047, -3.72460, -3.68186, -3.54700, -3.50318, -3.31373, -3.08271, -2.81588, -2.70203, -2.75709, -2.80654, -2.82280, -2.82055, -2.82711, -2.76579, -2.65514, -2.65420, -2.69478, -2.66541, -2.75483, -2.72286, -2.52550, -2.38634, -2.28696, -2.22136, -2.06904, -1.88048, -1.76761, -1.71583, -1.56186, -1.48249, -1.46703, -1.48687, -1.53809, -1.45279, -1.29154, -1.34076, -1.35954, -1.35598, -1.22321, -0.96609, -0.83677, -0.76498, -0.90568, -1.08543, -1.31333, -1.48378, -1.62152, -1.88136, -2.12806, -2.20955, -2.37588, -2.54869, -2.60855, -2.78221, -3.01300, -3.25336, -3.41078, -3.36632, -3.20913, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.48260, -3.46343, -3.51685, -3.53192, -3.48439, -3.47503, -3.39437, -3.23017, -3.24967, -3.37904, -3.33542, -3.33226, -3.32471, -3.32739, -3.25105, -3.13681, -3.12981, -3.16050, -3.06323, -2.94706, -2.86433, -2.73939, -2.70291, -2.63579, -2.40826, -2.21595, -2.07163, -1.97617, -2.04565, -2.00647, -1.98899, -1.81840, -1.62584, -1.41527, -1.19812, -0.94169, -0.65591, -0.57860, -0.56647, -0.49021, -0.51166, -0.67720, -0.74045, -0.73401, -0.60994, -0.45667, -0.33899, -0.25211, -0.13991, -0.08530, -0.02048, 0.04606, 0.05117, 0.09129, 0.02650, 0.06400, 0.22652, 0.26385, 0.21059, 0.18017, 0.04272, -0.02583, -0.27983, -0.45449, -0.61929, -0.66861, -0.62518, -0.59554, -0.57516, -0.68603, -0.79187, -0.79975, -0.83764, -1.00028, -0.95258, -0.96445, -1.04380, -1.16548, -1.23119, -1.23468, -1.23799, -1.34058, -1.48960, -1.66614, -1.76989, -1.66689, -1.59318, -1.55357, -1.47304, -1.38320, -1.30966, -1.11351, -1.02688, -0.91776, -0.98290, -1.01801, -1.04482, -1.06306, -1.00036, -0.93676, -0.81048, -0.76556, -0.79167, -0.61068, -0.31683, -0.21920, -0.13337, -0.13872, -0.07018, 0.02252, +-1.25607, -1.10762, -0.81506, -0.44649, -0.28543, -0.12691, 0.12301, 0.28239, 0.38708, 0.52281, 0.59340, 0.69443, 0.67331, 0.60602, 0.63325, 0.61513, 0.66877, 0.71383, 0.57563, 0.36370, 0.30392, 0.23438, 0.18654, 0.30890, 0.32259, 0.45340, 0.65169, 0.72283, 0.78798, 0.77788, 0.63680, 0.39642, 0.19006, 0.06711, 0.03193, 0.14127, 0.11297, -0.01565, -0.17806, -0.46022, -0.73132, -0.97607, -1.19083, -1.26788, -1.31996, -1.47611, -1.53957, -1.63678, -1.73621, -1.75444, -1.81659, -1.85212, -1.68679, -1.65018, -1.80044, -1.87538, -1.97862, -1.92246, -1.75862, -1.73490, -1.76758, -1.73008, -1.67089, -1.66834, -1.70062, -1.68230, -1.68047, -1.65369, -1.71616, -1.83351, -1.74732, -1.69642, -1.68405, -1.60906, -1.57397, -1.53749, -1.41330, -1.45444, -1.35433, -1.35092, -1.41584, -1.37322, -1.35101, -1.31996, -1.08616, -0.86003, -0.81307, -0.66810, -0.56525, -0.50002, -0.38874, -0.42841, -0.45608, -0.41694, -0.32809, -0.16336, -0.05030, 0.02810, -0.09770, -0.24625, -0.43473, -0.76562, -0.84100, -0.85453, -0.85184, -0.82628, -0.86671, -0.96441, -1.02146, -1.23946, -1.30070, -1.37037, -1.46908, -1.54105, -1.65732, -1.83727, -1.80241, -1.60280, -1.59214, -1.57905, -1.67502, -1.77060, -1.66825, -1.63589, -1.67045, -1.56797, -1.44958, -1.30008, -1.10790, -0.81431, -0.55537, -0.36555, -0.33462, -0.53961, -0.64757, -0.73817, -0.75663, -0.74011, -0.70116, -0.80213, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.61788, -1.67032, -1.69702, -1.69682, -1.81401, -1.75157, -1.73748, -1.85732, -1.96955, -2.24099, -2.52817, -2.79422, -3.01430, -3.16333, -3.22853, -3.30532, -3.59637, -3.80393, -3.95922, -4.09638, -4.13665, -4.10788, -4.14647, -4.13411, -4.33604, -4.45289, -4.50232, -4.50459, -4.29539, -4.06052, -4.03134, -4.02549, -3.86096, -3.86272, -3.88952, -3.92074, -3.97845, -3.83656, -3.67397, -3.64649, -3.58106, -3.61446, -3.77425, -4.06351, -4.32805, -4.56449, -4.64512, -4.53697, -4.54375, -4.44572, -4.37086, -4.32842, -4.24145, -4.10637, -4.08724, -4.04007, -4.14995, -4.22618, -4.23789, -4.29276, -4.25900, -4.17310, -4.21714, -4.19837, -4.01441, -3.88044, -3.74413, -3.58017, -3.59218, -3.54959, -3.41159, -3.33559, -3.19454, -3.02390, -2.86928, -2.79530, -2.77858, -2.81292, -2.82951, -2.78112, -2.82499, -2.83511, -2.76673, -2.76096, -2.77647, -2.74695, -2.79685, -2.72816, -2.63541, -2.56096, -2.46508, -2.47020, -2.34106, -2.09631, -2.01142, -1.96273, -1.69365, -1.56019, -1.53098, -1.48962, -1.57165, -1.56763, -1.49084, -1.52106, -1.47211, -1.37603, -1.17980, -0.91495, -0.72575, -0.63041, -0.76150, -0.91151, -1.18002, -1.45237, -1.64041, -1.86138, -2.04451, -2.12048, -2.25416, -2.38294, -2.54921, -2.84668, -3.07015, -3.32964, -3.47948, -3.35493, -3.22735, -3.16065, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.46624, -3.48298, -3.59262, -3.72521, -3.72690, -3.68004, -3.53806, -3.36882, -3.38283, -3.48370, -3.48064, -3.52357, -3.43668, -3.42639, -3.38298, -3.22428, -3.17781, -3.20787, -3.03743, -2.89077, -2.92368, -2.86282, -2.81930, -2.74661, -2.44589, -2.18819, -1.99723, -1.90553, -2.00551, -2.09762, -2.07881, -1.90119, -1.70631, -1.46889, -1.26439, -1.14651, -0.92147, -0.81705, -0.75398, -0.69091, -0.69734, -0.78366, -0.80890, -0.82246, -0.62559, -0.44804, -0.33124, -0.17820, -0.06302, -0.11637, -0.06844, 0.06054, 0.05500, 0.12209, 0.13309, 0.13112, 0.28543, 0.34918, 0.33736, 0.28093, 0.07665, -0.19941, -0.47907, -0.61463, -0.73506, -0.70692, -0.61196, -0.67939, -0.73110, -0.87158, -0.92315, -0.90221, -0.93610, -1.06976, -1.06383, -1.17073, -1.13083, -1.14609, -1.21737, -1.21994, -1.28217, -1.49762, -1.60609, -1.62963, -1.70022, -1.64769, -1.58905, -1.61890, -1.54848, -1.43976, -1.28755, -1.04592, -0.91785, -0.90367, -0.96040, -0.97359, -1.00006, -1.00711, -0.98095, -1.10117, -1.06085, -1.00883, -0.89899, -0.60051, -0.27296, -0.10906, 0.00800, -0.08893, -0.00849, 0.06035, +-1.37204, -1.20709, -0.90480, -0.45151, -0.09549, 0.07464, 0.19538, 0.40084, 0.54336, 0.60595, 0.57336, 0.52100, 0.46038, 0.49848, 0.63583, 0.66339, 0.66373, 0.69401, 0.55678, 0.40810, 0.31971, 0.13185, 0.05864, 0.25051, 0.33647, 0.44637, 0.51267, 0.53687, 0.62236, 0.58789, 0.50436, 0.31174, 0.14916, 0.04238, 0.04106, 0.14998, 0.16087, -0.02216, -0.27996, -0.46841, -0.67607, -1.02046, -1.31494, -1.46421, -1.52502, -1.62481, -1.65036, -1.77743, -1.88671, -1.83195, -1.85416, -1.87881, -1.77877, -1.84114, -1.95644, -1.94569, -1.95357, -1.90824, -1.83322, -1.85691, -1.85571, -1.86699, -1.75318, -1.64335, -1.58349, -1.62559, -1.71723, -1.73102, -1.68473, -1.77609, -1.83498, -1.85921, -1.84829, -1.84453, -1.75984, -1.67117, -1.53863, -1.53273, -1.38420, -1.36471, -1.43502, -1.37794, -1.30212, -1.20464, -0.96027, -0.87239, -0.88640, -0.73835, -0.56284, -0.46755, -0.41978, -0.54356, -0.53279, -0.54520, -0.38135, -0.18222, -0.09658, -0.15160, -0.33724, -0.50097, -0.60112, -0.87504, -1.03596, -1.02364, -0.92506, -0.96618, -1.00397, -1.12324, -1.16061, -1.30625, -1.35907, -1.52534, -1.75378, -1.84181, -1.88207, -1.98447, -1.88015, -1.80033, -1.81920, -1.80088, -1.84813, -1.92816, -1.87472, -1.87886, -1.80249, -1.78502, -1.67467, -1.44684, -1.12918, -0.84868, -0.65172, -0.58730, -0.52332, -0.60142, -0.68283, -0.72835, -0.73094, -0.89346, -0.92459, -1.02837, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.64052, -1.74264, -1.80310, -1.77766, -1.85321, -1.77798, -1.84457, -1.91981, -2.11017, -2.32802, -2.49467, -2.66900, -2.93396, -3.14364, -3.25519, -3.27731, -3.44695, -3.65871, -3.81724, -3.84461, -3.96310, -4.02738, -4.16574, -4.21459, -4.33516, -4.33678, -4.33289, -4.35807, -4.20688, -3.96367, -3.94812, -3.90921, -3.83458, -3.85973, -3.82301, -3.75032, -3.79206, -3.69668, -3.57567, -3.40360, -3.35475, -3.42804, -3.60260, -3.83266, -4.06398, -4.25152, -4.34855, -4.29342, -4.29648, -4.27882, -4.26922, -4.18594, -4.20445, -4.12123, -4.08033, -4.01206, -4.07110, -4.10524, -4.09617, -4.16658, -4.15976, -4.06208, -4.12022, -4.05975, -3.90701, -3.77500, -3.65033, -3.48438, -3.50273, -3.46145, -3.37368, -3.24445, -3.15740, -3.06424, -2.89123, -2.80354, -2.82841, -2.91521, -2.96610, -2.86375, -2.78248, -2.80356, -2.81172, -2.74390, -2.74842, -2.75749, -2.80739, -2.76280, -2.69081, -2.61292, -2.55067, -2.62913, -2.54410, -2.23972, -2.05209, -1.91218, -1.73120, -1.71750, -1.68195, -1.56278, -1.62222, -1.69102, -1.74966, -1.72300, -1.57869, -1.39944, -1.08311, -0.81019, -0.67574, -0.63549, -0.77028, -0.91834, -1.11894, -1.37174, -1.59867, -1.75263, -1.94943, -2.14297, -2.28450, -2.38492, -2.49374, -2.72874, -2.93425, -3.24041, -3.40224, -3.21608, -3.08222, -3.03273, -2.90004, -2.92982, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.68273, -3.66785, -3.73306, -3.77652, -3.69473, -3.56719, -3.52204, -3.54828, -3.62766, -3.55722, -3.48026, -3.27478, -3.28841, -3.36774, -3.25779, -3.16625, -3.13872, -3.02207, -3.08548, -3.21195, -3.10870, -2.94947, -2.75959, -2.45983, -2.28109, -2.08897, -2.05724, -2.07257, -2.13207, -2.12482, -1.99026, -1.78480, -1.56468, -1.33097, -1.22685, -1.08192, -0.91496, -0.76024, -0.78528, -0.78534, -0.84508, -0.76320, -0.63410, -0.39895, -0.31840, -0.31290, -0.14997, 0.02642, -0.00708, 0.00109, -0.03262, -0.06378, 0.00904, 0.05585, 0.06250, 0.19477, 0.22702, 0.25696, 0.07680, -0.15691, -0.41798, -0.62878, -0.75848, -0.83241, -0.80179, -0.64577, -0.64302, -0.75614, -0.88725, -0.87253, -0.94717, -0.95614, -1.11990, -1.17779, -1.24912, -1.10076, -1.07051, -1.19374, -1.26421, -1.33227, -1.49646, -1.53208, -1.61102, -1.72182, -1.75589, -1.72069, -1.71929, -1.62548, -1.59167, -1.38493, -1.17746, -0.98907, -0.92790, -0.98418, -1.08152, -1.12166, -1.14241, -1.08000, -1.15797, -1.18294, -1.12056, -0.84225, -0.55816, -0.25026, -0.13256, -0.01788, -0.00292, 0.17254, 0.22655, +-1.30723, -1.02071, -0.69224, -0.27541, 0.11365, 0.29867, 0.33718, 0.45859, 0.54225, 0.54526, 0.45932, 0.31255, 0.28947, 0.45315, 0.62638, 0.64767, 0.57683, 0.52506, 0.39713, 0.34069, 0.22931, 0.00258, -0.08886, 0.07912, 0.15705, 0.20373, 0.20569, 0.21386, 0.30463, 0.33673, 0.35863, 0.23664, 0.13381, 0.10836, 0.11092, 0.09286, 0.01465, -0.19614, -0.47177, -0.63076, -0.80199, -1.11562, -1.36792, -1.54296, -1.63296, -1.72456, -1.80447, -1.95005, -1.99164, -1.89341, -1.89754, -1.89053, -1.84157, -1.85997, -1.87817, -1.84588, -1.84987, -1.90094, -1.89478, -1.92317, -1.90006, -1.84745, -1.69293, -1.51374, -1.39614, -1.41606, -1.55416, -1.68964, -1.69327, -1.75644, -1.86167, -1.93953, -1.89771, -1.86784, -1.71573, -1.64019, -1.62112, -1.61016, -1.48021, -1.44121, -1.44354, -1.39544, -1.33191, -1.17205, -0.97440, -0.95863, -0.97466, -0.85441, -0.65951, -0.56747, -0.50362, -0.60275, -0.61025, -0.61439, -0.44836, -0.27910, -0.24720, -0.33615, -0.52298, -0.71876, -0.80645, -0.95604, -1.05358, -1.02952, -0.93177, -1.03094, -1.07455, -1.19147, -1.25077, -1.34774, -1.45750, -1.74056, -1.98697, -2.01847, -2.01066, -2.00009, -1.89441, -1.90327, -1.91009, -1.91616, -1.93073, -2.01736, -1.99520, -1.94692, -1.83564, -1.83068, -1.73872, -1.50820, -1.18190, -0.88406, -0.72627, -0.76383, -0.70492, -0.67216, -0.66654, -0.75706, -0.91317, -1.22363, -1.29343, -1.34386, -1.37944, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.72307, -1.80411, -1.81827, -1.96113, -1.95857, -2.05255, -2.15107, -2.35448, -2.50452, -2.56312, -2.66388, -2.83918, -3.00736, -3.16539, -3.25682, -3.40673, -3.56168, -3.68462, -3.67769, -3.82630, -3.93213, -4.09324, -4.16695, -4.15581, -4.06854, -4.07500, -4.11536, -4.01658, -3.84742, -3.80319, -3.72445, -3.68876, -3.67589, -3.60472, -3.52250, -3.64245, -3.63764, -3.52427, -3.31690, -3.25289, -3.31104, -3.41524, -3.51398, -3.60350, -3.67833, -3.85110, -4.00657, -4.09909, -4.08892, -4.08668, -4.05880, -4.18863, -4.14438, -4.05266, -3.99330, -4.01741, -4.02515, -4.04316, -4.09536, -4.03237, -3.92904, -3.94694, -3.85938, -3.76259, -3.62433, -3.53829, -3.44649, -3.55617, -3.55539, -3.43602, -3.25093, -3.12483, -3.00684, -2.81643, -2.76269, -2.82034, -2.89131, -2.94203, -2.87282, -2.77043, -2.74667, -2.75485, -2.65901, -2.61487, -2.60743, -2.62319, -2.65398, -2.65882, -2.61820, -2.64386, -2.73301, -2.60574, -2.29423, -2.00257, -1.78614, -1.70646, -1.74569, -1.73135, -1.64372, -1.74920, -1.88885, -1.91793, -1.74656, -1.49419, -1.21410, -0.91778, -0.77365, -0.72524, -0.68211, -0.79544, -1.02629, -1.27903, -1.48703, -1.68929, -1.85158, -2.08504, -2.30976, -2.39244, -2.45757, -2.49521, -2.62265, -2.84231, -3.17500, -3.31533, -3.16368, -3.05149, -3.00532, -2.98155, -3.03084, -3.02547, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.79822, -3.70776, -3.65168, -3.64422, -3.60093, -3.54800, -3.55334, -3.52493, -3.52867, -3.41035, -3.24331, -3.01146, -3.08255, -3.23896, -3.22841, -3.18182, -3.11918, -3.10067, -3.27095, -3.36327, -3.21126, -2.99303, -2.78871, -2.56258, -2.46118, -2.31523, -2.23036, -2.14124, -2.17119, -2.18551, -2.01451, -1.77547, -1.62864, -1.47119, -1.35175, -1.18244, -0.98280, -0.75828, -0.74281, -0.67949, -0.69390, -0.59969, -0.42095, -0.24781, -0.30469, -0.36786, -0.20626, -0.00587, 0.06347, 0.06452, -0.03241, -0.05375, -0.06652, -0.09210, -0.15031, -0.02944, 0.05282, 0.07498, -0.12170, -0.34283, -0.52156, -0.62536, -0.64453, -0.64290, -0.67881, -0.59655, -0.55048, -0.61827, -0.72220, -0.72135, -0.84812, -0.82522, -1.00970, -1.19032, -1.28054, -1.15304, -1.16385, -1.28823, -1.36310, -1.38736, -1.38099, -1.36073, -1.48170, -1.66519, -1.85801, -1.90382, -1.92579, -1.80662, -1.76660, -1.59879, -1.40117, -1.19504, -1.13519, -1.23079, -1.30992, -1.29610, -1.33010, -1.27858, -1.29240, -1.27314, -1.19094, -0.88938, -0.63868, -0.33356, -0.21708, -0.14087, -0.02491, 0.21138, 0.25565, +-1.21777, -0.86688, -0.42219, -0.08940, 0.14749, 0.32199, 0.32752, 0.38250, 0.45538, 0.44333, 0.37637, 0.16642, 0.11860, 0.35065, 0.56929, 0.59088, 0.50632, 0.42001, 0.24093, 0.20136, 0.08655, -0.06163, -0.15654, -0.09584, 0.00219, 0.01416, -0.03784, -0.01935, 0.02937, 0.08104, 0.14990, 0.01409, -0.08149, -0.08571, -0.01413, -0.12167, -0.34515, -0.52436, -0.75162, -0.90642, -1.02803, -1.27622, -1.44341, -1.63544, -1.78280, -1.80593, -1.82696, -1.91025, -1.88353, -1.76317, -1.81627, -1.82027, -1.78187, -1.69150, -1.62581, -1.64208, -1.60480, -1.68235, -1.74944, -1.78646, -1.79346, -1.73692, -1.56258, -1.44111, -1.36939, -1.41102, -1.44878, -1.59334, -1.71659, -1.75641, -1.83875, -1.92794, -1.82939, -1.75685, -1.57315, -1.55850, -1.68108, -1.64003, -1.46911, -1.35644, -1.30274, -1.25131, -1.28865, -1.20800, -1.07415, -1.01962, -0.94848, -0.86814, -0.63650, -0.52613, -0.50439, -0.60164, -0.64690, -0.70212, -0.56223, -0.50748, -0.52000, -0.62533, -0.69308, -0.82992, -0.99750, -1.08879, -1.10414, -1.08586, -0.95899, -0.99891, -0.99763, -1.11438, -1.28659, -1.38519, -1.50397, -1.77521, -2.01734, -2.02833, -2.07738, -2.09003, -1.99370, -1.96071, -1.87342, -1.92823, -1.90339, -1.93581, -1.95174, -1.89699, -1.80628, -1.83907, -1.70584, -1.54540, -1.26402, -1.03852, -0.86472, -0.87111, -0.91190, -0.89030, -0.83959, -1.01404, -1.25628, -1.57364, -1.63221, -1.63589, -1.74940, -1.83883, -1.80736, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.70550, -1.83582, -1.88551, -2.04520, -2.16363, -2.30513, -2.40102, -2.60188, -2.64706, -2.70494, -2.79659, -2.97995, -3.08027, -3.15546, -3.32837, -3.46932, -3.50369, -3.58814, -3.55020, -3.63863, -3.71465, -3.82192, -3.96366, -3.92729, -3.78809, -3.74024, -3.77729, -3.67827, -3.59214, -3.62030, -3.54645, -3.49361, -3.37372, -3.34082, -3.31972, -3.42547, -3.47856, -3.39209, -3.16789, -3.12499, -3.11403, -3.16689, -3.18435, -3.23546, -3.23375, -3.35138, -3.66487, -3.86562, -3.82205, -3.84871, -3.88512, -4.03810, -4.02878, -3.91043, -3.93440, -3.98230, -3.92621, -3.87596, -3.91176, -3.81672, -3.76161, -3.84875, -3.76940, -3.69405, -3.48935, -3.43264, -3.40078, -3.46192, -3.47965, -3.38704, -3.18160, -3.08053, -2.93229, -2.76583, -2.75057, -2.82803, -2.85093, -2.78028, -2.76978, -2.74652, -2.65398, -2.63860, -2.54624, -2.45658, -2.43781, -2.41634, -2.55336, -2.66479, -2.63855, -2.66743, -2.74660, -2.58107, -2.29169, -2.05372, -1.85131, -1.79146, -1.73025, -1.69091, -1.65225, -1.69565, -1.82389, -1.81313, -1.53564, -1.27180, -0.98067, -0.77162, -0.78916, -0.85432, -0.84804, -0.87446, -1.16783, -1.54366, -1.72902, -1.92839, -2.11469, -2.30637, -2.46202, -2.44552, -2.53429, -2.61474, -2.67343, -2.84882, -3.15146, -3.28772, -3.20267, -3.18103, -3.15346, -3.13794, -3.08937, -3.04925, -3.11348, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.78704, -3.64733, -3.57173, -3.54335, -3.46627, -3.42115, -3.30560, -3.28122, -3.21092, -2.99471, -2.75787, -2.84743, -3.03302, -3.07727, -3.13795, -3.12433, -3.16230, -3.28813, -3.28417, -3.17200, -2.91882, -2.72802, -2.60847, -2.53623, -2.40609, -2.28872, -2.11560, -2.17869, -2.21296, -2.07910, -1.77063, -1.62450, -1.58774, -1.43491, -1.20753, -1.01818, -0.73963, -0.63808, -0.49613, -0.48561, -0.50022, -0.33986, -0.19168, -0.25447, -0.31919, -0.14938, -0.01219, 0.03854, 0.02678, -0.02978, 0.00979, -0.08606, -0.09945, -0.14001, -0.06679, 0.02957, 0.04515, -0.16238, -0.32110, -0.51078, -0.57684, -0.58218, -0.47783, -0.46819, -0.49766, -0.44726, -0.45553, -0.58074, -0.59885, -0.72056, -0.71036, -0.93511, -1.26986, -1.39027, -1.26937, -1.23986, -1.33689, -1.35597, -1.36448, -1.32724, -1.29469, -1.40140, -1.55882, -1.85783, -1.91702, -1.89469, -1.80792, -1.78472, -1.67219, -1.58880, -1.42080, -1.47233, -1.61212, -1.70315, -1.60047, -1.55451, -1.58856, -1.60539, -1.50321, -1.41508, -1.12611, -0.85308, -0.51345, -0.32840, -0.30144, -0.14663, 0.13082, 0.23521, +-1.01104, -0.68415, -0.26198, 0.05483, 0.23085, 0.28792, 0.28406, 0.30858, 0.31666, 0.28846, 0.19858, 0.03812, 0.08408, 0.29249, 0.49860, 0.52526, 0.38907, 0.26692, 0.12019, 0.11010, -0.03481, -0.22572, -0.27521, -0.19834, -0.13035, -0.11625, -0.18600, -0.25919, -0.27946, -0.24484, -0.15693, -0.18665, -0.26817, -0.34044, -0.33866, -0.47256, -0.66045, -0.82996, -0.97660, -1.09453, -1.24371, -1.45115, -1.58545, -1.73358, -1.79160, -1.75486, -1.71096, -1.70298, -1.68537, -1.60869, -1.62960, -1.56722, -1.54362, -1.52176, -1.42773, -1.37753, -1.35496, -1.42621, -1.53622, -1.68143, -1.72736, -1.64943, -1.45712, -1.26337, -1.25705, -1.41394, -1.44933, -1.56866, -1.64802, -1.71656, -1.78439, -1.80052, -1.70279, -1.63694, -1.50018, -1.52986, -1.61658, -1.54702, -1.37094, -1.18518, -1.13867, -1.14491, -1.20811, -1.12048, -1.02660, -1.01854, -0.88506, -0.70071, -0.50989, -0.43509, -0.47169, -0.66350, -0.75222, -0.82205, -0.73660, -0.64037, -0.64271, -0.78608, -0.79808, -0.90417, -1.01249, -1.10081, -1.10487, -1.05204, -0.95600, -0.95683, -0.93384, -1.06360, -1.22576, -1.33163, -1.48217, -1.68948, -1.96880, -2.10571, -2.21444, -2.20003, -2.11171, -2.11063, -2.00695, -1.93989, -1.88401, -1.86575, -1.86157, -1.88442, -1.87312, -1.90471, -1.74296, -1.50315, -1.23751, -1.16351, -1.05781, -1.07866, -1.08501, -1.11385, -1.13389, -1.33057, -1.63489, -1.94950, -1.99912, -2.00278, -2.06742, -2.10292, -2.09537, -2.04540, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.91776, -1.97481, -2.17802, -2.38513, -2.63683, -2.77257, -2.89385, -2.84793, -2.79671, -2.83942, -3.09525, -3.20769, -3.29052, -3.38873, -3.45084, -3.43782, -3.43306, -3.38865, -3.44907, -3.46966, -3.54396, -3.65281, -3.60139, -3.51246, -3.42127, -3.44606, -3.41533, -3.38354, -3.37250, -3.26986, -3.24148, -3.14413, -3.04146, -3.07601, -3.21698, -3.27999, -3.26841, -3.12072, -3.07290, -3.00045, -2.88070, -2.75827, -2.84692, -2.87848, -3.03209, -3.30774, -3.48941, -3.49422, -3.51717, -3.60680, -3.80550, -3.81745, -3.73282, -3.73887, -3.71929, -3.65778, -3.57168, -3.62096, -3.64496, -3.68237, -3.73519, -3.61753, -3.59398, -3.47552, -3.34775, -3.28090, -3.29547, -3.27789, -3.24951, -3.13787, -3.05830, -2.89809, -2.68521, -2.59249, -2.68350, -2.72537, -2.66753, -2.63495, -2.59073, -2.52434, -2.47006, -2.41500, -2.40748, -2.41784, -2.43820, -2.57762, -2.65418, -2.68149, -2.70143, -2.73486, -2.61481, -2.38169, -2.14065, -1.93730, -1.89868, -1.84774, -1.70968, -1.60613, -1.61975, -1.67807, -1.61161, -1.36536, -1.13465, -0.87818, -0.70605, -0.71672, -0.88154, -1.00243, -1.08710, -1.36358, -1.70291, -1.92888, -2.10282, -2.25958, -2.43528, -2.51714, -2.49258, -2.58775, -2.65560, -2.74590, -2.89918, -3.14046, -3.35863, -3.40564, -3.39248, -3.30009, -3.23918, -3.19928, -3.12205, -3.14215, -3.22797, -3.31373, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.67068, -3.54840, -3.45323, -3.36460, -3.26600, -3.10179, -3.01223, -2.86365, -2.64504, -2.45610, -2.54448, -2.79278, -2.93099, -3.02703, -3.00012, -3.07926, -3.25234, -3.17792, -2.99681, -2.81016, -2.67560, -2.62183, -2.63914, -2.52739, -2.36087, -2.12709, -2.05603, -2.05980, -2.01526, -1.72238, -1.55953, -1.45005, -1.29211, -1.07103, -0.87355, -0.65863, -0.53775, -0.35534, -0.31259, -0.32512, -0.22571, -0.13527, -0.13510, -0.18301, -0.07231, 0.03528, 0.12520, 0.10144, -0.01696, 0.01041, 0.00843, 0.00206, -0.02303, 0.03066, 0.03273, 0.00871, -0.15126, -0.25651, -0.34953, -0.40682, -0.50540, -0.41162, -0.38898, -0.36128, -0.32411, -0.33206, -0.41252, -0.48746, -0.63877, -0.68703, -0.98186, -1.32229, -1.45140, -1.39426, -1.31620, -1.40966, -1.44886, -1.40645, -1.28753, -1.26040, -1.43855, -1.61360, -1.79309, -1.84740, -1.82132, -1.74987, -1.81672, -1.80329, -1.78729, -1.67641, -1.68948, -1.79580, -1.95584, -1.87968, -1.86561, -1.88078, -1.88537, -1.75564, -1.58988, -1.35947, -1.12778, -0.76491, -0.52932, -0.39734, -0.17686, 0.05233, 0.20772, +-0.90526, -0.51870, -0.16536, 0.17229, 0.36371, 0.28629, 0.28089, 0.23732, 0.16987, 0.17339, 0.05846, -0.00472, 0.15292, 0.22372, 0.28485, 0.29135, 0.26069, 0.18839, 0.00233, -0.04467, -0.17236, -0.36851, -0.45340, -0.41898, -0.36601, -0.30319, -0.25648, -0.37461, -0.54422, -0.54356, -0.58647, -0.58204, -0.49987, -0.51186, -0.61661, -0.75645, -0.81225, -0.97703, -1.06083, -1.20743, -1.42596, -1.52524, -1.61851, -1.71645, -1.67784, -1.67136, -1.65424, -1.58874, -1.52110, -1.42408, -1.45651, -1.33748, -1.25095, -1.27775, -1.28312, -1.30228, -1.32126, -1.35376, -1.42085, -1.55690, -1.66228, -1.50741, -1.37263, -1.23257, -1.19036, -1.33528, -1.40917, -1.52330, -1.51160, -1.64662, -1.70141, -1.63984, -1.58877, -1.51007, -1.46679, -1.52456, -1.48068, -1.40897, -1.31387, -1.12548, -1.04030, -0.98211, -1.08799, -1.00110, -0.86582, -0.80469, -0.66695, -0.55580, -0.49295, -0.50145, -0.57134, -0.66366, -0.77218, -0.77389, -0.78711, -0.79868, -0.70434, -0.72999, -0.73285, -0.87385, -0.88756, -0.99282, -1.00192, -0.95183, -0.97490, -0.92224, -0.89585, -1.04363, -1.17139, -1.32524, -1.55868, -1.71809, -1.97742, -2.14805, -2.39413, -2.44463, -2.35136, -2.30045, -2.23994, -2.18326, -2.10928, -2.00796, -1.93658, -1.85672, -1.92868, -1.90904, -1.74396, -1.60197, -1.33166, -1.25982, -1.20553, -1.24999, -1.17943, -1.31513, -1.47863, -1.68180, -2.02381, -2.24425, -2.26865, -2.29789, -2.27919, -2.26426, -2.32952, -2.24630, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.21802, -2.41276, -2.68005, -2.86657, -3.03800, -3.05009, -2.95162, -3.00133, -3.00591, -3.15739, -3.23751, -3.37891, -3.37580, -3.38215, -3.37291, -3.28661, -3.30232, -3.29826, -3.21728, -3.23960, -3.27651, -3.25901, -3.33474, -3.29768, -3.29983, -3.17986, -3.19341, -3.19584, -3.04215, -2.94014, -2.88592, -2.83707, -2.95581, -3.11885, -3.18349, -3.10184, -3.04752, -2.99465, -2.83647, -2.69888, -2.50707, -2.54873, -2.61519, -2.82172, -2.93996, -3.03769, -3.12452, -3.14680, -3.31569, -3.50369, -3.47337, -3.41241, -3.35778, -3.24486, -3.26538, -3.29445, -3.42438, -3.50759, -3.62782, -3.65567, -3.46174, -3.38555, -3.36519, -3.28618, -3.21982, -3.17706, -3.13991, -3.06171, -3.02260, -2.95123, -2.73932, -2.64217, -2.56941, -2.57638, -2.58825, -2.60572, -2.54570, -2.45330, -2.44833, -2.34178, -2.37396, -2.48904, -2.51765, -2.60975, -2.71532, -2.71048, -2.84668, -2.91679, -2.89245, -2.69807, -2.48200, -2.29553, -2.09521, -1.99501, -1.93776, -1.81606, -1.72865, -1.71437, -1.67016, -1.42291, -1.18933, -1.07078, -0.84539, -0.78372, -0.80222, -0.91550, -1.07158, -1.26855, -1.49670, -1.72000, -1.99194, -2.10384, -2.23007, -2.36960, -2.34022, -2.39527, -2.54806, -2.65443, -2.86264, -3.03539, -3.20711, -3.41212, -3.54147, -3.59249, -3.44498, -3.27242, -3.23583, -3.23628, -3.30452, -3.38601, -3.43275, -3.38917, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.54857, -3.39597, -3.30405, -3.09356, -2.88537, -2.71218, -2.45281, -2.29091, -2.20827, -2.29537, -2.51851, -2.65083, -2.84176, -2.85422, -2.92500, -3.07421, -3.00675, -2.91689, -2.87546, -2.81680, -2.72490, -2.65209, -2.58508, -2.34698, -2.13919, -2.06929, -1.94538, -1.82156, -1.52825, -1.32882, -1.04667, -0.92390, -0.78868, -0.65935, -0.62496, -0.43592, -0.17533, -0.06661, -0.03888, -0.06152, -0.08938, -0.03493, -0.01008, 0.12373, 0.12951, 0.20167, 0.22247, 0.11639, 0.04852, -0.01859, -0.06130, -0.05624, 0.01425, 0.05311, -0.04611, -0.09867, -0.16473, -0.34115, -0.39883, -0.48458, -0.43150, -0.42068, -0.27136, -0.27168, -0.29513, -0.31888, -0.48701, -0.60481, -0.68271, -1.02360, -1.32303, -1.49555, -1.59338, -1.54184, -1.61411, -1.53703, -1.48346, -1.39429, -1.39997, -1.57826, -1.75234, -1.88385, -1.94686, -1.92106, -1.85541, -1.83330, -1.91335, -1.88881, -1.79599, -1.89630, -1.91686, -2.02055, -2.02821, -2.14213, -2.13699, -2.10720, -1.92179, -1.63868, -1.51527, -1.30094, -0.89638, -0.61307, -0.37158, -0.16164, -0.09751, 0.03386, +-0.96772, -0.64413, -0.23303, 0.19822, 0.40163, 0.32859, 0.31592, 0.26969, 0.22095, 0.21394, 0.13065, 0.10176, 0.14533, 0.12302, 0.15517, 0.19518, 0.19452, 0.10758, -0.07751, -0.16280, -0.31795, -0.51222, -0.57907, -0.57979, -0.58702, -0.52599, -0.39976, -0.46341, -0.74212, -0.92750, -1.01797, -0.90126, -0.73986, -0.74321, -0.79346, -0.80915, -0.83306, -0.99689, -1.12449, -1.31569, -1.52763, -1.59546, -1.61918, -1.66384, -1.69834, -1.73546, -1.67266, -1.56341, -1.53447, -1.51577, -1.51794, -1.35073, -1.19756, -1.19929, -1.19372, -1.21758, -1.28439, -1.32798, -1.35873, -1.40233, -1.56655, -1.56891, -1.48132, -1.28521, -1.20925, -1.37817, -1.44313, -1.42278, -1.39727, -1.53988, -1.58353, -1.50439, -1.47017, -1.44328, -1.43313, -1.41521, -1.33909, -1.28236, -1.15622, -0.96205, -0.89876, -0.90975, -1.03146, -0.97725, -0.84202, -0.75073, -0.56855, -0.47854, -0.52743, -0.64118, -0.70875, -0.60273, -0.64278, -0.72552, -0.78158, -0.75424, -0.62918, -0.69868, -0.77817, -0.84046, -0.86696, -0.97737, -0.97432, -0.94852, -1.00356, -0.97310, -0.95467, -1.05536, -1.25188, -1.49874, -1.69284, -1.78745, -2.00462, -2.27713, -2.57812, -2.67516, -2.59869, -2.53819, -2.46495, -2.38200, -2.36020, -2.29532, -2.19012, -1.93782, -1.92813, -1.98669, -1.87299, -1.69063, -1.40727, -1.38042, -1.37434, -1.30694, -1.27960, -1.51507, -1.74024, -1.92224, -2.17862, -2.34598, -2.37038, -2.35639, -2.35532, -2.39886, -2.45318, -2.35495, -2.35127, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.61044, -2.87288, -2.92273, -3.01991, -3.13625, -3.16843, -3.23006, -3.21384, -3.34182, -3.42206, -3.43680, -3.39736, -3.41014, -3.37263, -3.25830, -3.26106, -3.21829, -3.09734, -3.00140, -2.98627, -3.05957, -3.16244, -3.12558, -3.11301, -3.07105, -3.11787, -3.14558, -3.02731, -2.94462, -2.89072, -2.77309, -2.87216, -3.06409, -3.13676, -2.93583, -2.80573, -2.81991, -2.72041, -2.54192, -2.34034, -2.42116, -2.54217, -2.57718, -2.53222, -2.60049, -2.69377, -2.74347, -2.91672, -3.08358, -3.09987, -3.02883, -2.97440, -2.93690, -2.97593, -3.06127, -3.25830, -3.50979, -3.68125, -3.64132, -3.39059, -3.27918, -3.25775, -3.11892, -3.03498, -3.06155, -3.11033, -2.98947, -2.88946, -2.86611, -2.75621, -2.69799, -2.63982, -2.67950, -2.75085, -2.71208, -2.60974, -2.54970, -2.54452, -2.40938, -2.41051, -2.52961, -2.61176, -2.69548, -2.78137, -2.85001, -3.01352, -3.08079, -3.06419, -2.94801, -2.78628, -2.56940, -2.31796, -2.18470, -2.10413, -1.89834, -1.76104, -1.75315, -1.68165, -1.33975, -1.04569, -1.02165, -0.94440, -0.85856, -0.78284, -0.89181, -1.12373, -1.30778, -1.42887, -1.64416, -1.94145, -2.05790, -2.14904, -2.22140, -2.18954, -2.28437, -2.47937, -2.74252, -2.98942, -3.07883, -3.19015, -3.43333, -3.65614, -3.70760, -3.54552, -3.40384, -3.43854, -3.43811, -3.48978, -3.57967, -3.63103, -3.54908, -3.45650, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.26299, -3.11303, -2.87996, -2.65714, -2.45342, -2.25948, -2.14523, -2.00849, -2.03230, -2.27757, -2.50675, -2.70553, -2.72593, -2.81315, -2.97108, -2.89772, -2.85776, -2.93877, -2.95163, -2.77355, -2.50443, -2.41153, -2.29512, -2.12690, -1.97897, -1.81213, -1.73002, -1.43729, -1.07451, -0.74438, -0.64929, -0.58582, -0.52504, -0.54499, -0.32027, 0.02434, 0.24147, 0.23776, 0.13018, 0.12873, 0.21717, 0.18054, 0.13461, 0.08742, 0.14637, 0.18194, 0.06668, -0.02047, -0.09034, -0.18288, -0.21268, -0.13582, 0.01124, -0.06543, -0.19886, -0.25709, -0.35041, -0.40708, -0.55190, -0.53476, -0.37699, -0.20160, -0.23347, -0.29005, -0.35093, -0.53317, -0.64802, -0.70921, -0.96763, -1.30858, -1.58135, -1.66722, -1.58879, -1.66303, -1.67328, -1.64462, -1.61059, -1.66373, -1.84202, -1.91674, -1.92122, -1.98350, -2.01144, -1.95977, -1.79900, -1.85196, -1.97770, -1.98100, -2.04395, -2.02130, -2.17134, -2.28595, -2.33630, -2.34632, -2.28056, -2.00589, -1.65590, -1.50142, -1.27256, -0.85689, -0.50489, -0.33918, -0.31077, -0.28846, -0.14110, +-0.81454, -0.60348, -0.31166, 0.11619, 0.33842, 0.28232, 0.27435, 0.25457, 0.26298, 0.24037, 0.15195, 0.08321, 0.06706, 0.10532, 0.11846, 0.18676, 0.28662, 0.21098, 0.01364, -0.09668, -0.28080, -0.50373, -0.62321, -0.76564, -0.84345, -0.76727, -0.72650, -0.84723, -1.01752, -1.21774, -1.34373, -1.13254, -0.89115, -0.89297, -0.99803, -0.97104, -0.97004, -1.15443, -1.33588, -1.53432, -1.70897, -1.77549, -1.77674, -1.78755, -1.81916, -1.74544, -1.66415, -1.56383, -1.47005, -1.43686, -1.42486, -1.23262, -1.00589, -0.92069, -0.86958, -0.92895, -1.02544, -1.03855, -1.14254, -1.30417, -1.46772, -1.53728, -1.56235, -1.30794, -1.15169, -1.29822, -1.46371, -1.41344, -1.32617, -1.42294, -1.44708, -1.37195, -1.35187, -1.35093, -1.35264, -1.28244, -1.19924, -1.04975, -0.90640, -0.75019, -0.63189, -0.63734, -0.82199, -0.86041, -0.77124, -0.68867, -0.49974, -0.44562, -0.54090, -0.61046, -0.68146, -0.62413, -0.56764, -0.58047, -0.69963, -0.61735, -0.45577, -0.55187, -0.81079, -0.91077, -0.91814, -1.00788, -0.99668, -0.96123, -1.01684, -1.01532, -1.05261, -1.16144, -1.42140, -1.61130, -1.77175, -1.89946, -2.00397, -2.19305, -2.49412, -2.61418, -2.55806, -2.51214, -2.44189, -2.41312, -2.50493, -2.42823, -2.31414, -2.10906, -1.96664, -1.90413, -1.88254, -1.65654, -1.32311, -1.26958, -1.41249, -1.45194, -1.48069, -1.73151, -1.94699, -2.07113, -2.27471, -2.42749, -2.48861, -2.45890, -2.49740, -2.48748, -2.54097, -2.56218, -2.53945, -2.52890, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.75932, -2.97984, -3.10664, -3.15731, -3.21697, -3.41189, -3.48080, -3.41347, -3.45174, -3.59737, -3.64250, -3.56647, -3.54325, -3.47306, -3.31279, -3.27591, -3.18868, -3.07398, -2.91895, -2.85424, -2.82159, -2.84682, -2.86185, -2.81903, -2.73482, -2.78514, -2.85379, -2.81402, -2.77479, -2.72058, -2.57815, -2.69352, -2.85625, -2.93076, -2.82276, -2.65013, -2.52746, -2.50494, -2.36066, -2.12760, -2.10678, -2.24826, -2.27013, -2.14389, -2.17675, -2.25466, -2.29014, -2.46010, -2.63061, -2.76959, -2.77986, -2.79103, -2.75670, -2.74219, -2.90181, -3.12048, -3.34618, -3.51114, -3.46274, -3.21424, -3.07875, -3.02240, -2.85735, -2.83237, -2.92086, -3.02786, -3.02984, -2.94837, -2.80636, -2.76859, -2.76402, -2.67089, -2.64088, -2.77238, -2.82753, -2.72949, -2.67797, -2.68050, -2.53118, -2.47505, -2.54021, -2.67768, -2.77983, -2.89147, -2.96736, -3.05196, -3.19342, -3.25272, -3.11753, -2.95257, -2.70360, -2.40062, -2.23697, -2.12874, -1.84306, -1.67450, -1.61961, -1.49067, -1.24232, -1.00240, -0.85968, -0.80861, -0.76378, -0.64103, -0.71278, -1.00616, -1.30076, -1.41030, -1.62443, -1.97032, -2.13038, -2.21024, -2.25308, -2.25508, -2.37408, -2.59266, -2.87963, -3.02357, -3.12354, -3.27025, -3.45456, -3.66325, -3.72054, -3.58423, -3.52232, -3.62828, -3.62044, -3.69817, -3.78829, -3.78629, -3.75462, -3.70440, -3.63811, -3.66491, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.83069, -2.60246, -2.43968, -2.30071, -2.16452, -1.96019, -1.78257, -1.79307, -1.96729, -2.18350, -2.35946, -2.36066, -2.45603, -2.64813, -2.62237, -2.67517, -2.82749, -2.80471, -2.63970, -2.42465, -2.22963, -2.06817, -1.96912, -1.74255, -1.51551, -1.46561, -1.32522, -0.97189, -0.62636, -0.52422, -0.46605, -0.39972, -0.39178, -0.14414, 0.19168, 0.42817, 0.40808, 0.39306, 0.40543, 0.40719, 0.32834, 0.22192, 0.15378, 0.20624, 0.24136, 0.12321, 0.03976, -0.06019, -0.20295, -0.20068, -0.16174, -0.11817, -0.11752, -0.16733, -0.26724, -0.22854, -0.18288, -0.28282, -0.37318, -0.24610, -0.07086, -0.11903, -0.25296, -0.39193, -0.60249, -0.72918, -0.80607, -1.02296, -1.41255, -1.63013, -1.65600, -1.61317, -1.64643, -1.65442, -1.67433, -1.66714, -1.70835, -1.83377, -1.82188, -1.78467, -1.87521, -1.86532, -1.82844, -1.78072, -1.83069, -1.96804, -2.15520, -2.23137, -2.18276, -2.28138, -2.49973, -2.59464, -2.56356, -2.43774, -2.13041, -1.74475, -1.54314, -1.27822, -0.90379, -0.57858, -0.55590, -0.56881, -0.52242, -0.44639, +-0.74138, -0.48745, -0.23156, 0.11346, 0.34471, 0.35175, 0.30801, 0.33090, 0.44746, 0.47129, 0.29020, 0.11499, 0.10515, 0.13339, 0.04527, 0.06497, 0.25629, 0.24606, 0.05733, -0.04369, -0.22939, -0.48699, -0.72669, -0.99460, -1.09663, -1.01604, -1.09052, -1.32114, -1.40449, -1.49605, -1.58188, -1.41804, -1.13760, -1.01534, -1.09217, -1.08668, -1.06006, -1.22822, -1.53575, -1.74614, -1.79015, -1.75112, -1.80752, -1.88779, -1.82668, -1.68538, -1.65296, -1.61439, -1.46957, -1.40128, -1.38868, -1.13729, -0.81332, -0.64762, -0.61861, -0.71315, -0.78637, -0.75176, -0.89446, -1.20981, -1.41630, -1.50001, -1.57394, -1.41354, -1.26430, -1.26724, -1.39860, -1.35824, -1.24928, -1.24687, -1.29626, -1.30403, -1.27188, -1.20627, -1.23324, -1.22478, -1.04641, -0.82441, -0.75337, -0.69387, -0.50938, -0.40253, -0.61520, -0.72870, -0.70729, -0.68325, -0.58435, -0.56454, -0.57192, -0.51001, -0.54621, -0.62144, -0.55954, -0.50315, -0.61617, -0.59986, -0.47005, -0.50092, -0.81674, -0.94876, -0.92820, -0.89844, -0.92408, -0.96761, -0.98406, -0.91472, -0.97691, -1.20163, -1.43569, -1.59858, -1.83058, -2.05299, -2.04537, -2.03267, -2.29402, -2.40385, -2.38718, -2.39043, -2.37005, -2.42006, -2.52528, -2.40126, -2.27858, -2.21640, -2.06074, -1.88262, -1.82049, -1.63800, -1.35746, -1.19357, -1.34216, -1.50478, -1.64602, -1.81984, -2.02106, -2.18348, -2.32612, -2.40778, -2.50834, -2.61533, -2.59996, -2.47074, -2.59013, -2.82449, -2.84590, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.89339, -3.05512, -3.29153, -3.36547, -3.41290, -3.65599, -3.76447, -3.70027, -3.56469, -3.65072, -3.71331, -3.66437, -3.52965, -3.40136, -3.28288, -3.21895, -3.08746, -2.97709, -2.91687, -2.73914, -2.50993, -2.53045, -2.69193, -2.69351, -2.49300, -2.48490, -2.52133, -2.50435, -2.49857, -2.47223, -2.40901, -2.49711, -2.55131, -2.58134, -2.61005, -2.51897, -2.33662, -2.30239, -2.27186, -2.14660, -1.98521, -1.99644, -1.96530, -1.84176, -1.79595, -1.84138, -1.93804, -2.06154, -2.14103, -2.32865, -2.56916, -2.64215, -2.53340, -2.55581, -2.84127, -3.08702, -3.18806, -3.30510, -3.25714, -3.01704, -2.88289, -2.83343, -2.73303, -2.71697, -2.80659, -2.94389, -3.06263, -3.05271, -2.85120, -2.81058, -2.87183, -2.85783, -2.72142, -2.73026, -2.78073, -2.78064, -2.76060, -2.75386, -2.67170, -2.54609, -2.48319, -2.60759, -2.85542, -3.03056, -2.99299, -3.02770, -3.27548, -3.41337, -3.19160, -2.95520, -2.68927, -2.35498, -2.15373, -2.02874, -1.78570, -1.60684, -1.44726, -1.25737, -1.15032, -1.06570, -0.86466, -0.75118, -0.72776, -0.68959, -0.72642, -0.91887, -1.19195, -1.31308, -1.48502, -1.82824, -2.15030, -2.29206, -2.30642, -2.30967, -2.50622, -2.74663, -2.88558, -2.96745, -3.18156, -3.42948, -3.54731, -3.67981, -3.73785, -3.62441, -3.65855, -3.85016, -3.89208, -3.94356, -3.92581, -3.84775, -3.86895, -3.93739, -3.79446, -3.71348, -3.80506, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.25823, -2.17999, -2.16199, -1.94992, -1.67963, -1.58129, -1.65973, -1.72872, -1.80742, -1.95666, -1.94147, -2.02452, -2.26699, -2.39533, -2.56635, -2.69391, -2.61027, -2.48393, -2.42716, -2.22760, -1.99926, -1.87302, -1.65904, -1.39237, -1.23754, -1.15098, -0.86100, -0.55571, -0.39586, -0.35786, -0.30796, -0.19032, 0.14168, 0.42494, 0.55740, 0.63097, 0.71351, 0.65505, 0.48942, 0.34514, 0.28885, 0.23802, 0.34381, 0.40705, 0.26496, 0.11944, -0.04241, -0.12864, -0.03807, -0.02619, -0.20224, -0.25759, -0.22517, -0.25306, -0.15660, -0.05754, -0.00905, -0.10819, -0.05126, 0.08650, 0.10258, -0.11032, -0.38438, -0.57364, -0.64195, -0.76342, -1.08409, -1.37466, -1.45097, -1.50405, -1.59318, -1.60652, -1.54227, -1.64698, -1.66670, -1.68494, -1.78930, -1.78505, -1.79554, -1.84679, -1.74801, -1.68284, -1.77295, -1.86935, -2.02724, -2.30194, -2.46600, -2.48643, -2.44915, -2.58646, -2.66103, -2.62134, -2.42024, -2.15191, -1.86540, -1.61262, -1.24959, -0.88964, -0.74674, -0.78731, -0.74176, -0.72253, -0.76789, +-0.70901, -0.44683, -0.13132, 0.12152, 0.24747, 0.28556, 0.30400, 0.50578, 0.59814, 0.52476, 0.37133, 0.25374, 0.17620, 0.04415, -0.00540, 0.07121, 0.17210, 0.11098, -0.08937, -0.20055, -0.33209, -0.59295, -0.81858, -1.02233, -1.24197, -1.27374, -1.35959, -1.54095, -1.55055, -1.58053, -1.57057, -1.46272, -1.30034, -1.17910, -1.19905, -1.21002, -1.22536, -1.37281, -1.70192, -1.73663, -1.67189, -1.66228, -1.73298, -1.77206, -1.72369, -1.74058, -1.65609, -1.48602, -1.38869, -1.43571, -1.43987, -1.14253, -0.74457, -0.58509, -0.58164, -0.59023, -0.72216, -0.74026, -0.77654, -1.01083, -1.22488, -1.38136, -1.44337, -1.33858, -1.39031, -1.40452, -1.42441, -1.35191, -1.34988, -1.30923, -1.35158, -1.26939, -1.19959, -1.21056, -1.20742, -1.12823, -0.91970, -0.84253, -0.80089, -0.64484, -0.45440, -0.36987, -0.53802, -0.66502, -0.67010, -0.70353, -0.70943, -0.57379, -0.48942, -0.41369, -0.37223, -0.43341, -0.39668, -0.40587, -0.52153, -0.49399, -0.49936, -0.58147, -0.84452, -0.87858, -0.86141, -0.73999, -0.83000, -0.84275, -0.82211, -0.86985, -0.90980, -1.04398, -1.21843, -1.56736, -1.84777, -1.92585, -1.89469, -1.94494, -2.19960, -2.31930, -2.32890, -2.34067, -2.35609, -2.31077, -2.38542, -2.36847, -2.21012, -2.13420, -2.03162, -1.85821, -1.70827, -1.46522, -1.37221, -1.28036, -1.38649, -1.52150, -1.77250, -1.87958, -2.06812, -2.17907, -2.25147, -2.45557, -2.63963, -2.74531, -2.62674, -2.55870, -2.68978, -2.83162, -2.88445, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.11923, -3.24118, -3.38190, -3.43301, -3.52308, -3.74481, -3.72169, -3.68700, -3.55654, -3.62877, -3.63236, -3.67989, -3.50080, -3.32017, -3.12723, -2.97002, -2.98542, -2.93842, -2.83422, -2.54553, -2.39948, -2.50880, -2.60241, -2.61143, -2.46660, -2.41711, -2.38932, -2.31840, -2.26475, -2.27283, -2.20718, -2.25556, -2.35260, -2.31535, -2.30985, -2.31351, -2.19987, -2.18053, -2.12092, -2.10877, -1.97824, -1.90770, -1.76314, -1.69826, -1.63489, -1.68783, -1.77036, -1.73060, -1.81867, -2.03941, -2.30765, -2.33312, -2.32830, -2.51718, -2.70066, -2.84060, -2.97375, -3.16328, -3.19165, -2.97593, -2.83053, -2.83881, -2.71679, -2.61417, -2.79322, -2.92842, -2.95094, -2.90223, -2.73530, -2.78051, -2.82071, -2.90470, -2.83049, -2.75256, -2.67550, -2.76753, -2.84470, -2.84468, -2.77056, -2.53299, -2.52555, -2.75243, -3.03688, -3.14501, -3.08788, -3.18305, -3.30270, -3.31064, -3.10884, -2.89140, -2.68462, -2.39063, -2.10712, -1.95677, -1.74503, -1.54351, -1.42995, -1.24602, -1.10034, -1.01401, -0.80608, -0.70771, -0.64682, -0.67167, -0.80699, -0.98480, -1.14233, -1.22171, -1.36559, -1.64793, -2.05257, -2.15813, -2.26753, -2.44465, -2.60975, -2.67918, -2.73713, -2.98157, -3.21985, -3.39921, -3.58863, -3.80424, -3.89535, -3.81305, -3.84933, -4.05067, -4.06710, -3.95234, -3.91703, -3.89115, -3.86479, -3.91723, -3.75186, -3.63299, -3.61901, -3.72712, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.16169, -2.05706, -1.93331, -1.66183, -1.53383, -1.49685, -1.49032, -1.51418, -1.57759, -1.75161, -1.79311, -1.81846, -2.04848, -2.25631, -2.37691, -2.51940, -2.53030, -2.41076, -2.36273, -2.21020, -2.05307, -1.86476, -1.55582, -1.30936, -1.09624, -0.96769, -0.67929, -0.51038, -0.34868, -0.30144, -0.10030, 0.11546, 0.28510, 0.50997, 0.70852, 0.85071, 0.79223, 0.69917, 0.61580, 0.43212, 0.32502, 0.30620, 0.46293, 0.57671, 0.42176, 0.20540, 0.09369, 0.03728, 0.06977, 0.12082, -0.08098, -0.21477, -0.20527, -0.15695, 0.02393, 0.02278, 0.05032, -0.04582, 0.03113, 0.09547, 0.16085, -0.07294, -0.28989, -0.40178, -0.60183, -0.82279, -1.10073, -1.21194, -1.32201, -1.44622, -1.47701, -1.47354, -1.50357, -1.68853, -1.74919, -1.73376, -1.81920, -1.89791, -1.85970, -1.87712, -1.88133, -1.75572, -1.74525, -1.80613, -1.99135, -2.29268, -2.40911, -2.57226, -2.56758, -2.57692, -2.48883, -2.51201, -2.37640, -2.22475, -1.95881, -1.64077, -1.39056, -1.07844, -0.92033, -0.86707, -0.87883, -0.90242, -0.81515, +-0.69531, -0.44061, -0.12905, 0.08090, 0.12342, 0.19819, 0.29236, 0.45814, 0.54026, 0.52761, 0.42843, 0.31507, 0.19826, 0.07374, 0.10601, 0.17450, 0.19723, 0.14190, -0.07653, -0.28827, -0.43792, -0.63766, -0.84033, -1.03802, -1.23409, -1.33390, -1.47035, -1.55785, -1.51002, -1.52472, -1.51440, -1.43759, -1.31770, -1.21980, -1.25245, -1.29028, -1.32946, -1.42393, -1.64628, -1.69110, -1.58920, -1.49668, -1.57997, -1.69077, -1.76029, -1.83943, -1.68142, -1.45514, -1.37085, -1.38955, -1.37158, -1.13648, -0.81177, -0.69604, -0.73541, -0.77881, -0.86012, -0.83221, -0.82527, -0.93052, -1.12824, -1.35104, -1.43645, -1.35732, -1.51790, -1.58751, -1.57491, -1.51633, -1.56926, -1.52120, -1.47541, -1.40360, -1.28046, -1.17386, -1.11550, -1.06935, -0.94828, -0.89437, -0.79957, -0.62185, -0.46845, -0.36183, -0.44268, -0.57674, -0.60942, -0.62026, -0.66023, -0.55472, -0.38524, -0.24866, -0.24874, -0.27013, -0.22798, -0.30642, -0.46660, -0.43709, -0.48090, -0.57023, -0.74459, -0.72383, -0.67639, -0.55827, -0.64392, -0.76372, -0.81552, -0.83323, -0.83042, -0.94447, -1.12922, -1.46638, -1.64981, -1.63771, -1.68783, -1.83307, -2.08090, -2.25887, -2.30654, -2.26864, -2.27593, -2.28845, -2.36596, -2.35977, -2.25694, -2.14994, -2.06910, -1.92400, -1.73976, -1.46913, -1.45036, -1.41756, -1.47633, -1.54677, -1.72780, -1.80071, -1.90470, -2.07979, -2.22715, -2.40452, -2.61971, -2.80558, -2.75885, -2.70959, -2.70647, -2.69411, -2.76064, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.26623, -3.42600, -3.48127, -3.45572, -3.51441, -3.66659, -3.55044, -3.48890, -3.40156, -3.49331, -3.51097, -3.58793, -3.45344, -3.20092, -3.01875, -2.89555, -2.86144, -2.77647, -2.68734, -2.52472, -2.52680, -2.61030, -2.60445, -2.61577, -2.47321, -2.36742, -2.34356, -2.29624, -2.20212, -2.15869, -2.14945, -2.21355, -2.23289, -2.19037, -2.17906, -2.21557, -2.16589, -2.16537, -2.04141, -1.98643, -1.86200, -1.74452, -1.57847, -1.50777, -1.45849, -1.48475, -1.61000, -1.63002, -1.66788, -1.77568, -1.99428, -2.06966, -2.16145, -2.35365, -2.41724, -2.52566, -2.70358, -2.95579, -3.09294, -2.96915, -2.85110, -2.84717, -2.75974, -2.65066, -2.72843, -2.82604, -2.80769, -2.70511, -2.60575, -2.75554, -2.81610, -2.93279, -2.91063, -2.79778, -2.67170, -2.74137, -2.83424, -2.79419, -2.73885, -2.67368, -2.76053, -2.95432, -3.21887, -3.33575, -3.29846, -3.32378, -3.27802, -3.21518, -3.01661, -2.76915, -2.62381, -2.44819, -2.16225, -1.94970, -1.81304, -1.71195, -1.56837, -1.36947, -1.15692, -0.93849, -0.70922, -0.64220, -0.58824, -0.60361, -0.75110, -0.92960, -1.05708, -1.09715, -1.20369, -1.38057, -1.74802, -1.99216, -2.19857, -2.38168, -2.51151, -2.56370, -2.67549, -2.96882, -3.15165, -3.30041, -3.55332, -3.80261, -3.93029, -3.93176, -3.95530, -4.05342, -4.05330, -3.94616, -3.87017, -3.86853, -3.84928, -3.84040, -3.67714, -3.56487, -3.49503, -3.52117, -3.61678, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.11593, -1.97238, -1.85637, -1.63957, -1.52753, -1.46092, -1.43408, -1.45778, -1.48141, -1.67042, -1.82521, -1.84896, -1.96046, -2.09374, -2.21561, -2.32983, -2.37672, -2.34572, -2.26334, -2.14044, -2.08479, -1.91690, -1.53652, -1.22657, -0.91717, -0.70673, -0.42614, -0.30669, -0.17161, -0.06008, 0.08463, 0.23917, 0.38577, 0.59544, 0.77995, 0.86056, 0.77000, 0.75113, 0.75252, 0.59456, 0.53710, 0.55752, 0.65535, 0.72315, 0.60072, 0.38346, 0.18017, 0.11249, 0.14901, 0.16280, 0.04156, -0.06632, -0.08146, -0.04118, 0.10949, 0.04467, 0.04860, -0.02489, 0.06358, 0.13762, 0.19726, 0.02299, -0.26398, -0.42766, -0.59024, -0.83476, -1.13298, -1.22996, -1.31919, -1.39783, -1.38030, -1.39903, -1.43342, -1.57064, -1.68561, -1.72487, -1.80163, -1.91373, -1.95308, -1.97152, -1.98226, -1.90396, -1.80612, -1.78328, -1.92020, -2.18339, -2.24237, -2.40867, -2.41026, -2.32827, -2.18607, -2.25079, -2.26297, -2.16168, -2.01655, -1.81621, -1.55938, -1.21998, -1.03529, -0.94607, -0.93245, -0.87958, -0.69750, +-0.81940, -0.55193, -0.23325, -0.05395, -0.05094, 0.12022, 0.38503, 0.50123, 0.53382, 0.62404, 0.58543, 0.44042, 0.29146, 0.25504, 0.29183, 0.23287, 0.22114, 0.24544, 0.14194, -0.14417, -0.39565, -0.53263, -0.68885, -0.88519, -1.03434, -1.22126, -1.49143, -1.55281, -1.45735, -1.48138, -1.50961, -1.48116, -1.37968, -1.25042, -1.26187, -1.33864, -1.42339, -1.44043, -1.47118, -1.54175, -1.51649, -1.36742, -1.43106, -1.62818, -1.80578, -1.85546, -1.68153, -1.58548, -1.52056, -1.42545, -1.28611, -1.10816, -0.94140, -0.83183, -0.83944, -0.87487, -0.87577, -0.84230, -0.90387, -0.97481, -1.14380, -1.41353, -1.54668, -1.53077, -1.74076, -1.81954, -1.79293, -1.76996, -1.84524, -1.73949, -1.51388, -1.40570, -1.31111, -1.11644, -0.98884, -0.99146, -0.95051, -0.83981, -0.68452, -0.65781, -0.57631, -0.40538, -0.35487, -0.45114, -0.56899, -0.52855, -0.51152, -0.40284, -0.18181, -0.05038, -0.16181, -0.19966, -0.10589, -0.20377, -0.40130, -0.43149, -0.51049, -0.57584, -0.67242, -0.64940, -0.61368, -0.49933, -0.46925, -0.59080, -0.75851, -0.75917, -0.69315, -0.82424, -1.03471, -1.26588, -1.32252, -1.41865, -1.57162, -1.71595, -1.87537, -2.01785, -2.16300, -2.10259, -2.07296, -2.12042, -2.23563, -2.28423, -2.31769, -2.26993, -2.14320, -1.99880, -1.83016, -1.60367, -1.61073, -1.57650, -1.56673, -1.58108, -1.69992, -1.74187, -1.68811, -1.79688, -2.04684, -2.22828, -2.41841, -2.69036, -2.76463, -2.71517, -2.58249, -2.61405, -2.73077, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.19605, -3.44545, -3.54843, -3.43883, -3.44083, -3.56152, -3.46290, -3.42296, -3.37122, -3.44081, -3.46613, -3.56560, -3.47633, -3.11069, -2.83837, -2.79043, -2.73829, -2.58099, -2.52503, -2.50281, -2.57870, -2.55658, -2.59522, -2.67928, -2.52023, -2.33854, -2.24375, -2.31368, -2.25033, -2.11731, -2.05121, -2.07116, -2.01702, -2.04670, -2.13678, -2.14375, -2.10014, -2.12692, -2.01117, -1.94506, -1.82235, -1.63349, -1.42526, -1.33598, -1.30212, -1.22886, -1.26496, -1.40113, -1.49340, -1.51360, -1.69859, -1.84820, -1.98970, -2.08224, -2.17360, -2.39116, -2.60197, -2.82269, -2.89546, -2.88014, -2.83879, -2.77079, -2.64077, -2.51435, -2.50479, -2.65194, -2.75414, -2.64002, -2.57255, -2.79483, -2.91583, -3.08285, -3.09995, -2.94292, -2.78240, -2.82785, -2.91645, -2.78066, -2.60963, -2.68817, -2.89126, -3.00919, -3.22076, -3.37412, -3.37059, -3.27349, -3.20207, -3.24950, -3.06673, -2.73610, -2.48686, -2.39423, -2.20153, -1.93686, -1.78428, -1.71557, -1.53715, -1.38884, -1.23772, -0.93022, -0.65243, -0.59985, -0.56668, -0.59193, -0.72690, -0.84782, -0.93708, -0.97828, -1.09378, -1.16501, -1.37150, -1.71279, -2.05005, -2.20091, -2.30484, -2.42591, -2.62186, -2.84528, -2.98571, -3.24410, -3.53398, -3.72528, -3.76624, -3.82566, -3.93440, -3.95316, -3.90478, -3.81125, -3.70478, -3.76249, -3.83960, -3.80998, -3.61535, -3.51907, -3.45373, -3.45221, -3.49297, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.97339, -1.80900, -1.78016, -1.65659, -1.48883, -1.37872, -1.49326, -1.57351, -1.53158, -1.61121, -1.77764, -1.88115, -1.87577, -1.86122, -1.92825, -2.00428, -2.11064, -2.22100, -2.16407, -2.02503, -2.03127, -1.92227, -1.57509, -1.24340, -0.84830, -0.54321, -0.26814, -0.17085, -0.01893, 0.22415, 0.33605, 0.34126, 0.48261, 0.73379, 0.87398, 0.88351, 0.85173, 0.93033, 0.83696, 0.65942, 0.68264, 0.80068, 0.89413, 0.83442, 0.75211, 0.60766, 0.38935, 0.31017, 0.29803, 0.18466, 0.06009, 0.03123, 0.01136, 0.01698, 0.08693, -0.01153, 0.01688, 0.01301, 0.11178, 0.18085, 0.24284, 0.19030, -0.09293, -0.37683, -0.52679, -0.71338, -1.03874, -1.19860, -1.24935, -1.21955, -1.30179, -1.40325, -1.39458, -1.41032, -1.47826, -1.65686, -1.75127, -1.81992, -1.85771, -1.86460, -1.88957, -1.93790, -1.89924, -1.80691, -1.89463, -2.12423, -2.18164, -2.32311, -2.28796, -2.12413, -1.97634, -2.08777, -2.18413, -2.01895, -1.86246, -1.81329, -1.58777, -1.18895, -0.99906, -0.93926, -0.89506, -0.72650, -0.63832, +-0.93690, -0.76625, -0.46873, -0.25466, -0.16482, 0.02112, 0.30345, 0.49323, 0.52004, 0.58450, 0.66242, 0.64272, 0.44458, 0.31800, 0.36969, 0.36560, 0.37629, 0.39785, 0.34092, 0.09575, -0.17322, -0.36335, -0.56382, -0.75543, -0.89354, -1.08414, -1.34698, -1.43039, -1.36884, -1.39440, -1.46019, -1.44750, -1.38783, -1.32393, -1.32510, -1.38875, -1.45997, -1.50510, -1.50022, -1.46859, -1.45541, -1.41575, -1.46312, -1.55032, -1.74633, -1.85987, -1.67599, -1.55927, -1.51327, -1.43844, -1.29500, -1.10040, -0.97701, -0.92696, -0.93615, -0.94999, -0.98139, -0.97838, -1.00672, -1.03238, -1.21670, -1.50610, -1.68173, -1.69291, -1.91928, -2.08636, -2.07875, -2.01626, -2.00281, -1.85885, -1.61840, -1.42649, -1.32866, -1.21840, -1.04958, -0.88745, -0.81613, -0.77832, -0.61270, -0.57386, -0.56501, -0.47371, -0.43654, -0.42169, -0.44815, -0.37497, -0.36746, -0.28069, -0.08232, 0.04983, -0.05647, -0.07787, -0.00240, -0.07721, -0.27771, -0.35169, -0.48815, -0.66138, -0.71784, -0.62026, -0.51785, -0.42488, -0.46445, -0.54106, -0.67191, -0.71674, -0.61378, -0.59410, -0.76696, -1.04239, -1.08271, -1.13578, -1.34066, -1.55690, -1.70995, -1.77849, -1.92522, -1.91630, -1.93696, -2.01768, -2.20012, -2.31572, -2.38193, -2.32585, -2.19789, -2.02941, -1.86948, -1.66025, -1.65566, -1.70461, -1.68889, -1.64946, -1.69706, -1.69614, -1.65427, -1.67226, -1.84195, -2.08312, -2.28141, -2.46644, -2.58681, -2.67602, -2.58178, -2.51255, -2.57049, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.05165, -3.14927, -3.38834, -3.48589, -3.41773, -3.39910, -3.45775, -3.34615, -3.31197, -3.40984, -3.55532, -3.56693, -3.58757, -3.42059, -3.08390, -2.79254, -2.69442, -2.68351, -2.54387, -2.37784, -2.35973, -2.53661, -2.51791, -2.48789, -2.59771, -2.53823, -2.41012, -2.28604, -2.33362, -2.25576, -2.14007, -2.05370, -2.02397, -1.93119, -1.93906, -1.99373, -2.00437, -1.96059, -1.98183, -1.89459, -1.83906, -1.80323, -1.63163, -1.34648, -1.13470, -1.00426, -0.94586, -1.00700, -1.16030, -1.36748, -1.45703, -1.49377, -1.54452, -1.74454, -1.90283, -1.98140, -2.18896, -2.44899, -2.73779, -2.80861, -2.76495, -2.67922, -2.63041, -2.54024, -2.45793, -2.45094, -2.55493, -2.63081, -2.56160, -2.57665, -2.85263, -3.01478, -3.16126, -3.21978, -3.11705, -2.95691, -2.93237, -2.92304, -2.80145, -2.64003, -2.70581, -2.95556, -3.08992, -3.17949, -3.26407, -3.34635, -3.31253, -3.20765, -3.23707, -3.10037, -2.82187, -2.55364, -2.38527, -2.14382, -1.90361, -1.77242, -1.71170, -1.54523, -1.38542, -1.20777, -0.90503, -0.64250, -0.57157, -0.51622, -0.48835, -0.63049, -0.79537, -0.90576, -0.93069, -0.99983, -1.07526, -1.23347, -1.49227, -1.85847, -2.10806, -2.17237, -2.18829, -2.43129, -2.75181, -2.87507, -3.07687, -3.34974, -3.58253, -3.66305, -3.70917, -3.77214, -3.76091, -3.72678, -3.67516, -3.64435, -3.73298, -3.78224, -3.70366, -3.49006, -3.38671, -3.34727, -3.32166, -3.34336, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.93215, -1.74289, -1.61459, -1.54724, -1.50991, -1.42305, -1.49405, -1.59730, -1.61108, -1.68610, -1.76439, -1.78947, -1.72874, -1.69015, -1.75103, -1.84641, -1.95547, -2.03139, -1.93739, -1.81677, -1.83910, -1.80861, -1.51608, -1.21698, -0.88529, -0.51329, -0.15503, 0.02539, 0.17065, 0.36003, 0.50533, 0.47751, 0.48472, 0.73460, 1.01907, 1.06003, 0.93596, 0.98002, 0.92019, 0.77446, 0.80598, 0.91969, 1.04617, 0.98265, 0.90091, 0.75454, 0.55726, 0.46339, 0.41038, 0.27065, 0.17439, 0.14645, 0.12968, 0.09880, 0.11952, 0.03448, 0.01151, 0.01317, 0.11614, 0.22808, 0.32654, 0.25220, 0.00647, -0.27743, -0.53441, -0.71992, -0.87489, -1.00740, -1.16198, -1.15725, -1.18341, -1.28241, -1.31706, -1.36950, -1.41224, -1.57567, -1.65109, -1.71014, -1.72892, -1.74086, -1.79073, -1.89592, -1.88159, -1.84069, -1.90267, -2.06386, -2.08385, -2.17785, -2.22465, -2.07328, -1.88366, -1.94828, -2.04096, -1.94116, -1.76467, -1.68362, -1.57376, -1.25530, -0.95662, -0.81839, -0.81376, -0.67696, -0.57941, +-0.88067, -0.71549, -0.52614, -0.30381, -0.12326, -0.02851, 0.17235, 0.42287, 0.55304, 0.64660, 0.67616, 0.66766, 0.49582, 0.31854, 0.34087, 0.35629, 0.45292, 0.51151, 0.45878, 0.30220, 0.01638, -0.32042, -0.58984, -0.77995, -0.86303, -0.98407, -1.23699, -1.40273, -1.40140, -1.40188, -1.49047, -1.45186, -1.33524, -1.23382, -1.26747, -1.36118, -1.42249, -1.63999, -1.70871, -1.56954, -1.44631, -1.38806, -1.51150, -1.58242, -1.64348, -1.68476, -1.51398, -1.41646, -1.38394, -1.35680, -1.32337, -1.15175, -1.04925, -1.06812, -1.02160, -0.96421, -1.04640, -1.08527, -1.11309, -1.12330, -1.28744, -1.53414, -1.75885, -1.79469, -1.94709, -2.07228, -2.11528, -2.06577, -1.92881, -1.82942, -1.65366, -1.43722, -1.32139, -1.21257, -1.13343, -0.99812, -0.81144, -0.72694, -0.54168, -0.46532, -0.49375, -0.46633, -0.57514, -0.53131, -0.44012, -0.38386, -0.38749, -0.29996, -0.14003, 0.05331, -0.01890, -0.04060, -0.00111, 0.00887, -0.17017, -0.29814, -0.45628, -0.65057, -0.70666, -0.59567, -0.36757, -0.32798, -0.47811, -0.52024, -0.51453, -0.42413, -0.35647, -0.40071, -0.52733, -0.78997, -0.87564, -0.92626, -1.13163, -1.29037, -1.45292, -1.50035, -1.65731, -1.80358, -1.89232, -1.92271, -2.11790, -2.20732, -2.29737, -2.27502, -2.17148, -1.94309, -1.79289, -1.62632, -1.57551, -1.57259, -1.56689, -1.62587, -1.64632, -1.69073, -1.77123, -1.77004, -1.79810, -1.90625, -2.07678, -2.30799, -2.43263, -2.55676, -2.58355, -2.48506, -2.46010, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.04916, -3.07545, -3.29146, -3.45537, -3.51774, -3.50799, -3.51129, -3.39627, -3.31830, -3.38908, -3.56369, -3.64819, -3.53330, -3.28843, -3.06938, -2.83748, -2.69256, -2.60181, -2.49044, -2.40739, -2.34049, -2.39565, -2.33740, -2.26833, -2.43093, -2.43151, -2.38710, -2.29703, -2.26279, -2.20215, -2.16455, -2.03851, -1.98021, -1.80110, -1.77181, -1.82683, -1.87797, -1.79622, -1.78288, -1.78636, -1.77156, -1.70313, -1.53434, -1.29352, -0.94269, -0.70832, -0.69798, -0.80935, -0.96535, -1.17080, -1.36867, -1.47849, -1.44399, -1.53960, -1.75250, -1.88893, -2.09803, -2.30621, -2.62727, -2.76772, -2.68443, -2.55150, -2.57080, -2.52252, -2.54152, -2.54816, -2.59111, -2.65016, -2.64297, -2.68015, -2.94213, -3.14475, -3.21557, -3.16184, -3.06032, -3.00874, -2.96683, -2.90018, -2.89708, -2.81210, -2.79492, -2.86971, -2.92828, -3.07047, -3.19436, -3.27024, -3.27320, -3.16914, -3.16957, -3.01784, -2.80108, -2.61978, -2.37236, -2.07586, -1.91064, -1.77416, -1.69971, -1.48869, -1.27445, -1.14581, -0.95995, -0.73126, -0.63741, -0.60365, -0.51712, -0.55788, -0.64642, -0.82610, -0.88484, -0.93472, -1.16219, -1.34533, -1.46271, -1.68411, -1.93921, -2.12873, -2.14591, -2.29094, -2.60888, -2.75358, -2.91871, -3.08584, -3.31996, -3.54965, -3.64490, -3.69234, -3.71929, -3.68614, -3.64540, -3.64427, -3.69855, -3.72983, -3.62065, -3.37086, -3.23311, -3.25956, -3.26845, -3.24505, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.68012, -1.55120, -1.43179, -1.32540, -1.34969, -1.35439, -1.41629, -1.49932, -1.53286, -1.70281, -1.74138, -1.66752, -1.64025, -1.65675, -1.73988, -1.85442, -1.91694, -1.96484, -1.85589, -1.72860, -1.64993, -1.66265, -1.44909, -1.17213, -0.85292, -0.46161, -0.06295, 0.25869, 0.30832, 0.34832, 0.51644, 0.57314, 0.61572, 0.77722, 1.02621, 1.19477, 1.07956, 1.00287, 0.88469, 0.76413, 0.86714, 0.91822, 1.04283, 1.03630, 0.90910, 0.74796, 0.64533, 0.56338, 0.53389, 0.35104, 0.18850, 0.09622, 0.11252, 0.05839, 0.07784, 0.12650, 0.21824, 0.21511, 0.20803, 0.38416, 0.46719, 0.33578, 0.13883, -0.07843, -0.30358, -0.56148, -0.75115, -0.81634, -0.97003, -1.05983, -1.08859, -1.15161, -1.16362, -1.36468, -1.49684, -1.61204, -1.72680, -1.80119, -1.73410, -1.72398, -1.66944, -1.79978, -1.87681, -1.97864, -2.04572, -2.14257, -2.13191, -2.14100, -2.15824, -2.03796, -1.88863, -1.81867, -1.88546, -1.89564, -1.70981, -1.50501, -1.35611, -1.19252, -1.06385, -0.87751, -0.78375, -0.70427, -0.62476, +-0.78435, -0.56199, -0.44492, -0.34983, -0.21438, -0.08726, 0.15670, 0.42937, 0.50269, 0.56501, 0.59899, 0.60620, 0.51765, 0.42926, 0.36891, 0.24295, 0.31854, 0.40562, 0.42319, 0.33222, 0.05487, -0.27602, -0.52599, -0.66649, -0.76305, -0.87696, -1.08427, -1.27521, -1.39138, -1.47569, -1.54651, -1.54064, -1.37717, -1.19772, -1.25582, -1.47463, -1.60580, -1.80426, -1.82320, -1.59873, -1.46100, -1.38298, -1.45593, -1.51043, -1.48970, -1.43667, -1.34153, -1.38059, -1.36755, -1.35742, -1.34953, -1.23479, -1.20456, -1.21233, -1.09667, -0.94428, -1.03549, -1.10742, -1.08461, -1.04760, -1.22374, -1.54147, -1.74991, -1.85412, -1.98960, -2.03360, -2.09275, -2.15330, -2.06447, -1.88551, -1.63429, -1.32644, -1.20749, -1.14599, -1.10292, -1.06975, -0.88860, -0.70557, -0.49985, -0.49548, -0.52817, -0.52907, -0.68685, -0.65830, -0.56037, -0.45264, -0.41027, -0.26755, -0.13075, 0.02750, 0.02614, 0.04949, 0.05387, -0.01869, -0.14620, -0.33672, -0.51010, -0.63975, -0.69304, -0.65085, -0.44001, -0.28435, -0.34162, -0.28706, -0.24973, -0.19941, -0.14871, -0.23704, -0.34865, -0.51854, -0.60623, -0.80076, -1.03011, -1.16943, -1.31390, -1.34795, -1.52286, -1.66027, -1.72057, -1.65828, -1.82240, -1.96251, -2.02234, -1.99099, -1.93289, -1.83983, -1.67965, -1.59687, -1.59078, -1.51110, -1.50659, -1.66380, -1.75759, -1.75791, -1.82263, -1.79566, -1.80452, -1.90569, -1.98879, -2.18040, -2.29252, -2.36402, -2.42617, -2.47268, -2.43982, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.93017, -3.01627, -3.20744, -3.37667, -3.50235, -3.65363, -3.63091, -3.53200, -3.45344, -3.39563, -3.52714, -3.69140, -3.64218, -3.37276, -3.13415, -2.83749, -2.65779, -2.58195, -2.44557, -2.38187, -2.30592, -2.24040, -2.09870, -2.12120, -2.30714, -2.31381, -2.28702, -2.18018, -2.13773, -2.05571, -1.99077, -1.80330, -1.71882, -1.59120, -1.53214, -1.56672, -1.64650, -1.68558, -1.65918, -1.67691, -1.69434, -1.54187, -1.36788, -1.24446, -0.97588, -0.68620, -0.55240, -0.54091, -0.67524, -0.96443, -1.23594, -1.39072, -1.35003, -1.35823, -1.53232, -1.81466, -2.09460, -2.28362, -2.58939, -2.72461, -2.67376, -2.52396, -2.51924, -2.44782, -2.48405, -2.59084, -2.62798, -2.64000, -2.62531, -2.73921, -3.00171, -3.21105, -3.31862, -3.21168, -3.08965, -3.10580, -3.15691, -3.08030, -3.00769, -2.84899, -2.76651, -2.81450, -2.84140, -2.96664, -3.08940, -3.10685, -3.04904, -3.02894, -3.10170, -2.96208, -2.77122, -2.61573, -2.39563, -2.09642, -1.89623, -1.71828, -1.60011, -1.41346, -1.17750, -0.99279, -0.81722, -0.69485, -0.70433, -0.74073, -0.72930, -0.70407, -0.67381, -0.85627, -1.02658, -1.12695, -1.31611, -1.40225, -1.39733, -1.57865, -1.85016, -2.07070, -2.11283, -2.18556, -2.39688, -2.59353, -2.84627, -2.96369, -3.17902, -3.43802, -3.59207, -3.67757, -3.67019, -3.59508, -3.49774, -3.50912, -3.56770, -3.55347, -3.43095, -3.26733, -3.22974, -3.25689, -3.33026, -3.26671, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.34736, -1.21048, -1.11380, -0.99759, -0.98746, -1.10874, -1.35192, -1.46513, -1.51835, -1.72911, -1.79350, -1.71421, -1.62154, -1.57455, -1.58360, -1.71122, -1.84312, -1.89590, -1.77137, -1.65900, -1.60279, -1.55197, -1.40940, -1.15259, -0.78111, -0.38768, -0.05730, 0.24221, 0.34217, 0.40172, 0.63463, 0.70660, 0.71239, 0.85365, 1.05468, 1.26703, 1.22982, 1.08655, 0.78177, 0.64353, 0.77870, 0.83908, 0.98673, 1.01076, 0.94255, 0.82368, 0.78971, 0.67471, 0.56684, 0.40298, 0.24765, 0.11986, 0.02106, -0.01215, -0.02734, 0.07711, 0.31463, 0.35893, 0.28391, 0.42392, 0.59401, 0.56126, 0.48770, 0.29503, 0.01075, -0.28634, -0.54194, -0.61644, -0.72843, -0.89486, -1.12026, -1.20150, -1.18791, -1.39475, -1.53801, -1.67459, -1.80095, -1.88062, -1.72801, -1.66894, -1.60233, -1.67552, -1.75768, -1.94100, -2.17986, -2.24809, -2.25449, -2.25436, -2.18338, -2.05956, -1.97372, -1.91375, -1.87714, -1.80859, -1.51529, -1.25308, -1.17460, -1.09007, -1.07848, -0.92923, -0.75713, -0.67192, -0.72282, +-0.64442, -0.46367, -0.26141, -0.22598, -0.25363, -0.12850, 0.04112, 0.25379, 0.32113, 0.35415, 0.44251, 0.55687, 0.50392, 0.46940, 0.49540, 0.32917, 0.33118, 0.40307, 0.46670, 0.38652, 0.08463, -0.17638, -0.44201, -0.59244, -0.69256, -0.75536, -0.92559, -1.21201, -1.37378, -1.40618, -1.44178, -1.50800, -1.39794, -1.28423, -1.27509, -1.49779, -1.73703, -1.86975, -1.89266, -1.70331, -1.50980, -1.39461, -1.36918, -1.33910, -1.35829, -1.36765, -1.23846, -1.25647, -1.23888, -1.21489, -1.19235, -1.14316, -1.25374, -1.30526, -1.24728, -1.13854, -1.16946, -1.14576, -1.05917, -1.10641, -1.28867, -1.51471, -1.62831, -1.78830, -1.98460, -2.10824, -2.10326, -2.13925, -2.18503, -1.97432, -1.70656, -1.39854, -1.15740, -1.07517, -1.01872, -1.00644, -0.92808, -0.80365, -0.52411, -0.46196, -0.49058, -0.50720, -0.65528, -0.64810, -0.63091, -0.51207, -0.46280, -0.37996, -0.23743, -0.07066, -0.00362, -0.05465, -0.06295, -0.06483, -0.08557, -0.30541, -0.48505, -0.65163, -0.64255, -0.52339, -0.41330, -0.20305, -0.19234, -0.19765, -0.12746, -0.12942, -0.08966, -0.10726, -0.19919, -0.37628, -0.37054, -0.50804, -0.76653, -0.95836, -1.11838, -1.15067, -1.33684, -1.42495, -1.46195, -1.48181, -1.62670, -1.76280, -1.73828, -1.78727, -1.79989, -1.70133, -1.45766, -1.44065, -1.50534, -1.52369, -1.51526, -1.54529, -1.69493, -1.70035, -1.74874, -1.87044, -1.87720, -1.94459, -1.96880, -2.04704, -2.12913, -2.26416, -2.27128, -2.25882, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.93370, -3.05936, -3.19644, -3.43203, -3.60678, -3.73050, -3.59517, -3.50688, -3.45289, -3.42101, -3.51503, -3.56215, -3.62399, -3.45814, -3.20083, -2.97352, -2.72374, -2.56494, -2.37748, -2.23563, -2.15954, -2.19393, -2.00916, -1.92651, -2.03627, -2.00992, -1.99404, -1.87820, -1.88757, -1.83415, -1.71373, -1.62154, -1.56527, -1.48723, -1.36323, -1.44209, -1.59499, -1.63047, -1.47691, -1.41040, -1.40054, -1.29385, -1.17145, -1.01994, -0.87238, -0.65344, -0.43852, -0.46107, -0.56562, -0.82244, -1.10004, -1.21861, -1.17531, -1.27588, -1.43106, -1.64495, -1.93361, -2.14850, -2.46897, -2.58780, -2.59693, -2.52009, -2.48481, -2.49815, -2.54553, -2.68190, -2.66655, -2.68596, -2.73559, -2.82038, -2.94911, -3.11502, -3.29776, -3.30442, -3.24759, -3.15589, -3.21659, -3.18514, -3.02451, -2.90523, -2.84288, -2.86380, -2.88611, -2.92433, -2.93549, -2.97338, -2.90846, -2.81640, -2.88484, -2.77005, -2.60329, -2.45708, -2.32080, -2.11112, -1.87201, -1.75990, -1.66253, -1.47949, -1.15950, -0.86966, -0.71902, -0.60804, -0.57285, -0.64961, -0.75699, -0.79658, -0.81043, -0.88661, -1.06058, -1.25845, -1.37274, -1.46097, -1.45362, -1.55464, -1.80290, -1.97301, -1.97763, -2.10723, -2.32018, -2.42122, -2.63388, -2.74579, -2.96013, -3.19063, -3.37038, -3.52624, -3.49720, -3.48021, -3.43630, -3.44433, -3.45726, -3.41437, -3.42151, -3.33805, -3.24094, -3.17969, -3.26113, -3.17599, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.04766, -0.88519, -0.75231, -0.69847, -0.75475, -0.87090, -1.16554, -1.34227, -1.44104, -1.66768, -1.76805, -1.76227, -1.61824, -1.50586, -1.51490, -1.62408, -1.76563, -1.82248, -1.80498, -1.69339, -1.53230, -1.35454, -1.24505, -1.01423, -0.71025, -0.27885, 0.09213, 0.27530, 0.40618, 0.47996, 0.63509, 0.74042, 0.72291, 0.86208, 1.08788, 1.24652, 1.13803, 1.05351, 0.79637, 0.66111, 0.78732, 0.85880, 1.02030, 1.01615, 0.97671, 0.86414, 0.70974, 0.54360, 0.41829, 0.33747, 0.14717, 0.04193, 0.01871, 0.08910, 0.01688, 0.07989, 0.25703, 0.38132, 0.47035, 0.55019, 0.74105, 0.77239, 0.65374, 0.52786, 0.25000, -0.06762, -0.31835, -0.44016, -0.66174, -0.82834, -1.04307, -1.15037, -1.12708, -1.26224, -1.35827, -1.55709, -1.73956, -1.85563, -1.80239, -1.71510, -1.63656, -1.60727, -1.74099, -1.96028, -2.17572, -2.15137, -2.18378, -2.20816, -2.19230, -2.05714, -1.86331, -1.87526, -1.82850, -1.67324, -1.43994, -1.14768, -1.08088, -1.02185, -0.98445, -0.86038, -0.79763, -0.69247, -0.67001, +-0.46433, -0.24571, -0.06219, -0.05059, -0.09671, -0.08353, -0.05490, 0.06434, 0.22067, 0.36244, 0.39010, 0.42598, 0.43765, 0.50847, 0.63587, 0.50117, 0.38058, 0.42575, 0.45314, 0.30070, 0.06873, -0.06357, -0.33096, -0.53789, -0.62368, -0.71583, -0.87518, -1.12748, -1.31814, -1.42596, -1.52365, -1.56834, -1.48691, -1.39364, -1.41952, -1.64070, -1.79154, -1.83009, -1.84079, -1.72938, -1.53741, -1.32799, -1.28209, -1.32249, -1.31489, -1.23571, -1.05412, -1.02494, -1.07697, -1.06935, -1.03665, -1.05093, -1.15454, -1.20490, -1.25717, -1.26146, -1.20993, -1.17135, -1.15941, -1.25043, -1.41274, -1.57679, -1.66774, -1.75361, -1.96257, -2.11420, -2.14574, -2.21043, -2.16403, -1.90960, -1.68470, -1.42861, -1.13503, -0.90989, -0.84444, -0.96188, -0.93703, -0.76590, -0.51169, -0.45941, -0.55245, -0.59393, -0.69957, -0.76792, -0.77201, -0.61502, -0.54698, -0.53858, -0.39589, -0.29013, -0.28705, -0.32113, -0.29759, -0.25414, -0.27486, -0.40486, -0.51970, -0.56507, -0.49692, -0.43862, -0.34766, -0.12520, -0.10320, -0.15866, -0.07437, 0.04854, 0.08477, -0.05011, -0.14873, -0.20981, -0.13522, -0.16559, -0.42882, -0.69222, -0.84931, -0.93090, -1.04686, -1.04840, -1.12455, -1.30207, -1.41769, -1.52361, -1.53403, -1.59110, -1.63256, -1.56034, -1.39307, -1.33998, -1.34643, -1.32980, -1.32845, -1.40756, -1.52888, -1.49930, -1.57376, -1.79087, -1.83431, -1.77506, -1.81036, -2.03753, -2.13422, -2.15030, -2.09227, -2.01904, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.98838, -3.12525, -3.33627, -3.59872, -3.75031, -3.76669, -3.64151, -3.56630, -3.54283, -3.47124, -3.46354, -3.49588, -3.50482, -3.28765, -3.06467, -2.91558, -2.67880, -2.37369, -2.11878, -2.05738, -2.01680, -2.00129, -1.79647, -1.60310, -1.63985, -1.66994, -1.66187, -1.60782, -1.59974, -1.46633, -1.31442, -1.36172, -1.38430, -1.37058, -1.35893, -1.46835, -1.54150, -1.48069, -1.31644, -1.18860, -1.11643, -0.97836, -0.84149, -0.77995, -0.69140, -0.46504, -0.33791, -0.46539, -0.56017, -0.65352, -0.84253, -1.09462, -1.19031, -1.27537, -1.35558, -1.48081, -1.80280, -2.16414, -2.48450, -2.61228, -2.63553, -2.54191, -2.49882, -2.62875, -2.68530, -2.72858, -2.75980, -2.87490, -2.96396, -2.97897, -3.04169, -3.15251, -3.26712, -3.24973, -3.18369, -3.13925, -3.20875, -3.11443, -2.95041, -2.86810, -2.82056, -2.76569, -2.72784, -2.81362, -2.85368, -2.84042, -2.74784, -2.58853, -2.59238, -2.54380, -2.38951, -2.27687, -2.22504, -2.05317, -1.83014, -1.79404, -1.66878, -1.39786, -1.09044, -0.82343, -0.64109, -0.47334, -0.42871, -0.54848, -0.67199, -0.74689, -0.82802, -0.98152, -1.15300, -1.26448, -1.35081, -1.50201, -1.54614, -1.55219, -1.63682, -1.83748, -1.99365, -2.15808, -2.30521, -2.30731, -2.43864, -2.61501, -2.84076, -3.04261, -3.20452, -3.26538, -3.21855, -3.35200, -3.45615, -3.42633, -3.45182, -3.47119, -3.47880, -3.37275, -3.26372, -3.20022, -3.19081, -3.02846, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.68103, -0.56604, -0.53564, -0.48630, -0.49590, -0.60280, -0.91299, -1.24111, -1.44930, -1.64248, -1.70867, -1.65672, -1.48495, -1.42891, -1.52524, -1.56845, -1.70920, -1.82930, -1.81624, -1.66862, -1.50969, -1.35849, -1.16255, -0.89109, -0.57566, -0.20749, 0.08086, 0.30712, 0.51433, 0.56929, 0.62214, 0.69012, 0.75595, 0.85738, 0.91756, 0.99602, 0.92619, 0.88804, 0.77272, 0.66551, 0.71293, 0.75158, 0.84061, 0.89817, 0.94541, 0.80788, 0.54742, 0.41928, 0.28474, 0.15185, -0.01700, -0.04415, 0.02701, 0.12590, 0.12055, 0.16342, 0.32059, 0.46974, 0.57441, 0.68985, 0.88632, 0.90968, 0.78626, 0.69955, 0.54763, 0.22053, -0.21041, -0.43624, -0.63548, -0.74285, -0.80713, -0.93653, -1.01022, -1.11890, -1.23837, -1.39690, -1.53241, -1.69153, -1.78602, -1.69492, -1.67134, -1.71390, -1.81908, -1.96849, -2.11985, -2.15484, -2.17148, -2.15774, -2.07387, -1.92872, -1.81358, -1.82618, -1.71305, -1.53766, -1.35614, -1.10465, -0.95451, -0.88434, -0.93571, -0.84971, -0.78792, -0.72858, -0.64277, +-0.52066, -0.25215, -0.06181, -0.01104, 0.03467, -0.05266, -0.08574, -0.01317, 0.10146, 0.27521, 0.40521, 0.37456, 0.29117, 0.42897, 0.56010, 0.42952, 0.28945, 0.41506, 0.43065, 0.21009, -0.00895, -0.04354, -0.15789, -0.30864, -0.37111, -0.55981, -0.71698, -0.87656, -1.13344, -1.39769, -1.60673, -1.64958, -1.63218, -1.58200, -1.62996, -1.81838, -1.83518, -1.80795, -1.75101, -1.64520, -1.58513, -1.42556, -1.25581, -1.25832, -1.29319, -1.09064, -0.90792, -0.94950, -1.06035, -0.99130, -0.90874, -0.96263, -1.06045, -1.14096, -1.18277, -1.18133, -1.07830, -1.15814, -1.28471, -1.38287, -1.55290, -1.72611, -1.84253, -1.85296, -1.99077, -2.12830, -2.18059, -2.27507, -2.11514, -1.86845, -1.67054, -1.41985, -1.23585, -0.99965, -0.78558, -0.77514, -0.80935, -0.60585, -0.45810, -0.57272, -0.71252, -0.66411, -0.66634, -0.81573, -0.88066, -0.79307, -0.62746, -0.55352, -0.39614, -0.41787, -0.49947, -0.42875, -0.37409, -0.36402, -0.43623, -0.52550, -0.57321, -0.51292, -0.37914, -0.39921, -0.33339, -0.19046, -0.18111, -0.16237, -0.11060, 0.04915, 0.17494, 0.12610, -0.06001, -0.06472, 0.02682, -0.04041, -0.25456, -0.42743, -0.49381, -0.62533, -0.73236, -0.82203, -0.90034, -1.08015, -1.12893, -1.24689, -1.34803, -1.31664, -1.29086, -1.28091, -1.25853, -1.24914, -1.19859, -1.16556, -1.15423, -1.34102, -1.47465, -1.45402, -1.54051, -1.63996, -1.71132, -1.68170, -1.72330, -1.88243, -2.02420, -1.94626, -1.83594, -1.87610, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.83010, -2.99352, -3.32592, -3.56252, -3.66437, -3.65069, -3.62652, -3.67381, -3.72392, -3.68004, -3.55038, -3.53791, -3.41761, -3.09914, -2.91125, -2.71278, -2.53741, -2.29186, -2.01017, -1.80110, -1.77212, -1.71998, -1.50057, -1.37307, -1.42430, -1.46697, -1.38890, -1.38283, -1.33886, -1.24132, -1.05344, -1.02273, -0.98776, -1.03918, -1.23723, -1.37238, -1.32427, -1.21044, -1.10361, -1.05861, -1.00056, -0.87727, -0.68380, -0.64209, -0.55904, -0.34207, -0.36307, -0.46875, -0.50408, -0.54904, -0.66917, -0.84343, -1.07303, -1.21694, -1.24176, -1.44213, -1.86969, -2.30362, -2.49373, -2.57288, -2.58743, -2.58685, -2.55843, -2.64098, -2.61951, -2.56977, -2.74021, -2.96817, -3.07837, -3.09915, -3.16374, -3.27722, -3.29952, -3.22953, -3.12756, -3.13655, -3.23489, -3.11304, -3.01204, -2.85891, -2.73381, -2.70523, -2.67153, -2.63817, -2.70846, -2.75725, -2.64663, -2.53338, -2.52732, -2.47023, -2.21769, -2.04483, -1.98914, -1.93350, -1.80474, -1.72451, -1.47033, -1.09462, -0.89497, -0.74659, -0.53827, -0.34620, -0.31121, -0.45647, -0.58416, -0.72090, -0.88228, -1.09926, -1.23965, -1.23744, -1.34739, -1.51066, -1.54865, -1.59290, -1.61953, -1.71109, -1.92851, -2.19639, -2.25561, -2.23440, -2.38553, -2.59036, -2.72254, -2.85017, -2.98173, -3.01877, -3.05112, -3.23023, -3.37878, -3.31224, -3.43082, -3.54044, -3.46031, -3.30929, -3.25287, -3.25758, -3.22445, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.48277, -0.38441, -0.39120, -0.34177, -0.41754, -0.76879, -1.19679, -1.41772, -1.53384, -1.55388, -1.49744, -1.44476, -1.45405, -1.55743, -1.50284, -1.64700, -1.78139, -1.66957, -1.48870, -1.41016, -1.33430, -1.09705, -0.79778, -0.50372, -0.20431, -0.00749, 0.28001, 0.51412, 0.56287, 0.63356, 0.59915, 0.64402, 0.79809, 0.87528, 0.79487, 0.73535, 0.70315, 0.59754, 0.52695, 0.57544, 0.61339, 0.59525, 0.66074, 0.66597, 0.57470, 0.41777, 0.42461, 0.24901, 0.00659, -0.11363, -0.07858, 0.01789, 0.11871, 0.15603, 0.17523, 0.25803, 0.39669, 0.44375, 0.57329, 0.72007, 0.72716, 0.75222, 0.66888, 0.51857, 0.31245, 0.01230, -0.34249, -0.54597, -0.60212, -0.64626, -0.79354, -0.91136, -1.02022, -1.20994, -1.32789, -1.49123, -1.58502, -1.63543, -1.50002, -1.57473, -1.73773, -1.74530, -1.78179, -1.92359, -2.07530, -2.15205, -2.11908, -2.01884, -1.86499, -1.84233, -1.82656, -1.65038, -1.47375, -1.20899, -1.02611, -0.94328, -0.84546, -0.73988, -0.72766, -0.73750, -0.75513, -0.79499, +-0.50820, -0.26887, -0.05905, 0.08217, 0.16480, 0.04909, -0.06507, -0.10017, -0.02501, 0.11512, 0.26353, 0.24173, 0.06107, 0.10170, 0.21198, 0.13597, 0.06520, 0.22111, 0.25794, 0.12249, 0.01962, 0.02063, -0.00246, -0.09284, -0.21426, -0.42403, -0.53162, -0.66815, -0.98069, -1.29279, -1.51910, -1.54637, -1.56331, -1.60267, -1.67654, -1.79187, -1.79230, -1.79336, -1.75375, -1.70133, -1.62850, -1.46909, -1.28442, -1.23787, -1.32903, -1.22853, -1.09030, -1.10740, -1.17473, -1.06604, -0.97071, -0.99107, -1.03686, -1.13630, -1.17677, -1.13632, -1.10526, -1.26854, -1.42262, -1.53100, -1.74427, -1.91105, -1.99767, -1.90233, -1.88379, -1.96966, -2.01983, -2.09337, -2.00084, -1.88173, -1.73152, -1.56737, -1.39644, -1.11078, -0.83553, -0.69067, -0.72410, -0.63786, -0.56396, -0.66415, -0.76100, -0.67273, -0.67181, -0.81000, -0.85280, -0.78716, -0.63591, -0.52230, -0.43845, -0.53188, -0.57310, -0.41423, -0.36815, -0.36134, -0.41970, -0.45783, -0.43512, -0.36392, -0.24807, -0.24301, -0.21902, -0.22356, -0.26051, -0.30856, -0.25991, -0.05946, 0.07439, 0.12386, -0.05656, -0.14961, -0.09382, -0.12277, -0.24007, -0.28972, -0.30599, -0.38881, -0.46035, -0.57856, -0.70368, -0.84127, -0.93776, -1.12433, -1.23137, -1.10310, -1.00861, -0.99156, -1.01293, -1.04770, -1.01319, -1.01449, -1.03903, -1.22752, -1.39321, -1.49112, -1.60115, -1.72904, -1.78589, -1.70204, -1.72810, -1.75837, -1.85428, -1.85600, -1.79422, -1.85126, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.63730, -2.85366, -3.18091, -3.35519, -3.47385, -3.51201, -3.55773, -3.65412, -3.71075, -3.67677, -3.52299, -3.41105, -3.20396, -2.94443, -2.78414, -2.64275, -2.50474, -2.23966, -1.98114, -1.69608, -1.61917, -1.62630, -1.45491, -1.31717, -1.31924, -1.28413, -1.18345, -1.15560, -1.06519, -0.93777, -0.78313, -0.64795, -0.56772, -0.71447, -0.99452, -1.14196, -1.12127, -1.01740, -0.90232, -0.86925, -0.79981, -0.69080, -0.54416, -0.49610, -0.40725, -0.30273, -0.37492, -0.47814, -0.46679, -0.40804, -0.49687, -0.62570, -0.86758, -1.13491, -1.27966, -1.54272, -1.96541, -2.32059, -2.42156, -2.42721, -2.39908, -2.38845, -2.41968, -2.46449, -2.44458, -2.49027, -2.73463, -2.95345, -3.08153, -3.13521, -3.17942, -3.25560, -3.21105, -3.11761, -3.06200, -3.08435, -3.16904, -3.13211, -3.10083, -2.98025, -2.84543, -2.74047, -2.67879, -2.58359, -2.61538, -2.74065, -2.71177, -2.60440, -2.52420, -2.37548, -2.08311, -1.84480, -1.69907, -1.62911, -1.60061, -1.55268, -1.30596, -0.99601, -0.83831, -0.69670, -0.50313, -0.34465, -0.29859, -0.41911, -0.51646, -0.65640, -0.86000, -1.05410, -1.12988, -1.16340, -1.34411, -1.55509, -1.63568, -1.64738, -1.66567, -1.74089, -1.91741, -2.22064, -2.31601, -2.27822, -2.36991, -2.50122, -2.57823, -2.68380, -2.78266, -2.80768, -2.91776, -3.10460, -3.23425, -3.24548, -3.42477, -3.54309, -3.46127, -3.36431, -3.33626, -3.33873, -3.25271, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.41833, -0.44226, -0.46421, -0.69209, -1.06077, -1.26711, -1.42202, -1.43572, -1.36095, -1.39273, -1.48923, -1.58778, -1.58053, -1.72836, -1.78191, -1.57856, -1.37881, -1.25677, -1.12650, -0.85074, -0.54579, -0.32528, -0.09892, 0.10527, 0.36239, 0.49249, 0.51511, 0.53336, 0.51969, 0.61913, 0.75989, 0.86640, 0.71431, 0.52133, 0.44733, 0.38882, 0.36678, 0.44421, 0.46122, 0.43938, 0.52304, 0.50356, 0.38772, 0.30461, 0.28401, 0.05682, -0.17472, -0.23668, -0.18928, -0.06681, 0.07000, 0.14833, 0.17409, 0.18573, 0.25831, 0.30777, 0.41094, 0.44301, 0.44478, 0.46963, 0.43698, 0.37611, 0.27273, 0.15756, -0.16772, -0.47146, -0.59338, -0.62902, -0.74425, -0.84542, -1.01567, -1.22514, -1.32068, -1.47708, -1.58296, -1.56082, -1.45136, -1.57133, -1.69444, -1.60972, -1.61749, -1.75197, -1.91032, -1.98012, -1.93281, -1.87795, -1.78385, -1.74329, -1.68484, -1.55019, -1.37357, -1.15798, -0.99772, -0.88464, -0.80693, -0.63798, -0.65941, -0.82413, -0.93864, -1.00528, +-0.53481, -0.35086, -0.20766, 0.00463, 0.22771, 0.17520, 0.07049, -0.01134, -0.03810, -0.03647, 0.00327, -0.04945, -0.12399, -0.10763, -0.08107, -0.09194, -0.19443, -0.10700, -0.08691, -0.09681, -0.00396, -0.03129, -0.06282, -0.13472, -0.23724, -0.37552, -0.45141, -0.60977, -0.93369, -1.20924, -1.47448, -1.52221, -1.52477, -1.63323, -1.78152, -1.85938, -1.79100, -1.79999, -1.77245, -1.69838, -1.59598, -1.46232, -1.34864, -1.33672, -1.38018, -1.34256, -1.35084, -1.29563, -1.34354, -1.27813, -1.20078, -1.19906, -1.14029, -1.28722, -1.37919, -1.31224, -1.26338, -1.36091, -1.53029, -1.70621, -1.97967, -2.10503, -2.18308, -2.01667, -1.79927, -1.79278, -1.87484, -1.96376, -1.90482, -1.85006, -1.72364, -1.54206, -1.34427, -1.06639, -0.83804, -0.70881, -0.69538, -0.59902, -0.63474, -0.62543, -0.67374, -0.67429, -0.72311, -0.87707, -0.82051, -0.77111, -0.70022, -0.57973, -0.52613, -0.55655, -0.57740, -0.43866, -0.43666, -0.37308, -0.39909, -0.41718, -0.31199, -0.25862, -0.24716, -0.26453, -0.19464, -0.19627, -0.24336, -0.27880, -0.25669, -0.13947, -0.10758, -0.07150, -0.17581, -0.16756, -0.19730, -0.16323, -0.20266, -0.26540, -0.25450, -0.31098, -0.25382, -0.35227, -0.57848, -0.72597, -0.89369, -1.04975, -1.16690, -1.03287, -0.91129, -0.82078, -0.85283, -0.96523, -0.95820, -0.98619, -1.09180, -1.31198, -1.41640, -1.49945, -1.62992, -1.75409, -1.83388, -1.77512, -1.82993, -1.81273, -1.83003, -1.73484, -1.78156, -1.83317, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.56134, -2.62863, -2.73602, -2.98370, -3.13699, -3.32449, -3.41833, -3.52812, -3.68219, -3.68551, -3.58564, -3.44693, -3.33051, -3.04905, -2.78535, -2.65412, -2.48608, -2.35695, -2.11637, -1.94136, -1.72115, -1.62921, -1.50500, -1.39068, -1.22026, -1.08791, -1.04628, -0.94669, -0.95694, -0.81872, -0.63606, -0.57870, -0.40876, -0.29601, -0.38347, -0.66507, -0.87296, -0.98162, -0.90292, -0.76542, -0.74547, -0.61098, -0.46063, -0.40773, -0.48336, -0.41211, -0.30661, -0.36056, -0.35155, -0.27535, -0.19197, -0.33455, -0.53757, -0.80132, -0.97989, -1.22012, -1.53927, -1.87288, -2.21477, -2.28971, -2.30108, -2.21964, -2.11538, -2.22545, -2.29622, -2.33604, -2.42934, -2.69894, -2.92040, -3.08942, -3.13560, -3.12710, -3.20796, -3.13704, -3.03193, -3.06371, -3.17249, -3.22764, -3.14632, -3.12359, -2.98564, -2.83152, -2.69690, -2.65519, -2.58539, -2.58319, -2.58116, -2.57915, -2.52671, -2.35326, -2.20334, -1.94721, -1.71393, -1.47993, -1.30863, -1.39660, -1.46202, -1.31874, -1.04280, -0.85936, -0.71120, -0.56241, -0.44257, -0.37613, -0.54572, -0.64637, -0.73476, -0.94009, -1.14136, -1.17492, -1.17264, -1.37382, -1.58516, -1.65558, -1.66194, -1.73286, -1.87578, -2.05309, -2.23308, -2.29755, -2.31802, -2.30790, -2.39104, -2.47888, -2.61871, -2.73791, -2.73773, -2.94665, -3.15876, -3.24586, -3.23689, -3.36144, -3.49527, -3.52105, -3.54878, -3.52944, -3.55264, -3.43072, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.49092, -0.51232, -0.54849, -0.83687, -1.09451, -1.33540, -1.42597, -1.30011, -1.41039, -1.59200, -1.67730, -1.68898, -1.76032, -1.79164, -1.60688, -1.41964, -1.17470, -0.96750, -0.68827, -0.35689, -0.19779, -0.08917, 0.08307, 0.37673, 0.50895, 0.53769, 0.58605, 0.58632, 0.65384, 0.69160, 0.72974, 0.62454, 0.50262, 0.33262, 0.32565, 0.31012, 0.31126, 0.31269, 0.28382, 0.45742, 0.42112, 0.21643, 0.11310, 0.00930, -0.16716, -0.37867, -0.44650, -0.42115, -0.24453, -0.10439, -0.05310, 0.01044, 0.00565, 0.00250, 0.03233, 0.18024, 0.22251, 0.22001, 0.28681, 0.29291, 0.26096, 0.18808, 0.15191, -0.06721, -0.24881, -0.50437, -0.56357, -0.65441, -0.84053, -1.04525, -1.29831, -1.34719, -1.51536, -1.74809, -1.73796, -1.66927, -1.67134, -1.70701, -1.61231, -1.65858, -1.75849, -1.89768, -1.98117, -1.88205, -1.81456, -1.79674, -1.79747, -1.66939, -1.48769, -1.31788, -1.07894, -0.89628, -0.77506, -0.77546, -0.70172, -0.77482, -0.86346, -1.06245, -1.11076, +-0.64400, -0.51032, -0.31565, -0.09391, 0.20873, 0.28053, 0.19954, 0.09484, -0.07190, -0.24225, -0.25160, -0.27893, -0.27839, -0.23327, -0.22479, -0.24968, -0.41807, -0.45669, -0.41394, -0.29477, -0.22399, -0.25148, -0.22232, -0.32142, -0.39484, -0.44296, -0.46892, -0.57510, -0.78909, -1.02119, -1.33536, -1.47585, -1.62722, -1.80500, -1.85933, -1.90862, -1.85531, -1.84966, -1.85194, -1.78955, -1.72626, -1.64326, -1.48518, -1.39428, -1.42168, -1.45387, -1.55548, -1.52813, -1.57772, -1.55587, -1.43160, -1.32826, -1.35670, -1.55995, -1.59021, -1.50971, -1.36523, -1.33814, -1.53253, -1.79095, -2.04031, -2.10923, -2.17696, -1.98785, -1.75827, -1.72576, -1.70411, -1.71860, -1.68130, -1.62587, -1.55708, -1.41847, -1.22077, -1.00149, -0.74159, -0.54095, -0.57163, -0.55797, -0.66794, -0.65106, -0.66086, -0.72309, -0.78371, -0.85315, -0.87092, -0.89826, -0.73061, -0.57228, -0.50788, -0.46498, -0.51353, -0.47978, -0.47115, -0.31694, -0.26946, -0.25933, -0.22747, -0.32176, -0.31969, -0.29660, -0.21951, -0.12162, -0.13673, -0.18591, -0.22532, -0.28224, -0.30220, -0.17711, -0.23001, -0.18619, -0.20910, -0.17918, -0.19262, -0.26459, -0.23035, -0.12301, -0.03051, -0.21203, -0.42468, -0.62995, -0.86972, -0.98058, -1.10494, -1.03732, -0.85908, -0.65629, -0.67873, -0.77758, -0.85421, -1.06004, -1.20973, -1.38798, -1.44427, -1.42509, -1.52633, -1.69638, -1.89766, -2.02843, -2.11945, -1.96166, -1.88599, -1.76902, -1.83887, -1.93396, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.63832, -2.72540, -2.67775, -2.76777, -2.92175, -3.12651, -3.22896, -3.39428, -3.54711, -3.55568, -3.52637, -3.34243, -3.12856, -2.84080, -2.54510, -2.41456, -2.26407, -2.18781, -2.08215, -1.94977, -1.67029, -1.54020, -1.38135, -1.25345, -1.05012, -0.81758, -0.74589, -0.69145, -0.62986, -0.52120, -0.49203, -0.41885, -0.21852, -0.09258, -0.07469, -0.28166, -0.50341, -0.65959, -0.58379, -0.50241, -0.47449, -0.29631, -0.24127, -0.21362, -0.29539, -0.34044, -0.26163, -0.29410, -0.23280, -0.14877, -0.17916, -0.38669, -0.56302, -0.80187, -0.95206, -1.15187, -1.44350, -1.75022, -2.07304, -2.18439, -2.11583, -2.01252, -2.00168, -2.04048, -2.07914, -2.21314, -2.35340, -2.60942, -2.84642, -3.00385, -2.95081, -2.89945, -2.95341, -2.90412, -2.96117, -3.07040, -3.13807, -3.19768, -3.06029, -2.96419, -2.82278, -2.70027, -2.65267, -2.64378, -2.46598, -2.32522, -2.27424, -2.29856, -2.30835, -2.17254, -2.03975, -1.84662, -1.54979, -1.23767, -1.17580, -1.27763, -1.29840, -1.25883, -1.04612, -0.86750, -0.73056, -0.56215, -0.38450, -0.29699, -0.51598, -0.71143, -0.95306, -1.21376, -1.30958, -1.31379, -1.29541, -1.44964, -1.68495, -1.80684, -1.88476, -1.97394, -2.03339, -2.12628, -2.26705, -2.34602, -2.40973, -2.41506, -2.43226, -2.48843, -2.58809, -2.69891, -2.89942, -3.16957, -3.27277, -3.31337, -3.23262, -3.25022, -3.38231, -3.49322, -3.56306, -3.56586, -3.61772, -3.50784, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.53457, -0.74687, -0.99127, -1.18205, -1.24043, -1.28689, -1.53319, -1.62764, -1.65759, -1.64086, -1.60358, -1.65078, -1.57239, -1.38338, -1.06412, -0.79623, -0.51236, -0.27106, -0.24133, -0.14683, 0.02457, 0.32679, 0.59490, 0.66564, 0.66960, 0.58217, 0.48544, 0.46420, 0.54098, 0.51360, 0.47413, 0.30166, 0.24207, 0.18374, 0.15347, 0.19326, 0.30316, 0.43039, 0.30369, 0.16888, 0.03049, -0.15514, -0.28395, -0.48486, -0.60526, -0.54049, -0.29689, -0.18065, -0.15953, -0.16141, -0.26779, -0.20449, -0.08646, 0.04556, 0.14217, 0.12404, 0.15372, 0.13213, 0.01603, -0.00961, 0.11677, 0.00377, -0.08683, -0.32006, -0.46623, -0.63734, -0.91327, -1.10904, -1.21213, -1.31707, -1.62851, -1.87824, -1.94865, -1.96569, -1.88430, -1.83006, -1.76843, -1.79441, -1.82931, -1.98087, -2.06200, -1.95854, -1.93042, -1.87029, -1.82594, -1.72434, -1.50079, -1.34031, -1.13351, -0.92601, -0.85841, -0.89423, -0.81446, -0.92094, -0.98357, -1.15028, -1.18841, +-0.67230, -0.42781, -0.19489, -0.08000, 0.02965, 0.06272, 0.04493, -0.04454, -0.12684, -0.27862, -0.43529, -0.51128, -0.48482, -0.45851, -0.42614, -0.38531, -0.46617, -0.59952, -0.67056, -0.58968, -0.51569, -0.38345, -0.26134, -0.42330, -0.56031, -0.56217, -0.53919, -0.59373, -0.73575, -1.01696, -1.31237, -1.45988, -1.69680, -1.83213, -1.86070, -2.01274, -2.11658, -2.14586, -2.04875, -1.97045, -1.87471, -1.73860, -1.67207, -1.59151, -1.57045, -1.62142, -1.71877, -1.69192, -1.67889, -1.67323, -1.60986, -1.49565, -1.55007, -1.61296, -1.54282, -1.52368, -1.42846, -1.37352, -1.54645, -1.79198, -1.93791, -2.01117, -2.06349, -1.85966, -1.74133, -1.64546, -1.52043, -1.47941, -1.45616, -1.45448, -1.38842, -1.30780, -1.09253, -0.77024, -0.53672, -0.33177, -0.35965, -0.47768, -0.68098, -0.71539, -0.68067, -0.73359, -0.86278, -0.90523, -0.95106, -0.84952, -0.56395, -0.46168, -0.46948, -0.41365, -0.42214, -0.41965, -0.39451, -0.30805, -0.27709, -0.22300, -0.26850, -0.31040, -0.20783, -0.18874, -0.19712, -0.19031, -0.18459, -0.23332, -0.26628, -0.19668, -0.22614, -0.14262, -0.14559, -0.13483, -0.14797, -0.09732, -0.06015, -0.08161, -0.12414, 0.00441, 0.06294, -0.04093, -0.17401, -0.45408, -0.75776, -0.86918, -0.96894, -0.98056, -0.85461, -0.73003, -0.77356, -0.72924, -0.80265, -1.01461, -1.17408, -1.40518, -1.51384, -1.55263, -1.57465, -1.69268, -1.95893, -2.06932, -2.23675, -2.17536, -2.05041, -1.96543, -2.03094, -2.09954, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.54884, -2.71678, -2.66904, -2.65496, -2.79255, -2.96319, -3.08053, -3.24848, -3.30183, -3.33900, -3.33109, -3.11563, -2.88887, -2.63340, -2.37956, -2.18708, -2.00958, -1.98947, -1.81551, -1.67207, -1.46981, -1.30783, -1.17484, -1.05810, -0.82790, -0.56284, -0.42485, -0.47737, -0.43447, -0.33053, -0.23607, -0.03885, 0.10462, 0.07487, 0.03881, -0.05963, -0.16950, -0.24625, -0.23161, -0.29582, -0.24732, -0.06057, -0.00209, 0.11884, 0.07642, -0.08872, -0.18794, -0.27349, -0.21851, -0.20348, -0.19473, -0.37806, -0.63719, -0.86154, -1.02437, -1.22947, -1.47928, -1.73972, -1.91948, -2.05415, -1.99987, -1.92575, -1.89311, -1.78389, -1.81054, -2.06969, -2.28071, -2.44146, -2.63506, -2.76885, -2.74298, -2.79212, -2.79183, -2.70564, -2.75089, -2.77991, -2.81361, -2.92960, -2.87217, -2.73469, -2.53093, -2.45246, -2.35861, -2.28126, -2.15149, -1.99304, -1.97145, -2.07082, -2.09703, -1.94460, -1.73079, -1.62339, -1.46298, -1.26313, -1.23884, -1.17138, -1.04723, -1.07902, -1.01419, -0.87544, -0.74477, -0.54351, -0.34681, -0.31162, -0.49184, -0.72023, -1.07088, -1.33471, -1.42145, -1.49415, -1.57568, -1.71927, -1.89280, -2.06401, -2.12042, -2.11827, -2.21340, -2.29597, -2.39260, -2.49920, -2.57167, -2.58752, -2.52202, -2.59527, -2.77869, -2.93040, -3.15480, -3.22052, -3.17820, -3.26971, -3.27864, -3.26512, -3.34814, -3.42474, -3.44211, -3.53668, -3.61591, -3.49644, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.17663, -1.20468, -1.34635, -1.51069, -1.48056, -1.52047, -1.54607, -1.42659, -1.40254, -1.36874, -1.20131, -1.01582, 0.00000, 0.00000, 0.00000, 0.00000, -0.05557, 0.05306, 0.25686, 0.48566, 0.60281, 0.56134, 0.43954, 0.40873, 0.31286, 0.30968, 0.32162, 0.25265, 0.07857, 0.02607, 0.06185, 0.14141, 0.14451, 0.26003, 0.29758, 0.26813, 0.27293, 0.11354, -0.13267, -0.27363, -0.44505, -0.58512, -0.48380, -0.30770, -0.25209, -0.20008, -0.26222, -0.31847, -0.18065, -0.09650, -0.07452, -0.05870, -0.00912, 0.06266, 0.03216, 0.00703, -0.09397, -0.07648, -0.12975, -0.19101, -0.33421, -0.47666, -0.69144, -0.97682, -1.25712, -1.32942, -1.48230, -1.66698, -1.78236, -1.95066, -2.12958, -2.15014, -2.07152, -2.02098, -1.99807, -2.05084, -2.24173, -2.25674, -2.17075, -2.07894, -1.93247, -1.88799, -1.84319, -1.69681, -1.51077, -1.30721, -1.13519, -0.97227, -1.01770, -1.02504, -1.05742, -1.08406, -1.22529, -1.26462, +-0.67009, -0.31511, -0.16500, -0.16105, -0.16283, -0.21753, -0.23356, -0.26302, -0.24253, -0.35764, -0.62116, -0.80233, -0.75611, -0.67372, -0.60975, -0.50009, -0.53091, -0.62837, -0.72225, -0.74312, -0.62834, -0.41492, -0.33334, -0.49027, -0.62851, -0.66653, -0.59976, -0.58949, -0.78009, -1.05617, -1.29795, -1.46130, -1.63041, -1.74336, -1.93490, -2.26144, -2.41829, -2.44004, -2.26351, -2.10578, -1.96239, -1.84805, -1.91765, -1.93715, -1.84995, -1.75250, -1.77979, -1.76168, -1.77349, -1.75384, -1.68090, -1.63359, -1.64581, -1.61455, -1.58840, -1.62463, -1.58075, -1.60473, -1.69675, -1.75043, -1.81513, -1.84807, -1.87433, -1.77613, -1.68355, -1.54842, -1.45423, -1.46175, -1.37812, -1.35867, -1.29362, -1.20031, -0.96921, -0.61286, -0.42156, -0.26379, -0.23224, -0.29050, -0.51952, -0.62261, -0.63440, -0.67662, -0.75004, -0.81277, -0.81283, -0.61295, -0.41505, -0.44395, -0.46504, -0.43448, -0.33692, -0.15251, -0.14955, -0.17399, -0.20363, -0.28113, -0.29650, -0.20058, -0.06341, -0.14690, -0.19673, -0.27768, -0.34031, -0.35752, -0.31529, -0.10320, -0.10199, -0.11889, -0.10060, 0.00525, 0.02832, 0.08112, 0.11013, 0.08523, 0.06704, 0.10490, 0.09282, 0.03112, -0.13562, -0.47980, -0.71166, -0.83662, -0.92623, -0.85705, -0.83824, -0.85932, -0.88799, -0.89566, -0.90815, -1.01774, -1.21765, -1.61536, -1.77844, -1.83532, -1.83107, -1.83159, -2.01169, -2.06005, -2.27010, -2.36810, -2.25988, -2.07939, -2.07434, -2.09685, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.44074, -2.58204, -2.59292, -2.60097, -2.59693, -2.71366, -2.84552, -2.90868, -3.01453, -3.07943, -3.05795, -2.92017, -2.83581, -2.57954, -2.24971, -2.00502, -1.78440, -1.72736, -1.48374, -1.33705, -1.24990, -1.10910, -0.89815, -0.74148, -0.53226, -0.34353, -0.28031, -0.31021, -0.28233, -0.14419, 0.08339, 0.29565, 0.28735, 0.17350, 0.07085, 0.00107, 0.08926, 0.11360, 0.03508, -0.05552, -0.12678, 0.00143, 0.14536, 0.31626, 0.23290, 0.05050, -0.07851, -0.21976, -0.20040, -0.19199, -0.13820, -0.30176, -0.65077, -0.91310, -1.02067, -1.22340, -1.48954, -1.72517, -1.84490, -1.83342, -1.73836, -1.69799, -1.61703, -1.52543, -1.67036, -1.94012, -2.12829, -2.23782, -2.30346, -2.39614, -2.52850, -2.64362, -2.70031, -2.61333, -2.49065, -2.43463, -2.54964, -2.70831, -2.63539, -2.47921, -2.23556, -2.10683, -1.94240, -1.83210, -1.81746, -1.78581, -1.76421, -1.82585, -1.82689, -1.64188, -1.45345, -1.35860, -1.30581, -1.28269, -1.24534, -1.11622, -1.03021, -1.06044, -1.03983, -0.96946, -0.80291, -0.54814, -0.43649, -0.40112, -0.55012, -0.82024, -1.11904, -1.37551, -1.58877, -1.75978, -1.84052, -1.95345, -2.07253, -2.19296, -2.21020, -2.22637, -2.42635, -2.57365, -2.56993, -2.52804, -2.55041, -2.58307, -2.59127, -2.71069, -2.91976, -3.13325, -3.24551, -3.15353, -3.13777, -3.28060, -3.35742, -3.41181, -3.41535, -3.32619, -3.31990, -3.44406, -3.56135, -3.54853, -3.24105, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.20994, 0.34710, 0.40622, 0.38179, 0.32657, 0.40161, 0.28339, 0.15460, 0.13294, 0.10228, -0.04457, -0.06120, 0.06011, 0.22621, 0.27828, 0.28973, 0.25716, 0.29211, 0.27977, 0.09893, -0.07499, -0.25315, -0.40798, -0.42468, -0.35459, -0.28257, -0.24024, -0.30118, -0.34875, -0.30674, -0.22301, -0.32296, -0.34800, -0.32874, -0.21142, -0.01642, 0.02155, 0.05532, -0.13597, -0.31691, -0.38875, -0.35287, -0.42597, -0.55892, -0.80733, -1.13396, -1.41756, -1.57092, -1.73362, -1.75572, -1.80831, -2.05926, -2.26417, -2.39661, -2.35389, -2.17673, -2.13054, -2.23093, -2.37165, -2.46245, -2.39092, -2.24124, -2.11164, -2.16579, -2.07891, -1.86292, -1.64861, -1.41435, -1.25747, -1.07191, -1.12243, -1.20899, -1.16268, -1.03776, -1.12985, -1.21472, +-0.63582, -0.31370, -0.11012, -0.09424, -0.20451, -0.36053, -0.45248, -0.45863, -0.40493, -0.54523, -0.75384, -0.89879, -0.94518, -0.89312, -0.82478, -0.68304, -0.67629, -0.69040, -0.67777, -0.76822, -0.75553, -0.58214, -0.48458, -0.53231, -0.60441, -0.66816, -0.68798, -0.74146, -0.90599, -1.03816, -1.13917, -1.27300, -1.44918, -1.70069, -1.97246, -2.31977, -2.49119, -2.47923, -2.30609, -2.15939, -2.04192, -2.07527, -2.18806, -2.16957, -2.10122, -1.93475, -1.87232, -1.88761, -1.94390, -1.86829, -1.67133, -1.66769, -1.75204, -1.75530, -1.74353, -1.74259, -1.68660, -1.71473, -1.78362, -1.82193, -1.80461, -1.69946, -1.60800, -1.53657, -1.52441, -1.55087, -1.43272, -1.34665, -1.21047, -1.16488, -1.12912, -1.06943, -0.85880, -0.60812, -0.40392, -0.11776, -0.04651, -0.12968, -0.32958, -0.49612, -0.58884, -0.64279, -0.57907, -0.61118, -0.65838, -0.50974, -0.37328, -0.37929, -0.31951, -0.23215, -0.08131, 0.06988, 0.06185, 0.01415, -0.02450, -0.15136, -0.12819, -0.07684, 0.09611, 0.04754, -0.05997, -0.24605, -0.41208, -0.47820, -0.36951, -0.13423, -0.05385, 0.01752, 0.03822, 0.12662, 0.21133, 0.23684, 0.22980, 0.16943, 0.22960, 0.21478, 0.06592, -0.06396, -0.22315, -0.49670, -0.62637, -0.71437, -0.81392, -0.86891, -0.98374, -1.06991, -1.01042, -1.00362, -0.95216, -1.14483, -1.36520, -1.72483, -1.93740, -2.04028, -2.05384, -2.01817, -2.07016, -2.14753, -2.33914, -2.36743, -2.29043, -2.19004, -2.11690, -2.11340, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.27833, -2.32847, -2.34375, -2.39781, -2.43819, -2.50175, -2.53656, -2.43296, -2.53476, -2.62197, -2.79238, -2.77895, -2.66772, -2.38583, -1.98961, -1.70988, -1.54371, -1.43869, -1.21819, -1.07229, -0.90402, -0.75267, -0.62700, -0.45530, -0.30322, -0.19704, -0.20694, -0.13973, -0.04333, 0.05741, 0.24343, 0.44646, 0.41221, 0.26742, 0.16193, 0.12506, 0.20850, 0.26370, 0.17569, 0.16945, 0.07577, 0.15614, 0.18486, 0.30464, 0.35531, 0.25437, 0.12001, -0.03531, -0.10649, -0.11687, -0.12871, -0.30759, -0.55340, -0.79353, -1.00358, -1.22983, -1.49599, -1.70349, -1.79538, -1.61516, -1.39779, -1.41146, -1.45712, -1.44465, -1.56696, -1.71598, -1.76796, -1.82254, -1.94691, -2.12436, -2.37880, -2.47144, -2.51271, -2.39424, -2.24802, -2.21768, -2.27025, -2.36312, -2.25337, -2.07128, -1.86151, -1.70178, -1.55504, -1.49213, -1.45262, -1.43100, -1.49077, -1.54240, -1.53394, -1.37659, -1.26733, -1.14443, -1.08640, -1.25201, -1.34769, -1.23539, -1.11420, -1.05180, -0.99080, -0.94449, -0.87141, -0.73237, -0.69809, -0.58080, -0.59985, -0.82435, -1.14819, -1.49117, -1.69331, -1.85881, -1.95714, -2.02956, -2.13371, -2.23410, -2.27221, -2.38681, -2.54108, -2.60713, -2.60319, -2.52140, -2.51865, -2.61176, -2.76594, -2.92142, -3.02274, -3.24046, -3.33824, -3.20896, -3.17223, -3.27193, -3.35416, -3.43408, -3.45701, -3.37529, -3.31600, -3.35534, -3.42383, -3.44250, -3.15660, -2.80963, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.34106, 0.35898, 0.32617, 0.34652, 0.39666, 0.30579, 0.22586, 0.09270, -0.03698, -0.12012, -0.10569, 0.07395, 0.28444, 0.44709, 0.38756, 0.20221, 0.17395, 0.18076, 0.11944, 0.08438, -0.06880, -0.24974, -0.34877, -0.31711, -0.26107, -0.16636, -0.28248, -0.34537, -0.42049, -0.37787, -0.44447, -0.45786, -0.40968, -0.25538, -0.04063, 0.07002, 0.05029, -0.20466, -0.41449, -0.54318, -0.57695, -0.59577, -0.75786, -1.05296, -1.41581, -1.62292, -1.81001, -2.06583, -2.08803, -2.04725, -2.21747, -2.36442, -2.49413, -2.49502, -2.43106, -2.41300, -2.46367, -2.46183, -2.55888, -2.50342, -2.47661, -2.34519, -2.27769, -2.10037, -1.81954, -1.58456, -1.40808, -1.28986, -1.20428, -1.23584, -1.17929, -1.04745, -0.96352, -1.03350, -1.21327, +-0.56283, -0.32090, -0.09600, -0.04150, -0.17432, -0.37976, -0.50463, -0.52776, -0.50487, -0.62295, -0.78919, -0.86985, -0.95474, -1.00627, -0.91080, -0.72799, -0.64115, -0.64799, -0.70845, -0.78430, -0.79581, -0.73220, -0.64434, -0.61671, -0.63764, -0.73303, -0.87140, -0.93715, -0.91614, -0.91062, -0.99304, -1.11894, -1.29821, -1.62277, -1.94630, -2.24035, -2.36002, -2.30226, -2.20930, -2.17300, -2.15968, -2.24275, -2.34284, -2.31511, -2.27414, -2.14647, -1.99117, -1.92944, -1.95875, -1.84826, -1.72358, -1.75783, -1.82149, -1.87807, -1.90681, -1.90360, -1.81581, -1.74310, -1.79456, -1.88009, -1.80331, -1.61381, -1.48142, -1.31235, -1.31925, -1.42027, -1.32428, -1.18924, -1.04220, -0.96405, -0.93382, -0.83929, -0.66999, -0.48998, -0.32169, -0.02364, 0.08001, -0.06382, -0.16841, -0.19837, -0.32401, -0.43222, -0.47018, -0.52382, -0.55545, -0.48330, -0.38624, -0.27705, -0.09475, 0.11028, 0.21993, 0.21570, 0.24339, 0.22599, 0.11695, 0.08321, 0.16741, 0.21217, 0.27420, 0.16916, -0.01135, -0.20554, -0.38685, -0.45580, -0.36846, -0.13191, -0.00980, 0.07673, 0.10401, 0.14181, 0.28683, 0.44218, 0.45019, 0.38729, 0.31052, 0.14868, -0.00357, -0.09626, -0.22134, -0.43765, -0.59498, -0.65828, -0.77515, -0.95668, -1.11348, -1.16452, -1.13696, -1.06511, -0.99112, -1.20342, -1.45427, -1.73181, -1.97500, -2.12215, -2.21566, -2.16876, -2.16661, -2.22326, -2.30850, -2.27223, -2.24450, -2.30879, -2.23612, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.12445, -2.13063, -2.10247, -2.15835, -2.23133, -2.18895, -2.05502, -1.99896, -2.09432, -2.19306, -2.40738, -2.45862, -2.34090, -2.09614, -1.69139, -1.44117, -1.30459, -1.21643, -1.00041, -0.80630, -0.60449, -0.43683, -0.42290, -0.30592, -0.07282, 0.05196, 0.13616, 0.18214, 0.14130, 0.16568, 0.31233, 0.48774, 0.49541, 0.33340, 0.27353, 0.26790, 0.27069, 0.32287, 0.32487, 0.32137, 0.29226, 0.35864, 0.28862, 0.28588, 0.37749, 0.32748, 0.22511, 0.11591, 0.05955, -0.02051, -0.13075, -0.28555, -0.47574, -0.73360, -1.07748, -1.33704, -1.39453, -1.48036, -1.47443, -1.35015, -1.28172, -1.30225, -1.39001, -1.41617, -1.41402, -1.41739, -1.33107, -1.40240, -1.67588, -1.94920, -2.15174, -2.24523, -2.28735, -2.15259, -2.02186, -2.04154, -2.06548, -2.10220, -1.92697, -1.70813, -1.48348, -1.31125, -1.21161, -1.15991, -1.13011, -1.08234, -1.14625, -1.21755, -1.15763, -1.05708, -0.97699, -0.89331, -0.97282, -1.22353, -1.35083, -1.27769, -1.12733, -1.02705, -0.92810, -0.85881, -0.86527, -0.85875, -0.84970, -0.76878, -0.75727, -0.88712, -1.20064, -1.53295, -1.71503, -1.91452, -2.05843, -2.08853, -2.13606, -2.23663, -2.33628, -2.43092, -2.47930, -2.47799, -2.50778, -2.55858, -2.54992, -2.61944, -2.83079, -3.00519, -3.13863, -3.30525, -3.34937, -3.29182, -3.26001, -3.31420, -3.32989, -3.34404, -3.41822, -3.41948, -3.29351, -3.27962, -3.36043, -3.32404, -3.05143, -2.77999, -2.42817, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.34034, 0.43867, 0.48174, 0.50337, 0.48775, 0.37670, 0.27562, 0.05744, -0.15445, -0.12472, 0.07485, 0.27547, 0.44715, 0.48828, 0.32515, 0.16072, 0.15188, 0.19073, 0.22512, 0.23864, 0.12546, -0.11403, -0.35292, -0.33333, -0.25102, -0.22158, -0.31162, -0.41323, -0.55245, -0.56175, -0.52735, -0.46662, -0.33884, -0.21200, -0.03220, 0.07956, 0.07372, -0.16324, -0.42675, -0.61241, -0.77254, -0.80340, -0.88053, -1.20018, -1.50025, -1.74502, -2.06318, -2.37313, -2.43092, -2.35110, -2.42160, -2.52430, -2.54268, -2.57242, -2.71059, -2.74343, -2.67622, -2.65711, -2.72072, -2.68635, -2.63830, -2.44265, -2.23138, -2.00494, -1.71180, -1.48748, -1.32023, -1.26974, -1.19596, -1.12927, -0.99260, -0.87220, -0.95940, -1.08057, -1.17783, +-0.56830, -0.43659, -0.24641, -0.14531, -0.20346, -0.37549, -0.49096, -0.54172, -0.59948, -0.66187, -0.77998, -0.79131, -0.74564, -0.76964, -0.75674, -0.72690, -0.65298, -0.71872, -0.79782, -0.72079, -0.70297, -0.75736, -0.76521, -0.74262, -0.75912, -0.93158, -1.08129, -1.01215, -0.88239, -0.88805, -1.07336, -1.22594, -1.34303, -1.66444, -1.97459, -2.16607, -2.25672, -2.22938, -2.27389, -2.34219, -2.42368, -2.40217, -2.38644, -2.35527, -2.27116, -2.13130, -2.02245, -2.03611, -2.06188, -1.98080, -1.91364, -1.82068, -1.80707, -1.91101, -2.03768, -2.08772, -1.99497, -1.90886, -1.91117, -1.87319, -1.79335, -1.65532, -1.57445, -1.30926, -1.17381, -1.22507, -1.19923, -1.06725, -0.99236, -0.92493, -0.89665, -0.69815, -0.52732, -0.30837, -0.14627, 0.06956, 0.19833, 0.12454, 0.05576, 0.00538, -0.14208, -0.30300, -0.45504, -0.39976, -0.39479, -0.41124, -0.40505, -0.26809, -0.00752, 0.22484, 0.29568, 0.35486, 0.42424, 0.38709, 0.21049, 0.24346, 0.38355, 0.39997, 0.23701, 0.05920, -0.17197, -0.27064, -0.37580, -0.37891, -0.36003, -0.14109, -0.01087, 0.04488, 0.08950, 0.18943, 0.34706, 0.46235, 0.48713, 0.45437, 0.24380, 0.12567, 0.02423, -0.05639, -0.21675, -0.47743, -0.70297, -0.82094, -0.95786, -0.98574, -1.03490, -1.06422, -1.14763, -1.10798, -1.05015, -1.23296, -1.55741, -1.73937, -1.97859, -2.14555, -2.33928, -2.30634, -2.33748, -2.32634, -2.27155, -2.19274, -2.17616, -2.23119, -2.18184, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.09643, -2.07851, -2.01780, -2.02847, -1.91244, -1.75433, -1.61206, -1.74271, -1.89406, -1.93783, -1.98576, -2.03973, -1.92493, -1.77883, -1.46841, -1.33031, -1.19357, -1.17110, -0.96249, -0.68820, -0.46624, -0.25130, -0.15432, -0.04923, 0.11214, 0.19920, 0.36827, 0.33259, 0.27330, 0.26351, 0.35018, 0.43847, 0.43871, 0.34898, 0.33722, 0.31562, 0.38482, 0.46363, 0.47301, 0.39098, 0.39068, 0.49816, 0.44282, 0.27757, 0.29421, 0.21213, 0.12445, 0.03878, 0.05795, -0.05919, -0.21175, -0.29705, -0.47262, -0.76108, -1.07856, -1.31075, -1.33451, -1.42184, -1.36342, -1.38716, -1.37304, -1.30132, -1.34588, -1.36992, -1.32282, -1.23838, -1.12485, -1.29734, -1.55120, -1.74629, -1.83650, -1.95296, -2.07078, -1.97006, -1.85123, -1.96293, -1.99544, -2.01929, -1.83136, -1.60948, -1.33607, -1.11985, -1.02519, -0.91273, -0.88594, -0.83175, -0.78805, -0.80743, -0.83604, -0.92386, -0.88422, -0.88128, -0.94405, -1.02807, -1.10130, -1.10748, -1.06178, -1.01413, -0.92243, -0.86856, -0.79028, -0.70186, -0.72472, -0.80332, -0.92703, -1.03713, -1.27874, -1.59534, -1.78844, -2.01093, -2.20220, -2.22668, -2.22468, -2.29833, -2.44066, -2.44685, -2.41445, -2.41053, -2.42184, -2.53763, -2.63384, -2.80621, -3.00036, -3.15051, -3.26801, -3.27744, -3.31381, -3.40734, -3.46489, -3.48163, -3.35589, -3.30190, -3.34168, -3.27659, -3.17485, -3.22684, -3.38229, -3.33108, -3.04496, -2.82999, -2.57062, -2.34321, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.34817, 0.49617, 0.47457, 0.43829, 0.32750, 0.18895, 0.01727, -0.06503, 0.02076, 0.17256, 0.28386, 0.35638, 0.26558, 0.24061, 0.25476, 0.31072, 0.32604, 0.32805, 0.30445, 0.14551, -0.14767, -0.33709, -0.35331, -0.34848, -0.44842, -0.52227, -0.59591, -0.71518, -0.81281, -0.70182, -0.60920, -0.43368, -0.37911, -0.21865, -0.14510, -0.07398, -0.16759, -0.39754, -0.57596, -0.71503, -0.82561, -1.04008, -1.42360, -1.65118, -1.91656, -2.14296, -2.42951, -2.56761, -2.58546, -2.67865, -2.74786, -2.70705, -2.74920, -2.83275, -2.86586, -2.79532, -2.86643, -2.95267, -2.90816, -2.76509, -2.57732, -2.27482, -2.05636, -1.78200, -1.58945, -1.35955, -1.31133, -1.14971, -0.96321, -0.83597, -0.80124, -0.92781, -1.07085, -1.17649, +-0.64598, -0.53218, -0.31314, -0.17828, -0.20060, -0.33766, -0.41673, -0.45896, -0.53648, -0.63491, -0.69894, -0.58693, -0.48095, -0.50768, -0.53999, -0.54246, -0.57417, -0.72427, -0.80331, -0.73820, -0.68264, -0.73350, -0.72700, -0.65433, -0.74691, -0.97100, -1.10795, -1.04188, -0.98466, -1.06501, -1.18795, -1.32335, -1.51433, -1.80910, -1.99444, -2.10247, -2.19785, -2.24699, -2.34191, -2.43978, -2.52628, -2.48823, -2.39624, -2.26797, -2.16901, -2.06604, -1.99141, -1.99110, -2.06290, -2.09029, -2.01420, -1.91458, -1.83918, -1.89701, -2.02190, -2.03289, -2.03841, -2.04846, -2.00579, -1.89509, -1.82322, -1.75081, -1.60122, -1.27684, -1.13842, -1.17327, -1.09673, -0.96613, -0.94133, -0.94046, -0.87794, -0.60540, -0.36315, -0.13843, 0.03059, 0.30395, 0.43239, 0.33901, 0.25862, 0.21340, 0.05346, -0.21387, -0.36506, -0.33424, -0.32186, -0.32992, -0.37010, -0.20157, 0.02375, 0.20023, 0.34100, 0.49434, 0.57317, 0.45374, 0.33255, 0.39741, 0.43232, 0.31561, 0.12334, -0.05889, -0.26893, -0.33755, -0.33939, -0.28686, -0.25707, -0.09332, -0.00481, 0.12242, 0.17064, 0.21572, 0.35629, 0.48573, 0.56391, 0.46275, 0.26365, 0.11092, -0.02474, -0.10154, -0.27870, -0.47094, -0.71366, -0.92562, -1.02635, -0.94285, -0.90405, -0.99112, -1.05716, -0.99825, -1.04321, -1.33175, -1.61277, -1.73107, -1.92608, -2.14912, -2.34756, -2.31370, -2.32580, -2.28965, -2.21998, -2.04988, -2.00422, -2.09829, -2.07903, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.92444, -1.88233, -1.89220, -1.83755, -1.61889, -1.42947, -1.40766, -1.56314, -1.64143, -1.66808, -1.70015, -1.63989, -1.49820, -1.39489, -1.23131, -1.15805, -1.02994, -1.03278, -0.86371, -0.61290, -0.29738, 0.01089, 0.12679, 0.21906, 0.34461, 0.43515, 0.48029, 0.41466, 0.31964, 0.25729, 0.34136, 0.37372, 0.43456, 0.42897, 0.35508, 0.35388, 0.48993, 0.57701, 0.48331, 0.38911, 0.49034, 0.59458, 0.42683, 0.25238, 0.25496, 0.16211, 0.02159, -0.06469, -0.00221, -0.08300, -0.21227, -0.31237, -0.42916, -0.66323, -1.00357, -1.28095, -1.35000, -1.40310, -1.43281, -1.49953, -1.49354, -1.43095, -1.40231, -1.38976, -1.26053, -1.10118, -1.07179, -1.25501, -1.41994, -1.53829, -1.62680, -1.73640, -1.80021, -1.75080, -1.77524, -1.87992, -1.84702, -1.85086, -1.71863, -1.51099, -1.19149, -0.91117, -0.77039, -0.67763, -0.62790, -0.53769, -0.51271, -0.54936, -0.61825, -0.70957, -0.77343, -0.85463, -0.88655, -0.91540, -0.92179, -0.94003, -0.90826, -0.85045, -0.85315, -0.81934, -0.63870, -0.47919, -0.56844, -0.74263, -0.85421, -0.99311, -1.33469, -1.66017, -1.80818, -2.01529, -2.23330, -2.27716, -2.21916, -2.23668, -2.35287, -2.41270, -2.39181, -2.33899, -2.37424, -2.54460, -2.69136, -2.85728, -3.07175, -3.25897, -3.35226, -3.37929, -3.41787, -3.53928, -3.59587, -3.51608, -3.36168, -3.28498, -3.24776, -3.13170, -3.08430, -3.19449, -3.26171, -3.20614, -3.05205, -2.91292, -2.64499, -2.40653, -2.38054, -2.38474, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.18443, 0.38496, 0.40185, 0.35766, 0.24716, 0.19808, 0.08410, 0.01635, 0.09647, 0.22479, 0.28080, 0.19775, 0.10463, 0.10890, 0.23438, 0.39394, 0.43074, 0.50124, 0.43185, 0.17391, -0.10572, -0.28778, -0.37888, -0.52380, -0.60764, -0.60799, -0.71462, -0.90097, -0.97043, -0.85897, -0.77253, -0.65860, -0.59696, -0.41404, -0.31757, -0.23540, -0.26554, -0.33698, -0.46859, -0.65597, -0.83853, -1.12174, -1.50916, -1.83181, -2.04551, -2.25202, -2.52787, -2.64619, -2.70747, -2.73309, -2.78601, -2.81811, -2.81479, -2.81410, -2.82761, -2.85700, -2.91072, -2.93483, -2.95387, -2.93207, -2.71652, -2.36556, -2.11015, -1.87040, -1.64648, -1.36083, -1.24982, -1.05536, -0.88323, -0.70781, -0.68330, -0.85910, -1.00296, -1.06415, +-0.60815, -0.35578, -0.18122, -0.13329, -0.13539, -0.19499, -0.27103, -0.30813, -0.32678, -0.47853, -0.61985, -0.45887, -0.29966, -0.34587, -0.44038, -0.40142, -0.38966, -0.51895, -0.55648, -0.51326, -0.44589, -0.53328, -0.65799, -0.61394, -0.69673, -0.83767, -1.00732, -1.14524, -1.17332, -1.29396, -1.32458, -1.45100, -1.67218, -1.78041, -1.90935, -2.06808, -2.13226, -2.19956, -2.31995, -2.43205, -2.43092, -2.39490, -2.39873, -2.29061, -2.17128, -2.08456, -2.01198, -1.93075, -1.91421, -1.95988, -1.88937, -1.83633, -1.76280, -1.82889, -2.01329, -2.01674, -2.04494, -2.06329, -2.03006, -2.00555, -1.84555, -1.74275, -1.53942, -1.30541, -1.24457, -1.09694, -0.92927, -0.84933, -0.79362, -0.78975, -0.71274, -0.46645, -0.13465, 0.07745, 0.16209, 0.41678, 0.60174, 0.51233, 0.41368, 0.38995, 0.29631, 0.02216, -0.13090, -0.16163, -0.11607, -0.10945, -0.24055, -0.17194, 0.00190, 0.17960, 0.40789, 0.52740, 0.66929, 0.57085, 0.47285, 0.43645, 0.30548, 0.22235, 0.11657, -0.08647, -0.18601, -0.17073, -0.13691, -0.16238, -0.10578, 0.02934, 0.04560, 0.14603, 0.24761, 0.23828, 0.29903, 0.40696, 0.56583, 0.50662, 0.39978, 0.24351, 0.09089, -0.04030, -0.30727, -0.50561, -0.67590, -0.88187, -0.95496, -1.02184, -0.93638, -0.95217, -0.93138, -0.86670, -1.04101, -1.28586, -1.45921, -1.63704, -1.78554, -2.00119, -2.17573, -2.21090, -2.15521, -2.07410, -2.05674, -1.95115, -1.87700, -1.99736, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.71345, -1.60737, -1.62048, -1.55080, -1.49861, -1.34409, -1.33703, -1.40866, -1.38996, -1.42887, -1.34004, -1.12501, -1.06840, -1.00114, -0.87474, -0.77980, -0.72634, -0.71760, -0.58237, -0.46039, -0.25079, 0.09063, 0.24142, 0.34084, 0.45100, 0.62577, 0.66390, 0.62832, 0.55008, 0.48695, 0.51784, 0.41244, 0.32597, 0.35404, 0.30363, 0.39038, 0.45784, 0.51822, 0.43674, 0.39157, 0.56061, 0.57683, 0.39626, 0.35383, 0.30579, 0.22335, 0.11374, 0.07328, 0.07517, -0.00052, -0.09255, -0.30192, -0.52073, -0.67808, -0.96063, -1.27000, -1.45132, -1.45676, -1.46822, -1.45189, -1.36935, -1.30072, -1.25506, -1.32980, -1.31604, -1.13772, -1.12706, -1.20177, -1.35297, -1.44941, -1.46382, -1.54799, -1.57150, -1.63475, -1.67863, -1.57099, -1.49251, -1.48887, -1.37943, -1.19599, -0.96649, -0.72506, -0.51312, -0.45724, -0.49554, -0.39955, -0.37649, -0.42537, -0.48842, -0.46277, -0.51261, -0.63083, -0.68738, -0.71705, -0.67385, -0.72752, -0.79249, -0.73100, -0.75206, -0.66270, -0.48420, -0.38721, -0.45157, -0.61350, -0.66440, -0.87789, -1.27322, -1.44967, -1.59648, -1.85968, -2.06695, -2.13648, -2.10045, -2.09649, -2.10943, -2.25025, -2.41704, -2.41795, -2.45200, -2.59718, -2.72839, -2.80639, -2.95019, -3.16612, -3.26567, -3.35637, -3.41004, -3.55348, -3.67982, -3.55336, -3.37446, -3.26492, -3.24021, -3.22662, -3.11227, -3.12531, -3.04279, -3.01752, -3.00488, -2.81133, -2.58487, -2.46535, -2.41068, -2.40759, -2.39790, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.24694, 0.32584, 0.34001, 0.21386, 0.17383, 0.11930, 0.00832, 0.03819, 0.15412, 0.27233, 0.21047, 0.19925, 0.23615, 0.40506, 0.53244, 0.47019, 0.49768, 0.46398, 0.24878, 0.02848, -0.30239, -0.45327, -0.64926, -0.71111, -0.71824, -0.87960, -0.95523, -0.92686, -0.93001, -0.84919, -0.74574, -0.63229, -0.51057, -0.40790, -0.35877, -0.46848, -0.52461, -0.55410, -0.72361, -0.92467, -1.22596, -1.52410, -1.84040, -1.98891, -2.19892, -2.46824, -2.60134, -2.72899, -2.77055, -2.75602, -2.75882, -2.68747, -2.78728, -2.80258, -2.85416, -2.83801, -2.79887, -2.89608, -2.88274, -2.62740, -2.38603, -2.09763, -1.77679, -1.46595, -1.22456, -1.08497, -0.91409, -0.84087, -0.76141, -0.68837, -0.80302, -0.88748, -0.87733, +-0.29889, -0.04618, 0.05513, 0.00715, -0.05818, -0.06227, -0.11785, -0.10631, -0.15277, -0.36991, -0.45590, -0.28982, -0.16603, -0.19869, -0.36777, -0.40221, -0.31225, -0.35512, -0.33459, -0.28988, -0.31379, -0.42611, -0.55554, -0.56448, -0.65875, -0.75344, -0.85111, -1.09029, -1.23710, -1.39187, -1.54312, -1.63475, -1.67255, -1.67359, -1.80633, -1.97502, -2.04639, -2.11553, -2.22950, -2.27198, -2.24682, -2.29458, -2.36098, -2.29678, -2.23383, -2.10300, -2.00110, -1.95051, -1.81824, -1.76595, -1.71877, -1.71928, -1.76883, -1.85464, -1.92982, -1.88303, -1.93348, -1.99720, -1.96402, -1.91115, -1.69072, -1.51115, -1.43651, -1.37703, -1.26730, -0.99577, -0.79198, -0.63541, -0.55968, -0.52209, -0.46210, -0.24974, 0.04114, 0.14374, 0.23794, 0.53193, 0.72239, 0.70090, 0.60783, 0.47951, 0.39240, 0.18660, 0.00477, -0.03909, 0.01689, 0.05731, 0.04391, 0.07912, 0.11649, 0.17847, 0.41252, 0.61665, 0.77934, 0.79837, 0.58485, 0.35167, 0.23574, 0.20307, 0.12872, 0.06738, 0.06462, 0.13740, 0.07748, -0.03423, -0.03006, -0.00422, 0.05923, 0.24027, 0.38095, 0.41292, 0.40617, 0.34185, 0.45894, 0.51648, 0.50346, 0.40950, 0.23505, 0.00672, -0.24153, -0.36923, -0.52533, -0.80504, -0.93161, -1.07106, -1.04893, -0.90446, -0.86613, -0.88197, -0.99178, -1.12331, -1.32252, -1.49184, -1.66055, -1.84335, -2.01857, -2.07408, -1.97811, -1.96640, -1.94326, -1.79995, -1.77577, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.52742, -1.37217, -1.24956, -1.30999, -1.32689, -1.34604, -1.28991, -1.21978, -1.22911, -1.23213, -1.13506, -0.88713, -0.75583, -0.72858, -0.71232, -0.56236, -0.42606, -0.39076, -0.33020, -0.31269, -0.30633, -0.11812, 0.14617, 0.33852, 0.50463, 0.56083, 0.74386, 0.86051, 0.85815, 0.84307, 0.77904, 0.63823, 0.44670, 0.27357, 0.21625, 0.13569, 0.23864, 0.36885, 0.40171, 0.40680, 0.38684, 0.41728, 0.43799, 0.40497, 0.36764, 0.35238, 0.31983, 0.27640, 0.27597, 0.22206, 0.12386, -0.07959, -0.40978, -0.57890, -0.66720, -0.84002, -1.05932, -1.38053, -1.48542, -1.46735, -1.36642, -1.17053, -1.07360, -1.11116, -1.25280, -1.25658, -1.14767, -1.22237, -1.24715, -1.27320, -1.32160, -1.28640, -1.40847, -1.58393, -1.66305, -1.50113, -1.26965, -1.10602, -1.00176, -0.88267, -0.75663, -0.66526, -0.50928, -0.35854, -0.33979, -0.29656, -0.17660, -0.16743, -0.16906, -0.22270, -0.19774, -0.22846, -0.37007, -0.51867, -0.59631, -0.61259, -0.66267, -0.65706, -0.61102, -0.69508, -0.63746, -0.45429, -0.39084, -0.41554, -0.51143, -0.64928, -0.85950, -1.08943, -1.20611, -1.37776, -1.63910, -1.85931, -1.96771, -1.96386, -1.90826, -1.88217, -2.07911, -2.29591, -2.36356, -2.47451, -2.53886, -2.62528, -2.71700, -2.78997, -3.00900, -3.15416, -3.30927, -3.46848, -3.59347, -3.61664, -3.46213, -3.40012, -3.42568, -3.42181, -3.41981, -3.22231, -3.04292, -2.94690, -2.88099, -2.76801, -2.59510, -2.49962, -2.43972, -2.37306, -2.32205, -2.32081, -2.23874, -2.03758, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.26378, 0.23776, 0.21853, 0.29020, 0.23981, 0.12414, 0.11989, 0.11012, 0.25318, 0.34491, 0.42721, 0.51186, 0.56263, 0.50730, 0.41798, 0.43447, 0.39815, 0.19474, 0.03147, -0.22691, -0.43442, -0.58726, -0.75714, -0.88381, -0.90663, -0.82012, -0.78654, -0.77775, -0.74180, -0.62851, -0.49618, -0.42765, -0.41696, -0.55331, -0.74972, -0.72722, -0.70898, -0.78529, -0.93002, -1.31885, -1.60419, -1.85376, -2.00603, -2.21815, -2.52638, -2.74563, -2.81446, -2.76274, -2.72490, -2.74266, -2.67509, -2.73624, -2.79873, -2.78156, -2.74114, -2.73753, -2.68511, -2.54011, -2.40055, -2.22658, -1.99359, -1.59284, -1.22636, -0.99712, -0.86960, -0.86957, -0.85554, -0.74118, -0.64698, -0.61205, -0.55085, -0.55841, +0.06169, 0.11710, 0.16015, 0.08196, -0.03805, 0.00221, -0.04637, 0.02223, 0.04414, -0.16968, -0.26202, -0.18074, -0.16650, -0.18510, -0.30610, -0.35343, -0.30522, -0.35496, -0.27088, -0.23359, -0.25358, -0.26431, -0.37689, -0.46382, -0.54050, -0.57137, -0.58760, -0.89570, -1.19648, -1.44846, -1.72322, -1.70532, -1.63681, -1.72945, -1.83258, -1.92741, -2.02144, -2.08025, -2.20954, -2.19074, -2.07116, -2.12554, -2.27231, -2.31901, -2.37201, -2.24301, -2.06954, -1.98488, -1.82590, -1.74136, -1.64564, -1.66341, -1.72024, -1.65391, -1.63310, -1.62474, -1.66096, -1.66476, -1.59971, -1.57388, -1.45245, -1.31822, -1.32111, -1.19158, -0.99304, -0.81837, -0.63908, -0.40769, -0.37449, -0.32254, -0.28428, -0.08214, 0.23903, 0.33655, 0.39209, 0.58670, 0.67335, 0.66363, 0.64224, 0.53514, 0.42167, 0.18692, 0.05163, 0.05760, 0.15282, 0.35901, 0.48277, 0.47429, 0.44019, 0.47983, 0.64656, 0.79930, 0.84819, 0.86938, 0.61810, 0.45359, 0.42113, 0.25070, 0.11323, 0.17321, 0.18906, 0.27465, 0.14395, 0.00130, 0.03014, 0.05271, 0.10052, 0.23277, 0.34040, 0.41164, 0.45764, 0.39760, 0.49487, 0.55215, 0.61041, 0.56590, 0.37964, 0.23530, 0.03518, -0.14810, -0.36612, -0.63467, -0.77133, -0.93461, -1.02046, -0.86310, -0.85081, -0.79683, -0.79580, -1.00764, -1.31138, -1.43881, -1.64901, -1.81621, -1.99277, -2.06873, -1.92275, -1.87029, -1.86223, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.16182, -1.02597, -0.93898, -0.92890, -0.92578, -0.94855, -1.03521, -1.03502, -1.07633, -1.00375, -0.73656, -0.53596, -0.58333, -0.54171, -0.57863, -0.45758, -0.31988, -0.30183, -0.15351, -0.06676, -0.10647, 0.00363, 0.17346, 0.34717, 0.58915, 0.72069, 0.92975, 1.01541, 1.02535, 1.05218, 0.92596, 0.77828, 0.61679, 0.36606, 0.21335, 0.16997, 0.29187, 0.45534, 0.37429, 0.32932, 0.27833, 0.30387, 0.45662, 0.44627, 0.27919, 0.28943, 0.27436, 0.24832, 0.27816, 0.18914, 0.10842, -0.06452, -0.42257, -0.59351, -0.70834, -0.87254, -0.96113, -1.19836, -1.30494, -1.36058, -1.29399, -1.04378, -0.95580, -0.92150, -0.95467, -0.97589, -0.98794, -1.09817, -1.10192, -1.04893, -1.14819, -1.19660, -1.38916, -1.58350, -1.51967, -1.28279, -1.14258, -0.92894, -0.73002, -0.59295, -0.47766, -0.47022, -0.31861, -0.10778, -0.08888, -0.04781, 0.02473, -0.03233, 0.01923, 0.05532, 0.09573, 0.00642, -0.17936, -0.34125, -0.46821, -0.47415, -0.43491, -0.42751, -0.49285, -0.59629, -0.52303, -0.32637, -0.34566, -0.44467, -0.56519, -0.74548, -0.81067, -0.94165, -1.18684, -1.38142, -1.60844, -1.85667, -1.95057, -1.95759, -1.86031, -1.72983, -1.87253, -2.10972, -2.27990, -2.53475, -2.60649, -2.60592, -2.63752, -2.67796, -2.89695, -3.02384, -3.23202, -3.43441, -3.45316, -3.42352, -3.35427, -3.37485, -3.43071, -3.41143, -3.45972, -3.33089, -3.11670, -3.00932, -2.73050, -2.48285, -2.47666, -2.48051, -2.39757, -2.35379, -2.28139, -2.30265, -2.21200, -1.96565, -1.79428, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.21274, 0.21488, 0.28886, 0.24067, 0.18725, 0.27872, 0.31033, 0.44077, 0.51973, 0.65908, 0.75030, 0.69372, 0.64045, 0.54760, 0.44587, 0.34653, 0.20290, 0.09316, -0.08809, -0.36125, -0.53409, -0.75885, -0.77694, -0.62548, -0.60612, -0.65580, -0.59716, -0.62777, -0.54121, -0.45854, -0.46295, -0.46838, -0.61914, -0.86299, -0.86833, -0.88627, -0.94110, -1.00337, -1.34458, -1.62928, -1.93815, -2.10117, -2.30981, -2.65955, -2.81204, -2.81467, -2.77855, -2.75612, -2.69973, -2.60321, -2.61975, -2.76613, -2.74672, -2.69997, -2.59770, -2.33935, -2.19829, -2.20026, -2.03776, -1.92466, -1.58585, -1.23711, -1.01468, -0.79852, -0.73418, -0.72516, -0.64366, -0.59636, -0.51737, -0.31061, -0.22372, +0.18864, 0.20012, 0.22479, 0.15091, 0.05445, 0.12256, 0.14898, 0.20916, 0.17092, -0.00615, -0.14213, -0.12771, -0.05074, -0.05475, -0.18556, -0.27915, -0.25492, -0.26861, -0.17480, -0.09482, -0.09151, -0.13100, -0.23401, -0.30115, -0.36261, -0.39544, -0.46227, -0.82552, -1.16380, -1.47423, -1.76777, -1.77371, -1.78158, -1.84553, -1.83316, -1.83689, -1.89053, -1.95342, -2.05587, -2.05097, -1.99244, -2.02034, -2.19367, -2.33066, -2.35018, -2.23252, -2.10654, -2.03401, -1.85556, -1.68026, -1.54291, -1.50852, -1.49732, -1.41468, -1.37487, -1.34314, -1.34241, -1.30354, -1.26364, -1.31227, -1.23487, -1.14203, -1.10025, -0.89847, -0.72547, -0.55233, -0.34963, -0.12453, -0.09617, -0.06249, 0.01749, 0.22149, 0.46098, 0.54134, 0.54328, 0.56344, 0.62567, 0.64881, 0.61591, 0.52978, 0.43966, 0.29233, 0.22049, 0.30439, 0.45301, 0.63542, 0.77956, 0.82083, 0.80882, 0.84336, 0.88086, 0.85794, 0.84041, 0.84624, 0.69193, 0.64145, 0.55333, 0.31543, 0.16687, 0.22659, 0.27867, 0.37521, 0.30306, 0.20063, 0.15198, 0.11397, 0.11615, 0.11616, 0.25288, 0.42562, 0.48259, 0.44482, 0.57231, 0.72839, 0.81287, 0.78405, 0.61970, 0.42122, 0.18172, -0.02189, -0.26593, -0.51163, -0.65709, -0.87085, -0.93346, -0.77864, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.53709, -1.70217, -1.84832, -1.91810, -1.87259, -1.86820, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.86607, -0.88099, -0.77671, -0.68341, -0.59376, -0.52596, -0.59867, -0.72424, -0.79147, -0.87811, -0.73105, -0.48504, -0.33806, -0.35446, -0.32053, -0.36755, -0.31409, -0.20241, -0.15261, -0.05485, 0.00262, -0.01533, -0.01168, 0.16275, 0.43836, 0.66541, 0.80274, 1.00572, 1.15362, 1.19517, 1.21225, 1.08088, 0.88016, 0.67696, 0.43613, 0.30867, 0.30577, 0.41401, 0.48174, 0.34557, 0.27056, 0.21553, 0.33576, 0.49910, 0.44160, 0.29371, 0.27219, 0.25337, 0.22772, 0.28092, 0.26439, 0.14684, -0.08592, -0.39764, -0.63445, -0.77740, -0.84167, -0.88293, -1.05325, -1.12680, -1.13790, -1.08890, -0.87395, -0.76029, -0.69115, -0.68070, -0.68406, -0.72119, -0.86159, -0.92161, -0.94732, -1.07979, -1.12724, -1.30592, -1.39406, -1.30350, -1.14344, -0.99470, -0.76869, -0.53339, -0.36834, -0.24377, -0.18576, -0.05716, 0.08006, 0.10209, 0.06436, 0.08434, 0.10736, 0.18086, 0.22184, 0.25712, 0.20915, 0.07366, -0.07651, -0.17152, -0.19948, -0.23157, -0.27409, -0.37150, -0.46567, -0.39008, -0.25384, -0.32758, -0.44090, -0.59471, -0.74850, -0.80024, -0.98774, -1.22381, -1.38525, -1.58282, -1.80492, -1.87339, -1.81915, -1.75922, -1.71038, -1.81240, -2.06409, -2.30013, -2.52614, -2.63584, -2.66265, -2.66776, -2.60931, -2.68702, -2.78741, -2.98674, -3.22653, -3.33627, -3.34064, -3.27983, -3.28270, -3.31053, -3.32186, -3.43445, -3.34110, -3.14724, -2.96968, -2.59710, -2.37115, -2.37845, -2.37177, -2.27701, -2.22835, -2.18904, -2.18679, -2.11671, -1.96178, -1.79907, -1.59126, -1.38700, -1.18035, -0.91671, -0.74019, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.10653, 0.12009, 0.22148, 0.36307, 0.51899, 0.59756, 0.71146, 0.81940, 0.95004, 1.04111, 0.98955, 0.85982, 0.70105, 0.54252, 0.39185, 0.26088, 0.13947, -0.07368, -0.30590, -0.46186, -0.61371, -0.48950, -0.35405, -0.39332, -0.44313, -0.41606, -0.47179, -0.45461, -0.41329, -0.44942, -0.55551, -0.74163, -0.95615, -1.03976, -1.02216, -0.98713, -1.05638, -1.37407, -1.65298, -1.90395, -2.06255, -2.26441, -2.58652, -2.80439, -2.86852, -2.82724, -2.77304, -2.64293, -2.51313, -2.56347, -2.68240, -2.63428, -2.55110, -2.35681, -2.11725, -2.00827, -1.97707, -1.84426, -1.80173, -1.59262, -1.28469, -1.01863, -0.78362, -0.66841, -0.59878, -0.60038, -0.55476, -0.37376, -0.13240, 0.01149, +0.18412, 0.31898, 0.33055, 0.25749, 0.16375, 0.22271, 0.28028, 0.24714, 0.18346, 0.17988, 0.09148, 0.08377, 0.16787, 0.10201, -0.00573, -0.15510, -0.25196, -0.27031, -0.19802, -0.05559, 0.08391, 0.06389, -0.00509, -0.08135, -0.25556, -0.38323, -0.51371, -0.86860, -1.20080, -1.50742, -1.78771, -1.90620, -2.00473, -1.94387, -1.81880, -1.70235, -1.66340, -1.69447, -1.78426, -1.93160, -2.00741, -1.90272, -1.95937, -2.10720, -2.12033, -2.11182, -2.04214, -2.01445, -1.93377, -1.74589, -1.56922, -1.44384, -1.29636, -1.23476, -1.24283, -1.19244, -1.19151, -1.15433, -1.10976, -1.13526, -1.03260, -0.90309, -0.83422, -0.68189, -0.59129, -0.33212, -0.11872, 0.11226, 0.23699, 0.30301, 0.43306, 0.51762, 0.60379, 0.74921, 0.79495, 0.69891, 0.69949, 0.62161, 0.56491, 0.53716, 0.48317, 0.43433, 0.44438, 0.54334, 0.70819, 0.82233, 0.88824, 0.98978, 1.00170, 1.01566, 1.00178, 0.90925, 0.81275, 0.79993, 0.73160, 0.72704, 0.58021, 0.43707, 0.28390, 0.28660, 0.37629, 0.51684, 0.58125, 0.44727, 0.26986, 0.25615, 0.29037, 0.20296, 0.31993, 0.42357, 0.48073, 0.50265, 0.60695, 0.74263, 0.79615, 0.76009, 0.66487, 0.44947, 0.12195, -0.08326, -0.30717, -0.53537, -0.66403, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.65542, -0.59753, -0.65914, -0.57144, -0.50389, -0.43925, -0.31926, -0.31481, -0.42982, -0.52229, -0.68129, -0.57892, -0.43967, -0.19676, -0.05734, -0.03481, -0.04629, -0.02292, 0.08288, 0.07929, -0.00546, 0.01332, 0.11788, 0.11909, 0.30381, 0.48325, 0.57918, 0.70953, 0.87607, 1.01188, 1.05952, 1.07301, 1.03949, 0.89961, 0.63953, 0.41370, 0.29150, 0.23733, 0.30539, 0.41585, 0.33989, 0.28671, 0.22220, 0.34580, 0.43519, 0.43518, 0.40991, 0.32277, 0.28537, 0.25689, 0.34290, 0.38981, 0.20610, -0.03659, -0.19218, -0.46737, -0.65839, -0.78498, -0.91352, -0.99360, -1.02274, -1.01187, -0.95779, -0.81164, -0.68287, -0.54817, -0.51358, -0.48036, -0.51285, -0.73856, -0.91602, -0.96928, -1.07971, -1.04548, -1.13482, -1.15231, -1.09862, -0.93478, -0.68571, -0.49574, -0.27452, -0.09099, 0.07624, 0.18094, 0.16118, 0.12262, 0.18795, 0.14175, 0.15741, 0.17532, 0.14833, 0.21798, 0.30580, 0.27225, 0.16853, 0.00470, -0.07492, -0.09331, -0.21843, -0.26869, -0.30039, -0.40583, -0.36726, -0.23972, -0.28661, -0.36751, -0.52404, -0.71516, -0.88488, -1.11601, -1.23019, -1.32566, -1.43913, -1.57058, -1.60094, -1.56830, -1.70541, -1.84595, -1.86917, -2.02743, -2.23750, -2.42262, -2.64583, -2.71823, -2.73440, -2.67736, -2.63883, -2.69141, -2.83110, -3.02973, -3.25986, -3.34840, -3.28449, -3.26266, -3.26361, -3.24987, -3.30252, -3.19315, -3.00091, -2.80832, -2.49356, -2.29900, -2.15991, -2.11398, -2.04854, -2.04239, -2.06278, -2.03884, -2.08902, -2.10224, -1.90898, -1.65669, -1.44705, -1.18724, -0.98307, -0.76810, -0.53831, -0.42121, -0.39283, -0.40483, -0.51644, -0.66725, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.49225, -0.25468, -0.09126, 0.06200, 0.05487, 0.13272, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.11983, 0.34094, 0.54658, 0.76734, 0.92057, 0.95302, 0.98362, 1.05899, 1.15203, 1.20659, 1.06565, 0.81344, 0.64835, 0.45879, 0.27700, 0.13710, -0.03144, -0.18929, -0.25723, -0.31859, -0.18956, -0.18843, -0.19225, -0.21985, -0.25056, -0.33322, -0.41454, -0.37092, -0.46397, -0.72621, -0.91007, -1.03652, -1.16219, -1.13197, -1.15255, -1.19818, -1.40269, -1.70084, -1.96850, -2.14115, -2.32218, -2.53976, -2.76567, -2.94197, -2.89305, -2.81405, -2.66744, -2.45163, -2.36838, -2.38584, -2.30096, -2.27639, -2.15110, -2.08372, -1.93569, -1.79646, -1.68120, -1.62239, -1.50245, -1.22002, -0.99902, -0.84768, -0.64455, -0.40712, -0.38593, -0.33596, -0.24138, -0.05827, 0.16433, +0.26732, 0.45271, 0.46259, 0.40837, 0.24206, 0.17041, 0.15421, 0.14885, 0.20180, 0.26666, 0.21910, 0.22443, 0.22576, 0.15427, 0.14133, 0.01916, -0.08166, -0.06396, -0.05580, 0.01766, 0.28669, 0.39709, 0.36514, 0.25115, -0.07820, -0.34626, -0.56216, -0.87969, -1.15597, -1.41900, -1.68644, -1.86060, -1.93741, -1.89172, -1.78744, -1.59118, -1.50692, -1.54876, -1.63532, -1.78410, -1.83288, -1.71107, -1.72303, -1.84288, -1.93873, -2.00017, -1.92737, -1.97442, -1.99764, -1.82132, -1.62966, -1.47237, -1.16910, -1.01635, -1.07339, -1.04157, -1.03083, -1.01364, -0.96255, -0.93664, -0.74754, -0.55678, -0.52063, -0.47088, -0.36469, -0.10862, 0.08045, 0.34631, 0.51207, 0.49652, 0.56752, 0.60933, 0.71215, 0.87958, 0.94134, 0.88245, 0.82058, 0.65555, 0.62023, 0.59153, 0.59241, 0.68804, 0.78922, 0.81458, 0.95651, 1.09938, 1.08803, 1.20186, 1.23263, 1.18778, 1.18066, 1.07458, 0.94769, 0.87016, 0.74184, 0.66355, 0.60346, 0.58762, 0.47417, 0.47997, 0.54202, 0.55902, 0.61032, 0.48806, 0.37707, 0.42648, 0.43962, 0.32596, 0.32436, 0.27635, 0.38460, 0.45488, 0.55813, 0.68769, 0.70856, 0.61081, 0.59617, 0.51555, 0.14384, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.80117, -0.54510, -0.26977, -0.24364, -0.17123, -0.13244, -0.23992, -0.21059, -0.19346, -0.24191, -0.26012, -0.40727, -0.44180, -0.32788, -0.02368, 0.16276, 0.20918, 0.24175, 0.18199, 0.20067, 0.11399, -0.00807, 0.03101, 0.14610, 0.19075, 0.34174, 0.30201, 0.30432, 0.41989, 0.58423, 0.76357, 0.84235, 0.83057, 0.88132, 0.92041, 0.68778, 0.44941, 0.33959, 0.18415, 0.19618, 0.32212, 0.32795, 0.30954, 0.23052, 0.23016, 0.31720, 0.42600, 0.48569, 0.45289, 0.45025, 0.33222, 0.30403, 0.29745, 0.19855, 0.09696, 0.01350, -0.26658, -0.50615, -0.80139, -0.96612, -0.93852, -0.91867, -0.82371, -0.68785, -0.61866, -0.54619, -0.36734, -0.34300, -0.34626, -0.36603, -0.64141, -0.88277, -0.95927, -1.02345, -0.91309, -0.92102, -0.96501, -0.87686, -0.60622, -0.34702, -0.20604, -0.03312, 0.05753, 0.15437, 0.22622, 0.20041, 0.12658, 0.12864, 0.08996, 0.15110, 0.07423, -0.01842, 0.10826, 0.25786, 0.28158, 0.23513, 0.04366, -0.08064, -0.04208, -0.15811, -0.23877, -0.22987, -0.37957, -0.41567, -0.31635, -0.30680, -0.31094, -0.40485, -0.62738, -0.85362, -1.03749, -1.16579, -1.25416, -1.27045, -1.36204, -1.45926, -1.55429, -1.75755, -1.91346, -1.93500, -2.00543, -2.13727, -2.33343, -2.58194, -2.64429, -2.71570, -2.74029, -2.67670, -2.70301, -2.79844, -2.82344, -2.97463, -3.13231, -3.12011, -3.14683, -3.19943, -3.17464, -3.11722, -2.91064, -2.69501, -2.56296, -2.36457, -2.12004, -1.91371, -1.84183, -1.77775, -1.87738, -2.06687, -2.10013, -2.12757, -2.11800, -1.96723, -1.72863, -1.46707, -1.26471, -1.14540, -0.85767, -0.59513, -0.47072, -0.38114, -0.35165, -0.43618, -0.47343, -0.56156, -0.63551, -0.54440, -0.53039, -0.52425, -0.43259, -0.37400, -0.25383, -0.06269, 0.07902, 0.20545, 0.31225, 0.43982, 0.40882, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.34419, 0.49079, 0.60794, 0.91426, 1.13737, 1.18572, 1.21718, 1.24561, 1.25060, 1.34824, 1.29499, 0.98423, 0.80386, 0.62195, 0.34832, 0.17960, 0.03488, -0.01751, 0.02691, 0.03487, 0.06355, 0.01896, 0.00043, -0.04395, -0.06030, -0.19163, -0.48155, -0.52708, -0.62397, -0.85344, -1.01271, -1.14617, -1.26541, -1.29807, -1.45066, -1.42677, -1.54175, -1.83488, -2.08479, -2.25228, -2.45261, -2.56915, -2.60760, -2.75223, -2.70489, -2.60784, -2.56215, -2.31760, -2.10561, -1.96695, -1.83278, -1.89930, -1.97064, -1.99641, -1.82967, -1.65056, -1.49970, -1.37493, -1.35961, -1.16858, -1.01826, -0.88710, -0.62984, -0.34309, -0.21287, -0.12734, -0.17694, -0.01403, 0.23190, +0.38129, 0.50051, 0.46494, 0.43740, 0.38704, 0.30064, 0.18756, 0.23352, 0.25657, 0.22842, 0.16844, 0.17156, 0.22855, 0.27801, 0.36937, 0.27959, 0.19930, 0.28108, 0.24618, 0.22596, 0.39065, 0.42055, 0.39101, 0.33293, 0.04929, -0.22202, -0.50080, -0.77426, -1.01714, -1.33169, -1.53398, -1.65467, -1.70390, -1.73829, -1.73156, -1.53554, -1.31046, -1.25746, -1.32953, -1.38080, -1.40528, -1.42603, -1.50802, -1.66881, -1.76205, -1.76543, -1.67592, -1.83275, -1.98246, -1.81456, -1.61772, -1.43796, -1.09395, -0.98169, -1.04304, -0.97660, -0.85303, -0.75522, -0.71515, -0.67734, -0.43778, -0.33060, -0.27544, -0.22280, -0.08474, 0.11491, 0.27305, 0.51657, 0.73413, 0.72253, 0.68790, 0.72935, 0.85396, 0.89252, 0.93447, 0.91593, 0.94011, 0.89269, 0.91798, 0.80693, 0.74998, 0.92526, 1.10575, 1.13324, 1.24816, 1.25671, 1.22338, 1.38136, 1.47329, 1.42739, 1.36377, 1.18816, 1.09567, 0.87113, 0.69320, 0.61112, 0.62986, 0.65745, 0.61425, 0.62263, 0.72466, 0.71062, 0.62663, 0.50789, 0.48287, 0.45083, 0.43715, 0.27193, 0.24463, 0.24456, 0.41668, 0.46680, 0.52480, 0.67621, 0.72554, 0.61418, 0.65650, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.80666, -0.58471, -0.28698, -0.06966, -0.02115, 0.07559, 0.17223, 0.03055, -0.06464, -0.17940, -0.14543, -0.16339, -0.22387, -0.22845, -0.09315, 0.11504, 0.23289, 0.23906, 0.32650, 0.35039, 0.29055, 0.13194, 0.07938, 0.04367, 0.10717, 0.10072, 0.22360, 0.18992, 0.20097, 0.29136, 0.40828, 0.59733, 0.75138, 0.74613, 0.84424, 0.81048, 0.55437, 0.34165, 0.34163, 0.26669, 0.27221, 0.26137, 0.27054, 0.16081, 0.04141, 0.03493, 0.16517, 0.28034, 0.38061, 0.41960, 0.51969, 0.49676, 0.36477, 0.21129, 0.19359, 0.10405, 0.03932, -0.21523, -0.43458, -0.66465, -0.70677, -0.59074, -0.61279, -0.54691, -0.35739, -0.32783, -0.26848, -0.24573, -0.37687, -0.45350, -0.43466, -0.59667, -0.77575, -0.91106, -0.91747, -0.85202, -0.88577, -0.86718, -0.70290, -0.42074, -0.22170, -0.16084, -0.00562, 0.15428, 0.21034, 0.19509, 0.26221, 0.17740, 0.09046, 0.03324, 0.12124, 0.09873, 0.07756, 0.23969, 0.32714, 0.30891, 0.32567, 0.15346, 0.05953, 0.03715, -0.17882, -0.34626, -0.35487, -0.46795, -0.51951, -0.51478, -0.48224, -0.46749, -0.55317, -0.64903, -0.78961, -0.95644, -1.18709, -1.36899, -1.36616, -1.32824, -1.40019, -1.57526, -1.70851, -1.81953, -1.87346, -1.90769, -2.03432, -2.18122, -2.33879, -2.36914, -2.53884, -2.71814, -2.68400, -2.68585, -2.70740, -2.62890, -2.77029, -2.93585, -2.93059, -2.96882, -3.05180, -3.07968, -2.98203, -2.70369, -2.54212, -2.37662, -2.16810, -1.90773, -1.75547, -1.70947, -1.63448, -1.65504, -1.84479, -1.94607, -1.88489, -1.82828, -1.82163, -1.66729, -1.49233, -1.32024, -1.14548, -0.77040, -0.50303, -0.39592, -0.24427, -0.21000, -0.31519, -0.33111, -0.47986, -0.54716, -0.40652, -0.31169, -0.25211, -0.16278, -0.13845, -0.00937, 0.00685, 0.11186, 0.26066, 0.43422, 0.53062, 0.45027, 0.37642, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.70955, 0.83818, 1.19545, 1.39939, 1.43545, 1.51257, 1.55574, 1.49099, 1.50794, 1.27908, 0.90924, 0.73381, 0.63120, 0.40276, 0.22405, 0.05323, 0.12145, 0.13357, 0.21193, 0.27406, 0.24541, 0.13726, 0.06643, 0.04360, -0.04039, -0.32375, -0.49397, -0.62899, -0.79066, -1.04891, -1.20031, -1.34934, -1.39564, -1.51130, -1.46688, -1.62450, -1.97622, -2.21623, -2.33107, -2.52261, -2.57327, -2.62329, -2.68559, -2.58260, -2.41330, -2.37969, -2.18499, -2.00852, -1.73190, -1.62917, -1.68451, -1.77338, -1.78618, -1.66142, -1.50138, -1.38895, -1.19114, -1.08299, -0.95024, -0.84797, -0.69927, -0.57379, -0.31938, -0.18137, -0.03165, -0.00645, 0.19836, 0.39314, +0.50908, 0.61420, 0.56032, 0.49829, 0.49024, 0.45952, 0.34165, 0.32453, 0.22206, 0.13345, 0.11822, 0.13255, 0.23030, 0.35734, 0.45850, 0.41500, 0.40507, 0.47912, 0.44598, 0.37481, 0.36390, 0.30526, 0.28505, 0.26985, 0.01111, -0.25073, -0.45632, -0.62880, -0.82195, -1.09806, -1.26320, -1.35611, -1.37895, -1.38232, -1.40947, -1.28693, -1.04347, -0.88445, -0.87409, -0.89233, -0.94604, -1.07191, -1.22152, -1.41042, -1.49612, -1.45828, -1.42933, -1.67708, -1.87108, -1.76094, -1.57718, -1.36556, -1.07596, -0.97674, -0.98360, -0.90125, -0.73499, -0.59431, -0.49338, -0.40226, -0.18082, -0.08000, 0.00456, 0.09575, 0.24568, 0.46896, 0.61967, 0.74247, 0.86741, 0.88553, 0.85580, 0.84929, 0.88968, 0.83423, 0.87846, 0.92223, 1.03037, 1.09843, 1.13047, 0.94771, 0.87126, 1.03132, 1.23122, 1.34711, 1.41713, 1.34652, 1.37060, 1.56559, 1.64612, 1.52841, 1.39885, 1.19897, 1.10411, 0.88266, 0.70945, 0.67457, 0.72464, 0.83720, 0.86114, 0.81050, 0.84623, 0.77911, 0.61045, 0.46313, 0.43320, 0.37724, 0.39616, 0.25553, 0.23988, 0.31190, 0.46419, 0.43716, 0.48319, 0.62785, 0.67668, 0.64089, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.10175, -0.99258, -0.68662, -0.37993, -0.09153, 0.04243, 0.09418, 0.19635, 0.31107, 0.12626, -0.01559, -0.13045, -0.08146, -0.04280, -0.01253, 0.06993, 0.19919, 0.33554, 0.37757, 0.30447, 0.33778, 0.39737, 0.35020, 0.17465, 0.12336, 0.04816, 0.09084, 0.06596, 0.13479, 0.12960, 0.12169, 0.13055, 0.25013, 0.46080, 0.62619, 0.69714, 0.78892, 0.67324, 0.45813, 0.31769, 0.38328, 0.32070, 0.31867, 0.24215, 0.16142, 0.01497, -0.10626, -0.09401, 0.01845, 0.15503, 0.32311, 0.40890, 0.51059, 0.51713, 0.38193, 0.15288, 0.08452, -0.04306, -0.06208, -0.19616, -0.35494, -0.47364, -0.39748, -0.27147, -0.30957, -0.29026, -0.19602, -0.17144, -0.11688, -0.22296, -0.41565, -0.51359, -0.50581, -0.64385, -0.76541, -0.83691, -0.81139, -0.79654, -0.84905, -0.75951, -0.56004, -0.27408, -0.08835, -0.10159, -0.02968, 0.12719, 0.20148, 0.17150, 0.24876, 0.16703, 0.08601, 0.08339, 0.21023, 0.25807, 0.28859, 0.37510, 0.38017, 0.34428, 0.35198, 0.25494, 0.21800, 0.10862, -0.16251, -0.41320, -0.52262, -0.68150, -0.77060, -0.79710, -0.78379, -0.77338, -0.79858, -0.75922, -0.80869, -0.94715, -1.17730, -1.43426, -1.53249, -1.50152, -1.50005, -1.61382, -1.70830, -1.78215, -1.77563, -1.72740, -1.84161, -1.97842, -2.12984, -2.24151, -2.48695, -2.72083, -2.73904, -2.68569, -2.59892, -2.47812, -2.55013, -2.63265, -2.63529, -2.76700, -2.93280, -2.94840, -2.80087, -2.49212, -2.30211, -2.09793, -1.85285, -1.60311, -1.45473, -1.44531, -1.44429, -1.45694, -1.57077, -1.61750, -1.50384, -1.44738, -1.50955, -1.42690, -1.35658, -1.23246, -1.02346, -0.66032, -0.41786, -0.28529, -0.14080, -0.14569, -0.23020, -0.25918, -0.40908, -0.42549, -0.27786, -0.18335, -0.13486, -0.01563, 0.01982, 0.10721, 0.06732, 0.12722, 0.28578, 0.45406, 0.59693, 0.54409, 0.39921, 0.38499, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.00216, 1.15553, 1.46239, 1.58000, 1.62440, 1.70742, 1.75804, 1.70932, 1.57027, 1.18495, 0.82247, 0.65595, 0.57873, 0.34883, 0.20217, 0.10206, 0.21227, 0.24699, 0.34137, 0.44358, 0.40562, 0.30212, 0.25022, 0.19105, 0.08850, -0.14700, -0.33744, -0.51436, -0.68151, -0.97960, -1.11181, -1.25423, -1.33310, -1.43590, -1.49761, -1.78008, -2.12350, -2.35531, -2.47412, -2.58964, -2.63236, -2.69838, -2.64802, -2.49359, -2.31367, -2.34379, -2.20601, -2.02004, -1.72151, -1.56359, -1.55085, -1.57954, -1.57161, -1.39600, -1.21735, -1.17840, -1.04748, -0.91853, -0.75615, -0.64836, -0.53346, -0.49287, -0.25599, -0.10519, 0.05041, 0.13909, 0.32599, 0.38689, +0.43988, 0.57239, 0.66775, 0.58938, 0.48134, 0.47401, 0.36349, 0.25819, 0.11213, 0.06865, 0.19446, 0.17953, 0.17816, 0.34377, 0.49242, 0.48038, 0.53577, 0.58923, 0.49021, 0.40773, 0.29749, 0.23358, 0.16157, 0.10083, -0.02360, -0.22491, -0.37919, -0.43157, -0.55702, -0.73638, -0.90908, -1.12236, -1.16044, -1.09545, -0.95858, -0.85945, -0.73093, -0.53153, -0.49591, -0.52042, -0.53572, -0.66903, -0.81868, -1.05785, -1.21501, -1.12016, -1.08575, -1.35114, -1.51985, -1.43695, -1.39324, -1.27757, -1.09702, -0.93507, -0.85881, -0.83463, -0.59647, -0.40688, -0.26657, -0.10061, 0.08098, 0.20799, 0.35073, 0.38462, 0.47852, 0.65611, 0.88705, 0.91773, 0.86898, 0.96716, 1.03241, 0.96851, 0.91480, 0.81821, 0.88954, 0.92111, 0.95796, 1.10639, 1.22746, 1.13453, 1.08257, 1.20084, 1.25804, 1.34806, 1.41876, 1.41826, 1.52595, 1.63993, 1.76576, 1.65886, 1.42254, 1.19120, 1.08924, 0.91309, 0.84136, 0.75901, 0.79562, 0.88523, 0.96919, 0.90880, 0.79559, 0.67979, 0.48940, 0.29873, 0.29470, 0.32139, 0.43665, 0.35535, 0.29227, 0.42132, 0.55966, 0.50154, 0.49707, 0.64629, 0.63043, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.97433, -0.99985, -0.85379, -0.63542, -0.39425, -0.11139, 0.05654, 0.16392, 0.15506, 0.29225, 0.22389, 0.13066, 0.08378, 0.15803, 0.16096, 0.24560, 0.29005, 0.39780, 0.45325, 0.47143, 0.42465, 0.32490, 0.35041, 0.37067, 0.17979, 0.14573, 0.11944, 0.15834, 0.12930, 0.01160, -0.04019, -0.02741, -0.00455, 0.11430, 0.38893, 0.53328, 0.54451, 0.60793, 0.54689, 0.52173, 0.41001, 0.45824, 0.44903, 0.42050, 0.27790, 0.17286, 0.02756, -0.01672, -0.10316, -0.12353, -0.03213, 0.19356, 0.37030, 0.36163, 0.29770, 0.27703, 0.06378, -0.07691, -0.23524, -0.24286, -0.21347, -0.35820, -0.43805, -0.27282, -0.08709, -0.09500, -0.05268, -0.11131, -0.24743, -0.22519, -0.31555, -0.35445, -0.46066, -0.50834, -0.59403, -0.70465, -0.71563, -0.61126, -0.64685, -0.69183, -0.62976, -0.48816, -0.24107, -0.05122, -0.01004, -0.03662, 0.01328, 0.12453, 0.07245, 0.10269, 0.09219, 0.10006, 0.21531, 0.29806, 0.32014, 0.42019, 0.48604, 0.44386, 0.47831, 0.49816, 0.35744, 0.26778, 0.09092, -0.11273, -0.45168, -0.68087, -0.75616, -0.83638, -0.94157, -0.98111, -1.01512, -1.00158, -0.95130, -1.05004, -1.18287, -1.31623, -1.45271, -1.68160, -1.83518, -1.79640, -1.81202, -1.86126, -1.85098, -1.76657, -1.60581, -1.72500, -1.94032, -2.12495, -2.29029, -2.54165, -2.69958, -2.66602, -2.63489, -2.52958, -2.40630, -2.31689, -2.26414, -2.28742, -2.38337, -2.57395, -2.59501, -2.37461, -2.05038, -1.83022, -1.62359, -1.46324, -1.27089, -1.16587, -1.13862, -1.25176, -1.37895, -1.39103, -1.34514, -1.22255, -1.12529, -1.16152, -1.10476, -1.14644, -1.12219, -0.86599, -0.50045, -0.30475, -0.16207, -0.01878, -0.15015, -0.24400, -0.20460, -0.18680, -0.13849, -0.11539, 0.02395, 0.07341, 0.13007, 0.16772, 0.22079, 0.21501, 0.28935, 0.28982, 0.35792, 0.48282, 0.57087, 0.44306, 0.31823, 0.43826, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.41680, 1.70874, 1.77809, 1.77737, 1.86783, 1.86697, 1.77340, 1.53468, 1.15159, 0.88072, 0.65980, 0.65911, 0.49539, 0.34813, 0.33449, 0.45590, 0.45201, 0.50492, 0.43852, 0.35460, 0.25286, 0.28983, 0.25432, 0.05000, -0.13999, -0.28086, -0.47754, -0.57803, -0.79750, -0.89303, -1.07539, -1.30839, -1.45168, -1.59339, -1.86559, -2.12127, -2.25641, -2.47018, -2.66893, -2.71781, -2.73629, -2.57234, -2.48734, -2.27264, -2.19879, -2.09883, -1.94310, -1.69295, -1.54423, -1.41277, -1.48291, -1.49358, -1.33153, -1.07855, -0.98188, -1.01305, -0.97764, -0.76382, -0.64585, -0.49014, -0.38719, -0.13789, 0.00935, -0.00655, 0.04894, 0.24576, 0.29144, +0.34843, 0.42849, 0.57772, 0.58045, 0.46499, 0.37740, 0.27602, 0.16099, 0.02812, 0.06574, 0.25297, 0.28664, 0.30240, 0.44703, 0.62716, 0.62276, 0.58302, 0.55934, 0.50781, 0.51835, 0.36350, 0.19050, 0.11870, 0.11667, 0.05717, -0.07247, -0.24813, -0.36661, -0.44750, -0.52690, -0.58467, -0.69996, -0.77125, -0.76188, -0.58261, -0.44079, -0.30701, -0.19213, -0.21224, -0.23629, -0.24260, -0.29718, -0.38897, -0.60071, -0.72472, -0.64759, -0.62247, -0.85400, -1.07062, -1.08043, -1.08951, -1.01432, -0.94077, -0.84668, -0.69815, -0.59706, -0.42498, -0.27408, -0.12327, 0.00018, 0.15267, 0.30987, 0.52891, 0.66992, 0.68230, 0.69040, 0.90829, 0.95824, 0.97242, 1.12178, 1.24520, 1.20709, 1.07591, 0.94368, 0.98353, 0.96272, 0.98816, 1.15191, 1.35189, 1.43100, 1.37023, 1.35177, 1.32732, 1.43754, 1.50794, 1.45791, 1.52906, 1.65515, 1.76725, 1.69457, 1.45915, 1.15205, 1.02555, 0.87237, 0.86502, 0.89485, 0.91195, 0.81598, 0.80877, 0.73746, 0.65528, 0.57608, 0.42849, 0.27329, 0.25913, 0.31784, 0.47876, 0.45259, 0.46918, 0.63775, 0.74298, 0.70823, 0.62869, 0.66986, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.96639, -0.83897, -0.84694, -0.81309, -0.72353, -0.53295, -0.26110, -0.11118, 0.01374, 0.11882, 0.28822, 0.29568, 0.28420, 0.22663, 0.27344, 0.20610, 0.25457, 0.40025, 0.57265, 0.57249, 0.57896, 0.52191, 0.41817, 0.41025, 0.39260, 0.22282, 0.19245, 0.17768, 0.20651, 0.13542, -0.02826, -0.07206, -0.07320, -0.01981, 0.01676, 0.14794, 0.26983, 0.32768, 0.40877, 0.36649, 0.40200, 0.44962, 0.48881, 0.46846, 0.45699, 0.26593, 0.16097, 0.05149, 0.05495, 0.04185, 0.01136, -0.01636, 0.13889, 0.26526, 0.23986, 0.17499, 0.20493, 0.08617, -0.09156, -0.32151, -0.35985, -0.28550, -0.34788, -0.37117, -0.27373, -0.08250, -0.05241, -0.07313, -0.20082, -0.33943, -0.31528, -0.42705, -0.45779, -0.45012, -0.47116, -0.59318, -0.70804, -0.71727, -0.59396, -0.56673, -0.55904, -0.42906, -0.25887, -0.13986, -0.05587, -0.03977, -0.03894, 0.01187, 0.07664, 0.02659, 0.05015, 0.08143, 0.17023, 0.29421, 0.31913, 0.33677, 0.44249, 0.52443, 0.49630, 0.49242, 0.48161, 0.36809, 0.23960, -0.02085, -0.27557, -0.54933, -0.70465, -0.74184, -0.78847, -0.95039, -1.10967, -1.18982, -1.19742, -1.13185, -1.17155, -1.33154, -1.44158, -1.49924, -1.73123, -1.93858, -1.97196, -1.93891, -1.93520, -1.93680, -1.89596, -1.76269, -1.83676, -1.98260, -2.16647, -2.32422, -2.52413, -2.69689, -2.67839, -2.58725, -2.42909, -2.35715, -2.28368, -2.07805, -1.91108, -1.87812, -1.98067, -1.99675, -1.83885, -1.54939, -1.33897, -1.10719, -0.87868, -0.76716, -0.81971, -0.86374, -1.00894, -1.11062, -1.10588, -1.05222, -0.97545, -0.92548, -0.94405, -0.92862, -1.00508, -0.94867, -0.69454, -0.36060, -0.20033, -0.14110, -0.07955, -0.18130, -0.15033, -0.03827, 0.02424, 0.14273, 0.23848, 0.38021, 0.40864, 0.38036, 0.29922, 0.31790, 0.38315, 0.53089, 0.57458, 0.54688, 0.51845, 0.63076, 0.55475, 0.42721, 0.45203, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.64509, 1.90465, 1.96737, 1.83300, 1.78268, 1.78580, 1.78981, 1.60026, 1.20262, 0.97453, 0.86607, 0.87465, 0.74180, 0.61038, 0.55840, 0.64281, 0.58869, 0.58650, 0.54563, 0.44853, 0.24030, 0.22190, 0.12131, -0.07050, -0.22391, -0.34327, -0.47352, -0.52576, -0.69864, -0.80377, -1.06104, -1.31942, -1.47367, -1.62828, -1.77254, -1.96395, -2.11881, -2.34158, -2.51187, -2.56421, -2.66398, -2.54403, -2.37204, -2.12883, -1.94447, -1.80037, -1.75474, -1.60747, -1.49637, -1.30792, -1.25823, -1.29244, -1.33618, -1.14651, -1.02418, -1.01962, -1.00001, -0.81012, -0.66307, -0.51199, -0.40326, -0.16751, -0.09098, -0.20486, -0.19042, -0.01862, 0.13429, +0.30578, 0.39114, 0.46363, 0.52915, 0.49809, 0.31573, 0.25513, 0.11968, -0.02386, 0.09636, 0.25603, 0.34326, 0.47084, 0.52472, 0.62952, 0.65297, 0.67271, 0.64345, 0.54937, 0.58277, 0.47755, 0.27914, 0.17282, 0.14951, 0.09586, 0.02938, -0.08895, -0.25191, -0.33466, -0.24072, -0.24260, -0.29056, -0.27019, -0.26659, -0.22145, -0.10741, 0.11141, 0.11790, 0.09553, 0.05210, -0.02119, 0.05178, 0.01350, -0.14973, -0.18502, -0.21402, -0.30912, -0.51146, -0.67929, -0.68866, -0.78464, -0.73997, -0.64634, -0.55307, -0.44697, -0.40094, -0.34746, -0.24259, -0.04862, 0.08056, 0.16605, 0.42779, 0.61383, 0.71461, 0.78054, 0.79156, 0.94791, 1.00689, 1.17957, 1.28498, 1.41615, 1.42064, 1.21920, 1.13854, 1.13918, 1.10042, 1.19668, 1.31149, 1.42468, 1.56672, 1.56187, 1.57811, 1.48303, 1.58867, 1.68526, 1.62739, 1.56935, 1.57689, 1.61405, 1.59093, 1.46421, 1.23802, 1.03025, 0.93644, 0.84167, 0.77254, 0.83686, 0.73534, 0.64845, 0.50895, 0.54585, 0.48832, 0.39265, 0.30053, 0.19433, 0.30037, 0.47276, 0.48588, 0.62240, 0.79238, 0.78146, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.87122, -0.91410, -0.78835, -0.77512, -0.70312, -0.76445, -0.68126, -0.42179, -0.20762, -0.06348, 0.07137, 0.21162, 0.23674, 0.22781, 0.24924, 0.22293, 0.20583, 0.27344, 0.33991, 0.57584, 0.68869, 0.72563, 0.56818, 0.52733, 0.47509, 0.35082, 0.23154, 0.11294, 0.11198, 0.16432, 0.06971, -0.01567, 0.00832, -0.11040, -0.10476, -0.13249, 0.00934, 0.08329, 0.12771, 0.24014, 0.27822, 0.29869, 0.34795, 0.34538, 0.33874, 0.35906, 0.28304, 0.13988, 0.07352, 0.13657, 0.06691, 0.07644, 0.09315, 0.22311, 0.22941, 0.26788, 0.23768, 0.19373, 0.14471, -0.11140, -0.37108, -0.38086, -0.32819, -0.32138, -0.28069, -0.36543, -0.27010, -0.21090, -0.11567, -0.20676, -0.34666, -0.31940, -0.42403, -0.55357, -0.58664, -0.63995, -0.75873, -0.83758, -0.74736, -0.64587, -0.53341, -0.39227, -0.33818, -0.19421, -0.07640, -0.03391, -0.12668, -0.07145, 0.04365, 0.01890, 0.03708, 0.06812, 0.12405, 0.30215, 0.37940, 0.36344, 0.41571, 0.42129, 0.43910, 0.43868, 0.50415, 0.47681, 0.31329, 0.17891, -0.04582, -0.33837, -0.63367, -0.81584, -0.88625, -0.91675, -0.99533, -1.19413, -1.32019, -1.25164, -1.25293, -1.29157, -1.36576, -1.43830, -1.55214, -1.74934, -1.87209, -2.00335, -1.94094, -1.95931, -2.05596, -2.03853, -1.98337, -2.01390, -2.00493, -2.18067, -2.36589, -2.50795, -2.63735, -2.63570, -2.57609, -2.37605, -2.23783, -2.13927, -1.91119, -1.67410, -1.52571, -1.49749, -1.42437, -1.29489, -1.10338, -0.82287, -0.66084, -0.48920, -0.34984, -0.42854, -0.56380, -0.70125, -0.68250, -0.75179, -0.72194, -0.71885, -0.79414, -0.75726, -0.78096, -0.86216, -0.73136, -0.56192, -0.35911, -0.20136, -0.11727, -0.02511, -0.13962, -0.04603, 0.13188, 0.23737, 0.35976, 0.45778, 0.56941, 0.62725, 0.63238, 0.55626, 0.49418, 0.67049, 0.80121, 0.79368, 0.82026, 0.80617, 0.87253, 0.77291, 0.72048, 0.59156, 0.67519, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.89271, 1.95777, 1.82437, 1.79836, 1.73435, 1.78093, 1.70516, 1.38229, 1.11957, 0.97413, 0.91094, 0.80340, 0.71040, 0.70148, 0.68390, 0.69419, 0.66756, 0.56689, 0.53398, 0.34772, 0.23468, -0.01547, -0.12214, -0.28464, -0.40944, -0.45802, -0.58194, -0.70131, -0.80911, -1.08838, -1.27484, -1.42098, -1.65441, -1.73637, -1.87028, -1.91506, -2.14045, -2.29078, -2.32242, -2.40106, -2.35126, -2.21158, -2.01599, -1.78862, -1.60910, -1.50818, -1.46570, -1.29153, -1.07947, -1.10520, -1.14620, -1.25099, -1.14148, -1.10761, -0.96122, -0.90379, -0.78132, -0.61552, -0.64022, -0.58638, -0.36944, -0.34758, -0.43435, -0.41448, -0.37286, -0.17440, +0.25168, 0.29717, 0.41386, 0.53775, 0.49384, 0.31477, 0.24823, 0.11915, 0.02537, 0.14791, 0.29855, 0.39617, 0.47226, 0.48870, 0.59751, 0.64376, 0.63781, 0.57612, 0.47967, 0.48532, 0.37503, 0.20520, 0.17270, 0.19482, 0.12613, 0.06651, 0.04889, 0.02960, -0.05393, -0.00754, 0.06618, 0.12326, 0.17207, 0.13069, 0.13945, 0.26961, 0.43722, 0.42177, 0.43696, 0.40425, 0.34391, 0.46953, 0.49635, 0.37695, 0.26353, 0.11729, 0.00962, -0.14703, -0.34764, -0.47681, -0.62426, -0.59515, -0.49924, -0.39634, -0.26766, -0.22481, -0.28680, -0.28178, -0.04325, 0.24370, 0.33880, 0.47694, 0.61316, 0.69645, 0.75215, 0.74322, 0.91990, 1.12264, 1.33086, 1.42050, 1.53181, 1.53888, 1.38470, 1.33144, 1.32361, 1.30756, 1.36238, 1.41626, 1.52851, 1.65723, 1.62100, 1.58077, 1.51482, 1.63400, 1.71783, 1.63826, 1.55948, 1.54835, 1.52739, 1.48048, 1.44166, 1.40612, 1.19602, 0.95214, 0.73386, 0.59971, 0.62488, 0.49865, 0.45399, 0.45406, 0.50296, 0.47681, 0.42887, 0.33799, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.10233, -0.31443, -0.47589, -0.60735, -0.80690, -0.86476, -0.78770, -0.76226, -0.80899, -0.87213, -0.88689, -0.73561, -0.74141, -0.77913, -0.89128, -0.85025, -0.62551, -0.41084, -0.21077, 0.00103, 0.13856, 0.12642, 0.07281, 0.19479, 0.19694, 0.10898, 0.18699, 0.28560, 0.54406, 0.68791, 0.73011, 0.67766, 0.61980, 0.47598, 0.32417, 0.21041, 0.07474, 0.06148, 0.10434, 0.07155, 0.01188, -0.02048, -0.13122, -0.12685, -0.23482, -0.23404, -0.17432, -0.08377, 0.07179, 0.11437, 0.12981, 0.19517, 0.18857, 0.17136, 0.20242, 0.28824, 0.23008, 0.06767, 0.04971, -0.00181, 0.04523, 0.04736, 0.12957, 0.23210, 0.33820, 0.30561, 0.23252, 0.12920, -0.15009, -0.37207, -0.35846, -0.27068, -0.27303, -0.32677, -0.44750, -0.35058, -0.28557, -0.23366, -0.28995, -0.38599, -0.35777, -0.50187, -0.71991, -0.77903, -0.84972, -0.95285, -0.96180, -0.73950, -0.53826, -0.44076, -0.34131, -0.29928, -0.19804, -0.15854, -0.16136, -0.15389, -0.03894, 0.02588, -0.00942, 0.03599, 0.11594, 0.25511, 0.47862, 0.56542, 0.47509, 0.40121, 0.38855, 0.46217, 0.49386, 0.47211, 0.36210, 0.15859, 0.01862, -0.19775, -0.49599, -0.75147, -0.93745, -1.07918, -1.15190, -1.13809, -1.22195, -1.40835, -1.44041, -1.43793, -1.42378, -1.46836, -1.57942, -1.66323, -1.76043, -1.85829, -1.97302, -1.92474, -1.98486, -2.09335, -2.09195, -2.03439, -2.04264, -2.05285, -2.18187, -2.28448, -2.37495, -2.55867, -2.67369, -2.64487, -2.43711, -2.23067, -2.03985, -1.73567, -1.41495, -1.18845, -1.09479, -0.93664, -0.73485, -0.63497, -0.46300, -0.31390, -0.16852, -0.09823, -0.23448, -0.33929, -0.34695, -0.30920, -0.38107, -0.39246, -0.49036, -0.59296, -0.52287, -0.50252, -0.55505, -0.52383, -0.46820, -0.31088, -0.15730, -0.10953, -0.08848, -0.17135, -0.05384, 0.12234, 0.23530, 0.40952, 0.55929, 0.65256, 0.70179, 0.77235, 0.85711, 0.79682, 0.84222, 0.92102, 0.94500, 1.01154, 1.01108, 1.09486, 1.10773, 1.04233, 0.86428, 0.90481, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.94300, 1.83004, 1.76614, 1.69055, 1.75548, 1.73816, 1.45516, 1.20417, 1.02804, 0.89233, 0.77593, 0.72875, 0.82705, 0.76256, 0.64720, 0.58996, 0.52620, 0.51913, 0.32114, 0.14785, -0.06826, -0.18068, -0.31463, -0.37330, -0.40599, -0.54428, -0.65795, -0.78759, -1.01620, -1.21556, -1.42492, -1.61151, -1.64646, -1.77995, -1.88753, -2.07487, -2.19317, -2.22484, -2.30657, -2.24823, -2.07319, -1.89966, -1.73132, -1.57479, -1.33474, -1.24508, -1.15373, -0.99585, -1.03137, -1.09213, -1.24890, -1.19521, -1.07000, -0.88080, -0.80452, -0.70033, -0.59724, -0.72143, -0.75384, -0.60985, -0.57686, -0.64122, -0.66859, -0.63250, -0.38385, +0.50555, 0.43085, 0.39365, 0.47152, 0.41704, 0.28549, 0.26218, 0.17114, 0.08379, 0.11188, 0.21948, 0.26966, 0.28901, 0.37078, 0.46216, 0.50627, 0.56135, 0.53095, 0.46026, 0.44098, 0.32885, 0.21234, 0.29025, 0.31447, 0.19546, 0.14947, 0.15501, 0.23503, 0.31271, 0.32726, 0.34755, 0.50325, 0.62234, 0.57317, 0.51401, 0.61771, 0.69785, 0.64837, 0.74952, 0.79087, 0.72622, 0.77650, 0.77708, 0.67117, 0.47865, 0.34692, 0.27646, 0.19062, 0.05460, -0.16752, -0.36938, -0.33120, -0.25985, -0.19574, -0.02999, 0.01787, -0.10965, -0.10452, 0.11557, 0.43892, 0.69276, 0.76939, 0.74984, 0.82390, 0.91199, 0.90161, 0.95850, 1.18386, 1.38686, 1.44382, 1.54359, 1.57938, 1.46427, 1.38950, 1.34974, 1.33656, 1.32932, 1.44872, 1.56839, 1.62055, 1.60875, 1.58826, 1.58592, 1.72704, 1.78578, 1.69264, 1.69256, 1.73430, 1.64127, 1.56715, 1.47177, 1.38450, 1.25575, 1.06139, 0.74568, 0.60148, 0.57288, 0.41899, 0.32461, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.02276, -0.05446, -0.11892, -0.33388, -0.51253, -0.62672, -0.80909, -0.87767, -0.88406, -0.89004, -1.01247, -1.02001, -0.92680, -0.79992, -0.79461, -0.84203, -0.89756, -0.80860, -0.62307, -0.46809, -0.28370, -0.04982, 0.03511, 0.08087, 0.05784, 0.07472, 0.08707, 0.11263, 0.17671, 0.33727, 0.63084, 0.79036, 0.69710, 0.59607, 0.50103, 0.30114, 0.18679, 0.17914, 0.05480, -0.03529, -0.05493, -0.01289, -0.12496, -0.17754, -0.19933, -0.20090, -0.29449, -0.29166, -0.19954, -0.01337, 0.19739, 0.19965, 0.18229, 0.24264, 0.21409, 0.23661, 0.28464, 0.31729, 0.28690, 0.19903, 0.04011, -0.04636, 0.03822, 0.06888, 0.01532, 0.04436, 0.20043, 0.20185, 0.11797, 0.00441, -0.26138, -0.45203, -0.46322, -0.37325, -0.45710, -0.54485, -0.52951, -0.39846, -0.31791, -0.25961, -0.31048, -0.36826, -0.31445, -0.40601, -0.61405, -0.69324, -0.86878, -0.96605, -0.87591, -0.70075, -0.49639, -0.30544, -0.30954, -0.31884, -0.22685, -0.17453, -0.20835, -0.19759, -0.05654, -0.05327, -0.07622, 0.04877, 0.15699, 0.30615, 0.51075, 0.62764, 0.49532, 0.37383, 0.46729, 0.61157, 0.67573, 0.61528, 0.43001, 0.17993, 0.06647, -0.11676, -0.41092, -0.62114, -0.87736, -1.11606, -1.23901, -1.32006, -1.41016, -1.49460, -1.61508, -1.68196, -1.57349, -1.52555, -1.71243, -1.92493, -1.97797, -2.02003, -2.08487, -2.03192, -2.11724, -2.22581, -2.20905, -2.10132, -2.11615, -2.18618, -2.21207, -2.25009, -2.27837, -2.33738, -2.45099, -2.47439, -2.30762, -2.05683, -1.76709, -1.38770, -1.06662, -0.86178, -0.72177, -0.59156, -0.45456, -0.26458, -0.06227, 0.05913, 0.22711, 0.25063, 0.05770, -0.15065, -0.16876, -0.14901, -0.19339, -0.17526, -0.26191, -0.34866, -0.27880, -0.19517, -0.23037, -0.34897, -0.31485, -0.20471, -0.05111, 0.05786, 0.06493, 0.00088, 0.10806, 0.25391, 0.33939, 0.54271, 0.70438, 0.75358, 0.81559, 0.86727, 0.96007, 1.03538, 1.05945, 0.99599, 1.10008, 1.26818, 1.31184, 1.27890, 1.28182, 1.24305, 1.13459, 1.20129, 1.29459, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.95797, 1.95132, 1.95911, 1.89039, 1.93975, 1.89923, 1.60352, 1.35934, 1.11965, 0.90169, 0.85411, 0.83247, 0.82526, 0.76117, 0.68546, 0.52018, 0.47696, 0.50405, 0.35479, 0.07117, -0.16450, -0.24036, -0.30096, -0.24744, -0.23316, -0.43334, -0.63103, -0.83358, -0.97917, -1.20657, -1.36518, -1.47297, -1.53267, -1.63121, -1.75497, -1.92703, -2.01524, -2.04562, -2.15002, -2.08610, -1.87971, -1.76380, -1.64421, -1.55843, -1.38841, -1.20214, -1.01452, -1.00425, -1.05205, -1.05786, -1.11833, -1.16863, -1.11815, -0.96597, -0.92010, -0.83716, -0.70828, -0.80980, -0.90784, -0.90708, -0.88028, -0.93202, -0.86886, -0.76408, -0.55962, +0.70513, 0.63671, 0.50313, 0.48179, 0.48260, 0.44907, 0.36720, 0.26007, 0.24445, 0.28276, 0.25419, 0.20617, 0.29762, 0.41365, 0.37938, 0.31364, 0.44580, 0.52315, 0.51314, 0.54465, 0.46987, 0.37684, 0.40302, 0.36502, 0.28730, 0.28465, 0.24767, 0.27172, 0.42108, 0.49201, 0.47455, 0.57404, 0.76173, 0.89543, 0.94533, 1.03770, 1.08742, 1.02407, 1.02527, 1.01918, 1.01327, 1.07201, 0.94237, 0.74635, 0.64043, 0.59837, 0.49893, 0.37077, 0.33255, 0.18789, -0.01933, 0.03597, 0.06049, 0.04049, 0.13487, 0.15908, 0.13844, 0.26985, 0.46558, 0.67729, 0.95224, 1.02535, 0.93430, 0.90916, 1.04245, 1.17380, 1.18773, 1.33113, 1.50863, 1.60593, 1.65147, 1.63288, 1.60809, 1.63762, 1.53837, 1.37535, 1.39121, 1.57787, 1.61122, 1.52408, 1.54795, 1.64605, 1.67317, 1.82603, 1.88072, 1.78642, 1.78365, 1.79828, 1.73835, 1.70858, 1.52226, 1.23647, 1.09023, 1.01512, 0.78267, 0.58350, 0.48900, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.01482, -0.02273, 0.09014, 0.20094, 0.09402, -0.01792, -0.10847, -0.25699, -0.48053, -0.72760, -0.89607, -0.87017, -0.90524, -1.05942, -1.15634, -1.02684, -0.94543, -0.97822, -0.98275, -0.88925, -0.87083, -0.73053, -0.57569, -0.50095, -0.40996, -0.31375, -0.23843, -0.02459, 0.07594, -0.02941, -0.07080, 0.00336, 0.07780, 0.20098, 0.46227, 0.70904, 0.60474, 0.44789, 0.31171, 0.19538, 0.13323, 0.07894, -0.00453, -0.00565, -0.01761, -0.09544, -0.25459, -0.24146, -0.25795, -0.36149, -0.41907, -0.24244, -0.08083, 0.17483, 0.40333, 0.36609, 0.31266, 0.28572, 0.31319, 0.47487, 0.55080, 0.44223, 0.33380, 0.29037, 0.11710, -0.06424, -0.06503, 0.03508, -0.02449, -0.08406, 0.03318, 0.12412, 0.08662, -0.09328, -0.32837, -0.40544, -0.41959, -0.52733, -0.69576, -0.68706, -0.62103, -0.59081, -0.55158, -0.38453, -0.38228, -0.38875, -0.28313, -0.26235, -0.37199, -0.53218, -0.77783, -0.84942, -0.74894, -0.70896, -0.61843, -0.42542, -0.44941, -0.52223, -0.49535, -0.32143, -0.20866, -0.15453, -0.01341, 0.04446, 0.08801, 0.15954, 0.21247, 0.40079, 0.63480, 0.65642, 0.51534, 0.53251, 0.67982, 0.73153, 0.71175, 0.70149, 0.56026, 0.33187, 0.28738, 0.14478, -0.15285, -0.44045, -0.76078, -0.97643, -1.11010, -1.33757, -1.56640, -1.63311, -1.77240, -1.93560, -1.89832, -1.76399, -1.83644, -2.05464, -2.12753, -2.10564, -2.11454, -2.16925, -2.32091, -2.35222, -2.24072, -2.18862, -2.27062, -2.25591, -2.20800, -2.28990, -2.32719, -2.16015, -2.07917, -2.10360, -1.97294, -1.77436, -1.51809, -1.21342, -0.95380, -0.71308, -0.50242, -0.41003, -0.38343, -0.10917, 0.21443, 0.35668, 0.46978, 0.50541, 0.41930, 0.17443, 0.03180, 0.01150, 0.03648, 0.03523, -0.04606, -0.02188, 0.13837, 0.17387, 0.01048, -0.09998, -0.03388, -0.01560, 0.07313, 0.26572, 0.37951, 0.32691, 0.43286, 0.56343, 0.61301, 0.74267, 0.83822, 0.92934, 1.04350, 1.03441, 1.00273, 1.12517, 1.21468, 1.12604, 1.18188, 1.39893, 1.58959, 1.53909, 1.49185, 1.48812, 1.50819, 1.54274, 1.51150, 1.55365, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.04452, 2.19021, 2.13903, 2.18142, 2.09374, 1.75029, 1.43996, 1.09593, 0.91870, 0.98972, 0.97264, 0.79661, 0.69649, 0.68429, 0.48758, 0.32399, 0.32660, 0.35202, 0.13197, -0.07887, -0.10505, -0.04699, 0.01056, -0.09931, -0.32742, -0.47684, -0.70233, -0.91897, -1.07942, -1.10451, -1.22354, -1.40792, -1.47897, -1.47756, -1.63008, -1.68071, -1.69806, -1.84710, -1.86371, -1.76895, -1.65652, -1.47686, -1.42549, -1.43591, -1.29142, -1.07180, -1.11937, -1.25358, -1.26567, -1.14891, -1.17050, -1.19989, -1.13338, -1.07667, -1.03808, -0.99393, -0.97453, -0.92327, -0.97011, -1.12087, -1.16662, -0.95490, -0.84994, -0.82034, +0.79058, 0.68148, 0.58598, 0.49697, 0.49344, 0.51120, 0.40543, 0.43869, 0.43698, 0.38861, 0.32983, 0.36866, 0.49290, 0.47698, 0.43340, 0.38954, 0.45976, 0.52388, 0.56830, 0.68162, 0.69573, 0.58497, 0.57127, 0.57148, 0.42947, 0.37340, 0.34459, 0.32617, 0.45914, 0.53854, 0.62304, 0.72269, 0.83183, 1.04670, 1.26659, 1.39595, 1.38486, 1.28510, 1.13895, 1.20630, 1.22895, 1.16970, 1.00146, 0.88024, 0.85394, 0.72651, 0.64667, 0.58982, 0.54123, 0.38815, 0.19755, 0.25523, 0.28578, 0.21163, 0.26697, 0.40056, 0.40346, 0.52833, 0.78301, 0.97573, 1.18267, 1.18537, 1.12670, 1.10572, 1.15482, 1.30129, 1.33220, 1.44546, 1.53128, 1.67217, 1.68847, 1.81574, 1.91384, 1.88686, 1.78516, 1.65061, 1.69590, 1.71132, 1.67967, 1.65929, 1.65556, 1.68891, 1.68973, 1.82538, 1.91864, 1.84187, 1.78744, 1.87173, 1.81272, 1.70982, 1.56105, 1.25862, 1.06251, 0.96959, 0.83185, 0.68658, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.36601, 0.20384, 0.23392, 0.33407, 0.26462, 0.26321, 0.21035, 0.26218, 0.16253, 0.10245, -0.07821, -0.19605, -0.48379, -0.72112, -0.80831, -0.88735, -0.95642, -1.07165, -1.04470, -0.99288, -1.01321, -1.01563, -1.00147, -0.93305, -0.92780, -0.81109, -0.67601, -0.62602, -0.60897, -0.49275, -0.41189, -0.27822, -0.07883, -0.10767, -0.14671, -0.13646, -0.11299, 0.07534, 0.24726, 0.47012, 0.40448, 0.32927, 0.11822, 0.05684, -0.01266, -0.04504, 0.01912, -0.02212, -0.07332, -0.16065, -0.23650, -0.29892, -0.41602, -0.45745, -0.45044, -0.28140, -0.11089, 0.15475, 0.37803, 0.36570, 0.28226, 0.33899, 0.49265, 0.59127, 0.67800, 0.60163, 0.47677, 0.40928, 0.22399, 0.09702, -0.03225, -0.03006, -0.10515, -0.12275, -0.09979, 0.00983, 0.00907, -0.10475, -0.15328, -0.26198, -0.39524, -0.60452, -0.71655, -0.75165, -0.84668, -0.82389, -0.74683, -0.58803, -0.54311, -0.48393, -0.32599, -0.19466, -0.25020, -0.35141, -0.52989, -0.76666, -0.77300, -0.73747, -0.68466, -0.53353, -0.58990, -0.60357, -0.63140, -0.48053, -0.28318, -0.09440, 0.04977, 0.14756, 0.23678, 0.29315, 0.45160, 0.58047, 0.68531, 0.65626, 0.63044, 0.68599, 0.69560, 0.72370, 0.71142, 0.66005, 0.52179, 0.35102, 0.37029, 0.29066, -0.02327, -0.29339, -0.51239, -0.79678, -0.98742, -1.19936, -1.46843, -1.59126, -1.81301, -1.98567, -2.03923, -1.99792, -2.00162, -2.08484, -2.16106, -2.17289, -2.18452, -2.31646, -2.34369, -2.35739, -2.37037, -2.35872, -2.33524, -2.22595, -2.24230, -2.26446, -2.17822, -1.94341, -1.80713, -1.81658, -1.70627, -1.57550, -1.44952, -1.21592, -0.88072, -0.66900, -0.47225, -0.29602, -0.22018, 0.09895, 0.43708, 0.65502, 0.78233, 0.73592, 0.67137, 0.47220, 0.28127, 0.15687, 0.19784, 0.15199, 0.22283, 0.32497, 0.36970, 0.34258, 0.20191, 0.14678, 0.08035, 0.09390, 0.28648, 0.47484, 0.55809, 0.51824, 0.64000, 0.80660, 0.84588, 0.93872, 1.12509, 1.19906, 1.22654, 1.23963, 1.21223, 1.32841, 1.40982, 1.38473, 1.46408, 1.57689, 1.77383, 1.77892, 1.78810, 1.72939, 1.78423, 1.74592, 1.77875, 1.85743, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.27463, 2.22765, 2.27944, 2.21307, 1.85943, 1.48257, 1.21763, 1.05382, 1.02489, 1.03840, 0.88065, 0.76348, 0.70552, 0.51632, 0.37425, 0.26728, 0.31930, 0.19324, 0.10664, 0.03606, 0.13131, 0.09033, -0.02601, -0.19492, -0.46121, -0.69326, -0.84570, -0.88069, -0.97627, -1.12573, -1.20009, -1.22714, -1.24210, -1.37084, -1.38398, -1.35944, -1.51036, -1.62669, -1.51062, -1.40340, -1.33507, -1.26423, -1.29761, -1.23559, -1.12986, -1.22312, -1.30160, -1.43231, -1.36708, -1.36980, -1.32702, -1.35573, -1.28685, -1.31061, -1.23982, -1.04216, -1.01554, -1.09851, -1.25938, -1.23606, -1.10489, -1.07744, -1.00772, +0.96911, 0.79252, 0.67325, 0.56693, 0.56394, 0.61014, 0.48308, 0.43988, 0.42710, 0.42010, 0.39701, 0.44191, 0.53221, 0.53075, 0.61000, 0.63675, 0.65080, 0.69557, 0.72320, 0.81715, 0.90520, 0.87049, 0.79680, 0.67024, 0.50035, 0.40637, 0.36498, 0.39541, 0.50532, 0.58327, 0.79381, 0.99513, 1.07254, 1.27124, 1.54484, 1.70404, 1.66950, 1.55272, 1.33749, 1.26044, 1.21052, 1.14319, 1.02418, 0.93714, 0.89028, 0.77621, 0.79379, 0.80043, 0.69358, 0.49869, 0.30026, 0.31857, 0.41794, 0.42616, 0.43284, 0.49891, 0.55262, 0.72372, 0.98340, 1.22650, 1.36860, 1.29136, 1.24033, 1.27759, 1.31786, 1.40310, 1.38956, 1.44311, 1.48947, 1.64501, 1.70579, 1.81292, 1.97415, 2.07256, 2.07831, 1.99960, 1.97275, 1.88607, 1.85426, 1.89050, 1.85568, 1.84942, 1.79594, 1.78293, 1.84609, 1.84448, 1.78308, 1.81424, 1.77337, 1.70008, 1.60916, 1.41751, 1.17629, 0.99452, 0.87226, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.89243, 0.89855, 0.85262, 0.86941, 0.79508, 0.65608, 0.60258, 0.56777, 0.62742, 0.64027, 0.50729, 0.48935, 0.36326, 0.32269, 0.20424, 0.14263, -0.02354, -0.13581, -0.37619, -0.65947, -0.80162, -0.88526, -0.95731, -1.03556, -0.99313, -0.97751, -1.00391, -0.97054, -0.97737, -0.93135, -0.92430, -0.89630, -0.82454, -0.73607, -0.66281, -0.61779, -0.61023, -0.51700, -0.33507, -0.25342, -0.23886, -0.26922, -0.29934, -0.09720, 0.04247, 0.21601, 0.21039, 0.17837, -0.00451, -0.05619, -0.09342, -0.18069, -0.18284, -0.22711, -0.24755, -0.27653, -0.30259, -0.41678, -0.55787, -0.51126, -0.46110, -0.29363, -0.12014, 0.07295, 0.24480, 0.28521, 0.25066, 0.31003, 0.49907, 0.61074, 0.64473, 0.60761, 0.52021, 0.41726, 0.20640, 0.11805, -0.00826, -0.06332, -0.12684, -0.12347, -0.11980, -0.04367, -0.01150, -0.09051, -0.09983, -0.15770, -0.32114, -0.61336, -0.79219, -0.91927, -1.05100, -0.95495, -0.86656, -0.69755, -0.54444, -0.46287, -0.33744, -0.15506, -0.12511, -0.23059, -0.42045, -0.67529, -0.79393, -0.79511, -0.75325, -0.65691, -0.71756, -0.67730, -0.65265, -0.50165, -0.27216, -0.03145, 0.12249, 0.21535, 0.36454, 0.45547, 0.60920, 0.69775, 0.72857, 0.66134, 0.64918, 0.66338, 0.62552, 0.69977, 0.68922, 0.60115, 0.48856, 0.34570, 0.35200, 0.29451, 0.02638, -0.26182, -0.48332, -0.73926, -0.96342, -1.16030, -1.35520, -1.51041, -1.78214, -1.95371, -2.02843, -2.05499, -2.07482, -2.09115, -2.11715, -2.12685, -2.17074, -2.37166, -2.46401, -2.48066, -2.47115, -2.43157, -2.37947, -2.23887, -2.15805, -2.02576, -1.86032, -1.64010, -1.48570, -1.51435, -1.47576, -1.39683, -1.33342, -1.22255, -0.99835, -0.76932, -0.51830, -0.26483, -0.03270, 0.32412, 0.64041, 0.88998, 1.03963, 0.95039, 0.86825, 0.72618, 0.58503, 0.41911, 0.39867, 0.33369, 0.37449, 0.47901, 0.52236, 0.47121, 0.30652, 0.19810, 0.09795, 0.21049, 0.49646, 0.63894, 0.68091, 0.62146, 0.68249, 0.85630, 0.95320, 1.04672, 1.21432, 1.32131, 1.37389, 1.40117, 1.45948, 1.55271, 1.56862, 1.58717, 1.75869, 1.87499, 2.00539, 1.99594, 2.03406, 1.99723, 2.06626, 2.05170, 2.01196, 2.08638, 2.15981, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.41684, 2.32740, 2.27105, 2.20712, 1.95177, 1.58747, 1.28861, 1.12561, 1.06851, 1.03975, 0.93053, 0.78877, 0.67467, 0.53837, 0.52191, 0.41255, 0.40469, 0.32046, 0.31636, 0.26931, 0.31233, 0.21527, -0.03809, -0.28000, -0.53264, -0.71101, -0.82285, -0.89273, -1.04719, -1.13994, -1.06491, -1.06414, -1.08804, -1.17114, -1.18861, -1.12437, -1.16515, -1.27146, -1.25739, -1.21740, -1.19770, -1.16052, -1.12869, -1.10692, -1.16980, -1.36083, -1.39106, -1.52893, -1.52825, -1.52820, -1.46582, -1.44546, -1.35394, -1.37512, -1.39619, -1.23631, -1.16588, -1.21761, -1.33663, -1.33988, -1.31073, -1.30403, -1.18157, +1.00964, 0.89967, 0.79152, 0.65391, 0.59525, 0.69584, 0.67667, 0.50359, 0.42808, 0.54371, 0.55527, 0.50062, 0.52816, 0.67251, 0.84195, 0.80536, 0.78364, 0.88074, 0.97407, 0.96785, 0.99255, 1.07070, 1.06000, 0.89969, 0.78037, 0.61551, 0.44796, 0.52492, 0.69343, 0.79363, 1.05362, 1.26129, 1.31052, 1.51993, 1.79990, 1.92377, 1.83233, 1.81460, 1.77707, 1.55068, 1.31245, 1.27516, 1.23442, 1.10698, 0.99966, 0.95980, 1.00590, 0.87958, 0.69036, 0.52062, 0.42397, 0.42477, 0.50288, 0.60427, 0.60045, 0.59113, 0.69956, 0.85990, 0.97283, 1.19494, 1.39452, 1.33046, 1.25894, 1.27334, 1.29214, 1.36242, 1.33433, 1.31950, 1.33695, 1.55154, 1.78857, 1.85490, 1.96266, 2.23700, 2.40606, 2.33870, 2.22057, 2.14666, 2.11620, 1.97269, 1.87724, 1.94024, 1.97641, 1.90036, 1.82051, 1.87254, 1.89248, 1.93839, 1.95382, 1.89654, 1.73196, 1.52781, 1.29974, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.84236, 0.82402, 0.81268, 0.90641, 0.93605, 0.96908, 0.99962, 0.96090, 0.83742, 0.79178, 0.90661, 0.87180, 0.65923, 0.55230, 0.38830, 0.34265, 0.25157, 0.14419, -0.04033, -0.15516, -0.21756, -0.44325, -0.73763, -0.83394, -0.89271, -1.03725, -1.04523, -0.97605, -0.86699, -0.92451, -1.01600, -0.91946, -0.80379, -0.73592, -0.81324, -0.74222, -0.57752, -0.56663, -0.62593, -0.58713, -0.56625, -0.55994, -0.44920, -0.36194, -0.35806, -0.23070, -0.16902, -0.00344, 0.12088, 0.13220, -0.05362, -0.18193, -0.13329, -0.17119, -0.35664, -0.45140, -0.38289, -0.38436, -0.40665, -0.53364, -0.62203, -0.67407, -0.70716, -0.49834, -0.25841, -0.00117, 0.10065, 0.15052, 0.21477, 0.32413, 0.51893, 0.65172, 0.54838, 0.38764, 0.37817, 0.32083, 0.08584, -0.06100, -0.20599, -0.24547, -0.20050, -0.14843, -0.18163, -0.19478, -0.09895, -0.05530, -0.10515, -0.12350, -0.17236, -0.49788, -0.79457, -0.97495, -0.98303, -0.90197, -0.93428, -0.74120, -0.44904, -0.26066, -0.25208, -0.16793, -0.06305, -0.11496, -0.27210, -0.37761, -0.56701, -0.76940, -0.76552, -0.65328, -0.67474, -0.63335, -0.62071, -0.50399, -0.22930, 0.04952, 0.15515, 0.17322, 0.43984, 0.71775, 0.82057, 0.79190, 0.78758, 0.64621, 0.53860, 0.49356, 0.52017, 0.59195, 0.48861, 0.40939, 0.39970, 0.39021, 0.30983, 0.13750, -0.06020, -0.27934, -0.45583, -0.61308, -0.91181, -1.26789, -1.41863, -1.51261, -1.76470, -1.95088, -2.09026, -2.16728, -2.17907, -2.14920, -2.14839, -2.16525, -2.12594, -2.19440, -2.37726, -2.45741, -2.32143, -2.21745, -2.22626, -2.09479, -1.83747, -1.62594, -1.59525, -1.45087, -1.23858, -1.17224, -1.17287, -1.14214, -1.03530, -0.98012, -0.86731, -0.57893, -0.29744, -0.10547, 0.18076, 0.56802, 0.85805, 1.08101, 1.14956, 1.01200, 0.98609, 0.94960, 0.85505, 0.60723, 0.53096, 0.55582, 0.53097, 0.53086, 0.61530, 0.59757, 0.38303, 0.20907, 0.18685, 0.37999, 0.51815, 0.56750, 0.65045, 0.68962, 0.73555, 0.80508, 0.94808, 1.08515, 1.26191, 1.45333, 1.54053, 1.47677, 1.51956, 1.63559, 1.60006, 1.62112, 1.82791, 2.00122, 2.20605, 2.26158, 2.30300, 2.27995, 2.41845, 2.59176, 2.52179, 2.49886, 2.63305, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.57107, 2.43837, 2.27705, 2.13709, 1.87653, 1.56926, 1.38719, 1.28483, 1.09760, 0.88280, 0.75142, 0.64446, 0.56367, 0.59507, 0.45736, 0.41700, 0.37707, 0.39920, 0.33534, 0.30862, 0.31247, 0.04915, -0.33884, -0.55822, -0.65532, -0.83469, -1.02019, -1.16197, -1.11803, -1.07737, -1.11254, -1.08081, -1.05877, -0.99703, -0.97624, -0.91195, -0.91759, -0.94533, -0.96431, -1.01482, -1.12562, -1.16304, -1.09601, -1.18538, -1.43267, -1.49886, -1.63231, -1.59977, -1.53049, -1.46869, -1.42864, -1.36138, -1.29308, -1.33193, -1.36184, -1.29958, -1.27241, -1.36258, -1.36341, -1.34396, -1.29701, -1.32194, +1.00511, 0.89200, 0.80202, 0.70823, 0.71040, 0.80762, 0.80643, 0.68808, 0.58954, 0.66614, 0.76057, 0.76415, 0.71129, 0.79872, 0.99566, 0.97623, 0.90222, 0.94740, 1.04659, 1.05846, 1.11685, 1.21774, 1.25463, 1.16090, 1.05674, 0.88021, 0.74586, 0.86610, 1.03676, 1.13950, 1.36351, 1.53303, 1.53164, 1.66626, 1.94594, 2.09709, 2.04153, 2.06665, 2.08893, 1.89533, 1.56155, 1.40285, 1.42567, 1.41328, 1.25977, 1.09664, 1.10010, 0.98744, 0.77364, 0.56650, 0.49629, 0.55193, 0.64661, 0.71052, 0.64649, 0.59513, 0.66217, 0.79749, 0.90138, 1.14034, 1.36091, 1.32084, 1.23584, 1.24000, 1.21790, 1.18220, 1.13796, 1.16996, 1.29041, 1.56825, 1.82635, 1.93764, 2.02341, 2.25159, 2.52036, 2.61051, 2.46592, 2.29150, 2.22020, 2.05928, 1.92900, 1.93337, 1.99786, 2.01126, 1.95220, 2.01184, 2.03040, 2.08098, 2.07979, 1.99776, 1.80888, 1.60216, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.76065, 0.72353, 0.67194, 0.70300, 0.73188, 0.88602, 0.92534, 0.99479, 1.09968, 1.11904, 1.03649, 1.04637, 1.14547, 1.06702, 0.81925, 0.69607, 0.54949, 0.41826, 0.29805, 0.17074, -0.00630, -0.09148, -0.17024, -0.36652, -0.69412, -0.92151, -1.02215, -1.05651, -1.04096, -1.03464, -0.87876, -0.84359, -0.92187, -0.87129, -0.75971, -0.63524, -0.70836, -0.64090, -0.54543, -0.60680, -0.72434, -0.74720, -0.74023, -0.69476, -0.56709, -0.41162, -0.34200, -0.23280, -0.19806, -0.12849, -0.00271, 0.03928, -0.12558, -0.26631, -0.27142, -0.27195, -0.44816, -0.64171, -0.59305, -0.46131, -0.46053, -0.71554, -0.87016, -0.92284, -0.96066, -0.79307, -0.58031, -0.24662, -0.05109, 0.08440, 0.15982, 0.27631, 0.44981, 0.53314, 0.40539, 0.28918, 0.31867, 0.26043, 0.00817, -0.19601, -0.36326, -0.47091, -0.44250, -0.38016, -0.39871, -0.37808, -0.31641, -0.23125, -0.20700, -0.25442, -0.25905, -0.40398, -0.63203, -0.88055, -0.91725, -0.81668, -0.85904, -0.73783, -0.52419, -0.32259, -0.28038, -0.15169, -0.02191, -0.04464, -0.16508, -0.19718, -0.32929, -0.52055, -0.54595, -0.46426, -0.47492, -0.44834, -0.46678, -0.47993, -0.28827, 0.00097, 0.14396, 0.22680, 0.50250, 0.80817, 0.91083, 0.72634, 0.58333, 0.47965, 0.42713, 0.31398, 0.25923, 0.35145, 0.30277, 0.21550, 0.17820, 0.21038, 0.16348, 0.01759, -0.15955, -0.32363, -0.43376, -0.57807, -0.89182, -1.26415, -1.42213, -1.52728, -1.77897, -1.98959, -2.14666, -2.27425, -2.35932, -2.32084, -2.26430, -2.19104, -2.06731, -2.05186, -2.16651, -2.28210, -2.19431, -1.99485, -1.88922, -1.80259, -1.63950, -1.43549, -1.38782, -1.27149, -1.08764, -0.99070, -0.91004, -0.76901, -0.61280, -0.59529, -0.52644, -0.25939, 0.04096, 0.26865, 0.55405, 0.86322, 1.10722, 1.30302, 1.34851, 1.17016, 1.07010, 1.03862, 0.95034, 0.69345, 0.58424, 0.58178, 0.59690, 0.55050, 0.52518, 0.57804, 0.53197, 0.34799, 0.23740, 0.41413, 0.53926, 0.53605, 0.56366, 0.64213, 0.78220, 0.88989, 1.03600, 1.12802, 1.28209, 1.46034, 1.53792, 1.47667, 1.53753, 1.63693, 1.58222, 1.61660, 1.86805, 2.09911, 2.33358, 2.47200, 2.57561, 2.63666, 2.84730, 3.05402, 3.04874, 2.97296, 2.93109, 2.92489, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.62381, 2.50937, 2.44923, 2.21808, 1.89078, 1.63281, 1.47152, 1.26743, 1.06019, 0.89858, 0.76219, 0.66002, 0.64087, 0.44044, 0.28205, 0.22408, 0.28122, 0.25937, 0.24434, 0.24955, 0.06801, -0.32282, -0.65037, -0.74047, -0.79474, -0.98299, -1.20378, -1.12673, -1.00654, -1.02430, -1.04355, -1.04945, -0.91573, -0.82757, -0.69079, -0.69957, -0.75312, -0.82957, -0.97033, -1.12594, -1.15526, -1.09079, -1.14674, -1.36761, -1.44737, -1.57273, -1.61396, -1.55573, -1.47878, -1.43507, -1.38788, -1.37336, -1.39249, -1.42978, -1.47382, -1.46788, -1.38672, -1.28024, -1.32276, -1.34143, -1.38791, +1.05077, 0.97771, 0.86681, 0.87454, 0.97881, 0.94819, 0.86981, 0.86600, 0.91379, 0.98110, 0.98192, 1.00069, 0.98684, 1.00477, 1.16215, 1.12237, 1.05216, 1.06942, 1.09523, 1.15809, 1.24350, 1.25532, 1.33214, 1.31737, 1.27153, 1.16638, 1.06414, 1.15391, 1.32623, 1.48594, 1.62323, 1.75850, 1.79505, 1.92726, 2.19436, 2.41207, 2.44621, 2.33140, 2.23638, 2.09215, 1.83141, 1.63523, 1.54961, 1.54614, 1.45279, 1.21901, 1.16079, 1.07634, 0.92875, 0.77672, 0.65243, 0.71371, 0.76250, 0.64449, 0.53298, 0.48996, 0.54029, 0.71733, 0.81174, 1.00953, 1.23020, 1.28268, 1.17661, 1.17764, 1.17906, 1.11397, 1.04332, 1.15483, 1.46577, 1.67346, 1.81904, 1.97354, 2.14904, 2.40251, 2.59957, 2.66811, 2.58095, 2.38990, 2.28962, 2.17867, 2.07072, 2.05670, 2.04238, 2.09791, 2.08559, 2.04771, 2.01554, 2.05814, 2.01400, 1.97507, 1.74623, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.50575, 0.62442, 0.77600, 0.83482, 0.70042, 0.72753, 0.81230, 0.75126, 0.66167, 0.52458, 0.57048, 0.68262, 0.79703, 0.80754, 0.93683, 1.07354, 1.21613, 1.17969, 1.18772, 1.22553, 1.19383, 0.95151, 0.84352, 0.79146, 0.66677, 0.51091, 0.33617, 0.24892, 0.09755, -0.16964, -0.45055, -0.74357, -0.93017, -1.09635, -1.16239, -1.08114, -1.06358, -0.92028, -0.78732, -0.82224, -0.74074, -0.71535, -0.64659, -0.67967, -0.69376, -0.74109, -0.83029, -0.99231, -0.93220, -0.84932, -0.77207, -0.68429, -0.45755, -0.34941, -0.26546, -0.19137, -0.13644, -0.05510, -0.06987, -0.14128, -0.31299, -0.49190, -0.54123, -0.60000, -0.66197, -0.65387, -0.60600, -0.62795, -0.92241, -1.14153, -1.16102, -1.16780, -0.95941, -0.81159, -0.50912, -0.20256, -0.04212, -0.02367, 0.11640, 0.23538, 0.35124, 0.25700, 0.18403, 0.19735, 0.17440, -0.05849, -0.31633, -0.45519, -0.54563, -0.55947, -0.60077, -0.54881, -0.48589, -0.55639, -0.51702, -0.39291, -0.32707, -0.30277, -0.43346, -0.57238, -0.75913, -0.85791, -0.77419, -0.81535, -0.70396, -0.62510, -0.53100, -0.41902, -0.23230, -0.10663, -0.05400, -0.15208, -0.09569, -0.14084, -0.30212, -0.37981, -0.30009, -0.28242, -0.30800, -0.32739, -0.37120, -0.25090, -0.04410, 0.20722, 0.41283, 0.54811, 0.71997, 0.79481, 0.62052, 0.42417, 0.23849, 0.22510, 0.15883, 0.02616, 0.10718, 0.11309, 0.08577, 0.01283, -0.04267, -0.05623, -0.17289, -0.39972, -0.48417, -0.53956, -0.64302, -0.89982, -1.26715, -1.48195, -1.59069, -1.80692, -2.08010, -2.20893, -2.26663, -2.33571, -2.32668, -2.20496, -2.02037, -1.96673, -1.98466, -2.00418, -2.01411, -1.94550, -1.83579, -1.69763, -1.57833, -1.53133, -1.38248, -1.28953, -1.08623, -0.85489, -0.80406, -0.65743, -0.43852, -0.33251, -0.30575, -0.22617, 0.03671, 0.39373, 0.63074, 0.84898, 1.08422, 1.34146, 1.48040, 1.55344, 1.44792, 1.31633, 1.18939, 1.04319, 0.84147, 0.61738, 0.51062, 0.58774, 0.62790, 0.59593, 0.58750, 0.59743, 0.50239, 0.34405, 0.44635, 0.56478, 0.57241, 0.60578, 0.64237, 0.83774, 0.99625, 1.05579, 1.10348, 1.25083, 1.39507, 1.49649, 1.40288, 1.42973, 1.52328, 1.58310, 1.65314, 1.94663, 2.28256, 2.60071, 2.78829, 2.93616, 3.14049, 3.26960, 3.35298, 3.38437, 3.34506, 3.23663, 3.10171, 3.02063, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.68310, 2.59131, 2.36371, 2.07503, 1.76794, 1.64765, 1.44594, 1.24923, 1.06444, 0.95778, 0.76895, 0.61166, 0.38985, 0.21800, 0.14088, 0.19157, 0.28916, 0.21550, 0.11143, -0.01894, -0.30010, -0.57550, -0.74276, -0.83477, -0.94551, -1.13932, -1.07072, -0.88640, -0.87701, -0.86739, -0.95980, -0.84799, -0.69115, -0.62228, -0.71464, -0.74580, -0.85940, -0.94545, -1.10296, -1.17140, -1.16162, -1.11085, -1.27164, -1.37000, -1.45007, -1.50999, -1.49847, -1.47659, -1.38640, -1.43949, -1.60114, -1.64567, -1.56417, -1.50783, -1.56337, -1.52940, -1.34532, -1.36746, -1.46717, -1.51315, +1.01131, 1.08481, 0.97760, 0.94913, 1.03717, 1.02879, 1.04841, 1.17226, 1.26250, 1.29080, 1.20221, 1.19461, 1.28924, 1.36258, 1.37116, 1.15789, 1.06783, 1.11181, 1.18407, 1.29110, 1.37768, 1.38162, 1.48846, 1.55354, 1.52804, 1.45907, 1.43948, 1.53240, 1.60473, 1.67547, 1.79150, 1.89161, 1.99050, 2.20592, 2.45868, 2.62648, 2.67598, 2.58876, 2.47193, 2.34143, 2.05753, 1.79426, 1.62172, 1.54602, 1.52715, 1.41176, 1.26428, 1.01818, 0.89232, 0.85332, 0.77505, 0.77104, 0.69100, 0.52055, 0.48078, 0.56086, 0.62463, 0.73412, 0.81369, 0.99882, 1.17376, 1.18942, 1.12277, 1.07994, 1.04356, 1.03142, 0.97030, 1.06541, 1.42412, 1.68019, 1.84600, 2.10840, 2.34581, 2.57708, 2.70528, 2.64851, 2.60268, 2.54980, 2.47639, 2.30044, 2.18446, 2.12726, 2.04266, 2.06768, 2.05066, 2.04050, 2.02568, 2.07132, 1.95763, 1.85045, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.11260, 0.14105, 0.32987, 0.46057, 0.52631, 0.57858, 0.59285, 0.70091, 0.78324, 0.84507, 0.75377, 0.58332, 0.46413, 0.37401, 0.49354, 0.65295, 0.77983, 0.79343, 0.98591, 1.16089, 1.33128, 1.37219, 1.41934, 1.36593, 1.18028, 0.98223, 0.90861, 0.89591, 0.85586, 0.68136, 0.43508, 0.34444, 0.20972, -0.11630, -0.42152, -0.72073, -0.91653, -1.04517, -1.14570, -1.07413, -0.99050, -0.87183, -0.85504, -0.87215, -0.75344, -0.74521, -0.74496, -0.83940, -0.87023, -0.93242, -0.95279, -1.10295, -1.07586, -0.90696, -0.72117, -0.60860, -0.51587, -0.45235, -0.41474, -0.36161, -0.24202, -0.18201, -0.30717, -0.39659, -0.50131, -0.69491, -0.73124, -0.72440, -0.70154, -0.67906, -0.76580, -0.90426, -1.12705, -1.26081, -1.33575, -1.34025, -1.16087, -1.06426, -0.79526, -0.46731, -0.21793, -0.14797, 0.04061, 0.10038, 0.13393, 0.09272, 0.13628, 0.17185, 0.00231, -0.25959, -0.48751, -0.59745, -0.60233, -0.64369, -0.84022, -0.85045, -0.72280, -0.69277, -0.54003, -0.38062, -0.34698, -0.33612, -0.48435, -0.58720, -0.63885, -0.69465, -0.79151, -0.93946, -0.87364, -0.84166, -0.75889, -0.64822, -0.40293, -0.17454, 0.03098, 0.03724, 0.07151, 0.02909, -0.06756, -0.13553, -0.19190, -0.23999, -0.29296, -0.32900, -0.31249, -0.22928, -0.18142, 0.02287, 0.33671, 0.51131, 0.66067, 0.66654, 0.45806, 0.29599, 0.11743, 0.08639, 0.04588, -0.08057, -0.14031, -0.19149, -0.16802, -0.23084, -0.33354, -0.43327, -0.54125, -0.68054, -0.61663, -0.58643, -0.73507, -0.98055, -1.23011, -1.38022, -1.58022, -1.89989, -2.20181, -2.31796, -2.23993, -2.14636, -2.14360, -2.12196, -1.95902, -1.86887, -1.79760, -1.71478, -1.69343, -1.66089, -1.65691, -1.60033, -1.45558, -1.35801, -1.28898, -1.28806, -1.04042, -0.73013, -0.61944, -0.44171, -0.22019, -0.10694, -0.01973, 0.12249, 0.33600, 0.65978, 0.93686, 1.20065, 1.35484, 1.44832, 1.52035, 1.59362, 1.61258, 1.55108, 1.29980, 0.95306, 0.74750, 0.64397, 0.65597, 0.82295, 0.82815, 0.73705, 0.67881, 0.67533, 0.67599, 0.60666, 0.57764, 0.47048, 0.45362, 0.52641, 0.60828, 0.79432, 0.91968, 1.01107, 1.14616, 1.38080, 1.47292, 1.46912, 1.36819, 1.45417, 1.56820, 1.63595, 1.79153, 2.06891, 2.43737, 2.87262, 3.09693, 3.19391, 3.42476, 3.59753, 3.66693, 3.74533, 3.67950, 3.51180, 3.33009, 3.15644, 3.21042, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.59834, 2.46026, 2.33114, 2.04370, 1.82906, 1.61506, 1.51226, 1.36111, 1.08988, 0.78339, 0.45345, 0.22057, 0.19894, 0.17902, 0.13304, 0.16639, 0.12216, 0.04987, 0.05969, -0.13865, -0.41875, -0.65428, -0.88674, -0.97119, -1.00961, -0.90056, -0.86906, -0.90319, -0.86768, -0.91362, -0.78694, -0.66470, -0.62802, -0.72773, -0.65464, -0.72013, -0.79989, -0.92842, -0.99884, -1.05275, -1.13481, -1.25057, -1.34654, -1.41024, -1.40751, -1.45669, -1.58216, -1.58324, -1.61972, -1.76752, -1.74606, -1.61221, -1.53056, -1.57485, -1.62021, -1.48131, -1.45216, -1.55994, -1.77600, +0.96784, 1.05485, 1.11173, 1.10150, 1.10397, 1.18757, 1.23877, 1.40278, 1.49447, 1.43303, 1.35651, 1.40579, 1.47295, 1.53392, 1.54906, 1.31742, 1.27412, 1.35524, 1.48744, 1.56193, 1.52420, 1.53177, 1.55428, 1.57162, 1.55691, 1.59112, 1.67828, 1.69473, 1.71436, 1.85836, 2.09547, 2.19790, 2.27662, 2.41580, 2.69592, 2.84974, 2.81057, 2.78405, 2.61245, 2.41465, 2.14269, 1.82559, 1.67470, 1.63615, 1.59193, 1.53490, 1.45584, 1.15996, 1.00423, 0.97793, 0.91534, 0.82355, 0.60265, 0.49390, 0.52723, 0.64945, 0.73308, 0.80800, 0.89066, 0.93412, 1.04300, 1.14949, 1.20883, 1.11993, 1.04698, 0.99823, 1.04862, 1.20584, 1.40745, 1.64607, 1.79460, 2.04787, 2.36712, 2.54576, 2.66698, 2.68453, 2.67485, 2.64643, 2.68688, 2.52447, 2.36270, 2.25155, 2.08003, 2.00674, 1.88120, 1.87824, 1.88275, 1.84638, 1.69358, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.06944, 0.02780, 0.06956, 0.18998, 0.39085, 0.48345, 0.54492, 0.57403, 0.64038, 0.69746, 0.83006, 0.72715, 0.55005, 0.51658, 0.53684, 0.73456, 0.84070, 0.89832, 0.89813, 0.98632, 1.14690, 1.33876, 1.50842, 1.51704, 1.42573, 1.27078, 1.22457, 1.13395, 1.06090, 0.91228, 0.73225, 0.59551, 0.41207, 0.22995, -0.09838, -0.46187, -0.67612, -0.87254, -0.97226, -1.02341, -1.01806, -1.05910, -0.97510, -0.97681, -0.97961, -0.82134, -0.77802, -0.79347, -0.99808, -1.06768, -1.02606, -1.03877, -1.15732, -1.18980, -0.97062, -0.81448, -0.71639, -0.64274, -0.52219, -0.53585, -0.52539, -0.46207, -0.39844, -0.41655, -0.55162, -0.63204, -0.78323, -0.93687, -0.93087, -0.91176, -0.90639, -0.96411, -1.09442, -1.29985, -1.29098, -1.25184, -1.25900, -1.16381, -1.13792, -0.93223, -0.71060, -0.48757, -0.33961, -0.19761, -0.13419, -0.11724, -0.02635, 0.03988, -0.00333, -0.22440, -0.37561, -0.53415, -0.63405, -0.70241, -0.79443, -0.87521, -0.92039, -0.83462, -0.70490, -0.61639, -0.48537, -0.49309, -0.56106, -0.65206, -0.68452, -0.75592, -0.74770, -0.82896, -1.02663, -0.97023, -0.88524, -0.73064, -0.67167, -0.52988, -0.27087, -0.06018, 0.03796, 0.08135, 0.11716, 0.06410, -0.04746, -0.12238, -0.07235, -0.11242, -0.18670, -0.21574, -0.25279, -0.22103, -0.13311, 0.07645, 0.29330, 0.36937, 0.38894, 0.29571, 0.20046, 0.14748, 0.13933, -0.05336, -0.22803, -0.31340, -0.41130, -0.37294, -0.42597, -0.50933, -0.67185, -0.83982, -0.88434, -0.81764, -0.80657, -0.98942, -1.15102, -1.26892, -1.42956, -1.64761, -1.86582, -2.04081, -2.12877, -2.02569, -1.92512, -1.85182, -1.90161, -1.90378, -1.82225, -1.77784, -1.67571, -1.58579, -1.57505, -1.57298, -1.51279, -1.42100, -1.25801, -1.07978, -1.07771, -0.86318, -0.56657, -0.39127, -0.20455, -0.07427, 0.04347, 0.12606, 0.26847, 0.48106, 0.84722, 1.17235, 1.39482, 1.54157, 1.64044, 1.70904, 1.68551, 1.68860, 1.56359, 1.34586, 1.02557, 0.79868, 0.83592, 0.92810, 1.05825, 1.04036, 0.87666, 0.79838, 0.84245, 0.82851, 0.73739, 0.72940, 0.56246, 0.52111, 0.60164, 0.69286, 0.80097, 0.79663, 0.90745, 1.10804, 1.34803, 1.43275, 1.45028, 1.48543, 1.57376, 1.73511, 1.92388, 2.18214, 2.37306, 2.66987, 2.98262, 3.24998, 3.41939, 3.56458, 3.77501, 3.83240, 3.84322, 3.84931, 3.72018, 3.58726, 3.44598, 3.39062, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.53298, 2.49012, 2.30069, 2.06031, 1.87200, 1.67614, 1.48490, 1.17710, 0.88364, 0.46968, 0.25923, 0.22870, 0.28514, 0.28197, 0.14035, 0.08131, 0.02553, 0.01056, -0.08358, -0.35949, -0.58866, -0.76441, -0.83870, -0.90587, -0.75253, -0.76836, -0.85565, -0.81657, -0.80459, -0.65767, -0.64070, -0.63406, -0.63623, -0.54346, -0.53619, -0.60944, -0.69007, -0.86430, -1.02471, -1.17620, -1.19412, -1.30703, -1.37901, -1.45156, -1.55234, -1.62948, -1.72307, -1.71996, -1.78845, -1.84930, -1.74491, -1.72005, -1.75664, -1.73424, -1.64076, -1.73422, -1.80176, -1.98646, +0.97548, 1.08480, 1.18023, 1.22116, 1.32478, 1.46878, 1.47660, 1.58074, 1.69978, 1.66793, 1.50558, 1.44592, 1.48947, 1.55546, 1.63834, 1.51385, 1.46562, 1.53216, 1.63585, 1.62840, 1.57914, 1.62519, 1.54416, 1.47192, 1.49488, 1.54237, 1.65536, 1.71036, 1.77331, 1.96303, 2.26860, 2.45689, 2.53058, 2.63379, 2.82966, 2.93515, 2.93309, 2.93865, 2.73644, 2.46754, 2.23521, 2.01303, 1.82273, 1.67607, 1.63156, 1.63965, 1.64592, 1.43717, 1.20399, 1.07316, 0.96097, 0.81031, 0.63243, 0.63005, 0.62857, 0.65820, 0.74222, 0.75550, 0.78460, 0.79427, 0.89308, 1.05024, 1.15316, 1.16369, 1.17458, 1.20689, 1.29079, 1.41415, 1.55509, 1.72600, 1.78822, 1.92299, 2.23011, 2.46748, 2.54329, 2.51436, 2.57728, 2.62694, 2.71338, 2.59083, 2.34881, 2.17137, 1.97325, 1.82172, 1.68071, 1.70114, 1.66728, 1.51456, 1.37324, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.41312, 0.13360, 0.08887, 0.09869, 0.11406, 0.32354, 0.54580, 0.61058, 0.53408, 0.55536, 0.60227, 0.74866, 0.76470, 0.64203, 0.65078, 0.74303, 0.92485, 1.01822, 1.07804, 1.03098, 0.94123, 1.05459, 1.22826, 1.38206, 1.42449, 1.42848, 1.39795, 1.38114, 1.33679, 1.23071, 1.05746, 0.86725, 0.67647, 0.45397, 0.24546, -0.11094, -0.50536, -0.66812, -0.75029, -0.88336, -1.13332, -1.22662, -1.26408, -1.19545, -1.11517, -1.12227, -1.01967, -0.91281, -0.92048, -1.11062, -1.10761, -1.00779, -1.11384, -1.22603, -1.29195, -1.18221, -1.08440, -0.98511, -0.84342, -0.71474, -0.68887, -0.66344, -0.56061, -0.43879, -0.44422, -0.54610, -0.58734, -0.75817, -1.02225, -1.10126, -1.05441, -1.06062, -1.22082, -1.32351, -1.39337, -1.30355, -1.13700, -1.16663, -1.22111, -1.24166, -1.13541, -0.98741, -0.73725, -0.57056, -0.53057, -0.42189, -0.33548, -0.23762, -0.18748, -0.24394, -0.39811, -0.51232, -0.60483, -0.67164, -0.74287, -0.81492, -0.85820, -0.87663, -0.79065, -0.73019, -0.82097, -0.78625, -0.71662, -0.75592, -0.93335, -1.00092, -1.01580, -0.92549, -0.86827, -1.02497, -1.02615, -0.89314, -0.73148, -0.69154, -0.56626, -0.35707, -0.27629, -0.16880, -0.02398, 0.06677, 0.03880, -0.03278, -0.01062, 0.09132, 0.07615, 0.00948, -0.06355, -0.16258, -0.22416, -0.25466, -0.13434, 0.02346, 0.03119, 0.08912, 0.18961, 0.21048, 0.09235, -0.03900, -0.27725, -0.45054, -0.49544, -0.59301, -0.64408, -0.71557, -0.77344, -0.89187, -0.98663, -0.98799, -1.04370, -1.11944, -1.25277, -1.38884, -1.49608, -1.62452, -1.75816, -1.85805, -1.87942, -1.84693, -1.73365, -1.66919, -1.68129, -1.78627, -1.79836, -1.75428, -1.78528, -1.73906, -1.56925, -1.45168, -1.51054, -1.56733, -1.46206, -1.20755, -0.91683, -0.83275, -0.72186, -0.51335, -0.33920, -0.15119, 0.04452, 0.22932, 0.24539, 0.32320, 0.59976, 0.96654, 1.25047, 1.46139, 1.62952, 1.74914, 1.80708, 1.77435, 1.72935, 1.61081, 1.42277, 1.17616, 1.05241, 1.12006, 1.16531, 1.18849, 1.18480, 1.11397, 0.96684, 0.87625, 0.85339, 0.79944, 0.86564, 0.80649, 0.70111, 0.69798, 0.74367, 0.77159, 0.77254, 0.91744, 1.05270, 1.18775, 1.32535, 1.41884, 1.55271, 1.71937, 1.94961, 2.18917, 2.41354, 2.62727, 2.88536, 3.14844, 3.38927, 3.52997, 3.68699, 3.91444, 3.93437, 3.86321, 3.94006, 3.98866, 3.85773, 3.57828, 3.41770, 3.28710, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.70099, 2.61406, 2.51546, 2.30707, 2.07888, 1.80346, 1.55313, 1.25547, 0.93881, 0.60195, 0.41388, 0.36891, 0.40667, 0.33768, 0.18178, 0.14507, 0.05815, -0.03899, -0.09723, -0.23162, -0.40663, -0.63554, -0.71181, -0.74215, -0.59931, -0.55739, -0.68461, -0.74830, -0.75425, -0.66704, -0.65362, -0.54785, -0.46537, -0.45020, -0.41662, -0.51687, -0.68325, -0.89226, -1.06342, -1.18832, -1.22893, -1.31218, -1.37873, -1.44273, -1.54812, -1.66113, -1.72375, -1.65754, -1.73467, -1.91823, -1.92599, -1.88168, -1.93116, -2.02387, -1.95970, -2.00925, -2.03828, -2.07492, +0.83167, 0.98548, 1.10577, 1.20830, 1.47925, 1.64315, 1.70627, 1.80359, 1.80308, 1.75680, 1.70689, 1.57531, 1.51044, 1.61098, 1.66417, 1.55668, 1.50014, 1.63886, 1.72159, 1.61465, 1.50228, 1.55240, 1.50946, 1.47121, 1.58330, 1.54970, 1.62150, 1.77072, 1.86465, 2.02379, 2.30781, 2.52281, 2.56074, 2.64625, 2.76945, 2.82691, 2.91474, 2.92660, 2.82049, 2.63729, 2.34278, 2.10468, 1.97167, 1.79813, 1.67774, 1.75244, 1.76051, 1.56236, 1.31898, 1.22707, 1.11683, 0.89899, 0.73447, 0.75440, 0.80134, 0.83654, 0.93987, 0.80820, 0.73878, 0.79435, 0.87936, 0.99391, 1.06675, 1.14961, 1.26809, 1.41359, 1.53850, 1.57820, 1.68548, 1.75336, 1.77496, 1.90069, 2.03750, 2.20007, 2.33244, 2.38587, 2.43206, 2.58390, 2.63863, 2.40410, 2.09486, 1.97163, 1.85044, 1.63464, 1.48023, 1.42727, 1.42012, 1.29244, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.86029, 0.78079, 0.46431, 0.22648, 0.12949, 0.07819, 0.15041, 0.27247, 0.45477, 0.59332, 0.62250, 0.58420, 0.67872, 0.79605, 0.76802, 0.68474, 0.80212, 1.02364, 1.13288, 1.17482, 1.11695, 1.09151, 0.98407, 1.10912, 1.21075, 1.24862, 1.37216, 1.51287, 1.54960, 1.48781, 1.40361, 1.25487, 1.07425, 0.92519, 0.62151, 0.36156, 0.12223, -0.25888, -0.49689, -0.65991, -0.77466, -0.92073, -1.17835, -1.42184, -1.43018, -1.37076, -1.35958, -1.39422, -1.28782, -1.04077, -1.05203, -1.18813, -1.20982, -1.02899, -1.09747, -1.14025, -1.23859, -1.32409, -1.26975, -1.15702, -0.99769, -0.89207, -0.87784, -0.84600, -0.75299, -0.56930, -0.58913, -0.64364, -0.66959, -0.88530, -1.04317, -1.16407, -1.21830, -1.24596, -1.30635, -1.42897, -1.38364, -1.22631, -1.12294, -1.24224, -1.38496, -1.32815, -1.31027, -1.21348, -1.05749, -0.87073, -0.77804, -0.53139, -0.35468, -0.35681, -0.34701, -0.37354, -0.47504, -0.59667, -0.72262, -0.79736, -0.88331, -0.88676, -0.92241, -0.91227, -0.81728, -0.90003, -1.03005, -1.06625, -1.06055, -1.07850, -1.12536, -1.23816, -1.22798, -1.04703, -0.98056, -1.11804, -1.11560, -0.84110, -0.69482, -0.67191, -0.65855, -0.52202, -0.45931, -0.29200, -0.00798, 0.07664, 0.06665, 0.08215, 0.13045, 0.18291, 0.12384, 0.03313, -0.11989, -0.22100, -0.33936, -0.42242, -0.33945, -0.30647, -0.24902, -0.10622, 0.02275, 0.08105, 0.04120, -0.22009, -0.53614, -0.65275, -0.75228, -0.91389, -1.03161, -1.01636, -1.01679, -1.06322, -1.15213, -1.17043, -1.25985, -1.33005, -1.33583, -1.51224, -1.68272, -1.74826, -1.80604, -1.84581, -1.79245, -1.68725, -1.60516, -1.58293, -1.69554, -1.84959, -1.81364, -1.83236, -1.82987, -1.73934, -1.62554, -1.49280, -1.45353, -1.54305, -1.47737, -1.12024, -0.83877, -0.77725, -0.74689, -0.52144, -0.32699, -0.15778, 0.08225, 0.31213, 0.38506, 0.50119, 0.85778, 1.11437, 1.30037, 1.52669, 1.67589, 1.76233, 1.79228, 1.77658, 1.69219, 1.59736, 1.45218, 1.25972, 1.26789, 1.29969, 1.31476, 1.33398, 1.24861, 1.19430, 1.12401, 1.02320, 0.92470, 0.95439, 1.05433, 1.01689, 0.86894, 0.86883, 0.89464, 0.82784, 0.83960, 0.93159, 1.03787, 1.16076, 1.42521, 1.55339, 1.71958, 2.01157, 2.29341, 2.48008, 2.58630, 2.76514, 2.96384, 3.18352, 3.41169, 3.48602, 3.67654, 3.86580, 3.87801, 3.90469, 3.97577, 4.06362, 4.00704, 3.75517, 3.44255, 3.31828, 3.23985, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.79697, 2.75037, 2.77760, 2.59371, 2.30722, 2.06271, 1.78449, 1.43337, 1.03960, 0.71872, 0.52421, 0.43571, 0.43955, 0.24958, 0.13505, 0.12078, 0.01433, 0.01025, -0.08123, -0.21831, -0.27483, -0.34373, -0.48429, -0.47023, -0.38187, -0.43070, -0.58289, -0.68139, -0.67927, -0.71505, -0.68902, -0.59220, -0.39598, -0.32710, -0.21110, -0.36051, -0.68627, -0.87487, -1.01257, -1.15268, -1.28026, -1.41538, -1.50962, -1.59117, -1.65249, -1.80776, -1.79306, -1.68096, -1.80385, -1.92352, -2.06083, -2.15067, -2.21432, -2.21463, -2.19065, -2.14155, -2.11382, -2.17550, +0.81647, 0.95329, 1.12867, 1.31752, 1.59184, 1.73034, 1.76404, 1.78572, 1.75573, 1.75237, 1.84368, 1.77446, 1.57442, 1.57867, 1.62835, 1.53436, 1.49362, 1.64491, 1.73190, 1.64145, 1.53431, 1.55836, 1.55836, 1.55761, 1.61617, 1.53857, 1.61655, 1.79752, 1.90026, 2.07830, 2.36385, 2.56881, 2.58162, 2.61079, 2.73030, 2.84085, 2.91588, 2.88038, 2.79813, 2.63371, 2.38290, 2.11892, 1.95111, 1.82311, 1.62160, 1.56617, 1.59161, 1.50902, 1.43822, 1.46779, 1.35647, 1.14053, 0.96520, 0.95652, 1.03427, 1.10404, 1.09351, 0.85702, 0.80353, 0.91221, 0.96904, 1.06032, 1.14875, 1.28793, 1.47813, 1.64119, 1.78315, 1.80155, 1.79846, 1.75999, 1.76452, 1.78525, 1.81299, 1.94113, 2.10018, 2.24403, 2.24540, 2.30882, 2.34547, 2.12235, 1.86435, 1.82792, 1.74765, 1.57514, 1.42857, 1.31094, 1.25688, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.91486, 0.88751, 0.87344, 0.66883, 0.44496, 0.19512, 0.02961, 0.01847, 0.08949, 0.24329, 0.43539, 0.66019, 0.72220, 0.75994, 0.81103, 0.76122, 0.71244, 0.93686, 1.20708, 1.33521, 1.32404, 1.18803, 1.15660, 1.11502, 1.17060, 1.14849, 1.15922, 1.35353, 1.53614, 1.59969, 1.54408, 1.42290, 1.26751, 1.10706, 0.99716, 0.69498, 0.35672, 0.01819, -0.36011, -0.63444, -0.81012, -0.88888, -1.02400, -1.18390, -1.44299, -1.57667, -1.58103, -1.58843, -1.60096, -1.42990, -1.17591, -1.13075, -1.19571, -1.20126, -1.03035, -1.03887, -1.09125, -1.26412, -1.38145, -1.29049, -1.20052, -1.07108, -0.95142, -0.90788, -0.85436, -0.84311, -0.73519, -0.70773, -0.76550, -0.90978, -1.11571, -1.24084, -1.28222, -1.29508, -1.36806, -1.35647, -1.46139, -1.48031, -1.34611, -1.26538, -1.41484, -1.50712, -1.40769, -1.35503, -1.26703, -1.16460, -1.02325, -0.86601, -0.60535, -0.49680, -0.53537, -0.52476, -0.53769, -0.56007, -0.59080, -0.70385, -0.78098, -0.85811, -0.86651, -0.89304, -0.89792, -0.90258, -1.05972, -1.27401, -1.35827, -1.33259, -1.33496, -1.26076, -1.31014, -1.38827, -1.27728, -1.18991, -1.23796, -1.11425, -0.80001, -0.65107, -0.62165, -0.64333, -0.57709, -0.48956, -0.32855, -0.10662, -0.00118, 0.09295, 0.15909, 0.14694, 0.14526, 0.08793, -0.02948, -0.24384, -0.36143, -0.41460, -0.40595, -0.41136, -0.51035, -0.54284, -0.43737, -0.25560, -0.17554, -0.17062, -0.45066, -0.86612, -1.02824, -1.12177, -1.26790, -1.33658, -1.28265, -1.24035, -1.22576, -1.30176, -1.38423, -1.50394, -1.54878, -1.51984, -1.64545, -1.77451, -1.80765, -1.80031, -1.75706, -1.65846, -1.52762, -1.45661, -1.49737, -1.62712, -1.75345, -1.77243, -1.86219, -1.88201, -1.80884, -1.68644, -1.57068, -1.47664, -1.48413, -1.47151, -1.21397, -0.97155, -0.88110, -0.79289, -0.52039, -0.30494, -0.10656, 0.15833, 0.39961, 0.54715, 0.71507, 0.95396, 1.09072, 1.26952, 1.46462, 1.55564, 1.67902, 1.79828, 1.90855, 1.85094, 1.70146, 1.55175, 1.42070, 1.43378, 1.39198, 1.34123, 1.26958, 1.20938, 1.22934, 1.24322, 1.23693, 1.10063, 1.05154, 1.15900, 1.17176, 1.06763, 1.08242, 1.04399, 1.00014, 1.07874, 1.14369, 1.18472, 1.31285, 1.58041, 1.71358, 1.92699, 2.29093, 2.59249, 2.78589, 2.88011, 3.04193, 3.19455, 3.31603, 3.49934, 3.59009, 3.70827, 3.75083, 3.74266, 3.77130, 3.90039, 4.03034, 3.99741, 3.85027, 3.51296, 3.29251, 3.20027, 3.06277, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.81921, 2.79691, 2.80919, 2.65345, 2.48365, 2.39568, 2.11122, 1.71303, 1.27748, 0.94559, 0.74888, 0.58797, 0.50844, 0.29864, 0.19076, 0.13035, 0.03662, -0.00617, -0.09022, -0.18845, -0.20427, -0.12976, -0.26480, -0.38497, -0.39802, -0.44328, -0.51355, -0.54785, -0.61790, -0.68718, -0.63622, -0.56114, -0.39066, -0.25037, -0.13083, -0.33453, -0.65645, -0.76708, -0.89482, -1.05180, -1.20325, -1.36479, -1.50373, -1.66621, -1.74417, -1.82852, -1.77086, -1.74741, -1.90143, -2.07013, -2.24289, -2.34120, -2.42880, -2.33924, -2.28680, -2.28500, -2.24696, -2.30760, +0.86634, 0.99556, 1.13015, 1.37096, 1.62260, 1.68824, 1.73687, 1.76674, 1.79449, 1.82755, 1.92171, 1.89624, 1.80614, 1.78679, 1.76153, 1.68330, 1.55003, 1.62223, 1.66832, 1.65586, 1.71071, 1.66750, 1.62619, 1.62419, 1.66454, 1.61765, 1.66951, 1.78367, 1.86553, 2.08307, 2.29893, 2.46466, 2.53640, 2.55397, 2.65702, 2.84486, 2.96917, 2.86967, 2.74666, 2.60552, 2.41994, 2.15201, 1.89765, 1.74904, 1.61257, 1.52425, 1.48881, 1.56917, 1.61524, 1.64602, 1.48561, 1.26790, 1.17887, 1.10223, 1.11976, 1.21291, 1.19829, 1.03647, 0.99303, 1.06237, 1.06706, 1.17633, 1.25312, 1.39229, 1.60040, 1.71559, 1.78244, 1.79168, 1.82360, 1.77401, 1.78987, 1.81630, 1.82302, 1.91961, 1.98545, 2.03089, 2.02504, 2.11546, 2.08922, 2.01977, 1.86360, 1.80893, 1.72220, 1.55096, 1.51194, 1.36016, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.86132, 0.96052, 0.93493, 0.83774, 0.67192, 0.54955, 0.29234, 0.09962, 0.09077, 0.13487, 0.24955, 0.38865, 0.63751, 0.81582, 0.92598, 0.83169, 0.80703, 0.77755, 0.94346, 1.19807, 1.30314, 1.40673, 1.31942, 1.19850, 1.18578, 1.17975, 1.16206, 1.15250, 1.28283, 1.32712, 1.36512, 1.31526, 1.18785, 1.14751, 1.09168, 0.96979, 0.66531, 0.37973, 0.05297, -0.32758, -0.64095, -0.85887, -0.89758, -1.03286, -1.14693, -1.33652, -1.39750, -1.52612, -1.52493, -1.47677, -1.35787, -1.16447, -1.17249, -1.13211, -1.08003, -1.06400, -1.09566, -1.18430, -1.27286, -1.30728, -1.19288, -1.18430, -1.13225, -1.07450, -1.05905, -0.93802, -0.89150, -0.87779, -0.90456, -0.93529, -1.10357, -1.29022, -1.33440, -1.30716, -1.29284, -1.46103, -1.53012, -1.65800, -1.59229, -1.54308, -1.44918, -1.46219, -1.51172, -1.39482, -1.36639, -1.21720, -1.05537, -1.04333, -0.95162, -0.84537, -0.79134, -0.84199, -0.83991, -0.85979, -0.80101, -0.72544, -0.79825, -0.78244, -0.74771, -0.81768, -0.99285, -1.01884, -1.01476, -1.15243, -1.28788, -1.34045, -1.27256, -1.30091, -1.25780, -1.27735, -1.25587, -1.25291, -1.19722, -1.10756, -0.97901, -0.74193, -0.70297, -0.64880, -0.53983, -0.52846, -0.45923, -0.37451, -0.24944, -0.18633, -0.07267, -0.02744, -0.05499, -0.03740, -0.10533, -0.19488, -0.34531, -0.47997, -0.56386, -0.47634, -0.49257, -0.68222, -0.76253, -0.71833, -0.53605, -0.50001, -0.55547, -0.80610, -1.07882, -1.26467, -1.38734, -1.41828, -1.47580, -1.45727, -1.52482, -1.57183, -1.57150, -1.74772, -1.90363, -1.90284, -1.79513, -1.79898, -1.85269, -1.88132, -1.83240, -1.72639, -1.69026, -1.55656, -1.39419, -1.42731, -1.57704, -1.64948, -1.63687, -1.74475, -1.73715, -1.62884, -1.48055, -1.42567, -1.41657, -1.42840, -1.35760, -1.19665, -1.09112, -0.90541, -0.73967, -0.43939, -0.25154, -0.07140, 0.23456, 0.37945, 0.50325, 0.71083, 0.92205, 1.07483, 1.24601, 1.35097, 1.37143, 1.55813, 1.72030, 1.91446, 1.93600, 1.74615, 1.49516, 1.35459, 1.40691, 1.35152, 1.32743, 1.32762, 1.35900, 1.42341, 1.42477, 1.43609, 1.39388, 1.37591, 1.34575, 1.38148, 1.29700, 1.25947, 1.17695, 1.16508, 1.39826, 1.44985, 1.39839, 1.52778, 1.77711, 1.94016, 2.09790, 2.40516, 2.68467, 2.97511, 3.11947, 3.28370, 3.47162, 3.54372, 3.61208, 3.67791, 3.79187, 3.75454, 3.74339, 3.82977, 3.98632, 4.08418, 3.96425, 3.81132, 3.60702, 3.51995, 3.36002, 3.27792, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.82044, 2.76881, 2.73357, 2.68665, 2.61029, 2.57125, 2.23267, 1.84448, 1.38001, 1.00266, 0.85253, 0.69266, 0.53673, 0.34491, 0.32981, 0.28454, 0.21624, 0.20586, 0.13625, 0.04460, -0.10909, -0.15209, -0.26970, -0.32513, -0.44792, -0.41281, -0.37679, -0.43174, -0.53980, -0.66865, -0.53706, -0.48197, -0.50529, -0.36971, -0.25971, -0.33880, -0.56452, -0.64388, -0.80831, -0.94689, -1.09880, -1.29312, -1.42041, -1.60022, -1.75902, -1.86403, -1.76497, -1.78709, -1.96195, -2.08594, -2.19267, -2.22067, -2.37553, -2.38378, -2.38725, -2.31147, -2.34132, -2.36880, +0.79063, 0.91442, 1.10759, 1.35556, 1.61352, 1.70757, 1.76742, 1.80162, 1.78653, 1.78956, 1.94610, 2.01754, 2.01986, 2.03685, 1.98606, 1.85173, 1.63596, 1.62943, 1.72235, 1.79315, 1.75828, 1.64567, 1.61901, 1.59185, 1.65761, 1.66305, 1.69342, 1.77990, 1.92280, 2.17743, 2.33253, 2.43618, 2.44310, 2.42479, 2.58681, 2.79726, 2.95155, 2.88317, 2.68860, 2.50118, 2.26639, 1.98679, 1.83608, 1.77343, 1.68085, 1.62371, 1.58910, 1.68047, 1.70004, 1.63432, 1.49789, 1.38792, 1.24328, 1.10494, 1.16182, 1.25924, 1.32506, 1.27959, 1.20620, 1.19815, 1.21042, 1.34866, 1.39654, 1.47929, 1.56226, 1.56533, 1.65547, 1.69577, 1.77716, 1.82252, 1.82382, 1.82487, 1.77422, 1.75496, 1.81212, 1.87736, 1.86889, 1.99345, 1.98498, 1.96180, 1.83811, 1.74494, 1.68820, 1.61557, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.59798, 0.68897, 0.81849, 0.91763, 0.81036, 0.70683, 0.58781, 0.53220, 0.46519, 0.35323, 0.33230, 0.31327, 0.29130, 0.41271, 0.71480, 0.87664, 0.95433, 0.81810, 0.78378, 0.75139, 0.86461, 1.11708, 1.32880, 1.44827, 1.28132, 1.16760, 1.13248, 1.09717, 1.12750, 1.10213, 1.13265, 1.10158, 1.15968, 1.10515, 0.98525, 0.97872, 0.88584, 0.80418, 0.57892, 0.34716, 0.15230, -0.19977, -0.55592, -0.82360, -0.95451, -1.04404, -1.01516, -1.13790, -1.15677, -1.29709, -1.31698, -1.27883, -1.22145, -1.06229, -0.98542, -0.96424, -1.06468, -1.08427, -1.13666, -1.23159, -1.20764, -1.16592, -1.06642, -1.06244, -1.00921, -1.03862, -1.08482, -0.98497, -0.98162, -0.94561, -0.96141, -1.01387, -1.09197, -1.23925, -1.29292, -1.33642, -1.50847, -1.72987, -1.73193, -1.82653, -1.71484, -1.66261, -1.55052, -1.46888, -1.47828, -1.36458, -1.23506, -1.08155, -1.07439, -1.09354, -1.06875, -1.11316, -1.08398, -1.14154, -1.17010, -1.15873, -0.99772, -0.87878, -0.91058, -0.84447, -0.84637, -0.92249, -1.09854, -1.14917, -1.04729, -1.09308, -1.17393, -1.21857, -1.24276, -1.28676, -1.16003, -1.12226, -1.05282, -1.05038, -1.01054, -0.91373, -0.83858, -0.69379, -0.61946, -0.55367, -0.55974, -0.54768, -0.47518, -0.46913, -0.40962, -0.41274, -0.36196, -0.30889, -0.19867, -0.10291, -0.17153, -0.25469, -0.45086, -0.59407, -0.64967, -0.62312, -0.65381, -0.82604, -0.93921, -0.96231, -0.91365, -0.95952, -0.95019, -1.08392, -1.26506, -1.43575, -1.56548, -1.58734, -1.66329, -1.69306, -1.75679, -1.84206, -1.98839, -2.19923, -2.28800, -2.25127, -2.06649, -1.97262, -1.97234, -1.95810, -1.80667, -1.64728, -1.64435, -1.52952, -1.40632, -1.43708, -1.51146, -1.56493, -1.50275, -1.52036, -1.49072, -1.38614, -1.30806, -1.32873, -1.29377, -1.26324, -1.19742, -1.08409, -1.03777, -0.87024, -0.70056, -0.41962, -0.18737, 0.02817, 0.15511, 0.16610, 0.31919, 0.55760, 0.87482, 1.13692, 1.29542, 1.35998, 1.42332, 1.65396, 1.78264, 1.89436, 1.80058, 1.54203, 1.32313, 1.20160, 1.29820, 1.35053, 1.38386, 1.45102, 1.47669, 1.47265, 1.52370, 1.62401, 1.63844, 1.67131, 1.60045, 1.58109, 1.48634, 1.41668, 1.39300, 1.49386, 1.64926, 1.59651, 1.57391, 1.68419, 1.92366, 2.11990, 2.22179, 2.46396, 2.78391, 3.17165, 3.33984, 3.47597, 3.60181, 3.58115, 3.64687, 3.71306, 3.83088, 3.88960, 3.90126, 3.98533, 4.08250, 4.04660, 3.92926, 3.86264, 3.74394, 3.75506, 3.61804, 3.51921, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.91305, 2.82630, 2.77873, 2.81575, 2.74708, 2.62211, 2.27064, 1.96827, 1.51955, 1.13026, 0.95603, 0.71823, 0.61092, 0.51146, 0.52828, 0.57519, 0.51420, 0.47229, 0.34837, 0.11963, -0.11808, -0.18074, -0.29845, -0.30979, -0.41104, -0.36510, -0.33516, -0.43562, -0.53069, -0.55491, -0.46440, -0.58115, -0.64155, -0.51614, -0.39339, -0.33699, -0.48460, -0.57450, -0.70227, -0.74507, -0.88678, -1.10493, -1.26279, -1.53758, -1.70332, -1.78469, -1.70986, -1.65595, -1.79742, -1.91330, -2.01116, -2.12843, -2.30553, -2.29185, -2.35853, -2.29814, -2.33456, -2.33293, +0.73057, 0.97260, 1.24247, 1.41708, 1.52006, 1.60969, 1.73392, 1.75773, 1.82105, 1.88656, 1.97029, 2.07560, 2.13799, 2.14082, 2.09425, 1.97498, 1.82217, 1.71217, 1.73054, 1.80969, 1.71315, 1.68260, 1.73418, 1.64613, 1.64064, 1.66974, 1.69279, 1.76845, 1.96264, 2.13814, 2.29479, 2.45134, 2.42861, 2.47785, 2.66767, 2.78118, 2.81287, 2.70950, 2.52017, 2.26324, 2.04834, 1.92719, 1.82453, 1.78563, 1.72657, 1.67175, 1.65886, 1.71672, 1.74720, 1.62712, 1.47626, 1.45797, 1.31114, 1.30349, 1.45361, 1.45567, 1.44377, 1.43600, 1.34517, 1.28696, 1.36882, 1.43843, 1.44438, 1.51613, 1.44348, 1.44841, 1.61176, 1.67295, 1.72004, 1.73739, 1.74236, 1.67564, 1.62108, 1.67852, 1.71350, 1.79757, 1.81335, 1.84662, 1.82043, 1.81968, 1.76968, 1.66988, 1.56088, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.43426, 0.47843, 0.52473, 0.71255, 0.77870, 0.71602, 0.68751, 0.58815, 0.50929, 0.51883, 0.54529, 0.49305, 0.43243, 0.50880, 0.59527, 0.80656, 0.91927, 0.88867, 0.75818, 0.74571, 0.77413, 0.90794, 1.04130, 1.26634, 1.31139, 1.20356, 1.19641, 1.12334, 1.03980, 1.06869, 1.05161, 0.96724, 0.89037, 0.87667, 0.77828, 0.79162, 0.80889, 0.74798, 0.73846, 0.56688, 0.33608, 0.12957, -0.12364, -0.44636, -0.76192, -0.83633, -0.90862, -0.86305, -0.91529, -0.99593, -1.12830, -1.12216, -1.07407, -0.99270, -0.95502, -0.86667, -0.92565, -1.02819, -0.93018, -0.97659, -1.12747, -1.10992, -1.03242, -0.97913, -0.93211, -0.92032, -1.06397, -1.06923, -1.00119, -0.95274, -0.83027, -0.86763, -1.00288, -1.11719, -1.20785, -1.29537, -1.47212, -1.62449, -1.81148, -1.82939, -1.85795, -1.80019, -1.79586, -1.70059, -1.58545, -1.47969, -1.43574, -1.23866, -1.07050, -1.07150, -0.99876, -1.05585, -1.31819, -1.41316, -1.45234, -1.48119, -1.41083, -1.25153, -1.22495, -1.15903, -1.02811, -0.99941, -0.94252, -1.01986, -1.13081, -1.12826, -1.10968, -1.10702, -1.18592, -1.15778, -1.11402, -0.97942, -0.89741, -0.86884, -0.91257, -0.89864, -0.83248, -0.71743, -0.67967, -0.59907, -0.54579, -0.59936, -0.50324, -0.42768, -0.55615, -0.64020, -0.67297, -0.67777, -0.59095, -0.36444, -0.29313, -0.31844, -0.34607, -0.50255, -0.55286, -0.58596, -0.69204, -0.85180, -0.98822, -1.06022, -1.17451, -1.16408, -1.21624, -1.28275, -1.38360, -1.55676, -1.76987, -1.86517, -1.83946, -1.82518, -1.93486, -2.08612, -2.24468, -2.45862, -2.51457, -2.44298, -2.43423, -2.32124, -2.18283, -2.13280, -2.05082, -1.81493, -1.67375, -1.60382, -1.45971, -1.39580, -1.33954, -1.31040, -1.41240, -1.45292, -1.40950, -1.27961, -1.22880, -1.15290, -1.11190, -1.13172, -1.11587, -1.08272, -1.04550, -1.00815, -0.85656, -0.64758, -0.45617, -0.29268, -0.07592, -0.06451, 0.02120, 0.27386, 0.48564, 0.83036, 1.18499, 1.34397, 1.42237, 1.59011, 1.74232, 1.80860, 1.87875, 1.69558, 1.51302, 1.39916, 1.26596, 1.26532, 1.31140, 1.40836, 1.44913, 1.48270, 1.56728, 1.64415, 1.80535, 1.86075, 1.84017, 1.72317, 1.65705, 1.63311, 1.59550, 1.58261, 1.74835, 1.79239, 1.79060, 1.87638, 1.91673, 2.05149, 2.27519, 2.38945, 2.55151, 2.88156, 3.21389, 3.38450, 3.56812, 3.62289, 3.67307, 3.82667, 3.84937, 3.86800, 3.91401, 3.99922, 4.04680, 4.10083, 4.15364, 4.04529, 3.98640, 3.89984, 3.83101, 3.69107, 3.58379, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 3.18133, 3.04743, 2.94168, 2.96806, 2.88356, 2.66039, 2.37048, 2.08523, 1.65785, 1.37238, 1.14239, 0.91845, 0.87647, 0.78385, 0.71534, 0.70114, 0.72126, 0.67161, 0.46785, 0.26677, -0.07449, -0.25686, -0.36463, -0.42057, -0.47817, -0.42961, -0.41825, -0.49771, -0.65291, -0.59968, -0.56217, -0.60888, -0.53453, -0.46658, -0.44751, -0.37670, -0.43589, -0.55515, -0.60947, -0.59838, -0.74619, -0.89289, -1.09413, -1.36552, -1.47259, -1.55876, -1.57729, -1.56698, -1.61164, -1.70411, -1.87860, -1.97043, -2.15249, -2.21123, -2.30119, -2.34054, -2.41108, -2.36836, +0.68029, 1.01175, 1.18773, 1.27241, 1.38537, 1.51684, 1.69120, 1.79653, 1.95191, 2.00803, 1.92730, 1.92574, 2.07781, 2.17066, 2.17235, 2.13663, 1.98788, 1.81409, 1.71827, 1.70853, 1.66681, 1.66087, 1.64488, 1.55146, 1.50751, 1.46778, 1.57555, 1.77672, 1.91446, 2.01891, 2.16114, 2.33020, 2.43344, 2.57382, 2.62520, 2.56186, 2.55279, 2.44832, 2.31537, 2.12946, 1.99246, 1.96032, 1.79157, 1.63479, 1.61878, 1.69492, 1.71658, 1.71321, 1.67676, 1.62193, 1.56960, 1.56004, 1.54230, 1.64432, 1.71340, 1.60746, 1.50490, 1.40695, 1.33904, 1.38620, 1.44741, 1.42798, 1.37384, 1.33328, 1.31160, 1.44054, 1.56920, 1.57381, 1.63680, 1.58420, 1.51070, 1.42723, 1.42654, 1.55789, 1.57592, 1.63929, 1.69588, 1.73673, 1.68554, 1.70974, 1.66572, 1.54148, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.41527, 0.38813, 0.38128, 0.45909, 0.58339, 0.69403, 0.71933, 0.56018, 0.51726, 0.56227, 0.59864, 0.56247, 0.53704, 0.72548, 0.74690, 0.72316, 0.76284, 0.84294, 0.81922, 0.86780, 0.93156, 1.04237, 1.12504, 1.20457, 1.18174, 1.15033, 1.11135, 0.96654, 0.90546, 0.85780, 0.81931, 0.83330, 0.76541, 0.69126, 0.60350, 0.59801, 0.66117, 0.68142, 0.62324, 0.33496, 0.15539, -0.01506, -0.19461, -0.36744, -0.63491, -0.67747, -0.77409, -0.81453, -0.84989, -0.88022, -0.96134, -0.89890, -0.87906, -0.84821, -0.81156, -0.81507, -0.93036, -0.95431, -0.83025, -0.89585, -1.00550, -1.04081, -1.00929, -0.85063, -0.76602, -0.80911, -0.92324, -0.99944, -0.94851, -0.80656, -0.73199, -0.96559, -1.13706, -1.20525, -1.30205, -1.42008, -1.61629, -1.63347, -1.73937, -1.84101, -1.85947, -1.76585, -1.78303, -1.72359, -1.65532, -1.55693, -1.47913, -1.30618, -1.12862, -1.04589, -0.99623, -1.19634, -1.49683, -1.67221, -1.75164, -1.63554, -1.53242, -1.52477, -1.57795, -1.57648, -1.39631, -1.20350, -1.01270, -1.08370, -1.22810, -1.28506, -1.27755, -1.18632, -1.20835, -1.10567, -0.98206, -0.90090, -0.86644, -0.79920, -0.79973, -0.77967, -0.76931, -0.72562, -0.67308, -0.61292, -0.59138, -0.58049, -0.51959, -0.58506, -0.76423, -0.90892, -0.96676, -0.88196, -0.72432, -0.56032, -0.53107, -0.62256, -0.62357, -0.58507, -0.56819, -0.75078, -0.94912, -1.04629, -1.12169, -1.13701, -1.23131, -1.23674, -1.33889, -1.58108, -1.80133, -1.93475, -2.09718, -2.12442, -2.04862, -2.05207, -2.16796, -2.37529, -2.56683, -2.67192, -2.62601, -2.54825, -2.56223, -2.54288, -2.48843, -2.34113, -2.10737, -1.89757, -1.71148, -1.58595, -1.49944, -1.40795, -1.28618, -1.30000, -1.49245, -1.56468, -1.47815, -1.26846, -1.18376, -1.05669, -0.94669, -1.04893, -1.15889, -1.12716, -1.02085, -0.92997, -0.77183, -0.62442, -0.50998, -0.41166, -0.26512, -0.17105, 0.03213, 0.24727, 0.43356, 0.76809, 1.06278, 1.26351, 1.50262, 1.69510, 1.75840, 1.71672, 1.68461, 1.63300, 1.61027, 1.50634, 1.31512, 1.28153, 1.29112, 1.36065, 1.40209, 1.47295, 1.62560, 1.69996, 1.80677, 1.88592, 1.92639, 1.84625, 1.84817, 1.86388, 1.87783, 1.91223, 1.97989, 1.97516, 1.98816, 2.00683, 1.98333, 2.07307, 2.28476, 2.47747, 2.70105, 2.91371, 3.14340, 3.32339, 3.41638, 3.49666, 3.69361, 3.83807, 3.71446, 3.71390, 3.78664, 3.90697, 3.98990, 4.07693, 4.25507, 4.17910, 4.04305, 3.95092, 3.89184, 3.75635, 3.67550, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 3.30082, 3.11401, 3.02853, 2.94834, 2.81675, 2.72754, 2.53794, 2.26508, 1.92490, 1.61118, 1.38512, 1.24593, 1.13486, 0.87218, 0.75840, 0.71027, 0.75117, 0.73990, 0.50812, 0.33209, -0.05419, -0.35329, -0.45976, -0.42691, -0.42479, -0.39926, -0.47975, -0.62911, -0.76764, -0.75623, -0.70763, -0.55543, -0.43123, -0.49694, -0.54909, -0.54111, -0.55392, -0.54213, -0.56712, -0.56584, -0.66039, -0.88886, -1.07782, -1.20708, -1.31490, -1.55762, -1.61034, -1.54416, -1.50856, -1.51724, -1.70226, -1.78846, -1.99304, -2.17955, -2.27245, -2.24276, -2.30369, -2.24104, +0.64261, 0.86480, 1.04585, 1.16435, 1.37175, 1.59795, 1.73952, 1.86273, 1.99392, 1.95421, 1.86744, 1.86960, 1.99529, 2.13644, 2.15661, 2.10474, 1.89058, 1.73570, 1.71787, 1.64585, 1.53535, 1.49274, 1.44035, 1.39045, 1.37972, 1.32679, 1.45346, 1.67583, 1.77623, 1.91788, 2.09994, 2.26611, 2.40612, 2.49725, 2.56772, 2.50649, 2.46941, 2.38330, 2.26777, 2.13623, 2.05466, 1.96286, 1.77122, 1.61568, 1.54376, 1.61996, 1.62738, 1.52069, 1.41166, 1.46284, 1.63125, 1.63813, 1.60676, 1.71261, 1.74585, 1.65375, 1.59682, 1.49731, 1.40340, 1.38089, 1.33813, 1.27857, 1.25120, 1.17151, 1.25102, 1.36879, 1.51276, 1.55691, 1.59051, 1.48655, 1.32802, 1.18224, 1.20935, 1.29590, 1.35171, 1.49872, 1.53308, 1.54436, 1.51606, 1.51132, 1.44435, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.24823, 0.23308, 0.25519, 0.36786, 0.42020, 0.59394, 0.68751, 0.79687, 0.73815, 0.72574, 0.75161, 0.72059, 0.63617, 0.64464, 0.76302, 0.72501, 0.65570, 0.62392, 0.72061, 0.79402, 0.80563, 0.85451, 0.94684, 1.13731, 1.20842, 1.11052, 1.05738, 0.99488, 0.83494, 0.78218, 0.68399, 0.61359, 0.60835, 0.61489, 0.59547, 0.60734, 0.56019, 0.61364, 0.51805, 0.42325, 0.18059, 0.04500, -0.08916, -0.23895, -0.40132, -0.60659, -0.69414, -0.77292, -0.70713, -0.71519, -0.78419, -0.82369, -0.82675, -0.87345, -0.90822, -0.73731, -0.68208, -0.88322, -0.96164, -0.84599, -0.87122, -0.88148, -0.86523, -0.81702, -0.69711, -0.62589, -0.66028, -0.62404, -0.71552, -0.68120, -0.69307, -0.75054, -1.00070, -1.17993, -1.24137, -1.35713, -1.55655, -1.70954, -1.69942, -1.78449, -1.83684, -1.85020, -1.82544, -1.83075, -1.83682, -1.79372, -1.72069, -1.52026, -1.28603, -1.22887, -1.25084, -1.23881, -1.42740, -1.58640, -1.70777, -1.82457, -1.78572, -1.77118, -1.87398, -1.88316, -1.90792, -1.69373, -1.50538, -1.28875, -1.24836, -1.35803, -1.42528, -1.40127, -1.30414, -1.24691, -1.14070, -1.02046, -0.87805, -0.83011, -0.80613, -0.73123, -0.72941, -0.80462, -0.89496, -0.79812, -0.65545, -0.70651, -0.74175, -0.68276, -0.77913, -0.91044, -0.99736, -1.03613, -0.98541, -0.87058, -0.81293, -0.75249, -0.83486, -0.81700, -0.76804, -0.80024, -0.96044, -1.11373, -1.13062, -1.16075, -1.22658, -1.32534, -1.40008, -1.61021, -1.85731, -2.05339, -2.21221, -2.33849, -2.38227, -2.38183, -2.47078, -2.50649, -2.53053, -2.66363, -2.76718, -2.70448, -2.63576, -2.62940, -2.60196, -2.59048, -2.47916, -2.25502, -2.08234, -1.80112, -1.61371, -1.56871, -1.50954, -1.44139, -1.38834, -1.54209, -1.62702, -1.53466, -1.35853, -1.25525, -1.08532, -0.96185, -1.00549, -1.10196, -1.14477, -1.04254, -0.95084, -0.85910, -0.77100, -0.60358, -0.37405, -0.26037, -0.17732, 0.07236, 0.28722, 0.49959, 0.82342, 1.04900, 1.21138, 1.42717, 1.58717, 1.66128, 1.62825, 1.55660, 1.58123, 1.53544, 1.50256, 1.39394, 1.36587, 1.36873, 1.39171, 1.43006, 1.53269, 1.62551, 1.69911, 1.80531, 1.82685, 1.88029, 1.91222, 1.98743, 2.01735, 2.07895, 2.23865, 2.22663, 2.10247, 2.05186, 2.02336, 2.01674, 2.13365, 2.32876, 2.48761, 2.60770, 2.71719, 2.94869, 3.22801, 3.27948, 3.37658, 3.49721, 3.64436, 3.54913, 3.57097, 3.71033, 3.85198, 3.92517, 4.05673, 4.21486, 4.19559, 4.14490, 4.06585, 4.00204, 3.89245, 3.74931, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 3.29066, 3.12020, 3.08389, 2.96547, 2.79109, 2.68844, 2.55946, 2.34635, 2.15714, 1.84390, 1.64825, 1.42932, 1.31398, 1.11002, 0.99125, 0.89896, 0.84357, 0.69618, 0.43783, 0.19274, -0.13080, -0.28929, -0.38510, -0.38249, -0.35812, -0.44736, -0.61337, -0.82925, -0.84888, -0.79215, -0.79967, -0.64054, -0.51014, -0.60008, -0.62468, -0.59992, -0.58839, -0.62321, -0.67803, -0.69271, -0.67789, -0.93076, -1.06034, -1.19805, -1.30248, -1.50927, -1.56056, -1.46278, -1.38937, -1.40336, -1.50759, -1.61792, -1.83368, -1.96470, -2.03595, -2.04195, -2.07926, -2.10857, +0.71165, 0.80679, 0.98167, 1.13272, 1.40941, 1.69549, 1.82998, 1.91659, 1.95050, 1.86723, 1.80717, 1.83126, 1.89171, 1.97717, 2.08225, 2.05421, 1.82991, 1.67031, 1.56461, 1.46008, 1.35667, 1.28980, 1.27241, 1.26106, 1.27956, 1.27115, 1.36081, 1.52942, 1.68690, 1.85447, 2.01507, 2.20755, 2.33466, 2.39449, 2.52022, 2.51913, 2.47474, 2.40667, 2.30171, 2.20231, 2.12813, 2.02769, 1.85188, 1.70376, 1.53840, 1.46026, 1.47695, 1.43463, 1.33512, 1.40075, 1.50563, 1.46796, 1.46207, 1.56359, 1.62830, 1.60749, 1.63518, 1.62549, 1.49013, 1.32510, 1.23032, 1.15203, 1.09350, 1.07302, 1.19028, 1.27970, 1.40600, 1.46944, 1.46272, 1.36715, 1.20163, 1.04950, 1.04857, 1.10409, 1.17034, 1.30123, 1.27449, 1.20706, 1.26658, 1.41110, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.10257, 0.01433, 0.03824, 0.18249, 0.37420, 0.54047, 0.72633, 0.77970, 0.88239, 0.89682, 0.89901, 0.94133, 0.89463, 0.81763, 0.79357, 0.81188, 0.72090, 0.62562, 0.52596, 0.49444, 0.59311, 0.71701, 0.78047, 0.90849, 1.05829, 1.06169, 1.03090, 1.01607, 0.95721, 0.83582, 0.72503, 0.61769, 0.51783, 0.40664, 0.48097, 0.57529, 0.57233, 0.54185, 0.53920, 0.37207, 0.25817, 0.10296, 0.00323, -0.07777, -0.22809, -0.41773, -0.63803, -0.73450, -0.74804, -0.59521, -0.57773, -0.74062, -0.78418, -0.70300, -0.76925, -0.79402, -0.64552, -0.66157, -0.84601, -0.91980, -0.82380, -0.75957, -0.72501, -0.61716, -0.51801, -0.51670, -0.47796, -0.43673, -0.40159, -0.44386, -0.42736, -0.54624, -0.69644, -0.90932, -1.09562, -1.16033, -1.28363, -1.47349, -1.62993, -1.67511, -1.78015, -1.84003, -1.87912, -1.97370, -2.00261, -1.88106, -1.76500, -1.61844, -1.43946, -1.35307, -1.39459, -1.47755, -1.49250, -1.56616, -1.61989, -1.66133, -1.79782, -1.95227, -2.06096, -2.13195, -2.15677, -2.14626, -1.90771, -1.73719, -1.55053, -1.46208, -1.53492, -1.54406, -1.46763, -1.32029, -1.23000, -1.14453, -1.02833, -0.87079, -0.80956, -0.86231, -0.78141, -0.65345, -0.73001, -0.86133, -0.86123, -0.88319, -0.98474, -0.99328, -0.89371, -0.89698, -0.98250, -1.01953, -1.05066, -1.11509, -1.07935, -0.98962, -0.92980, -0.97462, -0.93445, -0.93984, -1.02116, -1.12090, -1.22131, -1.19785, -1.21286, -1.29999, -1.43247, -1.58749, -1.84688, -2.06482, -2.18828, -2.37756, -2.54266, -2.51894, -2.52684, -2.60537, -2.61562, -2.65943, -2.73695, -2.79205, -2.73567, -2.63125, -2.60115, -2.53080, -2.49751, -2.47399, -2.34054, -2.12931, -1.86151, -1.72233, -1.66442, -1.61925, -1.56624, -1.45173, -1.54577, -1.61871, -1.53652, -1.39398, -1.28846, -1.12644, -0.96737, -0.94949, -1.02381, -1.15317, -1.17074, -1.04846, -0.91919, -0.78949, -0.55136, -0.36188, -0.28368, -0.17331, 0.07405, 0.33630, 0.58801, 0.89253, 1.09800, 1.17907, 1.26510, 1.42684, 1.52427, 1.48285, 1.45381, 1.47217, 1.39932, 1.41550, 1.41070, 1.43019, 1.47158, 1.51337, 1.59406, 1.67945, 1.72408, 1.75842, 1.81017, 1.76138, 1.74481, 1.90624, 2.15393, 2.22457, 2.29689, 2.34701, 2.22607, 2.10686, 2.05524, 2.06908, 2.13343, 2.25078, 2.40338, 2.42063, 2.35433, 2.45074, 2.73559, 3.02371, 3.14665, 3.24937, 3.30482, 3.42657, 3.39627, 3.45412, 3.67523, 3.85305, 3.94392, 4.05908, 4.18280, 4.19621, 4.19872, 4.15649, 4.05478, 3.98769, 3.92803, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 3.31961, 3.21293, 3.16346, 3.06742, 2.85861, 2.62186, 2.50424, 2.37050, 2.19110, 1.96605, 1.79834, 1.55273, 1.47105, 1.40356, 1.30932, 1.20216, 1.02772, 0.74839, 0.41418, 0.12330, -0.12828, -0.19855, -0.29671, -0.41348, -0.41144, -0.41853, -0.58261, -0.76577, -0.81315, -0.83765, -0.83493, -0.70935, -0.61231, -0.62732, -0.62204, -0.53235, -0.51916, -0.69748, -0.78707, -0.76501, -0.77432, -0.94971, -1.02062, -1.13932, -1.23759, -1.37229, -1.42348, -1.31295, -1.24263, -1.24141, -1.28715, -1.36916, -1.55380, -1.66590, -1.77297, -1.92202, -1.98350, -1.91832, +0.83873, 0.84463, 0.97460, 1.13926, 1.40882, 1.67374, 1.82720, 1.87055, 1.77241, 1.71864, 1.67599, 1.72074, 1.85006, 1.91907, 1.94368, 1.75718, 1.57041, 1.42752, 1.30105, 1.28601, 1.20814, 1.10235, 1.02712, 1.00247, 1.07353, 1.09945, 1.20635, 1.43474, 1.63525, 1.75622, 1.86197, 2.09528, 2.26926, 2.26640, 2.30962, 2.34742, 2.32819, 2.29664, 2.18421, 2.11910, 2.04864, 2.06322, 1.96550, 1.81745, 1.67502, 1.51562, 1.42279, 1.32407, 1.26077, 1.30043, 1.30655, 1.38389, 1.48460, 1.57962, 1.56237, 1.48792, 1.52937, 1.55160, 1.46017, 1.38648, 1.29509, 1.16486, 1.01143, 1.03345, 1.17096, 1.22038, 1.25181, 1.28315, 1.17037, 1.08775, 0.95031, 0.90769, 0.88696, 0.96060, 0.96329, 0.91918, 0.90663, 0.94764, 1.06200, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00001, 0.02029, 0.08300, 0.20315, 0.29956, 0.53549, 0.78979, 0.85981, 0.81253, 0.82499, 0.79822, 0.88957, 0.87853, 0.91210, 0.85780, 0.83996, 0.71162, 0.55052, 0.45192, 0.44329, 0.52649, 0.61446, 0.71887, 0.94074, 0.98482, 1.05652, 1.08603, 1.07215, 0.96348, 0.78809, 0.65565, 0.57739, 0.48262, 0.47194, 0.56872, 0.65715, 0.54398, 0.45118, 0.37013, 0.22616, 0.05581, 0.02461, -0.05184, -0.10784, -0.35270, -0.57900, -0.81891, -0.81175, -0.72854, -0.64036, -0.62226, -0.69277, -0.72799, -0.70848, -0.81700, -0.78657, -0.75643, -0.70155, -0.76034, -0.75612, -0.66742, -0.62241, -0.58155, -0.47196, -0.42132, -0.35876, -0.28933, -0.24332, -0.36003, -0.43434, -0.41066, -0.47210, -0.68168, -0.82250, -1.01495, -1.10763, -1.28593, -1.39468, -1.56238, -1.61746, -1.69557, -1.82620, -1.85380, -1.86932, -1.90973, -1.85998, -1.82616, -1.61004, -1.51994, -1.43863, -1.44718, -1.51621, -1.57555, -1.66657, -1.69659, -1.67532, -1.82710, -2.02009, -2.20614, -2.28051, -2.39088, -2.36335, -2.10273, -1.89591, -1.86568, -1.82793, -1.85031, -1.73934, -1.63429, -1.46507, -1.39177, -1.28721, -1.11331, -1.00696, -0.95158, -0.92282, -0.81775, -0.70910, -0.84788, -0.91259, -0.99678, -1.07432, -1.13134, -1.15160, -1.11496, -1.14152, -1.18820, -1.18124, -1.26998, -1.32069, -1.24595, -1.10714, -1.09064, -1.14956, -1.10511, -1.13326, -1.31993, -1.40559, -1.47167, -1.41932, -1.43369, -1.48122, -1.56713, -1.72406, -1.94112, -2.21263, -2.38225, -2.48562, -2.58650, -2.57782, -2.66490, -2.65200, -2.65179, -2.67974, -2.63341, -2.61964, -2.59956, -2.61100, -2.64522, -2.51733, -2.44309, -2.34373, -2.16326, -1.98313, -1.92399, -1.97425, -1.87281, -1.71037, -1.67530, -1.62589, -1.69363, -1.74073, -1.67737, -1.56990, -1.45167, -1.31777, -1.08343, -1.04692, -1.13721, -1.17609, -1.13942, -1.06339, -1.05335, -0.93328, -0.69247, -0.50402, -0.27020, -0.09618, 0.07277, 0.26010, 0.47064, 0.78950, 0.99776, 1.10380, 1.22792, 1.33362, 1.34416, 1.22861, 1.24907, 1.33349, 1.28431, 1.30682, 1.44450, 1.52809, 1.59683, 1.59519, 1.67525, 1.71876, 1.83176, 1.84794, 1.80894, 1.81608, 1.88008, 2.06162, 2.23756, 2.31772, 2.38905, 2.27097, 2.19595, 2.16304, 2.16122, 2.21437, 2.26937, 2.35434, 2.36309, 2.24922, 2.23961, 2.36636, 2.58174, 2.70783, 2.86545, 3.04507, 3.11205, 3.13998, 3.17086, 3.23216, 3.48953, 3.65440, 3.80573, 3.93637, 4.16984, 4.23012, 4.16539, 4.13634, 4.11626, 4.07890, 3.96733, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 3.44443, 3.28722, 3.17665, 3.07619, 2.85970, 2.69015, 2.57280, 2.41352, 2.14104, 1.99771, 1.90077, 1.69556, 1.50520, 1.48549, 1.40467, 1.34484, 1.08056, 0.77832, 0.40579, 0.18552, 0.00223, -0.14009, -0.22385, -0.29134, -0.36301, -0.46929, -0.64351, -0.69929, -0.77543, -0.72164, -0.68550, -0.66771, -0.67865, -0.68749, -0.62256, -0.51602, -0.57539, -0.69963, -0.77367, -0.78316, -0.92425, -1.06269, -1.06487, -1.09427, -1.26009, -1.33542, -1.35379, -1.18547, -1.17573, -1.17772, -1.27782, -1.29158, -1.36672, -1.52514, -1.69874, -1.85346, -1.92214, -1.89231, +0.87284, 0.86387, 1.04625, 1.23370, 1.36557, 1.50984, 1.71301, 1.79266, 1.66745, 1.58030, 1.59640, 1.73777, 1.83068, 1.78515, 1.67775, 1.44343, 1.29170, 1.18686, 1.09572, 1.01555, 0.91278, 0.84841, 0.85043, 0.91636, 0.95339, 0.99457, 1.15718, 1.40652, 1.55002, 1.62103, 1.79101, 2.01280, 2.07764, 1.97001, 1.98368, 2.06889, 2.08607, 2.07556, 2.02311, 2.02838, 2.00331, 2.01602, 2.01302, 2.02131, 1.92523, 1.71215, 1.53834, 1.44472, 1.36963, 1.31169, 1.28043, 1.33727, 1.47152, 1.57664, 1.54532, 1.48614, 1.40325, 1.37247, 1.41346, 1.48496, 1.39190, 1.21866, 1.12144, 1.14700, 1.09958, 0.98721, 1.03548, 1.08239, 0.93469, 0.82419, 0.76849, 0.84244, 0.81181, 0.76806, 0.66946, 0.63500, 0.69181, 0.79957, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.03376, 0.01876, 0.15888, 0.20300, 0.17506, 0.24156, 0.52141, 0.75066, 0.74249, 0.66375, 0.66955, 0.61534, 0.63769, 0.70694, 0.88865, 0.92172, 0.88925, 0.76393, 0.73193, 0.67479, 0.63309, 0.67487, 0.73430, 0.86657, 1.00241, 1.01233, 1.02355, 0.98772, 0.98920, 0.90892, 0.82311, 0.68378, 0.56519, 0.56075, 0.66308, 0.67103, 0.59403, 0.49759, 0.41905, 0.25713, 0.03335, -0.06798, 0.02139, -0.04722, -0.20744, -0.50231, -0.68235, -0.80894, -0.74512, -0.66815, -0.57769, -0.56975, -0.60796, -0.63132, -0.64545, -0.72961, -0.78707, -0.81483, -0.78799, -0.79165, -0.65987, -0.51207, -0.37382, -0.34757, -0.41708, -0.41958, -0.26239, -0.16183, -0.21430, -0.37062, -0.42118, -0.44886, -0.61288, -0.74917, -0.74572, -0.84900, -0.98912, -1.15199, -1.14998, -1.26068, -1.35046, -1.47922, -1.55528, -1.54312, -1.57922, -1.67402, -1.74963, -1.80676, -1.71716, -1.65389, -1.59954, -1.62633, -1.62486, -1.64887, -1.65942, -1.72557, -1.80889, -1.90717, -2.00254, -2.18435, -2.35445, -2.47164, -2.38074, -2.20732, -2.17701, -2.22350, -2.12098, -1.99313, -1.82603, -1.70894, -1.56042, -1.49338, -1.38501, -1.24561, -1.08425, -0.95153, -0.90244, -0.84501, -0.80932, -0.92401, -1.02900, -1.14371, -1.27683, -1.40218, -1.48252, -1.49621, -1.43032, -1.38389, -1.44833, -1.56862, -1.53103, -1.41999, -1.36108, -1.33994, -1.30084, -1.25862, -1.42050, -1.63528, -1.63314, -1.63816, -1.62015, -1.64145, -1.60409, -1.59926, -1.73837, -1.99918, -2.27780, -2.44449, -2.52692, -2.59186, -2.60501, -2.66717, -2.64312, -2.62709, -2.65294, -2.68725, -2.65464, -2.58492, -2.53302, -2.50016, -2.40928, -2.30361, -2.07983, -1.88980, -1.86209, -1.98499, -2.02918, -1.85637, -1.71355, -1.71473, -1.69549, -1.73809, -1.78406, -1.76362, -1.64666, -1.49315, -1.38243, -1.23786, -1.18992, -1.16927, -1.13714, -1.09479, -1.10301, -1.16922, -1.17793, -1.02197, -0.77218, -0.49017, -0.26557, -0.10101, 0.10765, 0.33866, 0.55535, 0.73569, 0.96104, 1.19428, 1.24061, 1.17823, 1.14044, 1.20439, 1.23845, 1.18865, 1.31759, 1.56958, 1.67175, 1.69083, 1.65715, 1.71652, 1.76404, 1.86884, 1.90260, 1.96145, 2.03951, 2.12824, 2.23422, 2.27289, 2.29086, 2.29148, 2.16035, 2.07791, 2.11154, 2.23258, 2.39121, 2.50449, 2.47854, 2.31071, 2.23156, 2.36614, 2.48449, 2.53012, 2.56323, 2.72319, 2.87782, 2.89864, 2.97222, 3.08115, 3.13375, 3.27712, 3.42872, 3.64526, 3.84352, 4.08617, 4.14907, 4.14693, 4.08110, 4.05051, 4.03777, 3.92886, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 3.49700, 3.46082, 3.30954, 3.13323, 2.99047, 2.92190, 2.76068, 2.46868, 2.19775, 2.09452, 1.93732, 1.63127, 1.40410, 1.39444, 1.35744, 1.28963, 1.05019, 0.82144, 0.52733, 0.32602, 0.09471, -0.05800, -0.12792, -0.18927, -0.29194, -0.44053, -0.57949, -0.65732, -0.70211, -0.69721, -0.71547, -0.72621, -0.68788, -0.51015, -0.39202, -0.42545, -0.53915, -0.56366, -0.61591, -0.73728, -0.87494, -0.92874, -0.95384, -1.09506, -1.23712, -1.22751, -1.18890, -1.09372, -1.14523, -1.17546, -1.33426, -1.35808, -1.39280, -1.44293, -1.61344, -1.81958, -1.90889, -1.93601, +0.87356, 0.96996, 1.13888, 1.26821, 1.34940, 1.46045, 1.63541, 1.73621, 1.75044, 1.64301, 1.53152, 1.62475, 1.61787, 1.44847, 1.27034, 1.17611, 1.15888, 1.09158, 1.03322, 0.89351, 0.80637, 0.73449, 0.66910, 0.79397, 0.85991, 0.99932, 1.15929, 1.29598, 1.43439, 1.48481, 1.69524, 1.78923, 1.71538, 1.71322, 1.76265, 1.82672, 1.92013, 1.99544, 2.01130, 2.03828, 2.12419, 2.08973, 1.97644, 2.02236, 2.00077, 1.80954, 1.63817, 1.62759, 1.61070, 1.50797, 1.48334, 1.47918, 1.58511, 1.59623, 1.42643, 1.36000, 1.28454, 1.34330, 1.46878, 1.47927, 1.41992, 1.24533, 1.24172, 1.20223, 0.94890, 0.86034, 0.94370, 0.93632, 0.87980, 0.80988, 0.77512, 0.77074, 0.73822, 0.60941, 0.36160, 0.32356, 0.47461, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.00737, -0.01642, 0.07423, 0.07197, 0.13678, 0.08326, 0.23292, 0.51779, 0.61734, 0.67485, 0.67599, 0.57717, 0.52688, 0.48837, 0.56317, 0.72774, 0.91018, 1.00151, 0.88207, 0.87015, 0.89475, 0.82338, 0.82907, 0.90746, 1.08363, 1.10711, 1.11740, 1.07216, 1.02882, 1.04754, 0.89398, 0.76504, 0.64438, 0.55678, 0.64809, 0.63550, 0.60804, 0.47053, 0.44394, 0.42675, 0.18841, 0.01426, 0.03568, 0.02835, -0.05596, -0.23577, -0.47587, -0.63431, -0.61975, -0.51091, -0.54359, -0.57256, -0.54204, -0.58892, -0.61526, -0.60922, -0.57937, -0.67138, -0.68326, -0.68556, -0.66025, -0.47809, -0.42834, -0.36962, -0.30460, -0.38521, -0.32067, -0.26757, -0.16641, -0.21632, -0.29708, -0.28702, -0.45445, -0.68319, -0.69225, -0.69692, -0.69780, -0.74531, -0.80671, -0.82535, -0.87199, -0.90889, -1.11826, -1.29544, -1.29537, -1.41838, -1.57568, -1.70340, -1.69387, -1.65644, -1.59814, -1.59783, -1.67865, -1.65111, -1.72645, -1.81693, -1.86075, -1.93331, -1.90204, -2.00080, -2.14015, -2.31407, -2.41796, -2.32223, -2.35999, -2.43895, -2.34579, -2.19544, -1.96671, -1.75061, -1.59321, -1.53275, -1.48291, -1.33095, -1.27806, -1.22246, -1.03649, -0.97807, -0.96414, -0.96771, -0.96554, -1.08549, -1.24746, -1.43665, -1.61686, -1.69112, -1.76007, -1.77539, -1.66793, -1.70369, -1.72442, -1.72098, -1.67825, -1.68124, -1.66441, -1.52386, -1.54595, -1.74522, -1.79236, -1.77936, -1.78342, -1.73724, -1.70499, -1.66717, -1.66460, -1.73600, -2.03181, -2.40073, -2.52394, -2.56429, -2.63500, -2.68311, -2.65604, -2.59367, -2.55824, -2.57283, -2.67258, -2.60551, -2.53282, -2.49816, -2.34888, -2.21924, -2.04133, -1.87158, -1.82651, -1.83746, -1.96623, -1.85979, -1.70608, -1.65541, -1.53678, -1.53075, -1.62258, -1.63936, -1.61252, -1.54031, -1.44026, -1.29338, -1.23877, -1.31308, -1.26063, -1.21250, -1.26231, -1.35981, -1.37412, -1.35947, -1.21463, -0.90553, -0.63003, -0.32727, -0.16106, -0.05680, 0.13340, 0.26380, 0.46186, 0.71642, 0.91868, 1.06018, 1.03998, 1.13560, 1.18632, 1.13775, 1.24505, 1.45404, 1.62394, 1.73586, 1.77199, 1.74505, 1.77333, 1.91731, 2.01238, 1.94238, 1.99750, 2.13391, 2.19532, 2.22770, 2.25514, 2.30527, 2.28040, 2.24633, 2.19057, 2.28432, 2.42339, 2.47476, 2.55381, 2.52980, 2.41284, 2.43303, 2.49093, 2.61039, 2.57718, 2.62239, 2.73037, 2.75855, 2.86850, 3.03029, 3.07684, 3.15242, 3.24551, 3.37171, 3.51247, 3.74870, 3.94347, 3.90451, 3.89314, 3.89591, 3.87605, 3.88268, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 3.43829, 3.38054, 3.26210, 3.19983, 3.01969, 2.85866, 2.52018, 2.27815, 2.10628, 1.76055, 1.48606, 1.35545, 1.28254, 1.32201, 1.29527, 1.11120, 0.84512, 0.65205, 0.49340, 0.15246, -0.09726, -0.12573, -0.19548, -0.26657, -0.35078, -0.37832, -0.50679, -0.56753, -0.64311, -0.66957, -0.62355, -0.56454, -0.36785, -0.19350, -0.23516, -0.30231, -0.43122, -0.46320, -0.59566, -0.65465, -0.63883, -0.78003, -0.93036, -0.94841, -1.01083, -1.00311, -1.01173, -1.10248, -1.24020, -1.37050, -1.32793, -1.40684, -1.49656, -1.58606, -1.80043, -1.91208, -1.97848, +0.95380, 1.05531, 1.19582, 1.31920, 1.41345, 1.53356, 1.65940, 1.76962, 1.78563, 1.62747, 1.50583, 1.50290, 1.37653, 1.18672, 0.95355, 0.88214, 0.99848, 0.98548, 0.92957, 0.78890, 0.62901, 0.51288, 0.50069, 0.66504, 0.70855, 0.83855, 1.00603, 1.11570, 1.29294, 1.40667, 1.45669, 1.40693, 1.41373, 1.51052, 1.61254, 1.73089, 1.85431, 1.99361, 2.04979, 2.11046, 2.17182, 2.01724, 1.88888, 1.97488, 1.99003, 1.90121, 1.72833, 1.64241, 1.67885, 1.63917, 1.60898, 1.57291, 1.53959, 1.41188, 1.26068, 1.23632, 1.17286, 1.24896, 1.40990, 1.41898, 1.36562, 1.27860, 1.20154, 1.06489, 0.88646, 0.87098, 0.90758, 0.92473, 0.93426, 0.91434, 0.83874, 0.72634, 0.57600, 0.30731, 0.07306, 0.12259, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.00486, -0.01159, -0.06355, -0.03466, -0.10362, -0.04937, 0.03392, 0.18850, 0.37626, 0.51190, 0.67563, 0.67398, 0.58450, 0.51596, 0.44170, 0.45435, 0.59789, 0.82191, 0.91263, 0.89465, 0.99178, 1.05134, 1.03462, 1.02173, 0.97525, 1.10166, 1.13527, 1.13039, 1.08756, 1.02852, 0.96729, 0.82505, 0.70931, 0.53148, 0.38680, 0.48370, 0.48899, 0.46461, 0.43702, 0.37697, 0.27578, 0.14719, 0.13485, 0.14124, 0.07984, -0.05173, -0.18536, -0.35671, -0.44207, -0.39152, -0.42517, -0.50711, -0.49727, -0.48187, -0.50155, -0.51383, -0.59550, -0.55069, -0.55196, -0.55474, -0.54976, -0.53468, -0.46169, -0.46593, -0.40177, -0.34422, -0.43417, -0.32442, -0.25167, -0.18166, -0.10620, -0.14587, -0.24144, -0.40269, -0.54724, -0.58601, -0.56543, -0.51471, -0.46240, -0.46784, -0.50106, -0.52630, -0.65166, -0.88774, -1.02576, -1.09662, -1.26032, -1.42194, -1.65183, -1.64350, -1.52892, -1.48422, -1.53010, -1.68732, -1.79459, -1.88487, -1.91366, -1.93737, -2.04398, -2.00770, -2.02722, -2.11110, -2.17262, -2.28701, -2.41621, -2.54848, -2.50866, -2.34918, -2.11146, -1.84593, -1.62286, -1.45776, -1.43143, -1.40882, -1.39228, -1.41659, -1.31627, -1.12243, -1.04596, -1.01900, -1.11300, -1.12436, -1.17743, -1.37277, -1.60257, -1.80848, -1.96295, -2.02324, -2.00143, -1.91953, -2.00737, -2.02703, -2.00344, -2.00178, -1.99087, -1.96960, -1.94159, -1.96934, -1.98670, -1.95624, -1.92997, -1.90877, -1.82899, -1.75796, -1.72783, -1.74743, -1.89134, -2.20821, -2.47353, -2.51783, -2.51155, -2.54454, -2.68736, -2.73951, -2.61281, -2.52372, -2.50383, -2.58989, -2.61075, -2.56852, -2.41806, -2.17539, -2.06728, -1.93919, -1.84101, -1.86823, -1.82057, -1.82004, -1.73034, -1.61417, -1.47484, -1.29225, -1.28346, -1.37079, -1.39347, -1.35863, -1.33244, -1.28488, -1.24499, -1.31680, -1.37194, -1.28394, -1.26838, -1.36642, -1.57180, -1.66229, -1.55481, -1.31120, -0.98948, -0.73305, -0.49314, -0.36183, -0.22079, -0.05909, -0.06226, 0.04520, 0.30612, 0.54062, 0.78708, 0.90486, 0.95588, 0.96217, 1.03692, 1.25933, 1.45632, 1.58082, 1.66829, 1.75328, 1.76235, 1.83386, 1.97188, 1.97848, 1.91959, 2.00315, 2.14372, 2.25215, 2.26096, 2.20551, 2.28360, 2.32901, 2.36864, 2.37413, 2.41289, 2.44075, 2.45129, 2.52619, 2.48863, 2.40115, 2.49417, 2.54236, 2.63154, 2.67458, 2.64493, 2.62109, 2.69245, 2.90843, 3.06796, 3.12233, 3.17679, 3.25544, 3.33528, 3.42299, 3.57442, 3.58910, 3.55089, 3.63156, 3.71621, 3.82464, 3.86380, 3.78378, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 3.33424, 3.29511, 3.15393, 3.10346, 2.93499, 2.76759, 2.53255, 2.21570, 1.84424, 1.49920, 1.35684, 1.25654, 1.23879, 1.30918, 1.33572, 1.16429, 0.88460, 0.70747, 0.45971, 0.14311, -0.03400, -0.07891, -0.11073, -0.12537, -0.26598, -0.28803, -0.38497, -0.52219, -0.63219, -0.67380, -0.65244, -0.50312, -0.25343, -0.10847, -0.18640, -0.23358, -0.34522, -0.37867, -0.36309, -0.38912, -0.47565, -0.59119, -0.61480, -0.63061, -0.70153, -0.78363, -0.89076, -1.04717, -1.23152, -1.32328, -1.34075, -1.42624, -1.44216, -1.49881, -1.64664, -1.73341, -1.93776, +1.08024, 1.03455, 1.15008, 1.32123, 1.45528, 1.59314, 1.60393, 1.70092, 1.80724, 1.65287, 1.47078, 1.29124, 1.01796, 0.89933, 0.80166, 0.82057, 0.87373, 0.75474, 0.69295, 0.55514, 0.41616, 0.37302, 0.39690, 0.52961, 0.60156, 0.76867, 0.94664, 0.98179, 1.10160, 1.23956, 1.21487, 1.24247, 1.34082, 1.32764, 1.44352, 1.62017, 1.69301, 1.82915, 1.85151, 1.97031, 2.13314, 1.99730, 1.86828, 1.92161, 1.86836, 1.80499, 1.68821, 1.60751, 1.62817, 1.55965, 1.53698, 1.44495, 1.33879, 1.31808, 1.26728, 1.22250, 1.17961, 1.28956, 1.46178, 1.42775, 1.28515, 1.22002, 1.07128, 1.06581, 1.06347, 0.90169, 0.79146, 0.83348, 0.83885, 0.85615, 0.69357, 0.48111, 0.36198, 0.14035, -0.02773, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.03456, 0.01059, 0.00215, 0.02346, 0.05300, -0.06634, -0.14639, -0.04379, 0.07886, 0.32006, 0.53569, 0.54207, 0.43074, 0.43075, 0.35087, 0.30903, 0.28398, 0.41936, 0.72312, 0.85704, 0.87917, 1.00044, 1.03398, 1.03242, 1.06096, 0.99539, 1.05572, 1.03303, 1.06818, 1.06119, 0.96963, 0.95161, 0.83861, 0.64674, 0.42148, 0.34442, 0.46437, 0.54780, 0.46993, 0.40945, 0.22140, 0.14938, 0.21451, 0.17178, 0.02793, -0.03943, -0.18445, -0.20778, -0.26614, -0.29589, -0.24169, -0.33539, -0.46762, -0.45209, -0.50897, -0.59572, -0.53610, -0.53353, -0.47279, -0.54286, -0.58184, -0.56599, -0.56575, -0.40100, -0.33628, -0.32069, -0.31853, -0.31863, -0.14355, -0.02775, -0.10368, -0.09426, -0.17483, -0.22383, -0.20910, -0.35595, -0.54128, -0.46746, -0.43364, -0.38137, -0.38712, -0.44694, -0.38813, -0.45166, -0.70458, -0.87695, -1.05338, -1.25916, -1.33392, -1.49112, -1.48569, -1.48169, -1.49975, -1.55952, -1.77123, -1.83328, -1.84257, -1.82470, -1.86809, -1.97533, -1.97796, -1.92707, -2.05196, -2.14625, -2.35438, -2.59346, -2.58943, -2.46164, -2.35948, -2.05858, -1.86797, -1.72483, -1.56617, -1.55177, -1.50576, -1.50294, -1.55033, -1.41706, -1.27449, -1.28783, -1.25221, -1.29298, -1.25730, -1.32061, -1.53635, -1.75397, -2.00855, -2.11848, -2.07094, -2.08022, -2.15667, -2.31716, -2.33517, -2.23214, -2.28933, -2.33589, -2.35071, -2.35921, -2.25371, -2.20759, -2.32138, -2.27734, -2.20229, -2.11763, -2.02776, -2.04450, -2.02081, -2.03633, -2.27616, -2.45355, -2.51578, -2.60566, -2.61136, -2.70447, -2.73593, -2.63299, -2.55882, -2.43318, -2.50125, -2.56289, -2.47952, -2.27855, -2.06058, -1.96011, -1.86140, -1.77912, -1.84396, -1.79756, -1.69789, -1.62427, -1.44540, -1.27134, -1.23179, -1.20572, -1.25813, -1.34014, -1.27006, -1.26344, -1.22107, -1.18525, -1.32873, -1.38764, -1.31648, -1.37158, -1.46477, -1.63843, -1.72686, -1.61920, -1.39676, -1.08148, -0.91643, -0.76370, -0.53808, -0.32974, -0.23591, -0.28498, -0.16975, 0.13130, 0.31974, 0.46529, 0.58659, 0.59519, 0.75215, 0.96125, 1.04089, 1.15030, 1.30531, 1.39786, 1.57486, 1.62538, 1.74049, 1.92905, 1.93452, 1.89065, 1.97428, 2.06423, 2.22105, 2.37698, 2.37702, 2.38433, 2.33247, 2.42064, 2.45539, 2.42960, 2.46685, 2.46320, 2.49666, 2.49442, 2.55231, 2.69183, 2.64684, 2.55560, 2.58403, 2.50840, 2.53632, 2.69033, 2.81105, 2.92495, 3.03948, 3.01123, 3.05885, 3.09380, 3.18169, 3.39074, 3.39789, 3.36735, 3.46357, 3.55840, 3.74410, 3.88122, 3.82324, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 3.23173, 3.09763, 2.98612, 2.96978, 2.84888, 2.57470, 2.31391, 1.89534, 1.56255, 1.39169, 1.22264, 1.06537, 1.11230, 1.12316, 1.17600, 1.02271, 0.78339, 0.70897, 0.52561, 0.29756, 0.14012, -0.03425, -0.13880, -0.06639, -0.14568, -0.21511, -0.45709, -0.64660, -0.70912, -0.73313, -0.54805, -0.32307, -0.18897, -0.15678, -0.16932, -0.14153, -0.20661, -0.33947, -0.27088, -0.27309, -0.31100, -0.31098, -0.40053, -0.53640, -0.54267, -0.67953, -0.83872, -1.04615, -1.26698, -1.25968, -1.21303, -1.31533, -1.37382, -1.51924, -1.67139, -1.64976, -1.79345, +1.18616, 1.13935, 1.24908, 1.43761, 1.58159, 1.67294, 1.66072, 1.69627, 1.74123, 1.58314, 1.29195, 1.00616, 0.82845, 0.80770, 0.77621, 0.80356, 0.78017, 0.61319, 0.51996, 0.43298, 0.33280, 0.24598, 0.24136, 0.38079, 0.49062, 0.66942, 0.78530, 0.76183, 0.88806, 1.04724, 1.11979, 1.21525, 1.25235, 1.20052, 1.30707, 1.45686, 1.49223, 1.56778, 1.62770, 1.79647, 1.96086, 1.89854, 1.77936, 1.78585, 1.79089, 1.74465, 1.60253, 1.52348, 1.57471, 1.56147, 1.51903, 1.40899, 1.31709, 1.35428, 1.37603, 1.38381, 1.37658, 1.47056, 1.57327, 1.45438, 1.31890, 1.26798, 1.15358, 1.24309, 1.22092, 0.96675, 0.78727, 0.76936, 0.74549, 0.71345, 0.53988, 0.33534, 0.24301, 0.09833, -0.04161, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.13542, 0.04826, 0.05395, 0.09653, 0.18444, 0.21736, 0.00778, -0.12975, -0.08024, 0.02202, 0.28396, 0.40877, 0.28870, 0.17156, 0.20681, 0.17593, 0.16737, 0.20384, 0.39578, 0.67258, 0.79731, 0.83239, 0.90605, 1.01418, 1.10724, 1.11160, 1.02450, 1.08293, 1.16555, 1.24373, 1.26039, 1.17200, 1.08122, 0.92557, 0.72900, 0.54631, 0.53669, 0.63945, 0.67168, 0.58437, 0.44732, 0.19435, 0.15883, 0.19731, 0.08158, -0.07745, -0.12579, -0.15987, -0.10773, -0.06336, -0.05460, -0.15119, -0.35442, -0.52819, -0.59147, -0.64285, -0.69026, -0.64552, -0.60687, -0.52765, -0.54381, -0.57954, -0.54172, -0.48975, -0.29186, -0.18579, -0.15176, -0.14458, -0.10668, 0.04416, 0.05408, -0.08789, -0.15230, -0.23181, -0.15514, -0.09248, -0.24754, -0.39883, -0.31305, -0.28585, -0.30876, -0.33540, -0.33648, -0.26989, -0.33527, -0.58213, -0.86105, -1.03238, -1.09507, -1.12763, -1.25299, -1.27825, -1.29992, -1.35385, -1.43140, -1.59545, -1.64120, -1.66200, -1.60783, -1.63553, -1.76144, -1.82998, -1.88458, -2.04988, -2.18557, -2.43922, -2.59036, -2.49264, -2.36841, -2.23330, -1.99678, -1.93834, -1.91181, -1.78455, -1.68928, -1.67172, -1.75680, -1.81949, -1.75977, -1.64469, -1.59658, -1.56216, -1.56362, -1.47649, -1.42557, -1.55304, -1.75113, -1.99514, -2.12696, -2.14042, -2.21872, -2.37717, -2.59813, -2.63716, -2.57928, -2.64287, -2.66171, -2.66564, -2.58796, -2.46059, -2.50370, -2.63699, -2.56671, -2.44670, -2.36544, -2.29207, -2.24903, -2.16124, -2.08968, -2.22147, -2.39435, -2.49726, -2.55518, -2.55376, -2.62859, -2.61204, -2.44679, -2.33014, -2.15556, -2.18836, -2.29699, -2.29577, -2.13888, -1.93599, -1.84351, -1.77246, -1.71947, -1.74606, -1.64719, -1.50876, -1.42812, -1.30912, -1.24825, -1.23315, -1.15362, -1.19456, -1.32326, -1.29090, -1.24891, -1.22998, -1.28343, -1.44797, -1.53693, -1.49168, -1.43592, -1.44797, -1.60746, -1.69535, -1.58266, -1.37248, -1.12307, -1.01968, -0.93398, -0.74091, -0.52308, -0.39685, -0.39423, -0.25354, 0.00589, 0.09594, 0.17204, 0.25829, 0.32864, 0.58517, 0.75778, 0.77308, 0.86680, 1.05897, 1.22695, 1.44168, 1.58623, 1.72984, 1.85651, 1.87147, 1.83617, 1.91381, 2.09573, 2.33617, 2.55555, 2.58302, 2.55441, 2.49039, 2.54497, 2.57462, 2.51748, 2.48016, 2.48759, 2.60276, 2.67152, 2.78864, 2.81967, 2.58153, 2.39757, 2.39483, 2.37762, 2.45783, 2.52489, 2.56819, 2.69328, 2.80364, 2.74839, 2.74501, 2.81596, 2.95839, 3.17608, 3.22874, 3.21714, 3.25704, 3.41623, 3.68497, 3.83951, 3.79825, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.96092, 2.84020, 2.80808, 2.63644, 2.34092, 2.03788, 1.63212, 1.44550, 1.34049, 1.15633, 1.03162, 1.05130, 1.02865, 1.05377, 0.97520, 0.87144, 0.81984, 0.66844, 0.51012, 0.26990, 0.05203, -0.04699, -0.01536, -0.09750, -0.20647, -0.43327, -0.57983, -0.55368, -0.50873, -0.32847, -0.21670, -0.20150, -0.22531, -0.18590, -0.11024, -0.23879, -0.39667, -0.32084, -0.26783, -0.19046, -0.20356, -0.36509, -0.47742, -0.46643, -0.57956, -0.78029, -1.01025, -1.19838, -1.22867, -1.22019, -1.32326, -1.49681, -1.65001, -1.67596, -1.60062, -1.67003, +1.19268, 1.24595, 1.33837, 1.51490, 1.64149, 1.71690, 1.74686, 1.64914, 1.56454, 1.51260, 1.22831, 0.92486, 0.81363, 0.73134, 0.70529, 0.70019, 0.59046, 0.43607, 0.33790, 0.32229, 0.29700, 0.14061, 0.07860, 0.19839, 0.29316, 0.45876, 0.58616, 0.59344, 0.72176, 0.88248, 1.01357, 1.05583, 1.00157, 1.03481, 1.11409, 1.23075, 1.29281, 1.39472, 1.54966, 1.62643, 1.65305, 1.70096, 1.65079, 1.64430, 1.72386, 1.64404, 1.51432, 1.44572, 1.44747, 1.44921, 1.38222, 1.30274, 1.29534, 1.31826, 1.34525, 1.41419, 1.42885, 1.52267, 1.61492, 1.49270, 1.34341, 1.28137, 1.19590, 1.24688, 1.09765, 0.91266, 0.75291, 0.70255, 0.70033, 0.66040, 0.54629, 0.28487, 0.09887, 0.05191, -0.01186, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.12097, 0.08672, 0.00860, 0.09764, 0.16833, 0.26757, 0.29351, 0.06737, -0.12376, -0.14906, -0.10313, 0.08205, 0.06103, 0.01575, -0.01826, 0.02705, 0.07303, 0.10688, 0.23732, 0.39301, 0.55266, 0.76315, 0.94178, 1.00956, 1.19736, 1.26182, 1.21979, 1.15202, 1.14873, 1.22998, 1.28703, 1.29553, 1.27367, 1.15707, 0.96423, 0.81465, 0.65471, 0.65151, 0.72883, 0.73746, 0.59149, 0.40270, 0.14605, 0.10585, 0.02396, -0.04158, -0.11990, -0.14402, -0.05832, 0.04716, 0.17946, 0.14140, -0.15692, -0.40690, -0.50803, -0.63087, -0.65486, -0.73490, -0.76621, -0.70735, -0.65710, -0.64517, -0.63293, -0.56584, -0.43832, -0.24484, -0.18158, -0.12884, -0.12324, -0.10748, -0.00376, 0.00085, -0.14048, -0.19508, -0.23850, -0.11359, -0.13945, -0.24633, -0.28742, -0.21901, -0.14376, -0.14837, -0.11902, -0.11241, -0.18017, -0.28364, -0.40318, -0.70196, -0.83483, -0.88678, -0.99013, -1.09701, -1.18310, -1.24865, -1.30988, -1.40719, -1.49339, -1.51139, -1.58978, -1.53600, -1.58697, -1.74486, -1.84334, -1.90582, -2.07639, -2.21872, -2.46292, -2.52279, -2.46750, -2.34316, -2.13235, -1.99429, -1.99054, -2.00017, -1.85942, -1.73490, -1.85913, -2.04376, -2.01528, -1.99187, -1.87729, -1.80957, -1.82302, -1.76688, -1.68012, -1.62126, -1.69697, -1.90003, -2.09150, -2.22774, -2.36457, -2.48976, -2.66266, -2.89991, -2.95432, -2.90892, -2.97751, -2.99756, -2.99947, -2.86046, -2.78042, -2.81154, -2.78739, -2.69059, -2.53345, -2.42425, -2.31202, -2.19082, -2.18252, -2.16529, -2.13477, -2.25903, -2.35391, -2.36919, -2.43683, -2.49821, -2.48671, -2.35409, -2.21390, -2.06193, -2.05844, -2.12429, -2.19804, -2.08380, -1.88827, -1.82520, -1.77005, -1.67519, -1.64080, -1.52793, -1.40015, -1.31988, -1.30258, -1.31443, -1.17528, -1.06478, -1.08695, -1.19377, -1.18136, -1.12865, -1.26601, -1.47935, -1.52943, -1.55373, -1.51299, -1.38159, -1.42953, -1.56853, -1.65267, -1.62936, -1.47752, -1.31213, -1.21245, -1.08934, -0.97096, -0.80540, -0.65959, -0.64790, -0.50317, -0.24296, -0.13841, -0.05725, 0.03072, 0.15081, 0.37480, 0.46138, 0.57188, 0.67988, 0.86654, 1.08776, 1.33259, 1.57347, 1.64637, 1.65272, 1.77980, 1.84034, 1.92156, 2.18731, 2.38652, 2.59127, 2.62193, 2.53613, 2.48358, 2.50943, 2.54974, 2.54078, 2.43787, 2.42982, 2.59557, 2.65723, 2.74554, 2.71382, 2.44544, 2.24561, 2.24163, 2.26796, 2.32065, 2.25604, 2.33562, 2.46125, 2.53425, 2.52610, 2.56109, 2.73206, 2.82373, 2.92054, 3.05441, 3.14839, 3.16231, 3.37109, 3.58884, 3.73982, 3.77083, 3.76000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.80045, 2.65150, 2.59556, 2.42927, 2.12982, 1.83331, 1.48408, 1.35686, 1.19640, 1.10196, 1.04348, 1.02884, 1.04957, 1.09630, 1.12207, 1.03323, 0.87461, 0.76427, 0.71416, 0.41506, 0.22172, 0.06150, 0.01322, -0.05428, -0.22137, -0.42847, -0.52292, -0.46345, -0.35823, -0.25299, -0.29471, -0.32326, -0.36412, -0.30824, -0.20772, -0.29867, -0.44692, -0.38259, -0.31002, -0.18725, -0.27743, -0.36278, -0.37301, -0.40009, -0.49423, -0.72531, -0.93763, -1.16118, -1.37111, -1.40889, -1.37667, -1.53722, -1.58495, -1.55938, -1.51715, -1.53679, +1.26068, 1.35998, 1.44057, 1.59791, 1.58707, 1.52501, 1.52210, 1.43322, 1.39417, 1.36988, 1.12543, 0.89027, 0.72205, 0.55585, 0.52013, 0.46971, 0.35691, 0.27685, 0.20804, 0.20986, 0.30861, 0.23170, 0.13307, 0.21974, 0.24725, 0.33996, 0.50058, 0.55970, 0.69623, 0.84684, 0.90136, 0.88521, 0.88982, 0.95513, 0.97577, 1.06810, 1.09265, 1.14088, 1.31729, 1.38884, 1.42547, 1.49984, 1.48089, 1.50508, 1.51854, 1.39085, 1.32614, 1.26135, 1.24024, 1.25708, 1.18624, 1.10888, 1.20237, 1.30359, 1.31320, 1.39242, 1.38696, 1.42157, 1.51414, 1.43048, 1.32399, 1.29822, 1.18212, 1.14450, 0.98554, 0.83353, 0.69385, 0.65990, 0.61144, 0.43812, 0.29791, 0.08841, -0.01351, -0.01317, -0.07011, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.09368, 0.09979, 0.23395, 0.21813, 0.33001, 0.36475, 0.33910, 0.32471, 0.13697, -0.03519, -0.09283, -0.17680, -0.16890, -0.19467, -0.13860, -0.09716, -0.00236, 0.06046, 0.00840, 0.13141, 0.28089, 0.48476, 0.79744, 1.04377, 1.17768, 1.33297, 1.26917, 1.24547, 1.19555, 1.14439, 1.17506, 1.18501, 1.13963, 1.18554, 1.24054, 1.08876, 0.97434, 0.84982, 0.75815, 0.79427, 0.78248, 0.58683, 0.39045, 0.13117, -0.01523, -0.11133, -0.12678, -0.17678, -0.11766, 0.03072, 0.02506, 0.10949, 0.03321, -0.24371, -0.43812, -0.54688, -0.65325, -0.70131, -0.89681, -0.91630, -0.81863, -0.73500, -0.63921, -0.53951, -0.49442, -0.37155, -0.10521, -0.06523, -0.02901, -0.01832, -0.13489, -0.11547, -0.08862, -0.15775, -0.09907, -0.07991, -0.04442, -0.07844, -0.10440, -0.11090, -0.03986, 0.04763, -0.04447, -0.04403, -0.06565, -0.13115, -0.18395, -0.27340, -0.50729, -0.65697, -0.89417, -1.05815, -1.17605, -1.29459, -1.35446, -1.39737, -1.50534, -1.52261, -1.36715, -1.40497, -1.39011, -1.49351, -1.78637, -1.93510, -1.99094, -2.13702, -2.23165, -2.42467, -2.48513, -2.40905, -2.25042, -2.08280, -2.01771, -2.04039, -2.17195, -2.12136, -2.04090, -2.13971, -2.23938, -2.17483, -2.09800, -1.96118, -1.99360, -2.00918, -1.93111, -1.88158, -1.85412, -1.91108, -2.10758, -2.26346, -2.30290, -2.46756, -2.63514, -2.78346, -3.05329, -3.13424, -3.10542, -3.16791, -3.16199, -3.15429, -3.08972, -3.01562, -2.91174, -2.77947, -2.63593, -2.45166, -2.41530, -2.35920, -2.23932, -2.22680, -2.18630, -2.13871, -2.21811, -2.26742, -2.35719, -2.47234, -2.49238, -2.46197, -2.31676, -2.13587, -2.00978, -2.02293, -1.96010, -1.96393, -1.89905, -1.75327, -1.80473, -1.81451, -1.65520, -1.54409, -1.41266, -1.30720, -1.31948, -1.35612, -1.30560, -1.11445, -0.98733, -0.95770, -1.09170, -1.17523, -1.17120, -1.32191, -1.48531, -1.47539, -1.46609, -1.40899, -1.38437, -1.49573, -1.55200, -1.60724, -1.64651, -1.57558, -1.49274, -1.41749, -1.17790, -0.99020, -0.89168, -0.77631, -0.81107, -0.73632, -0.48136, -0.32645, -0.18148, -0.04790, 0.03787, 0.17751, 0.29405, 0.45388, 0.56055, 0.72437, 0.85659, 0.97114, 1.18714, 1.28853, 1.37099, 1.57271, 1.71116, 1.89000, 2.12578, 2.23600, 2.44198, 2.44578, 2.35042, 2.33614, 2.34831, 2.35260, 2.41361, 2.42233, 2.43469, 2.57446, 2.54201, 2.47299, 2.40450, 2.19759, 2.06005, 2.10481, 2.12121, 2.10133, 2.06230, 2.17427, 2.28884, 2.37892, 2.39317, 2.36436, 2.52798, 2.61467, 2.72522, 2.91797, 3.07299, 3.16091, 3.29618, 3.35224, 3.53909, 3.64562, 3.71174, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.76707, 2.49144, 2.38909, 2.23134, 1.96117, 1.73545, 1.43116, 1.23723, 1.09668, 1.06905, 1.02019, 1.03097, 1.06342, 1.00209, 1.04057, 0.99719, 0.90021, 0.86360, 0.81626, 0.53675, 0.30387, -0.00941, -0.08526, -0.15570, -0.32893, -0.45918, -0.46505, -0.42849, -0.33311, -0.19282, -0.31583, -0.39540, -0.45167, -0.49343, -0.39052, -0.40506, -0.48781, -0.37090, -0.27507, -0.21290, -0.24445, -0.21911, -0.21666, -0.27430, -0.43098, -0.81803, -1.07067, -1.31256, -1.54453, -1.55701, -1.47029, -1.48064, -1.40518, -1.44206, -1.40197, -1.40871, +1.21969, 1.29412, 1.32458, 1.47808, 1.50543, 1.36841, 1.26458, 1.26856, 1.26168, 1.17479, 0.93331, 0.75345, 0.62364, 0.47351, 0.43252, 0.29732, 0.20766, 0.28873, 0.27298, 0.28793, 0.39057, 0.28536, 0.15383, 0.25855, 0.36462, 0.47121, 0.58870, 0.62757, 0.70728, 0.70915, 0.71499, 0.75662, 0.86195, 0.90635, 0.84739, 0.92116, 1.05725, 1.13096, 1.21251, 1.29564, 1.33293, 1.31846, 1.28830, 1.26027, 1.23670, 1.16700, 1.19468, 1.08390, 0.97720, 1.02922, 0.98177, 0.93028, 1.06550, 1.07041, 1.01340, 1.10127, 1.17875, 1.25621, 1.28839, 1.18778, 1.15082, 1.05974, 0.96897, 0.93475, 0.81222, 0.61880, 0.47896, 0.45935, 0.47425, 0.28058, 0.05198, -0.04816, -0.04568, -0.16320, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.13506, -0.04862, 0.22307, 0.36205, 0.39366, 0.48403, 0.51993, 0.43385, 0.33337, 0.17434, 0.13549, -0.02931, -0.19673, -0.29022, -0.28042, -0.23490, -0.19367, -0.10902, 0.03962, 0.05565, 0.12089, 0.26450, 0.53543, 0.77024, 1.01442, 1.11464, 1.23101, 1.18930, 1.25882, 1.22475, 1.09489, 1.07144, 1.04940, 0.93979, 1.05377, 1.11591, 0.99819, 0.93380, 0.93407, 0.88652, 0.86047, 0.73629, 0.57703, 0.27450, 0.04033, -0.13787, -0.21843, -0.30057, -0.36438, -0.25461, -0.02038, -0.02490, -0.06889, -0.15738, -0.24835, -0.45439, -0.59020, -0.76016, -0.81209, -0.92980, -0.83658, -0.68329, -0.59224, -0.39115, -0.16832, -0.21805, -0.16123, -0.08694, -0.12606, -0.06330, 0.06226, -0.01571, -0.07150, -0.12766, -0.04407, 0.02059, 0.06110, 0.04410, 0.03845, 0.01536, 0.00707, 0.02658, 0.13528, 0.09778, 0.03570, -0.05010, -0.04490, -0.15817, -0.26318, -0.49266, -0.66040, -0.95865, -1.12889, -1.27853, -1.48604, -1.54913, -1.53008, -1.65010, -1.57294, -1.41943, -1.46232, -1.47281, -1.53965, -1.80542, -1.98342, -2.15556, -2.23869, -2.37048, -2.52419, -2.51018, -2.39192, -2.32123, -2.28724, -2.29664, -2.24828, -2.30005, -2.34035, -2.36636, -2.32802, -2.36815, -2.29548, -2.20032, -2.03941, -2.01422, -1.94112, -1.89530, -2.00610, -2.11898, -2.13133, -2.26966, -2.32014, -2.38811, -2.64410, -2.83561, -2.86447, -3.00083, -3.09122, -3.21248, -3.26058, -3.27629, -3.31221, -3.28980, -3.20632, -3.05634, -2.89936, -2.75044, -2.53675, -2.41402, -2.36997, -2.30209, -2.20811, -2.22799, -2.30157, -2.43022, -2.47255, -2.51458, -2.55389, -2.49406, -2.48225, -2.35120, -2.07172, -1.93132, -1.90390, -1.82019, -1.85689, -1.85719, -1.73086, -1.76893, -1.78112, -1.65747, -1.52189, -1.44423, -1.46725, -1.47605, -1.44527, -1.34473, -1.19805, -1.10011, -0.98914, -0.97029, -1.04466, -1.11223, -1.15512, -1.22203, -1.26290, -1.33024, -1.36052, -1.41762, -1.44810, -1.32226, -1.35440, -1.48361, -1.46151, -1.43971, -1.36110, -1.11298, -1.04574, -1.05845, -0.94746, -0.88663, -0.79566, -0.64258, -0.51786, -0.33153, -0.25972, -0.16341, -0.06000, 0.07583, 0.20121, 0.30206, 0.44980, 0.58212, 0.62943, 0.72404, 0.90816, 1.10213, 1.24834, 1.42255, 1.63822, 1.89882, 2.07033, 2.34024, 2.29613, 2.14483, 2.19361, 2.21184, 2.18141, 2.25876, 2.22338, 2.23665, 2.32373, 2.25021, 2.10375, 2.00048, 1.84926, 1.83429, 1.81132, 1.85578, 1.85642, 1.88746, 1.95689, 2.06486, 2.19290, 2.36168, 2.38706, 2.42892, 2.50624, 2.63995, 2.77628, 3.00914, 3.13494, 3.23964, 3.28001, 3.54970, 3.69383, 3.74923, 3.88329, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.40465, 2.20951, 1.93664, 1.73566, 1.47082, 1.26213, 1.07333, 0.95130, 0.86014, 0.77991, 0.80837, 0.93399, 0.90457, 0.88841, 0.88633, 0.91666, 0.82895, 0.77370, 0.46776, 0.22298, -0.06837, -0.09750, -0.18153, -0.40198, -0.43519, -0.32191, -0.35687, -0.31801, -0.35003, -0.52194, -0.59825, -0.58375, -0.60272, -0.52100, -0.56187, -0.51300, -0.44717, -0.30476, -0.21465, -0.12382, -0.11261, -0.19314, -0.35003, -0.54672, -0.87324, -1.12035, -1.33809, -1.47537, -1.56721, -1.45431, -1.37702, -1.20692, -1.19970, -1.11686, -1.12398, +1.18922, 1.22810, 1.18790, 1.26066, 1.31309, 1.21520, 1.09844, 1.12084, 1.12016, 1.03814, 0.83778, 0.68509, 0.58705, 0.45331, 0.35572, 0.22140, 0.21940, 0.36639, 0.45988, 0.54103, 0.57023, 0.42436, 0.28491, 0.33800, 0.40379, 0.47637, 0.58805, 0.58813, 0.61031, 0.57136, 0.61879, 0.78263, 0.95294, 1.05057, 0.98146, 0.99772, 1.15796, 1.24774, 1.22847, 1.22041, 1.18351, 1.11099, 1.07967, 1.01058, 0.96865, 0.92778, 0.92714, 0.76932, 0.62819, 0.63861, 0.63964, 0.68146, 0.81647, 0.79143, 0.75693, 0.85350, 0.92701, 0.99198, 1.01468, 0.89234, 0.80334, 0.67655, 0.62247, 0.68706, 0.62972, 0.49797, 0.36648, 0.30638, 0.34618, 0.21179, -0.01510, -0.11026, -0.14853, -0.34012, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.18922, -0.09648, 0.03284, 0.27018, 0.36564, 0.44872, 0.51751, 0.49920, 0.34879, 0.26910, 0.21488, 0.24274, 0.09517, -0.07422, -0.13666, -0.14430, -0.13828, -0.19050, -0.21938, -0.07764, 0.02676, 0.11453, 0.23566, 0.46138, 0.60605, 0.82938, 0.90308, 0.98199, 0.98242, 1.05898, 0.99732, 0.90338, 0.86827, 0.84824, 0.82892, 0.96456, 0.99906, 0.94926, 0.92772, 0.90602, 0.79025, 0.72702, 0.59458, 0.45703, 0.16819, -0.04038, -0.12853, -0.19264, -0.28006, -0.36354, -0.33145, -0.15564, -0.13815, -0.18011, -0.20764, -0.19208, -0.39539, -0.51607, -0.69219, -0.73723, -0.75842, -0.66058, -0.56973, -0.45004, -0.21275, 0.04090, 0.01865, -0.01196, -0.12783, -0.16902, -0.03380, 0.13007, 0.04666, -0.00204, -0.02433, 0.10824, 0.15604, 0.13395, 0.14674, 0.15037, 0.16095, 0.17124, 0.10922, 0.15168, 0.13898, 0.08360, -0.02684, -0.06067, -0.25524, -0.36936, -0.57293, -0.71036, -0.95478, -1.15155, -1.40432, -1.65544, -1.75047, -1.74712, -1.80061, -1.73076, -1.67877, -1.70481, -1.64979, -1.66482, -1.95098, -2.15360, -2.31730, -2.36821, -2.48142, -2.60241, -2.50222, -2.39553, -2.37732, -2.39291, -2.44048, -2.38820, -2.39704, -2.44025, -2.49711, -2.43243, -2.46719, -2.40055, -2.30494, -2.14327, -2.04640, -1.95311, -2.03291, -2.24625, -2.45325, -2.46641, -2.44630, -2.39828, -2.51691, -2.76821, -2.88139, -2.83370, -2.99022, -3.15741, -3.32934, -3.40197, -3.43025, -3.48222, -3.43784, -3.35214, -3.19521, -3.00310, -2.87400, -2.71538, -2.55907, -2.46302, -2.37326, -2.24776, -2.32474, -2.47228, -2.62213, -2.66296, -2.63469, -2.62358, -2.62145, -2.66552, -2.54557, -2.24034, -1.96092, -1.79754, -1.74283, -1.79802, -1.76264, -1.63635, -1.73150, -1.79477, -1.70226, -1.60672, -1.57986, -1.62925, -1.54400, -1.40633, -1.28466, -1.12869, -1.05550, -0.95047, -0.85978, -0.88768, -0.96546, -0.98122, -1.03423, -1.10468, -1.21486, -1.30090, -1.36651, -1.29692, -1.10559, -1.12647, -1.26628, -1.30513, -1.27223, -1.15364, -1.06234, -1.17667, -1.23281, -1.12552, -1.05596, -0.98530, -0.86392, -0.77376, -0.61231, -0.54569, -0.41889, -0.28611, -0.15894, -0.01606, 0.09501, 0.22134, 0.35370, 0.41585, 0.48288, 0.67337, 0.87009, 0.98008, 1.14611, 1.32950, 1.59673, 1.82719, 2.10019, 2.04343, 1.89229, 1.92759, 2.00508, 2.07158, 2.10222, 1.98501, 1.98933, 2.01199, 1.84966, 1.63686, 1.59529, 1.53858, 1.57574, 1.57268, 1.65774, 1.75406, 1.80327, 1.85151, 1.92762, 2.01355, 2.23074, 2.33374, 2.35614, 2.41571, 2.52259, 2.65880, 2.96981, 3.13882, 3.26553, 3.35853, 3.61801, 3.70453, 3.68893, 3.71199, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 2.14112, 1.88451, 1.55876, 1.33923, 1.09192, 0.97199, 0.93608, 0.85221, 0.77014, 0.68466, 0.66861, 0.79195, 0.80160, 0.74460, 0.69158, 0.70749, 0.58425, 0.58506, 0.33529, 0.10401, -0.11197, -0.11171, -0.21807, -0.41937, -0.44241, -0.31697, -0.30967, -0.34353, -0.51423, -0.64125, -0.66433, -0.64711, -0.71223, -0.63897, -0.64658, -0.58550, -0.56200, -0.42960, -0.24277, -0.09473, -0.07155, -0.19404, -0.45319, -0.70197, -0.91457, -1.06216, -1.21764, -1.30924, -1.42678, -1.27096, -1.14235, -0.99569, -0.97468, -0.91134, -0.99853, +1.09387, 1.10541, 1.10897, 1.04381, 0.98666, 0.96602, 0.86438, 0.88280, 0.95293, 0.93353, 0.83738, 0.63240, 0.47237, 0.40831, 0.34795, 0.27177, 0.39837, 0.57502, 0.62844, 0.71961, 0.72215, 0.66326, 0.47680, 0.34161, 0.40192, 0.43095, 0.50448, 0.54383, 0.55462, 0.57385, 0.66531, 0.78248, 0.94833, 1.10837, 1.16532, 1.11505, 1.14244, 1.23376, 1.14386, 1.04345, 0.99617, 0.92167, 0.93101, 0.79880, 0.65886, 0.66302, 0.66345, 0.50607, 0.41464, 0.42496, 0.34257, 0.36921, 0.52520, 0.66066, 0.70388, 0.70231, 0.81717, 0.87470, 0.86266, 0.75487, 0.57029, 0.40997, 0.37001, 0.36665, 0.34663, 0.29309, 0.26718, 0.17928, 0.12848, 0.06978, -0.10382, -0.24807, -0.29997, -0.45511, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.14441, -0.02463, -0.06355, -0.03916, 0.13623, 0.29839, 0.45665, 0.41232, 0.43132, 0.33213, 0.29498, 0.36015, 0.40938, 0.28949, 0.16384, -0.01393, -0.08346, -0.14905, -0.23049, -0.33309, -0.33456, -0.19724, -0.05113, 0.03619, 0.25035, 0.39519, 0.63203, 0.69089, 0.63594, 0.65605, 0.73588, 0.68670, 0.69006, 0.79423, 0.75294, 0.74090, 0.89877, 1.01946, 1.10055, 0.96816, 0.89694, 0.75831, 0.63674, 0.54280, 0.43306, 0.16344, 0.00606, -0.15216, -0.21931, -0.30166, -0.34095, -0.35299, -0.35715, -0.33472, -0.27044, -0.24800, -0.17003, -0.31266, -0.37561, -0.49182, -0.62817, -0.62112, -0.55228, -0.52035, -0.38982, -0.07164, 0.12160, 0.04397, -0.02170, -0.12392, -0.02355, 0.03605, 0.18752, 0.16954, 0.12926, 0.17194, 0.32900, 0.31000, 0.26012, 0.17107, 0.14475, 0.16974, 0.25359, 0.23012, 0.13366, 0.08410, 0.10262, -0.02701, -0.09595, -0.29699, -0.41382, -0.56535, -0.75500, -0.94871, -1.12333, -1.40103, -1.67449, -1.72070, -1.78576, -1.93502, -1.94324, -1.91863, -1.81312, -1.78800, -1.78700, -2.00017, -2.23588, -2.35637, -2.33893, -2.44607, -2.51176, -2.50178, -2.48210, -2.48770, -2.45124, -2.41963, -2.48890, -2.57972, -2.55957, -2.61778, -2.56256, -2.56736, -2.53098, -2.43145, -2.38522, -2.32376, -2.20543, -2.30094, -2.52721, -2.65098, -2.65941, -2.66234, -2.59718, -2.69049, -2.76857, -2.85834, -2.82323, -2.94407, -3.18070, -3.36274, -3.41052, -3.47720, -3.50732, -3.53086, -3.53726, -3.40339, -3.15996, -2.94759, -2.90580, -2.84543, -2.67362, -2.55889, -2.40733, -2.42800, -2.57388, -2.66764, -2.78330, -2.79406, -2.72490, -2.75036, -2.84308, -2.64984, -2.31686, -2.03521, -1.80011, -1.72626, -1.65190, -1.58354, -1.51430, -1.57054, -1.68600, -1.66581, -1.56452, -1.56338, -1.56102, -1.46369, -1.39739, -1.29865, -1.09251, -0.91175, -0.86685, -0.86916, -0.86016, -0.95101, -0.98892, -1.01042, -1.05511, -1.09816, -1.23650, -1.34875, -1.17781, -0.95734, -0.98160, -1.05702, -1.09654, -1.16176, -1.09766, -1.14812, -1.27050, -1.32361, -1.31331, -1.18790, -1.12416, -1.03302, -0.91245, -0.78119, -0.69344, -0.56806, -0.54366, -0.44554, -0.27146, -0.04938, 0.08204, 0.14397, 0.26762, 0.36573, 0.51730, 0.72445, 0.85112, 1.02245, 1.10476, 1.25072, 1.52507, 1.81168, 1.77867, 1.67873, 1.74342, 1.78556, 1.87239, 1.88130, 1.81886, 1.83740, 1.70980, 1.56736, 1.37493, 1.34832, 1.37736, 1.42767, 1.46550, 1.59527, 1.60676, 1.62770, 1.63933, 1.74759, 1.79425, 1.89271, 2.05735, 2.15556, 2.21161, 2.36706, 2.57283, 2.94626, 3.11771, 3.16215, 3.31529, 3.56742, 3.61020, 3.53346, 3.52544, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.66761, 1.34373, 1.08748, 0.82642, 0.77334, 0.72629, 0.68611, 0.64195, 0.64628, 0.63010, 0.61364, 0.61574, 0.54405, 0.38142, 0.37244, 0.28553, 0.36739, 0.19728, -0.11684, -0.27065, -0.19796, -0.24502, -0.39109, -0.34942, -0.31576, -0.36139, -0.41373, -0.53714, -0.53325, -0.65076, -0.63785, -0.66673, -0.62587, -0.59368, -0.55531, -0.62851, -0.52123, -0.43540, -0.31298, -0.26706, -0.30318, -0.51507, -0.84927, -1.01145, -1.04055, -1.17241, -1.21656, -1.26512, -1.06390, -0.89848, -0.92565, -0.94562, -0.87715, -0.98390, +1.09403, 0.98873, 0.98680, 0.89339, 0.78367, 0.75891, 0.70521, 0.75338, 0.82818, 0.84047, 0.79896, 0.57864, 0.38210, 0.33245, 0.36179, 0.36914, 0.45539, 0.57661, 0.65079, 0.77821, 0.76956, 0.70424, 0.57204, 0.40580, 0.40383, 0.39952, 0.39431, 0.39454, 0.43382, 0.50556, 0.70177, 0.89196, 0.99246, 1.07486, 1.17554, 1.15979, 1.16852, 1.18040, 1.01429, 0.89260, 0.85646, 0.82534, 0.83769, 0.67506, 0.51363, 0.52292, 0.58863, 0.51225, 0.35524, 0.21545, 0.09638, 0.16289, 0.35170, 0.52792, 0.64891, 0.69999, 0.77709, 0.82224, 0.79965, 0.64279, 0.40735, 0.19896, 0.19497, 0.26203, 0.20215, 0.08530, 0.12254, 0.09113, 0.03258, -0.02560, -0.16104, -0.33730, -0.45608, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.04538, 0.00878, -0.05669, -0.07602, 0.02031, 0.11663, 0.28180, 0.33513, 0.41055, 0.40061, 0.42160, 0.45920, 0.50111, 0.36952, 0.27905, 0.17489, 0.04720, -0.23804, -0.42656, -0.53816, -0.53848, -0.38894, -0.24295, -0.17087, 0.00446, 0.16328, 0.43485, 0.50616, 0.41017, 0.36092, 0.41913, 0.47106, 0.54957, 0.66111, 0.65673, 0.70663, 0.85082, 0.94719, 1.09621, 1.07978, 0.99407, 0.84893, 0.71611, 0.54047, 0.39995, 0.13445, 0.03532, -0.01982, -0.10898, -0.32324, -0.38260, -0.44276, -0.52460, -0.50069, -0.38802, -0.30769, -0.21236, -0.31717, -0.34310, -0.41433, -0.50829, -0.46640, -0.42569, -0.40125, -0.32307, -0.13278, -0.00602, -0.03254, -0.06281, -0.15767, -0.00371, 0.15433, 0.31396, 0.33467, 0.32764, 0.33407, 0.45921, 0.33602, 0.22691, 0.22611, 0.25469, 0.20859, 0.27633, 0.27462, 0.17196, 0.13638, 0.19773, 0.10181, -0.02444, -0.30213, -0.44009, -0.56611, -0.68834, -0.81714, -1.00164, -1.25237, -1.57713, -1.74470, -1.84889, -1.97517, -2.01246, -2.04933, -1.93363, -1.81117, -1.77452, -1.91647, -2.09676, -2.24736, -2.26706, -2.39655, -2.45943, -2.45094, -2.47718, -2.59514, -2.58844, -2.52287, -2.59754, -2.71055, -2.70510, -2.73639, -2.66901, -2.66241, -2.65881, -2.63942, -2.64655, -2.61530, -2.53466, -2.54449, -2.69647, -2.83778, -2.85386, -2.81862, -2.72519, -2.82878, -2.87241, -2.82329, -2.73025, -2.86571, -3.11984, -3.32310, -3.37711, -3.45652, -3.51804, -3.52562, -3.53751, -3.50176, -3.30267, -3.06020, -3.05641, -3.07202, -2.91813, -2.75372, -2.52996, -2.50201, -2.63776, -2.74965, -2.89887, -2.89549, -2.79683, -2.75761, -2.81510, -2.67317, -2.36845, -2.05635, -1.77026, -1.67487, -1.56443, -1.39253, -1.28591, -1.32153, -1.44723, -1.55898, -1.57609, -1.59930, -1.58837, -1.43532, -1.32705, -1.31064, -1.17769, -0.93770, -0.82350, -0.80168, -0.82624, -0.96545, -1.02464, -1.07761, -1.12425, -1.12228, -1.21482, -1.26764, -1.07901, -0.84398, -0.83937, -0.97496, -1.09253, -1.16608, -1.11632, -1.29670, -1.50869, -1.48400, -1.37039, -1.20036, -1.13529, -1.10085, -1.06106, -0.93934, -0.83683, -0.66285, -0.62446, -0.63863, -0.55734, -0.26508, -0.01332, 0.10118, 0.21866, 0.29898, 0.41779, 0.61378, 0.77098, 0.94135, 0.98735, 1.11245, 1.36737, 1.63272, 1.65105, 1.53781, 1.54719, 1.59271, 1.70330, 1.70342, 1.59152, 1.58206, 1.48328, 1.36474, 1.21527, 1.18547, 1.16007, 1.19593, 1.22826, 1.42426, 1.55150, 1.56109, 1.42479, 1.48168, 1.53990, 1.60260, 1.74610, 1.89417, 2.01069, 2.20974, 2.44775, 2.82214, 2.99598, 3.05447, 3.22068, 3.46938, 3.53186, 3.33663, 3.18640, 3.11019, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.65554, 1.18629, 0.82172, 0.51013, 0.50687, 0.61674, 0.60951, 0.45681, 0.44413, 0.44105, 0.43030, 0.43546, 0.34951, 0.16125, 0.12835, 0.05374, 0.14168, 0.01333, -0.23450, -0.31806, -0.21474, -0.17341, -0.29271, -0.36306, -0.43358, -0.47856, -0.51157, -0.64400, -0.60381, -0.62204, -0.60299, -0.60683, -0.54322, -0.54856, -0.54268, -0.72141, -0.69153, -0.55914, -0.46894, -0.53675, -0.52881, -0.63660, -0.89295, -1.02266, -1.02946, -1.11896, -1.14108, -1.15854, -0.94290, -0.81027, -0.92511, -0.98063, -0.91396, -0.92900, +1.15929, 1.03908, 0.91037, 0.79402, 0.67344, 0.54505, 0.60435, 0.64463, 0.60183, 0.64492, 0.62906, 0.46313, 0.36598, 0.26609, 0.28181, 0.33558, 0.45195, 0.55382, 0.56799, 0.69116, 0.74012, 0.68216, 0.58552, 0.41184, 0.34534, 0.32084, 0.30124, 0.27268, 0.36265, 0.61893, 0.77215, 0.89869, 1.03667, 1.10267, 1.09633, 1.07458, 1.18239, 1.09355, 0.96824, 0.88634, 0.81591, 0.88899, 0.86123, 0.67975, 0.57850, 0.51112, 0.54146, 0.55888, 0.44982, 0.26073, 0.06091, 0.15751, 0.36969, 0.48077, 0.53177, 0.53845, 0.52737, 0.59251, 0.64550, 0.51113, 0.25413, 0.17126, 0.13442, 0.13906, 0.07645, -0.02251, 0.01321, -0.03855, -0.04645, -0.19107, -0.26902, -0.40653, -0.62627, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.07389, 0.06330, 0.00706, 0.01524, 0.10132, 0.14756, 0.20542, 0.27323, 0.38532, 0.48578, 0.54947, 0.54728, 0.50552, 0.48009, 0.35115, 0.18511, 0.09259, -0.23218, -0.49993, -0.67814, -0.54888, -0.43285, -0.34237, -0.26619, -0.24307, -0.04919, 0.26513, 0.37194, 0.34818, 0.23714, 0.17305, 0.29949, 0.43019, 0.58260, 0.53081, 0.59945, 0.75069, 0.88117, 1.02663, 1.05979, 0.96732, 0.86518, 0.76541, 0.56557, 0.27085, 0.13235, 0.10973, -0.00567, -0.11643, -0.33816, -0.41660, -0.59712, -0.59392, -0.55883, -0.45331, -0.30681, -0.32883, -0.39068, -0.39934, -0.46685, -0.43605, -0.31297, -0.33228, -0.28922, -0.22945, -0.04304, -0.04268, -0.04213, 0.02032, 0.01638, 0.10003, 0.20125, 0.30945, 0.35190, 0.36251, 0.41273, 0.43504, 0.37298, 0.31729, 0.29586, 0.42797, 0.45380, 0.47925, 0.33865, 0.30231, 0.29074, 0.34197, 0.36130, 0.11989, -0.21964, -0.34257, -0.46915, -0.53718, -0.65223, -0.98271, -1.27506, -1.62576, -1.73672, -1.87367, -1.98274, -1.98365, -1.97910, -1.91475, -1.84823, -1.89270, -1.96606, -2.04130, -2.14175, -2.32508, -2.41744, -2.40038, -2.49316, -2.51887, -2.58536, -2.58657, -2.67332, -2.71252, -2.79103, -2.89358, -2.85952, -2.84308, -2.83448, -2.75846, -2.78966, -2.79218, -2.73902, -2.81492, -2.79424, -2.81637, -2.81488, -2.88180, -2.91069, -2.79550, -2.85452, -2.94434, -2.88567, -2.80358, -2.91356, -3.08641, -3.17190, -3.25406, -3.30401, -3.33309, -3.47290, -3.54549, -3.49215, -3.28907, -3.15029, -3.14011, -3.14229, -3.07547, -2.81940, -2.64557, -2.70155, -2.79705, -2.96015, -3.09353, -2.97101, -2.91610, -2.85854, -2.81600, -2.57352, -2.26847, -2.04341, -1.77328, -1.57792, -1.43090, -1.29160, -1.27208, -1.30945, -1.38605, -1.48167, -1.59083, -1.61719, -1.49865, -1.44260, -1.37431, -1.31778, -1.21235, -1.05669, -0.87451, -0.70131, -0.75709, -0.86053, -0.96732, -1.15267, -1.18091, -1.14803, -1.13623, -1.05015, -0.99606, -0.90631, -0.88316, -0.99612, -1.14796, -1.28843, -1.24096, -1.39728, -1.60382, -1.56081, -1.40710, -1.23871, -1.17618, -1.14069, -1.18965, -1.10781, -0.84330, -0.68343, -0.69545, -0.69327, -0.59183, -0.33965, -0.10479, 0.08925, 0.12012, 0.18928, 0.29407, 0.41669, 0.66790, 0.86306, 0.94553, 1.16220, 1.33526, 1.41069, 1.42282, 1.39087, 1.46157, 1.40372, 1.45918, 1.50479, 1.40357, 1.33391, 1.22171, 1.10577, 1.01046, 0.98762, 0.92402, 0.88315, 1.01813, 1.20816, 1.34924, 1.48374, 1.41117, 1.40515, 1.38957, 1.50269, 1.54948, 1.74207, 1.96444, 2.08485, 2.31541, 2.63500, 2.80805, 2.94470, 3.07125, 3.20088, 3.29050, 3.12488, 3.04440, 2.94468, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.66110, 1.14103, 0.61526, 0.39808, 0.38421, 0.39917, 0.39998, 0.25119, 0.17063, 0.07397, 0.20667, 0.22118, 0.15175, 0.05172, -0.07764, -0.12784, -0.09994, -0.23961, -0.31718, -0.31368, -0.35084, -0.31864, -0.37057, -0.37417, -0.54181, -0.58932, -0.56063, -0.64836, -0.68216, -0.71562, -0.74592, -0.73564, -0.62823, -0.56219, -0.60607, -0.66929, -0.65102, -0.62471, -0.55251, -0.60404, -0.54146, -0.65966, -0.76818, -0.93729, -1.01852, -1.02278, -1.15010, -1.17073, -0.94568, -0.85209, -0.90732, -0.89890, -0.92960, -0.89693, +1.02457, 0.88429, 0.81042, 0.74500, 0.57191, 0.40901, 0.47208, 0.48664, 0.42318, 0.47276, 0.50721, 0.43389, 0.38020, 0.29428, 0.33866, 0.39396, 0.44391, 0.48722, 0.45858, 0.52382, 0.55431, 0.50416, 0.47066, 0.36166, 0.28618, 0.23745, 0.27330, 0.36639, 0.45505, 0.66208, 0.75837, 0.82108, 0.95057, 0.99016, 0.99986, 1.05718, 1.17423, 1.10356, 1.03448, 0.97925, 0.95028, 1.05915, 1.00824, 0.82480, 0.66311, 0.50869, 0.53965, 0.59302, 0.49257, 0.29186, 0.10267, 0.19046, 0.32696, 0.30773, 0.29252, 0.27681, 0.23677, 0.30926, 0.43832, 0.44861, 0.17453, 0.00655, -0.04406, -0.05632, -0.14900, -0.26077, -0.18033, -0.14158, -0.19097, -0.36735, -0.41752, -0.50179, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.19208, -0.14877, -0.03577, -0.02378, 0.05428, 0.15638, 0.18120, 0.20031, 0.27401, 0.39974, 0.51381, 0.58149, 0.67184, 0.61609, 0.48676, 0.31098, 0.12506, 0.03088, -0.28916, -0.52234, -0.59181, -0.46624, -0.40368, -0.38085, -0.37105, -0.39429, -0.19963, 0.11618, 0.26822, 0.26510, 0.12838, 0.08736, 0.23962, 0.30824, 0.31767, 0.24104, 0.32574, 0.50850, 0.68139, 0.84677, 0.90499, 0.80438, 0.69104, 0.61773, 0.53609, 0.20527, -0.02503, -0.04176, -0.16774, -0.30811, -0.53562, -0.58797, -0.59882, -0.50629, -0.45058, -0.34100, -0.23383, -0.27436, -0.27120, -0.27347, -0.32776, -0.29050, -0.20974, -0.17407, -0.06890, -0.02303, 0.05621, -0.01015, -0.01493, 0.07720, 0.08838, 0.10925, 0.16052, 0.25302, 0.28144, 0.29735, 0.49170, 0.54427, 0.42344, 0.39157, 0.39366, 0.55049, 0.56799, 0.54577, 0.49047, 0.46718, 0.42330, 0.47273, 0.48829, 0.26446, 0.00357, -0.08851, -0.19512, -0.34509, -0.63667, -1.02321, -1.31681, -1.65959, -1.81669, -1.97863, -2.09847, -2.10867, -2.10701, -2.05621, -2.01820, -2.10625, -2.17036, -2.19496, -2.16677, -2.34433, -2.52788, -2.52830, -2.57860, -2.55280, -2.60592, -2.63736, -2.67554, -2.68974, -2.77361, -2.91886, -2.94658, -2.96177, -2.90620, -2.76131, -2.73635, -2.74267, -2.78313, -2.90899, -2.84681, -2.80125, -2.82415, -2.96531, -3.04253, -2.92523, -2.98391, -3.09114, -3.01497, -2.90853, -2.95752, -3.03676, -2.95804, -2.95467, -3.10310, -3.24557, -3.44848, -3.58913, -3.59718, -3.44414, -3.24630, -3.14893, -3.12161, -3.05478, -2.82938, -2.76575, -2.88185, -2.96494, -3.10065, -3.19297, -3.08782, -3.03978, -2.94129, -2.85560, -2.63214, -2.35359, -2.17134, -1.93397, -1.71045, -1.53593, -1.40948, -1.43417, -1.48428, -1.52567, -1.46931, -1.43921, -1.50643, -1.46047, -1.44989, -1.39920, -1.34173, -1.28810, -1.11665, -0.84531, -0.63513, -0.63039, -0.69877, -0.82978, -1.01762, -1.03117, -0.96306, -0.90665, -0.88259, -0.96759, -0.95027, -0.94543, -1.12739, -1.36523, -1.53476, -1.48811, -1.59050, -1.73322, -1.65078, -1.47683, -1.34121, -1.31687, -1.23638, -1.21793, -1.20698, -1.01868, -0.85303, -0.81904, -0.75892, -0.63497, -0.35484, -0.10636, 0.01543, 0.01936, 0.07982, 0.18060, 0.34372, 0.65199, 0.86898, 0.97094, 1.14333, 1.23200, 1.23813, 1.21150, 1.15747, 1.17431, 1.05817, 1.05586, 1.10689, 1.04693, 1.05059, 1.00106, 0.90065, 0.81057, 0.81698, 0.87573, 0.80953, 0.81562, 0.95578, 1.10283, 1.28921, 1.29446, 1.35434, 1.44734, 1.54392, 1.55198, 1.74824, 1.96032, 2.05346, 2.24687, 2.52718, 2.71710, 2.81514, 2.85675, 2.97876, 3.09900, 2.97972, 2.89375, 2.79706, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.79043, 1.52216, 1.17387, 0.65826, 0.33396, 0.23706, 0.11594, 0.02560, -0.14251, -0.21746, -0.18052, 0.00157, 0.02315, -0.03525, -0.15143, -0.27778, -0.28432, -0.29012, -0.41374, -0.45617, -0.48458, -0.54764, -0.52601, -0.56076, -0.58392, -0.70816, -0.72039, -0.66872, -0.74702, -0.80585, -0.83761, -0.88357, -0.91314, -0.80037, -0.56664, -0.54085, -0.61985, -0.60068, -0.59748, -0.54987, -0.60566, -0.51491, -0.48721, -0.56957, -0.79881, -0.90102, -0.92198, -1.07672, -1.07762, -0.86013, -0.73975, -0.75918, -0.79262, -0.84281, -0.81208, +0.95775, 0.71783, 0.59667, 0.59910, 0.42660, 0.25368, 0.34089, 0.36753, 0.28254, 0.26053, 0.33911, 0.34200, 0.30319, 0.31792, 0.39269, 0.47179, 0.52871, 0.51903, 0.45989, 0.47342, 0.46204, 0.39772, 0.43129, 0.33884, 0.23096, 0.19721, 0.21506, 0.34560, 0.55429, 0.69799, 0.69967, 0.80514, 0.95754, 0.91479, 0.82896, 0.92937, 1.03772, 0.98160, 0.98764, 1.00176, 0.98375, 1.01843, 0.95949, 0.81574, 0.58801, 0.46943, 0.52197, 0.59859, 0.56323, 0.38610, 0.23533, 0.31554, 0.39129, 0.28496, 0.26452, 0.22757, 0.12495, 0.19999, 0.29356, 0.29970, 0.10884, -0.09824, -0.22295, -0.14403, -0.19332, -0.35761, -0.39633, -0.33579, -0.41229, -0.61065, -0.62117, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.18949, -0.12016, -0.03541, 0.02015, 0.15475, 0.28548, 0.31033, 0.35120, 0.42569, 0.47643, 0.57621, 0.59977, 0.66958, 0.71391, 0.59255, 0.31408, 0.19592, 0.12917, -0.20813, -0.54553, -0.59967, -0.51544, -0.53209, -0.55127, -0.52017, -0.57086, -0.46565, -0.20294, 0.02178, 0.00204, -0.05043, -0.00276, 0.15616, 0.23929, 0.16940, 0.09160, 0.19798, 0.40930, 0.59964, 0.78784, 0.86432, 0.66488, 0.51485, 0.42149, 0.31697, 0.07030, -0.11533, -0.23389, -0.28424, -0.35823, -0.55071, -0.68070, -0.60885, -0.45114, -0.40477, -0.29314, -0.12987, -0.14483, -0.15051, -0.17966, -0.16510, -0.18298, -0.11300, -0.00621, 0.11630, 0.20125, 0.22206, 0.12162, 0.09941, 0.18103, 0.17403, 0.17453, 0.25491, 0.29785, 0.32686, 0.35789, 0.53196, 0.65276, 0.61353, 0.48697, 0.52252, 0.70397, 0.70368, 0.53815, 0.47853, 0.47485, 0.39626, 0.43543, 0.50704, 0.33518, 0.10727, -0.01513, -0.05830, -0.29141, -0.66595, -0.99889, -1.27893, -1.55076, -1.71787, -1.91038, -2.06570, -2.12856, -2.16502, -2.12730, -2.04670, -2.19116, -2.27878, -2.28577, -2.27492, -2.38366, -2.46605, -2.55320, -2.54658, -2.43735, -2.47539, -2.64457, -2.73132, -2.71482, -2.80715, -2.96820, -2.97980, -2.99860, -2.96903, -2.87656, -2.77455, -2.79380, -2.88592, -2.94408, -2.85778, -2.74283, -2.75524, -2.92829, -3.01002, -2.89262, -2.95656, -3.06722, -2.92987, -2.84836, -2.89103, -2.91255, -2.84615, -2.80737, -2.88639, -3.15454, -3.39732, -3.51239, -3.54033, -3.53893, -3.42920, -3.27470, -3.22703, -3.17081, -2.93308, -2.90044, -3.06021, -3.19107, -3.24959, -3.29463, -3.22455, -3.09951, -2.98386, -2.87584, -2.64388, -2.39392, -2.21203, -1.97623, -1.75513, -1.58713, -1.41120, -1.46623, -1.56511, -1.57643, -1.49387, -1.38681, -1.33306, -1.34179, -1.35652, -1.20996, -1.10867, -1.16695, -1.12477, -0.84228, -0.66138, -0.65250, -0.65684, -0.73356, -0.90863, -0.97990, -0.89972, -0.83684, -0.92366, -1.01775, -1.02256, -1.02575, -1.20552, -1.50085, -1.68249, -1.63835, -1.71756, -1.83014, -1.68161, -1.51571, -1.45665, -1.44172, -1.39400, -1.38205, -1.29560, -1.17020, -1.07363, -0.90870, -0.74881, -0.65949, -0.48073, -0.23333, -0.15755, -0.16738, -0.06432, 0.11114, 0.29871, 0.55603, 0.75661, 0.87400, 0.95793, 1.07829, 1.10819, 1.07688, 1.03442, 0.97795, 0.83621, 0.81499, 0.85189, 0.80527, 0.90550, 0.91451, 0.77757, 0.71576, 0.72504, 0.80720, 0.85020, 0.81619, 0.81627, 1.00912, 1.21846, 1.20982, 1.19605, 1.34536, 1.44264, 1.42749, 1.62847, 1.87664, 1.94410, 2.04810, 2.28988, 2.53787, 2.57350, 2.65049, 2.83521, 2.98383, 2.94568, 2.83404, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.64242, 1.37484, 1.06564, 0.68247, 0.37393, 0.12218, -0.02286, -0.14653, -0.34962, -0.53867, -0.46579, -0.27975, -0.28338, -0.34672, -0.41825, -0.52326, -0.55478, -0.58819, -0.62761, -0.71223, -0.72364, -0.71832, -0.68789, -0.67020, -0.70673, -0.78639, -0.77223, -0.72701, -0.81139, -0.85024, -0.83000, -0.92551, -0.97416, -0.87361, -0.64016, -0.49310, -0.45491, -0.50259, -0.44411, -0.36413, -0.42431, -0.46375, -0.43512, -0.51123, -0.76465, -0.84715, -0.79483, -0.93295, -0.97678, -0.83150, -0.65375, -0.71568, -0.77780, -0.78848, -0.79194, +0.75665, 0.59019, 0.44594, 0.43687, 0.35446, 0.25621, 0.25477, 0.21272, 0.19371, 0.22540, 0.23366, 0.19802, 0.25775, 0.35063, 0.34171, 0.36858, 0.54876, 0.62188, 0.57430, 0.55746, 0.46551, 0.33562, 0.26488, 0.15316, 0.17201, 0.23542, 0.19367, 0.21386, 0.47884, 0.66739, 0.60291, 0.62998, 0.82529, 0.88039, 0.76547, 0.78416, 0.87494, 0.86758, 0.87771, 0.89087, 0.95329, 1.02550, 0.86165, 0.64011, 0.52173, 0.55439, 0.56667, 0.54829, 0.59529, 0.55571, 0.45532, 0.54601, 0.56433, 0.39379, 0.31020, 0.20825, 0.10705, 0.16940, 0.15927, 0.02307, -0.12832, -0.27773, -0.43032, -0.39395, -0.36068, -0.37896, -0.45894, -0.48022, -0.55174, -0.67774, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.07045, -0.18607, -0.12439, 0.04045, 0.10767, 0.32081, 0.51701, 0.55184, 0.53341, 0.48394, 0.53960, 0.70615, 0.66107, 0.56160, 0.63029, 0.61807, 0.33961, 0.13725, 0.04911, -0.15828, -0.46310, -0.56194, -0.51289, -0.54373, -0.66915, -0.76520, -0.79170, -0.58183, -0.35261, -0.24639, -0.20560, -0.08001, -0.01983, 0.02189, 0.10666, 0.15237, 0.12787, 0.27875, 0.45686, 0.57064, 0.70389, 0.67880, 0.46965, 0.37188, 0.22572, -0.05030, -0.25996, -0.31656, -0.42672, -0.50162, -0.50663, -0.48297, -0.55029, -0.52106, -0.39871, -0.31174, -0.22533, -0.13177, -0.07456, 0.06674, 0.07226, -0.04003, -0.09713, 0.04823, 0.11693, 0.13879, 0.26164, 0.41411, 0.32026, 0.28473, 0.35817, 0.33001, 0.28016, 0.24708, 0.30224, 0.48131, 0.54690, 0.53848, 0.58809, 0.62612, 0.53626, 0.52469, 0.66368, 0.73666, 0.54615, 0.42548, 0.43493, 0.46459, 0.51331, 0.46960, 0.30030, 0.20236, 0.10531, -0.06118, -0.33844, -0.58754, -0.85338, -1.21714, -1.51806, -1.60398, -1.78049, -1.94194, -2.04259, -2.14103, -2.16499, -2.21087, -2.35702, -2.32639, -2.30201, -2.41006, -2.52157, -2.47262, -2.50850, -2.54776, -2.49246, -2.43924, -2.58834, -2.71333, -2.68719, -2.68988, -2.80915, -2.95032, -3.04814, -2.97253, -2.87445, -2.83530, -2.84263, -2.79741, -2.81269, -2.84133, -2.73195, -2.60232, -2.72777, -2.80320, -2.68466, -2.73492, -2.86545, -2.87215, -2.87166, -2.81012, -2.73059, -2.75587, -2.80072, -2.84954, -3.12014, -3.40279, -3.52006, -3.42411, -3.39247, -3.39077, -3.30739, -3.21906, -3.15203, -3.03958, -3.09196, -3.15234, -3.16891, -3.26600, -3.37542, -3.23636, -3.03895, -3.01056, -2.96752, -2.66149, -2.37399, -2.18930, -1.91753, -1.68340, -1.54168, -1.46338, -1.56147, -1.56801, -1.50557, -1.51715, -1.51658, -1.38490, -1.30340, -1.27362, -1.09131, -0.87935, -0.86371, -0.95297, -0.82484, -0.69859, -0.67583, -0.69710, -0.77233, -0.83841, -0.85389, -0.88236, -0.91589, -0.95677, -1.02056, -1.14345, -1.23789, -1.30979, -1.52628, -1.74776, -1.74030, -1.80619, -1.87390, -1.77088, -1.67892, -1.60141, -1.54466, -1.57156, -1.65445, -1.48889, -1.31544, -1.27172, -1.13842, -0.88127, -0.66270, -0.53014, -0.37663, -0.27651, -0.19133, -0.12441, -0.05427, 0.15873, 0.49575, 0.64201, 0.65558, 0.78229, 0.99410, 0.97505, 0.87369, 0.89250, 0.90565, 0.74609, 0.73439, 0.77314, 0.71084, 0.73459, 0.64884, 0.57280, 0.64179, 0.67713, 0.68615, 0.80948, 0.85742, 0.76262, 0.81918, 0.99110, 1.09613, 1.11817, 1.24827, 1.37066, 1.40551, 1.54923, 1.71297, 1.80803, 1.97041, 2.15409, 2.30370, 2.42899, 2.64065, 2.76959, 2.78704, 2.82631, 2.87241, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.62518, 1.32299, 0.88477, 0.56249, 0.35849, 0.06422, -0.19150, -0.31946, -0.37689, -0.59490, -0.66601, -0.55316, -0.50613, -0.58306, -0.73657, -0.80627, -0.73297, -0.76327, -0.86752, -0.90099, -0.78003, -0.78145, -0.85821, -0.80074, -0.70403, -0.79033, -0.79503, -0.76741, -0.86229, -0.89804, -0.93719, -0.98248, -0.90541, -0.83970, -0.77251, -0.61671, -0.42141, -0.37976, -0.33751, -0.26506, -0.23124, -0.30553, -0.35806, -0.46521, -0.65836, -0.72770, -0.73653, -0.82856, -0.80029, -0.73063, -0.72863, -0.78013, -0.68743, -0.70071, -0.86988, +0.54727, 0.46679, 0.42439, 0.37483, 0.30247, 0.25361, 0.18227, 0.21982, 0.18515, 0.14005, 0.12201, 0.15011, 0.21535, 0.18016, 0.14502, 0.18261, 0.35477, 0.44068, 0.46387, 0.50433, 0.38661, 0.14222, -0.02236, -0.03667, 0.01340, 0.10188, 0.11620, 0.08899, 0.33811, 0.52072, 0.51428, 0.49219, 0.58695, 0.71407, 0.69586, 0.64065, 0.60958, 0.59830, 0.58863, 0.77417, 0.91162, 0.91051, 0.71480, 0.56327, 0.57490, 0.58612, 0.60015, 0.60047, 0.60539, 0.54069, 0.47077, 0.58291, 0.59372, 0.39570, 0.31912, 0.33923, 0.16486, 0.05570, 0.01695, -0.14996, -0.26494, -0.40431, -0.51651, -0.50595, -0.53598, -0.45879, -0.47586, -0.52228, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.01323, -0.03154, -0.03144, 0.05208, 0.07103, 0.32974, 0.60675, 0.64299, 0.56003, 0.54360, 0.56728, 0.65100, 0.63950, 0.50972, 0.56899, 0.59921, 0.38773, 0.14760, -0.11242, -0.29708, -0.49705, -0.52504, -0.57114, -0.57770, -0.79633, -0.85685, -0.78725, -0.63580, -0.44154, -0.34360, -0.20355, -0.14700, -0.12814, -0.04551, 0.03446, 0.10637, 0.15753, 0.36538, 0.49732, 0.49195, 0.53800, 0.60321, 0.44191, 0.23577, 0.07535, -0.25642, -0.45098, -0.46242, -0.53011, -0.55519, -0.61608, -0.47711, -0.43194, -0.37566, -0.44008, -0.35983, -0.35743, -0.24208, -0.03649, 0.08546, 0.15094, 0.07439, 0.08081, 0.09660, 0.00478, 0.05790, 0.23510, 0.40030, 0.31455, 0.27698, 0.35691, 0.33329, 0.23685, 0.27074, 0.39005, 0.55105, 0.67865, 0.60170, 0.54505, 0.52545, 0.46159, 0.50881, 0.52788, 0.59867, 0.45619, 0.41996, 0.38429, 0.50707, 0.52774, 0.45215, 0.35499, 0.17090, 0.02377, -0.17800, -0.34079, -0.53269, -0.79012, -1.07131, -1.38252, -1.55524, -1.74547, -1.87365, -1.95994, -2.09488, -2.23699, -2.30157, -2.38037, -2.41482, -2.37556, -2.48367, -2.58804, -2.48276, -2.47188, -2.48019, -2.58713, -2.57710, -2.70022, -2.74637, -2.77028, -2.71266, -2.75759, -2.89738, -2.92302, -2.94476, -2.96151, -2.92725, -2.77184, -2.66693, -2.77734, -2.81910, -2.66707, -2.52065, -2.61881, -2.66768, -2.54640, -2.54552, -2.73864, -2.82166, -2.83407, -2.87483, -2.75793, -2.74383, -2.80959, -2.85059, -3.10491, -3.29155, -3.41174, -3.29433, -3.22499, -3.20793, -3.28110, -3.27309, -3.23957, -3.21147, -3.14537, -3.11794, -3.08727, -3.15125, -3.20209, -3.06703, -2.96447, -2.91277, -2.81928, -2.56755, -2.34148, -2.17501, -1.87274, -1.60248, -1.53322, -1.51132, -1.53026, -1.55954, -1.50123, -1.53456, -1.62174, -1.48127, -1.37254, -1.22837, -1.03160, -0.83953, -0.72034, -0.78162, -0.82455, -0.87295, -0.91295, -0.96104, -0.85570, -0.83953, -0.94556, -1.06107, -1.05120, -1.02367, -1.19278, -1.34676, -1.39533, -1.41659, -1.63413, -1.91155, -1.97146, -2.04009, -2.10661, -2.01717, -1.82605, -1.76804, -1.74593, -1.74557, -1.81722, -1.60804, -1.45119, -1.39523, -1.33015, -1.16374, -0.87246, -0.67685, -0.53389, -0.43303, -0.23816, -0.21306, -0.10627, 0.10936, 0.36173, 0.51367, 0.60591, 0.81726, 0.91680, 0.85854, 0.82495, 0.83675, 0.79624, 0.59741, 0.59043, 0.65725, 0.54246, 0.43107, 0.36408, 0.29190, 0.32636, 0.44248, 0.49090, 0.69104, 0.83027, 0.76596, 0.73590, 0.70795, 0.81099, 0.93882, 1.13607, 1.20678, 1.27604, 1.33369, 1.58826, 1.79264, 1.87824, 2.02575, 2.21215, 2.51355, 2.65330, 2.67423, 2.66406, 2.68880, 2.74303, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.71804, 1.52491, 1.22706, 0.73365, 0.42176, 0.25736, 0.00566, -0.20836, -0.38654, -0.36205, -0.54962, -0.69413, -0.77192, -0.69317, -0.77723, -0.82580, -0.77600, -0.78746, -0.84277, -0.90204, -0.79622, -0.74927, -0.84897, -0.89779, -0.81636, -0.75032, -0.91245, -0.97089, -0.95929, -1.09683, -1.19500, -1.13238, -1.06360, -0.96698, -0.85903, -0.83482, -0.71456, -0.49296, -0.34488, -0.20909, -0.24333, -0.24860, -0.33841, -0.34966, -0.54724, -0.67964, -0.76724, -0.71431, -0.62946, -0.70241, -0.77564, -0.88780, -0.83518, -0.73159, -0.81614, -0.95581, +0.50109, 0.43898, 0.44532, 0.40069, 0.29463, 0.23097, 0.10576, 0.05616, -0.05018, -0.11997, -0.09691, -0.01955, 0.01381, -0.04895, -0.00134, 0.02682, 0.08265, 0.13762, 0.17849, 0.25076, 0.19021, -0.02801, -0.24795, -0.28452, -0.20673, -0.10869, -0.02675, 0.03055, 0.24278, 0.37227, 0.40761, 0.42417, 0.45694, 0.55281, 0.56498, 0.49471, 0.42266, 0.40318, 0.39749, 0.57351, 0.72989, 0.78293, 0.66502, 0.56205, 0.53844, 0.48863, 0.56124, 0.64267, 0.60444, 0.51699, 0.44974, 0.51039, 0.50966, 0.33354, 0.23239, 0.23244, 0.06293, -0.09456, -0.13832, -0.20983, -0.31562, -0.48984, -0.56533, -0.50949, -0.58296, -0.53433, -0.51272, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.08543, 0.06523, 0.18852, 0.15983, 0.16411, 0.13015, 0.31454, 0.60094, 0.67698, 0.55278, 0.46261, 0.45197, 0.49252, 0.48918, 0.46866, 0.51835, 0.50968, 0.33117, 0.13562, -0.16604, -0.38889, -0.52264, -0.49357, -0.53203, -0.51390, -0.71776, -0.84834, -0.82302, -0.72089, -0.54679, -0.40641, -0.26546, -0.25011, -0.17034, 0.04015, 0.08791, 0.09912, 0.14898, 0.29565, 0.41883, 0.44381, 0.46727, 0.50078, 0.35190, 0.11215, -0.07561, -0.32491, -0.52418, -0.58299, -0.62821, -0.58545, -0.65182, -0.52571, -0.42440, -0.33296, -0.42598, -0.38521, -0.42867, -0.44593, -0.29251, -0.15057, 0.00341, 0.04931, 0.05863, -0.03524, -0.15999, 0.01132, 0.20758, 0.33710, 0.26643, 0.17304, 0.24214, 0.27575, 0.19573, 0.20077, 0.32513, 0.49889, 0.62997, 0.62965, 0.55169, 0.43343, 0.34980, 0.46041, 0.48039, 0.53569, 0.44411, 0.44657, 0.40425, 0.48763, 0.48393, 0.33986, 0.19951, -0.00385, -0.14672, -0.30773, -0.46688, -0.69842, -0.90504, -0.99704, -1.23979, -1.45810, -1.65429, -1.83184, -1.94240, -2.05759, -2.22724, -2.38973, -2.52567, -2.59693, -2.58338, -2.62028, -2.69011, -2.60949, -2.57864, -2.47988, -2.54927, -2.57734, -2.72098, -2.79984, -2.85018, -2.78304, -2.74589, -2.86048, -2.90396, -2.95222, -2.98460, -2.89026, -2.68795, -2.62741, -2.75074, -2.67748, -2.48606, -2.38821, -2.48437, -2.58281, -2.51362, -2.46890, -2.65527, -2.82758, -2.90767, -2.99139, -2.88899, -2.78672, -2.76659, -2.79690, -3.03158, -3.11993, -3.18123, -3.11174, -3.07226, -3.06140, -3.18392, -3.23164, -3.22261, -3.25797, -3.23717, -3.17724, -3.06886, -3.01456, -2.98575, -2.88769, -2.80803, -2.63762, -2.49116, -2.33694, -2.18638, -2.11443, -1.89366, -1.60838, -1.53401, -1.60374, -1.68348, -1.71720, -1.65520, -1.60350, -1.59218, -1.46548, -1.40613, -1.24752, -1.01785, -0.85792, -0.72853, -0.76909, -0.87928, -1.03277, -1.13761, -1.21508, -1.12697, -1.09788, -1.20225, -1.30680, -1.28324, -1.29969, -1.49473, -1.54230, -1.48951, -1.50856, -1.73807, -2.06578, -2.21935, -2.29234, -2.31309, -2.24727, -2.06278, -1.96574, -1.94400, -1.91188, -1.90479, -1.75225, -1.67161, -1.58823, -1.46976, -1.31828, -1.03773, -0.81659, -0.67558, -0.57386, -0.35512, -0.31476, -0.23664, -0.03036, 0.23099, 0.44152, 0.60024, 0.78209, 0.82296, 0.81095, 0.85169, 0.80520, 0.68248, 0.40248, 0.29111, 0.35342, 0.27637, 0.13250, 0.02508, -0.03998, -0.04564, 0.06081, 0.23629, 0.48980, 0.67818, 0.70244, 0.72951, 0.63976, 0.67153, 0.83348, 1.06104, 1.12962, 1.19353, 1.24546, 1.46551, 1.68688, 1.79632, 1.96795, 2.19980, 2.50592, 2.57809, 2.60949, 2.66490, 2.62947, 2.61741, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.48268, 1.25846, 0.96550, 0.59813, 0.33888, 0.17835, -0.01855, -0.13724, -0.30384, -0.31552, -0.47861, -0.62533, -0.75369, -0.69889, -0.74819, -0.80223, -0.74156, -0.75004, -0.80875, -0.83306, -0.74294, -0.80116, -0.94308, -0.91621, -0.85664, -0.84186, -1.00181, -1.13426, -1.15781, -1.31517, -1.48844, -1.47164, -1.35297, -1.17485, -1.01016, -0.85741, -0.70995, -0.53040, -0.34965, -0.13162, -0.18910, -0.29281, -0.41766, -0.43540, -0.64285, -0.76987, -0.83693, -0.81415, -0.72295, -0.82422, -0.94101, -1.05486, -1.01032, -0.95430, -1.00661, -0.96856, +0.41284, 0.42939, 0.48184, 0.40756, 0.18005, 0.11840, 0.07239, -0.14578, -0.35265, -0.33402, -0.29674, -0.26937, -0.22772, -0.13762, -0.04327, -0.20289, -0.25973, -0.13627, 0.01288, 0.03262, -0.08060, -0.18246, -0.33231, -0.37790, -0.22490, -0.17490, -0.19891, -0.08190, 0.17649, 0.27729, 0.28106, 0.27104, 0.28256, 0.41681, 0.46495, 0.37675, 0.26515, 0.31740, 0.47295, 0.54802, 0.62811, 0.82898, 0.78837, 0.59782, 0.47693, 0.47069, 0.57943, 0.54658, 0.48869, 0.53377, 0.59300, 0.57268, 0.41069, 0.23385, 0.13333, 0.09683, 0.03187, -0.12165, -0.30579, -0.37425, -0.42385, -0.58973, -0.65853, -0.62224, -0.73132, -0.65084, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.35426, -0.22360, 0.00693, 0.27322, 0.31369, 0.24578, 0.32460, 0.37367, 0.47542, 0.58762, 0.66840, 0.57888, 0.45124, 0.45469, 0.45171, 0.29766, 0.26345, 0.37370, 0.36854, 0.18400, -0.02127, -0.30226, -0.43534, -0.45158, -0.40507, -0.45207, -0.41396, -0.44701, -0.62913, -0.76530, -0.65714, -0.47098, -0.40534, -0.31393, -0.19101, 0.03555, 0.15853, 0.09948, 0.10629, 0.19242, 0.28996, 0.30780, 0.38212, 0.45841, 0.46565, 0.33874, 0.11615, -0.19342, -0.49040, -0.65470, -0.71720, -0.76374, -0.73931, -0.80827, -0.64891, -0.47132, -0.34784, -0.42291, -0.42865, -0.37758, -0.48507, -0.52938, -0.33550, -0.08582, -0.06390, -0.11428, -0.17559, -0.17001, -0.06284, 0.05278, 0.24016, 0.29585, 0.24711, 0.18674, 0.19507, 0.17600, 0.17819, 0.31591, 0.53411, 0.55200, 0.48307, 0.47482, 0.38664, 0.29025, 0.36933, 0.38563, 0.49678, 0.52259, 0.54394, 0.46255, 0.41965, 0.48808, 0.37217, 0.10126, -0.05803, -0.10784, -0.31575, -0.59143, -0.85770, -0.93200, -1.01139, -1.25809, -1.39527, -1.50354, -1.64865, -1.90173, -2.07614, -2.18631, -2.38322, -2.59305, -2.65005, -2.75527, -2.90836, -2.91731, -2.79396, -2.74400, -2.57332, -2.55238, -2.52421, -2.59629, -2.71542, -2.82155, -2.82121, -2.66640, -2.66834, -2.81712, -2.85124, -2.76054, -2.67145, -2.56109, -2.53402, -2.51389, -2.43026, -2.36481, -2.30363, -2.34299, -2.39431, -2.46615, -2.51621, -2.64043, -2.80254, -2.90014, -2.90007, -2.87491, -2.89296, -2.79818, -2.74095, -2.93771, -3.00331, -3.06172, -3.01832, -2.92839, -2.89050, -3.02166, -3.12262, -3.04135, -2.98798, -3.12851, -3.12859, -2.89122, -2.76830, -2.73794, -2.64121, -2.44320, -2.25486, -2.25715, -2.17408, -1.98665, -1.89078, -1.84522, -1.70149, -1.57677, -1.64683, -1.76700, -1.72625, -1.69664, -1.69510, -1.56009, -1.35989, -1.33311, -1.25847, -1.09256, -0.96408, -0.80409, -0.82584, -0.98303, -1.22747, -1.30580, -1.28178, -1.32792, -1.37264, -1.35496, -1.43396, -1.52465, -1.62622, -1.70344, -1.65464, -1.68638, -1.71612, -1.83812, -2.05861, -2.29284, -2.47346, -2.43042, -2.33695, -2.17388, -1.98082, -1.99232, -2.09541, -2.09996, -1.95939, -1.91124, -1.82136, -1.66334, -1.45381, -1.09089, -0.81832, -0.73307, -0.71760, -0.49404, -0.29497, -0.25005, -0.10960, 0.25187, 0.50346, 0.57204, 0.67549, 0.80419, 0.84874, 0.71522, 0.57004, 0.48836, 0.26218, 0.06009, -0.02022, -0.03346, -0.07268, -0.15436, -0.15080, -0.20345, -0.27882, -0.10527, 0.24276, 0.48614, 0.56929, 0.63411, 0.57503, 0.66238, 0.87502, 1.07098, 1.10345, 1.17938, 1.38417, 1.54272, 1.64914, 1.85228, 2.07730, 2.21388, 2.41666, 2.53172, 2.64642, 2.57732, 2.45435, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.30813, 1.08269, 0.68970, 0.36421, 0.25525, 0.17448, 0.01947, -0.10592, -0.28624, -0.27981, -0.35654, -0.46905, -0.61995, -0.61818, -0.53322, -0.59826, -0.65244, -0.59135, -0.61687, -0.76572, -0.80484, -0.87524, -0.95539, -1.05067, -1.09174, -1.00255, -0.99804, -1.08454, -1.24373, -1.45247, -1.63299, -1.64332, -1.48371, -1.23460, -1.13992, -1.00053, -0.75209, -0.54119, -0.38237, -0.20566, -0.28583, -0.38235, -0.46327, -0.51683, -0.76693, -0.95289, -0.89161, -0.85045, -0.90508, -0.98058, -1.02258, -1.17766, -1.20410, -1.12898, -1.03483, -1.00034, +0.31366, 0.32252, 0.38674, 0.32139, 0.08930, -0.05000, -0.13995, -0.36184, -0.58808, -0.57091, -0.45417, -0.36744, -0.36148, -0.27300, -0.14727, -0.33143, -0.46660, -0.37361, -0.20324, -0.20254, -0.26515, -0.25179, -0.31568, -0.36542, -0.28324, -0.27222, -0.22795, -0.02898, 0.18034, 0.19419, 0.15225, 0.15131, 0.12891, 0.19445, 0.23816, 0.19614, 0.17435, 0.34351, 0.57485, 0.64586, 0.61173, 0.73253, 0.80464, 0.71749, 0.56364, 0.53296, 0.64555, 0.58359, 0.48663, 0.52525, 0.63998, 0.65128, 0.49428, 0.31556, 0.16513, 0.08819, 0.01994, -0.14734, -0.36139, -0.43297, -0.48808, -0.64716, -0.70804, -0.66912, -0.81438, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.12530, -0.04426, 0.02975, 0.20168, 0.42877, 0.39387, 0.30630, 0.39445, 0.48937, 0.57604, 0.59569, 0.65530, 0.59685, 0.48273, 0.40310, 0.28386, 0.09491, 0.11506, 0.23007, 0.18872, -0.00925, -0.19764, -0.43192, -0.52048, -0.46905, -0.41603, -0.45392, -0.35405, -0.30753, -0.41547, -0.56690, -0.54061, -0.34288, -0.19288, -0.12564, -0.04290, 0.20710, 0.32381, 0.23897, 0.16192, 0.18799, 0.28716, 0.30923, 0.42238, 0.46278, 0.43602, 0.30062, 0.06684, -0.23674, -0.48036, -0.66065, -0.80653, -0.90517, -0.88076, -0.87297, -0.74517, -0.59059, -0.47979, -0.52806, -0.47050, -0.39342, -0.47255, -0.57195, -0.49190, -0.29331, -0.21288, -0.23267, -0.29006, -0.23373, -0.15227, -0.08930, 0.06976, 0.21647, 0.28376, 0.18864, 0.17232, 0.13985, 0.16344, 0.28892, 0.44734, 0.43946, 0.42117, 0.46432, 0.42627, 0.32978, 0.33944, 0.31185, 0.38038, 0.46901, 0.53289, 0.50378, 0.52851, 0.59115, 0.49649, 0.20320, -0.05180, -0.11523, -0.21321, -0.45884, -0.80109, -0.90608, -0.98015, -1.19055, -1.34642, -1.48958, -1.59796, -1.83566, -1.96096, -2.06524, -2.26729, -2.54292, -2.72499, -2.91795, -3.04357, -2.96072, -2.82418, -2.78563, -2.61423, -2.53605, -2.49664, -2.53151, -2.63580, -2.73512, -2.68840, -2.58075, -2.57951, -2.67699, -2.73160, -2.62591, -2.46353, -2.35485, -2.38403, -2.31628, -2.21913, -2.24546, -2.32097, -2.41804, -2.41753, -2.49330, -2.54582, -2.66990, -2.80633, -2.85891, -2.81089, -2.80414, -2.85927, -2.78949, -2.73069, -2.88088, -2.92737, -2.93046, -2.88648, -2.81605, -2.77981, -2.88712, -2.91223, -2.79503, -2.68207, -2.77753, -2.86388, -2.69028, -2.45905, -2.31369, -2.25181, -2.12251, -1.97311, -2.00976, -1.99579, -1.87157, -1.75978, -1.75957, -1.68118, -1.59690, -1.63885, -1.67262, -1.61890, -1.61000, -1.59022, -1.39813, -1.18115, -1.16893, -1.15851, -1.05773, -1.01932, -1.01401, -1.10901, -1.23266, -1.39106, -1.43573, -1.43639, -1.50331, -1.61218, -1.59990, -1.59677, -1.66770, -1.86097, -1.96144, -1.85507, -1.86456, -1.91685, -2.04472, -2.18566, -2.32538, -2.42335, -2.37574, -2.35067, -2.24549, -2.06151, -2.07075, -2.17453, -2.13398, -1.99530, -1.98350, -1.91410, -1.73572, -1.49566, -1.15163, -0.84719, -0.72732, -0.69438, -0.48023, -0.25978, -0.14220, -0.06026, 0.17536, 0.45842, 0.63470, 0.70925, 0.77335, 0.80101, 0.58185, 0.31326, 0.13262, -0.03686, -0.10907, -0.15644, -0.14354, -0.18098, -0.23438, -0.21182, -0.28430, -0.38698, -0.19521, 0.15045, 0.32562, 0.40287, 0.54594, 0.57023, 0.63227, 0.80242, 0.97567, 1.06403, 1.24581, 1.47820, 1.63339, 1.65526, 1.76448, 2.03284, 2.25767, 2.39092, 2.40542, 2.50425, 2.44141, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.26546, 1.00087, 0.59589, 0.33751, 0.29858, 0.25184, 0.15175, 0.06228, -0.12473, -0.21117, -0.27769, -0.33955, -0.47100, -0.46894, -0.38541, -0.37971, -0.45352, -0.50816, -0.54692, -0.66126, -0.80709, -1.02228, -1.09134, -1.13740, -1.19719, -1.15912, -1.13059, -1.11059, -1.21951, -1.37336, -1.56822, -1.58085, -1.44133, -1.30076, -1.24257, -1.02209, -0.71464, -0.54130, -0.47353, -0.37096, -0.43831, -0.54856, -0.64860, -0.75394, -1.02418, -1.15305, -1.06283, -0.97367, -1.06145, -1.24623, -1.27214, -1.24289, -1.19541, -1.20873, -1.16323, -1.13924, +0.19467, 0.19174, 0.20965, 0.24449, 0.14378, -0.17375, -0.45412, -0.64280, -0.73430, -0.70118, -0.64904, -0.56176, -0.56850, -0.54511, -0.38089, -0.46799, -0.53908, -0.46438, -0.38882, -0.37575, -0.36134, -0.33100, -0.30910, -0.37268, -0.34183, -0.29380, -0.19275, -0.00904, 0.14438, 0.16033, 0.08128, 0.14843, 0.16239, 0.16343, 0.15425, 0.21284, 0.35624, 0.46540, 0.58269, 0.64587, 0.62659, 0.67989, 0.70623, 0.68288, 0.60629, 0.57476, 0.69503, 0.66459, 0.57203, 0.58328, 0.61502, 0.64985, 0.55403, 0.30056, 0.09246, -0.03377, -0.15331, -0.29140, -0.53079, -0.66914, -0.73735, -0.78319, -0.84821, -0.75468, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.24510, -0.05611, 0.11165, 0.26624, 0.38412, 0.53187, 0.50236, 0.46698, 0.61372, 0.65537, 0.68892, 0.65142, 0.57571, 0.49620, 0.38434, 0.19844, 0.07101, -0.10023, -0.05038, 0.04598, 0.07426, -0.13994, -0.30093, -0.42644, -0.46469, -0.41528, -0.37069, -0.31184, -0.29555, -0.34127, -0.40509, -0.42902, -0.31991, -0.17931, -0.04916, 0.04009, 0.06300, 0.25955, 0.42908, 0.39030, 0.32296, 0.20691, 0.23205, 0.25316, 0.25417, 0.19475, 0.14829, -0.01181, -0.14050, -0.40014, -0.58084, -0.72551, -0.80445, -0.95284, -0.95434, -0.83624, -0.72150, -0.64012, -0.62584, -0.60768, -0.57715, -0.60171, -0.64990, -0.65252, -0.53914, -0.46191, -0.42756, -0.33218, -0.32279, -0.26438, -0.15826, -0.11415, 0.08478, 0.22909, 0.30418, 0.21928, 0.10553, 0.02311, 0.11058, 0.19518, 0.38496, 0.38452, 0.38815, 0.42656, 0.51559, 0.42255, 0.33609, 0.30139, 0.33904, 0.44911, 0.51935, 0.66248, 0.75652, 0.67275, 0.49105, 0.23405, 0.01203, -0.12569, -0.24423, -0.37701, -0.69441, -0.88923, -0.94877, -1.15311, -1.29645, -1.53797, -1.71257, -1.87102, -1.98952, -2.16105, -2.29039, -2.55853, -2.74087, -2.98442, -3.12434, -3.03966, -2.83384, -2.78656, -2.71216, -2.59890, -2.50882, -2.48912, -2.55362, -2.51263, -2.41888, -2.51903, -2.62749, -2.59177, -2.49198, -2.39407, -2.31407, -2.18623, -2.19418, -2.15613, -2.05164, -2.14213, -2.26489, -2.42517, -2.46820, -2.50094, -2.58346, -2.80061, -2.89416, -2.91473, -2.76607, -2.74035, -2.85325, -2.90422, -2.83631, -2.89784, -2.95568, -2.84778, -2.70725, -2.64497, -2.66209, -2.68537, -2.61856, -2.62857, -2.57979, -2.53382, -2.51011, -2.40020, -2.24167, -2.04668, -1.97449, -1.96976, -1.86261, -1.87676, -1.84242, -1.78535, -1.71094, -1.63496, -1.59273, -1.66264, -1.69028, -1.65318, -1.54187, -1.49934, -1.53197, -1.41498, -1.16935, -1.05988, -1.07638, -0.98473, -0.98049, -1.12235, -1.31687, -1.32262, -1.31327, -1.47741, -1.65838, -1.71591, -1.74279, -1.72375, -1.79270, -1.86937, -2.04268, -2.16107, -1.99662, -1.92488, -1.93208, -2.05855, -2.23221, -2.26725, -2.27899, -2.36702, -2.44223, -2.42341, -2.26833, -2.20404, -2.30154, -2.25990, -2.08554, -2.00292, -1.98347, -1.79838, -1.49995, -1.17659, -0.87321, -0.63790, -0.47438, -0.42163, -0.36799, -0.23313, -0.10850, 0.05926, 0.24680, 0.48133, 0.61859, 0.61038, 0.65233, 0.49819, 0.18889, -0.06729, -0.29877, -0.25826, -0.22326, -0.31251, -0.44171, -0.49899, -0.45568, -0.40465, -0.45606, -0.28853, 0.02125, 0.22910, 0.30013, 0.53853, 0.71215, 0.76645, 0.84597, 1.00933, 1.24034, 1.37235, 1.45376, 1.57323, 1.64457, 1.78855, 2.00879, 2.23855, 2.38017, 2.30068, 2.33175, 2.33410, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.12860, 0.94406, 0.53953, 0.26167, 0.21724, 0.29163, 0.25545, 0.23249, 0.11657, -0.03597, -0.16015, -0.23717, -0.27540, -0.37844, -0.46087, -0.44510, -0.44161, -0.47971, -0.54398, -0.65388, -0.81973, -1.15237, -1.27910, -1.21693, -1.24684, -1.22109, -1.31887, -1.29543, -1.27633, -1.39596, -1.58358, -1.54960, -1.45675, -1.32175, -1.26258, -1.00520, -0.70589, -0.49550, -0.52176, -0.51451, -0.52567, -0.62580, -0.77583, -0.95312, -1.11488, -1.21081, -1.23751, -1.18780, -1.21838, -1.35524, -1.41946, -1.33824, -1.18277, -1.25315, -1.33562, -1.30799, +0.05748, 0.11962, 0.03933, 0.00602, -0.00584, -0.27008, -0.53810, -0.71294, -0.83457, -0.82496, -0.85107, -0.83810, -0.78797, -0.70714, -0.62624, -0.76952, -0.81078, -0.72425, -0.63247, -0.55040, -0.42692, -0.31314, -0.18815, -0.18836, -0.19641, -0.16173, -0.03516, 0.13730, 0.18062, 0.10176, 0.04192, 0.13161, 0.21959, 0.29883, 0.23379, 0.22905, 0.41903, 0.55970, 0.66305, 0.74173, 0.70857, 0.73082, 0.69117, 0.60062, 0.59610, 0.64866, 0.69341, 0.56121, 0.46979, 0.47102, 0.46651, 0.46691, 0.37246, 0.13511, -0.04975, -0.13735, -0.30442, -0.47766, -0.68046, -0.77766, -0.87960, -0.98969, -1.03522, -0.92004, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.28205, -0.25433, -0.12731, 0.01614, 0.10843, 0.31635, 0.52722, 0.63946, 0.54540, 0.55762, 0.71868, 0.72785, 0.70003, 0.60946, 0.51378, 0.41677, 0.31935, 0.07086, -0.10491, -0.20609, -0.06045, 0.02647, -0.03341, -0.23162, -0.39050, -0.45114, -0.35745, -0.33359, -0.39262, -0.31576, -0.24148, -0.25530, -0.23737, -0.23472, -0.14040, -0.05960, -0.05778, 0.03125, 0.13876, 0.29179, 0.32109, 0.27427, 0.20506, 0.03461, -0.00283, -0.03355, -0.04898, -0.12143, -0.11332, -0.27038, -0.40371, -0.59380, -0.63172, -0.66554, -0.79168, -0.94439, -1.00670, -0.92920, -0.74469, -0.71469, -0.87556, -0.90789, -0.83074, -0.82930, -0.78462, -0.74147, -0.62122, -0.54414, -0.56205, -0.40483, -0.24981, -0.17407, -0.19970, -0.17031, 0.05881, 0.20137, 0.26355, 0.17352, 0.09689, 0.06711, 0.26528, 0.34812, 0.47155, 0.46983, 0.51994, 0.55693, 0.52718, 0.39627, 0.27551, 0.24502, 0.40600, 0.55411, 0.52930, 0.65173, 0.78101, 0.68208, 0.53721, 0.28840, 0.05162, -0.11110, -0.33613, -0.45899, -0.64798, -0.82726, -1.02448, -1.28161, -1.43167, -1.69953, -1.89508, -2.04657, -2.11812, -2.26679, -2.25882, -2.41623, -2.61630, -2.87769, -3.02479, -2.99088, -2.91820, -2.91751, -2.89214, -2.79163, -2.56821, -2.46696, -2.57975, -2.54813, -2.39780, -2.45373, -2.45059, -2.32788, -2.19781, -2.10313, -2.14016, -2.05494, -1.96721, -1.91874, -1.97854, -2.17319, -2.31764, -2.47997, -2.53354, -2.58683, -2.65705, -2.86740, -2.88016, -2.84875, -2.73643, -2.72677, -2.80046, -2.85151, -2.88422, -2.97414, -3.02589, -2.90865, -2.66149, -2.53692, -2.62966, -2.70091, -2.58017, -2.55012, -2.43706, -2.30926, -2.25386, -2.15087, -2.08388, -1.94399, -1.79372, -1.75292, -1.77158, -1.87780, -1.86039, -1.83730, -1.74637, -1.61826, -1.55456, -1.63866, -1.64344, -1.57203, -1.47207, -1.42435, -1.43237, -1.31365, -1.15047, -1.10965, -1.15389, -1.12288, -1.09237, -1.17334, -1.40318, -1.45221, -1.39359, -1.52159, -1.68860, -1.70805, -1.74104, -1.76343, -1.93704, -2.09511, -2.17447, -2.15570, -2.01226, -1.99023, -1.95266, -2.04294, -2.20240, -2.23023, -2.24113, -2.35721, -2.43396, -2.41381, -2.32999, -2.30751, -2.38839, -2.33324, -2.23569, -2.24017, -2.21527, -2.03904, -1.66642, -1.23815, -0.96898, -0.79936, -0.60375, -0.52290, -0.46505, -0.28929, -0.16815, -0.02872, 0.08688, 0.23514, 0.41782, 0.48157, 0.50394, 0.29291, -0.01885, -0.30048, -0.58781, -0.56945, -0.50218, -0.54927, -0.65641, -0.64293, -0.59604, -0.54320, -0.53947, -0.33160, -0.06167, 0.09268, 0.24227, 0.52197, 0.78271, 0.96133, 0.99513, 1.04589, 1.28125, 1.43841, 1.50790, 1.67179, 1.76763, 1.93605, 2.12154, 2.23292, 2.37222, 2.34800, 2.29226, 2.12400, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.84123, 0.48422, 0.27109, 0.23132, 0.23466, 0.24218, 0.24136, 0.16860, 0.12301, -0.03279, -0.24532, -0.31057, -0.39297, -0.49155, -0.42891, -0.42705, -0.48530, -0.52847, -0.69558, -0.86324, -1.13818, -1.35328, -1.46522, -1.51152, -1.48231, -1.61064, -1.58543, -1.51710, -1.53427, -1.63569, -1.48276, -1.36721, -1.24152, -1.12253, -0.81781, -0.56160, -0.52083, -0.62439, -0.68473, -0.71111, -0.71459, -0.87017, -1.15446, -1.29149, -1.27777, -1.27199, -1.16428, -1.17877, -1.32272, -1.40712, -1.43432, -1.29625, -1.27341, -1.35167, -1.45237, +-0.05756, -0.04598, -0.07515, -0.18040, -0.24245, -0.36403, -0.60310, -0.76376, -0.93672, -1.01698, -0.99246, -0.92450, -0.90646, -0.80974, -0.71866, -0.91290, -0.98020, -0.91416, -0.77187, -0.61648, -0.46248, -0.25175, -0.08722, -0.05446, -0.07214, 0.02231, 0.19325, 0.25752, 0.21834, 0.17271, 0.17027, 0.18002, 0.24066, 0.31016, 0.37149, 0.37923, 0.44897, 0.60547, 0.65014, 0.69807, 0.67934, 0.65647, 0.68057, 0.67109, 0.63033, 0.63661, 0.67309, 0.50298, 0.41485, 0.40721, 0.39397, 0.32987, 0.11648, -0.11158, -0.28233, -0.35393, -0.48456, -0.58075, -0.68022, -0.83649, -0.97281, -1.03781, -0.98681, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.30891, -0.20797, -0.12686, -0.05837, 0.09629, 0.21655, 0.33550, 0.47935, 0.64706, 0.60684, 0.67868, 0.83499, 0.82385, 0.73473, 0.52010, 0.40447, 0.30925, 0.17644, -0.08076, -0.24974, -0.23965, -0.14002, -0.06735, -0.07212, -0.10850, -0.30360, -0.37417, -0.34804, -0.31677, -0.32164, -0.33926, -0.19475, -0.12571, -0.09994, -0.07083, -0.11151, -0.08997, -0.05116, -0.01014, 0.03573, 0.22052, 0.20585, 0.14150, 0.06844, -0.11243, -0.17208, -0.28994, -0.33637, -0.40474, -0.44877, -0.59537, -0.71127, -0.74103, -0.72569, -0.64958, -0.69325, -0.71348, -0.87220, -0.93214, -0.88616, -0.90148, -1.02033, -1.15756, -1.06215, -0.98599, -0.95723, -0.87770, -0.81243, -0.69662, -0.55049, -0.34633, -0.24360, -0.12603, -0.18005, -0.15416, 0.10744, 0.28229, 0.38432, 0.24713, 0.15925, 0.19734, 0.38028, 0.47615, 0.56093, 0.65927, 0.66411, 0.63092, 0.51613, 0.46087, 0.32398, 0.29575, 0.46402, 0.65070, 0.72601, 0.70945, 0.72457, 0.63533, 0.45618, 0.24411, -0.02562, -0.19197, -0.33422, -0.44197, -0.69056, -0.82389, -1.01940, -1.27469, -1.41366, -1.69711, -1.89220, -2.12016, -2.23931, -2.31592, -2.25976, -2.26686, -2.43098, -2.59102, -2.78879, -2.90486, -2.94855, -2.88717, -2.87868, -2.81507, -2.61859, -2.51347, -2.52770, -2.59309, -2.50722, -2.42534, -2.32363, -2.11087, -2.00593, -1.96346, -1.96334, -1.87025, -1.85476, -1.78850, -1.86896, -2.11810, -2.27550, -2.45229, -2.50269, -2.63187, -2.76203, -2.88872, -2.90090, -2.84394, -2.80383, -2.73793, -2.75592, -2.83682, -2.88869, -2.86147, -2.87003, -2.83884, -2.68506, -2.61278, -2.60463, -2.72068, -2.66206, -2.52559, -2.39583, -2.23386, -2.17511, -2.10445, -1.95527, -1.73774, -1.63130, -1.57774, -1.60210, -1.77037, -1.77502, -1.77976, -1.64714, -1.51041, -1.51346, -1.55586, -1.58984, -1.53243, -1.44871, -1.32198, -1.24442, -1.17724, -1.07634, -1.00827, -1.08117, -1.21799, -1.27824, -1.36297, -1.42415, -1.46432, -1.50209, -1.54693, -1.69934, -1.70839, -1.74206, -1.84107, -1.98917, -2.10646, -2.22722, -2.18334, -1.98763, -1.96627, -1.85272, -1.86300, -1.96798, -2.04812, -2.20644, -2.34122, -2.43650, -2.44028, -2.40167, -2.36369, -2.40067, -2.47169, -2.48964, -2.46935, -2.35236, -2.23799, -1.87207, -1.47022, -1.13682, -0.97536, -0.89811, -0.74227, -0.62433, -0.40157, -0.23130, -0.15952, -0.04371, 0.12531, 0.23635, 0.25488, 0.33918, 0.15119, -0.13375, -0.40318, -0.70693, -0.76085, -0.77828, -0.76966, -0.79642, -0.72562, -0.64819, -0.57319, -0.51446, -0.42218, -0.21559, 0.01157, 0.34489, 0.58543, 0.83768, 0.98000, 1.05702, 1.13973, 1.25842, 1.46477, 1.57218, 1.71538, 1.84216, 1.93653, 2.11490, 2.26375, 2.36673, 2.29531, 2.23915, 1.96611, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.70177, 0.47923, 0.24379, 0.20519, 0.23496, 0.36330, 0.30054, 0.20163, 0.11446, 0.00479, -0.13273, -0.33366, -0.43450, -0.53168, -0.53883, -0.53118, -0.66708, -0.66267, -0.69037, -0.84878, -1.18127, -1.41355, -1.63227, -1.72017, -1.68784, -1.78232, -1.71265, -1.68103, -1.66763, -1.67896, -1.51698, -1.35178, -1.18619, -0.90613, -0.66802, -0.52266, -0.59177, -0.65517, -0.79515, -0.86071, -0.89120, -1.01043, -1.17726, -1.37747, -1.34338, -1.26688, -1.18511, -1.13945, -1.31599, -1.42842, -1.43270, -1.35644, -1.40405, -1.39737, -1.46226, +-0.04206, -0.06413, -0.11550, -0.26124, -0.32459, -0.38948, -0.63669, -0.76871, -0.83259, -0.89217, -0.97445, -0.97654, -0.90712, -0.77719, -0.61213, -0.75041, -0.94210, -0.99718, -0.91312, -0.72609, -0.44445, -0.14138, -0.03860, -0.06895, -0.05696, 0.06074, 0.24986, 0.31760, 0.28736, 0.25848, 0.24564, 0.23680, 0.25340, 0.34253, 0.50908, 0.55937, 0.58049, 0.64247, 0.55496, 0.51733, 0.56813, 0.64175, 0.65013, 0.61615, 0.61393, 0.61265, 0.67229, 0.57906, 0.43845, 0.36567, 0.32183, 0.20791, -0.00416, -0.18985, -0.41707, -0.55129, -0.56905, -0.58248, -0.66692, -0.84205, -0.96426, -0.95903, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.18154, -0.20238, -0.20436, -0.01894, 0.16975, 0.28482, 0.28174, 0.28977, 0.33643, 0.49557, 0.59500, 0.68676, 0.77841, 0.74278, 0.59791, 0.37729, 0.30848, 0.20034, -0.01962, -0.26100, -0.42990, -0.44679, -0.39868, -0.32128, -0.20247, -0.10690, -0.19881, -0.28711, -0.32594, -0.30325, -0.26926, -0.25576, -0.07675, 0.00080, -0.03481, 0.02461, 0.01981, -0.05941, -0.16123, -0.17069, -0.14046, 0.06494, 0.15284, 0.06596, -0.07382, -0.25553, -0.33055, -0.40511, -0.40895, -0.56211, -0.80805, -0.97199, -1.03755, -1.00057, -0.92688, -0.75434, -0.64576, -0.59089, -0.65253, -0.76716, -0.85790, -0.96405, -1.08206, -1.14671, -1.00278, -0.90538, -0.96177, -0.91331, -0.78902, -0.69925, -0.61359, -0.39623, -0.29655, -0.17234, -0.13105, -0.11487, 0.09416, 0.33947, 0.49815, 0.40000, 0.38188, 0.39876, 0.40225, 0.45581, 0.56331, 0.70652, 0.68187, 0.59288, 0.48234, 0.45248, 0.42484, 0.46425, 0.66205, 0.88428, 0.99072, 0.94309, 0.86714, 0.68959, 0.38282, 0.15544, 0.01277, -0.10627, -0.32308, -0.45799, -0.70666, -0.82414, -0.87533, -1.05879, -1.26366, -1.58691, -1.83605, -2.08445, -2.14042, -2.18136, -2.23090, -2.18991, -2.26219, -2.36770, -2.54296, -2.72561, -2.82196, -2.82563, -2.78986, -2.67731, -2.50058, -2.38396, -2.39040, -2.51739, -2.49034, -2.41557, -2.33002, -2.08997, -1.88773, -1.84243, -1.97617, -1.95984, -1.94652, -1.83008, -1.77346, -1.99521, -2.23868, -2.47064, -2.58795, -2.76565, -2.82211, -2.85247, -2.98353, -3.00790, -3.00113, -2.91993, -2.88959, -2.92476, -2.88420, -2.77666, -2.70064, -2.65508, -2.58861, -2.57155, -2.55195, -2.65739, -2.57671, -2.41429, -2.35007, -2.22815, -2.07491, -1.93777, -1.81341, -1.58159, -1.46233, -1.41843, -1.37837, -1.51079, -1.58824, -1.64628, -1.55646, -1.44457, -1.41016, -1.38646, -1.46602, -1.47386, -1.39729, -1.27978, -1.16799, -1.05150, -0.91996, -0.83036, -0.94498, -1.17834, -1.35363, -1.46364, -1.43615, -1.42130, -1.44412, -1.47919, -1.69759, -1.77711, -1.74032, -1.74450, -1.93956, -2.14692, -2.29532, -2.28133, -2.04585, -1.94772, -1.79693, -1.73504, -1.81748, -1.96303, -2.16095, -2.27097, -2.44677, -2.55834, -2.53154, -2.50585, -2.54403, -2.65212, -2.70980, -2.66061, -2.50263, -2.34281, -1.98844, -1.60466, -1.27416, -1.12466, -1.05611, -0.88278, -0.74268, -0.50783, -0.25497, -0.12072, -0.10525, -0.07563, -0.00899, -0.01744, 0.10162, 0.02860, -0.25117, -0.50346, -0.73927, -0.83588, -0.87130, -0.80557, -0.80166, -0.73378, -0.60156, -0.49846, -0.48419, -0.50343, -0.37413, -0.11683, 0.28230, 0.58520, 0.82410, 0.93990, 1.01485, 1.10878, 1.26243, 1.54106, 1.65113, 1.68727, 1.81377, 1.94140, 2.02247, 2.02542, 2.14153, 2.11729, 2.07245, 1.83769, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.41453, 0.20718, 0.21601, 0.33544, 0.48699, 0.46128, 0.34401, 0.23534, 0.17799, 0.09343, -0.13803, -0.30248, -0.50189, -0.67341, -0.68808, -0.74556, -0.76170, -0.86263, -0.99450, -1.25034, -1.41041, -1.56659, -1.74545, -1.83082, -1.87887, -1.76239, -1.68996, -1.55663, -1.54880, -1.54788, -1.41724, -1.23923, -0.92010, -0.72876, -0.65790, -0.74851, -0.85160, -0.95519, -0.97527, -0.93844, -0.98611, -1.09434, -1.26751, -1.24780, -1.22391, -1.27656, -1.19244, -1.21719, -1.35794, -1.54989, -1.57538, -1.60126, -1.51001, -1.38695, +-0.10715, -0.05888, -0.14108, -0.33606, -0.41319, -0.54989, -0.68308, -0.65746, -0.64908, -0.67774, -0.72232, -0.81542, -0.76260, -0.56208, -0.43680, -0.55717, -0.81820, -0.87969, -0.88164, -0.78996, -0.50678, -0.16774, -0.01604, 0.01338, 0.14992, 0.20030, 0.31158, 0.40888, 0.36397, 0.27661, 0.21757, 0.21755, 0.19351, 0.30999, 0.48162, 0.49118, 0.53172, 0.50515, 0.45107, 0.48493, 0.47236, 0.50899, 0.54734, 0.51287, 0.53407, 0.70002, 0.77226, 0.65051, 0.44379, 0.39923, 0.37272, 0.19315, -0.00707, -0.18586, -0.37035, -0.47434, -0.36254, -0.42853, -0.58864, -0.69742, -0.75482, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.07798, -0.07349, -0.16301, -0.13333, 0.01318, 0.21402, 0.38898, 0.40777, 0.30790, 0.36071, 0.41211, 0.41790, 0.45363, 0.56553, 0.61033, 0.42507, 0.24812, 0.16740, 0.09075, -0.14091, -0.29744, -0.50674, -0.61573, -0.54334, -0.46522, -0.35344, -0.28878, -0.35593, -0.45720, -0.46340, -0.33882, -0.29978, -0.20675, -0.07380, -0.05172, 0.01759, 0.06151, 0.08056, 0.03133, -0.08426, -0.21334, -0.11635, 0.07104, 0.10902, -0.01296, -0.15018, -0.24096, -0.39440, -0.46804, -0.56528, -0.74653, -1.03716, -1.07708, -1.07618, -1.08812, -0.98775, -0.83934, -0.73836, -0.69947, -0.66389, -0.73588, -0.88079, -1.00728, -1.18510, -1.13324, -0.93054, -0.81763, -0.69569, -0.66736, -0.59975, -0.55838, -0.49626, -0.40142, -0.23936, -0.09506, -0.09014, -0.11033, 0.05892, 0.40892, 0.51769, 0.46984, 0.45219, 0.53276, 0.51887, 0.61512, 0.72795, 0.74378, 0.68533, 0.59551, 0.51756, 0.51945, 0.55579, 0.63024, 0.78191, 1.00943, 1.05548, 1.05265, 1.01343, 0.75850, 0.51774, 0.26351, 0.11599, 0.04776, -0.08572, -0.30982, -0.51127, -0.60058, -0.69169, -0.90812, -1.19400, -1.43492, -1.72249, -1.89045, -1.92568, -1.91550, -2.02013, -1.99263, -2.00807, -2.17749, -2.29409, -2.42058, -2.58088, -2.73875, -2.79121, -2.68922, -2.56481, -2.38417, -2.38326, -2.49554, -2.46452, -2.50550, -2.35729, -2.10308, -1.92988, -1.87109, -1.94797, -2.04195, -2.02216, -1.86080, -1.84016, -2.07378, -2.35002, -2.45981, -2.61912, -2.82683, -2.92696, -2.94427, -3.11702, -3.14301, -3.03489, -2.97243, -2.93022, -2.89731, -2.86548, -2.81962, -2.74792, -2.64670, -2.57831, -2.52103, -2.53314, -2.62149, -2.45364, -2.32531, -2.18582, -2.03160, -1.90921, -1.74561, -1.53379, -1.37408, -1.28773, -1.18265, -1.14277, -1.22937, -1.33803, -1.34007, -1.36742, -1.41269, -1.44596, -1.38458, -1.35616, -1.27919, -1.11904, -1.11347, -1.07267, -0.88412, -0.74886, -0.69037, -0.83719, -1.10160, -1.36368, -1.49014, -1.47618, -1.44790, -1.36982, -1.41437, -1.57100, -1.61310, -1.65326, -1.68237, -1.84266, -2.12268, -2.31345, -2.22635, -2.04853, -2.00106, -1.90183, -1.76074, -1.82209, -2.03257, -2.19735, -2.24886, -2.39857, -2.54464, -2.50589, -2.61099, -2.71686, -2.73280, -2.74072, -2.71602, -2.61066, -2.44465, -2.13001, -1.74435, -1.42980, -1.32645, -1.18886, -1.03794, -0.85531, -0.53446, -0.33947, -0.21523, -0.14897, -0.12712, -0.13168, -0.08440, -0.07915, -0.26283, -0.57490, -0.70261, -0.74540, -0.84613, -0.87544, -0.82898, -0.76429, -0.63774, -0.38409, -0.28338, -0.33271, -0.36305, -0.32164, -0.20742, 0.06109, 0.34242, 0.55184, 0.69225, 0.80522, 0.86818, 1.11592, 1.40398, 1.51443, 1.62727, 1.69803, 1.80356, 1.88090, 1.83627, 1.84421, 1.90546, 1.83973, 1.56784, 1.23369, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.50893, 0.37674, 0.43801, 0.56114, 0.64479, 0.60229, 0.45431, 0.33406, 0.30744, 0.14207, -0.07804, -0.28679, -0.53564, -0.60408, -0.67859, -0.78882, -0.88002, -1.03165, -1.23482, -1.30462, -1.32275, -1.48609, -1.75021, -1.91512, -1.87581, -1.80839, -1.68667, -1.49771, -1.37405, -1.39318, -1.23997, -1.12851, -0.96375, -0.80597, -0.75846, -0.87637, -1.04711, -1.14426, -1.13228, -1.06295, -1.02085, -1.12790, -1.18846, -1.12053, -1.17754, -1.18784, -1.16976, -1.24053, -1.40489, -1.59142, -1.70004, -1.60032, -1.43840, -1.34288, +-0.11376, -0.03717, -0.07826, -0.24063, -0.40572, -0.61020, -0.71559, -0.63459, -0.53638, -0.51191, -0.45669, -0.51414, -0.59409, -0.50792, -0.42514, -0.49257, -0.65770, -0.69058, -0.71688, -0.66675, -0.43911, -0.13122, 0.10799, 0.24285, 0.37201, 0.38153, 0.46521, 0.53170, 0.44056, 0.34574, 0.33810, 0.40356, 0.37082, 0.41936, 0.53269, 0.51715, 0.48727, 0.39156, 0.35252, 0.36587, 0.32072, 0.28414, 0.32449, 0.38345, 0.39651, 0.58044, 0.70063, 0.58422, 0.40944, 0.41548, 0.41764, 0.28382, 0.10238, -0.08675, -0.20698, -0.24252, -0.19753, -0.35658, -0.49723, -0.51649, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.15513, -0.04554, -0.11842, -0.25254, -0.29834, -0.19877, -0.01158, 0.21999, 0.40375, 0.29108, 0.22384, 0.20387, 0.14447, 0.17989, 0.36533, 0.48788, 0.41311, 0.28983, 0.17690, 0.07101, -0.15654, -0.35752, -0.62510, -0.68947, -0.52918, -0.46498, -0.39991, -0.39837, -0.47952, -0.56128, -0.54315, -0.32316, -0.19956, -0.12291, -0.14128, -0.20426, -0.17558, -0.10803, -0.01247, 0.00833, 0.00205, -0.17448, -0.19912, -0.05497, -0.04088, -0.13903, -0.19626, -0.24882, -0.38069, -0.52424, -0.75240, -0.95904, -1.15562, -1.12509, -1.11838, -1.10719, -0.95729, -0.87468, -0.82317, -0.78063, -0.69863, -0.71588, -0.88522, -0.99975, -1.11966, -1.04166, -0.89053, -0.75046, -0.55800, -0.46407, -0.38455, -0.36874, -0.24806, -0.20796, -0.16333, -0.02610, -0.01128, -0.02357, 0.17821, 0.48288, 0.57396, 0.54556, 0.53111, 0.69000, 0.81480, 0.92278, 0.93373, 0.86176, 0.83175, 0.76544, 0.75229, 0.84423, 0.92113, 0.98950, 1.01041, 1.13489, 1.17824, 1.18995, 1.11964, 0.85049, 0.56174, 0.29394, 0.16847, 0.12964, 0.14235, -0.06337, -0.37417, -0.50926, -0.64551, -0.91504, -1.17246, -1.35802, -1.53328, -1.57042, -1.58316, -1.57811, -1.65147, -1.69601, -1.81785, -2.02514, -2.07493, -2.17229, -2.37383, -2.59599, -2.73982, -2.71556, -2.69066, -2.53248, -2.42864, -2.46611, -2.49457, -2.59440, -2.49695, -2.25242, -2.05554, -1.96469, -1.90214, -1.96958, -2.07945, -2.04090, -2.08945, -2.29884, -2.44400, -2.40859, -2.47050, -2.65362, -2.84440, -2.97294, -3.13331, -3.15204, -3.05070, -2.95956, -2.85342, -2.80604, -2.85023, -2.86029, -2.79212, -2.63960, -2.53463, -2.47621, -2.45754, -2.49704, -2.35714, -2.25475, -2.11620, -1.95524, -1.80569, -1.61974, -1.32118, -1.16595, -1.20519, -1.14457, -1.05050, -1.02307, -1.02819, -0.99646, -1.08132, -1.22876, -1.35743, -1.34781, -1.23340, -1.07650, -0.95123, -1.00175, -0.97106, -0.78063, -0.67951, -0.61115, -0.69696, -0.90867, -1.17888, -1.34470, -1.31995, -1.24289, -1.17167, -1.22431, -1.36057, -1.43036, -1.52495, -1.65790, -1.81740, -2.04143, -2.28073, -2.22727, -2.07093, -2.05292, -1.97496, -1.84616, -1.89386, -2.05903, -2.16082, -2.18627, -2.29325, -2.43776, -2.53143, -2.75288, -2.84721, -2.76642, -2.71269, -2.67798, -2.59794, -2.45271, -2.18852, -1.87989, -1.57512, -1.43918, -1.32738, -1.23990, -1.08972, -0.84036, -0.66593, -0.52742, -0.35877, -0.17975, -0.22858, -0.28977, -0.37139, -0.62141, -0.88640, -0.89362, -0.82048, -0.81711, -0.81609, -0.80290, -0.73332, -0.55664, -0.32842, -0.24607, -0.22342, -0.18787, -0.20719, -0.20506, -0.04725, 0.17827, 0.35852, 0.47577, 0.62829, 0.75507, 0.98547, 1.15429, 1.22758, 1.32230, 1.43449, 1.60319, 1.72977, 1.77531, 1.68176, 1.59448, 1.52134, 1.30714, 1.11662, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.63221, 0.71705, 0.83546, 0.90179, 0.84112, 0.66889, 0.48021, 0.39907, 0.19748, -0.06680, -0.36167, -0.58515, -0.62627, -0.70337, -0.83810, -0.99976, -1.10781, -1.32474, -1.44069, -1.39396, -1.51022, -1.75060, -1.87634, -1.85737, -1.78178, -1.64976, -1.44626, -1.23415, -1.14733, -1.01689, -1.03055, -0.94682, -0.77204, -0.73867, -0.84611, -0.98784, -1.05636, -1.04542, -1.06279, -1.02893, -1.04151, -0.99711, -0.92526, -1.00057, -1.08566, -1.16753, -1.30684, -1.48947, -1.54270, -1.59730, -1.56503, -1.43389, -1.38956, +-0.05717, 0.01848, -0.05432, -0.13525, -0.32433, -0.59620, -0.65013, -0.50184, -0.27636, -0.22179, -0.22093, -0.29669, -0.36381, -0.41353, -0.45997, -0.38708, -0.44436, -0.50238, -0.60582, -0.57364, -0.27528, -0.08016, 0.13225, 0.33747, 0.46474, 0.48374, 0.53347, 0.54657, 0.44523, 0.42274, 0.45289, 0.57578, 0.62717, 0.58994, 0.51491, 0.48010, 0.47312, 0.36649, 0.36034, 0.35942, 0.31163, 0.18224, 0.07885, 0.12226, 0.23703, 0.47352, 0.55737, 0.53819, 0.41173, 0.41408, 0.40197, 0.30033, 0.28024, 0.07423, -0.09674, -0.11516, -0.13850, -0.26963, -0.37824, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.40764, -0.26998, -0.09871, -0.21845, -0.36672, -0.43001, -0.35780, -0.20862, -0.06566, 0.16742, 0.18652, 0.12278, -0.01441, -0.01594, 0.03292, 0.16900, 0.30090, 0.30145, 0.34847, 0.23190, 0.00372, -0.19666, -0.41659, -0.62611, -0.66149, -0.53307, -0.55107, -0.54071, -0.63054, -0.70137, -0.64366, -0.51502, -0.30217, -0.16899, -0.07459, -0.22590, -0.36309, -0.33461, -0.21807, -0.01487, -0.00893, -0.03800, -0.16951, -0.15632, -0.13497, -0.08054, -0.12240, -0.21841, -0.31120, -0.50436, -0.59443, -0.80413, -1.09008, -1.21397, -1.18442, -1.11365, -1.07232, -0.95151, -1.02517, -1.03239, -0.98163, -0.85376, -0.72992, -0.81400, -0.95452, -1.05560, -0.92489, -0.83009, -0.69322, -0.39477, -0.19536, -0.05766, -0.10652, -0.05179, -0.03838, 0.02249, 0.06344, 0.14535, 0.19733, 0.32381, 0.53048, 0.55558, 0.64592, 0.76247, 0.87495, 1.06519, 1.14942, 1.13349, 1.01126, 1.00620, 0.95156, 1.03302, 1.19382, 1.25975, 1.34477, 1.30422, 1.25936, 1.21380, 1.27976, 1.22904, 0.96395, 0.67889, 0.42849, 0.38483, 0.31225, 0.28909, 0.09666, -0.16573, -0.43165, -0.60726, -0.81656, -1.05218, -1.19849, -1.36107, -1.26795, -1.14185, -1.22825, -1.32666, -1.52164, -1.72396, -1.94913, -1.98539, -2.12449, -2.35849, -2.59485, -2.81378, -2.82904, -2.82379, -2.75758, -2.64149, -2.54866, -2.57538, -2.68512, -2.57027, -2.33296, -2.08237, -1.99059, -1.92905, -1.99005, -2.06316, -2.17064, -2.24943, -2.30199, -2.34771, -2.25252, -2.33925, -2.47909, -2.63418, -2.95380, -3.13639, -3.15323, -3.01032, -2.88643, -2.78580, -2.83535, -2.99643, -3.03938, -2.99008, -2.74523, -2.48605, -2.44003, -2.48198, -2.43806, -2.25571, -2.16002, -1.97994, -1.78466, -1.56685, -1.39583, -1.17304, -1.03878, -0.98518, -0.95427, -0.87101, -0.68045, -0.61978, -0.60321, -0.81406, -1.06610, -1.14164, -1.23134, -1.12539, -0.94489, -0.85017, -0.89122, -0.87953, -0.79354, -0.78701, -0.69013, -0.69443, -0.77332, -0.91750, -1.08037, -1.12843, -1.03537, -0.96013, -1.01900, -1.10280, -1.18435, -1.30142, -1.52350, -1.76438, -1.96811, -2.09801, -2.07820, -2.04317, -1.97909, -1.97700, -1.96664, -2.05942, -2.16634, -2.06050, -2.10713, -2.27097, -2.44470, -2.65905, -2.89841, -2.98095, -2.89234, -2.82449, -2.75661, -2.71712, -2.55953, -2.23034, -1.97139, -1.76446, -1.61342, -1.49335, -1.47008, -1.34401, -1.10457, -0.87534, -0.70227, -0.57020, -0.36995, -0.33707, -0.40156, -0.63244, -0.86594, -1.07898, -1.06558, -0.95775, -0.90007, -0.75114, -0.74766, -0.78363, -0.63684, -0.50318, -0.37966, -0.26097, -0.20503, -0.30567, -0.32956, -0.25989, -0.10097, 0.10827, 0.24512, 0.35703, 0.49401, 0.73753, 0.84049, 0.95527, 1.12573, 1.33436, 1.57033, 1.63648, 1.64676, 1.52369, 1.41689, 1.28975, 1.25495, 1.24611, 1.24590, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.76264, 0.82706, 0.96687, 1.02868, 0.95449, 0.82055, 0.61752, 0.40600, 0.15757, -0.04935, -0.36379, -0.55569, -0.54217, -0.57985, -0.67870, -0.98472, -1.21922, -1.41038, -1.43585, -1.42633, -1.43832, -1.58922, -1.73618, -1.77619, -1.80504, -1.63352, -1.36116, -1.17017, -1.01381, -0.93813, -0.94542, -0.90189, -0.78487, -0.83214, -0.88983, -0.96476, -1.01990, -0.96638, -0.96375, -0.96297, -0.93895, -0.76353, -0.69064, -0.78918, -0.90322, -1.07942, -1.22331, -1.44004, -1.47859, -1.45732, -1.36496, -1.37813, -1.39591, +-0.10156, -0.08482, -0.10105, -0.10176, -0.17346, -0.36062, -0.37907, -0.21965, -0.06281, -0.07122, -0.03811, -0.03902, -0.06228, -0.17439, -0.32717, -0.27102, -0.31613, -0.41563, -0.46124, -0.34993, -0.18324, -0.14935, 0.02943, 0.25380, 0.42443, 0.45257, 0.46217, 0.52631, 0.58062, 0.68484, 0.67687, 0.69545, 0.68561, 0.55436, 0.43034, 0.41755, 0.51512, 0.52799, 0.46932, 0.37184, 0.20866, -0.03336, -0.10715, -0.01237, 0.14293, 0.40710, 0.46873, 0.45774, 0.32524, 0.30475, 0.35741, 0.35504, 0.32628, 0.05703, -0.12332, -0.17795, -0.16790, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.54502, -0.53244, -0.39959, -0.20036, -0.23515, -0.38475, -0.42888, -0.43255, -0.46922, -0.39559, -0.11867, -0.01265, -0.01463, -0.12566, -0.07683, -0.07097, -0.05571, 0.09362, 0.23212, 0.27083, 0.03015, -0.20484, -0.32788, -0.44249, -0.53479, -0.63016, -0.63998, -0.68171, -0.66272, -0.79128, -0.83957, -0.70646, -0.56802, -0.38295, -0.29187, -0.19784, -0.24716, -0.35614, -0.33285, -0.26201, -0.17843, -0.17671, -0.14687, -0.23638, -0.15124, -0.14575, -0.09939, -0.13724, -0.31264, -0.44287, -0.59665, -0.69161, -0.93274, -1.15491, -1.26384, -1.27941, -1.15220, -1.08518, -0.98223, -1.07552, -1.04049, -0.98440, -0.87676, -0.73242, -0.83836, -0.92072, -0.91876, -0.75407, -0.60405, -0.51074, -0.21312, 0.00355, 0.02605, 0.00197, 0.14394, 0.13596, 0.19372, 0.21954, 0.33579, 0.37689, 0.37861, 0.53816, 0.70401, 0.87610, 0.93078, 0.99895, 1.13786, 1.22823, 1.27807, 1.19487, 1.25812, 1.31144, 1.52178, 1.63617, 1.59504, 1.61705, 1.47743, 1.40483, 1.33891, 1.37883, 1.41070, 1.15939, 0.86217, 0.59126, 0.43939, 0.33398, 0.36079, 0.20364, -0.01114, -0.31826, -0.52946, -0.68691, -0.86864, -0.95708, -1.03207, -0.96804, -0.96995, -1.06107, -1.15116, -1.41511, -1.61547, -1.85848, -1.95477, -2.12673, -2.31375, -2.52957, -2.76341, -2.84102, -2.99516, -3.03469, -2.91022, -2.77202, -2.68766, -2.68690, -2.52202, -2.33124, -2.23277, -2.16955, -2.01156, -2.04834, -2.10327, -2.20548, -2.19659, -2.12899, -2.14777, -2.11149, -2.18313, -2.29908, -2.60967, -2.98448, -3.11363, -3.09480, -2.89524, -2.82999, -2.82495, -2.93234, -3.04090, -3.03586, -3.01408, -2.78362, -2.57228, -2.55195, -2.57568, -2.50455, -2.20810, -2.02460, -1.80508, -1.57783, -1.44171, -1.34207, -1.09362, -0.87440, -0.67420, -0.56961, -0.50616, -0.34679, -0.31407, -0.30862, -0.46181, -0.70965, -0.90901, -1.07517, -0.98565, -0.84820, -0.74265, -0.73581, -0.71440, -0.69426, -0.72761, -0.64617, -0.64264, -0.67407, -0.81568, -0.93601, -0.94519, -0.91037, -0.83742, -0.81992, -0.87455, -1.00838, -1.27447, -1.59062, -1.72681, -1.81132, -1.86932, -1.90181, -1.97107, -1.94741, -2.05098, -2.11453, -2.11986, -2.10516, -2.05798, -2.24965, -2.44203, -2.63453, -2.79509, -2.94189, -3.03280, -2.98799, -2.90873, -2.81569, -2.82806, -2.71954, -2.43548, -2.24768, -2.03941, -1.87767, -1.73659, -1.66035, -1.55855, -1.29395, -1.05771, -0.95012, -0.83515, -0.64087, -0.55684, -0.53349, -0.74250, -0.96481, -1.17024, -1.18132, -1.02829, -0.88884, -0.78369, -0.84407, -0.85900, -0.78350, -0.73053, -0.60069, -0.46198, -0.40559, -0.48332, -0.40700, -0.37199, -0.34309, -0.23845, -0.16233, -0.02418, 0.09384, 0.33140, 0.58368, 0.83428, 1.10609, 1.31539, 1.39390, 1.42997, 1.49365, 1.37955, 1.37550, 1.34845, 1.43796, 1.46825, 1.35669, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.88228, 1.10379, 1.17599, 1.06815, 0.88387, 0.56756, 0.31995, 0.12270, 0.00649, -0.15626, -0.35736, -0.39062, -0.44384, -0.63220, -0.94679, -1.15508, -1.31792, -1.25677, -1.23062, -1.21964, -1.34962, -1.50521, -1.51567, -1.52692, -1.46888, -1.38544, -1.19655, -1.03475, -0.96438, -0.84712, -0.80748, -0.80347, -0.89885, -0.85186, -0.87654, -0.98642, -0.98249, -1.01117, -0.91847, -0.80430, -0.60803, -0.49976, -0.61924, -0.76409, -1.00958, -1.24007, -1.39681, -1.30715, -1.27379, -1.20274, -1.27708, -1.33310, +-0.21567, -0.17883, -0.07722, -0.03440, -0.05581, -0.10378, -0.04584, 0.02656, 0.12608, 0.12697, 0.13423, 0.22409, 0.23674, 0.03877, -0.19121, -0.21543, -0.21568, -0.38103, -0.42068, -0.24689, -0.19518, -0.12840, 0.09891, 0.22920, 0.32550, 0.38034, 0.36114, 0.44784, 0.64954, 0.75121, 0.72330, 0.70278, 0.59607, 0.50376, 0.49137, 0.49215, 0.52453, 0.53853, 0.43256, 0.18852, -0.01385, -0.14287, -0.14232, 0.00446, 0.14380, 0.27232, 0.26679, 0.23998, 0.17095, 0.11345, 0.14583, 0.23831, 0.18662, 0.05105, -0.01298, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.44909, -0.53481, -0.43969, -0.35513, -0.30104, -0.36543, -0.46135, -0.51594, -0.53523, -0.56480, -0.57130, -0.33724, -0.22023, -0.28177, -0.36560, -0.28455, -0.23230, -0.25093, -0.16650, 0.07404, 0.04768, -0.14500, -0.25433, -0.37925, -0.50580, -0.54366, -0.69345, -0.86698, -0.88254, -0.89289, -1.00093, -0.91001, -0.79029, -0.64386, -0.45189, -0.39762, -0.37622, -0.35399, -0.30637, -0.31328, -0.33064, -0.27504, -0.32864, -0.28860, -0.34478, -0.34548, -0.36706, -0.33790, -0.31033, -0.43975, -0.66477, -0.75795, -0.90603, -1.06360, -1.10296, -1.23990, -1.38752, -1.27268, -1.16366, -1.08309, -1.04380, -0.96700, -0.94770, -0.78266, -0.71113, -0.80863, -0.75209, -0.60861, -0.45686, -0.36472, -0.26754, -0.05937, 0.06280, 0.10994, 0.11468, 0.28984, 0.31475, 0.28068, 0.28034, 0.39120, 0.44220, 0.45668, 0.50027, 0.77559, 0.94297, 1.00583, 1.15359, 1.23568, 1.26300, 1.36590, 1.43608, 1.54035, 1.70144, 1.91614, 1.87550, 1.84317, 1.81718, 1.70773, 1.76993, 1.74183, 1.65679, 1.54749, 1.30693, 0.99529, 0.62084, 0.45107, 0.33000, 0.33901, 0.26183, 0.02140, -0.32486, -0.56402, -0.67816, -0.71537, -0.84307, -0.86410, -0.89125, -0.96823, -0.92613, -0.94317, -1.24167, -1.47135, -1.70290, -1.92804, -2.15007, -2.32666, -2.59358, -2.70507, -2.78181, -3.03515, -3.08205, -2.95599, -2.89798, -2.88141, -2.77559, -2.54383, -2.43673, -2.35144, -2.25901, -2.09535, -2.08212, -2.18717, -2.31861, -2.25744, -2.11792, -2.02292, -2.11572, -2.19335, -2.30706, -2.66332, -2.85869, -2.88054, -2.94100, -2.85322, -2.85469, -2.95517, -3.05778, -3.01871, -2.99551, -2.91789, -2.71213, -2.62323, -2.56688, -2.50584, -2.49622, -2.29609, -2.05828, -1.76846, -1.55352, -1.38179, -1.24060, -1.01266, -0.71170, -0.46309, -0.36776, -0.33933, -0.24336, -0.13814, -0.17145, -0.23758, -0.37554, -0.62915, -0.70493, -0.59555, -0.62401, -0.62228, -0.55639, -0.50298, -0.49800, -0.51820, -0.56149, -0.57558, -0.56903, -0.75076, -0.75775, -0.65078, -0.69210, -0.75644, -0.73185, -0.75008, -0.99582, -1.33483, -1.62160, -1.73282, -1.73688, -1.79675, -1.97471, -2.13365, -2.15597, -2.19796, -2.26859, -2.25646, -2.17946, -2.28209, -2.47530, -2.58052, -2.79770, -2.88990, -2.88275, -2.97510, -3.02867, -2.96722, -2.97251, -3.01433, -2.90738, -2.74203, -2.53955, -2.23842, -2.06239, -1.99839, -1.93122, -1.80032, -1.59230, -1.36463, -1.20446, -1.15436, -0.99868, -0.89225, -0.88656, -0.99332, -1.11338, -1.20169, -1.21349, -1.14048, -0.96952, -0.96135, -0.92623, -0.77837, -0.79108, -0.87723, -0.78424, -0.68835, -0.70233, -0.71051, -0.62615, -0.60169, -0.56062, -0.57939, -0.50320, -0.28370, -0.18691, -0.05428, 0.22700, 0.62473, 0.91998, 1.09672, 1.16977, 1.17059, 1.27235, 1.25419, 1.29192, 1.35517, 1.49502, 1.54339, 1.37546, 1.12262, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 1.06225, 1.12773, 1.13390, 0.89580, 0.55045, 0.36144, 0.21060, 0.06075, -0.10238, -0.27502, -0.39201, -0.49973, -0.61368, -0.84418, -0.96743, -1.05423, -1.05040, -1.06393, -1.08790, -1.17462, -1.22579, -1.24766, -1.18616, -1.26194, -1.27747, -1.03883, -0.93620, -0.95549, -0.79029, -0.70373, -0.81419, -0.89571, -0.82908, -0.88391, -0.92894, -0.99348, -1.02958, -0.80626, -0.61274, -0.51857, -0.54419, -0.64354, -0.80202, -1.07930, -1.19815, -1.28191, -1.17723, -1.16389, -1.23942, -1.36636, -1.39564, +-0.27752, -0.15879, -0.11458, -0.09553, -0.02513, 0.02401, 0.15768, 0.25125, 0.37340, 0.39139, 0.28534, 0.30595, 0.37261, 0.20361, -0.01760, -0.05899, -0.08049, -0.24523, -0.35244, -0.26349, -0.16674, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.24536, 0.41187, 0.59348, 0.66911, 0.63513, 0.57726, 0.53470, 0.54141, 0.48214, 0.37798, 0.36186, 0.32426, 0.20865, -0.00574, -0.13591, -0.13115, -0.13950, -0.08688, 0.05037, 0.16797, 0.15227, 0.15054, 0.08228, 0.01281, 0.00463, 0.05288, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.66399, -0.59835, -0.51636, -0.45507, -0.50761, -0.52138, -0.62976, -0.71087, -0.70662, -0.67133, -0.63235, -0.70980, -0.62424, -0.50677, -0.51306, -0.56958, -0.45842, -0.39673, -0.39280, -0.32088, -0.14447, -0.11151, -0.16013, -0.29508, -0.51491, -0.67634, -0.78161, -0.91888, -0.99953, -1.04839, -1.13139, -1.21948, -1.16523, -1.01256, -0.75717, -0.59676, -0.64890, -0.61219, -0.52602, -0.39651, -0.35318, -0.37418, -0.28816, -0.40737, -0.50272, -0.57333, -0.56318, -0.59387, -0.53964, -0.48862, -0.57716, -0.80777, -0.99314, -1.14534, -1.17357, -1.18091, -1.36182, -1.50580, -1.44207, -1.31302, -1.08260, -0.96570, -0.92035, -0.90363, -0.81039, -0.74428, -0.69468, -0.58260, -0.48371, -0.29444, -0.20136, -0.10209, 0.11575, 0.21393, 0.31878, 0.29116, 0.31865, 0.33592, 0.36647, 0.39141, 0.53895, 0.59667, 0.60799, 0.59685, 0.73048, 0.87243, 1.06534, 1.24339, 1.26213, 1.29929, 1.40179, 1.56535, 1.85555, 2.07328, 2.19230, 2.10353, 2.00169, 1.97408, 2.03294, 2.15051, 1.98715, 1.82824, 1.65499, 1.40479, 1.14183, 0.74399, 0.58663, 0.42098, 0.27384, 0.19010, 0.04064, -0.27063, -0.47780, -0.60013, -0.62763, -0.73494, -0.82831, -0.88360, -0.85396, -0.78631, -0.86295, -1.14442, -1.44284, -1.72450, -1.89926, -2.13302, -2.40099, -2.68487, -2.81086, -2.87721, -3.01828, -3.03771, -3.05436, -3.07012, -3.07399, -2.95869, -2.67100, -2.53821, -2.36857, -2.24298, -2.18816, -2.19970, -2.24884, -2.37617, -2.29496, -2.12507, -1.99341, -2.05487, -2.18901, -2.33291, -2.55245, -2.65367, -2.74420, -2.87539, -2.92058, -3.00475, -3.02971, -3.04121, -2.98087, -2.93497, -2.88526, -2.71765, -2.55145, -2.42322, -2.43470, -2.51365, -2.37210, -2.14502, -1.79954, -1.52064, -1.24653, -1.05298, -0.93896, -0.72487, -0.44304, -0.30627, -0.24148, -0.12582, -0.00794, -0.02104, -0.08996, -0.19332, -0.31383, -0.30634, -0.28841, -0.41835, -0.50986, -0.49044, -0.34194, -0.24023, -0.31787, -0.43395, -0.50444, -0.53459, -0.61393, -0.51335, -0.46663, -0.60267, -0.70205, -0.71234, -0.72749, -0.97508, -1.30403, -1.59474, -1.82822, -1.92178, -1.95106, -2.10176, -2.25928, -2.29217, -2.33685, -2.39882, -2.45035, -2.47056, -2.55631, -2.66968, -2.78365, -2.97704, -2.98953, -2.94379, -2.96479, -2.94741, -2.96441, -3.06334, -3.15799, -3.16229, -3.00555, -2.72463, -2.46203, -2.34682, -2.26625, -2.21176, -2.09027, -1.90958, -1.69260, -1.48720, -1.50563, -1.45249, -1.31120, -1.23141, -1.23005, -1.21382, -1.23771, -1.22608, -1.21371, -1.15584, -1.11621, -0.96311, -0.82668, -0.91585, -1.06439, -1.06413, -0.96730, -0.88122, -0.90534, -0.89260, -0.88640, -0.90840, -0.90039, -0.71693, -0.52610, -0.53989, -0.43477, -0.19258, 0.22068, 0.58116, 0.80979, 0.98706, 0.97424, 0.99161, 1.05965, 1.22765, 1.36442, 1.56282, 1.61119, 1.45093, 1.19285, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.70669, 0.49128, 0.18485, -0.00409, -0.18375, -0.34134, -0.41364, -0.50788, -0.53074, -0.71505, -0.88736, -0.93956, -0.87740, -0.89646, -0.90356, -0.97123, -0.97332, -0.95231, -0.95740, -1.04423, -0.97638, -0.79008, -0.81082, -0.87787, -0.79576, -0.71382, -0.71242, -0.77694, -0.77972, -0.82593, -0.90764, -0.98042, -0.93191, -0.71814, -0.65721, -0.61779, -0.68723, -0.79609, -0.90480, -1.13155, -1.12572, -1.19012, -1.22609, -1.26177, -1.30645, -1.41508, -1.36104, +-0.21776, -0.13799, -0.10940, -0.11270, -0.01749, 0.11499, 0.26030, 0.41086, 0.55941, 0.52477, 0.40341, 0.40873, 0.43626, 0.29467, 0.05162, -0.05164, -0.11372, -0.17488, -0.13153, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.40432, 0.51303, 0.57091, 0.56376, 0.58729, 0.55035, 0.44187, 0.26000, 0.18204, 0.09052, -0.04483, -0.16514, -0.16655, -0.11455, -0.11882, -0.10816, -0.05305, 0.06437, 0.08202, 0.05056, -0.03002, -0.05993, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.85772, -0.91751, -0.81211, -0.72682, -0.63289, -0.65568, -0.68252, -0.81221, -0.93355, -0.93341, -0.84922, -0.85319, -0.94438, -0.85995, -0.74540, -0.69659, -0.70072, -0.66785, -0.65873, -0.62269, -0.43544, -0.28452, -0.26137, -0.23562, -0.37067, -0.65978, -0.83498, -1.00265, -1.12120, -1.14165, -1.20811, -1.29664, -1.33410, -1.39077, -1.22759, -1.04930, -0.85454, -0.80796, -0.68711, -0.53360, -0.43508, -0.44953, -0.46051, -0.42493, -0.53558, -0.61265, -0.69652, -0.72728, -0.79481, -0.87866, -0.91903, -1.00247, -1.05762, -1.19530, -1.40254, -1.43161, -1.41862, -1.53286, -1.51949, -1.43781, -1.32977, -1.14504, -1.04370, -0.98384, -0.84214, -0.78563, -0.68123, -0.65677, -0.51785, -0.35020, -0.11410, -0.00073, 0.08496, 0.25763, 0.40419, 0.48306, 0.43289, 0.44585, 0.43713, 0.47014, 0.50658, 0.56585, 0.63113, 0.66168, 0.77152, 0.85712, 0.85360, 0.99689, 1.22130, 1.30194, 1.45469, 1.60938, 1.77667, 2.06166, 2.26571, 2.30867, 2.34843, 2.25463, 2.28781, 2.33207, 2.37915, 2.18117, 1.99315, 1.83621, 1.63578, 1.37012, 1.03016, 0.78725, 0.49482, 0.27037, 0.12851, -0.00029, -0.21313, -0.45160, -0.61652, -0.71184, -0.69520, -0.66238, -0.74906, -0.78339, -0.77278, -0.95816, -1.19621, -1.46751, -1.76750, -1.95629, -2.21938, -2.56285, -2.74779, -2.87635, -2.91958, -3.06708, -3.12029, -3.12223, -3.10881, -3.08265, -2.95365, -2.72783, -2.56844, -2.40569, -2.35397, -2.29457, -2.24710, -2.24551, -2.31417, -2.33850, -2.24813, -2.17807, -2.05841, -1.99056, -2.16045, -2.40499, -2.54304, -2.73734, -2.88579, -2.97003, -3.06198, -3.04378, -2.99251, -2.95250, -2.84582, -2.81199, -2.66977, -2.46686, -2.31312, -2.26136, -2.30652, -2.21270, -2.05024, -1.81294, -1.54306, -1.23366, -1.05143, -0.92307, -0.72381, -0.48615, -0.29964, -0.21082, -0.11093, -0.07982, -0.03544, 0.01247, -0.08684, -0.17482, -0.10374, -0.09897, -0.20359, -0.28179, -0.30183, -0.16637, -0.07645, -0.23383, -0.31504, -0.35486, -0.38490, -0.40068, -0.31929, -0.27217, -0.41289, -0.54291, -0.64136, -0.75340, -0.98283, -1.26598, -1.63294, -1.95185, -2.09167, -2.16100, -2.21595, -2.32297, -2.42613, -2.56651, -2.65039, -2.62844, -2.74555, -2.92042, -2.97600, -3.04215, -3.10613, -2.99741, -2.96548, -3.00241, -3.01044, -3.06850, -3.11793, -3.15811, -3.23831, -3.13252, -2.96891, -2.74283, -2.61122, -2.47340, -2.38988, -2.31854, -2.20409, -2.01269, -1.86368, -1.82818, -1.72181, -1.62207, -1.53669, -1.52506, -1.52211, -1.53329, -1.45421, -1.28568, -1.26272, -1.29074, -1.14106, -1.04412, -1.14638, -1.26765, -1.31092, -1.21751, -1.10766, -1.14352, -1.11555, -1.04629, -1.13427, -1.11227, -1.03472, -0.84473, -0.79009, -0.63604, -0.42785, -0.12497, 0.17762, 0.46688, 0.71412, 0.80062, 0.89517, 0.98506, 1.16580, 1.34291, 1.46004, 1.47514, 1.38735, 1.34619, 1.26264, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.02977, -0.15222, -0.29168, -0.39088, -0.48875, -0.58104, -0.78579, -0.89114, -0.91212, -0.82331, -0.78755, -0.86917, -0.95291, -0.94038, -0.73983, -0.67580, -0.81195, -0.76088, -0.59372, -0.64148, -0.65761, -0.60394, -0.56908, -0.59348, -0.71119, -0.80530, -0.73144, -0.79382, -0.78875, -0.82091, -0.71500, -0.70614, -0.69487, -0.72195, -0.81239, -0.95165, -1.13396, -1.17677, -1.26613, -1.31006, -1.35418, -1.35486, -1.35847, -1.30577, +0.01717, 0.01509, 0.02036, -0.03942, 0.00504, 0.18464, 0.37068, 0.56216, 0.68629, 0.60821, 0.50044, 0.48561, 0.37767, 0.15137, -0.00871, -0.04333, -0.05295, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.59229, 0.64440, 0.56612, 0.42745, 0.19444, 0.05447, -0.07769, -0.17440, -0.17335, -0.08900, -0.03161, -0.08757, -0.12892, -0.20958, -0.19598, -0.05492, 0.04852, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.79911, -0.87719, -0.92378, -1.02720, -0.99309, -0.93868, -0.79274, -0.71862, -0.73938, -0.87277, -1.01950, -1.05826, -1.03313, -1.10988, -1.20332, -1.09327, -1.00216, -1.01303, -0.93066, -0.80854, -0.81128, -0.75470, -0.64378, -0.58543, -0.50337, -0.39548, -0.40699, -0.63317, -0.86419, -1.08235, -1.24741, -1.33162, -1.34191, -1.33492, -1.39281, -1.45708, -1.34424, -1.27962, -1.04127, -0.82619, -0.61891, -0.44551, -0.45162, -0.54362, -0.61800, -0.64398, -0.70846, -0.73092, -0.80015, -0.94190, -1.05005, -1.11784, -1.24499, -1.31377, -1.34687, -1.52068, -1.68177, -1.68940, -1.61046, -1.52290, -1.37496, -1.24452, -1.18459, -1.23292, -1.19023, -1.02942, -0.84098, -0.69300, -0.57704, -0.61740, -0.48140, -0.24021, 0.00252, 0.14125, 0.22212, 0.38287, 0.53870, 0.57505, 0.53423, 0.57060, 0.52997, 0.44860, 0.45946, 0.63336, 0.78368, 0.92887, 1.09603, 1.02646, 0.91717, 0.97232, 1.21566, 1.48542, 1.72684, 1.95886, 2.09623, 2.19695, 2.34621, 2.42858, 2.54079, 2.58672, 2.68012, 2.61564, 2.50853, 2.31350, 2.11448, 2.02198, 1.91396, 1.70231, 1.43545, 1.12299, 0.71969, 0.42536, 0.19786, -0.01810, -0.17965, -0.25928, -0.38750, -0.48766, -0.48894, -0.51744, -0.60984, -0.72518, -0.79832, -1.00554, -1.25851, -1.47109, -1.74907, -2.04761, -2.35966, -2.64375, -2.80647, -2.89862, -2.92760, -3.12140, -3.21222, -3.13866, -3.05870, -2.97574, -2.82549, -2.64445, -2.52396, -2.44191, -2.46663, -2.35790, -2.21688, -2.20845, -2.23119, -2.19723, -2.14199, -2.11612, -1.95940, -1.88796, -2.04058, -2.27230, -2.46863, -2.64109, -2.79980, -2.89328, -2.92791, -2.94098, -2.89288, -2.82493, -2.78421, -2.75825, -2.60847, -2.40371, -2.21901, -2.05387, -1.97517, -1.86672, -1.77245, -1.64980, -1.46604, -1.19951, -1.02367, -0.83578, -0.60576, -0.47274, -0.34256, -0.12307, 0.04040, 0.02522, 0.03449, -0.04988, -0.17324, -0.18440, -0.04186, 0.10598, 0.08454, 0.02895, -0.01476, -0.02858, -0.07741, -0.21891, -0.28497, -0.29281, -0.24342, -0.24522, -0.19757, -0.13631, -0.25181, -0.40692, -0.58299, -0.74012, -0.94133, -1.18451, -1.54961, -1.90546, -2.08990, -2.29240, -2.38722, -2.35435, -2.37625, -2.53417, -2.69405, -2.80724, -3.04773, -3.26131, -3.25807, -3.17106, -3.08082, -2.96787, -3.00548, -3.15342, -3.29905, -3.28734, -3.23703, -3.22796, -3.20802, -3.14742, -3.11245, -2.92887, -2.75358, -2.54115, -2.39631, -2.32124, -2.24650, -2.13476, -2.04718, -1.92958, -1.75670, -1.76402, -1.82939, -1.84811, -1.77104, -1.74208, -1.61692, -1.46431, -1.51572, -1.55292, -1.43239, -1.32733, -1.36473, -1.47121, -1.50661, -1.44688, -1.42370, -1.39835, -1.28728, -1.21984, -1.25775, -1.26693, -1.30646, -1.08926, -0.89009, -0.63388, -0.39508, -0.19653, 0.01100, 0.24006, 0.51178, 0.72646, 0.94453, 1.04025, 1.08939, 1.28717, 1.47376, 1.49414, 1.51437, 1.54413, 1.43997, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.10524, -0.01778, -0.16001, -0.36234, -0.58606, -0.86020, -0.91145, -0.91887, -0.92180, -0.84391, -0.80917, -0.86516, -0.81565, -0.61903, -0.61884, -0.72708, -0.67211, -0.47048, -0.39489, -0.38275, -0.32787, -0.36977, -0.57741, -0.76715, -0.85009, -0.73249, -0.65008, -0.52575, -0.60856, -0.61669, -0.63521, -0.68754, -0.67225, -0.72268, -0.84554, -1.02804, -1.16900, -1.27687, -1.29827, -1.33149, -1.36113, -1.28297, -1.07908, +0.24512, 0.13796, 0.05150, -0.05644, -0.01556, 0.18930, 0.39239, 0.57662, 0.65240, 0.63829, 0.50660, 0.40866, 0.30343, 0.09700, -0.03604, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.44159, 0.26256, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.32987, -0.32495, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.50977, -0.66377, -0.73462, -0.85902, -1.02687, -1.11568, -1.03099, -0.94565, -0.87063, -0.77539, -0.83654, -0.95278, -1.13796, -1.19141, -1.25212, -1.28677, -1.39207, -1.40990, -1.33094, -1.30244, -1.18731, -1.08526, -1.08228, -0.99296, -0.98181, -0.80146, -0.61821, -0.51062, -0.51911, -0.73659, -0.93821, -1.16402, -1.41602, -1.46981, -1.41337, -1.35085, -1.47305, -1.49568, -1.36253, -1.31134, -1.19818, -0.94769, -0.75028, -0.54969, -0.64570, -0.75028, -0.91119, -0.91584, -0.95713, -1.07523, -1.11576, -1.18557, -1.28637, -1.39867, -1.56472, -1.56809, -1.68820, -1.74596, -1.77509, -1.74987, -1.68835, -1.57727, -1.35033, -1.15376, -1.12336, -1.16984, -1.11011, -0.90978, -0.83283, -0.67952, -0.55892, -0.55545, -0.52775, -0.27840, -0.07024, 0.12965, 0.17433, 0.33638, 0.43228, 0.51522, 0.54355, 0.51009, 0.46812, 0.44445, 0.49376, 0.71621, 0.89038, 1.16680, 1.30452, 1.30782, 1.25786, 1.25882, 1.37116, 1.58008, 1.85496, 2.18090, 2.31030, 2.41670, 2.56754, 2.66515, 2.66688, 2.73194, 2.86454, 2.83714, 2.56466, 2.35643, 2.12960, 2.10504, 2.01212, 1.86573, 1.62508, 1.36869, 1.00568, 0.60090, 0.33264, 0.19177, 0.08031, 0.03145, -0.13772, -0.18748, -0.32093, -0.36901, -0.42136, -0.57815, -0.76454, -1.07404, -1.31844, -1.43862, -1.73019, -2.02789, -2.33131, -2.56128, -2.82441, -2.95726, -2.95557, -3.05089, -3.23040, -3.18166, -3.11139, -2.96727, -2.82794, -2.65652, -2.59996, -2.54736, -2.50198, -2.40664, -2.25921, -2.14938, -2.07471, -2.00373, -2.02226, -1.98687, -1.96809, -1.92393, -1.95287, -2.09241, -2.31413, -2.54536, -2.71183, -2.75645, -2.79853, -2.78546, -2.68356, -2.58029, -2.68104, -2.74583, -2.59659, -2.32744, -2.20009, -2.04348, -1.89659, -1.71160, -1.63132, -1.54423, -1.40188, -1.15585, -0.90414, -0.74007, -0.55286, -0.38897, -0.24821, -0.02892, 0.04863, 0.05583, 0.01631, -0.10607, -0.06941, 0.03804, 0.17441, 0.28620, 0.26277, 0.26013, 0.17252, 0.07783, 0.01547, -0.09827, -0.27223, -0.40470, -0.32747, -0.24664, -0.23640, -0.24297, -0.36048, -0.51504, -0.68611, -0.84017, -1.02902, -1.25822, -1.47388, -1.81912, -2.09135, -2.32775, -2.45006, -2.40642, -2.46262, -2.55488, -2.72062, -2.93103, -3.09369, -3.28406, -3.33968, -3.30656, -3.22689, -3.10895, -3.20922, -3.41327, -3.54907, -3.49580, -3.47925, -3.55558, -3.43258, -3.26617, -3.23466, -3.12133, -2.88645, -2.61631, -2.40764, -2.34359, -2.27547, -2.24010, -2.09352, -1.96078, -1.87967, -1.89943, -1.96391, -2.00848, -1.97905, -1.94112, -1.81345, -1.77420, -1.73504, -1.70270, -1.62623, -1.59814, -1.65388, -1.70474, -1.73287, -1.72475, -1.65907, -1.57156, -1.45653, -1.49855, -1.49197, -1.44306, -1.44157, -1.27698, -1.01633, -0.72724, -0.40721, -0.26627, -0.09107, 0.02081, 0.33126, 0.61716, 0.81807, 1.00823, 1.14773, 1.37048, 1.51858, 1.51097, 1.59652, 1.56573, 1.58233, 1.47354, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.05398, -0.36835, -0.57318, -0.80986, -0.92281, -0.92545, -0.89855, -0.82604, -0.80720, -0.86549, -0.72732, -0.62143, -0.51942, -0.50430, -0.45059, -0.33192, -0.31384, -0.30030, -0.23130, -0.36133, -0.59127, -0.78890, -0.84427, -0.82020, -0.70256, -0.47781, -0.43695, -0.56042, -0.61263, -0.77378, -0.75757, -0.83509, -0.89818, -1.05581, -1.11778, -1.13847, -1.22620, -1.27386, -1.23066, -1.09981, -0.88267, +0.21496, 0.04036, -0.04198, -0.13914, -0.12497, 0.05813, 0.29419, 0.49865, 0.54360, 0.51148, 0.44463, 0.41253, 0.33619, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.32701, -0.46639, -0.59913, -0.62843, -0.71568, -0.90986, -1.06506, -1.12958, -1.05350, -1.00094, -0.91529, -0.79708, -0.89628, -1.06710, -1.23520, -1.24966, -1.33026, -1.40478, -1.51778, -1.53761, -1.51888, -1.50625, -1.41513, -1.34346, -1.34101, -1.31227, -1.28583, -1.08055, -0.90022, -0.79943, -0.76854, -0.85510, -1.05060, -1.34685, -1.58989, -1.54707, -1.47933, -1.44605, -1.47853, -1.43273, -1.34233, -1.41390, -1.39243, -1.16986, -1.02013, -0.87661, -0.94881, -0.99886, -1.17671, -1.24523, -1.30730, -1.36141, -1.38572, -1.41700, -1.50414, -1.65495, -1.81033, -1.87427, -2.00313, -2.02873, -2.00890, -1.92394, -1.81322, -1.58191, -1.34106, -1.21217, -1.13761, -1.04158, -0.95535, -0.84508, -0.80285, -0.66404, -0.60152, -0.68303, -0.67053, -0.38712, -0.17792, -0.01780, 0.02680, 0.20063, 0.26833, 0.33934, 0.40313, 0.49933, 0.52336, 0.54659, 0.64090, 0.84902, 1.02985, 1.24294, 1.39788, 1.46277, 1.44821, 1.45709, 1.50406, 1.74382, 2.00526, 2.24970, 2.44228, 2.69036, 2.85061, 2.82365, 2.74584, 2.80324, 2.90972, 2.82890, 2.57071, 2.42577, 2.21756, 2.13464, 2.03650, 1.96405, 1.77021, 1.53677, 1.19657, 0.88657, 0.67756, 0.57446, 0.46811, 0.35596, 0.15087, -0.01809, -0.24071, -0.34871, -0.45469, -0.62323, -0.83128, -1.04738, -1.22651, -1.41440, -1.69934, -1.87681, -2.13438, -2.43440, -2.73350, -2.84821, -2.84577, -2.98599, -3.18821, -3.14503, -3.09065, -2.99170, -2.86570, -2.64236, -2.57205, -2.54851, -2.49419, -2.31227, -2.13014, -2.00477, -1.89656, -1.84249, -1.87356, -1.94725, -2.06009, -2.07116, -2.09142, -2.14156, -2.26654, -2.36513, -2.46061, -2.60054, -2.69178, -2.57214, -2.39200, -2.32605, -2.47022, -2.54713, -2.45682, -2.31807, -2.26793, -2.09614, -1.90659, -1.72013, -1.64121, -1.49740, -1.30319, -1.07316, -0.85350, -0.64346, -0.41288, -0.24486, -0.11937, 0.01575, 0.03291, -0.02114, -0.09032, -0.15532, -0.03919, 0.13314, 0.29140, 0.46824, 0.49881, 0.40751, 0.24258, 0.19262, 0.18840, 0.01048, -0.28194, -0.49532, -0.48164, -0.47395, -0.50846, -0.47805, -0.55387, -0.72352, -0.89615, -0.99613, -1.14479, -1.37042, -1.55576, -1.80319, -1.99704, -2.25337, -2.44549, -2.48459, -2.57815, -2.65748, -2.80513, -2.99136, -3.14759, -3.36652, -3.48725, -3.45994, -3.34794, -3.30737, -3.48391, -3.63818, -3.69130, -3.70032, -3.78127, -3.85844, -3.69891, -3.51891, -3.48742, -3.30775, -2.98040, -2.69758, -2.52195, -2.43317, -2.32999, -2.32032, -2.21117, -2.06333, -1.92477, -1.93959, -2.01259, -2.09238, -2.12018, -2.14642, -2.12583, -2.11559, -2.06455, -2.00199, -1.89825, -1.81831, -1.75735, -1.81282, -1.92920, -1.92253, -1.76248, -1.68036, -1.63249, -1.64992, -1.60668, -1.56170, -1.57207, -1.38121, -1.08949, -0.82550, -0.54670, -0.38399, -0.16962, -0.10726, 0.11896, 0.41963, 0.74315, 1.04640, 1.29501, 1.53148, 1.61936, 1.54656, 1.51871, 1.48560, 1.54553, 1.49888, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.36286, -0.58481, -0.77116, -0.76674, -0.75928, -0.74841, -0.70988, -0.74788, -0.79655, -0.71338, -0.59904, -0.44671, -0.38637, -0.33487, -0.27996, -0.22544, -0.25092, -0.31047, -0.44168, -0.56482, -0.75243, -0.89079, -0.90605, -0.79813, -0.59606, -0.58835, -0.69016, -0.69618, -0.89712, -0.99330, -1.07870, -1.04252, -1.08286, -1.05816, -1.02393, -1.00489, -1.04827, -1.01323, -0.87700, -0.69499, +-0.02098, -0.05124, -0.13660, -0.27937, -0.27168, -0.10736, 0.07470, 0.27826, 0.48220, 0.47457, 0.33308, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.23884, -0.42898, -0.47361, -0.51912, -0.59642, -0.68816, -0.78674, -0.79983, -0.96680, -0.99989, -1.07719, -1.14947, -1.05673, -0.93825, -0.88120, -0.88664, -1.02016, -1.17452, -1.25048, -1.24987, -1.30714, -1.51952, -1.62638, -1.66317, -1.72872, -1.68512, -1.53412, -1.40669, -1.39237, -1.28181, -1.17463, -1.07346, -1.03472, -1.14145, -1.18918, -1.29260, -1.48339, -1.61571, -1.67170, -1.58993, -1.59642, -1.47177, -1.34113, -1.38361, -1.47386, -1.49402, -1.47286, -1.36301, -1.22281, -1.21294, -1.30205, -1.38951, -1.41081, -1.56392, -1.66661, -1.66569, -1.71976, -1.77624, -1.83883, -1.88249, -2.05410, -2.17497, -2.23166, -2.16269, -2.00936, -1.97114, -1.75039, -1.41887, -1.22611, -1.07011, -1.07341, -0.99376, -0.98551, -0.91506, -0.72391, -0.74982, -0.82266, -0.71653, -0.53410, -0.29029, -0.10580, -0.00461, 0.07042, 0.15987, 0.30921, 0.33037, 0.44484, 0.62711, 0.70565, 0.84568, 1.03619, 1.24674, 1.33020, 1.48820, 1.58315, 1.63000, 1.73898, 1.72705, 1.87323, 2.13127, 2.34708, 2.66138, 2.86626, 3.04129, 2.93872, 2.83121, 2.90948, 2.87401, 2.79575, 2.74231, 2.56909, 2.41060, 2.33761, 2.26685, 2.12501, 1.95969, 1.83313, 1.48914, 1.15845, 1.02867, 0.86739, 0.69826, 0.55787, 0.43701, 0.15711, -0.13050, -0.30938, -0.42905, -0.53054, -0.80471, -1.08520, -1.20839, -1.40907, -1.60254, -1.78318, -1.96803, -2.27704, -2.55524, -2.58507, -2.67534, -2.86195, -2.92085, -2.97178, -2.97035, -2.88062, -2.73047, -2.52023, -2.36880, -2.20585, -2.17475, -2.15207, -2.00859, -1.96699, -1.92543, -1.85355, -1.75108, -1.85157, -2.00282, -2.07546, -2.15367, -2.12626, -2.19835, -2.28959, -2.27011, -2.40021, -2.45343, -2.37766, -2.22252, -2.12063, -2.20611, -2.19213, -2.22169, -2.24521, -2.13816, -2.03753, -1.90981, -1.69953, -1.54978, -1.38723, -1.16862, -0.88334, -0.74019, -0.64357, -0.37504, -0.21551, -0.16342, -0.06989, 0.08035, 0.04392, -0.03899, -0.06157, 0.03191, 0.24421, 0.36556, 0.48168, 0.60563, 0.50564, 0.36244, 0.27381, 0.20600, 0.03357, -0.30288, -0.50105, -0.63396, -0.78601, -0.73263, -0.64381, -0.69483, -0.77576, -0.89299, -1.05374, -1.26679, -1.43919, -1.65020, -1.93287, -2.06100, -2.26476, -2.51865, -2.63777, -2.67512, -2.72073, -2.83759, -2.93825, -3.10398, -3.30875, -3.53425, -3.68247, -3.59198, -3.52814, -3.61868, -3.75274, -3.86315, -3.85782, -3.99060, -3.98711, -3.87504, -3.78716, -3.60730, -3.32405, -3.04994, -2.78401, -2.63860, -2.54972, -2.47184, -2.38297, -2.31085, -2.25612, -2.07235, -2.03508, -2.17090, -2.30223, -2.31179, -2.35809, -2.44698, -2.36316, -2.27850, -2.14853, -2.02352, -2.01815, -1.89536, -1.86710, -1.93175, -1.93309, -1.89789, -1.78990, -1.77545, -1.63306, -1.50941, -1.52495, -1.45565, -1.26597, -1.12888, -0.91928, -0.68363, -0.46836, -0.27516, -0.10489, 0.12012, 0.30412, 0.60569, 1.00204, 1.30076, 1.56790, 1.72927, 1.69157, 1.51620, 1.50115, 1.55320, 1.62490, 1.60717, 1.45219, 0.00000, 0.00000, 1.55912, 1.56449, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.64647, -0.69103, -0.66334, -0.71114, -0.65132, -0.59466, -0.52965, -0.53280, -0.38815, -0.23768, -0.13977, -0.08653, -0.21423, -0.27433, -0.30101, -0.37829, -0.38873, -0.54657, -0.66781, -0.87301, -0.93810, -0.85583, -0.86632, -0.89908, -0.83058, -0.85838, -0.99162, -1.10236, -1.15659, -1.15876, -1.07640, -0.87713, -0.83855, -0.83479, -0.84207, -0.88834, -0.78813, -0.56190, +-0.23536, -0.15586, -0.24530, -0.39235, -0.37779, -0.22683, -0.09631, 0.09137, 0.27304, 0.24142, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.12750, -0.25422, -0.46688, -0.69988, -0.74263, -0.78757, -0.84790, -0.92861, -1.03660, -0.95440, -0.95283, -1.01503, -1.18551, -1.21085, -1.03648, -0.95157, -0.90580, -0.86420, -0.94253, -1.10097, -1.21446, -1.23847, -1.36748, -1.54178, -1.58809, -1.62395, -1.66982, -1.72128, -1.71796, -1.52649, -1.37551, -1.21348, -1.17855, -1.24015, -1.37499, -1.52077, -1.49529, -1.55067, -1.68270, -1.70248, -1.74129, -1.65229, -1.60710, -1.57334, -1.55798, -1.55555, -1.50092, -1.55695, -1.63851, -1.61517, -1.50637, -1.50204, -1.61804, -1.68662, -1.74405, -1.86196, -1.91361, -1.92443, -1.93384, -1.96379, -2.07548, -2.05074, -2.14663, -2.27960, -2.33200, -2.24534, -2.14912, -2.11165, -1.85943, -1.51039, -1.33623, -1.19855, -1.24256, -1.19410, -1.11613, -1.09224, -1.03342, -1.02374, -0.94766, -0.83647, -0.68361, -0.42744, -0.18015, -0.01929, 0.08005, 0.20217, 0.28858, 0.29568, 0.46219, 0.72302, 0.92991, 1.12799, 1.16063, 1.29949, 1.41618, 1.55527, 1.69901, 1.78055, 1.86205, 1.92270, 2.10970, 2.31916, 2.39265, 2.62663, 2.80748, 2.99881, 3.06970, 2.99325, 2.92260, 2.84276, 2.89402, 2.89914, 2.73588, 2.61558, 2.60552, 2.54184, 2.34325, 2.13702, 1.92111, 1.60526, 1.38008, 1.29344, 1.13545, 0.93370, 0.66944, 0.55518, 0.35983, 0.03515, -0.18740, -0.31513, -0.50899, -0.81354, -1.05450, -1.17598, -1.43603, -1.63608, -1.79947, -1.94733, -2.12552, -2.36708, -2.51918, -2.62756, -2.65105, -2.61095, -2.63181, -2.62334, -2.51824, -2.40254, -2.24589, -2.05184, -1.90592, -1.88277, -1.89726, -1.83230, -1.84150, -1.82973, -1.82909, -1.73062, -1.69321, -1.77177, -1.86612, -2.00140, -2.15062, -2.29382, -2.31058, -2.20345, -2.28023, -2.30142, -2.23298, -2.11217, -1.91688, -1.92743, -2.02489, -2.11622, -2.04743, -1.92950, -1.90780, -1.85698, -1.65109, -1.44907, -1.25558, -1.00838, -0.81353, -0.75314, -0.62150, -0.29588, -0.10302, -0.05958, -0.06080, 0.07991, 0.15154, 0.12088, 0.11245, 0.18170, 0.26772, 0.29445, 0.41930, 0.56375, 0.40120, 0.19908, 0.07230, -0.01303, -0.08846, -0.31108, -0.56973, -0.79109, -0.87841, -0.80175, -0.74066, -0.74674, -0.73957, -0.79060, -1.01754, -1.28975, -1.55575, -1.85020, -2.05368, -2.10952, -2.22415, -2.40204, -2.61198, -2.76411, -2.82752, -2.91887, -2.98744, -3.10946, -3.32977, -3.63946, -3.82801, -3.78058, -3.78200, -3.89572, -4.02450, -4.10869, -4.01113, -4.04810, -4.12820, -4.14836, -3.98407, -3.65539, -3.33866, -3.07991, -2.86713, -2.74309, -2.65944, -2.55662, -2.48993, -2.53765, -2.46953, -2.20746, -2.13678, -2.24642, -2.43842, -2.57186, -2.61813, -2.66512, -2.55913, -2.43583, -2.34112, -2.29780, -2.26900, -2.07125, -2.00283, -2.02868, -1.98438, -1.95289, -1.81030, -1.72034, -1.60517, -1.51887, -1.40756, -1.19227, -1.08858, -1.04586, -0.92054, -0.69563, -0.44664, -0.24159, -0.01725, 0.14989, 0.32434, 0.63579, 0.97468, 1.29511, 1.56665, 1.68992, 1.75113, 1.66936, 1.64525, 1.67958, 1.73210, 1.65594, 1.54312, 1.66016, 1.78618, 1.72252, 1.68005, 1.60220, 1.65540, 1.62137, 1.53206, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.50811, -0.49614, -0.52076, -0.45327, -0.46729, -0.37852, -0.31050, -0.17897, -0.03193, 0.03807, -0.02110, -0.18707, -0.26186, -0.34940, -0.54048, -0.55243, -0.66720, -0.71853, -0.80205, -0.95725, -1.07696, -1.17268, -1.08482, -0.94381, -0.92522, -0.95703, -0.98070, -1.01320, -1.05995, -1.02959, -0.92999, -0.86084, -0.72715, -0.65119, -0.64740, -0.55496, -0.43873, +-0.32179, -0.39770, -0.50792, -0.61990, -0.58619, -0.37479, -0.28946, -0.10724, 0.07213, 0.01416, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.22466, -0.20920, -0.36360, -0.52693, -0.64845, -0.83040, -0.93817, -0.96897, -0.93353, -0.93815, -1.04107, -1.04215, -1.01215, -1.14967, -1.23680, -1.09901, -1.00827, -0.99696, -0.92538, -0.96626, -1.00849, -1.18600, -1.30302, -1.26424, -1.38954, -1.52253, -1.51514, -1.59033, -1.63741, -1.69035, -1.79092, -1.68186, -1.58972, -1.39805, -1.37503, -1.51598, -1.59497, -1.65782, -1.64308, -1.70575, -1.75270, -1.68596, -1.67396, -1.67853, -1.66454, -1.80657, -1.80575, -1.67500, -1.66009, -1.79220, -1.85453, -1.94499, -1.89302, -1.98160, -2.13735, -2.12772, -2.13235, -2.18615, -2.19145, -2.25187, -2.25054, -2.19224, -2.26684, -2.20716, -2.30742, -2.39923, -2.41374, -2.32326, -2.11698, -1.99894, -1.80461, -1.55157, -1.38018, -1.26055, -1.28443, -1.34513, -1.25767, -1.31549, -1.30377, -1.21506, -1.18378, -1.18943, -0.97872, -0.74499, -0.43827, -0.22886, -0.06203, 0.20712, 0.35629, 0.36412, 0.50182, 0.68430, 0.88262, 1.18103, 1.24921, 1.36925, 1.42979, 1.60059, 1.80937, 1.86170, 2.01644, 2.19382, 2.37672, 2.50756, 2.53288, 2.66855, 2.85700, 2.94613, 3.09098, 3.04645, 2.96505, 3.00164, 3.01473, 2.84523, 2.72632, 2.59581, 2.62299, 2.57002, 2.32294, 2.16531, 1.99143, 1.70723, 1.54684, 1.44689, 1.26365, 1.12658, 0.89827, 0.80454, 0.56783, 0.20931, -0.02944, -0.25619, -0.45773, -0.69286, -0.91908, -1.07956, -1.29527, -1.46967, -1.59012, -1.87481, -2.07698, -2.33801, -2.53794, -2.50322, -2.44598, -2.49385, -2.40091, -2.34041, -2.22012, -2.13344, -2.10231, -1.89045, -1.69323, -1.64997, -1.63101, -1.64156, -1.74218, -1.66837, -1.61756, -1.54195, -1.55891, -1.65412, -1.72707, -1.92847, -2.15226, -2.29026, -2.29179, -2.21351, -2.17503, -2.07666, -1.90126, -1.87024, -1.76887, -1.83157, -2.02062, -2.01573, -1.88322, -1.94501, -1.96686, -1.93349, -1.74757, -1.50075, -1.32003, -0.98047, -0.68998, -0.61486, -0.42546, -0.09963, 0.03052, 0.10941, 0.12810, 0.23152, 0.24744, 0.18368, 0.22005, 0.26552, 0.31785, 0.38911, 0.46215, 0.43376, 0.20831, 0.00318, -0.07718, -0.21514, -0.33937, -0.50734, -0.76641, -0.84594, -0.82720, -0.94967, -0.99837, -0.98860, -0.97868, -0.94170, -1.17645, -1.41400, -1.60226, -1.86180, -1.99905, -2.07845, -2.26329, -2.38996, -2.54950, -2.72922, -2.90579, -3.11420, -3.16572, -3.28118, -3.45641, -3.62935, -3.78778, -3.88201, -4.00668, -4.13803, -4.21475, -4.30069, -4.25760, -4.26324, -4.42146, -4.36052, -4.06078, -3.83573, -3.57015, -3.24897, -3.07116, -2.91146, -2.84058, -2.68543, -2.53176, -2.58840, -2.51931, -2.29992, -2.32467, -2.41981, -2.53951, -2.66362, -2.74225, -2.85664, -2.77893, -2.71298, -2.66990, -2.53763, -2.43242, -2.27144, -2.20483, -2.10850, -1.92135, -1.82761, -1.76620, -1.69885, -1.71102, -1.56038, -1.27555, -1.10496, -1.08414, -1.00436, -0.93180, -0.64523, -0.40053, -0.20849, 0.09243, 0.27771, 0.47116, 0.76342, 0.94256, 1.19115, 1.52055, 1.69013, 1.82759, 1.76250, 1.76807, 1.76864, 1.70514, 1.67534, 1.64692, 1.74049, 1.83409, 1.80815, 1.77448, 1.69919, 1.61866, 1.57355, 1.39289, 1.25403, 1.14280, 0.95450, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.28496, -0.21255, -0.26672, -0.21379, -0.22576, -0.11519, 0.01201, -0.01423, -0.02288, -0.09804, -0.22679, -0.42437, -0.66525, -0.72239, -0.78019, -0.90610, -0.94366, -1.14664, -1.29038, -1.24856, -1.13506, -1.09587, -1.00898, -1.02404, -0.96738, -0.96076, -1.04425, -1.02423, -0.95495, -0.86797, -0.64461, -0.52272, -0.48991, -0.31298, -0.19894, +-0.45332, -0.60417, -0.69793, -0.76837, -0.73112, -0.52881, -0.40075, -0.25163, -0.17141, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.37456, -0.33374, -0.32554, -0.49402, -0.66539, -0.77307, -0.94039, -1.04084, -1.01134, -0.89198, -0.87668, -1.02535, -1.07202, -1.06231, -1.14985, -1.12867, -0.99365, -0.96384, -0.94531, -0.90733, -1.02769, -1.09694, -1.20738, -1.28096, -1.28230, -1.41124, -1.55483, -1.57594, -1.59613, -1.60469, -1.69044, -1.85813, -1.82734, -1.75940, -1.59464, -1.54596, -1.65620, -1.71180, -1.71678, -1.64681, -1.66809, -1.67370, -1.64623, -1.73118, -1.77148, -1.80517, -1.97680, -1.92171, -1.82624, -1.89232, -2.02444, -2.10315, -2.25658, -2.35487, -2.52975, -2.65806, -2.63023, -2.56471, -2.55375, -2.57753, -2.57015, -2.47129, -2.39452, -2.44570, -2.35480, -2.35369, -2.37797, -2.32986, -2.16124, -1.89821, -1.76693, -1.61735, -1.44943, -1.30915, -1.22517, -1.31636, -1.40481, -1.35081, -1.42102, -1.40034, -1.39852, -1.45726, -1.45487, -1.24780, -1.04751, -0.78084, -0.52618, -0.22797, 0.10493, 0.29065, 0.31013, 0.33302, 0.47278, 0.71169, 1.02481, 1.16480, 1.33314, 1.47862, 1.73286, 2.01509, 2.10645, 2.27201, 2.42890, 2.58000, 2.69202, 2.70263, 2.77250, 2.85723, 2.90167, 3.06061, 3.07515, 3.11291, 3.16628, 3.03285, 2.77414, 2.65688, 2.53399, 2.53030, 2.47949, 2.28569, 2.14639, 2.00013, 1.75092, 1.53742, 1.45073, 1.37169, 1.28015, 1.11061, 1.07865, 0.92540, 0.58789, 0.31248, 0.01949, -0.21011, -0.44447, -0.65451, -0.80263, -0.97930, -1.14378, -1.38190, -1.77589, -2.00363, -2.25186, -2.38042, -2.32845, -2.32476, -2.35583, -2.18006, -2.06683, -1.98057, -1.92691, -1.90703, -1.74368, -1.58293, -1.52454, -1.53707, -1.56618, -1.60314, -1.47631, -1.38595, -1.31896, -1.33265, -1.46166, -1.56391, -1.76346, -2.00004, -2.15764, -2.16198, -2.07366, -1.95396, -1.77719, -1.61048, -1.63525, -1.64349, -1.79417, -1.94045, -1.90594, -1.84861, -1.97765, -2.02225, -1.98781, -1.83899, -1.60964, -1.36942, -0.97025, -0.62154, -0.48223, -0.30535, 0.02347, 0.22890, 0.34294, 0.34829, 0.41201, 0.45116, 0.42345, 0.47825, 0.51941, 0.54583, 0.56384, 0.50488, 0.35154, 0.11726, -0.07383, -0.21123, -0.42863, -0.57295, -0.71475, -0.85222, -0.83419, -0.86559, -1.08272, -1.20371, -1.24356, -1.28770, -1.25568, -1.39197, -1.56384, -1.71453, -1.89151, -2.02209, -2.14821, -2.30614, -2.42142, -2.57258, -2.72699, -2.89231, -3.08969, -3.14291, -3.23878, -3.36046, -3.48974, -3.65935, -3.83478, -4.08288, -4.28298, -4.39323, -4.51918, -4.47166, -4.46786, -4.56434, -4.39906, -4.12177, -3.98062, -3.75182, -3.44629, -3.28735, -3.15289, -3.01646, -2.76149, -2.56736, -2.59013, -2.57769, -2.47384, -2.46399, -2.47920, -2.54446, -2.63435, -2.70031, -2.80723, -2.82296, -2.82396, -2.77016, -2.61802, -2.52186, -2.37950, -2.28526, -2.10338, -1.85200, -1.77432, -1.71706, -1.67462, -1.69722, -1.47902, -1.21701, -1.09579, -1.04336, -0.95272, -0.87879, -0.58832, -0.29821, -0.06464, 0.19785, 0.34534, 0.50310, 0.71093, 0.87986, 1.16152, 1.50214, 1.71930, 1.93684, 1.98365, 2.02600, 1.99696, 1.83756, 1.74840, 1.71488, 1.80303, 1.90208, 1.89799, 1.84600, 1.70116, 1.56874, 1.45761, 1.24210, 1.17512, 1.07164, 0.82420, 0.68856, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.04449, 0.03872, -0.05819, -0.01061, -0.00884, 0.03918, 0.09140, 0.01040, -0.01392, -0.07849, -0.22942, -0.45676, -0.71322, -0.83401, -0.98275, -1.14351, -1.16772, -1.31980, -1.35974, -1.27800, -1.19504, -1.14887, -1.05309, -1.08592, -1.09259, -1.07240, -1.08522, -1.07614, -1.01193, -0.89751, -0.69944, -0.48685, -0.29440, -0.04990, 0.06501, +-0.72602, -0.77094, -0.80595, -0.79553, -0.73357, -0.55810, -0.37608, -0.39542, -0.49821, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.55905, -0.49090, -0.40338, -0.42480, -0.59144, -0.76542, -0.96633, -1.14369, -1.19104, -1.13680, -0.97705, -0.91693, -1.04364, -1.11815, -1.09621, -1.08114, -1.02895, -1.03497, -0.97462, -0.91471, -0.91659, -0.99341, -0.96346, -0.90600, -1.04224, -1.26746, -1.37095, -1.45757, -1.56009, -1.53908, -1.60566, -1.70958, -1.84743, -1.94460, -1.97459, -1.92396, -1.84921, -1.83349, -1.91135, -1.93317, -1.80215, -1.76589, -1.72410, -1.75964, -1.93295, -2.01843, -2.06758, -2.16782, -2.08791, -2.13784, -2.21313, -2.35150, -2.47079, -2.58073, -2.70622, -2.86559, -3.04219, -3.12820, -2.96214, -2.78103, -2.80575, -2.66845, -2.54023, -2.51792, -2.56871, -2.55779, -2.49897, -2.44003, -2.31685, -2.04949, -1.82958, -1.74755, -1.61774, -1.53049, -1.38824, -1.28622, -1.34652, -1.47227, -1.48753, -1.55220, -1.55736, -1.69798, -1.66974, -1.53328, -1.36928, -1.20131, -0.94183, -0.61445, -0.32679, -0.14404, 0.03340, 0.22017, 0.23057, 0.37649, 0.54872, 0.74911, 0.97009, 1.17771, 1.39547, 1.70085, 2.01458, 2.21940, 2.36699, 2.41286, 2.52649, 2.63539, 2.69036, 2.79263, 2.88043, 2.90408, 3.00998, 3.02476, 3.15570, 3.14459, 3.00025, 2.79233, 2.64399, 2.56207, 2.57962, 2.57892, 2.39795, 2.14216, 1.96547, 1.84608, 1.58280, 1.50223, 1.48264, 1.38454, 1.29947, 1.27135, 1.15684, 0.87703, 0.55893, 0.26568, 0.02312, -0.25994, -0.44071, -0.61948, -0.80435, -0.96354, -1.25373, -1.66378, -1.85333, -2.04571, -2.12111, -2.21776, -2.24283, -2.15687, -1.99526, -1.85692, -1.75349, -1.60970, -1.52200, -1.55314, -1.57643, -1.45150, -1.45417, -1.44068, -1.42223, -1.37584, -1.27547, -1.22754, -1.27209, -1.44487, -1.61577, -1.74917, -1.92391, -2.09293, -2.07394, -1.97738, -1.87293, -1.70252, -1.50962, -1.51111, -1.56177, -1.76337, -1.84952, -1.88951, -1.89149, -1.92640, -1.98829, -1.91899, -1.74243, -1.49676, -1.21514, -0.95281, -0.68052, -0.35870, -0.14878, 0.16202, 0.43102, 0.50856, 0.50650, 0.53578, 0.58928, 0.63139, 0.66517, 0.66427, 0.63471, 0.50341, 0.31679, 0.15254, -0.00020, -0.11220, -0.26504, -0.54056, -0.69288, -0.83297, -0.90225, -0.94166, -1.06182, -1.14362, -1.25851, -1.37538, -1.48189, -1.47492, -1.49055, -1.72076, -1.98188, -2.03857, -2.11620, -2.24252, -2.32653, -2.53156, -2.69215, -2.79827, -2.92893, -3.03074, -3.08885, -3.16132, -3.27589, -3.50113, -3.69608, -3.85972, -4.15896, -4.39634, -4.51015, -4.61464, -4.54184, -4.51810, -4.52327, -4.33748, -4.16251, -3.98772, -3.83115, -3.63382, -3.45671, -3.28699, -3.05380, -2.86353, -2.77602, -2.67188, -2.62520, -2.60035, -2.45930, -2.42934, -2.45327, -2.54905, -2.68249, -2.79513, -2.91035, -2.90723, -2.74558, -2.62549, -2.60593, -2.48140, -2.35969, -2.13893, -1.88819, -1.80747, -1.72486, -1.60642, -1.54126, -1.35611, -1.27068, -1.10880, -0.97525, -0.88750, -0.76777, -0.46752, -0.09370, 0.10196, 0.18430, 0.29575, 0.48464, 0.62812, 0.90462, 1.21755, 1.54895, 1.80117, 1.96594, 2.06581, 2.15041, 2.14572, 1.99731, 1.78871, 1.67668, 1.78089, 1.88568, 1.89997, 1.84706, 1.71695, 1.56032, 1.38132, 1.12090, 1.02938, 0.83412, 0.67833, 0.63943, 0.69706, 0.69003, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.27636, 0.22168, 0.25881, 0.25747, 0.19023, 0.10819, 0.02155, -0.10963, -0.28184, -0.42711, -0.62260, -0.78026, -0.89130, -1.09322, -1.31745, -1.36143, -1.43276, -1.39211, -1.41600, -1.32787, -1.20117, -1.12675, -1.15719, -1.22401, -1.16889, -1.15064, -1.22080, -1.12984, -0.86308, -0.69763, -0.41987, -0.12969, 0.14575, 0.33024, +-0.94346, -0.90673, -0.87902, -0.80227, -0.83762, -0.80530, -0.65827, -0.69536, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.81027, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.74578, -0.67560, -0.54548, -0.56196, -0.73544, -0.84178, -0.95411, -1.12494, -1.18185, -1.25901, -1.25141, -1.15732, -1.19785, -1.22750, -1.12343, -1.08711, -1.08800, -1.12481, -1.05025, -0.96376, -0.91211, -0.92647, -0.89769, -0.77824, -0.89739, -1.13439, -1.20444, -1.27834, -1.39445, -1.47980, -1.69717, -1.77855, -1.87209, -2.02627, -2.14251, -2.18781, -2.13814, -2.00441, -1.94440, -2.02130, -1.94857, -1.93188, -1.95445, -1.97735, -2.12519, -2.22487, -2.25188, -2.35967, -2.36414, -2.43100, -2.51305, -2.71233, -2.83364, -2.92312, -3.08686, -3.19947, -3.36624, -3.41968, -3.16808, -2.92271, -2.85604, -2.70042, -2.67856, -2.67178, -2.73518, -2.74502, -2.61956, -2.47073, -2.32386, -2.06475, -1.80336, -1.75372, -1.68027, -1.67859, -1.65467, -1.53317, -1.50438, -1.63179, -1.64025, -1.70685, -1.78300, -1.86493, -1.68796, -1.47759, -1.29414, -1.16425, -1.04018, -0.74983, -0.52949, -0.39326, -0.17281, 0.09191, 0.22541, 0.34913, 0.32397, 0.44662, 0.69531, 0.95353, 1.21748, 1.49471, 1.74459, 2.00458, 2.31498, 2.39672, 2.49965, 2.59477, 2.55316, 2.66439, 2.82187, 2.87258, 2.97188, 2.95118, 3.02580, 3.06604, 3.09509, 2.98125, 2.84461, 2.74592, 2.60901, 2.53907, 2.32495, 2.07644, 1.96945, 1.88735, 1.68522, 1.61327, 1.50047, 1.42109, 1.37547, 1.30442, 1.18619, 0.96808, 0.63318, 0.33618, 0.22599, -0.03215, -0.23280, -0.47842, -0.80892, -0.98506, -1.20247, -1.51314, -1.59643, -1.72548, -1.85044, -1.98970, -1.93929, -1.81360, -1.68646, -1.57293, -1.58081, -1.43156, -1.30004, -1.36302, -1.40751, -1.31156, -1.26015, -1.21309, -1.34418, -1.45679, -1.43091, -1.39952, -1.41957, -1.54538, -1.71590, -1.81740, -1.83311, -1.92742, -1.90566, -1.83022, -1.90345, -1.84074, -1.60631, -1.51059, -1.42592, -1.54601, -1.67203, -1.75579, -1.71820, -1.71098, -1.76330, -1.66143, -1.56389, -1.39952, -1.15009, -0.90761, -0.56861, -0.17555, 0.05157, 0.28619, 0.38716, 0.40448, 0.42073, 0.45798, 0.55267, 0.64183, 0.63561, 0.52774, 0.51565, 0.38512, 0.16654, 0.06188, -0.08233, -0.16482, -0.24444, -0.47693, -0.57534, -0.68536, -0.82815, -0.94940, -1.03330, -1.00692, -1.07983, -1.23532, -1.48863, -1.64154, -1.67268, -1.89895, -2.15627, -2.25035, -2.33437, -2.40058, -2.51596, -2.76294, -2.86875, -2.92880, -3.01815, -3.06377, -3.12307, -3.21847, -3.31129, -3.50853, -3.70820, -3.81932, -4.09758, -4.36257, -4.44314, -4.49484, -4.39488, -4.31754, -4.31856, -4.16745, -3.97649, -3.79833, -3.72493, -3.60180, -3.49539, -3.43625, -3.25891, -3.16129, -3.07071, -2.87430, -2.78987, -2.71761, -2.57131, -2.57208, -2.53334, -2.64293, -2.79830, -2.90037, -3.01823, -2.98520, -2.70780, -2.45599, -2.44540, -2.33774, -2.24509, -2.12898, -1.91448, -1.79829, -1.65841, -1.38609, -1.24875, -1.14466, -1.09594, -0.91351, -0.76788, -0.67250, -0.62514, -0.53867, -0.22767, -0.03095, 0.08317, 0.24734, 0.44241, 0.61765, 0.86213, 1.06561, 1.41845, 1.68075, 1.80099, 1.91797, 2.05063, 2.10711, 2.09217, 2.00704, 1.85256, 1.89888, 1.92565, 1.81351, 1.76394, 1.70975, 1.57817, 1.42717, 1.13690, 0.96075, 0.81064, 0.77191, 0.73168, 0.73951, 0.73679, 0.67077, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.36626, 0.38514, 0.43060, 0.41983, 0.28167, 0.07980, -0.03122, -0.11230, -0.34804, -0.50913, -0.67432, -0.83429, -0.89531, -1.05834, -1.29459, -1.30632, -1.33602, -1.35803, -1.44770, -1.39467, -1.29642, -1.21850, -1.24340, -1.43780, -1.42348, -1.41373, -1.45426, -1.27412, -0.95456, -0.72994, -0.46605, -0.27177, 0.05950, 0.35751, +-1.17061, -1.15134, -1.11864, -0.97984, -0.94901, -0.99089, -0.95281, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.86997, -1.05047, -1.02256, -1.01917, -1.10020, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.89493, -0.90392, -0.88799, -0.67086, -0.66261, -0.83184, -0.85295, -0.95537, -1.15720, -1.23480, -1.33551, -1.40229, -1.36705, -1.37978, -1.31984, -1.26455, -1.20799, -1.25576, -1.27006, -1.24449, -1.15239, -1.01803, -0.87676, -0.82608, -0.78566, -0.82969, -0.95052, -1.08321, -1.17235, -1.31627, -1.43520, -1.65033, -1.68443, -1.83700, -2.09729, -2.20028, -2.26365, -2.27194, -2.07761, -2.04059, -2.20114, -2.19709, -2.12309, -2.11114, -2.12093, -2.27160, -2.32064, -2.49173, -2.66591, -2.77108, -2.80564, -2.94008, -3.15437, -3.24975, -3.23265, -3.31573, -3.43484, -3.55155, -3.48797, -3.30639, -3.07900, -3.01743, -2.86824, -2.83317, -2.75337, -2.81450, -2.84114, -2.59581, -2.35324, -2.25856, -2.02755, -1.88954, -1.92154, -1.92471, -1.91099, -1.89593, -1.80464, -1.80889, -1.82162, -1.89231, -1.93076, -2.02603, -2.00765, -1.83419, -1.62896, -1.41884, -1.20081, -1.06401, -0.86281, -0.67103, -0.43619, -0.27255, -0.03775, 0.07468, 0.18075, 0.14725, 0.33101, 0.59975, 0.80791, 1.09854, 1.37228, 1.49209, 1.78411, 2.10258, 2.24206, 2.35870, 2.52258, 2.49364, 2.54967, 2.63806, 2.81147, 2.86040, 2.85580, 2.89256, 3.01321, 3.11863, 3.05851, 2.91551, 2.83835, 2.66648, 2.46897, 2.18482, 2.04244, 1.91827, 1.82138, 1.63570, 1.61330, 1.54707, 1.55982, 1.55668, 1.38415, 1.25610, 1.13886, 0.75359, 0.47894, 0.33714, 0.02847, -0.24310, -0.45741, -0.74723, -0.91660, -1.17148, -1.34726, -1.46012, -1.59035, -1.72316, -1.80084, -1.73600, -1.62368, -1.51204, -1.35395, -1.32871, -1.26157, -1.20563, -1.15700, -1.19525, -1.14785, -1.12019, -1.09898, -1.29827, -1.46730, -1.48557, -1.54786, -1.55390, -1.51364, -1.67148, -1.73424, -1.76978, -1.93609, -1.97796, -1.86595, -1.90787, -1.87237, -1.72812, -1.52522, -1.35140, -1.41472, -1.53495, -1.60346, -1.56764, -1.58724, -1.63970, -1.47960, -1.31744, -1.21414, -1.04701, -0.67542, -0.28263, 0.04115, 0.19113, 0.30050, 0.29817, 0.34834, 0.43473, 0.42532, 0.48804, 0.64155, 0.55841, 0.38735, 0.33793, 0.14078, -0.11229, -0.13571, -0.16948, -0.19098, -0.26748, -0.40366, -0.45421, -0.58607, -0.72108, -0.84799, -0.91423, -0.94080, -1.04703, -1.18399, -1.39165, -1.62768, -1.78111, -1.94182, -2.18135, -2.42671, -2.58018, -2.65722, -2.73636, -2.84204, -2.80624, -2.88838, -3.05793, -3.08318, -3.17762, -3.29312, -3.36077, -3.58948, -3.81440, -3.84341, -3.93818, -4.11516, -4.23413, -4.28629, -4.17026, -4.15750, -4.13578, -4.01272, -3.81114, -3.72460, -3.71681, -3.58882, -3.43074, -3.44702, -3.43620, -3.37139, -3.23628, -3.09309, -3.00858, -2.94605, -2.79599, -2.72277, -2.55744, -2.66401, -2.85718, -2.88517, -2.97912, -2.97580, -2.66746, -2.44394, -2.43059, -2.28732, -2.10966, -1.97603, -1.81410, -1.71443, -1.49199, -1.26480, -1.07463, -0.99174, -0.89544, -0.77064, -0.66494, -0.58063, -0.52059, -0.55004, -0.38880, -0.16083, 0.09648, 0.25348, 0.43993, 0.56129, 0.71027, 0.85957, 1.28092, 1.54954, 1.63318, 1.83242, 2.01746, 2.07859, 2.20162, 2.11855, 1.90874, 1.87634, 1.89973, 1.77651, 1.69221, 1.60360, 1.57523, 1.37484, 1.15673, 1.00490, 0.96430, 0.91949, 0.83697, 0.78953, 0.84194, 0.79780, 0.75959, 0.75054, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.57223, 0.51173, 0.48816, 0.35873, 0.04175, -0.07041, -0.20064, -0.45740, -0.62047, -0.68947, -0.79129, -0.85124, -1.05496, -1.17418, -1.23778, -1.24309, -1.32771, -1.44142, -1.52004, -1.50355, -1.44975, -1.38115, -1.50457, -1.56429, -1.60571, -1.58327, -1.48075, -1.18310, -0.95374, -0.66848, -0.44175, -0.00757, 0.38740, +-1.28720, -1.26421, -1.28417, -1.21082, -1.14902, -1.15217, -1.13351, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.04913, -1.22160, -1.34685, -1.27738, -1.29692, -1.40936, -1.56637, -1.67506, -1.61635, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.23826, -1.05924, -1.08113, -1.08719, -0.92679, -0.86949, -0.92144, -0.95344, -1.10272, -1.26367, -1.32282, -1.51658, -1.68731, -1.64904, -1.59409, -1.45753, -1.40898, -1.33490, -1.35112, -1.38000, -1.34193, -1.25157, -1.11997, -0.90060, -0.78217, -0.76598, -0.79957, -0.90191, -1.08080, -1.16948, -1.31096, -1.39022, -1.53240, -1.61122, -1.89189, -2.23054, -2.37716, -2.38993, -2.31145, -2.17079, -2.24626, -2.39598, -2.36676, -2.31092, -2.33281, -2.30938, -2.42712, -2.48032, -2.70865, -2.94490, -3.05158, -3.12011, -3.23441, -3.37193, -3.46417, -3.39895, -3.35297, -3.41714, -3.50602, -3.46244, -3.40333, -3.19119, -3.10575, -2.95797, -2.90852, -2.84794, -2.93576, -2.93574, -2.66626, -2.34987, -2.16060, -2.03789, -2.11195, -2.17492, -2.14861, -2.14167, -2.20936, -2.16242, -2.19770, -2.18516, -2.24190, -2.25498, -2.22447, -2.15357, -1.98363, -1.80012, -1.63664, -1.38893, -1.17882, -0.97945, -0.78476, -0.52523, -0.41121, -0.20294, -0.14142, -0.04792, 0.00900, 0.23966, 0.46498, 0.63309, 0.86513, 1.13423, 1.32348, 1.58670, 1.78351, 1.97580, 2.17791, 2.37198, 2.31994, 2.33645, 2.39510, 2.58841, 2.67396, 2.76089, 2.92607, 3.09696, 3.25466, 3.22934, 3.02260, 2.87030, 2.67600, 2.46564, 2.19533, 2.04217, 1.80642, 1.69277, 1.54637, 1.57341, 1.62039, 1.69349, 1.65226, 1.40993, 1.22438, 1.15478, 0.92130, 0.69133, 0.38880, 0.00602, -0.28812, -0.50211, -0.80343, -0.96643, -1.18860, -1.32465, -1.46555, -1.61648, -1.64763, -1.65283, -1.57689, -1.46386, -1.39293, -1.24073, -1.15333, -1.10385, -1.10711, -1.04994, -1.10373, -1.03438, -1.00452, -1.02529, -1.21189, -1.38939, -1.49437, -1.62748, -1.66953, -1.56911, -1.58577, -1.59274, -1.75256, -2.02300, -2.08564, -1.97879, -2.00950, -1.92309, -1.77296, -1.53661, -1.30614, -1.31499, -1.32812, -1.36193, -1.34974, -1.33211, -1.36763, -1.24340, -1.07576, -0.95176, -0.78564, -0.39682, -0.04924, 0.22312, 0.31008, 0.29205, 0.25828, 0.35232, 0.44966, 0.42459, 0.41059, 0.49589, 0.41111, 0.24685, 0.07903, -0.19720, -0.39716, -0.36209, -0.39129, -0.40066, -0.42864, -0.50420, -0.53058, -0.64534, -0.68085, -0.70891, -0.75722, -0.82178, -1.01371, -1.20233, -1.35093, -1.52539, -1.70344, -1.88750, -2.17765, -2.48055, -2.64785, -2.75017, -2.77189, -2.75278, -2.69308, -2.81016, -3.04859, -3.17870, -3.27752, -3.34542, -3.43461, -3.65451, -3.80753, -3.73943, -3.74145, -3.86596, -3.97300, -4.07491, -4.01228, -3.99345, -3.89254, -3.73601, -3.61193, -3.57354, -3.61454, -3.54893, -3.37405, -3.35736, -3.42046, -3.45588, -3.37928, -3.26259, -3.12057, -3.04804, -2.89665, -2.76440, -2.60829, -2.72691, -2.91597, -2.95744, -2.98399, -2.90611, -2.67940, -2.56472, -2.49912, -2.28185, -2.09215, -1.97710, -1.80713, -1.68661, -1.44153, -1.24654, -1.04541, -0.86588, -0.73166, -0.58894, -0.52573, -0.54394, -0.50142, -0.48972, -0.35189, -0.13962, 0.12944, 0.26895, 0.45782, 0.53912, 0.62485, 0.73601, 1.09175, 1.29962, 1.43518, 1.68957, 1.93252, 2.12015, 2.27473, 2.11167, 1.89912, 1.82117, 1.77769, 1.63312, 1.56871, 1.45196, 1.41243, 1.24494, 1.12763, 1.15037, 1.19697, 1.20194, 1.09101, 0.91703, 0.95597, 1.00439, 1.00441, 0.98375, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.44271, 0.31985, 0.18031, -0.06923, -0.22063, -0.47204, -0.69051, -0.76245, -0.78825, -0.93854, -1.02786, -1.21082, -1.26032, -1.28710, -1.27793, -1.29705, -1.41671, -1.52015, -1.53709, -1.57283, -1.49525, -1.50130, -1.53713, -1.59090, -1.61292, -1.65615, -1.41621, -1.19338, -0.84027, -0.47756, -0.01620, 0.35514, +-1.38137, -1.32710, -1.32932, -1.43266, -1.46712, -1.34380, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.39919, -1.37150, -1.43760, -1.50477, -1.57425, -1.58174, -1.59609, -1.74467, -1.82889, -1.75371, -1.64380, -1.55163, -1.43547, -1.44158, 0.00000, 0.00000, 0.00000, -1.44730, -1.48888, -1.43701, -1.38292, -1.31890, -1.27008, -1.24587, -1.25533, -1.42677, -1.54595, -1.46264, -1.26648, -1.22820, -1.14912, -1.02185, -1.04715, -1.05721, -1.12603, -1.22997, -1.33642, -1.47185, -1.63790, -1.82174, -1.75974, -1.55122, -1.34191, -1.28914, -1.24811, -1.42202, -1.45526, -1.31860, -1.13632, -1.05593, -0.95537, -0.80436, -0.78294, -0.87842, -0.97454, -1.13708, -1.18483, -1.35070, -1.49939, -1.55410, -1.65623, -2.02633, -2.36297, -2.45962, -2.50646, -2.45141, -2.39730, -2.45169, -2.48091, -2.50479, -2.44090, -2.50296, -2.53492, -2.58964, -2.64181, -2.80725, -2.98291, -3.23951, -3.39769, -3.47097, -3.43830, -3.50654, -3.55304, -3.47164, -3.48586, -3.58831, -3.56701, -3.53780, -3.25925, -3.09910, -3.05071, -3.01980, -2.97483, -3.04302, -3.01856, -2.70610, -2.42542, -2.22786, -2.15252, -2.22793, -2.20268, -2.25082, -2.23018, -2.36897, -2.43553, -2.48374, -2.44774, -2.44921, -2.41404, -2.45797, -2.41332, -2.24179, -2.02128, -1.88936, -1.76272, -1.53065, -1.27019, -1.09872, -0.81100, -0.63738, -0.39727, -0.33563, -0.34713, -0.21451, 0.08132, 0.27619, 0.40228, 0.67329, 0.92890, 1.13140, 1.34561, 1.50019, 1.77587, 1.89293, 2.10436, 2.17301, 2.22891, 2.32347, 2.50510, 2.61547, 2.84469, 2.97858, 3.11374, 3.26622, 3.27962, 3.07767, 2.74089, 2.48505, 2.39772, 2.19146, 2.02519, 1.73335, 1.62941, 1.57580, 1.49353, 1.53807, 1.67564, 1.65548, 1.42786, 1.34699, 1.28822, 1.10806, 0.90508, 0.51816, 0.17560, -0.25300, -0.48161, -0.70123, -0.88631, -1.06106, -1.17590, -1.36621, -1.50895, -1.62029, -1.66641, -1.58091, -1.42676, -1.32866, -1.28846, -1.23092, -1.12485, -1.17437, -1.13028, -1.11930, -0.98109, -0.89834, -1.06479, -1.29277, -1.38108, -1.47673, -1.66294, -1.67848, -1.62830, -1.67699, -1.66284, -1.78254, -1.91463, -2.05934, -2.05787, -2.01444, -1.86675, -1.67455, -1.39907, -1.19968, -1.16219, -1.18885, -1.29903, -1.27484, -1.11035, -0.98990, -0.98237, -0.95477, -0.75081, -0.56090, -0.25309, 0.04307, 0.31265, 0.45107, 0.32001, 0.22873, 0.39646, 0.54392, 0.50892, 0.47910, 0.46854, 0.25577, 0.09559, -0.09816, -0.28854, -0.48568, -0.53913, -0.54757, -0.59890, -0.63212, -0.63308, -0.65756, -0.72742, -0.76031, -0.82091, -0.83026, -0.85749, -1.02029, -1.30444, -1.50303, -1.54771, -1.70736, -1.95190, -2.21844, -2.42812, -2.48606, -2.67170, -2.79683, -2.73387, -2.68440, -2.80968, -2.93414, -3.05002, -3.26827, -3.38257, -3.47026, -3.50403, -3.57098, -3.56187, -3.50388, -3.62514, -3.73616, -3.83120, -3.80167, -3.69178, -3.53229, -3.51058, -3.48946, -3.42481, -3.40289, -3.47760, -3.45801, -3.36249, -3.39221, -3.48831, -3.40512, -3.23625, -2.96111, -2.91397, -2.91633, -2.77004, -2.64557, -2.73170, -2.83271, -2.83227, -2.90933, -2.85883, -2.70785, -2.56421, -2.43859, -2.30165, -2.06839, -1.96844, -1.82609, -1.61804, -1.35399, -1.16518, -0.98460, -0.89133, -0.72795, -0.51413, -0.41781, -0.55386, -0.63572, -0.49642, -0.27175, -0.12172, 0.10571, 0.23133, 0.44689, 0.52096, 0.54239, 0.68241, 0.95265, 1.08228, 1.29771, 1.69021, 1.89344, 2.06617, 2.17787, 2.05544, 1.92962, 1.69519, 1.66491, 1.59527, 1.55444, 1.46693, 1.39169, 1.29261, 1.27246, 1.22036, 1.28396, 1.39630, 1.39548, 1.19982, 1.12594, 1.24363, 1.36656, 1.29037, 1.20642, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.34795, 0.21388, -0.02628, -0.31084, -0.49920, -0.75342, -0.85821, -0.98317, -0.97484, -1.13499, -1.29950, -1.40786, -1.37810, -1.35591, -1.32321, -1.46161, -1.58487, -1.58288, -1.50966, -1.57890, -1.66563, -1.66822, -1.60768, -1.63596, -1.60437, -1.65126, -1.46622, -1.24928, -0.96397, -0.52470, -0.05463, 0.26333, +-1.49220, -1.54148, -1.52395, -1.64062, -1.67289, -1.49446, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.63861, -1.61420, -1.58992, -1.70578, -1.77692, -1.76888, -1.75863, -1.78362, -1.92381, -1.98639, -1.86727, -1.74042, -1.65169, -1.49895, -1.46521, -1.50361, -1.43812, -1.27014, -1.32058, -1.44174, -1.45732, -1.43436, -1.38480, -1.34908, -1.36026, -1.41081, -1.61130, -1.75438, -1.65228, -1.37368, -1.23699, -1.16745, -1.11106, -1.14039, -1.11956, -1.25839, -1.43779, -1.48677, -1.53362, -1.62340, -1.72807, -1.64220, -1.42602, -1.22030, -1.22625, -1.16835, -1.29958, -1.33830, -1.24876, -1.02698, -0.91561, -0.86450, -0.74568, -0.73759, -0.86200, -0.97043, -1.11618, -1.16117, -1.36053, -1.53938, -1.57761, -1.65377, -1.96662, -2.33496, -2.51514, -2.59150, -2.56994, -2.59692, -2.70146, -2.66320, -2.59940, -2.53568, -2.60453, -2.68107, -2.78557, -2.84213, -2.96541, -3.00063, -3.16964, -3.40045, -3.63551, -3.59911, -3.60896, -3.67539, -3.62667, -3.65117, -3.74252, -3.71185, -3.63743, -3.29852, -3.09661, -3.04531, -3.01009, -2.94151, -2.92134, -2.95354, -2.78926, -2.54009, -2.30229, -2.20587, -2.27870, -2.20799, -2.17943, -2.18866, -2.38528, -2.52166, -2.65735, -2.61329, -2.62616, -2.57854, -2.56189, -2.55020, -2.52072, -2.31542, -2.14897, -2.04584, -1.82171, -1.56201, -1.41385, -1.12152, -0.88528, -0.58926, -0.48235, -0.48290, -0.32492, -0.02164, 0.20025, 0.26998, 0.41717, 0.64300, 0.87039, 1.05140, 1.13645, 1.40536, 1.59907, 1.84792, 2.06167, 2.26472, 2.36408, 2.51420, 2.54356, 2.77053, 2.98353, 3.11500, 3.10823, 3.07100, 2.92192, 2.57493, 2.33884, 2.32773, 2.18234, 2.04303, 1.77133, 1.69145, 1.66565, 1.52114, 1.51584, 1.66842, 1.75687, 1.60107, 1.48932, 1.41902, 1.28490, 1.06988, 0.60009, 0.25118, -0.09338, -0.25177, -0.39565, -0.56730, -0.78442, -0.93658, -1.19790, -1.36787, -1.44264, -1.48862, -1.52811, -1.44483, -1.34134, -1.32578, -1.28322, -1.16294, -1.19544, -1.13570, -1.08282, -0.92486, -0.85947, -1.07655, -1.32398, -1.38887, -1.41633, -1.61202, -1.75280, -1.80136, -1.85283, -1.81595, -1.86727, -1.87166, -1.90261, -1.89300, -1.84277, -1.68152, -1.51422, -1.27221, -1.15375, -1.14832, -1.10556, -1.16619, -1.18367, -0.99987, -0.77052, -0.72930, -0.72776, -0.51285, -0.32681, -0.10738, 0.11555, 0.37687, 0.54475, 0.44176, 0.37271, 0.55089, 0.75072, 0.70425, 0.53891, 0.41931, 0.19615, 0.08987, -0.11289, -0.30525, -0.43031, -0.47247, -0.48307, -0.55283, -0.64391, -0.68207, -0.73916, -0.84577, -0.85310, -0.86459, -0.92006, -0.99658, -1.09313, -1.33655, -1.53449, -1.56432, -1.72395, -1.96819, -2.19886, -2.33770, -2.35141, -2.55985, -2.73673, -2.71624, -2.65734, -2.73832, -2.82149, -2.91556, -3.13322, -3.26160, -3.41224, -3.44116, -3.40202, -3.32233, -3.25189, -3.36231, -3.49298, -3.62675, -3.59462, -3.47169, -3.25167, -3.18780, -3.25368, -3.28990, -3.25144, -3.36976, -3.43312, -3.33569, -3.32475, -3.37655, -3.25885, -3.05646, -2.75236, -2.74065, -2.81005, -2.68931, -2.53815, -2.51892, -2.62984, -2.70387, -2.78724, -2.72843, -2.61573, -2.49894, -2.31561, -2.10153, -1.84350, -1.75133, -1.66608, -1.50844, -1.25846, -1.10796, -0.90554, -0.75664, -0.63429, -0.55372, -0.48448, -0.61735, -0.72813, -0.55842, -0.30371, -0.17037, 0.01409, 0.11271, 0.31664, 0.40043, 0.49688, 0.70244, 0.95056, 1.07841, 1.21824, 1.51564, 1.70911, 1.89220, 1.95888, 1.81725, 1.77091, 1.64807, 1.69232, 1.70331, 1.68862, 1.57084, 1.48860, 1.38516, 1.40372, 1.38610, 1.42400, 1.46735, 1.54591, 1.47356, 1.41708, 1.53964, 1.67417, 1.54811, 1.39561, 1.17107, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.18646, -0.46049, -0.67119, -0.99321, -1.09475, -1.13314, -1.09954, -1.23049, -1.39840, -1.54109, -1.50918, -1.54203, -1.53001, -1.61422, -1.72155, -1.79180, -1.70470, -1.72359, -1.84205, -1.85756, -1.75746, -1.71921, -1.56388, -1.52206, -1.35705, -1.19548, -0.99619, -0.59590, -0.15424, 0.18439, +-1.59772, -1.70310, -1.79455, -1.86242, -1.77099, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.67306, -1.69616, -1.64670, -1.72968, -1.84838, -1.87593, -1.92238, -1.98952, -2.08705, -2.11550, -2.06838, -1.94906, -1.71474, -1.56287, -1.49883, -1.49054, -1.41911, -1.27422, -1.29159, -1.33360, -1.50086, -1.53509, -1.52364, -1.58388, -1.55655, -1.62930, -1.79983, -1.82001, -1.73349, -1.50016, -1.30150, -1.17097, -1.08584, -1.15070, -1.11874, -1.25598, -1.48956, -1.56922, -1.60368, -1.67893, -1.69220, -1.54712, -1.37963, -1.25669, -1.15690, -1.11297, -1.22168, -1.16321, -1.06857, -0.92558, -0.86578, -0.72065, -0.68632, -0.67723, -0.76834, -0.97393, -1.07320, -1.13713, -1.34906, -1.45287, -1.52505, -1.68826, -1.91624, -2.22866, -2.39761, -2.57395, -2.60350, -2.65260, -2.78760, -2.82335, -2.79294, -2.78522, -2.80888, -2.83111, -2.94059, -3.06509, -3.02805, -2.99592, -3.14401, -3.32942, -3.63665, -3.73018, -3.83725, -3.79038, -3.78721, -3.81360, -3.82402, -3.86647, -3.71517, -3.35541, -3.15354, -2.99364, -2.91556, -2.92678, -2.85039, -2.86845, -2.70682, -2.54850, -2.31417, -2.18445, -2.23162, -2.21295, -2.20495, -2.32306, -2.53761, -2.67541, -2.82216, -2.85383, -2.75573, -2.70708, -2.73244, -2.67464, -2.65239, -2.48255, -2.40480, -2.18524, -1.97730, -1.76964, -1.56789, -1.38249, -1.10841, -0.75577, -0.59411, -0.47093, -0.26371, -0.10596, 0.08964, 0.15190, 0.31272, 0.41920, 0.59635, 0.77208, 0.88018, 1.11558, 1.34315, 1.56638, 1.87602, 2.21218, 2.39088, 2.45059, 2.51215, 2.71023, 2.86548, 3.03924, 3.02722, 2.95933, 2.70117, 2.47575, 2.30517, 2.26808, 2.22881, 2.04258, 1.80899, 1.77796, 1.73876, 1.64629, 1.68545, 1.71671, 1.82111, 1.73344, 1.70475, 1.57793, 1.41173, 1.17240, 0.71796, 0.32950, 0.03756, -0.10622, -0.20756, -0.34792, -0.53663, -0.79451, -1.01130, -1.12407, -1.24992, -1.26751, -1.31129, -1.28626, -1.35421, -1.30487, -1.23378, -1.18348, -1.09802, -1.07423, -1.04565, -0.88195, -0.88474, -1.06043, -1.22882, -1.43608, -1.51599, -1.68484, -1.76699, -1.85083, -1.91882, -1.86130, -1.82202, -1.78672, -1.75662, -1.76023, -1.74598, -1.60158, -1.40351, -1.25852, -1.12899, -1.03188, -1.02182, -1.01985, -0.96355, -0.77718, -0.65276, -0.53920, -0.43878, -0.30764, -0.07228, 0.06641, 0.18156, 0.45392, 0.59290, 0.56799, 0.62760, 0.70306, 0.81242, 0.74746, 0.59815, 0.43738, 0.20275, 0.15471, 0.00120, -0.23285, -0.36356, -0.43155, -0.46547, -0.51255, -0.57197, -0.69263, -0.76822, -0.78371, -0.85376, -0.85865, -0.86622, -0.93394, -1.08218, -1.28581, -1.38989, -1.53212, -1.66172, -1.88687, -2.17240, -2.27439, -2.32608, -2.49970, -2.56144, -2.61072, -2.63890, -2.68448, -2.67930, -2.71329, -2.94275, -3.05525, -3.23217, -3.33334, -3.29240, -3.19107, -3.11933, -3.16806, -3.25159, -3.42360, -3.40827, -3.16996, -2.99910, -2.93622, -2.95625, -3.02789, -3.08663, -3.25410, -3.24322, -3.23630, -3.18811, -3.17449, -3.12692, -2.88869, -2.64185, -2.65646, -2.64101, -2.57015, -2.49064, -2.38998, -2.45702, -2.52127, -2.64975, -2.55948, -2.40996, -2.29053, -2.11145, -1.87006, -1.63717, -1.52158, -1.44532, -1.35826, -1.19740, -0.92574, -0.73061, -0.60795, -0.47141, -0.47605, -0.52385, -0.72606, -0.74618, -0.67442, -0.44362, -0.25623, -0.16335, -0.02263, 0.16111, 0.24838, 0.49323, 0.74276, 0.88775, 1.02789, 1.11622, 1.37905, 1.50663, 1.70829, 1.81112, 1.70494, 1.66635, 1.62772, 1.69569, 1.77001, 1.79491, 1.69305, 1.55772, 1.58605, 1.61856, 1.56869, 1.65227, 1.69484, 1.76632, 1.66617, 1.74112, 1.81089, 1.86454, 1.75846, 1.48305, 1.27758, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.47666, -0.67414, -1.00660, -1.19284, -1.23472, -1.25143, -1.33287, -1.44848, -1.58099, -1.66393, -1.64906, -1.64158, -1.75732, -1.82649, -1.92891, -1.88662, -1.99301, -1.97210, -1.94779, -1.86909, -1.70492, -1.55882, -1.44822, -1.26330, -1.16820, -1.00263, -0.63687, -0.35358, -0.02424, +-1.83758, -1.95205, -1.98091, -1.93937, -1.78055, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.68226, -1.73096, -1.82352, -1.80311, -1.85143, -1.95274, -2.00999, -2.13847, -2.25933, -2.33507, -2.26562, -2.11831, -2.04072, -1.82447, -1.61406, -1.50993, -1.48989, -1.43681, -1.26682, -1.21137, -1.26588, -1.48490, -1.59360, -1.68409, -1.78909, -1.73500, -1.74400, -1.83019, -1.81108, -1.74000, -1.51873, -1.32151, -1.23697, -1.23594, -1.34467, -1.31598, -1.38184, -1.58174, -1.70674, -1.78081, -1.82712, -1.76736, -1.55069, -1.29588, -1.24761, -1.21782, -1.18281, -1.27369, -1.15090, -1.04848, -0.92248, -0.82025, -0.68006, -0.67524, -0.68841, -0.81149, -0.99413, -1.00702, -1.03269, -1.19975, -1.32744, -1.49313, -1.70823, -1.91756, -2.18786, -2.35792, -2.58092, -2.70504, -2.79717, -2.93927, -3.01505, -3.02594, -3.05019, -3.04826, -2.95249, -2.88805, -3.05403, -3.10226, -3.07066, -3.21911, -3.38242, -3.68032, -3.81759, -3.90575, -3.89383, -3.93225, -3.92160, -3.91246, -3.92170, -3.67533, -3.30016, -3.08026, -2.93217, -2.92288, -2.92949, -2.79375, -2.73579, -2.61148, -2.56430, -2.42588, -2.29733, -2.30714, -2.32489, -2.37665, -2.55586, -2.79073, -2.91679, -2.91684, -2.95157, -2.95710, -2.96578, -3.05221, -2.98289, -2.92340, -2.73510, -2.54951, -2.25874, -2.03178, -1.81028, -1.61953, -1.47586, -1.16740, -0.81578, -0.60557, -0.41105, -0.22590, -0.13190, -0.02137, -0.00726, 0.09059, 0.13324, 0.26406, 0.43430, 0.60217, 0.90124, 1.15506, 1.35564, 1.67160, 2.06358, 2.42370, 2.50887, 2.49475, 2.63162, 2.70151, 2.82010, 2.79326, 2.75018, 2.59695, 2.45740, 2.33198, 2.30460, 2.26300, 2.05928, 1.89301, 1.92318, 1.95252, 1.95144, 1.94125, 1.87141, 1.91875, 1.84263, 1.79067, 1.59482, 1.36370, 1.10093, 0.67657, 0.29732, 0.03619, -0.08660, -0.19806, -0.35721, -0.44085, -0.67758, -0.97051, -1.11452, -1.27218, -1.27353, -1.28837, -1.25219, -1.25127, -1.18161, -1.13963, -1.13664, -1.05290, -1.01208, -0.91870, -0.77389, -0.84835, -1.03100, -1.23981, -1.49649, -1.58385, -1.73013, -1.78195, -1.81852, -1.88793, -1.85912, -1.81218, -1.76426, -1.72586, -1.72928, -1.71498, -1.60115, -1.33239, -1.18577, -1.13544, -1.02369, -1.00797, -0.97131, -0.87333, -0.69662, -0.53135, -0.38320, -0.28827, -0.16767, 0.08550, 0.25551, 0.39044, 0.64004, 0.76393, 0.80705, 0.87861, 0.87634, 0.91065, 0.79330, 0.58400, 0.36650, 0.13028, 0.10637, -0.03554, -0.29658, -0.46423, -0.55518, -0.60462, -0.65755, -0.61777, -0.63293, -0.73955, -0.75311, -0.81226, -0.82547, -0.81671, -0.88868, -0.96227, -1.04467, -1.11664, -1.33474, -1.54990, -1.80437, -2.05273, -2.10173, -2.14530, -2.29052, -2.31964, -2.37151, -2.43334, -2.52022, -2.55271, -2.60111, -2.82695, -2.92744, -3.08621, -3.22546, -3.23687, -3.18623, -3.11037, -3.08942, -3.05895, -3.08474, -3.09979, -2.94091, -2.83506, -2.85905, -2.90892, -2.98047, -2.96580, -2.97290, -2.94235, -2.99572, -2.95732, -2.90967, -2.82410, -2.56809, -2.37602, -2.41590, -2.43519, -2.45565, -2.40437, -2.30737, -2.41520, -2.54219, -2.70115, -2.60183, -2.42186, -2.28347, -2.09528, -1.82990, -1.58036, -1.42060, -1.28742, -1.11298, -1.03855, -0.88423, -0.71098, -0.60389, -0.47185, -0.55227, -0.67146, -0.80009, -0.80242, -0.76690, -0.56309, -0.40485, -0.26433, -0.01001, 0.17214, 0.24586, 0.48947, 0.70303, 0.83586, 0.98740, 1.04801, 1.20556, 1.24633, 1.38107, 1.50516, 1.47559, 1.47904, 1.49706, 1.59823, 1.69694, 1.76147, 1.78116, 1.62823, 1.60745, 1.68952, 1.68181, 1.76472, 1.77450, 1.85492, 1.90300, 2.02828, 2.04770, 2.03949, 1.88360, 1.59667, 1.46098, 1.43971, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.81196, -1.08854, -1.29113, -1.38397, -1.45583, -1.55380, -1.61303, -1.55819, -1.62921, -1.74757, -1.80832, -1.94340, -2.00016, -2.09745, -2.06395, -2.07034, -1.93230, -1.83781, -1.75980, -1.62560, -1.48552, -1.29288, -1.09087, -0.99640, -0.87555, -0.66658, -0.50874, -0.24608, +-1.97672, -2.14064, -2.17905, -2.03439, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.56107, -1.66346, -1.80730, -1.96929, -2.00683, -2.04292, -2.10409, -2.04629, -2.15158, -2.33217, -2.38170, -2.28254, -2.05395, -1.88678, -1.74796, -1.56260, -1.36814, -1.34218, -1.42209, -1.38100, -1.29988, -1.40489, -1.60084, -1.62638, -1.70340, -1.87295, -1.89667, -1.78716, -1.72137, -1.73333, -1.65525, -1.45099, -1.25630, -1.22335, -1.37687, -1.53267, -1.50194, -1.49621, -1.66400, -1.77209, -1.86298, -1.94890, -1.84630, -1.64467, -1.37042, -1.21730, -1.21109, -1.24191, -1.21841, -1.05259, -1.04236, -1.04890, -0.91270, -0.78325, -0.79141, -0.78584, -0.87357, -1.04913, -1.09109, -1.07638, -1.13611, -1.36968, -1.57674, -1.80100, -2.00856, -2.20600, -2.38397, -2.55654, -2.67122, -2.77598, -2.92808, -2.96135, -2.93509, -3.04267, -3.06184, -2.95664, -2.86905, -2.98193, -3.10147, -3.19612, -3.26069, -3.37922, -3.64038, -3.83837, -3.92317, -4.00461, -4.10914, -4.02072, -3.89246, -3.87127, -3.70146, -3.38073, -3.06688, -3.00184, -3.02202, -2.93545, -2.70531, -2.51902, -2.48482, -2.56664, -2.54852, -2.46572, -2.47376, -2.48814, -2.50116, -2.71168, -2.93847, -3.07528, -3.05765, -3.03632, -3.08781, -3.25308, -3.29298, -3.15691, -3.07307, -2.97379, -2.73892, -2.42071, -2.19314, -1.92600, -1.64962, -1.53747, -1.32599, -1.07655, -0.79018, -0.59685, -0.39678, -0.20733, -0.08130, -0.04390, -0.02578, 0.00448, 0.14685, 0.32739, 0.53536, 0.89104, 1.22479, 1.34992, 1.58852, 1.94843, 2.31862, 2.49589, 2.61225, 2.69191, 2.76322, 2.83884, 2.76426, 2.64070, 2.54221, 2.44676, 2.28266, 2.24812, 2.29866, 2.12080, 1.94183, 1.97512, 2.16141, 2.20576, 2.10738, 1.99335, 1.96335, 1.88733, 1.75339, 1.47512, 1.22859, 1.02047, 0.65698, 0.31628, 0.16287, -0.00565, -0.20322, -0.40952, -0.51509, -0.66909, -0.88395, -1.14776, -1.31538, -1.26710, -1.25531, -1.29794, -1.27743, -1.19570, -1.21510, -1.27322, -1.14908, -1.05265, -0.94886, -0.85042, -0.86292, -1.05637, -1.32171, -1.48381, -1.49806, -1.56013, -1.59174, -1.62282, -1.70654, -1.72340, -1.73796, -1.72894, -1.63016, -1.65003, -1.60237, -1.44916, -1.22801, -1.08521, -0.96167, -0.88572, -0.84409, -0.74262, -0.68050, -0.66536, -0.55696, -0.40781, -0.36844, -0.24613, 0.10575, 0.38184, 0.49274, 0.61839, 0.77312, 0.87142, 0.89854, 0.91712, 0.95635, 0.87814, 0.63466, 0.33244, 0.09219, 0.06523, -0.09741, -0.38076, -0.48068, -0.56475, -0.67183, -0.74845, -0.73849, -0.68244, -0.66105, -0.68833, -0.72718, -0.65415, -0.62880, -0.83190, -0.96212, -0.94220, -1.00101, -1.22936, -1.42770, -1.64587, -1.87721, -1.94710, -1.92051, -2.00586, -2.08460, -2.09031, -2.15524, -2.26711, -2.35588, -2.48234, -2.68782, -2.73779, -2.78205, -2.88497, -2.89196, -2.91084, -2.90464, -2.82449, -2.75818, -2.71912, -2.68169, -2.63826, -2.65130, -2.68853, -2.78121, -2.92938, -2.92827, -2.77798, -2.76782, -2.88040, -2.81195, -2.66150, -2.55382, -2.40259, -2.22878, -2.19748, -2.31841, -2.37883, -2.33082, -2.26137, -2.39551, -2.61070, -2.74918, -2.59804, -2.38685, -2.25256, -2.03366, -1.73198, -1.52254, -1.32067, -1.17296, -0.99130, -0.88650, -0.85762, -0.80669, -0.61201, -0.44543, -0.58395, -0.81741, -0.87964, -0.87735, -0.85095, -0.62702, -0.42191, -0.25615, -0.04355, 0.10386, 0.22136, 0.35748, 0.56776, 0.77255, 1.00308, 1.18407, 1.26126, 1.21400, 1.26296, 1.38505, 1.41135, 1.48597, 1.56272, 1.58080, 1.66324, 1.73135, 1.75280, 1.67926, 1.67903, 1.72646, 1.84594, 1.91133, 1.81394, 1.75874, 1.89012, 2.02192, 1.97978, 1.99282, 1.95694, 1.71982, 1.56356, 1.53386, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.93083, -1.14539, -1.31890, -1.39609, -1.58277, -1.76452, -1.81285, -1.68315, -1.61301, -1.66795, -1.82650, -1.88914, -1.88962, -1.97954, -2.05760, -2.03063, -1.84755, -1.76912, -1.70902, -1.54302, -1.42130, -1.26944, -1.11006, -0.88118, -0.74343, -0.62360, -0.50199, -0.28814, +-2.08755, -2.14435, -2.21779, -2.08111, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.75870, -1.77592, -1.86602, -2.05100, -2.11373, -2.14836, -2.18673, -2.11531, -2.17034, -2.23092, -2.18197, -2.14819, -2.02257, -1.81044, -1.66594, -1.59122, -1.47669, -1.38491, -1.39202, -1.41735, -1.40357, -1.50897, -1.62952, -1.64057, -1.75230, -1.86315, -1.80462, -1.69037, -1.63386, -1.56404, -1.43621, -1.36545, -1.29578, -1.22247, -1.32983, -1.51773, -1.50465, -1.51237, -1.70780, -1.86832, -2.01579, -2.02361, -1.81068, -1.67442, -1.53512, -1.30009, -1.19911, -1.25899, -1.24918, -1.02088, -0.91900, -0.98805, -0.90776, -0.73278, -0.67118, -0.70299, -0.88484, -1.03976, -1.01367, -1.05745, -1.23878, -1.47863, -1.59522, -1.87660, -2.19170, -2.30328, -2.32904, -2.40550, -2.42091, -2.49687, -2.66614, -2.74764, -2.81978, -2.92650, -2.90226, -2.92497, -3.05626, -3.15617, -3.19289, -3.30023, -3.38513, -3.45744, -3.54055, -3.71834, -3.88506, -4.00387, -4.07209, -3.98353, -3.91194, -3.86926, -3.66568, -3.41420, -3.18349, -3.06294, -2.90633, -2.78211, -2.62729, -2.41132, -2.33446, -2.49189, -2.54205, -2.50677, -2.53493, -2.58078, -2.66882, -2.81073, -2.89416, -3.05410, -3.20700, -3.20052, -3.18764, -3.39268, -3.46110, -3.25702, -3.00456, -2.90860, -2.76828, -2.48431, -2.21007, -1.96475, -1.81451, -1.75190, -1.49649, -1.30778, -1.14269, -0.92775, -0.56112, -0.28041, -0.19521, -0.12399, 0.01099, 0.06456, 0.23133, 0.43398, 0.64722, 0.94239, 1.15696, 1.27159, 1.60441, 1.95472, 2.15617, 2.31999, 2.61102, 2.76450, 2.80156, 2.85179, 2.88008, 2.75705, 2.58817, 2.46926, 2.33057, 2.29627, 2.30324, 2.18427, 2.17061, 2.25551, 2.35241, 2.33528, 2.26874, 2.11139, 1.89017, 1.74470, 1.69025, 1.41497, 1.20986, 1.09499, 0.80136, 0.48673, 0.26092, 0.05948, -0.06740, -0.28414, -0.53146, -0.69066, -0.78293, -1.04079, -1.29379, -1.29226, -1.17682, -1.21199, -1.29166, -1.26139, -1.23855, -1.29623, -1.26746, -1.19430, -0.99664, -0.82870, -0.87901, -1.08513, -1.21939, -1.28668, -1.35730, -1.40163, -1.30540, -1.33668, -1.45903, -1.49710, -1.53150, -1.54101, -1.55311, -1.62844, -1.43722, -1.19231, -1.09304, -1.02552, -0.80322, -0.67487, -0.66775, -0.61871, -0.53603, -0.54044, -0.52463, -0.41665, -0.32725, -0.17279, 0.10162, 0.30794, 0.45211, 0.60187, 0.68648, 0.76653, 0.91997, 1.02398, 0.99207, 0.89131, 0.74296, 0.47025, 0.22563, 0.20622, 0.04979, -0.22662, -0.36500, -0.46716, -0.49626, -0.54013, -0.67227, -0.72698, -0.61243, -0.57418, -0.64119, -0.58329, -0.46571, -0.61754, -0.82173, -0.84628, -0.86329, -1.00708, -1.22893, -1.50301, -1.66133, -1.65157, -1.66485, -1.79746, -1.82304, -1.79886, -1.98533, -2.19058, -2.19346, -2.21661, -2.38481, -2.38906, -2.32901, -2.37441, -2.46250, -2.60197, -2.57185, -2.41812, -2.41913, -2.50879, -2.45364, -2.38699, -2.46818, -2.56941, -2.62136, -2.68787, -2.73547, -2.65811, -2.65718, -2.71128, -2.65746, -2.53939, -2.37241, -2.18210, -2.07001, -2.10406, -2.19895, -2.20699, -2.26073, -2.32115, -2.39102, -2.47984, -2.54543, -2.31639, -2.07049, -1.95242, -1.83205, -1.65749, -1.42919, -1.14884, -1.07023, -1.04312, -0.91494, -0.85537, -0.87573, -0.74025, -0.52883, -0.49951, -0.72179, -0.83708, -0.82253, -0.74491, -0.56824, -0.46875, -0.31981, -0.09489, -0.01734, 0.00798, 0.20020, 0.57671, 0.78779, 0.95266, 1.25657, 1.46761, 1.38797, 1.39659, 1.49313, 1.50523, 1.53491, 1.48450, 1.48242, 1.67148, 1.74196, 1.64872, 1.63593, 1.74512, 1.76179, 1.78614, 1.80619, 1.79600, 1.70018, 1.76016, 1.88196, 1.88609, 1.92676, 1.88404, 1.71916, 1.68671, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.87347, -1.08763, -1.31098, -1.51867, -1.72903, -1.82747, -1.87852, -1.87122, -1.73029, -1.57474, -1.66946, -1.75873, -1.74524, -1.70632, -1.80332, -1.87894, -1.77444, -1.72304, -1.70273, -1.62677, -1.48320, -1.21036, -1.04594, -0.88681, -0.69470, -0.43425, -0.32057, -0.24127, +-2.20197, -2.14397, -2.12463, -2.04019, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.88515, -1.95761, -1.99211, -2.06592, -2.21284, -2.23406, -2.24185, -2.31704, -2.21678, -2.08100, -2.09409, -2.01994, -1.98188, -1.96456, -1.80442, -1.71802, -1.69938, -1.70343, -1.66891, -1.57078, -1.48107, -1.47106, -1.61990, -1.68667, -1.73941, -1.72149, -1.74382, -1.73095, -1.64674, -1.52541, -1.34347, -1.33036, -1.38236, -1.36387, -1.29789, -1.36851, -1.53624, -1.52475, -1.57352, -1.85029, -2.01442, -2.01229, -1.95879, -1.74471, -1.59779, -1.53961, -1.28439, -1.14184, -1.15050, -1.15987, -1.02161, -0.84669, -0.85250, -0.74885, -0.60047, -0.47722, -0.58305, -0.68524, -0.76609, -0.83658, -0.98387, -1.24993, -1.43834, -1.62519, -1.94465, -2.22409, -2.30474, -2.29620, -2.30121, -2.20964, -2.24022, -2.45361, -2.61513, -2.65575, -2.79093, -2.87854, -2.99103, -3.27356, -3.39096, -3.37807, -3.38877, -3.43352, -3.58140, -3.56749, -3.68283, -3.83643, -4.05178, -4.07880, -4.05739, -3.92173, -3.78160, -3.67739, -3.50424, -3.29911, -3.00312, -2.78075, -2.65852, -2.50388, -2.35292, -2.34994, -2.52909, -2.56204, -2.52425, -2.58830, -2.69738, -2.70664, -2.75977, -2.84874, -2.97320, -3.21001, -3.25906, -3.25026, -3.42871, -3.44305, -3.29391, -2.96904, -2.83414, -2.67339, -2.51601, -2.22544, -2.08446, -1.99818, -1.89168, -1.72108, -1.57786, -1.44157, -1.09721, -0.72117, -0.45086, -0.29924, -0.18455, -0.02798, 0.03274, 0.22406, 0.45001, 0.64662, 0.81807, 1.05358, 1.22758, 1.52204, 1.92511, 2.07368, 2.20466, 2.54235, 2.75270, 2.85130, 2.80934, 2.86721, 2.78699, 2.68585, 2.48095, 2.37608, 2.31064, 2.34010, 2.43084, 2.49734, 2.57971, 2.57603, 2.54186, 2.38436, 2.10649, 1.82908, 1.66006, 1.58835, 1.31853, 1.19108, 1.18156, 0.96575, 0.63286, 0.43705, 0.27496, 0.07011, -0.13876, -0.39859, -0.55917, -0.61732, -0.85982, -1.07950, -1.19937, -1.10451, -1.13790, -1.21989, -1.30841, -1.25793, -1.29616, -1.28349, -1.10178, -0.93085, -0.78559, -0.84833, -0.92836, -0.98064, -1.10834, -1.19692, -1.20276, -1.10826, -1.19908, -1.34096, -1.37687, -1.38117, -1.41324, -1.43361, -1.45618, -1.31003, -1.04859, -0.95564, -0.92508, -0.68482, -0.54169, -0.48116, -0.53383, -0.52275, -0.51649, -0.45950, -0.39149, -0.25235, -0.08414, 0.08569, 0.30390, 0.40726, 0.51897, 0.58281, 0.78154, 1.04337, 1.08446, 1.03768, 0.99168, 0.87585, 0.60756, 0.37287, 0.35894, 0.23187, -0.06031, -0.16202, -0.14331, -0.20349, -0.27161, -0.42246, -0.54872, -0.42683, -0.40185, -0.45983, -0.47399, -0.38778, -0.44422, -0.57427, -0.66532, -0.73187, -0.82057, -1.07078, -1.23337, -1.33788, -1.39464, -1.47248, -1.54840, -1.51301, -1.64536, -1.92639, -2.12390, -2.07210, -2.01285, -2.11388, -2.07200, -1.95027, -2.01893, -2.16210, -2.26487, -2.30290, -2.20681, -2.20742, -2.36218, -2.31690, -2.25766, -2.30904, -2.41825, -2.49088, -2.47401, -2.50103, -2.53400, -2.62846, -2.59577, -2.55706, -2.31765, -2.08991, -2.00749, -1.96383, -1.96150, -1.95396, -2.06666, -2.22238, -2.30244, -2.33168, -2.33709, -2.29366, -1.97293, -1.69053, -1.61876, -1.58642, -1.38421, -1.19380, -1.00923, -0.96336, -1.01410, -0.87499, -0.78441, -0.77788, -0.69396, -0.58728, -0.43600, -0.54909, -0.64414, -0.71233, -0.61740, -0.56063, -0.43864, -0.27753, -0.21018, -0.20277, -0.16399, 0.21580, 0.62312, 0.80923, 0.98796, 1.31032, 1.52711, 1.43771, 1.44240, 1.50544, 1.44635, 1.38849, 1.38039, 1.38446, 1.53144, 1.66523, 1.59659, 1.66453, 1.81552, 1.81092, 1.73343, 1.59514, 1.65705, 1.62791, 1.71717, 1.72245, 1.75935, 1.76871, 1.83137, 1.82816, 1.76699, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.77829, -1.05412, -1.39757, -1.57509, -1.73208, -1.85136, -1.84902, -1.88807, -1.72883, -1.46678, -1.47014, -1.51927, -1.61548, -1.55950, -1.64621, -1.71539, -1.80708, -1.81677, -1.87332, -1.77204, -1.44223, -1.14054, -0.98726, -0.86432, -0.54055, -0.26452, -0.22300, -0.15857, +-2.15595, -2.06957, -1.99042, -1.92062, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -1.99175, -2.04723, -2.14499, -2.21914, -2.33528, -2.32795, -2.29617, -2.36881, -2.31694, -2.15163, -2.12545, -2.02373, -1.91130, -1.88361, -1.85807, -1.90558, -1.89476, -1.86239, -1.87404, -1.79617, -1.62914, -1.54834, -1.66690, -1.71194, -1.81475, -1.81589, -1.82352, -1.83273, -1.72072, -1.53704, -1.36535, -1.40894, -1.44672, -1.42118, -1.42858, -1.47818, -1.62165, -1.67687, -1.75739, -1.98792, -2.06887, -1.95027, -1.81009, -1.62895, -1.47365, -1.35522, -1.12908, -0.99793, -0.93509, -0.87865, -0.85071, -0.75596, -0.70283, -0.52775, -0.37835, -0.28508, -0.43552, -0.51766, -0.54711, -0.66993, -0.87843, -1.18528, -1.41938, -1.66691, -1.86908, -1.95719, -2.06719, -2.14943, -2.20590, -2.16063, -2.15002, -2.30875, -2.50642, -2.63272, -2.84859, -3.04267, -3.18244, -3.36666, -3.49903, -3.53799, -3.47667, -3.39064, -3.53340, -3.57009, -3.70220, -3.85416, -4.09376, -4.14071, -4.14662, -4.03056, -3.85285, -3.75565, -3.61860, -3.41971, -3.09979, -2.84793, -2.63828, -2.37764, -2.33222, -2.42900, -2.56128, -2.57430, -2.48888, -2.54213, -2.70732, -2.76141, -2.78552, -2.84567, -2.92567, -3.06262, -3.19375, -3.29014, -3.42800, -3.30789, -3.17431, -2.96090, -2.85703, -2.65863, -2.51027, -2.27032, -2.22365, -2.26457, -2.18121, -2.03276, -1.83336, -1.58232, -1.22440, -0.95382, -0.69689, -0.36913, -0.20014, -0.08159, -0.02288, 0.07232, 0.26939, 0.50684, 0.66192, 0.89928, 1.08416, 1.33812, 1.75943, 2.05077, 2.21920, 2.49067, 2.67249, 2.86159, 2.82966, 2.82351, 2.75587, 2.71525, 2.55570, 2.49597, 2.40624, 2.36285, 2.51334, 2.66573, 2.76233, 2.73374, 2.58798, 2.29519, 2.02709, 1.93309, 1.80196, 1.60779, 1.30617, 1.14140, 1.19120, 1.12258, 0.84510, 0.61197, 0.37649, 0.10287, -0.09227, -0.19464, -0.30554, -0.44329, -0.70905, -0.80310, -0.88966, -0.90121, -1.02555, -1.15308, -1.25992, -1.18823, -1.15497, -1.14264, -0.99323, -0.90428, -0.81822, -0.80717, -0.79454, -0.85616, -1.00003, -0.99097, -0.96660, -0.96829, -1.09960, -1.29030, -1.35866, -1.30726, -1.29478, -1.32184, -1.34064, -1.25996, -1.06568, -0.88531, -0.79236, -0.61706, -0.51511, -0.37673, -0.36760, -0.40622, -0.47769, -0.45840, -0.36665, -0.15411, 0.01286, 0.05821, 0.15008, 0.21673, 0.37699, 0.58243, 0.88275, 1.07603, 1.05381, 1.11775, 1.20168, 1.10003, 0.83610, 0.54141, 0.43431, 0.35649, 0.14745, 0.08479, 0.10825, -0.01126, -0.11195, -0.13755, -0.14951, -0.09146, -0.17913, -0.23768, -0.21219, -0.15716, -0.18370, -0.26222, -0.39186, -0.53325, -0.66569, -0.93278, -1.07326, -1.15048, -1.23201, -1.31704, -1.36004, -1.38787, -1.60449, -1.80566, -1.91666, -1.89870, -1.82834, -1.89861, -1.86949, -1.72437, -1.80716, -2.01140, -2.17306, -2.29893, -2.27956, -2.22895, -2.23058, -2.18522, -2.22039, -2.26473, -2.25516, -2.27054, -2.28122, -2.34632, -2.46018, -2.55901, -2.44198, -2.33747, -2.10121, -1.94305, -1.95650, -1.93410, -1.84665, -1.82080, -2.00538, -2.14181, -2.14986, -2.16589, -2.12600, -2.00581, -1.71233, -1.42663, -1.31731, -1.27963, -1.09830, -0.98099, -0.92193, -0.88821, -0.80359, -0.63857, -0.54423, -0.50016, -0.40336, -0.40302, -0.33840, -0.40220, -0.44979, -0.52496, -0.48009, -0.53454, -0.50773, -0.40342, -0.39061, -0.36179, -0.24942, 0.16091, 0.54220, 0.80569, 1.12287, 1.37304, 1.45560, 1.32712, 1.24356, 1.26365, 1.20867, 1.11692, 1.13204, 1.15167, 1.23010, 1.37621, 1.53243, 1.72255, 1.82801, 1.77327, 1.69058, 1.53980, 1.60971, 1.67091, 1.77668, 1.68452, 1.65151, 1.61679, 1.69480, 1.76115, 1.69735, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.75298, -1.04832, -1.44591, -1.62579, -1.73021, -1.80482, -1.76640, -1.70495, -1.56709, -1.38043, -1.34885, -1.29179, -1.39253, -1.44589, -1.59745, -1.69735, -1.87256, -1.92194, -1.99098, -1.91553, -1.53248, -1.18729, -0.97992, -0.77132, -0.45353, -0.29841, -0.26518, -0.06220, +-2.12518, -1.98779, -1.87461, -1.83917, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.03478, -2.16730, -2.22275, -2.16294, -2.17105, -2.27660, -2.40067, -2.44241, -2.42927, -2.33685, -2.22052, -2.13266, -2.11016, -2.06727, -2.06299, -2.16567, -2.12244, -2.02270, -2.02384, -1.92193, -1.75618, -1.68568, -1.80891, -1.79024, -1.78826, -1.92217, -1.98885, -1.85884, -1.70795, -1.63295, -1.52710, -1.43059, -1.39929, -1.54378, -1.65510, -1.63176, -1.67835, -1.81599, -1.97097, -2.00707, -1.90634, -1.71218, -1.44923, -1.33094, -1.33092, -1.23071, -1.00020, -0.86361, -0.77303, -0.69165, -0.66779, -0.51851, -0.37982, -0.21099, -0.15403, -0.12119, -0.17111, -0.32529, -0.41322, -0.44111, -0.65049, -1.05191, -1.31504, -1.44950, -1.50902, -1.68577, -1.90266, -1.96572, -2.03452, -2.13138, -2.26322, -2.37099, -2.50511, -2.69267, -2.91400, -3.13264, -3.34002, -3.45077, -3.51140, -3.58543, -3.58228, -3.50229, -3.61359, -3.60492, -3.69913, -3.87494, -4.13364, -4.18696, -4.04169, -3.97861, -3.87846, -3.63618, -3.47522, -3.44666, -3.27116, -2.97749, -2.65229, -2.48287, -2.49753, -2.44003, -2.38168, -2.35090, -2.37387, -2.46950, -2.62235, -2.75364, -2.78364, -2.79108, -2.95610, -3.09968, -3.17345, -3.25013, -3.36142, -3.23808, -3.17107, -3.02173, -2.91563, -2.73950, -2.61881, -2.47640, -2.35133, -2.40764, -2.40034, -2.14711, -1.83909, -1.65968, -1.42434, -1.16301, -0.84176, -0.57589, -0.45794, -0.26310, -0.08796, -0.01645, 0.02235, 0.26313, 0.56690, 0.87182, 1.07905, 1.33653, 1.58670, 1.81840, 2.08321, 2.38113, 2.53519, 2.72975, 2.73548, 2.79432, 2.84662, 2.85078, 2.75037, 2.69779, 2.70769, 2.62308, 2.59052, 2.76372, 2.90920, 2.76694, 2.50391, 2.26372, 2.18622, 2.13633, 1.91733, 1.68523, 1.45319, 1.29004, 1.20659, 1.13858, 0.97766, 0.76767, 0.52634, 0.33895, 0.08248, -0.09245, -0.17603, -0.31963, -0.60090, -0.65920, -0.72075, -0.76350, -0.86485, -0.96566, -1.04279, -1.02620, -0.88266, -0.84961, -0.90423, -0.86877, -0.76132, -0.79748, -0.84209, -0.88189, -0.85240, -0.82514, -0.92274, -0.92625, -0.90856, -1.00034, -1.19795, -1.27173, -1.23560, -1.25090, -1.26884, -1.12441, -1.04529, -0.97800, -0.80913, -0.58075, -0.47741, -0.33011, -0.25557, -0.23703, -0.27511, -0.29713, -0.26578, -0.13834, 0.06453, 0.13391, 0.06766, 0.16803, 0.50363, 0.77136, 0.97594, 1.05942, 1.13838, 1.23414, 1.23141, 1.16984, 1.04570, 0.85018, 0.63818, 0.49581, 0.40751, 0.37884, 0.32636, 0.24232, 0.07913, -0.01983, 0.05846, 0.14137, 0.01815, -0.01933, 0.04347, 0.10237, 0.13222, 0.04660, -0.15972, -0.42432, -0.59163, -0.76794, -1.00206, -1.08263, -1.00581, -1.08492, -1.24794, -1.32563, -1.36237, -1.44492, -1.67835, -1.77290, -1.67536, -1.65546, -1.70770, -1.69353, -1.75606, -1.95303, -2.16671, -2.24236, -2.28249, -2.34770, -2.23946, -2.08653, -2.14959, -2.23168, -2.22039, -2.20726, -2.16740, -2.20600, -2.31347, -2.36815, -2.16539, -1.89268, -1.81095, -1.83368, -1.79473, -1.81011, -1.84382, -1.86412, -1.92145, -1.91956, -1.97564, -1.96809, -1.77283, -1.54441, -1.37167, -1.24344, -1.08554, -0.97123, -0.81739, -0.68959, -0.67076, -0.71197, -0.54808, -0.29610, -0.19627, -0.20999, -0.18355, -0.26600, -0.25697, -0.29498, -0.35190, -0.44519, -0.42614, -0.41186, -0.52297, -0.51845, -0.32917, -0.21084, -0.20402, 0.05552, 0.44646, 0.81901, 1.05110, 1.18504, 1.27007, 1.20669, 1.06468, 0.95171, 0.92235, 0.89139, 0.95426, 1.06576, 1.13820, 1.13446, 1.29402, 1.58772, 1.71256, 1.65403, 1.62922, 1.58748, 1.75986, 1.93140, 1.97612, 1.75815, 1.60073, 1.59451, 1.58630, 1.54455, 1.58277, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.54286, -0.79654, -1.08794, -1.36243, -1.49927, -1.54108, -1.55111, -1.65740, -1.67646, -1.54046, -1.42470, -1.42851, -1.36654, -1.43991, -1.47717, -1.60629, -1.74617, -1.91472, -1.94806, -1.86172, -1.79676, -1.59562, -1.20972, -0.88207, -0.70532, -0.50448, -0.38617, -0.22850, -0.03443, +-2.15882, -2.08280, -1.98462, -1.95717, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.14820, -2.23585, -2.24365, -2.16864, -2.13675, -2.30299, -2.49310, -2.52368, -2.52394, -2.45722, -2.37313, -2.32934, -2.30030, -2.21307, -2.23289, -2.36976, -2.29834, -2.16403, -2.18878, -2.14948, -2.03856, -1.98279, -2.04419, -1.93223, -1.82329, -1.90969, -2.04107, -1.94273, -1.70686, -1.58395, -1.54383, -1.47724, -1.44737, -1.63989, -1.82654, -1.87993, -1.88360, -1.94279, -1.99629, -1.85403, -1.65864, -1.43428, -1.19305, -1.14290, -1.15921, -1.03977, -0.85006, -0.76107, -0.66855, -0.56052, -0.47850, -0.31136, -0.14617, 0.00920, 0.03747, 0.08110, 0.06918, -0.06996, -0.25045, -0.37408, -0.52931, -0.78540, -1.01617, -1.16939, -1.24167, -1.52691, -1.83682, -1.95774, -2.03908, -2.14488, -2.32703, -2.41227, -2.51595, -2.68514, -2.92649, -3.18145, -3.35376, -3.38437, -3.42993, -3.57858, -3.66993, -3.64919, -3.76207, -3.76099, -3.79232, -3.92543, -4.13316, -4.08753, -3.85025, -3.71658, -3.66155, -3.51916, -3.36095, -3.29342, -3.22759, -3.07582, -2.78413, -2.65217, -2.63358, -2.50526, -2.35776, -2.24235, -2.29661, -2.38896, -2.54238, -2.69693, -2.77967, -2.84683, -3.02702, -3.10603, -3.09468, -3.15510, -3.26652, -3.18908, -3.19729, -3.16099, -3.10079, -2.98585, -2.91184, -2.75896, -2.58874, -2.51098, -2.46977, -2.29649, -1.98959, -1.76740, -1.57280, -1.36009, -1.03149, -0.79730, -0.70405, -0.53604, -0.30950, -0.14397, -0.11597, 0.18720, 0.57438, 0.93831, 1.14813, 1.31914, 1.46154, 1.68270, 1.98188, 2.28835, 2.47325, 2.68362, 2.73625, 2.83046, 2.97152, 3.03729, 2.99031, 3.00667, 3.05260, 3.01480, 2.88071, 2.83574, 2.90290, 2.82517, 2.60289, 2.37233, 2.32176, 2.24282, 1.96460, 1.66968, 1.46047, 1.36584, 1.24687, 1.20282, 1.08106, 0.93694, 0.77592, 0.60590, 0.33336, 0.14967, 0.05428, -0.12341, -0.42154, -0.51779, -0.61003, -0.72156, -0.81741, -0.84809, -0.87722, -0.83564, -0.71217, -0.69368, -0.80086, -0.87878, -0.80570, -0.75117, -0.76123, -0.82574, -0.73769, -0.69185, -0.82617, -0.86280, -0.80218, -0.79370, -0.99416, -1.10511, -1.12156, -1.14798, -1.15372, -1.00627, -0.93532, -0.86373, -0.65741, -0.41633, -0.30415, -0.15814, -0.06076, -0.05433, -0.09568, -0.11760, -0.14167, -0.05971, 0.13758, 0.25711, 0.22969, 0.27376, 0.56303, 0.89048, 1.08775, 1.08297, 1.16008, 1.24897, 1.21228, 1.14379, 1.06072, 1.00921, 0.89617, 0.80895, 0.76344, 0.72153, 0.62467, 0.50324, 0.29267, 0.16289, 0.25220, 0.31439, 0.18890, 0.19695, 0.27184, 0.26782, 0.20354, 0.04626, -0.18422, -0.42468, -0.55796, -0.65973, -0.84403, -0.96110, -0.87686, -0.85131, -0.95418, -1.05211, -1.05827, -1.12675, -1.43075, -1.65994, -1.68112, -1.64064, -1.66850, -1.63835, -1.65400, -1.84567, -2.05584, -2.12512, -2.19651, -2.27885, -2.12977, -1.96963, -2.05052, -2.13303, -2.15979, -2.20017, -2.18738, -2.18101, -2.19998, -2.15899, -1.91006, -1.61964, -1.58010, -1.73736, -1.79997, -1.80173, -1.79752, -1.84873, -1.89123, -1.77719, -1.74589, -1.69394, -1.48521, -1.22606, -1.04619, -0.93473, -0.74807, -0.64818, -0.51692, -0.41440, -0.40576, -0.39063, -0.16296, 0.07293, 0.07052, -0.04444, -0.08017, -0.21248, -0.28773, -0.34026, -0.40523, -0.47367, -0.38926, -0.32766, -0.40715, -0.43775, -0.28917, -0.11656, -0.04937, 0.08348, 0.32593, 0.65890, 0.82940, 0.92721, 0.98071, 0.94806, 0.87992, 0.79527, 0.83755, 0.83873, 0.93879, 1.07060, 1.11241, 1.08065, 1.22098, 1.49058, 1.60276, 1.59712, 1.67076, 1.70879, 1.85332, 2.01872, 2.01233, 1.74860, 1.57792, 1.52169, 1.48909, 1.36682, 1.29940, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.57791, -0.83397, -1.02365, -1.18789, -1.27222, -1.32156, -1.42829, -1.63134, -1.66149, -1.54767, -1.51394, -1.56649, -1.54061, -1.60286, -1.65329, -1.75775, -1.87873, -1.97891, -1.89265, -1.72802, -1.59473, -1.48442, -1.26174, -0.92731, -0.63237, -0.41326, -0.34592, -0.18128, 0.00863, +-2.16880, -2.19515, -2.15521, -2.03895, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.33560, -2.28545, -2.19287, -2.13671, -2.19928, -2.39518, -2.62095, -2.75019, -2.77379, -2.73727, -2.66826, -2.59061, -2.55353, -2.49713, -2.50991, -2.55838, -2.47927, -2.30190, -2.32027, -2.37805, -2.35580, -2.23615, -2.15197, -2.10632, -2.02953, -2.00293, -2.04450, -1.99817, -1.84194, -1.67333, -1.63648, -1.69948, -1.67617, -1.76573, -1.89220, -1.96638, -2.03931, -2.01360, -1.93649, -1.76241, -1.53391, -1.31838, -1.15073, -1.08741, -1.07637, -0.97668, -0.82637, -0.67535, -0.59788, -0.43675, -0.22323, -0.05191, 0.09892, 0.27824, 0.37587, 0.31121, 0.19301, 0.05535, -0.12243, -0.29358, -0.47638, -0.59094, -0.72266, -0.95202, -1.08784, -1.37759, -1.71953, -1.87187, -2.06209, -2.17957, -2.34973, -2.53538, -2.67987, -2.83406, -3.09283, -3.25715, -3.36373, -3.38332, -3.45510, -3.55741, -3.74159, -3.77379, -3.84428, -3.86380, -3.83198, -3.85457, -3.88914, -3.89979, -3.79665, -3.63820, -3.52584, -3.43624, -3.36392, -3.25057, -3.15072, -3.12843, -2.93946, -2.75414, -2.67458, -2.46298, -2.34705, -2.22211, -2.27655, -2.47144, -2.66767, -2.81604, -2.96629, -2.99417, -3.15337, -3.19480, -3.12774, -3.04736, -3.15471, -3.15377, -3.19271, -3.25302, -3.24582, -3.19830, -3.09115, -2.99916, -2.94190, -2.80359, -2.63011, -2.42904, -2.21028, -2.00666, -1.76897, -1.59588, -1.31931, -1.00931, -0.89117, -0.70454, -0.53138, -0.34444, -0.22799, 0.07932, 0.46189, 0.86819, 1.04761, 1.23869, 1.33387, 1.52732, 1.78880, 2.21610, 2.50070, 2.74187, 2.89577, 2.98517, 3.13807, 3.25378, 3.34797, 3.36503, 3.27930, 3.21333, 3.13273, 3.03114, 2.94317, 2.83593, 2.70820, 2.49653, 2.37452, 2.31692, 2.00085, 1.71026, 1.47506, 1.36797, 1.29055, 1.21256, 1.02923, 0.96041, 0.87585, 0.81595, 0.58039, 0.35873, 0.17351, 0.06781, -0.17207, -0.35108, -0.45928, -0.61187, -0.71230, -0.69546, -0.58473, -0.51778, -0.60737, -0.75058, -0.82028, -0.85214, -0.83863, -0.77733, -0.69360, -0.74458, -0.70487, -0.58511, -0.66817, -0.65197, -0.61322, -0.64155, -0.78356, -0.94164, -1.11328, -1.16271, -1.18530, -0.95571, -0.78283, -0.67627, -0.52064, -0.27028, -0.12212, -0.00624, 0.12377, 0.11891, 0.06677, 0.06554, 0.15632, 0.27319, 0.27953, 0.27572, 0.33526, 0.45398, 0.65445, 0.89767, 1.09043, 1.06001, 1.06711, 1.18938, 1.20165, 1.18718, 1.10724, 1.08795, 1.14766, 1.13659, 1.00457, 0.89927, 0.73875, 0.64429, 0.48368, 0.30406, 0.28788, 0.35812, 0.33423, 0.35745, 0.46043, 0.42336, 0.22399, -0.03916, -0.19601, -0.32030, -0.56850, -0.75234, -0.83791, -0.85435, -0.77788, -0.74796, -0.74230, -0.77285, -0.83837, -0.91468, -1.19246, -1.48232, -1.63258, -1.70363, -1.68527, -1.57850, -1.62557, -1.81718, -2.03787, -2.13564, -2.17782, -2.26352, -2.18675, -2.05202, -2.01777, -2.06475, -2.03531, -2.05727, -2.11006, -2.10846, -1.99023, -1.78023, -1.66728, -1.57907, -1.60206, -1.74741, -1.85248, -1.91574, -1.85749, -1.85673, -1.93596, -1.71610, -1.46168, -1.30425, -1.09614, -0.95982, -0.77091, -0.58696, -0.47721, -0.47135, -0.39130, -0.30435, -0.18593, -0.09918, 0.10985, 0.29025, 0.29229, 0.07231, 0.00265, -0.11176, -0.27488, -0.36927, -0.39655, -0.34888, -0.35126, -0.40995, -0.45309, -0.38016, -0.22306, -0.10612, 0.00441, 0.10253, 0.16093, 0.39413, 0.61227, 0.75475, 0.84662, 0.75755, 0.72088, 0.69045, 0.67423, 0.65154, 0.75714, 0.87127, 1.01818, 1.04304, 1.17490, 1.38242, 1.58012, 1.61425, 1.76727, 1.91702, 1.99995, 2.08481, 2.02328, 1.83814, 1.57649, 1.31023, 1.19307, 1.09503, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.69677, -0.85542, -1.01403, -1.15143, -1.19747, -1.29813, -1.41655, -1.67895, -1.74983, -1.71571, -1.64563, -1.71910, -1.73777, -1.75199, -1.82991, -1.92341, -1.99188, -1.89401, -1.75584, -1.69919, -1.58913, -1.45724, -1.27240, -1.01086, -0.66576, -0.32105, -0.25090, -0.14572, 0.10825, +-2.20236, -2.20490, -2.28496, -2.24641, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.46784, -2.46839, -2.37640, -2.32724, -2.41704, -2.61652, -2.81503, -2.93812, -2.92024, -2.85448, -2.83038, -2.77992, -2.74621, -2.68058, -2.72734, -2.80510, -2.73406, -2.59783, -2.57028, -2.56078, -2.60152, -2.52752, -2.36478, -2.28304, -2.16112, -2.03172, -2.01677, -2.01739, -2.04850, -2.02160, -1.96452, -2.01330, -2.02844, -2.10458, -2.08630, -2.06092, -2.13928, -2.09998, -1.98082, -1.76162, -1.47986, -1.22946, -1.14464, -1.11642, -1.03441, -0.85170, -0.72567, -0.64984, -0.56815, -0.40150, -0.10245, 0.19173, 0.30677, 0.36083, 0.47939, 0.49809, 0.44948, 0.35892, 0.14440, -0.02834, -0.25652, -0.48223, -0.58800, -0.73047, -0.91638, -1.30022, -1.63491, -1.78799, -2.02981, -2.19205, -2.37857, -2.58376, -2.76139, -2.87417, -3.12702, -3.27147, -3.33272, -3.31829, -3.42076, -3.61097, -3.81070, -3.86681, -3.90677, -3.82119, -3.78146, -3.84477, -3.79826, -3.79346, -3.75223, -3.54245, -3.43767, -3.39903, -3.37671, -3.34529, -3.14428, -3.00563, -2.91140, -2.89033, -2.84623, -2.61208, -2.50521, -2.40774, -2.49561, -2.67810, -2.82736, -2.86825, -3.02046, -3.08041, -3.20973, -3.18800, -3.11586, -3.11454, -3.23699, -3.31867, -3.38250, -3.30451, -3.27859, -3.39601, -3.35306, -3.22048, -3.15008, -2.95948, -2.76773, -2.53583, -2.33761, -2.25275, -1.99266, -1.69702, -1.43151, -1.23399, -1.12591, -0.93064, -0.80566, -0.62829, -0.45331, -0.06957, 0.33075, 0.80289, 0.99744, 1.18086, 1.30975, 1.56615, 1.82261, 2.15642, 2.46175, 2.74645, 2.97012, 3.17883, 3.33600, 3.37636, 3.45929, 3.48933, 3.41925, 3.44829, 3.45418, 3.33883, 3.12717, 2.81166, 2.63785, 2.55034, 2.43730, 2.24572, 1.87210, 1.62225, 1.43105, 1.34292, 1.26755, 1.20044, 1.01710, 1.03901, 1.00462, 0.94764, 0.73453, 0.52130, 0.33670, 0.21236, 0.00963, -0.21198, -0.36371, -0.38300, -0.41563, -0.51331, -0.45416, -0.35623, -0.47552, -0.60781, -0.65463, -0.67026, -0.67334, -0.72849, -0.65532, -0.58640, -0.53139, -0.49995, -0.58628, -0.52730, -0.51454, -0.59717, -0.74081, -0.86947, -1.04412, -1.02620, -1.02002, -0.81197, -0.60012, -0.41415, -0.25049, -0.15355, -0.11728, -0.03089, 0.05326, 0.12374, 0.18956, 0.19612, 0.35776, 0.54002, 0.48971, 0.44459, 0.49570, 0.61173, 0.76757, 0.83857, 0.91488, 0.97812, 1.06897, 1.13545, 1.10151, 1.11580, 1.05811, 1.04917, 1.14936, 1.19160, 1.05826, 0.95110, 0.82240, 0.76469, 0.64105, 0.44948, 0.38934, 0.40345, 0.33287, 0.30856, 0.35937, 0.38305, 0.24755, -0.08586, -0.28561, -0.34070, -0.55581, -0.69831, -0.70149, -0.68766, -0.63123, -0.67669, -0.70078, -0.61907, -0.63471, -0.82245, -1.19418, -1.49023, -1.65909, -1.77379, -1.77701, -1.64974, -1.65089, -1.75483, -1.91675, -2.10496, -2.22800, -2.31354, -2.28670, -2.24423, -2.21431, -2.14911, -1.98904, -1.90093, -1.87529, -1.95364, -1.92906, -1.67602, -1.57983, -1.57776, -1.63796, -1.77678, -1.84641, -1.94647, -1.96747, -1.87409, -1.80992, -1.57094, -1.32824, -1.11457, -0.90605, -0.85836, -0.67711, -0.40576, -0.24385, -0.25861, -0.15770, -0.06024, 0.05950, 0.14227, 0.34487, 0.46333, 0.37057, 0.13950, 0.05944, -0.00719, -0.07220, -0.21637, -0.35673, -0.32102, -0.35258, -0.43173, -0.40338, -0.29232, -0.14541, -0.10433, -0.11095, 0.01746, 0.14716, 0.29764, 0.36584, 0.48964, 0.61753, 0.54094, 0.49597, 0.43345, 0.41500, 0.42416, 0.56615, 0.67205, 0.86772, 1.01276, 1.27793, 1.45350, 1.52728, 1.53432, 1.68359, 1.89596, 2.09863, 2.12107, 1.89629, 1.72135, 1.49349, 1.18370, 1.05560, 0.93670, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.87083, -0.95583, -1.04397, -1.17711, -1.16272, -1.27394, -1.43374, -1.69772, -1.74757, -1.76190, -1.81899, -1.92670, -1.97015, -1.98547, -1.95373, -2.00066, -2.11426, -1.95178, -1.75271, -1.70157, -1.53306, -1.36662, -1.16251, -0.93061, -0.72493, -0.36756, -0.14049, -0.00364, 0.12776, +-2.27349, -2.30323, -2.34211, -2.41782, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.49728, -2.61368, -2.58925, -2.54840, -2.58197, -2.73855, -2.95245, -3.01448, -2.96270, -2.86590, -2.88000, -2.79907, -2.73171, -2.74249, -2.82712, -2.86241, -2.79710, -2.83274, -2.86001, -2.85596, -2.76973, -2.67114, -2.58596, -2.45352, -2.35464, -2.21011, -2.17072, -2.24729, -2.28445, -2.24831, -2.26066, -2.32354, -2.28241, -2.33601, -2.20916, -2.10482, -2.13783, -2.10553, -2.09359, -1.88415, -1.59168, -1.32828, -1.23268, -1.12800, -0.92232, -0.74962, -0.62163, -0.51143, -0.34070, -0.29637, -0.09730, 0.12921, 0.30347, 0.37029, 0.43444, 0.60674, 0.67007, 0.63855, 0.45666, 0.21227, -0.00683, -0.26144, -0.48064, -0.63831, -0.75473, -1.12051, -1.39458, -1.52372, -1.75809, -1.95467, -2.25009, -2.47769, -2.66994, -2.79652, -3.02874, -3.16000, -3.16281, -3.24469, -3.39206, -3.57240, -3.62181, -3.73789, -3.81843, -3.82962, -3.83064, -3.86869, -3.89458, -3.80495, -3.69310, -3.45679, -3.33381, -3.41065, -3.37901, -3.26673, -3.06304, -2.97100, -2.89815, -2.99305, -3.01871, -2.81326, -2.71338, -2.61907, -2.74773, -2.88012, -2.93941, -2.92072, -3.00988, -3.07037, -3.08534, -3.13558, -3.19160, -3.29548, -3.33021, -3.49685, -3.57381, -3.47719, -3.40068, -3.45364, -3.52052, -3.35113, -3.21405, -3.07588, -2.89806, -2.73070, -2.49326, -2.27327, -1.98718, -1.72600, -1.41982, -1.28517, -1.18944, -0.97781, -0.87115, -0.68126, -0.54056, -0.17540, 0.23650, 0.68771, 0.94363, 1.16862, 1.49727, 1.79025, 1.99974, 2.19177, 2.52404, 2.77125, 3.00225, 3.24527, 3.44823, 3.58919, 3.56009, 3.54513, 3.55955, 3.61523, 3.65783, 3.41194, 3.09078, 2.78218, 2.56587, 2.41926, 2.35652, 2.14696, 1.82577, 1.68122, 1.53668, 1.48902, 1.34551, 1.20595, 1.06630, 1.05371, 0.98689, 0.86881, 0.77188, 0.60036, 0.43336, 0.30193, 0.23814, 0.03073, -0.15861, -0.15736, -0.18646, -0.28142, -0.37877, -0.34114, -0.34398, -0.40730, -0.40366, -0.47798, -0.52515, -0.51558, -0.40280, -0.36621, -0.28427, -0.27458, -0.36558, -0.29321, -0.33933, -0.45092, -0.65458, -0.80807, -0.86126, -0.79325, -0.75043, -0.65374, -0.43062, -0.20989, -0.09523, -0.08721, -0.01231, 0.06248, 0.03134, 0.06664, 0.16995, 0.32171, 0.47509, 0.57836, 0.58179, 0.51654, 0.53243, 0.57029, 0.63860, 0.74751, 0.89043, 0.95830, 1.10308, 1.18285, 1.11213, 1.14373, 1.09678, 1.06537, 1.04287, 0.97969, 0.90422, 0.83821, 0.80304, 0.77102, 0.73476, 0.61310, 0.48159, 0.43203, 0.36557, 0.27970, 0.18157, 0.20023, 0.12264, -0.05034, -0.24708, -0.36654, -0.46106, -0.53873, -0.48905, -0.48738, -0.53533, -0.55023, -0.51182, -0.48431, -0.54655, -0.77312, -1.20131, -1.43204, -1.52375, -1.60231, -1.67489, -1.71754, -1.72173, -1.75717, -1.84400, -2.04156, -2.15470, -2.20817, -2.31803, -2.37458, -2.29339, -2.08821, -1.93860, -1.84327, -1.83480, -1.88545, -1.93730, -1.83442, -1.70295, -1.68954, -1.70882, -1.78957, -1.89007, -1.90075, -1.82176, -1.71279, -1.59026, -1.33759, -1.21032, -1.00714, -0.79798, -0.74506, -0.55603, -0.32968, -0.10768, -0.05736, 0.08980, 0.21941, 0.32022, 0.38591, 0.45497, 0.51428, 0.46312, 0.38915, 0.25478, 0.18798, 0.11373, 0.00288, -0.14668, -0.27840, -0.32635, -0.39306, -0.35660, -0.25120, -0.24884, -0.22139, -0.15575, 0.00884, 0.17944, 0.35743, 0.29855, 0.32181, 0.41839, 0.37412, 0.35089, 0.22566, 0.22351, 0.29825, 0.44177, 0.56685, 0.79136, 1.08388, 1.32939, 1.42544, 1.42139, 1.48165, 1.51654, 1.70311, 1.90090, 1.97588, 1.83849, 1.58301, 1.39087, 1.13777, 0.99280, 0.87904, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.85546, -0.96543, -1.08582, -1.23371, -1.23812, -1.31355, -1.45863, -1.58406, -1.67570, -1.75666, -1.88900, -1.90275, -1.99154, -2.04570, -2.03870, -2.04000, -2.04350, -1.98191, -1.81763, -1.70726, -1.51248, -1.24486, -1.05491, -0.83633, -0.61391, -0.33713, -0.17184, 0.04294, 0.15409, +-2.32365, -2.38380, -2.41080, -2.52464, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.55231, -2.64276, -2.70901, -2.71071, -2.71890, -2.82598, -2.96489, -2.95782, -2.97594, -2.94154, -2.94509, -2.84640, -2.76471, -2.78199, -2.82189, -2.80591, -2.76466, -2.85055, -2.94358, -2.97736, -2.84657, -2.71995, -2.65274, -2.55018, -2.58923, -2.57273, -2.47297, -2.43772, -2.47516, -2.50360, -2.53277, -2.57025, -2.40198, -2.32148, -2.21954, -2.17456, -2.19481, -2.15248, -2.14315, -1.92812, -1.74248, -1.59369, -1.44492, -1.26778, -1.02800, -0.84931, -0.65343, -0.43356, -0.21151, -0.17338, -0.07753, 0.07089, 0.27801, 0.41379, 0.53050, 0.76319, 0.81312, 0.72055, 0.62882, 0.47645, 0.20484, -0.17684, -0.45900, -0.63103, -0.65346, -0.84829, -1.10284, -1.26770, -1.48887, -1.69674, -2.00192, -2.20063, -2.44971, -2.70410, -2.92564, -3.05000, -3.07158, -3.20772, -3.35106, -3.44775, -3.44138, -3.52165, -3.64491, -3.77210, -3.85780, -3.90155, -3.92277, -3.74079, -3.56513, -3.41783, -3.25505, -3.22891, -3.21634, -3.20479, -3.08727, -3.10816, -3.04382, -3.03490, -3.10032, -2.98735, -2.91723, -2.84060, -2.91976, -2.94536, -2.99916, -3.08552, -3.12867, -3.14091, -3.11394, -3.21593, -3.35401, -3.43973, -3.44632, -3.55456, -3.60837, -3.53298, -3.44009, -3.41497, -3.45021, -3.26293, -3.13676, -3.14884, -2.98126, -2.70796, -2.45209, -2.28526, -2.01748, -1.79223, -1.46155, -1.19771, -1.09641, -0.93687, -0.81495, -0.61025, -0.45957, -0.06023, 0.31860, 0.62046, 0.90720, 1.21008, 1.63234, 1.94120, 2.13351, 2.31489, 2.59395, 2.85647, 3.11372, 3.41884, 3.70915, 3.91760, 3.87962, 3.84351, 3.83554, 3.72560, 3.65495, 3.39248, 3.03339, 2.64552, 2.41629, 2.26041, 2.23149, 2.19982, 1.99810, 1.85944, 1.70026, 1.61797, 1.42805, 1.29609, 1.15601, 0.96058, 0.81016, 0.69792, 0.66778, 0.55571, 0.44392, 0.39553, 0.38833, 0.26566, 0.12403, 0.11969, 0.08772, -0.00001, -0.13721, -0.12695, -0.10517, -0.25147, -0.28460, -0.28055, -0.29818, -0.34877, -0.25207, -0.21733, -0.10179, 0.05579, 0.02527, 0.02890, -0.07700, -0.22172, -0.44887, -0.55904, -0.55280, -0.59191, -0.59584, -0.56083, -0.40259, -0.22520, -0.12671, -0.01976, 0.13487, 0.22718, 0.18181, 0.18274, 0.28208, 0.47760, 0.58959, 0.61640, 0.61971, 0.46717, 0.41910, 0.52303, 0.61730, 0.67506, 0.82944, 0.91143, 1.05008, 1.22674, 1.20216, 1.16657, 1.07674, 0.98760, 0.86973, 0.79848, 0.78147, 0.67025, 0.63232, 0.63001, 0.61712, 0.51972, 0.37859, 0.35347, 0.31294, 0.21680, 0.11702, 0.13886, 0.11013, 0.04561, -0.10228, -0.21359, -0.25909, -0.37635, -0.38930, -0.32252, -0.32253, -0.39868, -0.42656, -0.45219, -0.56055, -0.71091, -1.04180, -1.26975, -1.35351, -1.42092, -1.53963, -1.65561, -1.67351, -1.76882, -1.88027, -1.98241, -2.05174, -2.13539, -2.31367, -2.37636, -2.24166, -2.00620, -1.87056, -1.83084, -1.83977, -1.86285, -1.91755, -1.86554, -1.75976, -1.79161, -1.84294, -1.81009, -1.79128, -1.78718, -1.73005, -1.59270, -1.43378, -1.13474, -0.98030, -0.85771, -0.72637, -0.66875, -0.48774, -0.27517, -0.00134, 0.04707, 0.13807, 0.30509, 0.40441, 0.42381, 0.41965, 0.47970, 0.53245, 0.54360, 0.46974, 0.40789, 0.32001, 0.22455, 0.08126, -0.10393, -0.18750, -0.32257, -0.42786, -0.32709, -0.27491, -0.27908, -0.27800, -0.09120, 0.10398, 0.34188, 0.36612, 0.28024, 0.25354, 0.20615, 0.21662, 0.17613, 0.27344, 0.33365, 0.36031, 0.49777, 0.72843, 1.01090, 1.15223, 1.17149, 1.20798, 1.28785, 1.35582, 1.53927, 1.71904, 1.85402, 1.82470, 1.58489, 1.39018, 1.11848, 0.83932, 0.72440, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.79660, -0.86755, -0.95264, -1.02732, -1.20437, -1.35533, -1.42712, -1.53725, -1.62532, -1.75418, -1.85233, -1.90868, -1.86332, -1.87626, -1.89911, -1.89346, -1.86063, -1.79860, -1.75619, -1.62180, -1.52532, -1.45767, -1.17421, -0.86387, -0.64688, -0.55217, -0.38321, -0.28420, -0.02630, 0.28675, +-2.52719, -2.52326, -2.59600, -2.76182, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.61187, -2.68608, -2.83804, -2.82754, -2.85137, -2.95093, -3.02448, -2.98166, -2.97615, -2.88903, -2.77389, -2.76182, -2.74921, -2.71150, -2.74061, -2.79458, -2.84041, -2.91707, -3.03962, -3.06591, -3.00579, -2.95910, -2.82586, -2.78723, -2.86199, -2.83793, -2.78148, -2.66737, -2.61906, -2.71923, -2.75853, -2.59301, -2.36058, -2.28827, -2.27959, -2.20301, -2.14628, -2.13904, -2.11740, -1.95963, -1.85351, -1.78383, -1.56651, -1.44679, -1.27891, -1.00708, -0.69253, -0.43399, -0.26220, -0.25667, -0.26527, -0.13281, 0.09670, 0.26552, 0.55002, 0.78340, 0.80416, 0.78491, 0.70601, 0.59873, 0.36853, -0.03504, -0.39384, -0.49175, -0.52528, -0.69320, -0.96595, -1.12631, -1.25085, -1.47892, -1.74848, -1.97564, -2.22247, -2.52395, -2.67036, -2.85022, -2.98093, -3.07202, -3.18739, -3.30940, -3.41771, -3.53173, -3.69625, -3.86530, -3.98697, -4.10911, -4.03359, -3.75513, -3.53528, -3.31767, -3.17866, -3.07051, -3.01502, -3.08326, -3.13749, -3.10123, -3.02340, -3.01716, -3.12106, -3.08118, -2.99637, -3.05353, -3.12378, -3.14805, -3.15457, -3.22733, -3.09143, -3.04154, -3.10301, -3.23698, -3.43584, -3.56077, -3.62851, -3.67361, -3.67961, -3.61158, -3.50131, -3.50088, -3.40167, -3.15665, -3.04478, -2.94202, -2.82314, -2.58827, -2.34066, -2.17816, -2.02543, -1.74244, -1.37323, -1.08596, -1.00816, -0.90579, -0.67851, -0.53684, -0.36452, -0.00191, 0.40855, 0.70112, 1.10381, 1.47683, 1.78342, 2.06747, 2.27356, 2.41945, 2.58164, 2.81659, 3.10005, 3.48631, 3.88291, 4.02737, 4.04675, 4.09287, 4.00663, 3.88070, 3.67353, 3.35943, 3.04487, 2.71998, 2.43652, 2.35377, 2.35392, 2.30694, 2.09888, 1.89159, 1.79093, 1.62963, 1.46263, 1.29991, 1.16318, 0.85629, 0.68860, 0.65085, 0.57704, 0.54019, 0.53473, 0.49065, 0.39327, 0.27407, 0.20174, 0.21103, 0.26940, 0.17120, 0.03522, 0.05605, 0.00340, -0.06822, -0.12245, -0.15784, -0.12237, -0.09603, -0.09152, -0.01623, 0.17679, 0.34047, 0.30361, 0.21524, 0.19665, 0.03222, -0.19201, -0.33463, -0.35286, -0.46156, -0.45909, -0.38742, -0.38204, -0.30010, -0.15701, 0.03061, 0.15246, 0.17099, 0.14813, 0.17583, 0.32411, 0.44759, 0.50848, 0.60373, 0.59479, 0.52838, 0.51396, 0.56973, 0.65032, 0.70883, 0.75275, 0.83709, 1.04125, 1.23060, 1.22596, 1.08905, 1.02377, 0.83977, 0.61587, 0.52718, 0.56294, 0.51967, 0.54399, 0.62038, 0.49420, 0.33394, 0.26956, 0.26214, 0.20387, 0.09542, 0.01197, 0.01223, 0.06649, 0.05450, -0.08182, -0.09724, -0.11829, -0.15754, -0.15000, -0.14906, -0.14941, -0.21443, -0.35226, -0.43638, -0.43907, -0.55104, -0.84722, -1.13697, -1.20448, -1.27038, -1.45882, -1.60804, -1.64343, -1.73173, -1.79748, -1.71418, -1.84340, -2.05748, -2.19797, -2.22536, -2.15424, -2.03364, -1.93689, -1.90870, -1.84695, -1.83687, -1.92528, -1.83761, -1.80446, -1.86376, -1.85314, -1.82012, -1.72560, -1.59357, -1.51018, -1.39482, -1.12212, -0.89455, -0.84763, -0.85317, -0.74147, -0.61063, -0.50411, -0.33042, -0.09463, 0.00582, 0.13792, 0.43652, 0.53623, 0.47290, 0.45260, 0.47457, 0.50942, 0.49797, 0.45006, 0.38313, 0.36655, 0.31807, 0.09684, -0.05168, -0.17609, -0.36962, -0.45596, -0.43775, -0.35606, -0.29551, -0.30840, -0.20768, 0.07174, 0.31436, 0.32087, 0.14903, 0.07247, 0.08958, 0.06831, 0.13929, 0.25114, 0.31738, 0.33736, 0.59689, 0.78253, 0.89388, 0.97936, 0.99457, 1.03234, 1.06745, 1.15271, 1.30912, 1.48419, 1.64193, 1.56451, 1.40754, 1.24646, 1.00049, 0.83838, 0.66344, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.95349, -0.97300, -0.99899, -1.11191, -1.33911, -1.37819, -1.46828, -1.64660, -1.79881, -1.87606, -1.86285, -1.81677, -1.80024, -1.79181, -1.75625, -1.66232, -1.65539, -1.56411, -1.37209, -1.30413, -1.17035, -0.97028, -0.71814, -0.50739, -0.43926, -0.42122, -0.25881, 0.05292, 0.43223, +-2.71044, -2.73359, -2.80203, -2.95028, -3.03618, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -2.81804, -2.82988, -2.92954, -2.92601, -2.95618, -2.99809, -3.05585, -3.04648, -2.95298, -2.75663, -2.65191, -2.71557, -2.67145, -2.55843, -2.62184, -2.75403, -2.84791, -2.89590, -3.03279, -3.11490, -3.11199, -3.10330, -3.00680, -3.01713, -3.07817, -3.06260, -3.03040, -2.92533, -2.81485, -2.84642, -2.92023, -2.71156, -2.44691, -2.42784, -2.42049, -2.21220, -2.02094, -1.96092, -1.96321, -1.92632, -1.87327, -1.82073, -1.69646, -1.67313, -1.49769, -1.12212, -0.73983, -0.47600, -0.33658, -0.35760, -0.36568, -0.23942, 0.02288, 0.29088, 0.60731, 0.73787, 0.68579, 0.63127, 0.58283, 0.49994, 0.37180, 0.17161, -0.22892, -0.46480, -0.55737, -0.72510, -0.95316, -1.05934, -1.11393, -1.25227, -1.52675, -1.83954, -2.04608, -2.26612, -2.44596, -2.73432, -2.88016, -2.86625, -2.96368, -3.12509, -3.32984, -3.51549, -3.71475, -3.92845, -4.01399, -4.08177, -3.98987, -3.76587, -3.58674, -3.42112, -3.28422, -3.11724, -3.01651, -3.02568, -3.17756, -3.18486, -3.04946, -3.03679, -3.10499, -3.04215, -2.99109, -3.08161, -3.21396, -3.31732, -3.28643, -3.22656, -3.00982, -2.99130, -3.07164, -3.14647, -3.30730, -3.41699, -3.49865, -3.50908, -3.51127, -3.55093, -3.48946, -3.44769, -3.27352, -3.06251, -2.92752, -2.75713, -2.65919, -2.51725, -2.30630, -2.00651, -1.89129, -1.75013, -1.38853, -1.09429, -1.01955, -0.86793, -0.57232, -0.36910, -0.20879, 0.05097, 0.48105, 0.91976, 1.38945, 1.71862, 1.94426, 2.24316, 2.45498, 2.59970, 2.76327, 2.98333, 3.26119, 3.58832, 3.94716, 4.09033, 4.14147, 4.17406, 4.01942, 3.77721, 3.49547, 3.23291, 3.02611, 2.92146, 2.70491, 2.51142, 2.44928, 2.32794, 2.06360, 1.87465, 1.77489, 1.63480, 1.48306, 1.22841, 1.05275, 0.81349, 0.72291, 0.70157, 0.64058, 0.73334, 0.77284, 0.65553, 0.46634, 0.31102, 0.27805, 0.25207, 0.35479, 0.36937, 0.24191, 0.13859, 0.00685, -0.06384, -0.13706, -0.21493, -0.14268, 0.06785, 0.09330, 0.06332, 0.25187, 0.41034, 0.35472, 0.29633, 0.35430, 0.28375, 0.10223, -0.12509, -0.24622, -0.33863, -0.31836, -0.27947, -0.31582, -0.22450, -0.06363, 0.08983, 0.13636, 0.07847, 0.07097, 0.10648, 0.21600, 0.30628, 0.38213, 0.52874, 0.55515, 0.53468, 0.54594, 0.55440, 0.58281, 0.69471, 0.72462, 0.69423, 0.83846, 1.02122, 1.01978, 0.88719, 0.83237, 0.66861, 0.50422, 0.40465, 0.43444, 0.51604, 0.58887, 0.57441, 0.32679, 0.16892, 0.18198, 0.16761, 0.14647, 0.09331, 0.00332, -0.06826, -0.03155, 0.03949, -0.04389, -0.08235, -0.10674, -0.11546, -0.14608, -0.19073, -0.19313, -0.16976, -0.26729, -0.45509, -0.47238, -0.52393, -0.77251, -1.02260, -1.07710, -1.12837, -1.28591, -1.43446, -1.48210, -1.51050, -1.51047, -1.46044, -1.70728, -1.97421, -2.04874, -2.05718, -2.06362, -2.05330, -1.98010, -1.88890, -1.79613, -1.71534, -1.74629, -1.71815, -1.79752, -1.91896, -1.94099, -1.89284, -1.75718, -1.47656, -1.23918, -1.19356, -1.01545, -0.82768, -0.80166, -0.81820, -0.67685, -0.50448, -0.41772, -0.35492, -0.24929, -0.10472, 0.15066, 0.46969, 0.58633, 0.57116, 0.56068, 0.49625, 0.48426, 0.47286, 0.40568, 0.30624, 0.28140, 0.27161, 0.05644, -0.11832, -0.30751, -0.53624, -0.68337, -0.70953, -0.59564, -0.42346, -0.27742, -0.24378, -0.09894, 0.12328, 0.13216, 0.02050, 0.03924, 0.09262, 0.10877, 0.15845, 0.15635, 0.20029, 0.32019, 0.60307, 0.66540, 0.67439, 0.80760, 0.89770, 0.95823, 1.01033, 1.09690, 1.20012, 1.28050, 1.38909, 1.31719, 1.17392, 0.96972, 0.76197, 0.61653, 0.40005, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.95306, -0.94592, -0.98309, -1.17346, -1.26981, -1.43233, -1.61901, -1.73704, -1.80927, -1.75034, -1.66934, -1.65528, -1.62173, -1.59472, -1.48499, -1.45165, -1.34468, -1.16247, -1.07631, -0.95161, -0.82424, -0.66925, -0.47717, -0.26256, -0.22184, -0.12896, 0.17636, 0.54857, +-2.81293, -2.93582, -3.08353, -3.15224, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.05845, -2.96139, -3.03056, -3.07221, -3.16130, -3.14310, -3.02389, -3.06204, -2.98585, -2.76732, -2.70481, -2.75377, -2.65429, -2.53257, -2.65976, -2.82349, -2.97377, -2.99080, -3.04686, -3.15137, -3.20483, -3.15337, -3.05798, -3.11823, -3.14200, -3.10991, -3.03165, -2.95301, -2.95095, -2.98649, -2.98831, -2.80201, -2.62987, -2.54296, -2.48924, -2.24568, -2.05126, -1.99730, -1.89617, -1.93998, -1.99110, -1.93726, -1.86393, -1.80631, -1.60241, -1.24507, -0.94859, -0.70928, -0.58696, -0.54628, -0.36803, -0.17263, 0.02785, 0.32761, 0.64205, 0.66617, 0.59515, 0.53830, 0.55593, 0.53835, 0.38355, 0.22095, -0.13448, -0.41968, -0.62988, -0.69520, -0.84390, -0.96879, -1.06270, -1.22283, -1.39359, -1.70867, -1.95218, -2.08806, -2.32710, -2.63873, -2.80623, -2.80773, -2.97034, -3.12195, -3.31976, -3.48758, -3.61871, -3.80213, -3.91956, -3.95195, -3.82150, -3.71722, -3.61015, -3.47443, -3.32135, -3.10621, -3.08785, -3.14481, -3.27957, -3.24765, -3.18624, -3.11070, -3.10246, -3.05999, -3.05671, -3.18857, -3.19999, -3.22387, -3.25625, -3.13718, -2.98998, -2.98341, -3.04411, -3.06124, -3.16821, -3.21286, -3.29183, -3.30201, -3.27265, -3.32424, -3.35848, -3.33191, -3.08850, -2.93447, -2.80234, -2.61305, -2.51847, -2.34830, -2.20686, -1.90840, -1.76609, -1.62803, -1.40234, -1.10331, -0.97166, -0.82067, -0.50590, -0.31547, -0.08851, 0.21096, 0.51965, 1.01332, 1.45739, 1.80942, 2.06412, 2.37676, 2.52570, 2.67532, 2.87665, 3.10303, 3.42771, 3.74457, 3.97171, 4.05957, 4.15665, 4.11822, 3.89746, 3.61301, 3.33472, 3.21351, 3.03111, 2.94213, 2.77750, 2.61629, 2.42370, 2.27989, 2.10299, 1.92681, 1.78147, 1.53504, 1.37412, 1.17837, 0.89946, 0.75153, 0.76253, 0.81222, 0.78963, 0.91592, 0.87612, 0.69327, 0.48281, 0.30046, 0.32989, 0.36687, 0.42005, 0.39989, 0.31215, 0.13903, -0.03092, -0.06168, -0.11212, -0.11540, -0.07061, 0.10075, 0.13089, 0.15438, 0.28576, 0.43530, 0.45924, 0.39774, 0.42257, 0.29583, 0.15607, 0.06147, -0.14727, -0.24633, -0.25549, -0.23669, -0.25316, -0.15397, -0.07128, -0.02993, -0.04023, -0.14045, -0.10279, 0.00343, 0.04291, 0.05079, 0.19618, 0.38445, 0.40337, 0.41171, 0.44179, 0.50676, 0.49864, 0.54848, 0.59552, 0.63091, 0.68303, 0.76675, 0.80020, 0.66271, 0.58277, 0.42019, 0.39004, 0.47359, 0.43766, 0.50106, 0.54641, 0.46006, 0.19482, 0.04534, 0.03254, -0.02791, -0.01866, -0.06959, -0.12452, -0.12674, -0.10151, -0.04425, -0.05470, -0.09352, -0.17959, -0.19025, -0.23033, -0.20983, -0.16496, -0.16803, -0.26587, -0.41676, -0.48782, -0.59040, -0.70469, -0.85504, -0.88732, -0.97629, -1.11550, -1.10113, -1.16664, -1.23534, -1.24179, -1.31552, -1.62017, -1.90342, -2.01809, -2.10284, -2.14094, -2.18375, -2.06548, -1.83219, -1.72376, -1.68886, -1.66776, -1.63780, -1.79835, -1.90351, -1.86915, -1.71864, -1.52868, -1.31788, -1.12644, -1.07153, -0.95179, -0.83235, -0.66047, -0.63118, -0.54479, -0.45732, -0.44436, -0.31501, -0.26334, -0.18902, 0.12682, 0.40713, 0.56209, 0.56741, 0.51633, 0.35850, 0.35121, 0.35041, 0.29838, 0.25169, 0.20381, 0.10204, -0.11182, -0.24967, -0.47468, -0.68975, -0.84840, -0.86333, -0.70546, -0.57540, -0.41396, -0.30659, -0.14965, -0.03017, 0.06372, 0.05837, 0.09788, 0.12162, 0.07923, 0.15869, 0.10915, 0.02994, 0.17183, 0.36934, 0.39425, 0.37657, 0.52459, 0.60916, 0.69005, 0.75646, 0.86387, 1.01923, 1.09536, 1.12654, 1.08256, 1.00875, 0.73960, 0.49860, 0.31304, 0.09434, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.81359, -0.93120, -1.09216, -1.25421, -1.39765, -1.54287, -1.64998, -1.78785, -1.74145, -1.65322, -1.62711, -1.48944, -1.36429, -1.29504, -1.28201, -1.13135, -1.00462, -0.92397, -0.78086, -0.61976, -0.38742, -0.25697, -0.06421, 0.02757, 0.17297, 0.36247, 0.70846, +-2.95409, -3.17253, -3.33627, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.06978, -2.99952, -3.13664, -3.21968, -3.25575, -3.15356, -3.04822, -3.13579, -3.06726, -2.87712, -2.77501, -2.75276, -2.63271, -2.51100, -2.61398, -2.74994, -2.96843, -3.04984, -3.13887, -3.27502, -3.28700, -3.19061, -3.02593, -3.01018, -3.03780, -3.01061, -2.99468, -3.02248, -3.02284, -3.00329, -2.93182, -2.73257, -2.61807, -2.51055, -2.47418, -2.29503, -2.10021, -2.02489, -1.97556, -2.11712, -2.19648, -2.15207, -2.00663, -1.82624, -1.60878, -1.29881, -1.05324, -0.79790, -0.68796, -0.64069, -0.38966, -0.19007, 0.00179, 0.27193, 0.58584, 0.69406, 0.65403, 0.64090, 0.64894, 0.55447, 0.40203, 0.24978, -0.06983, -0.27493, -0.48793, -0.50894, -0.65158, -0.84139, -0.95294, -1.10521, -1.30982, -1.70921, -1.93578, -2.03962, -2.25778, -2.50928, -2.71603, -2.78937, -2.97600, -3.05574, -3.21187, -3.39003, -3.52230, -3.75590, -3.89110, -3.92146, -3.75624, -3.57285, -3.48443, -3.34988, -3.25168, -3.20703, -3.24982, -3.27868, -3.38425, -3.28302, -3.25331, -3.17040, -3.14456, -3.14689, -3.12532, -3.17333, -3.10835, -3.14930, -3.16847, -3.05862, -2.96137, -2.89701, -2.92886, -2.91659, -2.94648, -2.87972, -2.95475, -3.04685, -3.07075, -3.18829, -3.23267, -3.19269, -2.91564, -2.65512, -2.53661, -2.39393, -2.34611, -2.27768, -2.13663, -1.77091, -1.58476, -1.35914, -1.18129, -0.92265, -0.79662, -0.71098, -0.38524, -0.12782, 0.10147, 0.28568, 0.52841, 0.98862, 1.40730, 1.85267, 2.16994, 2.48084, 2.61075, 2.81151, 3.01080, 3.18282, 3.49420, 3.73676, 3.92080, 4.00187, 4.09242, 4.10613, 3.87104, 3.59443, 3.31235, 3.09841, 2.89525, 2.85631, 2.73847, 2.67971, 2.47424, 2.33426, 2.22475, 2.02468, 1.85222, 1.60289, 1.38676, 1.08026, 0.78425, 0.70036, 0.79219, 0.96706, 0.98261, 1.06268, 0.96328, 0.82887, 0.65537, 0.44463, 0.46715, 0.44926, 0.43020, 0.33755, 0.23767, 0.18160, 0.08187, 0.10132, 0.07595, -0.00404, -0.02367, 0.14785, 0.19781, 0.31734, 0.47805, 0.63143, 0.66834, 0.52985, 0.47842, 0.34919, 0.21353, 0.06314, -0.15177, -0.24522, -0.28637, -0.23820, -0.25299, -0.18945, -0.15293, -0.10741, -0.10584, -0.24236, -0.23715, -0.20599, -0.22160, -0.22092, -0.06871, 0.20417, 0.27140, 0.28760, 0.32491, 0.31273, 0.23021, 0.31227, 0.44197, 0.59844, 0.67288, 0.69687, 0.68804, 0.49671, 0.39529, 0.32286, 0.40239, 0.45943, 0.35725, 0.37699, 0.37061, 0.32920, 0.12779, -0.00766, -0.03687, -0.07200, -0.05616, -0.19150, -0.28210, -0.28639, -0.26775, -0.18700, -0.17084, -0.12848, -0.16715, -0.19621, -0.23076, -0.25270, -0.24441, -0.20164, -0.24950, -0.32758, -0.36838, -0.49359, -0.56860, -0.68430, -0.69126, -0.72548, -0.81592, -0.85138, -1.01299, -1.10701, -1.15420, -1.24584, -1.51921, -1.81287, -1.98821, -2.11164, -2.12348, -2.19172, -2.10443, -1.88149, -1.81712, -1.78662, -1.74194, -1.63652, -1.69522, -1.74354, -1.61285, -1.44510, -1.33231, -1.16951, -1.02067, -0.94506, -0.77949, -0.66017, -0.43809, -0.43200, -0.44073, -0.40294, -0.39583, -0.30285, -0.32925, -0.24777, 0.06953, 0.35978, 0.54600, 0.50437, 0.41976, 0.28460, 0.35927, 0.35690, 0.26078, 0.18966, 0.04593, -0.10862, -0.32871, -0.40694, -0.49101, -0.66904, -0.81121, -0.86835, -0.83891, -0.73629, -0.53861, -0.34183, -0.05167, 0.06129, 0.16893, 0.15232, 0.11283, 0.13565, 0.11839, 0.14232, -0.03393, -0.15228, -0.07191, 0.05638, 0.12604, 0.10535, 0.22114, 0.29973, 0.44211, 0.51045, 0.58912, 0.74789, 0.76525, 0.80470, 0.82033, 0.81471, 0.65639, 0.37323, 0.13302, -0.11311, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.95992, -1.11493, -1.25374, -1.27863, -1.37905, -1.49305, -1.64297, -1.56786, -1.49880, -1.51349, -1.34870, -1.22795, -1.15364, -1.13762, -0.97189, -0.75041, -0.66095, -0.50299, -0.30506, -0.12935, -0.02760, 0.18351, 0.27512, 0.48673, 0.64545, 0.95550, +-3.08480, -3.26735, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.13884, -3.18999, -3.23852, -3.31086, -3.38753, -3.35639, -3.20238, -3.21017, -3.17746, -2.99245, -2.89175, -2.81431, -2.68168, -2.58732, -2.53214, -2.55915, -2.70422, -2.86668, -2.91794, -3.13293, -3.29829, -3.24146, -3.13737, -3.02199, -2.97047, -2.99835, -3.07686, -3.11282, -3.12103, -3.06375, -2.89727, -2.75908, -2.68261, -2.65850, -2.55625, -2.44351, -2.32626, -2.19170, -2.06318, -2.09269, -2.15017, -2.13482, -2.20278, -2.14878, -1.88531, -1.64169, -1.40009, -1.11507, -0.86704, -0.71277, -0.55805, -0.38553, -0.18898, 0.11841, 0.35708, 0.51357, 0.63688, 0.71620, 0.75657, 0.77019, 0.67427, 0.45765, 0.28047, 0.02087, -0.17220, -0.36427, -0.43716, -0.55957, -0.74831, -0.93080, -1.02801, -1.32683, -1.67983, -1.78022, -1.93352, -2.19134, -2.34477, -2.50040, -2.68406, -2.86404, -3.00920, -3.21126, -3.29690, -3.47183, -3.72345, -3.80651, -3.82012, -3.73059, -3.54662, -3.36184, -3.22695, -3.19268, -3.23971, -3.36530, -3.33838, -3.38471, -3.35877, -3.36215, -3.29550, -3.16617, -3.08332, -3.12032, -3.07502, -3.08876, -3.10015, -2.93882, -2.84148, -2.83111, -2.69411, -2.63330, -2.66013, -2.64117, -2.55865, -2.64990, -2.72006, -2.88957, -3.07015, -2.99599, -2.82098, -2.59964, -2.41183, -2.33213, -2.31770, -2.32141, -2.18767, -2.01485, -1.64185, -1.40972, -1.20955, -1.06599, -0.86759, -0.71500, -0.57157, -0.34742, -0.00496, 0.18123, 0.35207, 0.75636, 1.19836, 1.48767, 1.88845, 2.22939, 2.46991, 2.64457, 2.86294, 2.95973, 3.17698, 3.43600, 3.61085, 3.90687, 4.11539, 4.13729, 4.01617, 3.78193, 3.52372, 3.19578, 2.97886, 2.79215, 2.80701, 2.82602, 2.77484, 2.52560, 2.31284, 2.17650, 2.05054, 1.80824, 1.63043, 1.36715, 1.01982, 0.90536, 0.90839, 0.91963, 1.10249, 1.20549, 1.15782, 0.99191, 0.91494, 0.75210, 0.69372, 0.70645, 0.54761, 0.47222, 0.37816, 0.25990, 0.22320, 0.21525, 0.23066, 0.14164, 0.08337, 0.06867, 0.22716, 0.35076, 0.45517, 0.55618, 0.66160, 0.69575, 0.66011, 0.54599, 0.44732, 0.26941, -0.03639, -0.15552, -0.16594, -0.28968, -0.31068, -0.33165, -0.35714, -0.35521, -0.24310, -0.23783, -0.26436, -0.25665, -0.39943, -0.41001, -0.28884, -0.17239, 0.00921, 0.11149, 0.17003, 0.19135, 0.18135, 0.08844, 0.12672, 0.29618, 0.47412, 0.53453, 0.52736, 0.49403, 0.42354, 0.31258, 0.30813, 0.41291, 0.36330, 0.36264, 0.40771, 0.24816, 0.18087, 0.12252, 0.05072, -0.00936, -0.02810, -0.16446, -0.34999, -0.37966, -0.41768, -0.36147, -0.21891, -0.22187, -0.22633, -0.23878, -0.24635, -0.33096, -0.37086, -0.34507, -0.29118, -0.23524, -0.22139, -0.25074, -0.38399, -0.48456, -0.54844, -0.57364, -0.56089, -0.55754, -0.72834, -0.88006, -0.89180, -1.04554, -1.19633, -1.35432, -1.61495, -1.88075, -2.03669, -2.11623, -2.15893, -2.02465, -1.91033, -1.84495, -1.69346, -1.57917, -1.50818, -1.53925, -1.55035, -1.46878, -1.29275, -1.12546, -0.99593, -0.83057, -0.71006, -0.58800, -0.49767, -0.35125, -0.31320, -0.36006, -0.44458, -0.42426, -0.42585, -0.34483, -0.06179, 0.18233, 0.34767, 0.48459, 0.39880, 0.29386, 0.28938, 0.35500, 0.29615, 0.25740, 0.11348, -0.07711, -0.17108, -0.35512, -0.49480, -0.56664, -0.67238, -0.83264, -0.88257, -0.81194, -0.74518, -0.55081, -0.35771, -0.11843, 0.01268, 0.11226, 0.10810, 0.03284, -0.01158, 0.05782, -0.00243, -0.14110, -0.11036, -0.14258, -0.20988, -0.12843, -0.10459, -0.07720, 0.04021, 0.19124, 0.26999, 0.49385, 0.61037, 0.55875, 0.62677, 0.67602, 0.63666, 0.50230, 0.25944, -0.02920, -0.28482, -0.42050, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.89268, -0.99030, -1.13479, -1.11634, -1.19136, -1.36785, -1.46137, -1.39089, -1.39076, -1.31612, -1.19334, -1.13805, -0.98349, -0.86654, -0.69652, -0.46813, -0.33823, -0.24220, -0.15147, 0.03334, 0.15920, 0.39149, 0.49203, 0.60692, 0.72956, 0.99055, +-3.13616, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.21824, -3.23820, -3.32990, -3.38911, -3.35242, -3.32848, -3.31705, -3.25258, -3.20415, -3.00698, -2.80447, -2.73953, -2.68379, -2.53630, -2.40815, -2.33022, -2.39275, -2.56932, -2.71961, -2.82378, -3.02960, -3.16921, -3.23238, -3.22885, -3.12743, -3.08161, -3.09733, -3.17455, -3.18172, -3.13863, -3.10255, -2.91703, -2.66021, -2.54316, -2.51369, -2.36681, -2.22680, -2.14421, -2.12895, -2.10692, -2.08439, -2.02609, -2.05551, -2.24335, -2.31747, -2.11389, -1.79591, -1.45135, -1.18196, -0.95888, -0.75635, -0.59561, -0.45388, -0.19084, 0.13085, 0.29120, 0.43037, 0.57429, 0.75775, 0.92274, 0.97250, 0.91911, 0.60213, 0.31755, 0.18373, 0.10456, -0.06066, -0.18318, -0.36051, -0.54068, -0.78928, -0.98717, -1.22976, -1.40534, -1.51657, -1.76503, -2.03753, -2.19912, -2.30364, -2.44205, -2.69953, -3.01777, -3.29870, -3.40371, -3.51320, -3.60027, -3.68286, -3.80548, -3.75648, -3.63466, -3.40859, -3.17739, -3.09238, -3.06604, -3.23849, -3.30059, -3.30721, -3.26049, -3.27362, -3.16650, -2.99594, -2.87935, -2.96271, -3.03962, -3.08768, -2.94273, -2.70766, -2.65587, -2.66555, -2.53575, -2.39025, -2.29166, -2.33701, -2.37417, -2.44386, -2.53121, -2.69760, -2.73870, -2.61746, -2.52256, -2.39249, -2.32987, -2.32303, -2.27812, -2.18294, -1.87896, -1.70019, -1.52042, -1.31245, -1.03816, -0.87519, -0.63619, -0.44399, -0.25390, -0.09700, 0.10624, 0.29523, 0.64055, 1.10184, 1.42919, 1.61682, 1.84123, 2.11495, 2.45496, 2.67393, 2.81953, 2.85863, 3.01912, 3.23885, 3.49494, 3.85314, 4.01565, 4.02693, 3.84995, 3.61520, 3.45209, 3.17170, 3.05749, 2.89776, 2.81172, 2.84828, 2.82914, 2.54748, 2.29749, 2.08507, 1.96996, 1.73865, 1.48181, 1.22001, 1.07556, 1.09566, 1.05162, 0.94079, 1.01166, 1.14495, 1.20254, 1.08596, 0.98327, 0.85335, 0.82402, 0.78567, 0.66188, 0.56872, 0.39719, 0.33486, 0.34818, 0.36048, 0.37865, 0.29901, 0.36696, 0.39140, 0.41925, 0.51633, 0.64770, 0.68150, 0.74983, 0.78230, 0.79610, 0.68094, 0.45673, 0.19341, -0.08052, -0.16000, -0.20613, -0.36684, -0.49181, -0.58574, -0.56059, -0.52889, -0.48098, -0.46177, -0.42093, -0.37005, -0.41995, -0.34542, -0.26524, -0.22073, -0.11582, -0.04202, 0.07077, 0.12786, 0.17536, 0.09319, -0.04576, -0.00190, 0.21429, 0.32321, 0.36043, 0.37394, 0.40600, 0.36060, 0.27006, 0.22770, 0.23757, 0.36452, 0.37931, 0.16929, 0.07104, 0.06027, 0.11619, 0.09428, -0.02387, -0.28868, -0.48060, -0.44929, -0.37466, -0.25834, -0.25803, -0.36496, -0.37977, -0.40018, -0.36026, -0.38768, -0.36647, -0.31848, -0.36393, -0.33818, -0.21153, -0.16380, -0.26320, -0.34164, -0.42258, -0.44336, -0.44945, -0.47235, -0.57637, -0.64596, -0.69993, -0.96412, -1.20418, -1.35716, -1.49912, -1.64774, -1.84810, -1.99843, -2.03526, -1.93568, -1.80996, -1.65108, -1.52096, -1.48147, -1.44463, -1.50149, -1.50882, -1.41312, -1.16316, -0.88353, -0.83089, -0.77272, -0.59640, -0.44151, -0.40749, -0.36164, -0.34451, -0.36316, -0.50324, -0.55851, -0.48631, -0.21188, 0.09753, 0.20818, 0.24732, 0.26842, 0.27351, 0.38655, 0.45196, 0.42982, 0.28953, 0.22102, 0.13503, 0.07187, -0.02607, -0.28371, -0.44791, -0.57925, -0.66015, -0.74192, -0.72499, -0.57651, -0.61197, -0.61021, -0.50238, -0.27456, -0.11253, 0.05301, 0.06914, 0.00008, -0.07959, -0.12236, -0.17526, -0.14250, -0.07016, -0.19721, -0.36230, -0.35007, -0.27061, -0.13328, -0.02092, 0.06684, 0.16581, 0.38633, 0.49611, 0.52066, 0.50635, 0.38967, 0.34084, 0.21736, 0.01276, -0.18952, -0.35594, -0.35039, -0.47837, -0.52876, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.73665, -0.84130, -0.90452, -1.01209, -1.05713, -1.10013, -1.11332, -1.14757, -1.09976, -1.01065, -0.89532, -0.73061, -0.68648, -0.50073, -0.29989, -0.19121, -0.10093, -0.08724, 0.16192, 0.30531, 0.41958, 0.50042, 0.63275, 0.76268, 1.03335, +-3.20109, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.60610, -3.53396, -3.42158, -3.41084, -3.51447, -3.57396, -3.50390, -3.35911, -3.18818, -3.16155, -3.12438, -2.86046, -2.68265, -2.58155, -2.46739, -2.32132, -2.17885, -2.09416, -2.23189, -2.39093, -2.56329, -2.78571, -2.97446, -3.15443, -3.23581, -3.24496, -3.15195, -3.09744, -3.12746, -3.18442, -3.15767, -3.17722, -3.16864, -2.95320, -2.63488, -2.38399, -2.30950, -2.24627, -2.18299, -2.09632, -1.99007, -2.03630, -2.10787, -2.08911, -2.19504, -2.40025, -2.43348, -2.24510, -1.90877, -1.54594, -1.35820, -1.13499, -0.84434, -0.72861, -0.54962, -0.30894, 0.03743, 0.25661, 0.49581, 0.70842, 0.90235, 1.06456, 1.13171, 1.06774, 0.77853, 0.56537, 0.50979, 0.49053, 0.31925, 0.05687, -0.22428, -0.42594, -0.56762, -0.78612, -1.05427, -1.16733, -1.29398, -1.55770, -1.75887, -1.95364, -2.12459, -2.31851, -2.66864, -3.04620, -3.24234, -3.39985, -3.43150, -3.47393, -3.50773, -3.62226, -3.59549, -3.55846, -3.42410, -3.22100, -3.05562, -2.96908, -3.09424, -3.14753, -3.14767, -3.06659, -3.05642, -3.04868, -2.96830, -2.91796, -2.87698, -2.92348, -3.00046, -2.79991, -2.55902, -2.55031, -2.52550, -2.41655, -2.25277, -2.10940, -2.19688, -2.29095, -2.23790, -2.32842, -2.37511, -2.39246, -2.30147, -2.29988, -2.27877, -2.27811, -2.29711, -2.21922, -1.99704, -1.66699, -1.49193, -1.34201, -1.14322, -0.82707, -0.60999, -0.44261, -0.27114, -0.09790, 0.17784, 0.41317, 0.53568, 0.85994, 1.23859, 1.43183, 1.62847, 1.80472, 2.05468, 2.42609, 2.63773, 2.73144, 2.88193, 2.97782, 3.18108, 3.35887, 3.64547, 3.78945, 3.83180, 3.72028, 3.51994, 3.34908, 3.15614, 3.08863, 2.94536, 2.85084, 2.82409, 2.74241, 2.47134, 2.11952, 1.84611, 1.68535, 1.58708, 1.42407, 1.11269, 1.00100, 1.06819, 0.96451, 0.86342, 0.91171, 1.04151, 1.19158, 1.16349, 1.02641, 1.00048, 0.90148, 0.81069, 0.68999, 0.60652, 0.51613, 0.54356, 0.59857, 0.62524, 0.61000, 0.59490, 0.70985, 0.71835, 0.71158, 0.77314, 0.87700, 0.90383, 0.84981, 0.78356, 0.68258, 0.59714, 0.44046, 0.11845, -0.16064, -0.20186, -0.31026, -0.44994, -0.57149, -0.69940, -0.66530, -0.64650, -0.73621, -0.66188, -0.58410, -0.47051, -0.39780, -0.29963, -0.23206, -0.21368, -0.13966, -0.08842, -0.03106, 0.00735, 0.03537, -0.08089, -0.24523, -0.21831, 0.00359, 0.17111, 0.16675, 0.11217, 0.10431, 0.17001, 0.20302, 0.07209, 0.04499, 0.21063, 0.21692, 0.08825, 0.04234, 0.01571, 0.06035, 0.01895, -0.17703, -0.36607, -0.45564, -0.41484, -0.31136, -0.25748, -0.31828, -0.45446, -0.47261, -0.49611, -0.48549, -0.47305, -0.39719, -0.37150, -0.42368, -0.38796, -0.26291, -0.18228, -0.28299, -0.39276, -0.48987, -0.40440, -0.24022, -0.27768, -0.38080, -0.40842, -0.52939, -0.84775, -1.13638, -1.35291, -1.46145, -1.52137, -1.71245, -1.82048, -1.81031, -1.78489, -1.63196, -1.50487, -1.40141, -1.43167, -1.44012, -1.48410, -1.48621, -1.33530, -0.99992, -0.73514, -0.73318, -0.74326, -0.60913, -0.44306, -0.45950, -0.55970, -0.60716, -0.56173, -0.48311, -0.48803, -0.43354, -0.14552, 0.05135, 0.06632, 0.12005, 0.14389, 0.26373, 0.49841, 0.55769, 0.52965, 0.45090, 0.32077, 0.30427, 0.24364, 0.15746, -0.09234, -0.24263, -0.37365, -0.47349, -0.56121, -0.54505, -0.50648, -0.62303, -0.68515, -0.63235, -0.39100, -0.21197, -0.11132, -0.08058, -0.09293, -0.00510, -0.06813, -0.23862, -0.22751, -0.20420, -0.35779, -0.44576, -0.44867, -0.35652, -0.17193, -0.07480, -0.00471, 0.17786, 0.26493, 0.35461, 0.33662, 0.28842, 0.15658, 0.12536, 0.02129, -0.19464, -0.40785, -0.49181, -0.47338, -0.62783, -0.72223, -0.64059, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.56840, -0.63721, -0.74526, -0.72703, -0.76266, -0.84068, -0.80091, -0.84389, -0.76127, -0.68314, -0.54857, -0.52526, -0.38029, -0.23956, -0.16644, -0.11329, -0.05287, 0.20179, 0.32806, 0.43695, 0.54153, 0.71862, 0.90580, 1.05738, +0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.65556, -3.70199, -3.66280, -3.70780, -3.74844, -3.72267, -3.63855, -3.51624, -3.35279, -3.21160, -3.20509, -3.14736, -2.87223, -2.59579, -2.37667, -2.20097, -2.03060, -1.97208, -1.99404, -2.09133, -2.19432, -2.38855, -2.63575, -2.87277, -3.10425, -3.10612, -3.04617, -2.97659, -2.93368, -2.97123, -3.02307, -3.02823, -3.13997, -3.13373, -2.86046, -2.58487, -2.37160, -2.21584, -2.11735, -2.09092, -2.02330, -1.97660, -2.12114, -2.26404, -2.30377, -2.34870, -2.43490, -2.39905, -2.18265, -1.92509, -1.72427, -1.56188, -1.28927, -0.94714, -0.74182, -0.52935, -0.34449, 0.02812, 0.37114, 0.71365, 0.99223, 1.17672, 1.27140, 1.28361, 1.20059, 1.02099, 0.97096, 0.89319, 0.72163, 0.54561, 0.32916, 0.00044, -0.25309, -0.43864, -0.72245, -0.97310, -1.06548, -1.12956, -1.26385, -1.40634, -1.59280, -1.88769, -2.31127, -2.69492, -2.99087, -3.09740, -3.16815, -3.19472, -3.29652, -3.28532, -3.30704, -3.30618, -3.35794, -3.33755, -3.20004, -3.04406, -2.97417, -3.03561, -3.00382, -3.02122, -3.05619, -3.03321, -2.97154, -2.96798, -2.97222, -2.92526, -3.01140, -3.04651, -2.83049, -2.56012, -2.45381, -2.43034, -2.31907, -2.17906, -2.15548, -2.21224, -2.21994, -2.12319, -2.08791, -2.02541, -2.09059, -2.04637, -2.07639, -2.14350, -2.15549, -2.14539, -2.01555, -1.76939, -1.52570, -1.34529, -1.09650, -0.89229, -0.70596, -0.47251, -0.19448, -0.00882, 0.16266, 0.43168, 0.57478, 0.66681, 0.92564, 1.22000, 1.44797, 1.65389, 1.86902, 2.14244, 2.37099, 2.53448, 2.68688, 2.89108, 3.05183, 3.24845, 3.26765, 3.45129, 3.64923, 3.72112, 3.66486, 3.49071, 3.30924, 3.15095, 3.05261, 2.91353, 2.86934, 2.76367, 2.47723, 2.16873, 1.90628, 1.66410, 1.51421, 1.45011, 1.23835, 0.91564, 0.80673, 0.90630, 0.94800, 0.91508, 0.97447, 1.07869, 1.14258, 1.15244, 1.10773, 1.11151, 0.99682, 0.89240, 0.73010, 0.68481, 0.76882, 0.86888, 0.93017, 0.97268, 0.97515, 0.98784, 1.04175, 1.01606, 1.05404, 1.09341, 1.02486, 0.94528, 0.90400, 0.80669, 0.63586, 0.49195, 0.25104, -0.08380, -0.32441, -0.30426, -0.30555, -0.41390, -0.52799, -0.65694, -0.73955, -0.80429, -0.90333, -0.81378, -0.66376, -0.46460, -0.38381, -0.31975, -0.21449, -0.17723, -0.12450, -0.09983, -0.09849, -0.12736, -0.18502, -0.32836, -0.41207, -0.33036, -0.21801, -0.13006, -0.09174, -0.13760, -0.15334, -0.05189, -0.02508, -0.18040, -0.23626, -0.09182, 0.04513, 0.05547, 0.05117, 0.00005, -0.11829, -0.27701, -0.39886, -0.44177, -0.39370, -0.30285, -0.28351, -0.32870, -0.35983, -0.46304, -0.50350, -0.52634, -0.52067, -0.50355, -0.45914, -0.48114, -0.47576, -0.37331, -0.34479, -0.38268, -0.41726, -0.42649, -0.44911, -0.27067, -0.10974, -0.20584, -0.31068, -0.32387, -0.37155, -0.63193, -0.97048, -1.23243, -1.41434, -1.55567, -1.67033, -1.69707, -1.65278, -1.58312, -1.46365, -1.42591, -1.32623, -1.36023, -1.39731, -1.40384, -1.35750, -1.15704, -0.83415, -0.65648, -0.68373, -0.70857, -0.69385, -0.66867, -0.64153, -0.66849, -0.72478, -0.64506, -0.49307, -0.48563, -0.43417, -0.21522, -0.07474, -0.01318, 0.07869, 0.19494, 0.36315, 0.50114, 0.57756, 0.63940, 0.62845, 0.56499, 0.54816, 0.43756, 0.40442, 0.25217, 0.11671, -0.00265, -0.10919, -0.22381, -0.30104, -0.44878, -0.61955, -0.65173, -0.64656, -0.52669, -0.33603, -0.15516, -0.08241, -0.01860, 0.11551, -0.02841, -0.28079, -0.34786, -0.32592, -0.37145, -0.41431, -0.39903, -0.33732, -0.28442, -0.18082, -0.04331, 0.13235, 0.18814, 0.21790, 0.09678, 0.06020, 0.02952, 0.00982, -0.08480, -0.31545, -0.55093, -0.62963, -0.66724, -0.78252, -0.78943, -0.73620, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.32030, -0.33560, -0.41888, -0.52215, -0.56152, -0.55736, -0.48165, -0.49377, -0.44029, -0.47930, -0.37695, -0.28435, -0.18418, -0.11051, -0.06498, -0.01966, 0.08357, 0.28962, 0.38753, 0.54618, 0.65399, 0.72272, 0.91576, 1.11733, +0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.77766, -3.77966, -3.89609, -4.00271, -4.04490, -3.99586, -3.82436, -3.67455, -3.52982, -3.46587, -3.43198, -3.28193, -3.11547, -2.90837, -2.68708, -2.41023, -2.10821, -1.91844, -1.93171, -1.95192, -1.93672, -2.02123, -2.28192, -2.49707, -2.67385, -2.90551, -2.93534, -2.87176, -2.84553, -2.84508, -2.93404, -2.97119, -2.99330, -3.01311, -3.01362, -2.81812, -2.54714, -2.36802, -2.22445, -2.16889, -2.11779, -2.05424, -2.13686, -2.22082, -2.31329, -2.35473, -2.39605, -2.44194, -2.31266, -2.11174, -1.96227, -1.81039, -1.59969, -1.30305, -1.03482, -0.70646, -0.34707, -0.15464, 0.07644, 0.42747, 0.80938, 1.15910, 1.28306, 1.31952, 1.30663, 1.39777, 1.36227, 1.30434, 1.15710, 0.88042, 0.65891, 0.45013, 0.11798, -0.17224, -0.49209, -0.64676, -0.76678, -0.86313, -1.00256, -1.14800, -1.19288, -1.29696, -1.64992, -2.12426, -2.48901, -2.73330, -2.89819, -2.91935, -2.92994, -3.05129, -3.15824, -3.15203, -3.18771, -3.22729, -3.30934, -3.21078, -3.14489, -3.05459, -3.08839, -3.13101, -3.12290, -3.13430, -3.12474, -3.09665, -3.15051, -3.07646, -3.08907, -3.05710, -2.97401, -2.79777, -2.62569, -2.57146, -2.50414, -2.31443, -2.22070, -2.16004, -2.11439, -2.07607, -2.13040, -2.04906, -1.87164, -1.84659, -1.94784, -2.04334, -2.14361, -2.03909, -1.97895, -1.79567, -1.67302, -1.47111, -1.25010, -1.02165, -0.80023, -0.62818, -0.37765, -0.02684, 0.14655, 0.36698, 0.46993, 0.61237, 0.79525, 1.05710, 1.24999, 1.38592, 1.59551, 1.91059, 2.17398, 2.35450, 2.48817, 2.64620, 2.73706, 2.93212, 3.18772, 3.27721, 3.33002, 3.51963, 3.54806, 3.51892, 3.29841, 3.13361, 2.97151, 2.91343, 2.82099, 2.65996, 2.47431, 2.20546, 1.92836, 1.73223, 1.46603, 1.37778, 1.22984, 1.05474, 0.89309, 0.86631, 0.93075, 0.99365, 1.02637, 1.12054, 1.11586, 1.13109, 1.20438, 1.25151, 1.12573, 0.93474, 0.90342, 0.90805, 0.88580, 1.00769, 1.03298, 1.08358, 1.11229, 1.18442, 1.18616, 1.19878, 1.23396, 1.22774, 1.19406, 1.06921, 0.89467, 0.82688, 0.66978, 0.57547, 0.35677, 0.08573, -0.12483, -0.26477, -0.26181, -0.33442, -0.48697, -0.58413, -0.73782, -0.83804, -0.85809, -0.86679, -0.85222, -0.73671, -0.50280, -0.37838, -0.42116, -0.37879, -0.34994, -0.28685, -0.31184, -0.36883, -0.44692, -0.48830, -0.50589, -0.57636, -0.55761, -0.49762, -0.46099, -0.41317, -0.47769, -0.40486, -0.32292, -0.27718, -0.27939, -0.31978, -0.29992, -0.22720, -0.17890, -0.11739, -0.22653, -0.44527, -0.54561, -0.49908, -0.46068, -0.43454, -0.36245, -0.34855, -0.46010, -0.52284, -0.63594, -0.70928, -0.70855, -0.67739, -0.65620, -0.66356, -0.63381, -0.61848, -0.53567, -0.45884, -0.48249, -0.47503, -0.47116, -0.38202, -0.16562, -0.09584, -0.13145, -0.21385, -0.26115, -0.32972, -0.56116, -0.83420, -1.10409, -1.34003, -1.50222, -1.58845, -1.64708, -1.68454, -1.53462, -1.35389, -1.35683, -1.37389, -1.40393, -1.39585, -1.30523, -1.22130, -1.01515, -0.79653, -0.60823, -0.67176, -0.79350, -0.79967, -0.78937, -0.67897, -0.67016, -0.73185, -0.65440, -0.56326, -0.40789, -0.29695, -0.19626, -0.18951, -0.11509, 0.09841, 0.34980, 0.49155, 0.56145, 0.63479, 0.72433, 0.66834, 0.65466, 0.67109, 0.62093, 0.56279, 0.46357, 0.30242, 0.21144, 0.07896, -0.01845, -0.17270, -0.32406, -0.52143, -0.66893, -0.66707, -0.56077, -0.39480, -0.24601, -0.18377, -0.00953, 0.08626, 0.06760, -0.10719, -0.22450, -0.28936, -0.40517, -0.45800, -0.41690, -0.40230, -0.34543, -0.22350, -0.09908, -0.10608, -0.06512, 0.00586, -0.05864, -0.17037, -0.19560, -0.28249, -0.33655, -0.58930, -0.76969, -0.87356, -0.84163, -0.83162, -0.89598, -0.90699, -0.86441, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.35980, -0.27013, -0.32615, -0.43893, -0.44642, -0.33055, -0.31127, -0.30995, -0.26851, -0.28724, -0.28446, -0.15531, -0.07383, 0.03872, 0.04136, 0.11247, 0.20508, 0.42953, 0.53513, 0.53778, 0.56120, 0.64069, 0.85623, 1.09196, +0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.90068, -3.94590, -3.98504, -4.08478, -4.16025, -4.10679, -3.94656, -3.75124, -3.64470, -3.63603, -3.70253, -3.70518, -3.49346, -3.27526, -3.09598, -2.84412, -2.48908, -2.21398, -2.06230, -1.98684, -1.85803, -1.80846, -1.89584, -2.10811, -2.29270, -2.49344, -2.76894, -2.81243, -2.75732, -2.79891, -2.88735, -2.96645, -2.94188, -2.96242, -2.94543, -2.86833, -2.61941, -2.35968, -2.22597, -2.17384, -2.19639, -2.16868, -2.15161, -2.25333, -2.30417, -2.33571, -2.28023, -2.21060, -2.15070, -2.06224, -1.99121, -1.84416, -1.59686, -1.37910, -1.11537, -0.85195, -0.47778, -0.09928, 0.01716, 0.17721, 0.50347, 0.82906, 1.11561, 1.22770, 1.32535, 1.38898, 1.56816, 1.64581, 1.63665, 1.37449, 1.01560, 0.71505, 0.45447, 0.10274, -0.28866, -0.65114, -0.74489, -0.80042, -0.86601, -0.97593, -1.01580, -1.04269, -1.17953, -1.44616, -1.76362, -2.13045, -2.45141, -2.66225, -2.71136, -2.77081, -2.99697, -3.15207, -3.12143, -3.19572, -3.28318, -3.37516, -3.25183, -3.24247, -3.22937, -3.26496, -3.22630, -3.17900, -3.15366, -3.18295, -3.25766, -3.32312, -3.23593, -3.21157, -3.09976, -2.98479, -2.84209, -2.69530, -2.56635, -2.47377, -2.34421, -2.23538, -2.00039, -1.91037, -1.97085, -2.10073, -2.03831, -1.85113, -1.84911, -1.97167, -1.99690, -2.01504, -1.88250, -1.77778, -1.57524, -1.57881, -1.47398, -1.24640, -0.88800, -0.62414, -0.45237, -0.22982, 0.04878, 0.19220, 0.32322, 0.35329, 0.51035, 0.71680, 1.00670, 1.21409, 1.41816, 1.61670, 1.82369, 2.05218, 2.33112, 2.45907, 2.49726, 2.53698, 2.74958, 3.02977, 3.12377, 3.16750, 3.39648, 3.40155, 3.27865, 3.01573, 2.91351, 2.78143, 2.70345, 2.59198, 2.47089, 2.30909, 2.12654, 1.89121, 1.65434, 1.36583, 1.20749, 1.04161, 0.94638, 0.90356, 0.95979, 1.03939, 1.21833, 1.28461, 1.23125, 1.13451, 1.22617, 1.34422, 1.32509, 1.13126, 0.95681, 1.00957, 1.04192, 1.02586, 1.12425, 1.04406, 0.99075, 0.99352, 1.16756, 1.19512, 1.13612, 1.13163, 1.17500, 1.13942, 0.99391, 0.77543, 0.61980, 0.42604, 0.32005, 0.11097, -0.11234, -0.27366, -0.38744, -0.41609, -0.45162, -0.59489, -0.80738, -0.98191, -0.93810, -0.82780, -0.81849, -0.83011, -0.72334, -0.52745, -0.50742, -0.64624, -0.60922, -0.56368, -0.55567, -0.65043, -0.69642, -0.72406, -0.71899, -0.69530, -0.67695, -0.64945, -0.63595, -0.63542, -0.65092, -0.71948, -0.65130, -0.59872, -0.49616, -0.44331, -0.50021, -0.54556, -0.46087, -0.37335, -0.39882, -0.58055, -0.67616, -0.57362, -0.47727, -0.44240, -0.47381, -0.49703, -0.56630, -0.73069, -0.75421, -0.85525, -1.00909, -1.06744, -0.99509, -0.92788, -0.96136, -0.93111, -0.82205, -0.63803, -0.47633, -0.43104, -0.44853, -0.49117, -0.43447, -0.29403, -0.25000, -0.27354, -0.35848, -0.38457, -0.36834, -0.47171, -0.73297, -1.04615, -1.22235, -1.30344, -1.46255, -1.61502, -1.66391, -1.48287, -1.31780, -1.38503, -1.41461, -1.36886, -1.30775, -1.20867, -1.07370, -0.85259, -0.72729, -0.60694, -0.64451, -0.68173, -0.67386, -0.65364, -0.53881, -0.57670, -0.68634, -0.69191, -0.62501, -0.42559, -0.30802, -0.23660, -0.17506, 0.05761, 0.29760, 0.50293, 0.61592, 0.72027, 0.73474, 0.75027, 0.70247, 0.67791, 0.64381, 0.54695, 0.51214, 0.47825, 0.30465, 0.18196, 0.08672, 0.06239, -0.08680, -0.25308, -0.43921, -0.54170, -0.57081, -0.50654, -0.40680, -0.35878, -0.32056, -0.15382, -0.02160, 0.06862, -0.02394, -0.11713, -0.17482, -0.25044, -0.37696, -0.45679, -0.42789, -0.22921, -0.13669, -0.16166, -0.27379, -0.24740, -0.16896, -0.27434, -0.39670, -0.41559, -0.56140, -0.67421, -0.89276, -0.94721, -1.02657, -0.99876, -0.92228, -0.91123, -0.96019, -0.94419, -0.78909, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.44786, -0.42472, -0.41906, -0.37641, -0.35246, -0.27761, -0.25610, -0.23943, -0.21565, -0.27890, -0.27910, -0.07782, 0.04741, 0.14542, 0.14332, 0.27194, 0.33809, 0.47496, 0.53369, 0.53780, 0.51083, 0.59289, 0.79287, 0.96916, +0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.90801, -3.88340, -3.97510, -4.17487, -4.19106, -4.08196, -3.93521, -3.75358, -3.57391, -3.62218, -3.75766, -3.75058, -3.57826, -3.30022, -3.13015, -2.97309, -2.59079, -2.31644, -2.07962, -1.91905, -1.76906, -1.69170, -1.79283, -1.86417, -2.07884, -2.43613, -2.65727, -2.70206, -2.72060, -2.75338, -2.83250, -2.88002, -2.86187, -2.79346, -2.78823, -2.80133, -2.54332, -2.27310, -2.18225, -2.14205, -2.07580, -2.02310, -2.07019, -2.11894, -2.17572, -2.11476, -1.99976, -1.98618, -1.89020, -1.79743, -1.69409, -1.50843, -1.32913, -1.10350, -0.89154, -0.51270, -0.14537, 0.05016, 0.16741, 0.35823, 0.58145, 0.88921, 1.13164, 1.25408, 1.35928, 1.56902, 1.79082, 1.79032, 1.74919, 1.47179, 1.03902, 0.70877, 0.52191, 0.22510, -0.25992, -0.59381, -0.73207, -0.73494, -0.73822, -0.88927, -0.88431, -0.87749, -0.97914, -1.15679, -1.52666, -1.87021, -2.28166, -2.44172, -2.48573, -2.70653, -2.94181, -3.02234, -3.10045, -3.20155, -3.35263, -3.44342, -3.38585, -3.31382, -3.25725, -3.35969, -3.33348, -3.23317, -3.25234, -3.30037, -3.32276, -3.30043, -3.29656, -3.21625, -3.11820, -2.97010, -2.77002, -2.69280, -2.57049, -2.43243, -2.28934, -2.09468, -1.93228, -1.84950, -2.00968, -2.07076, -1.93610, -1.86482, -1.87154, -1.84575, -1.86150, -1.78346, -1.65279, -1.51834, -1.39947, -1.38297, -1.22926, -1.06766, -0.73217, -0.40604, -0.28243, -0.11100, 0.15442, 0.36134, 0.36211, 0.40865, 0.53577, 0.72330, 1.06102, 1.19141, 1.34144, 1.56827, 1.73400, 2.00631, 2.21136, 2.34889, 2.31787, 2.41312, 2.71424, 2.86587, 2.88176, 3.04474, 3.22611, 3.25752, 3.13123, 2.91585, 2.77875, 2.69578, 2.69171, 2.50842, 2.32081, 2.21693, 2.01894, 1.77385, 1.56478, 1.40903, 1.19587, 1.08340, 1.02752, 1.02379, 1.18606, 1.23217, 1.34781, 1.43359, 1.33575, 1.31293, 1.36402, 1.47812, 1.39128, 1.22191, 1.19542, 1.17383, 1.07704, 1.13609, 1.13662, 1.00426, 0.91807, 0.94525, 1.09365, 1.14587, 1.15748, 1.05530, 0.97661, 0.96477, 0.78947, 0.54760, 0.39225, 0.30154, 0.13738, -0.06978, -0.27539, -0.45227, -0.51460, -0.61080, -0.72334, -0.79240, -0.97770, -1.02647, -0.95924, -0.84618, -0.86288, -0.87134, -0.64984, -0.54397, -0.67266, -0.72999, -0.72123, -0.70789, -0.72086, -0.81598, -0.89119, -0.90842, -0.79928, -0.81153, -0.87839, -0.82045, -0.82528, -0.87640, -0.91018, -0.86124, -0.80901, -0.78203, -0.66240, -0.65318, -0.64224, -0.69436, -0.68892, -0.55182, -0.58501, -0.68802, -0.70572, -0.59140, -0.50688, -0.50947, -0.45225, -0.54783, -0.76393, -0.84080, -0.83931, -0.98943, -1.16005, -1.25460, -1.21295, -1.15086, -1.06610, -1.00913, -0.94307, -0.70414, -0.50445, -0.49156, -0.53090, -0.49120, -0.46953, -0.43639, -0.36876, -0.40750, -0.39314, -0.36839, -0.40858, -0.44670, -0.67801, -0.92127, -1.05815, -1.18768, -1.33757, -1.53703, -1.46819, -1.29858, -1.27882, -1.28514, -1.25673, -1.25197, -1.15653, -1.06160, -0.91549, -0.73103, -0.53494, -0.43115, -0.55776, -0.57474, -0.53717, -0.56965, -0.48697, -0.46029, -0.52856, -0.61056, -0.50263, -0.33604, -0.16894, -0.05336, -0.02549, 0.26525, 0.52640, 0.74371, 0.86699, 0.87276, 0.88236, 0.81025, 0.84091, 0.80167, 0.58317, 0.46696, 0.49246, 0.40558, 0.28597, 0.18834, 0.14635, 0.09064, 0.02332, -0.12417, -0.40151, -0.52861, -0.56660, -0.60750, -0.54436, -0.42330, -0.27857, -0.17719, 0.00744, 0.08173, 0.04340, 0.01546, -0.10475, -0.15714, -0.23520, -0.30665, -0.22002, -0.11475, -0.05028, -0.21963, -0.32341, -0.30553, -0.41061, -0.56354, -0.59805, -0.68900, -0.80862, -0.93900, -1.10247, -1.16774, -1.15533, -1.06958, -1.07817, -1.11562, -1.11979, -1.15283, -1.01856, -0.85261, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.51201, -0.47766, -0.36582, -0.35790, -0.29557, -0.29221, -0.19877, -0.07116, -0.14017, -0.22479, -0.09157, 0.05941, 0.21520, 0.29373, 0.32771, 0.40383, 0.47682, 0.62624, 0.58512, 0.51338, 0.52171, 0.52955, 0.65180, 0.80658, +0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.61942, -3.76537, -3.82864, -4.02005, -4.22236, -4.16344, -3.97023, -3.81166, -3.74975, -3.65934, -3.62781, -3.68385, -3.67358, -3.54174, -3.35444, -3.24075, -3.06318, -2.63817, -2.36007, -2.07955, -1.84438, -1.68056, -1.54344, -1.58622, -1.73803, -2.02905, -2.30511, -2.41802, -2.52827, -2.60644, -2.60729, -2.60674, -2.60565, -2.60755, -2.59678, -2.67877, -2.69650, -2.43627, -2.15818, -2.01744, -2.00107, -1.97795, -1.84830, -1.80871, -1.80901, -1.82701, -1.79878, -1.78799, -1.79805, -1.68755, -1.61338, -1.50739, -1.31172, -1.15460, -0.83972, -0.49324, -0.13580, 0.10925, 0.27571, 0.46402, 0.62225, 0.76290, 1.01213, 1.22157, 1.32834, 1.46456, 1.69919, 1.81083, 1.75474, 1.69271, 1.43952, 1.07041, 0.71180, 0.44562, 0.22136, -0.13950, -0.43053, -0.55452, -0.57007, -0.62927, -0.73559, -0.70245, -0.74534, -0.91975, -1.11859, -1.49414, -1.75881, -2.06066, -2.29555, -2.48812, -2.69743, -2.76355, -2.81310, -2.97146, -3.13078, -3.30086, -3.41008, -3.41764, -3.37721, -3.39972, -3.49330, -3.43432, -3.31811, -3.29238, -3.34130, -3.42569, -3.35936, -3.29455, -3.21873, -3.13179, -3.00232, -2.88067, -2.80483, -2.63307, -2.45063, -2.30536, -2.08921, -1.98145, -1.92567, -1.99043, -2.03577, -2.01199, -1.95526, -1.80553, -1.68811, -1.62285, -1.47067, -1.33610, -1.24040, -1.19718, -1.17495, -1.08819, -0.94222, -0.58535, -0.23062, -0.04180, 0.12787, 0.28929, 0.51595, 0.61801, 0.69656, 0.78221, 0.88177, 1.03768, 1.09201, 1.27087, 1.52285, 1.62587, 1.83895, 1.97987, 2.13963, 2.28144, 2.43665, 2.60884, 2.69389, 2.82811, 3.04126, 3.18231, 3.21129, 3.12864, 2.95267, 2.78894, 2.69617, 2.60040, 2.39058, 2.24038, 2.14562, 1.95593, 1.70331, 1.40427, 1.29458, 1.23704, 1.19726, 1.19497, 1.24221, 1.33940, 1.35980, 1.47015, 1.52248, 1.36692, 1.35835, 1.37106, 1.45606, 1.46797, 1.36511, 1.30469, 1.22944, 1.16563, 1.19416, 1.09454, 0.93938, 0.87214, 0.90304, 1.00255, 1.04995, 0.99559, 0.83737, 0.76810, 0.78283, 0.67480, 0.48089, 0.21844, 0.07916, -0.03960, -0.22725, -0.39618, -0.55324, -0.73902, -0.94839, -1.05442, -1.04849, -1.16442, -1.13264, -1.06809, -0.96724, -0.86817, -0.80203, -0.67590, -0.66147, -0.70550, -0.68162, -0.70655, -0.72724, -0.73811, -0.81215, -0.90461, -0.96095, -0.96808, -1.07826, -1.15575, -1.07373, -1.03232, -1.06122, -1.14964, -1.07993, -0.90561, -0.80968, -0.69591, -0.72360, -0.78906, -0.88314, -0.87047, -0.71529, -0.76914, -0.83155, -0.77816, -0.66635, -0.54312, -0.52054, -0.54717, -0.70627, -0.83489, -0.80687, -0.82795, -0.99788, -1.15130, -1.23198, -1.20042, -1.12996, -1.03673, -1.00198, -0.93013, -0.68544, -0.49729, -0.47378, -0.55633, -0.55448, -0.50765, -0.48396, -0.41455, -0.41447, -0.37775, -0.37612, -0.40980, -0.40800, -0.63046, -0.86880, -1.02121, -1.18614, -1.25370, -1.34184, -1.30967, -1.24644, -1.18293, -1.04736, -1.00063, -1.04418, -0.98677, -0.90346, -0.78321, -0.62100, -0.44538, -0.42730, -0.52332, -0.46020, -0.37059, -0.35907, -0.34429, -0.41220, -0.41159, -0.40345, -0.29741, -0.15526, -0.03457, 0.03553, 0.13526, 0.47247, 0.68729, 0.82798, 0.92272, 0.89724, 0.94812, 0.95169, 0.91912, 0.74617, 0.52779, 0.53097, 0.57979, 0.49739, 0.44438, 0.41208, 0.36379, 0.25027, 0.11996, -0.12864, -0.38179, -0.45907, -0.52541, -0.59522, -0.56842, -0.48517, -0.21279, 0.00826, 0.18525, 0.24610, 0.19263, 0.07942, -0.04842, -0.04863, -0.09298, -0.18357, -0.10976, -0.08717, -0.04535, -0.14544, -0.31016, -0.50099, -0.71121, -0.78217, -0.80820, -0.91427, -1.00854, -1.10757, -1.21657, -1.25416, -1.21430, -1.21208, -1.26253, -1.29869, -1.27850, -1.26129, -1.15212, -1.08819, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.59918, -0.59589, -0.46751, -0.46175, -0.34471, -0.18011, -0.01644, 0.06224, 0.03626, 0.11812, 0.27482, 0.36028, 0.46445, 0.55341, 0.63322, 0.69129, 0.70459, 0.68971, 0.60225, 0.57411, 0.62744, 0.64291, 0.68602, 0.69024, +0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -3.26593, -3.50412, -3.65162, -3.71840, -3.96295, -4.13329, -4.05786, -3.93601, -3.79910, -3.78278, -3.74588, -3.67359, -3.69039, -3.63996, -3.58395, -3.46860, -3.25936, -2.99929, -2.60874, -2.30968, -1.93739, -1.56131, -1.43848, -1.42295, -1.51876, -1.83200, -1.99198, -2.04204, -2.21199, -2.41092, -2.48252, -2.47046, -2.36261, -2.39691, -2.44513, -2.43184, -2.53396, -2.51084, -2.30803, -2.17297, -2.02641, -1.94807, -1.93074, -1.82511, -1.80725, -1.72627, -1.69395, -1.67319, -1.62711, -1.62306, -1.59790, -1.55724, -1.38362, -1.11843, -0.94052, -0.65640, -0.23505, 0.03728, 0.32191, 0.62187, 0.71810, 0.76650, 0.89724, 1.03899, 1.24656, 1.30228, 1.46584, 1.74417, 1.75740, 1.64000, 1.55673, 1.29573, 1.00732, 0.72813, 0.43150, 0.21105, -0.11987, -0.33578, -0.42801, -0.46265, -0.41882, -0.41459, -0.48365, -0.66939, -0.91640, -1.13168, -1.39831, -1.65713, -1.87841, -2.24062, -2.45309, -2.49295, -2.56537, -2.75204, -2.94945, -3.22345, -3.35683, -3.48750, -3.57064, -3.52682, -3.57571, -3.63394, -3.54686, -3.52344, -3.51054, -3.46495, -3.51296, -3.43651, -3.45307, -3.40695, -3.33499, -3.25572, -3.06110, -2.90037, -2.73735, -2.57450, -2.38084, -2.14345, -1.98703, -2.03328, -2.05400, -2.15097, -2.15087, -1.94613, -1.75363, -1.68251, -1.46124, -1.31306, -1.18929, -1.17193, -1.18497, -1.04102, -0.91243, -0.75564, -0.38890, -0.09089, 0.11265, 0.37510, 0.55174, 0.78714, 0.88148, 0.97911, 0.99559, 0.92137, 0.96672, 1.03215, 1.26170, 1.51430, 1.64404, 1.81503, 2.01065, 2.11636, 2.33366, 2.43071, 2.48326, 2.65508, 2.84811, 2.93894, 3.07815, 3.04490, 2.99395, 2.85226, 2.63989, 2.56472, 2.45557, 2.25904, 2.18763, 2.04795, 1.76478, 1.54302, 1.24608, 1.16050, 1.12725, 1.12025, 1.18551, 1.22695, 1.34239, 1.43860, 1.55759, 1.53721, 1.39461, 1.41120, 1.50241, 1.49175, 1.50962, 1.41679, 1.32075, 1.31646, 1.21968, 0.99001, 0.86066, 0.73920, 0.71551, 0.75494, 0.75319, 0.83101, 0.81701, 0.65914, 0.65602, 0.65999, 0.54181, 0.43550, 0.12917, -0.10721, -0.36030, -0.58095, -0.63085, -0.75939, -0.96591, -1.15221, -1.21737, -1.20681, -1.24141, -1.16972, -1.04128, -1.00452, -0.87898, -0.79065, -0.80395, -0.74886, -0.70985, -0.82276, -0.87882, -0.92344, -0.94150, -0.94885, -1.05847, -1.09849, -1.14943, -1.33868, -1.40897, -1.35795, -1.37526, -1.35713, -1.39289, -1.29810, -1.11983, -1.02007, -0.85236, -0.89939, -0.98461, -0.99048, -0.93518, -0.85999, -0.93001, -0.92622, -0.73831, -0.68625, -0.67932, -0.70229, -0.80335, -0.79189, -0.73436, -0.81482, -0.90132, -1.03465, -1.17578, -1.19362, -1.18996, -1.07269, -0.87590, -0.83123, -0.77641, -0.61802, -0.60516, -0.55499, -0.52019, -0.48908, -0.49162, -0.56372, -0.46289, -0.43342, -0.39759, -0.34211, -0.35101, -0.40736, -0.61348, -0.80304, -0.92719, -1.13566, -1.26426, -1.30435, -1.37672, -1.28652, -1.07846, -0.98710, -0.95631, -0.95968, -0.99411, -0.90916, -0.86567, -0.71377, -0.48278, -0.48757, -0.51628, -0.40178, -0.36312, -0.31024, -0.22976, -0.30412, -0.30662, -0.32305, -0.20385, -0.09016, -0.02902, 0.14357, 0.36405, 0.62367, 0.72772, 0.83567, 0.99799, 1.05477, 1.04386, 1.04844, 0.86399, 0.69154, 0.61520, 0.57071, 0.56130, 0.58219, 0.56712, 0.60945, 0.46861, 0.25622, 0.08546, -0.16457, -0.29916, -0.29453, -0.45639, -0.57890, -0.48586, -0.36779, -0.07567, 0.07191, 0.21337, 0.26247, 0.17890, 0.11887, 0.03737, -0.01146, -0.09106, -0.14440, -0.06757, -0.05629, -0.14884, -0.23272, -0.50261, -0.78994, -0.97454, -1.12222, -1.27620, -1.29947, -1.39065, -1.41464, -1.48283, -1.50367, -1.38449, -1.38016, -1.41088, -1.41034, -1.45093, -1.44697, -1.28251, -1.22926, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.73294, -0.71252, -0.56965, -0.44605, -0.35233, -0.08315, 0.10653, 0.22422, 0.42074, 0.54344, 0.50278, 0.54458, 0.52002, 0.66615, 0.83821, 0.90313, 0.93724, 0.86627, 0.79034, 0.84052, 0.83006, 0.72371, 0.73623, 0.69771, +0.00000, 0.00000, 0.00000, 0.00000, -3.11209, -3.18038, -3.37342, -3.48878, -3.53381, -3.77422, -4.01486, -4.02172, -3.93641, -3.82417, -3.81407, -3.73066, -3.54580, -3.48828, -3.41492, -3.38191, -3.27305, -3.02690, -2.77811, -2.44398, -2.13744, -1.71952, -1.34731, -1.31790, -1.38857, -1.54201, -1.82234, -1.82030, -1.81890, -2.01708, -2.19871, -2.25490, -2.26796, -2.21754, -2.31244, -2.38632, -2.37817, -2.46346, -2.48330, -2.39380, -2.30902, -2.16395, -2.06420, -2.01264, -1.88438, -1.82970, -1.69860, -1.61316, -1.51029, -1.38504, -1.37478, -1.38244, -1.33279, -1.11166, -0.84761, -0.73296, -0.51422, -0.13127, 0.16423, 0.56226, 0.90431, 0.92919, 0.93124, 1.03364, 1.10855, 1.23499, 1.26704, 1.43945, 1.65857, 1.60926, 1.41506, 1.28766, 1.12516, 0.95228, 0.73659, 0.47853, 0.30051, 0.04855, -0.14804, -0.26163, -0.29867, -0.20976, -0.19527, -0.34385, -0.60247, -0.88211, -1.11063, -1.36277, -1.59454, -1.78707, -2.11747, -2.22291, -2.24688, -2.47054, -2.80738, -3.09620, -3.44663, -3.62943, -3.74552, -3.80056, -3.76763, -3.80328, -3.85774, -3.83358, -3.82302, -3.76433, -3.67644, -3.66327, -3.51846, -3.47200, -3.41922, -3.34339, -3.24659, -2.99193, -2.80511, -2.67698, -2.57756, -2.40687, -2.20324, -2.10146, -2.14770, -2.15817, -2.24048, -2.11451, -1.82921, -1.67278, -1.58656, -1.32345, -1.20983, -1.16929, -1.17341, -1.09710, -0.86710, -0.69499, -0.54529, -0.27156, 0.01981, 0.30145, 0.58014, 0.76282, 1.01017, 1.15316, 1.25497, 1.21116, 1.05927, 1.06430, 1.13787, 1.40270, 1.66858, 1.84109, 2.01344, 2.16623, 2.24706, 2.40344, 2.40307, 2.47552, 2.65293, 2.75586, 2.78098, 2.88245, 2.79789, 2.68433, 2.55087, 2.39209, 2.31136, 2.19753, 1.99904, 1.87637, 1.77235, 1.57763, 1.39411, 1.14158, 1.09335, 1.12511, 1.14443, 1.19853, 1.18670, 1.29313, 1.40254, 1.53253, 1.54115, 1.45211, 1.49154, 1.57633, 1.55803, 1.56456, 1.46841, 1.42238, 1.39737, 1.14396, 0.77891, 0.64978, 0.56221, 0.49782, 0.50222, 0.49671, 0.57359, 0.57611, 0.39732, 0.30964, 0.29860, 0.25861, 0.19843, -0.11099, -0.37882, -0.64787, -0.83615, -0.80836, -0.89282, -1.04210, -1.18139, -1.21930, -1.19045, -1.22042, -1.19180, -1.11378, -1.11577, -0.98643, -0.89919, -0.89176, -0.82665, -0.88210, -1.08886, -1.16295, -1.22131, -1.27726, -1.27293, -1.29544, -1.23904, -1.25295, -1.45546, -1.60672, -1.61452, -1.60539, -1.56527, -1.60391, -1.53616, -1.33750, -1.18836, -0.94683, -0.91993, -0.94828, -0.91126, -0.83912, -0.77905, -0.84623, -0.82888, -0.67797, -0.72112, -0.78542, -0.82750, -0.81158, -0.62773, -0.55850, -0.71736, -0.83354, -0.96026, -1.13433, -1.21713, -1.22666, -1.07126, -0.83221, -0.76818, -0.79060, -0.72355, -0.72150, -0.59589, -0.46820, -0.38875, -0.36061, -0.41665, -0.30074, -0.26666, -0.27951, -0.28499, -0.33246, -0.41705, -0.59120, -0.74296, -0.89316, -1.17541, -1.34245, -1.39788, -1.45769, -1.30923, -1.12595, -1.10847, -1.04499, -0.96981, -1.01440, -0.98728, -0.96062, -0.79132, -0.55978, -0.55866, -0.63303, -0.60553, -0.54796, -0.41905, -0.25730, -0.25045, -0.21942, -0.20579, -0.05831, 0.07513, 0.14147, 0.34863, 0.56346, 0.76007, 0.83216, 0.96700, 1.19059, 1.25824, 1.22937, 1.18573, 0.96298, 0.85173, 0.74524, 0.54968, 0.48952, 0.54272, 0.53541, 0.53159, 0.35527, 0.15455, -0.01839, -0.18396, -0.24502, -0.25219, -0.37087, -0.42551, -0.29598, -0.16108, 0.05852, 0.13013, 0.22834, 0.26732, 0.19780, 0.17106, 0.08680, -0.00013, -0.09339, -0.12378, -0.07412, -0.15850, -0.32770, -0.47346, -0.76115, -0.96044, -1.15924, -1.43170, -1.62144, -1.60369, -1.66849, -1.70383, -1.76925, -1.76288, -1.63128, -1.59336, -1.58576, -1.61387, -1.64967, -1.58143, -1.35713, -1.23590, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.68759, -0.64038, -0.49442, -0.37623, -0.27597, -0.01804, 0.19096, 0.44952, 0.72695, 0.75557, 0.61814, 0.61089, 0.52866, 0.66098, 0.88781, 1.04506, 1.13044, 1.10174, 1.05376, 1.02895, 0.91865, 0.75600, 0.72932, 0.68877, +0.00000, 0.00000, 0.00000, -3.15613, -2.98438, -2.97068, -3.07466, -3.28154, -3.43669, -3.56974, -3.83712, -3.94212, -3.83717, -3.78419, -3.75001, -3.61385, -3.39368, -3.27371, -3.20620, -3.12179, -2.98426, -2.83074, -2.65284, -2.37423, -2.07866, -1.64894, -1.32110, -1.33846, -1.44116, -1.60301, -1.76277, -1.72865, -1.80097, -1.89019, -2.02233, -2.07971, -2.08245, -2.07978, -2.18888, -2.38098, -2.50713, -2.50329, -2.50961, -2.51415, -2.37865, -2.27309, -2.17491, -2.08776, -1.97120, -1.86756, -1.73914, -1.60239, -1.39102, -1.26875, -1.25717, -1.22310, -1.13934, -0.87565, -0.61488, -0.53549, -0.38843, -0.06679, 0.29137, 0.71470, 0.98519, 1.09867, 1.11983, 1.18822, 1.29098, 1.40607, 1.47063, 1.51010, 1.49542, 1.44732, 1.29270, 1.12300, 1.09705, 0.97288, 0.78335, 0.59730, 0.42520, 0.24127, 0.00098, -0.17882, -0.21832, -0.24145, -0.29987, -0.43824, -0.69329, -0.93056, -1.13891, -1.38844, -1.62443, -1.81887, -2.06813, -2.12011, -2.27906, -2.55476, -2.96275, -3.34066, -3.66168, -3.81835, -3.84809, -3.92255, -4.01982, -4.00849, -3.94822, -3.98659, -3.90867, -3.83884, -3.79156, -3.73708, -3.57519, -3.42577, -3.34722, -3.25107, -3.07478, -2.87093, -2.72572, -2.59573, -2.56618, -2.42423, -2.26468, -2.20230, -2.23273, -2.23684, -2.27009, -2.03931, -1.80606, -1.60194, -1.43606, -1.22926, -1.10716, -1.04899, -0.96639, -0.84728, -0.73971, -0.60204, -0.35792, -0.15973, 0.19448, 0.53611, 0.73602, 0.90060, 1.09969, 1.27226, 1.37944, 1.32171, 1.22532, 1.18731, 1.22517, 1.51884, 1.77397, 1.98416, 2.16590, 2.29603, 2.35830, 2.42690, 2.35787, 2.47479, 2.52803, 2.56903, 2.61913, 2.64096, 2.56317, 2.47493, 2.42160, 2.31302, 2.08925, 1.88481, 1.77947, 1.59787, 1.59832, 1.56905, 1.38729, 1.19861, 1.13455, 1.18091, 1.20943, 1.19186, 1.14619, 1.16793, 1.18947, 1.33598, 1.39472, 1.38181, 1.45232, 1.56478, 1.59188, 1.60113, 1.50405, 1.50185, 1.34187, 0.99829, 0.69050, 0.52999, 0.45321, 0.38733, 0.40934, 0.42420, 0.34183, 0.21603, 0.09563, -0.08539, -0.08966, -0.02621, -0.11225, -0.36977, -0.64275, -0.89502, -1.02955, -1.01251, -1.04110, -1.16200, -1.33570, -1.34903, -1.29485, -1.33286, -1.34328, -1.28178, -1.27467, -1.14553, -1.06272, -0.98564, -1.00832, -1.16494, -1.29777, -1.38476, -1.43093, -1.45362, -1.39249, -1.29631, -1.25553, -1.32081, -1.40836, -1.59470, -1.65529, -1.58274, -1.60636, -1.68938, -1.70388, -1.53726, -1.32383, -1.04658, -0.90222, -0.86606, -0.89430, -0.81644, -0.72007, -0.76186, -0.74384, -0.64873, -0.72742, -0.79657, -0.81710, -0.66987, -0.49104, -0.51854, -0.60461, -0.72615, -0.85957, -1.01622, -1.14536, -1.15956, -1.12679, -1.03476, -0.86921, -0.85561, -0.81244, -0.67874, -0.52646, -0.37336, -0.28858, -0.27568, -0.28310, -0.19615, -0.16016, -0.22961, -0.41470, -0.52676, -0.59420, -0.73544, -0.84232, -0.98654, -1.26656, -1.42672, -1.49495, -1.50634, -1.40493, -1.37229, -1.30768, -1.19582, -1.03754, -0.96267, -0.90084, -0.81330, -0.74918, -0.68880, -0.62470, -0.68452, -0.76431, -0.61492, -0.46547, -0.27582, -0.20645, -0.20248, -0.15245, 0.00496, 0.18787, 0.30571, 0.40713, 0.53869, 0.74670, 0.85981, 1.07852, 1.34873, 1.42379, 1.39124, 1.32050, 1.12932, 1.00791, 0.73045, 0.47984, 0.37760, 0.38893, 0.41391, 0.42268, 0.32839, 0.10776, -0.15198, -0.20025, -0.13683, -0.18868, -0.18075, -0.18604, -0.09348, 0.01244, 0.06524, 0.06753, 0.12353, 0.15951, 0.14229, 0.03446, -0.10377, -0.16177, -0.23573, -0.22100, -0.18696, -0.32123, -0.54057, -0.75734, -1.02536, -1.13312, -1.41262, -1.66237, -1.78940, -1.78090, -1.76043, -1.73585, -1.75148, -1.80838, -1.83794, -1.79988, -1.66817, -1.74443, -1.71195, -1.59217, -1.35879, -1.14832, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.69865, -0.58625, -0.41680, -0.29077, -0.18901, -0.00203, 0.18627, 0.51754, 0.68899, 0.70448, 0.63320, 0.58644, 0.55390, 0.72784, 1.02053, 1.21195, 1.20996, 1.19033, 1.28316, 1.17202, 1.02562, 0.86160, 0.76884, 0.74835, +0.00000, 0.00000, -3.19048, -2.93997, -2.85710, -2.88586, -2.94974, -3.16538, -3.32565, -3.42340, -3.64723, -3.79937, -3.87540, -3.92370, -3.83753, -3.65707, -3.42477, -3.26944, -3.18497, -3.06061, -2.78345, -2.55102, -2.39517, -2.18740, -2.04016, -1.73357, -1.46315, -1.46383, -1.51357, -1.59015, -1.71846, -1.71879, -1.74316, -1.73164, -1.84223, -1.90910, -2.00001, -2.16655, -2.35813, -2.57872, -2.65155, -2.52955, -2.48761, -2.49232, -2.45057, -2.44349, -2.28061, -2.13194, -2.02239, -1.95989, -1.85230, -1.67892, -1.31237, -1.04715, -1.02239, -0.98223, -0.98272, -0.81409, -0.51359, -0.35757, -0.19508, 0.15450, 0.50474, 0.85074, 1.12623, 1.36827, 1.45569, 1.53676, 1.56377, 1.53813, 1.57245, 1.47732, 1.32489, 1.28484, 1.16308, 1.04511, 1.00153, 0.79973, 0.65896, 0.54531, 0.43433, 0.31235, 0.06563, -0.20694, -0.27504, -0.28170, -0.42269, -0.55734, -0.81586, -1.10911, -1.28784, -1.49282, -1.71998, -1.85932, -2.09286, -2.20384, -2.38162, -2.64926, -3.11358, -3.49337, -3.78097, -3.97856, -3.98553, -4.08486, -4.19026, -4.06836, -3.89362, -3.84252, -3.81440, -3.95324, -3.94466, -3.85171, -3.63807, -3.42656, -3.32718, -3.23657, -3.02618, -2.70814, -2.53480, -2.38135, -2.40165, -2.41043, -2.28419, -2.20212, -2.22692, -2.12930, -2.08678, -1.88638, -1.67738, -1.39235, -1.20406, -1.09009, -1.06294, -1.11482, -1.00823, -0.89210, -0.82154, -0.64563, -0.37035, -0.09924, 0.29941, 0.55805, 0.74184, 0.87698, 1.04378, 1.20689, 1.30484, 1.27911, 1.28202, 1.42135, 1.48974, 1.76257, 1.97037, 2.03883, 2.18524, 2.36033, 2.42898, 2.48608, 2.37664, 2.43235, 2.46593, 2.56754, 2.58543, 2.51994, 2.39257, 2.22189, 2.21746, 2.14102, 1.85998, 1.62634, 1.54649, 1.46022, 1.56937, 1.51304, 1.33966, 1.17592, 1.07486, 1.10236, 1.14113, 1.09335, 1.02447, 1.12591, 1.14077, 1.24515, 1.28767, 1.21128, 1.31308, 1.51168, 1.57094, 1.65133, 1.58812, 1.46579, 1.20363, 0.92404, 0.67226, 0.48854, 0.37735, 0.18454, 0.13679, 0.12094, -0.00227, -0.09825, -0.19478, -0.37191, -0.36782, -0.41921, -0.56177, -0.74281, -0.95621, -1.16662, -1.28480, -1.30444, -1.31942, -1.29958, -1.41602, -1.41723, -1.36710, -1.56328, -1.65700, -1.52445, -1.42269, -1.19935, -1.08944, -1.07923, -1.17204, -1.25631, -1.27651, -1.33110, -1.40378, -1.55563, -1.52915, -1.36488, -1.25233, -1.23815, -1.27675, -1.45872, -1.55590, -1.60016, -1.70290, -1.78903, -1.83565, -1.68528, -1.43486, -1.15392, -0.95945, -0.73872, -0.65908, -0.58347, -0.51279, -0.63672, -0.68834, -0.63279, -0.70602, -0.70523, -0.65300, -0.52945, -0.43149, -0.45840, -0.50103, -0.61539, -0.72049, -0.91988, -1.16353, -1.26587, -1.31382, -1.25899, -1.04777, -0.92580, -0.77255, -0.62997, -0.53602, -0.37323, -0.28534, -0.28379, -0.28450, -0.21983, -0.21886, -0.28917, -0.48438, -0.62599, -0.67354, -0.85828, -1.04406, -1.16591, -1.37560, -1.45156, -1.43068, -1.46982, -1.52957, -1.59095, -1.47518, -1.30882, -1.04597, -0.93852, -0.95100, -0.89204, -0.90515, -0.85349, -0.69531, -0.68324, -0.71250, -0.58981, -0.53466, -0.35652, -0.27326, -0.24867, -0.16156, -0.01141, 0.15459, 0.35966, 0.51855, 0.54611, 0.71281, 0.81595, 0.99279, 1.30232, 1.44542, 1.44921, 1.44287, 1.27397, 1.10577, 0.82523, 0.59198, 0.41347, 0.37796, 0.32115, 0.19965, 0.15396, -0.01379, -0.19013, -0.11316, 0.02292, 0.05074, 0.06479, -0.05504, 0.00436, 0.03923, -0.05713, -0.13297, -0.08178, -0.01968, 0.03738, 0.00263, -0.18113, -0.25286, -0.32522, -0.37244, -0.33110, -0.47215, -0.74523, -0.92115, -1.14829, -1.24750, -1.49196, -1.64777, -1.76624, -1.76494, -1.70439, -1.72188, -1.71254, -1.80506, -1.86835, -1.78677, -1.64392, -1.66217, -1.60020, -1.57540, -1.35111, -1.11925, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.65309, -0.62664, -0.41751, -0.18178, -0.03800, 0.14736, 0.25624, 0.46946, 0.55294, 0.62706, 0.63190, 0.62474, 0.62746, 0.68908, 0.95626, 1.14789, 1.16124, 1.23608, 1.40331, 1.33995, 1.15057, 0.84929, 0.75563, 0.79022, +0.00000, -3.20776, -3.01970, -2.78009, -2.75810, -2.88854, -2.99566, -3.10461, -3.26894, -3.45704, -3.66604, -3.83688, -3.97889, -3.97504, -3.76148, -3.61527, -3.43817, -3.18718, -3.12783, -3.01779, -2.65056, -2.38198, -2.22067, -1.97958, -1.83224, -1.61491, -1.52231, -1.51867, -1.48728, -1.55792, -1.70201, -1.78258, -1.75905, -1.77207, -1.92058, -1.98515, -2.06138, -2.33282, -2.60998, -2.70319, -2.62820, -2.49317, -2.45966, -2.50158, -2.52695, -2.50565, -2.19440, -2.00829, -1.92106, -1.80801, -1.71599, -1.55440, -1.13439, -0.92257, -0.96460, -0.92275, -0.89201, -0.73053, -0.45266, -0.24294, 0.02400, 0.32823, 0.68797, 0.93803, 1.20472, 1.45483, 1.62453, 1.75800, 1.76659, 1.63069, 1.56189, 1.46287, 1.34331, 1.23149, 1.09688, 0.94084, 0.84061, 0.66274, 0.62919, 0.53322, 0.43091, 0.43773, 0.25863, -0.08960, -0.17710, -0.27386, -0.53962, -0.67852, -0.81861, -1.07405, -1.33482, -1.64057, -1.81213, -2.03239, -2.27008, -2.46414, -2.59335, -2.88359, -3.31223, -3.59647, -3.73800, -3.90353, -3.99895, -4.09829, -4.10896, -4.00036, -3.76760, -3.67897, -3.68947, -3.90298, -3.82922, -3.70495, -3.57287, -3.37200, -3.26919, -3.26622, -3.01688, -2.66454, -2.46672, -2.28447, -2.20592, -2.20646, -2.11771, -2.13235, -2.11621, -2.03230, -1.87814, -1.74856, -1.57407, -1.35243, -1.19101, -1.12534, -1.08669, -1.14795, -1.10442, -1.03136, -0.89402, -0.75103, -0.51188, -0.24591, 0.18541, 0.47952, 0.81928, 1.02384, 1.12613, 1.30049, 1.42437, 1.37777, 1.52294, 1.75060, 1.77659, 1.93582, 2.15898, 2.18721, 2.25080, 2.32775, 2.48054, 2.49456, 2.43805, 2.45375, 2.53937, 2.61234, 2.51813, 2.35335, 2.20767, 2.03572, 2.01682, 1.95289, 1.79239, 1.53637, 1.45415, 1.41433, 1.52743, 1.41335, 1.31039, 1.19650, 1.00890, 1.04453, 1.16097, 1.04966, 1.01781, 1.13911, 1.12399, 1.09837, 1.11937, 1.09946, 1.25417, 1.37477, 1.46624, 1.53123, 1.50920, 1.32207, 1.08525, 0.85753, 0.60912, 0.37441, 0.25494, 0.04648, -0.13413, -0.26323, -0.28147, -0.32382, -0.39070, -0.54780, -0.55732, -0.68330, -0.79890, -0.84503, -1.03342, -1.22178, -1.32791, -1.49174, -1.50156, -1.43547, -1.56434, -1.61800, -1.52895, -1.68134, -1.74749, -1.63634, -1.39692, -1.13417, -1.06314, -1.12895, -1.25327, -1.28586, -1.25420, -1.26323, -1.29314, -1.43816, -1.45922, -1.33476, -1.13403, -1.12237, -1.23575, -1.47223, -1.62700, -1.72419, -1.78277, -1.76978, -1.84962, -1.72176, -1.37777, -1.18449, -1.01260, -0.65985, -0.50026, -0.49286, -0.46142, -0.52620, -0.55717, -0.57168, -0.57911, -0.49916, -0.46420, -0.42265, -0.42795, -0.47631, -0.61008, -0.75535, -0.78375, -0.88154, -1.13840, -1.34119, -1.34497, -1.27561, -1.13619, -0.94232, -0.70249, -0.55027, -0.47668, -0.28025, -0.23951, -0.30965, -0.27200, -0.26260, -0.31799, -0.33948, -0.52617, -0.70790, -0.72664, -0.85903, -1.09065, -1.29135, -1.48816, -1.46997, -1.44502, -1.48261, -1.66298, -1.76417, -1.69062, -1.51327, -1.22242, -1.08172, -1.14645, -1.19273, -1.15650, -0.97866, -0.80612, -0.71830, -0.69478, -0.57464, -0.50954, -0.31882, -0.29988, -0.28686, -0.08637, 0.01569, 0.06063, 0.34021, 0.50724, 0.46504, 0.61881, 0.82053, 1.01649, 1.25671, 1.37868, 1.46994, 1.40990, 1.28759, 1.10538, 0.93066, 0.71538, 0.50595, 0.45090, 0.37501, 0.16792, 0.09670, 0.05701, 0.04845, 0.06885, 0.18783, 0.22754, 0.20437, 0.03454, 0.12013, 0.08225, -0.12629, -0.14830, -0.05987, -0.03406, 0.07893, -0.00222, -0.27148, -0.41530, -0.41180, -0.40788, -0.37691, -0.58356, -0.79906, -1.00410, -1.17482, -1.36126, -1.57872, -1.74471, -1.88351, -1.85803, -1.67692, -1.65274, -1.66408, -1.73197, -1.68864, -1.66085, -1.61082, -1.66852, -1.57798, -1.54576, -1.30088, -1.10051, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.57616, -0.54163, -0.32785, -0.10115, 0.18313, 0.33123, 0.39482, 0.44395, 0.46522, 0.50057, 0.55968, 0.62499, 0.69691, 0.68149, 0.83226, 1.00301, 1.14042, 1.21903, 1.39167, 1.35032, 1.19718, 0.92667, 0.94969, 1.07235, +0.00000, -3.02140, -2.89627, -2.73658, -2.73719, -2.88885, -3.01916, -3.11063, -3.33990, -3.59571, -3.79367, -3.91479, -3.93021, -3.82010, -3.59583, -3.48710, -3.36073, -3.10752, -2.98683, -2.85101, -2.57882, -2.38144, -2.15887, -1.84118, -1.70797, -1.55983, -1.56118, -1.59643, -1.56743, -1.65895, -1.78355, -1.83408, -1.79919, -1.82153, -2.02136, -2.14613, -2.19157, -2.40752, -2.65065, -2.67631, -2.58570, -2.49799, -2.48016, -2.52419, -2.50603, -2.42544, -2.10386, -1.92782, -1.82488, -1.66317, -1.47632, -1.23975, -0.94334, -0.93740, -1.00374, -0.91757, -0.86503, -0.69963, -0.43458, -0.23583, 0.02892, 0.29410, 0.69771, 1.01451, 1.25981, 1.51147, 1.70871, 1.81651, 1.83251, 1.72361, 1.62419, 1.55820, 1.46589, 1.27886, 1.11807, 0.91994, 0.82601, 0.73763, 0.71272, 0.55837, 0.43716, 0.44252, 0.35116, 0.10714, -0.04872, -0.31562, -0.61880, -0.72370, -0.84452, -1.13243, -1.47913, -1.87740, -2.05472, -2.31546, -2.53382, -2.63733, -2.73649, -2.98123, -3.32440, -3.57486, -3.62775, -3.70025, -3.82224, -3.91503, -3.92179, -3.90301, -3.67484, -3.58789, -3.55798, -3.65339, -3.54038, -3.46505, -3.44441, -3.39581, -3.30883, -3.22660, -2.97083, -2.70713, -2.48363, -2.24287, -2.14487, -2.16386, -2.07455, -2.12086, -2.10162, -2.02286, -1.80586, -1.58215, -1.44125, -1.28854, -1.17251, -1.15663, -1.08120, -1.06244, -1.02940, -0.98518, -0.85738, -0.78956, -0.58276, -0.35624, 0.08827, 0.49257, 0.93140, 1.16589, 1.26696, 1.40352, 1.54930, 1.62203, 1.81788, 1.93311, 1.89911, 2.03901, 2.24992, 2.21197, 2.21164, 2.22576, 2.38949, 2.41853, 2.43350, 2.56606, 2.66825, 2.66703, 2.47424, 2.19014, 1.98788, 1.85439, 1.84276, 1.80184, 1.73055, 1.49500, 1.45703, 1.43772, 1.50058, 1.38366, 1.30496, 1.16678, 0.97080, 0.97679, 1.09709, 1.05164, 1.01570, 0.99090, 0.93155, 0.89300, 0.88171, 0.83450, 0.99136, 1.06551, 1.14064, 1.18997, 1.20454, 1.18918, 1.08329, 0.89652, 0.66020, 0.35471, 0.19317, 0.03424, -0.19091, -0.40262, -0.42754, -0.51496, -0.54633, -0.65158, -0.64986, -0.71689, -0.79194, -0.83945, -1.03459, -1.28778, -1.47179, -1.61804, -1.58940, -1.62607, -1.80133, -1.81944, -1.69282, -1.80836, -1.82401, -1.70742, -1.43755, -1.19579, -1.15663, -1.14042, -1.21421, -1.24590, -1.18834, -1.19627, -1.18695, -1.20578, -1.16969, -1.06977, -0.93781, -1.07086, -1.26547, -1.52882, -1.68745, -1.72268, -1.73816, -1.76354, -1.90541, -1.83663, -1.49787, -1.25574, -1.04167, -0.74259, -0.60261, -0.56394, -0.51401, -0.56078, -0.55154, -0.50263, -0.42986, -0.31852, -0.30341, -0.24848, -0.25112, -0.35500, -0.57458, -0.80580, -0.85944, -0.86363, -1.00831, -1.18164, -1.16250, -1.12891, -1.04584, -0.82756, -0.56762, -0.38914, -0.32608, -0.19541, -0.21997, -0.36647, -0.38553, -0.34780, -0.34840, -0.40025, -0.63541, -0.80082, -0.80631, -0.98494, -1.27534, -1.50595, -1.72699, -1.71547, -1.70494, -1.68326, -1.76499, -1.84164, -1.77959, -1.64676, -1.47510, -1.35384, -1.35573, -1.38734, -1.28023, -1.05204, -0.89957, -0.78326, -0.75466, -0.59265, -0.45516, -0.30454, -0.36594, -0.38157, -0.19449, -0.07381, 0.01022, 0.24613, 0.33365, 0.36131, 0.59248, 0.81116, 0.98590, 1.19138, 1.29161, 1.40527, 1.31299, 1.23748, 1.18093, 1.07276, 0.92070, 0.73217, 0.62346, 0.55307, 0.39589, 0.33512, 0.34507, 0.34609, 0.25612, 0.35383, 0.38712, 0.36049, 0.22028, 0.25769, 0.12500, -0.11343, -0.14979, -0.02515, 0.07115, 0.11832, -0.12952, -0.42563, -0.58135, -0.60027, -0.61186, -0.56781, -0.73966, -0.87675, -1.06150, -1.19448, -1.34560, -1.58613, -1.75027, -1.87385, -1.85237, -1.60412, -1.48042, -1.49464, -1.57454, -1.53098, -1.59197, -1.59463, -1.69581, -1.59331, -1.48971, -1.27197, -1.15470, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.40825, -0.42387, -0.24242, -0.04388, 0.26759, 0.40847, 0.45765, 0.53719, 0.52490, 0.52878, 0.60219, 0.63573, 0.69015, 0.68950, 0.81831, 0.99501, 1.15935, 1.17689, 1.35337, 1.34378, 1.27556, 1.14817, 1.22196, 1.29889, +-3.00851, -2.90997, -2.76321, -2.75641, -2.86820, -2.96542, -3.09147, -3.20972, -3.43286, -3.67676, -3.79363, -3.91840, -3.90225, -3.69656, -3.48071, -3.37737, -3.16709, -2.90298, -2.82696, -2.71586, -2.53327, -2.29364, -2.07712, -1.83756, -1.68724, -1.59789, -1.64291, -1.65909, -1.66248, -1.72990, -1.87739, -2.01070, -1.96135, -1.90745, -2.04107, -2.27149, -2.41572, -2.53639, -2.71128, -2.74038, -2.64316, -2.56365, -2.48984, -2.53743, -2.54021, -2.37561, -2.06389, -1.90350, -1.70759, -1.45784, -1.27296, -1.01912, -0.80264, -0.79652, -0.83926, -0.83876, -0.74503, -0.59761, -0.36907, -0.14500, 0.06502, 0.32865, 0.74084, 0.98008, 1.23015, 1.55617, 1.83315, 1.87134, 1.78970, 1.74735, 1.67954, 1.60047, 1.52649, 1.32474, 1.18860, 0.97025, 0.80441, 0.79116, 0.75666, 0.55086, 0.45510, 0.49300, 0.35337, 0.12792, -0.07220, -0.32837, -0.58571, -0.81035, -0.93053, -1.25550, -1.67653, -2.05272, -2.24036, -2.47147, -2.64836, -2.82222, -2.91567, -3.05789, -3.26250, -3.51334, -3.64395, -3.65890, -3.72921, -3.83002, -3.83097, -3.82830, -3.58563, -3.49867, -3.53555, -3.52041, -3.37692, -3.34114, -3.34432, -3.30155, -3.28842, -3.20199, -2.95662, -2.67247, -2.36687, -2.23757, -2.15205, -2.16990, -2.09244, -2.05833, -2.00183, -1.88562, -1.61408, -1.45822, -1.34857, -1.18471, -1.04122, -1.06088, -1.10000, -1.06661, -0.97608, -0.94825, -0.82126, -0.74963, -0.52486, -0.28752, 0.04893, 0.49659, 0.96976, 1.20428, 1.33858, 1.55440, 1.66120, 1.73712, 1.93043, 2.03197, 2.06797, 2.09790, 2.28377, 2.24014, 2.17809, 2.20637, 2.37017, 2.41682, 2.50260, 2.57255, 2.61948, 2.59833, 2.41686, 2.10222, 1.75107, 1.58624, 1.63490, 1.59710, 1.57336, 1.42596, 1.46225, 1.51935, 1.46717, 1.33910, 1.28968, 1.13182, 0.95525, 1.04358, 1.11421, 1.02651, 0.94672, 0.86183, 0.88289, 0.75960, 0.69722, 0.64829, 0.74523, 0.83212, 0.93491, 0.98775, 1.07179, 1.07114, 0.98563, 0.85326, 0.70108, 0.43218, 0.14963, -0.05453, -0.22969, -0.48750, -0.56813, -0.67514, -0.68959, -0.70674, -0.77508, -0.83670, -0.86500, -0.94501, -1.15604, -1.35366, -1.59930, -1.78418, -1.73451, -1.78851, -1.85437, -1.90349, -1.82526, -1.88823, -1.90779, -1.76963, -1.46334, -1.24925, -1.17009, -1.15813, -1.26439, -1.26795, -1.13056, -1.07493, -1.13433, -1.15693, -1.01798, -0.92169, -0.87999, -1.07937, -1.29582, -1.50155, -1.72011, -1.78321, -1.76234, -1.85471, -2.06641, -1.95913, -1.64030, -1.42986, -1.18944, -0.92032, -0.67864, -0.61452, -0.59845, -0.57897, -0.55134, -0.43930, -0.26661, -0.14907, -0.08947, -0.05405, -0.14609, -0.27381, -0.47118, -0.68723, -0.85947, -0.93726, -0.96346, -1.06476, -1.04759, -0.99934, -0.91010, -0.63786, -0.43825, -0.34434, -0.27444, -0.21177, -0.29623, -0.41297, -0.45267, -0.48421, -0.48352, -0.56332, -0.71798, -0.86727, -0.99087, -1.18853, -1.53298, -1.77992, -1.95297, -1.96471, -1.92385, -1.88654, -2.00047, -2.02779, -1.89141, -1.70998, -1.67764, -1.68109, -1.58264, -1.52726, -1.38998, -1.11822, -0.94299, -0.78168, -0.79959, -0.71413, -0.50972, -0.37341, -0.46349, -0.43227, -0.21646, -0.14021, -0.03584, 0.16509, 0.30931, 0.42424, 0.56958, 0.79943, 0.95294, 1.13874, 1.30277, 1.42062, 1.35740, 1.30518, 1.18807, 1.10266, 1.05160, 0.96772, 0.80445, 0.63276, 0.54210, 0.53571, 0.52698, 0.51498, 0.39929, 0.52478, 0.55342, 0.42939, 0.32056, 0.30480, 0.09686, -0.11793, -0.10541, -0.04150, 0.03870, 0.01735, -0.23516, -0.46896, -0.75123, -0.78525, -0.81359, -0.79246, -0.85257, -0.91843, -1.04093, -1.11952, -1.36105, -1.61469, -1.70208, -1.72646, -1.71693, -1.57388, -1.41668, -1.39951, -1.53733, -1.51776, -1.58852, -1.56446, -1.64503, -1.64800, -1.51159, -1.30345, -1.23121, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, -0.17468, -0.20846, -0.10570, 0.10532, 0.39526, 0.52365, 0.59037, 0.56524, 0.50558, 0.54045, 0.67571, 0.69302, 0.60881, 0.60071, 0.80536, 0.98811, 1.16028, 1.18332, 1.38023, 1.42919, 1.30142, 1.22934, 1.31878, 1.33132, +-3.05631, -3.03065, -2.84332, -2.86716, -3.01271, -3.06254, -3.17321, -3.29736, -3.48142, -3.66665, -3.71709, -3.84786, -3.87749, -3.66862, -3.39308, -3.21663, -2.99208, -2.74874, -2.65600, -2.56083, -2.49734, -2.32021, -2.09849, -1.83005, -1.61971, -1.52466, -1.62045, -1.69824, -1.76053, -1.86155, -1.98449, -2.10125, -2.11001, -2.08544, -2.11619, -2.34701, -2.58229, -2.69745, -2.80126, -2.79210, -2.67629, -2.59747, -2.51880, -2.56292, -2.55116, -2.30341, -1.92062, -1.72142, -1.56216, -1.35031, -1.14957, -0.87947, -0.72421, -0.72114, -0.65506, -0.57798, -0.48841, -0.40918, -0.24699, -0.06515, 0.10049, 0.29300, 0.70886, 0.96189, 1.19033, 1.46582, 1.79692, 1.86591, 1.74576, 1.72918, 1.68752, 1.57501, 1.45529, 1.24310, 1.11678, 0.91602, 0.75794, 0.78233, 0.80464, 0.63825, 0.45101, 0.36106, 0.16340, -0.01594, -0.18866, -0.42538, -0.62260, -0.82962, -0.94885, -1.26898, -1.73951, -2.17034, -2.37896, -2.61907, -2.73890, -2.90033, -3.06470, -3.29526, -3.38598, -3.52371, -3.67898, -3.70911, -3.77248, -3.86575, -3.82023, -3.73349, -3.45762, -3.38798, -3.47399, -3.43375, -3.24736, -3.14660, -3.20089, -3.23965, -3.20990, -3.07511, -2.87844, -2.67337, -2.32870, -2.13924, -2.03888, -2.04557, -1.99425, -1.99213, -1.90087, -1.79317, -1.49516, -1.29582, -1.19062, -1.11936, -0.95538, -0.94262, -1.07878, -1.08724, -0.97928, -0.92874, -0.75736, -0.63247, -0.36719, -0.14757, 0.07521, 0.45882, 0.91494, 1.26587, 1.45249, 1.62584, 1.70654, 1.77852, 1.96760, 2.05312, 2.12697, 2.21011, 2.40583, 2.41947, 2.34742, 2.27716, 2.36420, 2.34156, 2.47774, 2.60359, 2.62135, 2.43878, 2.21225, 1.95856, 1.59776, 1.44990, 1.52278, 1.46104, 1.43479, 1.34845, 1.43077, 1.51244, 1.39153, 1.25591, 1.26639, 1.21168, 1.00541, 0.96255, 0.97925, 0.89602, 0.80129, 0.65514, 0.68638, 0.61816, 0.59128, 0.59012, 0.66493, 0.69845, 0.80694, 0.83665, 0.94313, 0.97465, 0.86474, 0.62826, 0.47196, 0.32239, 0.06405, -0.15157, -0.28988, -0.59429, -0.76475, -0.91685, -0.94688, -0.89308, -0.95109, -1.00813, -1.02743, -1.06037, -1.24803, -1.50249, -1.80230, -1.98346, -1.90573, -1.93236, -1.94027, -1.94860, -1.89735, -1.91484, -1.88083, -1.76200, -1.48085, -1.34914, -1.30000, -1.23206, -1.27301, -1.30434, -1.19135, -1.07627, -1.14215, -1.18082, -1.00853, -0.92408, -0.94001, -1.12379, -1.28100, -1.43885, -1.73439, -1.88683, -1.86922, -1.91326, -2.11253, -2.09074, -1.85368, -1.64925, -1.35619, -1.08596, -0.80974, -0.65232, -0.56873, -0.46675, -0.40141, -0.33649, -0.20944, -0.12721, -0.06753, 0.05305, 0.02801, -0.14263, -0.37502, -0.56399, -0.78751, -0.95704, -0.96832, -0.98949, -0.93079, -0.84081, -0.73868, -0.46801, -0.30314, -0.27031, -0.23598, -0.17157, -0.23538, -0.38034, -0.50481, -0.61490, -0.65888, -0.75843, -0.84885, -0.91958, -1.03644, -1.25627, -1.62449, -1.90482, -2.06570, -2.06492, -2.05627, -2.00220, -2.08167, -2.13293, -2.05521, -1.83230, -1.80952, -1.84256, -1.67259, -1.56614, -1.47638, -1.23289, -1.02954, -0.83821, -0.87944, -0.86004, -0.66843, -0.49396, -0.48570, -0.45910, -0.31121, -0.24406, -0.09460, 0.11636, 0.27907, 0.42928, 0.57542, 0.81618, 0.99444, 1.19555, 1.36825, 1.49609, 1.41250, 1.34574, 1.20886, 1.04545, 0.91561, 0.94901, 0.87943, 0.68977, 0.60073, 0.60396, 0.59062, 0.57480, 0.46335, 0.59469, 0.62831, 0.49108, 0.36317, 0.29678, 0.09202, -0.13269, -0.15279, -0.11075, -0.04431, -0.12885, -0.41188, -0.58520, -0.77534, -0.75712, -0.77260, -0.79342, -0.87861, -0.91897, -1.05877, -1.11528, -1.32661, -1.56005, -1.67987, -1.65127, -1.63325, -1.57739, -1.43010, -1.38867, -1.55007, -1.55900, -1.62231, -1.56784, -1.59631, -1.62723, -1.50165, -1.27844, -1.11182, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.18876, 0.18264, 0.19165, 0.27483, 0.47577, 0.53117, 0.64599, 0.67589, 0.60815, 0.51724, 0.64393, 0.73047, 0.59836, 0.55683, 0.78450, 0.98829, 1.19998, 1.23780, 1.39818, 1.43269, 1.29705, 1.26165, 1.36025, 1.41190, +-2.88387, -2.89998, -2.86077, -2.91940, -3.01505, -3.13839, -3.19329, -3.34491, -3.59005, -3.69348, -3.71353, -3.81106, -3.79519, -3.67863, -3.44260, -3.22200, -2.93967, -2.68365, -2.55324, -2.39705, -2.38683, -2.35498, -2.22954, -1.98569, -1.76149, -1.62287, -1.71066, -1.91710, -2.03598, -2.03527, -2.15322, -2.21636, -2.19025, -2.16028, -2.22429, -2.48442, -2.69197, -2.92645, -2.96427, -2.89827, -2.84533, -2.69399, -2.59023, -2.56791, -2.39070, -2.09903, -1.74493, -1.50889, -1.36123, -1.19031, -1.01992, -0.71531, -0.55138, -0.53457, -0.38933, -0.23071, -0.19843, -0.18676, -0.05825, 0.04356, 0.16433, 0.43829, 0.79698, 1.02978, 1.29728, 1.55684, 1.82658, 1.84839, 1.82902, 1.77596, 1.76751, 1.64869, 1.34479, 1.12173, 0.95842, 0.74523, 0.69583, 0.73715, 0.75210, 0.69044, 0.47306, 0.29938, -0.03096, -0.18488, -0.29698, -0.52174, -0.73187, -0.93472, -1.10654, -1.39095, -1.82608, -2.29991, -2.58648, -2.67787, -2.76662, -2.96481, -3.15385, -3.45085, -3.53610, -3.67269, -3.68181, -3.71161, -3.75134, -3.75664, -3.76078, -3.59316, -3.32192, -3.29992, -3.36070, -3.34311, -3.25004, -3.09553, -3.13635, -3.11430, -3.05597, -2.84002, -2.66534, -2.54988, -2.25328, -1.98863, -1.87319, -1.83353, -1.76206, -1.79034, -1.75163, -1.51102, -1.19589, -1.02365, -0.89174, -0.85469, -0.74308, -0.89802, -1.04176, -1.11032, -1.06442, -0.95190, -0.84658, -0.67415, -0.32216, -0.08167, 0.14928, 0.49078, 0.76970, 1.17632, 1.43888, 1.66752, 1.69339, 1.75275, 1.94675, 2.05046, 2.11141, 2.25555, 2.41689, 2.49339, 2.45359, 2.29737, 2.19163, 2.18708, 2.37386, 2.49691, 2.55587, 2.35548, 2.10079, 1.73929, 1.49567, 1.40506, 1.40993, 1.39469, 1.25430, 1.14702, 1.27188, 1.34853, 1.29387, 1.28798, 1.27930, 1.29660, 1.08043, 0.99702, 0.95723, 0.91811, 0.87564, 0.72731, 0.68058, 0.62609, 0.57723, 0.58872, 0.65519, 0.64178, 0.63205, 0.73073, 0.91026, 0.87437, 0.74349, 0.49421, 0.30888, 0.05517, -0.10433, -0.24215, -0.38190, -0.59601, -0.89954, -1.18098, -1.25780, -1.20572, -1.16618, -1.09974, -1.21340, -1.27899, -1.43535, -1.64053, -1.95758, -2.12195, -2.00401, -1.94318, -1.96852, -1.99154, -2.02561, -2.07184, -1.97968, -1.83580, -1.65252, -1.49372, -1.35381, -1.29020, -1.22865, -1.18371, -1.09210, -1.10866, -1.17896, -1.17845, -1.09143, -0.96163, -1.02658, -1.22329, -1.27849, -1.42638, -1.73914, -1.86631, -1.93696, -1.98377, -2.11454, -2.08667, -1.92079, -1.75507, -1.41291, -1.09725, -0.85446, -0.66977, -0.54559, -0.38685, -0.25065, -0.21318, -0.24263, -0.18425, -0.04784, 0.04000, 0.06428, -0.05419, -0.24906, -0.51694, -0.78728, -0.94696, -1.08237, -1.00600, -0.88816, -0.83443, -0.70169, -0.48846, -0.31200, -0.18244, -0.21167, -0.22486, -0.25647, -0.34801, -0.51411, -0.73778, -0.83718, -0.94609, -1.03542, -1.08869, -1.18539, -1.41590, -1.74353, -2.00302, -2.19884, -2.19916, -2.09757, -2.09722, -2.19621, -2.23088, -2.18738, -2.04607, -2.03538, -1.89902, -1.70749, -1.52064, -1.43990, -1.32594, -1.07188, -0.85568, -0.85816, -0.76894, -0.64174, -0.55287, -0.45209, -0.37569, -0.23655, -0.22395, -0.02550, 0.24174, 0.38566, 0.44863, 0.54003, 0.72037, 0.90172, 1.11596, 1.25400, 1.36690, 1.48055, 1.41854, 1.24408, 1.05687, 0.86035, 0.89631, 0.83507, 0.78499, 0.63433, 0.61387, 0.65404, 0.55845, 0.49376, 0.61824, 0.66637, 0.66038, 0.50375, 0.25311, 0.01166, -0.21997, -0.20333, -0.20365, -0.10064, -0.15514, -0.44050, -0.63202, -0.73349, -0.71909, -0.72659, -0.77612, -0.95113, -1.07931, -1.09150, -1.12225, -1.28566, -1.37347, -1.43298, -1.41390, -1.53858, -1.44386, -1.33609, -1.29535, -1.37658, -1.51371, -1.59179, -1.53933, -1.54254, -1.48258, -1.34523, -1.24604, -1.01868, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.46060, 0.54878, 0.53948, 0.49077, 0.46501, 0.52135, 0.66668, 0.69714, 0.67912, 0.53567, 0.60154, 0.59303, 0.57467, 0.55437, 0.74071, 1.05381, 1.23491, 1.25023, 1.34770, 1.29260, 1.21050, 1.25809, 1.24615, 1.32721, +-2.80398, -2.81526, -2.78178, -2.82252, -2.94298, -3.12511, -3.19122, -3.38545, -3.62917, -3.67265, -3.66997, -3.72121, -3.69414, -3.64709, -3.46578, -3.30284, -3.07004, -2.83385, -2.69510, -2.49445, -2.46748, -2.48943, -2.45171, -2.26934, -2.06078, -1.91983, -1.92977, -2.07594, -2.25893, -2.27618, -2.40063, -2.46133, -2.39041, -2.32356, -2.34410, -2.53109, -2.71143, -2.98141, -3.01510, -2.95572, -2.87522, -2.60501, -2.44115, -2.37582, -2.18769, -1.98631, -1.70414, -1.47305, -1.32673, -1.16374, -1.00268, -0.69175, -0.50911, -0.47453, -0.32255, -0.15395, -0.09412, -0.05582, 0.12416, 0.31015, 0.36182, 0.56134, 0.85207, 1.00606, 1.25360, 1.50419, 1.77451, 1.84731, 1.84551, 1.77161, 1.76668, 1.63941, 1.33587, 1.17391, 0.97891, 0.69553, 0.60025, 0.57700, 0.59360, 0.59691, 0.38998, 0.16956, -0.23171, -0.41115, -0.49986, -0.70161, -0.93221, -1.16815, -1.35567, -1.61252, -1.97410, -2.30761, -2.64014, -2.77492, -2.88129, -3.14608, -3.33795, -3.61847, -3.67007, -3.68880, -3.59790, -3.56756, -3.55932, -3.56480, -3.59387, -3.40027, -3.17636, -3.18121, -3.24594, -3.28500, -3.22910, -3.07166, -3.11411, -3.08580, -3.01527, -2.76543, -2.53304, -2.37972, -2.10838, -1.85852, -1.73518, -1.67028, -1.55982, -1.45629, -1.46067, -1.28396, -0.98684, -0.90001, -0.80372, -0.76898, -0.67188, -0.76150, -0.85143, -0.93203, -0.93667, -0.91918, -0.89453, -0.66588, -0.27421, -0.00277, 0.22722, 0.48036, 0.66955, 1.06465, 1.34623, 1.57585, 1.56761, 1.59041, 1.77836, 1.90892, 1.96567, 2.08870, 2.22691, 2.32692, 2.31675, 2.28258, 2.13407, 2.03497, 2.20126, 2.26954, 2.34648, 2.22275, 2.00696, 1.70792, 1.51082, 1.38452, 1.32518, 1.27517, 1.09250, 1.04556, 1.19737, 1.26416, 1.21109, 1.17456, 1.13548, 1.17791, 1.01562, 0.95565, 0.90549, 0.87699, 0.87001, 0.75614, 0.68592, 0.58023, 0.47700, 0.46504, 0.51099, 0.56559, 0.50462, 0.51530, 0.68325, 0.61340, 0.49860, 0.29789, 0.10256, -0.15510, -0.27028, -0.37338, -0.48541, -0.66693, -1.01946, -1.30093, -1.38756, -1.34733, -1.27639, -1.21876, -1.39069, -1.48744, -1.63982, -1.83735, -2.16112, -2.33495, -2.20576, -2.08538, -2.10346, -2.15751, -2.22845, -2.28653, -2.17831, -1.91628, -1.69299, -1.56667, -1.41967, -1.39500, -1.34207, -1.27692, -1.18487, -1.16179, -1.16170, -1.12679, -1.06965, -0.97369, -1.10993, -1.29323, -1.29273, -1.41443, -1.67074, -1.79417, -1.92131, -1.97059, -2.06353, -2.03101, -1.89976, -1.79405, -1.48776, -1.15899, -0.92762, -0.79277, -0.70035, -0.52053, -0.33139, -0.15498, -0.10406, -0.10724, -0.04255, -0.07324, -0.10206, -0.16831, -0.28117, -0.46169, -0.64817, -0.78749, -0.97263, -0.90606, -0.82022, -0.76664, -0.60321, -0.42189, -0.24428, -0.11760, -0.21211, -0.27470, -0.32007, -0.41627, -0.62621, -0.92222, -1.06818, -1.18276, -1.26877, -1.34048, -1.43145, -1.61403, -1.88864, -2.06564, -2.19382, -2.29735, -2.26101, -2.29900, -2.42006, -2.40187, -2.32310, -2.16623, -2.08908, -1.89481, -1.69857, -1.48068, -1.39530, -1.28199, -0.97031, -0.74537, -0.72686, -0.64043, -0.59259, -0.56801, -0.47204, -0.38196, -0.25570, -0.29862, -0.12372, 0.17723, 0.35708, 0.41453, 0.47056, 0.60539, 0.72548, 0.90908, 1.12646, 1.20128, 1.33076, 1.29779, 1.09706, 0.93674, 0.76788, 0.84038, 0.88143, 0.89755, 0.72628, 0.68008, 0.68709, 0.57752, 0.58986, 0.71665, 0.77382, 0.79477, 0.56294, 0.22547, -0.05839, -0.31196, -0.30752, -0.33515, -0.21649, -0.20315, -0.43558, -0.64524, -0.79774, -0.85295, -0.88802, -0.92412, -0.97833, -1.13237, -1.17767, -1.20375, -1.38489, -1.40041, -1.38035, -1.30474, -1.32632, -1.18493, -1.10680, -1.08751, -1.19883, -1.38576, -1.41837, -1.38776, -1.40315, -1.31598, -1.23009, -1.20529, -0.99161, -0.74183, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.47255, 0.62969, 0.66199, 0.70639, 0.58535, 0.51498, 0.62336, 0.59825, 0.59837, 0.48689, 0.55222, 0.60818, 0.65258, 0.63051, 0.77390, 1.05178, 1.20187, 1.26292, 1.34661, 1.25938, 1.18356, 1.19086, 1.11877, 1.20957 \ No newline at end of file diff --git a/data/heightmaps/ground1.txt b/examples/pybullet/gym/pybullet_data/heightmaps/ground1.txt similarity index 100% rename from data/heightmaps/ground1.txt rename to examples/pybullet/gym/pybullet_data/heightmaps/ground1.txt diff --git a/data/heightmaps/ground2.txt b/examples/pybullet/gym/pybullet_data/heightmaps/ground2.txt similarity index 100% rename from data/heightmaps/ground2.txt rename to examples/pybullet/gym/pybullet_data/heightmaps/ground2.txt diff --git a/data/heightmaps/ground3.txt b/examples/pybullet/gym/pybullet_data/heightmaps/ground3.txt similarity index 100% rename from data/heightmaps/ground3.txt rename to examples/pybullet/gym/pybullet_data/heightmaps/ground3.txt diff --git a/data/heightmaps/ground4.txt b/examples/pybullet/gym/pybullet_data/heightmaps/ground4.txt similarity index 100% rename from data/heightmaps/ground4.txt rename to examples/pybullet/gym/pybullet_data/heightmaps/ground4.txt diff --git a/data/heightmaps/ground5.txt b/examples/pybullet/gym/pybullet_data/heightmaps/ground5.txt similarity index 100% rename from data/heightmaps/ground5.txt rename to examples/pybullet/gym/pybullet_data/heightmaps/ground5.txt diff --git a/data/heightmaps/ground6.txt b/examples/pybullet/gym/pybullet_data/heightmaps/ground6.txt similarity index 100% rename from data/heightmaps/ground6.txt rename to examples/pybullet/gym/pybullet_data/heightmaps/ground6.txt diff --git a/data/heightmaps/ground7.txt b/examples/pybullet/gym/pybullet_data/heightmaps/ground7.txt similarity index 100% rename from data/heightmaps/ground7.txt rename to examples/pybullet/gym/pybullet_data/heightmaps/ground7.txt diff --git a/examples/pybullet/gym/pybullet_data/heightmaps/readme.txt b/examples/pybullet/gym/pybullet_data/heightmaps/readme.txt new file mode 100644 index 000000000..d66dbce8a --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/heightmaps/readme.txt @@ -0,0 +1,4 @@ +wm_height_out.png and gimp_overlay_out assets from this Blender tutorial: +https://www.beamng.com/threads/tutorial-adding-heightmap-roads-using-blender.16356/ + +groundX.txt assets from DeepLoco, used with permission from Jason Peng. \ No newline at end of file diff --git a/examples/pybullet/gym/pybullet_data/heightmaps/wm_height_out.png b/examples/pybullet/gym/pybullet_data/heightmaps/wm_height_out.png new file mode 100644 index 000000000..d3edf9ff0 Binary files /dev/null and b/examples/pybullet/gym/pybullet_data/heightmaps/wm_height_out.png differ diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 1065c166d..62868dcb5 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -12394,6 +12394,8 @@ initpybullet(void) PyModule_AddIntConstant(m, "GEOM_MESH", GEOM_MESH); PyModule_AddIntConstant(m, "GEOM_PLANE", GEOM_PLANE); PyModule_AddIntConstant(m, "GEOM_CAPSULE", GEOM_CAPSULE); + PyModule_AddIntConstant(m, "GEOM_HEIGHTFIELD", GEOM_HEIGHTFIELD); + PyModule_AddIntConstant(m, "GEOM_FORCE_CONCAVE_TRIMESH", GEOM_FORCE_CONCAVE_TRIMESH); PyModule_AddIntConstant(m, "GEOM_CONCAVE_INTERNAL_EDGE", GEOM_CONCAVE_INTERNAL_EDGE);