diff --git a/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC.ino b/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC.ino new file mode 100644 index 00000000..67fe6682 --- /dev/null +++ b/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC.ino @@ -0,0 +1,152 @@ +/* + BicopShield closed-loop eMPC control example + + Explicit Model Predictive Control (eMPC). + + This example initialises the sampling subsystem from + the AutomationShield library and then realises eMPC control of + the angle of the arm. MPC control is implemented + by using the MPT3 software, see BicopShield_Export_EMPC.m + for the problem definition. The example allows the user to select + whether the reference altitude is given by the potentiometer or by + a predetermined reference trajectory. Upload the code to your board + and open the Serial Plotter tool in Arduino IDE. + + Tested on an UNO(max prediction horizon 1). + + This code is part of the AutomationShield hardware and software + ecosystem. Visit http://www.automationshield.com for more + details. This code is licensed under a Creative Commons + Attribution-NonCommercial 4.0 International License. + + Created by Martin Nemček. + Created on: 6.5.2024 + Last update: 24.5.2024 +*/ + +#include // Include main library +#include // Include sampling library + +#include "ectrl.h" // Include header file for EMPC controller + +#include + +#define MANUAL 0 // Choose manual reference using potentiometer (1) or automatic reference trajectory (0) + +#define USE_KALMAN 0 // (1) use Kalman filter for state estimation, (0) use direct measurement and simple difference for speed + +#define Ts 10.0 // Sampling period in milliseconds +unsigned long k = 0; // Sample index +bool nextStep = false; // Flag for step function +bool realTimeViolation = false; // Flag for real-time sampling violation + +float R[]={0.8,1.0,0.35,1.3,1.0,0.35,0.8,1.2,0.0}; // Reference trajectory +float y = 0.0; // [rad] Output (Current object height) +float yprev= 0.0; // [rad] Previous output (Object height in previous sample) +float u1,u2; +int T = 1000; // Section length +int i = 0; // Section counter + + +// Kalman filter +#if USE_KALMAN +BLA::Matrix<2, 2> A = {0.99999, 0.00998, -0.00246, 0.99525}; +BLA::Matrix<2, 2> B = {7.78747048702292e-06, -9.62042244147616e-06, 0.00156, -0.00192}; +BLA::Matrix<1, 2> C = {1, 0}; +BLA::Matrix<2, 2> Q_Kalman = {1, 0, 0, 100}; +BLA::Matrix<1, 1> R_Kalman = {0.01}; +#endif + +float X[3] = {0.0, 0.0, 0.0}; // Estimated initial state vector +float Xr[3] = {0.0, 0.0, 0.0}; // Initial reference state vector +//float Xk[2] = {0.0, 0.0}; + +float u = 0.0; // [V] Input (Magnet voltage) +static float u_opt[MPT_RANGE]; // predicted inputs +float BaseU=50.0; // Base input +float ref_read; // Variable for potentiometer +extern struct mpc_ctl ctl; // Object representing presets for MPC controller + +void setup() { + Serial.begin(115200); //--Initialize serial communication + BicopShield.begin(); //--Initialize AeroShield + delay(1000); + BicopShield.calibrate(); // Calibrate AeroShield board + store the 0° value of the pendulum + Serial.println("r, y, u"); //--Print header + Sampling.period(Ts*1000.0); + Sampling.interrupt(stepEnable); +} + +void loop(){ + if (nextStep) { // Running the algorithm once every sample + step(); + nextStep = false; // Setting the flag to false # built-in ISR sets flag to true at the end of each sample + } +} + +void stepEnable() { // ISR + // if (nextStep) { // If previous sample still running + // realTimeViolation = true; // Real-time has been violated + // noInterrupts(); + // Serial.println("Real-time samples violated."); // Print error message + // BicopShield.actuatorWrite(0.0,0.0); // Turn off the fan + // while (1); // Stop program execution + //} + nextStep = true; // Enable step flag +} + +void step() { // Define step function + #if MANUAL + ref_read=BicopShield.referenceRead(); + Xr[1] = AutomationShield.mapFloat(ref_read,0,100,0,100); //--Sensing Pot reference + #elif !MANUAL + if(i >= sizeof(R)/sizeof(float)){ // If trajectory ended + BicopShield.actuatorWriteVolt(0.0,0.0); // Stop the Motor + while(true); // End of program execution + } + if (k % (T*i) == 0){ // Moving through trajectory values + //r = R[i]; + Xr[1] = R[i]; + i++; // Change input value after defined amount of samples + } + k++; // Increment + #endif + + y = BicopShield.sensorReadRadian(); // Angle in radians + + #if USE_KALMAN + BLA::Matrix<2, 1> Xk = {X[1], X[2]}; + BLA::Matrix<2, 1> U = {u_opt[0], u_opt[1]}; + BicopShield.getKalmanEstimate(Xk, U, y, A, B, C, Q_Kalman, R_Kalman); // State estimation using Kalman filter + X[1] = Xk(0); + X[2] = Xk(1); + X[0] = X[0] + (Xr[1]- X[1]); + #else + // Direct angle and simple difference for Angular speed + // Saving valuable milliseconds for MPC algorithm + + X[1] = y; // Arm angle + X[2] = (y-yprev)/(float(Ts)/1000.0); // Angular speed of the arm + #endif + + X[0] = X[0] + (Xr[1] - X[1]); // Integral state + yprev=y; + + empcSequential(X, u_opt); // solve Explicit MPC problem + u1 =BaseU+u_opt[0]; // Save system input into input variable + u2 =BaseU+u_opt[1]; + + BicopShield.actuatorWrite(u1,u2); // Actuation + + Serial.print(Xr[1],3); // Printing reference + Serial.print(", "); + Serial.print(X[1],3); // Printing output + Serial.print(", "); + Serial.print(X[2],4); + Serial.print(", "); + Serial.print(u1,3); // Printing input + Serial.print(", "); + Serial.print(u2,3); // Printing input + Serial.print(", "); + Serial.println(X[1],4); +} diff --git a/examples/BicopShield/BicopShield_EMPC/ectrl.h b/examples/BicopShield/BicopShield_EMPC/ectrl.h new file mode 100644 index 00000000..0130b96b --- /dev/null +++ b/examples/BicopShield/BicopShield_EMPC/ectrl.h @@ -0,0 +1,98 @@ +/* + MATRICES FOR EXPLICIT MPC POLYTOPES AND CORRESPONDING PWA LAWS + + The automatically generated set of matrices have been adapted from + the C code auto-generation routine of the Multi-Parametric Toolbox 3 + MPT3) of Kvasnica et al. for MATLAB. Please see http://www.mpt3.org + for more information. Please see the original "toC.m" for more details + in the MPT3. + + The following C code has been slightly adapted to perform microcontroller + architecutre-specific changes for AVR and ARM Cortex-A devices. + + The list of changes from the original are as follows: + - Changed "static" modifiers to "const" so microcontrollers will + prefer to use ROM instead of RAM. + - Added PROGMEM functionality for the AVR architecture, and calling + the necessary headers. + - Removed the possibility to use PWQ, this only handles PWA. + - Removed matrix export for the tie-breaking function. + + Usage: include alongside with the empcSequential.h header to your + example. + + This code snippet has been altered for the needs of the + the AutomationShield hardware and software ecosystem. + Visit http://www.automationshield.com for more details. + + + Copyright (C) 2005 by Michal Kvasnica (michal.kvasnica@stuba.sk) + Revised in 2012-2013 by Martin Herceg (herceg@control.ee.ethz.ch) + Adapted for MCU use by Gergely Tak�cs in 2020 (gergely.takacs@stuba.sk) +*/ +#include + +#define MPT_NR 5 +#define MPT_DOMAIN 3 +#define MPT_RANGE 2 +#define MPT_ABSTOL 1.000000e-08 + +const float MPT_A[] PROGMEM = { +2.9635436e-02, -9.8775575e-01, -1.5316764e-01, -7.0710678e-01, 7.0710678e-01, +0.0000000e+00, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, 2.9635436e-02, -9.8775575e-01, -1.5316764e-01, +-2.9635436e-02, 9.8775575e-01, 1.5316764e-01, 2.9635436e-02, -9.8775575e-01, +-1.5316764e-01, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, 0.0000000e+00, -9.9995024e-01, +-9.9758962e-03, 0.0000000e+00, -1.0000000e+00, 0.0000000e+00, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, +0.0000000e+00, 9.9995024e-01, 9.9758962e-03, 0.0000000e+00, 1.0000000e+00, +0.0000000e+00, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 2.9635436e-02, -9.8775575e-01, +-1.5316764e-01 }; + +const float MPT_B[] PROGMEM = { +1.2172140e-01, 7.0710678e+03, 7.0710678e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, 1.2172140e-01, 7.0710678e+03, 7.0710678e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.4834728e-01, +-1.2172140e-01, -1.2172140e-01, 1.4834728e-01, 7.0710678e+03, 7.0710678e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, -1.4834728e-01, +7.0710678e+03, 9.9996259e+03, 1.0000000e+04, 7.0710678e+03, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 7.0710678e+03, 7.0710678e+03, +9.9996259e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.4834728e-01 }; + +const int MPT_NC[] PROGMEM = { +8, 8, 8, 9, 9 +}; + + +const float MPT_F[] PROGMEM = { +5.9124557e+00, -1.9706348e+02, -3.0557908e+01, -7.3040818e+00, 2.4344669e+02, +3.7750381e+01, 6.3618820e+00, -2.1204296e+02, -3.2880720e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1204296e+02, -3.2880720e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00 +}; + + +const float MPT_G[] PROGMEM = { +-3.5527137e-15, 0.0000000e+00, -1.8459251e+00, -3.0000000e+01, 1.8459251e+00, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01 +}; + diff --git a/examples/BicopShield/BicopShield_EMPC/ectrl_due.h b/examples/BicopShield/BicopShield_EMPC/ectrl_due.h new file mode 100644 index 00000000..db74230c --- /dev/null +++ b/examples/BicopShield/BicopShield_EMPC/ectrl_due.h @@ -0,0 +1,1366 @@ +/* + MATRICES FOR EXPLICIT MPC POLYTOPES AND CORRESPONDING PWA LAWS + + The automatically generated set of matrices have been adapted from + the C code auto-generation routine of the Multi-Parametric Toolbox 3 + MPT3) of Kvasnica et al. for MATLAB. Please see http://www.mpt3.org + for more information. Please see the original "toC.m" for more details + in the MPT3. + + The following C code has been slightly adapted to perform microcontroller + architecutre-specific changes for AVR and ARM Cortex-A devices. + + The list of changes from the original are as follows: + - Changed "static" modifiers to "const" so microcontrollers will + prefer to use ROM instead of RAM. + - Added PROGMEM functionality for the AVR architecture, and calling + the necessary headers. + - Removed the possibility to use PWQ, this only handles PWA. + - Removed matrix export for the tie-breaking function. + + Usage: include alongside with the empcSequential.h header to your + example. + + This code snippet has been altered for the needs of the + the AutomationShield hardware and software ecosystem. + Visit http://www.automationshield.com for more details. + + + Copyright (C) 2005 by Michal Kvasnica (michal.kvasnica@stuba.sk) + Revised in 2012-2013 by Martin Herceg (herceg@control.ee.ethz.ch) + Adapted for MCU use by Gergely Tak�cs in 2020 (gergely.takacs@stuba.sk) +*/ +#define MPT_NR 129 +#define MPT_DOMAIN 3 +#define MPT_RANGE 6 +#define MPT_ABSTOL 1.000000e-08 + +const float MPT_A[] = { +-2.7941309e-02, 9.8641862e-01, 1.6185672e-01, -2.8670865e-02, 9.8702068e-01, +1.5801315e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, +8.9441719e-01, 4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9361501e-02, +-9.8754664e-01, -1.5456238e-01, -2.8707816e-02, 9.8705077e-01, 1.5781835e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7941309e-02, -9.8641862e-01, +-1.6185672e-01, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, -2.7941309e-02, +9.8641862e-01, 1.6185672e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -3.1638477e-01, 9.4858479e-01, 9.3580493e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, -2.8670865e-02, +9.8702068e-01, 1.5801315e-01, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 3.1621947e-01, -9.4863900e-01, +-9.4490605e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, 3.1638477e-01, +-9.4858479e-01, -9.3580493e-03, -2.7841079e-02, 9.8633695e-01, 1.6237087e-01, +-2.8623413e-02, 9.8698410e-01, 1.5825010e-01, 2.9361501e-02, -9.8754664e-01, +-1.5456238e-01, -2.9361501e-02, 9.8754664e-01, 1.5456238e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, -4.4755899e-01, 8.9424397e-01, 4.3207198e-03, +-3.1693421e-01, 9.4840421e-01, 9.0639411e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.8707816e-02, -9.8705077e-01, +-1.5781835e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.8707816e-02, +9.8705077e-01, 1.5781835e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +-2.8660499e-02, 9.8701434e-01, 1.5805462e-01, 2.9431206e-02, -9.8760061e-01, +-1.5420392e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.7841079e-02, -9.8633695e-01, -1.6237087e-01, +-2.7841079e-02, 9.8633695e-01, 1.6237087e-01, -2.8763969e-02, 9.8709643e-01, +1.5752230e-01, 2.7941309e-02, -9.8641862e-01, -1.6185672e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, +-2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9401253e-02, -9.8757655e-01, +-1.5436364e-01, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, +-2.8623413e-02, 9.8698410e-01, 1.5825010e-01, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, 2.8670865e-02, -9.8702068e-01, -1.5801315e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, +-3.1660445e-01, 9.4851268e-01, 9.2370891e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.8670865e-02, 9.8702068e-01, 1.5801315e-01, +2.9461666e-02, -9.8762191e-01, -1.5406159e-01, 3.1621947e-01, -9.4863900e-01, +-9.4490605e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -5.1465432e-01, +8.5739605e-01, 1.7123568e-03, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +3.1693421e-01, -9.4840421e-01, -9.0639411e-03, 3.1621947e-01, -9.4863900e-01, +-9.4490605e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, +3.1660445e-01, -9.4851268e-01, -9.2370891e-03, -2.7686827e-02, 9.8621074e-01, +1.6316196e-01, -2.8550707e-02, 9.8692793e-01, 1.5861313e-01, 2.9361501e-02, +-9.8754664e-01, -1.5456238e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, +-4.4801347e-01, 8.9401724e-01, 4.1366262e-03, -3.1787210e-01, 9.4809498e-01, +8.5583910e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.9361501e-02, 9.8754664e-01, 1.5456238e-01, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 4.4755899e-01, -8.9424397e-01, +-4.3207198e-03, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, +2.8660499e-02, -9.8701434e-01, -1.5805462e-01, -2.8660499e-02, 9.8701434e-01, +1.5805462e-01, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.8707816e-02, +-9.8705077e-01, -1.5781835e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7828592e-02, -9.8632425e-01, -1.6245013e-01, -2.8707816e-02, 9.8705077e-01, +1.5781835e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, -2.7828592e-02, +9.8632425e-01, 1.6245013e-01, 2.7896798e-02, -9.8638139e-01, -1.6209107e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8763969e-02, -9.8709643e-01, +-1.5752230e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, -2.8763969e-02, +9.8709643e-01, 1.5752230e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, +2.9431206e-02, -9.8760061e-01, -1.5420392e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 2.7686827e-02, -9.8621074e-01, -1.6316196e-01, -2.9431206e-02, +9.8760061e-01, 1.5420392e-01, -2.7686827e-02, 9.8621074e-01, 1.6316196e-01, +-2.8716859e-02, 9.8706023e-01, 1.5775753e-01, 2.9536735e-02, -9.8768205e-01, +-1.5366115e-01, -2.9536735e-02, 9.8768205e-01, 1.5366115e-01, 2.7841079e-02, +-9.8633695e-01, -1.6237087e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7641502e-02, 9.8617252e-01, 1.6340044e-01, 2.9401253e-02, -9.8757655e-01, +-1.5436364e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8550707e-02, +-9.8692793e-01, -1.5861313e-01, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, +-2.8550707e-02, 9.8692793e-01, 1.5861313e-01, -2.7727550e-02, 9.8624160e-01, +1.6296839e-01, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, -2.9461666e-02, +9.8762191e-01, 1.5406159e-01, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8623413e-02, 9.8698410e-01, +1.5825010e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, 2.8670865e-02, +-9.8702068e-01, -1.5801315e-01, -2.8670865e-02, 9.8702068e-01, 1.5801315e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -3.1638477e-01, 9.4858479e-01, 9.3580493e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9401253e-02, -9.8757655e-01, +-1.5436364e-01, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -5.1465432e-01, +8.5739605e-01, 1.7123568e-03, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +-3.1621947e-01, 9.4863900e-01, 9.4490605e-03, 3.1787210e-01, -9.4809498e-01, +-8.5583910e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -3.1621947e-01, +9.4863900e-01, 9.4490605e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 3.1638477e-01, -9.4858479e-01, +-9.3580493e-03, -2.7841079e-02, 9.8633695e-01, 1.6237087e-01, -2.8623413e-02, +9.8698410e-01, 1.5825010e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, +-4.4755899e-01, 8.9424397e-01, 4.3207198e-03, -3.1693421e-01, 9.4840421e-01, +9.0639411e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.9361501e-02, -9.8754664e-01, -1.5456238e-01, -2.9361501e-02, 9.8754664e-01, +1.5456238e-01, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, 4.4801347e-01, -8.9401724e-01, -4.1366262e-03, 2.9470725e-02, +-9.8763026e-01, -1.5400634e-01, 2.7641502e-02, -9.8617252e-01, -1.6340044e-01, +2.8588002e-02, -9.8695841e-01, -1.5841660e-01, -2.9470725e-02, 9.8763026e-01, +1.5400634e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.7641502e-02, +9.8617252e-01, 1.6340044e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, +-2.9530786e-02, 9.8767524e-01, 1.5370603e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, 2.7727550e-02, -9.8624160e-01, -1.6296839e-01, -2.8660499e-02, +9.8701434e-01, 1.5805462e-01, -2.7727550e-02, 9.8624160e-01, 1.6296839e-01, +2.9575905e-02, -9.8771133e-01, -1.5346531e-01, -2.9575905e-02, 9.8771133e-01, +1.5346531e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, +2.8716859e-02, -9.8706023e-01, -1.5775753e-01, -2.8716859e-02, 9.8706023e-01, +1.5775753e-01, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, -2.8707816e-02, +9.8705077e-01, 1.5781835e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.9470725e-02, -9.8763026e-01, +-1.5400634e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, 2.8763969e-02, +-9.8709643e-01, -1.5752230e-01, 2.7828592e-02, -9.8632425e-01, -1.6245013e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, -2.8763969e-02, 9.8709643e-01, 1.5752230e-01, 2.9635436e-02, +-9.8775575e-01, -1.5316764e-01, -2.8660499e-02, 9.8701434e-01, 1.5805462e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7841079e-02, -9.8633695e-01, +-1.6237087e-01, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, -2.9431206e-02, +9.8760061e-01, 1.5420392e-01, -2.7841079e-02, 9.8633695e-01, 1.6237087e-01, +-2.8644678e-02, 9.8700467e-01, 1.5811791e-01, 2.9536735e-02, -9.8768205e-01, +-1.5366115e-01, 2.7686827e-02, -9.8621074e-01, -1.6316196e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.7686827e-02, 9.8621074e-01, 1.6316196e-01, +-2.9536735e-02, 9.8768205e-01, 1.5366115e-01, -2.7796248e-02, 9.8629934e-01, +1.6260684e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8623413e-02, +-9.8698410e-01, -1.5825010e-01, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, +-2.9401253e-02, 9.8757655e-01, 1.5436364e-01, -2.8623413e-02, 9.8698410e-01, +1.5825010e-01, -2.7572044e-02, 9.8611385e-01, 1.6376585e-01, 2.9461666e-02, +-9.8762191e-01, -1.5406159e-01, 2.8550707e-02, -9.8692793e-01, -1.5861313e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8550707e-02, 9.8692793e-01, +1.5861313e-01, -2.9461666e-02, 9.8762191e-01, 1.5406159e-01, -2.7796248e-02, +9.8629934e-01, 1.6260684e-01, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, +2.9401253e-02, -9.8757655e-01, -1.5436364e-01, -2.9401253e-02, 9.8757655e-01, +1.5436364e-01, -2.8623413e-02, 9.8698410e-01, 1.5825010e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9361501e-02, -9.8754664e-01, +-1.5456238e-01, 2.8670865e-02, -9.8702068e-01, -1.5801315e-01, -5.1465432e-01, +8.5739605e-01, 1.7123568e-03, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, 3.1693421e-01, -9.4840421e-01, -9.0639411e-03, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, 4.4755899e-01, +-8.9424397e-01, -4.3207198e-03, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, +-2.8670865e-02, 9.8702068e-01, 1.5801315e-01, -2.9361501e-02, 9.8754664e-01, +1.5456238e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, +8.9441719e-01, 4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, +7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 2.8660499e-02, +-9.8701434e-01, -1.5805462e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, +-2.9470725e-02, 9.8763026e-01, 1.5400634e-01, -2.8660499e-02, 9.8701434e-01, +1.5805462e-01, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9530786e-02, +-9.8767524e-01, -1.5370603e-01, 2.8588002e-02, -9.8695841e-01, -1.5841660e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7572044e-02, -9.8611385e-01, +-1.6376585e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.9530786e-02, +9.8767524e-01, 1.5370603e-01, -2.7572044e-02, 9.8611385e-01, 1.6376585e-01, +2.9575905e-02, -9.8771133e-01, -1.5346531e-01, 2.7641502e-02, -9.8617252e-01, +-1.6340044e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7641502e-02, +9.8617252e-01, 1.6340044e-01, 2.8644678e-02, -9.8700467e-01, -1.5811791e-01, +-2.9575905e-02, 9.8771133e-01, 1.5346531e-01, -2.8644678e-02, 9.8700467e-01, +1.5811791e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, 2.9470725e-02, +-9.8763026e-01, -1.5400634e-01, -2.9470725e-02, 9.8763026e-01, 1.5400634e-01, +-2.8660499e-02, 9.8701434e-01, 1.5805462e-01, 2.7796248e-02, -9.8629934e-01, +-1.6260684e-01, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9635436e-02, +-9.8775575e-01, -1.5316764e-01, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, +2.8716859e-02, -9.8706023e-01, -1.5775753e-01, 2.7727550e-02, -9.8624160e-01, +-1.6296839e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7727550e-02, +9.8624160e-01, 1.6296839e-01, -2.8716859e-02, 9.8706023e-01, 1.5775753e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 2.9470725e-02, -9.8763026e-01, +-1.5400634e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8660499e-02, +9.8701434e-01, 1.5805462e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, +-4.4721134e-01, 8.9441719e-01, 4.4615011e-03, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7941309e-02, -9.8641862e-01, -1.6185672e-01, 2.9431206e-02, -9.8760061e-01, +-1.5420392e-01, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, -2.7941309e-02, +9.8641862e-01, 1.6185672e-01, 2.8763969e-02, -9.8709643e-01, -1.5752230e-01, +-2.8763969e-02, 9.8709643e-01, 1.5752230e-01, 2.7896798e-02, -9.8638139e-01, +-1.6209107e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7896798e-02, +9.8638139e-01, 1.6209107e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, +2.7828592e-02, -9.8632425e-01, -1.6245013e-01, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8707816e-02, +9.8705077e-01, 1.5781835e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, +-2.8707816e-02, 9.8705077e-01, 1.5781835e-01, -2.9431206e-02, 9.8760061e-01, +1.5420392e-01, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, +-8.9441719e-01, -4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 2.7941309e-02, +-9.8641862e-01, -1.6185672e-01, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, +-2.8716859e-02, 9.8706023e-01, 1.5775753e-01, 2.7841079e-02, -9.8633695e-01, +-1.6237087e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7841079e-02, +9.8633695e-01, 1.6237087e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, +-2.9536735e-02, 9.8768205e-01, 1.5366115e-01, 2.7686827e-02, -9.8621074e-01, +-1.6316196e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.7686827e-02, +9.8621074e-01, 1.6316196e-01, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7896798e-02, 9.8638139e-01, +1.6209107e-01, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.8670865e-02, -9.8702068e-01, -1.5801315e-01, +-2.8670865e-02, 9.8702068e-01, 1.5801315e-01, -2.7727550e-02, 9.8624160e-01, +1.6296839e-01, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, +-2.9461666e-02, 9.8762191e-01, 1.5406159e-01, -2.7641502e-02, 9.8617252e-01, +1.6340044e-01, 2.8550707e-02, -9.8692793e-01, -1.5861313e-01, -2.8550707e-02, +9.8692793e-01, 1.5861313e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.9401253e-02, 9.8757655e-01, 1.5436364e-01, -2.7841079e-02, 9.8633695e-01, +1.6237087e-01, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, -2.9361501e-02, +9.8754664e-01, 1.5456238e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.8623413e-02, -9.8698410e-01, -1.5825010e-01, -2.9470725e-02, 9.8763026e-01, +1.5400634e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7896798e-02, +-9.8638139e-01, -1.6209107e-01, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, +-2.8707816e-02, 9.8705077e-01, 1.5781835e-01, -2.7896798e-02, 9.8638139e-01, +1.6209107e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.7727550e-02, -9.8624160e-01, -1.6296839e-01, +-2.8660499e-02, 9.8701434e-01, 1.5805462e-01, 2.9530786e-02, -9.8767524e-01, +-1.5370603e-01, -2.9530786e-02, 9.8767524e-01, 1.5370603e-01, -2.7727550e-02, +9.8624160e-01, 1.6296839e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, +-2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.8716859e-02, -9.8706023e-01, +-1.5775753e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, -2.9575905e-02, +9.8771133e-01, 1.5346531e-01, -2.8716859e-02, 9.8706023e-01, 1.5775753e-01, +2.8588002e-02, -9.8695841e-01, -1.5841660e-01, -2.8588002e-02, 9.8695841e-01, +1.5841660e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.7641502e-02, -9.8617252e-01, -1.6340044e-01, +-2.9470725e-02, 9.8763026e-01, 1.5400634e-01, -2.7641502e-02, 9.8617252e-01, +1.6340044e-01, 2.9635436e-02, -9.8775575e-01, -1.5316764e-01, 2.8644678e-02, +-9.8700467e-01, -1.5811791e-01, 2.7572044e-02, -9.8611385e-01, -1.6376585e-01, +-2.7572044e-02, 9.8611385e-01, 1.6376585e-01, -2.8644678e-02, 9.8700467e-01, +1.5811791e-01, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, 2.7641502e-02, +-9.8617252e-01, -1.6340044e-01, -2.7641502e-02, 9.8617252e-01, 1.6340044e-01, +2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 2.8588002e-02, -9.8695841e-01, -1.5841660e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, +2.9431206e-02, -9.8760061e-01, -1.5420392e-01, -2.9431206e-02, 9.8760061e-01, +1.5420392e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7841079e-02, +-9.8633695e-01, -1.6237087e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, +-2.7841079e-02, 9.8633695e-01, 1.6237087e-01, 2.8716859e-02, -9.8706023e-01, +-1.5775753e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, -2.9575905e-02, +9.8771133e-01, 1.5346531e-01, -2.8716859e-02, 9.8706023e-01, 1.5775753e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, -2.7796248e-02, 9.8629934e-01, +1.6260684e-01, 2.7727550e-02, -9.8624160e-01, -1.6296839e-01, 2.9530786e-02, +-9.8767524e-01, -1.5370603e-01, -2.9530786e-02, 9.8767524e-01, 1.5370603e-01, +-2.7727550e-02, 9.8624160e-01, 1.6296839e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8660499e-02, +9.8701434e-01, 1.5805462e-01, 2.7941309e-02, -9.8641862e-01, -1.6185672e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7941309e-02, 9.8641862e-01, +1.6185672e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, 2.8763969e-02, +-9.8709643e-01, -1.5752230e-01, 2.7896798e-02, -9.8638139e-01, -1.6209107e-01, +2.8707816e-02, -9.8705077e-01, -1.5781835e-01, -2.8707816e-02, 9.8705077e-01, +1.5781835e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8670865e-02, 9.8702068e-01, +1.5801315e-01, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, 2.7828592e-02, +-9.8632425e-01, -1.6245013e-01, -2.8763969e-02, 9.8709643e-01, 1.5752230e-01, +-2.9536735e-02, 9.8768205e-01, 1.5366115e-01, 2.7941309e-02, -9.8641862e-01, +-1.6185672e-01, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, +-8.9441719e-01, -4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -2.7941309e-02, +9.8641862e-01, 1.6185672e-01, 2.7841079e-02, -9.8633695e-01, -1.6237087e-01, +-2.8660499e-02, 9.8701434e-01, 1.5805462e-01, -2.7841079e-02, 9.8633695e-01, +1.6237087e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9431206e-02, +-9.8760061e-01, -1.5420392e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, +-2.8550707e-02, 9.8692793e-01, 1.5861313e-01, 2.9361501e-02, -9.8754664e-01, +-1.5456238e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7686827e-02, +-9.8621074e-01, -1.6316196e-01, -2.7828592e-02, 9.8632425e-01, 1.6245013e-01, +-2.9461666e-02, 9.8762191e-01, 1.5406159e-01, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7686827e-02, +9.8621074e-01, 1.6316196e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.9361501e-02, 9.8754664e-01, 1.5456238e-01, 2.8550707e-02, -9.8692793e-01, +-1.5861313e-01, -2.9530786e-02, 9.8767524e-01, 1.5370603e-01, 2.8707816e-02, +-9.8705077e-01, -1.5781835e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7828592e-02, -9.8632425e-01, -1.6245013e-01, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, -2.9575905e-02, 9.8771133e-01, 1.5346531e-01, 2.7896798e-02, +-9.8638139e-01, -1.6209107e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7896798e-02, 9.8638139e-01, 1.6209107e-01, 2.8763969e-02, -9.8709643e-01, +-1.5752230e-01, -2.8763969e-02, 9.8709643e-01, 1.5752230e-01, 2.8660499e-02, +-9.8701434e-01, -1.5805462e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.9470725e-02, 9.8763026e-01, 1.5400634e-01, -2.7796248e-02, 9.8629934e-01, +1.6260684e-01, 2.8716859e-02, -9.8706023e-01, -1.5775753e-01, 2.7727550e-02, +-9.8624160e-01, -1.6296839e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7727550e-02, 9.8624160e-01, 1.6296839e-01, -2.8716859e-02, 9.8706023e-01, +1.5775753e-01, 2.9635436e-02, -9.8775575e-01, -1.5316764e-01, -2.9635436e-02, +9.8775575e-01, 1.5316764e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, +-2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, -2.8660499e-02, 9.8701434e-01, 1.5805462e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7686827e-02, -9.8621074e-01, +-1.6316196e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, 2.8588002e-02, +-9.8695841e-01, -1.5841660e-01, -2.7686827e-02, 9.8621074e-01, 1.6316196e-01, +2.8644678e-02, -9.8700467e-01, -1.5811791e-01, -2.8644678e-02, 9.8700467e-01, +1.5811791e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, 2.7641502e-02, +-9.8617252e-01, -1.6340044e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7641502e-02, 9.8617252e-01, 1.6340044e-01, -2.9575905e-02, 9.8771133e-01, +1.5346531e-01, 2.7572044e-02, -9.8611385e-01, -1.6376585e-01, -2.7572044e-02, +9.8611385e-01, 1.6376585e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, +2.8588002e-02, -9.8695841e-01, -1.5841660e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.9530786e-02, +9.8767524e-01, 1.5370603e-01, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8550707e-02, -9.8692793e-01, +-1.5861313e-01, 2.7641502e-02, -9.8617252e-01, -1.6340044e-01, -2.8550707e-02, +9.8692793e-01, 1.5861313e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, +-2.9536735e-02, 9.8768205e-01, 1.5366115e-01, 2.7841079e-02, -9.8633695e-01, +-1.6237087e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7841079e-02, +9.8633695e-01, 1.6237087e-01, 2.8716859e-02, -9.8706023e-01, -1.5775753e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, -2.8660499e-02, 9.8701434e-01, 1.5805462e-01, +-2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9461666e-02, -9.8762191e-01, +-1.5406159e-01, -2.9461666e-02, 9.8762191e-01, 1.5406159e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.8623413e-02, 9.8698410e-01, 1.5825010e-01, +2.7727550e-02, -9.8624160e-01, -1.6296839e-01, 2.7941309e-02, -9.8641862e-01, +-1.6185672e-01, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, +-3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, +2.8707816e-02, -9.8705077e-01, -1.5781835e-01, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, -2.8670865e-02, 9.8702068e-01, 1.5801315e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, +2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.7941309e-02, -9.8641862e-01, +-1.6185672e-01, -2.8707816e-02, 9.8705077e-01, 1.5781835e-01, -2.9431206e-02, +9.8760061e-01, 1.5420392e-01, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, +7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -2.8623413e-02, 9.8698410e-01, +1.5825010e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9361501e-02, +-9.8754664e-01, -1.5456238e-01, 2.7841079e-02, -9.8633695e-01, -1.6237087e-01, +-2.9361501e-02, 9.8754664e-01, 1.5456238e-01, -2.9635436e-02, 9.8775575e-01, +1.5316764e-01, 2.8763969e-02, -9.8709643e-01, -1.5752230e-01, 2.7828592e-02, +-9.8632425e-01, -1.6245013e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7828592e-02, 9.8632425e-01, 1.6245013e-01, -2.8763969e-02, 9.8709643e-01, +1.5752230e-01, 2.7896798e-02, -9.8638139e-01, -1.6209107e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8707816e-02, -9.8705077e-01, +-1.5781835e-01, -2.8707816e-02, 9.8705077e-01, 1.5781835e-01, 2.8716859e-02, +-9.8706023e-01, -1.5775753e-01, -2.8716859e-02, 9.8706023e-01, 1.5775753e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9575905e-02, +-9.8771133e-01, -1.5346531e-01, -2.9575905e-02, 9.8771133e-01, 1.5346531e-01, +2.7727550e-02, -9.8624160e-01, -1.6296839e-01, -2.7727550e-02, 9.8624160e-01, +1.6296839e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, -2.8660499e-02, +9.8701434e-01, 1.5805462e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, +-2.9530786e-02, 9.8767524e-01, 1.5370603e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, 2.9401253e-02, +-9.8757655e-01, -1.5436364e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, +-2.9401253e-02, 9.8757655e-01, 1.5436364e-01, -2.8623413e-02, 9.8698410e-01, +1.5825010e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, 2.7686827e-02, +-9.8621074e-01, -1.6316196e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7686827e-02, 9.8621074e-01, 1.6316196e-01, -2.9536735e-02, 9.8768205e-01, +1.5366115e-01, 2.8644678e-02, -9.8700467e-01, -1.5811791e-01, 2.7641502e-02, +-9.8617252e-01, -1.6340044e-01, 2.8588002e-02, -9.8695841e-01, -1.5841660e-01, +-2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.7641502e-02, 9.8617252e-01, +1.6340044e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, +2.8550707e-02, -9.8692793e-01, -1.5861313e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, -2.8550707e-02, 9.8692793e-01, 1.5861313e-01, -2.9461666e-02, +9.8762191e-01, 1.5406159e-01, 2.7572044e-02, -9.8611385e-01, -1.6376585e-01, +2.7841079e-02, -9.8633695e-01, -1.6237087e-01, 2.9431206e-02, -9.8760061e-01, +-1.5420392e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, -2.7841079e-02, +9.8633695e-01, 1.6237087e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.8660499e-02, -9.8701434e-01, -1.5805462e-01, 2.8623413e-02, -9.8698410e-01, +-1.5825010e-01, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, -2.9401253e-02, +9.8757655e-01, 1.5436364e-01, -2.8623413e-02, 9.8698410e-01, 1.5825010e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7796248e-02, -9.8629934e-01, +-1.6260684e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, +8.9441719e-01, 4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, +7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, 2.8670865e-02, +-9.8702068e-01, -1.5801315e-01, 2.7941309e-02, -9.8641862e-01, -1.6185672e-01, +-2.8670865e-02, 9.8702068e-01, 1.5801315e-01, -2.9361501e-02, 9.8754664e-01, +1.5456238e-01, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, +-8.9441719e-01, -4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 2.7941309e-02, +-9.8641862e-01, -1.6185672e-01, 2.7828592e-02, -9.8632425e-01, -1.6245013e-01, +-2.9530786e-02, 9.8767524e-01, 1.5370603e-01, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.8707816e-02, 9.8705077e-01, 1.5781835e-01, +2.8763969e-02, -9.8709643e-01, -1.5752230e-01, -2.9575905e-02, 9.8771133e-01, +1.5346531e-01, -2.8763969e-02, 9.8709643e-01, 1.5752230e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +-2.9401253e-02, 9.8757655e-01, 1.5436364e-01, 7.0710678e-01, -7.0710678e-01, +0.0000000e+00, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, 3.1638477e-01, +-9.4858479e-01, -9.3580493e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.8670865e-02, -9.8702068e-01, -1.5801315e-01, 2.7896798e-02, +-9.8638139e-01, -1.6209107e-01, -2.8670865e-02, 9.8702068e-01, 1.5801315e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7841079e-02, 9.8633695e-01, +1.6237087e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, 2.8716859e-02, +-9.8706023e-01, -1.5775753e-01, -2.9536735e-02, 9.8768205e-01, 1.5366115e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, -2.8660499e-02, 9.8701434e-01, 1.5805462e-01, -2.7796248e-02, +9.8629934e-01, 1.6260684e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, +-2.9470725e-02, 9.8763026e-01, 1.5400634e-01, 2.8623413e-02, -9.8698410e-01, +-1.5825010e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8623413e-02, +9.8698410e-01, 1.5825010e-01, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, +2.7727550e-02, -9.8624160e-01, -1.6296839e-01, -2.9461666e-02, 9.8762191e-01, +1.5406159e-01, 2.7686827e-02, -9.8621074e-01, -1.6316196e-01, -2.7686827e-02, +9.8621074e-01, 1.6316196e-01, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.9431206e-02, 9.8760061e-01, +1.5420392e-01, 2.8588002e-02, -9.8695841e-01, -1.5841660e-01, 2.8550707e-02, +-9.8692793e-01, -1.5861313e-01, -2.8550707e-02, 9.8692793e-01, 1.5861313e-01, +2.9401253e-02, -9.8757655e-01, -1.5436364e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, 2.7641502e-02, +-9.8617252e-01, -1.6340044e-01, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, +-2.9361501e-02, 9.8754664e-01, 1.5456238e-01, 7.0710678e-01, -7.0710678e-01, +0.0000000e+00, 4.4755899e-01, -8.9424397e-01, -4.3207198e-03, 3.1693421e-01, +-9.4840421e-01, -9.0639411e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, 2.7841079e-02, +-9.8633695e-01, -1.6237087e-01, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, +-4.4721134e-01, 8.9441719e-01, 4.4615011e-03, 7.0710678e-01, -7.0710678e-01, +0.0000000e+00, -5.1465432e-01, 8.5739605e-01, 1.7123568e-03, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, -4.4755899e-01, 8.9424397e-01, 4.3207198e-03, +3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, -3.1693421e-01, 9.4840421e-01, 9.0639411e-03, +-2.9461666e-02, 9.8762191e-01, 1.5406159e-01, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, +-8.9441719e-01, -4.4615011e-03, 3.1660445e-01, -9.4851268e-01, -9.2370891e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -2.8670865e-02, +9.8702068e-01, 1.5801315e-01, 2.7828592e-02, -9.8632425e-01, -1.6245013e-01, +2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.8707816e-02, -9.8705077e-01, +-1.5781835e-01, -2.9470725e-02, 9.8763026e-01, 1.5400634e-01, -2.8707816e-02, +9.8705077e-01, 1.5781835e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.9536735e-02, 9.8768205e-01, +1.5366115e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7941309e-02, +9.8641862e-01, 1.6185672e-01, 2.8763969e-02, -9.8709643e-01, -1.5752230e-01, +4.4721134e-01, -8.9441719e-01, -4.4615011e-03, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -3.1621947e-01, +9.4863900e-01, 9.4490605e-03, -3.1638477e-01, 9.4858479e-01, 9.3580493e-03, +2.7841079e-02, -9.8633695e-01, -1.6237087e-01, -2.7841079e-02, 9.8633695e-01, +1.6237087e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9431206e-02, +-9.8760061e-01, -1.5420392e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, +-2.9431206e-02, 9.8760061e-01, 1.5420392e-01, 2.8623413e-02, -9.8698410e-01, +-1.5825010e-01, -2.8623413e-02, 9.8698410e-01, 1.5825010e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, -2.9401253e-02, 9.8757655e-01, +1.5436364e-01, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, 4.4801347e-01, -8.9401724e-01, -4.1366262e-03, +3.1787210e-01, -9.4809498e-01, -8.5583910e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, -2.9361501e-02, 9.8754664e-01, 1.5456238e-01, +2.8550707e-02, -9.8692793e-01, -1.5861313e-01, 2.7686827e-02, -9.8621074e-01, +-1.6316196e-01, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, -5.1465432e-01, 8.5739605e-01, 1.7123568e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -4.4801347e-01, 8.9401724e-01, 4.1366262e-03, 3.1621947e-01, +-9.4863900e-01, -9.4490605e-03, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, -3.1787210e-01, 9.4809498e-01, 8.5583910e-03, 3.1621947e-01, +-9.4863900e-01, -9.4490605e-03, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, -3.1660445e-01, 9.4851268e-01, 9.2370891e-03, 2.8670865e-02, +-9.8702068e-01, -1.5801315e-01, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, +-2.8670865e-02, 9.8702068e-01, 1.5801315e-01, 7.0710678e-01, -7.0710678e-01, +0.0000000e+00, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, 3.1638477e-01, +-9.4858479e-01, -9.3580493e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.7941309e-02, +-9.8641862e-01, -1.6185672e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, +-2.7941309e-02, 9.8641862e-01, 1.6185672e-01, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, 4.4755899e-01, -8.9424397e-01, -4.3207198e-03, +3.1693421e-01, -9.4840421e-01, -9.0639411e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, +2.8623413e-02, -9.8698410e-01, -1.5825010e-01, 2.7841079e-02, -9.8633695e-01, +-1.6237087e-01, -2.9361501e-02, 9.8754664e-01, 1.5456238e-01, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, -5.1465432e-01, 8.5739605e-01, 1.7123568e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, -4.4755899e-01, +8.9424397e-01, 4.3207198e-03, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 3.1621947e-01, -9.4863900e-01, +-9.4490605e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -3.1693421e-01, +9.4840421e-01, 9.0639411e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, +-3.1621947e-01, 9.4863900e-01, 9.4490605e-03, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -3.1638477e-01, +9.4858479e-01, 9.3580493e-03, -2.9361501e-02, 9.8754664e-01, 1.5456238e-01, +7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, 2.7941309e-02, -9.8641862e-01, -1.6185672e-01 }; + +const float MPT_B[] = { +-1.3895442e-01, -1.2758139e-01, 7.0710678e+03, 4.4721137e+03, 3.1621952e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, -9.1989026e-02, -1.2700513e-01, +1.0000000e+04, 1.3895442e-01, -1.0333071e-01, -1.1385063e-01, -1.3964801e-01, +7.0710678e+03, 4.4721137e+03, 3.1640234e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.2758139e-01, -1.0463051e-01, -1.0451399e-01, 4.4721137e+03, +1.0000000e+04, -3.1621952e+03, 3.1621952e+03, -3.1640234e+03, -1.5524321e-01, +-1.4266334e-01, -7.0682278e-02, 9.1989026e-02, 7.0710678e+03, 4.4758646e+03, +3.1701189e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +1.3964801e-01, 1.2700513e-01, -1.1591788e-01, -1.0283622e-01, -1.1308694e-01, +-1.4206672e-01, -8.1046541e-02, 1.0333071e-01, 1.0000000e+04, 1.5524321e-01, +-1.2845172e-01, -1.2796905e-01, 1.1385063e-01, 1.0000000e+04, -1.1872361e-01, +-1.5596377e-01, -8.2175907e-02, 1.0463051e-01, 1.0000000e+04, 1.4266334e-01, +-1.1809773e-01, -1.4274260e-01, 1.0451399e-01, 7.0710678e+03, 4.4721137e+03, +3.1664528e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0824316e-01, +-1.2193486e-01, -3.1621952e+03, 3.1621952e+03, 5.1465433e+03, 1.0000000e+04, +-3.1701189e+03, -3.1621952e+03, 4.4721137e+03, 1.0000000e+04, 3.1621955e+03, +-3.1664528e+03, -1.7814849e-01, -1.6367246e-01, 1.2772450e-01, 7.0710678e+03, +4.4807683e+03, 3.1805169e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +7.0682278e-02, -4.4721137e+03, 4.4721137e+03, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, -4.4758646e+03, -9.2490697e-02, 1.1591788e-01, 1.5596377e-01, +1.4206672e-01, -1.1639930e-01, -1.2770703e-01, 1.0283622e-01, 1.0000000e+04, +1.4274260e-01, 1.1925800e-01, -1.3314513e-01, -1.1394861e-01, 1.1308694e-01, +1.0000000e+04, 1.2796905e-01, -1.3123181e-01, -1.0212614e-01, -1.6304718e-01, +1.2562400e-01, 1.0000000e+04, 1.7814849e-01, 8.1046541e-02, -1.4875994e-01, +-1.4300339e-01, -9.4959558e-02, 1.1872361e-01, 1.2845172e-01, 1.0000000e+04, +-1.7890763e-01, 1.2596141e-01, 1.0000000e+04, 1.6367246e-01, 8.2175907e-02, +-1.3681143e-01, -1.5910730e-01, -9.7735705e-02, 1.2193486e-01, 1.1809773e-01, +1.0000000e+04, 1.0742179e-01, -1.2242478e-01, -1.0824316e-01, 1.3131057e-01, +7.0710678e+03, 4.4721137e+03, 3.1640235e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.2088866e-01, -3.1621940e+03, 5.1465433e+03, 1.0000000e+04, +3.1621952e+03, -3.1805169e+03, -3.1621955e+03, 3.1621956e+03, 4.4721137e+03, +1.0000000e+04, -3.1640235e+03, -1.7350735e-01, -1.6044994e-01, 7.0710678e+03, +4.4758643e+03, 3.1701183e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +1.4903125e-01, -1.2772450e-01, -4.4721132e+03, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, 4.4721137e+03, -4.4807683e+03, 1.2386938e-01, 1.7890763e-01, +1.6304718e-01, 9.2490697e-02, -1.3508390e-01, -1.4804153e-01, -1.0798073e-01, +1.3314513e-01, 1.1639930e-01, 1.5910730e-01, 1.1845977e-01, -1.2860539e-01, +-1.0633205e-01, 1.3123181e-01, 1.2770703e-01, 1.0000000e+04, 1.2871086e-01, +1.4300339e-01, -1.1566153e-01, -1.1925800e-01, 1.4342692e-01, 1.0000000e+04, +1.2242478e-01, -1.3213141e-01, -9.5863716e-02, 1.0212614e-01, 1.1394861e-01, +1.0000000e+04, 1.4701368e-01, 1.3415792e-01, -1.4834728e-01, -1.5983067e-01, +1.0000000e+04, 1.7350735e-01, 1.4790817e-01, -1.2562400e-01, -1.4671586e-01, +-1.6394595e-01, 1.2422293e-01, 1.4875994e-01, 1.0000000e+04, 1.1734926e-01, +9.4959558e-02, -1.7425525e-01, 1.0000000e+04, 1.6044994e-01, 1.4841602e-01, +-1.2596141e-01, -1.3588434e-01, -1.8212204e-01, 1.2519039e-01, 1.3681143e-01, +1.0000000e+04, 1.0826153e-01, 9.7735705e-02, -1.3867612e-01, -1.0742179e-01, +-9.8434055e-02, 1.2088866e-01, 1.3198740e-01, 1.0000000e+04, -1.0783877e-01, +7.0710678e+03, 4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.2145607e-01, -1.3131057e-01, 5.1465433e+03, 1.0000000e+04, +-3.1621939e+03, 3.1621940e+03, -3.1701183e+03, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, -4.4721132e+03, 4.4721132e+03, -4.4758643e+03, -1.7189507e-01, +-1.5971609e-01, -1.4903125e-01, 7.0710678e+03, 4.4721132e+03, 3.1621939e+03, +7.0710678e+03, 4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, 1.7425525e-01, 1.5983067e-01, 1.4729656e-01, +-1.2386938e-01, -1.3416325e-01, -1.4599851e-01, 1.2310596e-01, 1.3508390e-01, +1.0000000e+04, 1.8212204e-01, 1.1933228e-01, 1.0798073e-01, -1.4899185e-01, +1.2247802e-01, 1.4804153e-01, 1.0000000e+04, 1.3065475e-01, 1.6394595e-01, +1.0633205e-01, -1.3430757e-01, -1.1845977e-01, -1.0870423e-01, 1.3213141e-01, +1.4412718e-01, 1.3867612e-01, -1.1041938e-01, -1.2172140e-01, 1.4834728e-01, +1.1566153e-01, 1.2860539e-01, 1.0000000e+04, 1.4693877e-01, 1.3339106e-01, +-1.2871086e-01, -1.0765585e-01, 1.0000000e+04, -1.0069582e-01, 7.0710678e+03, +4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +1.0783877e-01, -1.3271674e-01, -1.4342692e-01, -8.2734975e-02, -1.3415792e-01, +1.6000083e-01, 9.5863716e-02, 1.0000000e+04, 1.4607673e-01, -1.4737777e-01, +-1.4701368e-01, 1.7580768e-01, 1.0000000e+04, 1.3493007e-01, -1.4827035e-01, +-1.5909898e-01, -1.4790817e-01, 7.0710678e+03, 4.4721137e+03, 3.1621956e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.7189507e-01, -1.4679127e-01, +-1.6073291e-01, 1.4671586e-01, 1.0000000e+04, 9.7219855e-02, 1.4798698e-01, +-1.2422293e-01, -1.1734926e-01, -1.4729556e-01, 1.4673781e-01, 1.1043258e-01, +1.0000000e+04, -1.7263779e-01, -1.4841602e-01, 1.0000000e+04, 1.5971609e-01, +-1.3664868e-01, -1.7744068e-01, 1.3588434e-01, 1.0000000e+04, 1.4938955e-01, +-1.2519039e-01, -1.6152086e-01, -1.0826153e-01, 1.3512256e-01, 1.0000000e+04, +9.8434055e-02, -1.2401135e-01, -1.0014932e-01, 1.2145607e-01, 1.0000000e+04, +-1.3198740e-01, -1.4729656e-01, 1.0000000e+04, 1.7263779e-01, 1.5909898e-01, +-1.3493007e-01, -1.4607673e-01, 1.3416325e-01, 1.0000000e+04, 1.7744068e-01, +1.0069582e-01, 1.4827035e-01, -1.2310596e-01, -1.4693877e-01, 1.4599851e-01, +1.1041938e-01, 1.6073291e-01, 1.4737777e-01, -1.2247802e-01, -1.3339106e-01, +-1.1933228e-01, 1.4729556e-01, 1.0765585e-01, 1.0000000e+04, 1.6152086e-01, +1.0870423e-01, -1.3065475e-01, 1.2172140e-01, 1.3430757e-01, 1.4899185e-01, +1.4899185e-01, 1.3430757e-01, 1.2172140e-01, -1.3065475e-01, 1.6152086e-01, +1.0870423e-01, 1.0000000e+04, 1.4729556e-01, 1.0765585e-01, -1.1933228e-01, +-1.1043258e-01, 1.3271674e-01, 1.0000000e+04, 1.2401135e-01, -1.4412718e-01, +-9.7219855e-02, -1.3339106e-01, -1.2247802e-01, 1.4737777e-01, 1.6073291e-01, +1.1041938e-01, 1.4599851e-01, -1.4693877e-01, -1.2310596e-01, 1.4827035e-01, +1.7744068e-01, 1.0069582e-01, 1.0000000e+04, 1.3416325e-01, 8.2734975e-02, +7.0710678e+03, 4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.4679127e-01, -1.4798698e-01, -1.6000083e-01, -1.4607673e-01, +-1.3493007e-01, 1.5909898e-01, 1.7263779e-01, 1.0000000e+04, -1.4729656e-01, +1.0000000e+04, 1.3664868e-01, -1.4938955e-01, -1.7580768e-01, -1.6000083e-01, +-1.4798698e-01, 1.4679127e-01, 7.0710678e+03, 4.4721137e+03, 3.1621956e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 8.2734975e-02, -9.7219855e-02, +-1.4412718e-01, 1.2401135e-01, 1.0000000e+04, 1.3271674e-01, -1.1043258e-01, +-1.3512256e-01, 1.0014932e-01, 1.0000000e+04, -1.4673781e-01, -1.7580768e-01, +-1.4938955e-01, 1.3664868e-01, 1.0000000e+04, -1.4673781e-01, 1.0000000e+04, +1.0014932e-01, -1.3512256e-01, -1.4827035e-01, 1.3493007e-01, 1.0000000e+04, +1.7580768e-01, -1.4701368e-01, -1.4737777e-01, 1.4607673e-01, 1.0000000e+04, +9.5863716e-02, 1.6000083e-01, -1.3415792e-01, -1.0069582e-01, 1.0000000e+04, +-1.0765585e-01, -1.2871086e-01, 1.3339106e-01, 1.4693877e-01, 1.0000000e+04, +1.2860539e-01, 1.1566153e-01, 1.4834728e-01, -1.2172140e-01, -1.1041938e-01, +1.3867612e-01, 1.4412718e-01, 1.3213141e-01, -1.0870423e-01, -1.1845977e-01, +1.0000000e+04, 1.4673781e-01, 1.1043258e-01, -1.4729556e-01, -1.1734926e-01, +-1.3430757e-01, 1.6394595e-01, 1.0633205e-01, 1.3065475e-01, 1.0000000e+04, +1.4804153e-01, 1.2247802e-01, -1.4899185e-01, 1.8212204e-01, 1.0798073e-01, +1.1933228e-01, 1.0000000e+04, 1.3508390e-01, 1.2310596e-01, 9.8434055e-02, +1.0000000e+04, 1.3512256e-01, -1.6152086e-01, -1.0826153e-01, -1.2422293e-01, +1.4798698e-01, 9.7219855e-02, 1.0000000e+04, 1.4671586e-01, -1.6073291e-01, +-1.4599851e-01, -1.3416325e-01, -1.2386938e-01, 1.4729656e-01, 1.5983067e-01, +1.7425525e-01, -1.2519039e-01, 1.4938955e-01, 1.0000000e+04, 1.3588434e-01, +-1.7744068e-01, -1.4679127e-01, 1.7189507e-01, 7.0710678e+03, 4.4721137e+03, +3.1621956e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, -1.4790817e-01, +-1.5909898e-01, -1.3664868e-01, 1.5971609e-01, 1.0000000e+04, -1.4841602e-01, +-1.7263779e-01, -8.2734975e-02, -1.4342692e-01, -1.3271674e-01, 1.0783877e-01, +7.0710678e+03, 4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.3198740e-01, 1.0000000e+04, 1.2145607e-01, -1.2401135e-01, +-1.0014932e-01, -1.4834728e-01, 1.3415792e-01, 1.4701368e-01, 1.0000000e+04, +1.1394861e-01, 1.0212614e-01, -9.5863716e-02, -1.3213141e-01, 1.2242478e-01, +1.0000000e+04, 1.4342692e-01, -1.1925800e-01, -1.1566153e-01, 1.4300339e-01, +1.2871086e-01, 1.0000000e+04, 1.2770703e-01, 1.3123181e-01, -1.0633205e-01, +-1.2860539e-01, 1.5910730e-01, 1.1845977e-01, 1.1639930e-01, 1.3314513e-01, +-1.0798073e-01, 1.0000000e+04, 1.3198740e-01, 1.2088866e-01, -1.3867612e-01, +-9.8434055e-02, -1.0742179e-01, 9.4959558e-02, 1.1734926e-01, 1.0000000e+04, +1.4875994e-01, 1.2422293e-01, -1.6394595e-01, -1.4804153e-01, -1.3508390e-01, +1.6304718e-01, 1.7890763e-01, 9.2490697e-02, 1.2386938e-01, 9.7735705e-02, +1.0826153e-01, 1.0000000e+04, 1.3681143e-01, 1.2519039e-01, -1.8212204e-01, +-1.4671586e-01, -1.2562400e-01, 1.4790817e-01, 1.7350735e-01, 1.0000000e+04, +-1.5983067e-01, -1.3588434e-01, -1.2596141e-01, 1.4841602e-01, 1.6044994e-01, +1.0000000e+04, -1.7425525e-01, 7.0710678e+03, 4.4721137e+03, 3.1621956e+03, +7.0710678e+03, 4.4721132e+03, 3.1621939e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, -1.4903125e-01, -1.5971609e-01, -1.7189507e-01, +-1.3131057e-01, -1.2145607e-01, 7.0710678e+03, 4.4721137e+03, 3.1621956e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, -1.0783877e-01, -1.1394861e-01, +-1.3314513e-01, 1.4274260e-01, 1.1925800e-01, 1.0000000e+04, 1.0283622e-01, +-1.0212614e-01, -1.3123181e-01, 1.2796905e-01, 1.0000000e+04, 1.1308694e-01, +-1.2088866e-01, 7.0710678e+03, 4.4721137e+03, 3.1640235e+03, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, 1.3131057e-01, -1.2242478e-01, -1.0824316e-01, +1.0000000e+04, 1.2845172e-01, 1.1872361e-01, -1.4300339e-01, -9.4959558e-02, +-1.2770703e-01, -1.1639930e-01, 1.4206672e-01, 1.5596377e-01, 1.1591788e-01, +-9.2490697e-02, 1.0742179e-01, 1.0000000e+04, 1.1809773e-01, 1.2193486e-01, +-1.5910730e-01, -9.7735705e-02, -1.4875994e-01, 1.7814849e-01, 8.1046541e-02, +1.0000000e+04, 1.2562400e-01, -1.6304718e-01, -1.3681143e-01, 1.6367246e-01, +8.2175907e-02, 1.0000000e+04, 1.2596141e-01, -1.7890763e-01, -1.2772450e-01, +1.4903125e-01, 7.0710678e+03, 4.4758643e+03, 3.1701183e+03, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, -1.6044994e-01, -1.7350735e-01, 4.4721132e+03, +-4.4721132e+03, 7.0710678e+03, -5.1465433e+03, 1.0000000e+04, -4.4758643e+03, +3.1621940e+03, -3.1621939e+03, 5.1465433e+03, 1.0000000e+04, -3.1701183e+03, +-1.2193486e-01, 1.0824316e-01, 7.0710678e+03, 4.4721137e+03, 3.1664528e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0451399e-01, -1.4274260e-01, +-1.1308694e-01, -1.0283622e-01, -1.1591788e-01, 1.2700513e-01, 1.3964801e-01, +1.0000000e+04, -1.1872361e-01, 1.0000000e+04, 1.1385063e-01, -1.2796905e-01, +4.4721137e+03, 1.0000000e+04, 3.1621956e+03, -3.1621955e+03, -3.1640235e+03, +-1.2845172e-01, 1.5524321e-01, 1.0000000e+04, 1.0333071e-01, -1.4206672e-01, +-8.1046541e-02, -1.1809773e-01, 1.4266334e-01, 1.0000000e+04, 1.0463051e-01, +-1.5596377e-01, -8.2175907e-02, 7.0682278e-02, 7.0710678e+03, 4.4807683e+03, +3.1805169e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.2772450e-01, +-1.6367246e-01, -1.7814849e-01, 4.4721137e+03, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, -4.4721132e+03, -4.4807683e+03, 3.1621952e+03, 5.1465433e+03, +1.0000000e+04, -3.1621940e+03, -3.1805169e+03, 3.1621955e+03, 4.4721137e+03, +1.0000000e+04, -3.1621952e+03, -3.1664528e+03, -1.0451399e-01, -1.0463051e-01, +1.2758139e-01, 7.0710678e+03, 4.4721137e+03, 3.1640234e+03, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, -1.3964801e-01, -1.1385063e-01, -1.0333071e-01, +1.3895442e-01, 1.0000000e+04, -1.2700513e-01, 7.0710678e+03, 4.4758646e+03, +3.1701189e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 9.1989026e-02, +-1.4266334e-01, -1.5524321e-01, -7.0682278e-02, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, 4.4721137e+03, -4.4721137e+03, -4.4758646e+03, 5.1465433e+03, +1.0000000e+04, 3.1621952e+03, -3.1621952e+03, -3.1701189e+03, 3.1621952e+03, +-3.1621952e+03, 4.4721137e+03, 1.0000000e+04, -3.1640234e+03, -9.1989026e-02, +7.0710678e+03, 4.4721137e+03, 3.1621952e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.2758139e-01, -1.3895442e-01 }; + +const int MPT_NC[] = { +9, 5, 10, 5, 10, +6, 6, 4, 6, 10, +5, 5, 10, 6, 6, +6, 5, 6, 5, 6, +6, 10, 5, 5, 10, +6, 6, 6, 7, 6, +6, 6, 6, 6, 6, +6, 9, 5, 6, 13, +6, 7, 7, 6, 7, +4, 10, 6, 5, 10, +6, 5, 5, 5, 5, +5, 6, 7, 6, 7, +6, 7, 6, 6, 7, +10, 6, 4, 10, 6, +4, 4, 4, 5, 6, +4, 7, 6, 5, 7, +7, 5, 6, 6, 5, +10, 5, 10, 5, 6, +6, 7, 6, 6, 6, +6, 6, 6, 6, 13, +9, 6, 5, 10, 5, +6, 6, 6, 6, 10, +6, 5, 10, 6, 4, +5, 6, 6, 10, 6, +5, 5, 10, 5, 10, +6, 5, 5, 9 }; + + +const float MPT_F[] = { +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.3618820e+00, -2.2459502e+02, -3.6852726e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1042831e+00, -2.4457143e+02, -3.9153690e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2841140e+05, -3.8522632e+05, -3.8371043e+03, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.8766090e+00, -2.6492238e+02, -4.1463390e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.7892413e+00, -2.3343210e+02, -3.7323176e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.0032591e+00, -2.1226462e+02, -3.4881232e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.5490076e+00, -2.5331631e+02, +-3.9552799e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.9397388e+00, -2.1042948e+02, -3.4640919e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9124557e+00, -2.0872882e+02, +-3.4249316e+01, -7.3040818e+00, 2.5785773e+02, 4.2310644e+01, 7.4840827e+00, +-2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.5450076e+00, -2.2531786e+02, +-3.6071366e+01, -8.0855186e+00, 2.7835135e+02, 4.4561553e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +3.2153807e+04, -9.6459448e+04, -9.6079874e+02, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.0832974e+04, +-1.5249580e+05, -1.5189572e+03, -6.2797629e+04, 1.8838903e+05, 1.8764771e+03, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.1874573e+00, -2.4174341e+02, -3.7835615e+01, -8.8791830e+00, +2.9864302e+02, 4.6741057e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.2841140e+05, +-2.5682122e+05, -1.2810668e+03, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1903322e+00, -2.4096420e+02, -3.7574805e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3823383e+00, -2.1979587e+02, +-3.5196807e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6226667e+00, +-1.9951011e+02, -3.2892355e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.2779292e+00, -2.1585184e+02, -3.4512289e+01, -7.7555776e+00, +2.6665731e+02, 4.2635513e+01, 5.5241768e+00, -1.9579250e+02, -3.2247525e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, +-2.1832144e+02, -3.4840055e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.6001466e+00, -1.9801127e+02, -3.2538994e+01, -6.9182639e+00, 2.4461757e+02, +4.0197760e+01, 6.9164460e+00, -2.3208992e+02, -3.6238511e+01, -8.5443832e+00, +2.8671738e+02, 4.4768040e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.3848450e+00, -1.9180933e+02, +-3.1733570e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.1042831e+00, +-2.3756088e+02, -3.6959139e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.5432465e+00, -1.9638280e+02, -3.2328552e+01, -6.8479712e+00, +2.4260579e+02, 3.9937786e+01, 6.8607153e+00, -2.3044873e+02, -3.6020404e+01, +-8.4755351e+00, 2.8468990e+02, 4.4498595e+01, 6.0753667e+00, -2.1001053e+02, +-3.3751631e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.9588145e+00, -2.3327526e+02, -3.6389185e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.1643997e+00, -2.1255901e+02, -3.4081082e+01, -7.6153263e+00, +2.6258944e+02, 4.2102813e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.1042831e+00, +-2.4457143e+02, -3.9153690e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.2728415e+04, -3.8184464e+04, -3.8034206e+02, -1.5724327e+04, +4.7172015e+04, 4.6986391e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2841140e+05, -3.8522632e+05, -3.8371043e+03, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.8766090e+00, -2.6492238e+02, -4.1463390e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.0832974e+04, -1.0166532e+05, -5.0712347e+02, -6.2797629e+04, 1.2559449e+05, +6.2648610e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.6155691e+00, -2.2170260e+02, +-3.4571242e+01, -8.1726884e+00, 2.7388516e+02, 4.2708342e+01, 5.8435113e+00, +-2.0173857e+02, -3.2381037e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.1186804e+00, -1.8262040e+02, -3.0258654e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.7075935e+00, -2.2433958e+02, -3.4912636e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.9269319e+00, -2.0411252e+02, -3.2685368e+01, +-7.3219653e+00, 2.5215488e+02, 4.0378586e+01, 5.1959216e+00, -1.8481380e+02, +-3.0538976e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.2673222e+02, -3.5228440e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.0634493e+02, -3.2979210e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.2649152e+00, -1.8681595e+02, -3.0799524e+01, -6.5041284e+00, +2.3078718e+02, 3.8048868e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, -2.3343210e+02, +-3.7323176e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.0032591e+00, +-2.1226462e+02, -3.4881232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.9124557e+00, -2.0289842e+02, -3.2378828e+01, -7.3040818e+00, +2.5065502e+02, 3.9999895e+01, 5.1792514e+00, -1.8356736e+02, -3.0234014e+01, +-6.3983018e+00, 2.2677397e+02, 3.7350252e+01, 7.5490076e+00, -2.5331631e+02, +-3.9552799e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.9397388e+00, -2.1042948e+02, -3.4640919e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.5450076e+00, -2.1885921e+02, -3.4049578e+01, -8.0855186e+00, +2.7037252e+02, 4.2063893e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.0532039e+00, -1.7999621e+02, +-2.9779167e+01, -6.2425863e+00, 2.2236226e+02, 3.6788347e+01, 7.4840827e+00, +-2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.4187419e+00, -2.1517080e+02, -3.3565025e+01, +-7.9295336e+00, 2.6581596e+02, 4.1465290e+01, 5.6581569e+00, -1.9558861e+02, +-3.1433826e+01, -6.9899282e+00, 2.4162467e+02, 3.8832467e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.4840827e+00, -2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 3.2153807e+04, -9.6459448e+04, -9.6079874e+02, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.2841140e+05, +-2.5682122e+05, -1.2810668e+03, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.2065976e+00, -2.0758346e+02, +-3.2304982e+01, -7.6674565e+00, 2.5644278e+02, 3.9908667e+01, 5.4574857e+00, +-1.8841160e+02, -3.0241928e+01, -6.7420246e+00, 2.3275841e+02, 3.7360029e+01, +4.7568922e+00, -1.7013019e+02, -2.8253853e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.2779292e+00, -2.0965654e+02, -3.2575312e+01, -7.7555776e+00, +2.5900380e+02, 4.0242627e+01, 5.5241768e+00, -1.9034559e+02, -3.0493318e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 4.8170813e+00, -1.7186017e+02, +-2.8475776e+01, -5.9508870e+00, 2.1231123e+02, 3.5178174e+01, 7.1903322e+00, +-2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1204296e+02, -3.2880720e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, -1.9248909e+02, +-3.0764691e+01, -6.9182639e+00, 2.3779562e+02, 3.8005836e+01, 4.8873543e+00, +-1.7383837e+02, -2.8725374e+01, -6.0377003e+00, 2.1475504e+02, 3.5486521e+01, +7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.3618820e+00, -2.2459502e+02, -3.6852726e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1832144e+02, -3.4840055e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, -1.9801127e+02, +-3.2538994e+01, -6.9182639e+00, 2.4461757e+02, 4.0197760e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.2779292e+00, -2.1585184e+02, -3.4512289e+01, -7.7555776e+00, 2.6665731e+02, +4.2635513e+01, 5.5241768e+00, -1.9579250e+02, -3.2247525e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, +-2.2459502e+02, -3.6852726e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.1042831e+00, -2.3756088e+02, -3.6959139e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.5432465e+00, -1.9638280e+02, -3.2328552e+01, +-6.8479712e+00, 2.4260579e+02, 3.9937786e+01, 6.9164460e+00, -2.3208992e+02, +-3.6238511e+01, -8.5443832e+00, 2.8671738e+02, 4.4768040e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.3848450e+00, -1.9180933e+02, -3.1733570e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1042831e+00, -2.4457143e+02, -3.9153690e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.9588145e+00, +-2.3327526e+02, -3.6389185e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.1643997e+00, -2.1255901e+02, -3.4081082e+01, -7.6153263e+00, 2.6258944e+02, +4.2102813e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.8607153e+00, -2.3044873e+02, -3.6020404e+01, +-8.4755351e+00, 2.8468990e+02, 4.4498595e+01, 6.0753667e+00, -2.1001053e+02, +-3.3751631e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.8766090e+00, -2.6492238e+02, -4.1463390e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.3343210e+02, -3.7323176e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.1226462e+02, -3.4881232e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.7075935e+00, -2.2433958e+02, -3.4912636e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.9269319e+00, -2.0411252e+02, -3.2685368e+01, +-7.3219653e+00, 2.5215488e+02, 4.0378586e+01, 5.1959216e+00, -1.8481380e+02, +-3.0538976e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.2673222e+02, -3.5228440e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.0634493e+02, -3.2979210e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.2649152e+00, -1.8681595e+02, -3.0799524e+01, -6.5041284e+00, +2.3078718e+02, 3.8048868e+01, 6.6155691e+00, -2.2170260e+02, -3.4571242e+01, +-8.1726884e+00, 2.7388516e+02, 4.2708342e+01, 5.8435113e+00, -2.0173857e+02, +-3.2381037e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.1186804e+00, +-1.8262040e+02, -3.0258654e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.9124557e+00, -1.9706348e+02, -3.0557908e+01, -7.3040818e+00, 2.4344669e+02, +3.7750381e+01, 5.1792514e+00, -1.7846056e+02, -2.8589338e+01, -6.3983018e+00, +2.2046517e+02, 3.5318466e+01, 4.4939680e+00, -1.6072671e+02, -2.6692199e+01, +-5.5517219e+00, 1.9855727e+02, 3.2974793e+01, 6.6155691e+00, -2.2170260e+02, +-3.4571242e+01, -8.1726884e+00, 2.7388516e+02, 4.2708342e+01, 5.8435113e+00, +-2.0173857e+02, -3.2381037e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.1186804e+00, -1.8262040e+02, -3.0258654e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.5490076e+00, -2.5331631e+02, -3.9552799e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9397388e+00, -2.1042948e+02, +-3.4640919e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.2673222e+02, -3.5228440e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.0634493e+02, -3.2979210e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.2649152e+00, -1.8681595e+02, -3.0799524e+01, -6.5041284e+00, +2.3078718e+02, 3.8048868e+01, 6.7075935e+00, -2.2433958e+02, -3.4912636e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9269319e+00, -2.0411252e+02, +-3.2685368e+01, -7.3219653e+00, 2.5215488e+02, 4.0378586e+01, 5.1959216e+00, +-1.8481380e+02, -3.0538976e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.9124557e+00, -2.0872882e+02, -3.4249316e+01, +-7.3040818e+00, 2.5785773e+02, 4.2310644e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.3343210e+02, -3.7323176e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.1226462e+02, -3.4881232e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.5450076e+00, -2.2531786e+02, -3.6071366e+01, +-8.0855186e+00, 2.7835135e+02, 4.4561553e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.9124557e+00, -2.0872882e+02, -3.4249316e+01, -7.3040818e+00, +2.5785773e+02, 4.2310644e+01, 7.5490076e+00, -2.5331631e+02, -3.9552799e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9397388e+00, +-2.1042948e+02, -3.4640919e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.1874573e+00, -2.4174341e+02, -3.7835615e+01, -8.8791830e+00, 2.9864302e+02, +4.6741057e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.5450076e+00, +-2.2531786e+02, -3.6071366e+01, -8.0855186e+00, 2.7835135e+02, 4.4561553e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.1874573e+00, -2.4174341e+02, -3.7835615e+01, -8.8791830e+00, +2.9864302e+02, 4.6741057e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.2779292e+00, -2.1585184e+02, -3.4512289e+01, -7.7555776e+00, 2.6665731e+02, +4.2635513e+01, 5.5241768e+00, -1.9579250e+02, -3.2247525e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1832144e+02, +-3.4840055e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, +-1.9801127e+02, -3.2538994e+01, -6.9182639e+00, 2.4461757e+02, 4.0197760e+01, +7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1204296e+02, +-3.2880720e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, +-1.9248909e+02, -3.0764691e+01, -6.9182639e+00, 2.3779562e+02, 3.8005836e+01, +4.8873543e+00, -1.7383837e+02, -2.8725374e+01, -6.0377003e+00, 2.1475504e+02, +3.5486521e+01, 7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, +-3.2892355e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.9164460e+00, +-2.3208992e+02, -3.6238511e+01, -8.5443832e+00, 2.8671738e+02, 4.4768040e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.3848450e+00, -1.9180933e+02, -3.1733570e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.2779292e+00, -2.0965654e+02, -3.2575312e+01, +-7.7555776e+00, 2.5900380e+02, 4.0242627e+01, 5.5241768e+00, -1.9034559e+02, +-3.0493318e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 4.8170813e+00, +-1.7186017e+02, -2.8475776e+01, -5.9508870e+00, 2.1231123e+02, 3.5178174e+01, +6.2065976e+00, -2.0758346e+02, -3.2304982e+01, -7.6674565e+00, 2.5644278e+02, +3.9908667e+01, 5.4574857e+00, -1.8841160e+02, -3.0241928e+01, -6.7420246e+00, +2.3275841e+02, 3.7360029e+01, 4.7568922e+00, -1.7013019e+02, -2.8253853e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.8607153e+00, -2.3044873e+02, +-3.6020404e+01, -8.4755351e+00, 2.8468990e+02, 4.4498595e+01, 6.0753667e+00, +-2.1001053e+02, -3.3751631e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.1042831e+00, -2.3756088e+02, -3.6959139e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.5432465e+00, -1.9638280e+02, +-3.2328552e+01, -6.8479712e+00, 2.4260579e+02, 3.9937786e+01, 7.1903322e+00, +-2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.9588145e+00, -2.3327526e+02, -3.6389185e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.1643997e+00, -2.1255901e+02, +-3.4081082e+01, -7.6153263e+00, 2.6258944e+02, 4.2102813e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.2459502e+02, -3.6852726e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.1042831e+00, +-2.4457143e+02, -3.9153690e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.2459502e+02, +-3.6852726e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.8766090e+00, +-2.6492238e+02, -4.1463390e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9124557e+00, -2.0289842e+02, +-3.2378828e+01, -7.3040818e+00, 2.5065502e+02, 3.9999895e+01, 5.1792514e+00, +-1.8356736e+02, -3.0234014e+01, -6.3983018e+00, 2.2677397e+02, 3.7350252e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.7892413e+00, -2.3343210e+02, -3.7323176e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.0032591e+00, -2.1226462e+02, -3.4881232e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, -2.2673222e+02, +-3.5228440e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.0032591e+00, +-2.0634493e+02, -3.2979210e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.2649152e+00, -1.8681595e+02, -3.0799524e+01, -6.5041284e+00, 2.3078718e+02, +3.8048868e+01, 6.7075935e+00, -2.2433958e+02, -3.4912636e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.9269319e+00, -2.0411252e+02, -3.2685368e+01, +-7.3219653e+00, 2.5215488e+02, 4.0378586e+01, 5.1959216e+00, -1.8481380e+02, +-3.0538976e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.4840827e+00, +-2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.5450076e+00, -2.1885921e+02, -3.4049578e+01, +-8.0855186e+00, 2.7037252e+02, 4.2063893e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.0532039e+00, +-1.7999621e+02, -2.9779167e+01, -6.2425863e+00, 2.2236226e+02, 3.6788347e+01, +6.6155691e+00, -2.2170260e+02, -3.4571242e+01, -8.1726884e+00, 2.7388516e+02, +4.2708342e+01, 5.8435113e+00, -2.0173857e+02, -3.2381037e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.1186804e+00, -1.8262040e+02, -3.0258654e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.4187419e+00, -2.1517080e+02, +-3.3565025e+01, -7.9295336e+00, 2.6581596e+02, 4.1465290e+01, 5.6581569e+00, +-1.9558861e+02, -3.1433826e+01, -6.9899282e+00, 2.4162467e+02, 3.8832467e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.5490076e+00, -2.5331631e+02, -3.9552799e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9397388e+00, -2.1042948e+02, +-3.4640919e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.4840827e+00, +-2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.2779292e+00, +-2.1585184e+02, -3.4512289e+01, -7.7555776e+00, 2.6665731e+02, 4.2635513e+01, +5.5241768e+00, -1.9579250e+02, -3.2247525e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1832144e+02, -3.4840055e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, -1.9801127e+02, +-3.2538994e+01, -6.9182639e+00, 2.4461757e+02, 4.0197760e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.1042831e+00, -2.4457143e+02, -3.9153690e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1042831e+00, -2.3756088e+02, -3.6959139e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.5432465e+00, +-1.9638280e+02, -3.2328552e+01, -6.8479712e+00, 2.4260579e+02, 3.9937786e+01, +7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.9588145e+00, -2.3327526e+02, +-3.6389185e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.1643997e+00, +-2.1255901e+02, -3.4081082e+01, -7.6153263e+00, 2.6258944e+02, 4.2102813e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.9164460e+00, -2.3208992e+02, -3.6238511e+01, -8.5443832e+00, +2.8671738e+02, 4.4768040e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.3848450e+00, -1.9180933e+02, +-3.1733570e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.8607153e+00, +-2.3044873e+02, -3.6020404e+01, -8.4755351e+00, 2.8468990e+02, 4.4498595e+01, +6.0753667e+00, -2.1001053e+02, -3.3751631e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.8766090e+00, -2.6492238e+02, -4.1463390e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2841140e+05, -2.5682122e+05, -1.2810668e+03, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 3.2153807e+04, -9.6459448e+04, +-9.6079874e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.5450076e+00, -2.2531786e+02, -3.6071366e+01, +-8.0855186e+00, 2.7835135e+02, 4.4561553e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.7892413e+00, -2.3343210e+02, -3.7323176e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.0032591e+00, -2.1226462e+02, -3.4881232e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9124557e+00, +-2.0872882e+02, -3.4249316e+01, -7.3040818e+00, 2.5785773e+02, 4.2310644e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.2841140e+05, -3.8522632e+05, -3.8371043e+03, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.5490076e+00, -2.5331631e+02, +-3.9552799e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.9397388e+00, -2.1042948e+02, -3.4640919e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.4840827e+00, -2.5138740e+02, -3.9293232e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.6599679e+00, -2.2964705e+02, -3.6820928e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.1874573e+00, +-2.4174341e+02, -3.7835615e+01, -8.8791830e+00, 2.9864302e+02, 4.6741057e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.0832974e+04, -1.0166532e+05, -5.0712347e+02, +-6.2797629e+04, 1.2559449e+05, 6.2648610e+02, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2728415e+04, -3.8184464e+04, -3.8034206e+02, -1.5724327e+04, 4.7172015e+04, +4.6986391e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.0832974e+04, +-1.5249580e+05, -1.5189572e+03, -6.2797629e+04, 1.8838903e+05, 1.8764771e+03, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1042831e+00, -2.4457143e+02, -3.9153690e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3618820e+00, -2.2459502e+02, -3.6852726e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.8766090e+00, -2.6492238e+02, -4.1463390e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2841140e+05, -2.5682122e+05, -1.2810668e+03, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 3.2153807e+04, -9.6459448e+04, +-9.6079874e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.2841140e+05, -3.8522632e+05, -3.8371043e+03, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00 }; + + +const float MPT_G[] = { +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-1.6381611e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -1.6130791e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +1.2841142e+09, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -5.3227337e+00, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.6017534e-02, -3.0000000e+01, -5.1591655e-02, +-3.0000000e+01, -3.4960128e+00, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-3.1202736e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 1.9308683e-01, -2.3853405e-01, -3.3663248e+00, 3.0000000e+01, +-3.1942680e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 4.2564978e-01, -5.2583579e-01, 3.0000000e+01, -3.0000000e+01, +3.2153809e+08, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 5.0832984e+08, -6.2797642e+08, +3.0000000e+01, -3.0000000e+01, -6.9817364e+00, 8.6250411e+00, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 1.2841141e+09, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -1.7181011e+00, +3.0000000e+01, -1.6364983e+00, -3.0000000e+01, -1.5485846e+00, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 1.7955880e+00, -2.2182191e+00, 1.6645618e+00, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 1.6963948e+00, -3.0000000e+01, +1.5825300e+00, -1.9550131e+00, -5.2379373e+00, 6.4708007e+00, 3.0000000e+01, +-3.0000000e+01, -4.6483190e+00, -3.0000000e+01, -1.4441660e+00, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, -1.2909582e+00, 1.5948135e+00, -5.1086242e+00, +6.3110510e+00, -4.8282165e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-1.1991136e+00, 3.0000000e+01, -1.1495962e+00, 1.4201789e+00, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 2.5371228e+00, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 1.2728415e+08, -1.5724326e+08, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +1.2841143e+09, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -9.9795922e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +5.0832974e+08, -6.2797629e+08, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.5219333e+00, 4.3508976e+00, -3.3275489e+00, -3.0000000e+01, +-3.1302912e+00, -3.0000000e+01, 2.4245252e-01, 3.0000000e+01, 2.1305034e-01, +-2.6319640e-01, 1.8456136e-01, -3.0000000e+01, 1.2467036e-01, 3.0000000e+01, +1.0514253e-01, -3.0000000e+01, 9.5068259e-02, -1.1744466e-01, -3.0000000e+01, +3.0000000e+01, 3.9196804e+00, 3.0000000e+01, 3.6547656e+00, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 3.2920777e+00, -4.0669404e+00, 3.0769136e+00, +-3.8011327e+00, -7.9379602e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-7.0168247e+00, -3.0000000e+01, -3.2422172e+00, 4.0053442e+00, 3.0000000e+01, +-3.0000000e+01, -2.8664279e+00, 3.5411046e+00, -7.7792671e+00, -3.0000000e+01, +-7.3327762e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -2.9907429e+00, +3.6946798e+00, -2.8289988e+00, 3.4948657e+00, 3.0000000e+01, -3.0000000e+01, +7.7218343e-01, 3.0000000e+01, 7.1023890e-01, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.2153802e+08, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 1.2841140e+09, -3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-5.9377393e+00, -3.0000000e+01, -5.5923108e+00, -3.0000000e+01, -5.2486125e+00, +-3.0000000e+01, -1.5894631e+00, 1.9635780e+00, -1.5035024e+00, 1.8573847e+00, +-1.4207708e+00, -3.0000000e+01, -1.7136118e+00, 2.1169480e+00, -1.6172667e+00, +-3.0000000e+01, -1.5149956e+00, 1.8715830e+00, 2.2377114e+00, 3.0000000e+01, +2.0953391e+00, 3.0000000e+01, 1.9483870e+00, -3.0000000e+01, 1.8459251e+00, +3.0000000e+01, 1.7287396e+00, -2.1356364e+00, 1.6157524e+00, -1.9960552e+00, +1.9819268e+00, 3.0000000e+01, 1.8604734e+00, -3.0000000e+01, 1.7516409e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +5.4464788e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 5.3882451e+00, +3.0000000e+01, 5.0400093e+00, -6.2262860e+00, -3.0000000e+01, 3.0000000e+01, +5.2228117e+00, -6.4521150e+00, 4.8990951e+00, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -9.1383290e+00, -3.0000000e+01, +-5.5943680e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -4.9274050e+00, +6.0871778e+00, -1.6678938e+00, 2.0604692e+00, 3.0000000e+01, -3.0000000e+01, +-1.4607834e+00, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -9.5756569e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -5.2856540e+00, -3.0000000e+01, +-4.9801580e+00, 6.1523474e+00, 3.0000000e+01, -3.0000000e+01, -1.3148224e+00, +1.6242947e+00, -1.2469793e+00, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +2.5821883e+00, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -7.6260377e+00, -3.0000000e+01, +-7.1508378e+00, -3.0000000e+01, -3.6779812e+00, -3.0000000e+01, -3.4604985e+00, +4.2750027e+00, -3.2509673e+00, -3.0000000e+01, -3.8310276e+00, -3.0000000e+01, +-3.6012147e+00, -3.0000000e+01, -3.3695393e+00, 4.1626342e+00, 1.1766914e-01, +-1.4536516e-01, 1.0784894e-01, 3.0000000e+01, 8.9408793e-02, -3.0000000e+01, +-3.5527137e-15, 0.0000000e+00, 7.1054274e-15, 0.0000000e+00, -3.5527137e-15, +0.0000000e+00, -1.1766914e-01, 1.4536516e-01, -1.0784894e-01, -3.0000000e+01, +-8.9408793e-02, 3.0000000e+01, 4.0414091e+00, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.5428710e+00, -3.0000000e+01, 3.8310276e+00, 3.0000000e+01, +3.6012147e+00, 3.0000000e+01, 3.3695393e+00, -4.1626342e+00, 3.6779812e+00, +3.0000000e+01, 3.4604985e+00, -4.2750027e+00, 3.2509673e+00, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 6.7772422e+00, +-8.3724148e+00, -3.0000000e+01, 3.0000000e+01, 7.6260377e+00, 3.0000000e+01, +7.1508378e+00, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 6.9100842e+00, +-8.5365241e+00, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, -3.0000000e+01, -6.7772422e+00, 8.3724148e+00, -4.0414091e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.5428710e+00, 3.0000000e+01, +-2.3155684e-01, 2.8605882e-01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -6.9100842e+00, 8.5365241e+00, +3.0000000e+01, -3.0000000e+01, 2.3155684e-01, -2.8605882e-01, -3.0000000e+01, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-5.2228117e+00, 6.4521150e+00, -4.8990951e+00, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -5.3882451e+00, -3.0000000e+01, -5.0400093e+00, 6.2262860e+00, +-1.9819268e+00, -3.0000000e+01, -1.8604734e+00, 3.0000000e+01, -1.7516409e+00, +-3.0000000e+01, -1.8459251e+00, -3.0000000e+01, -1.7287396e+00, 2.1356364e+00, +-1.6157524e+00, 1.9960552e+00, -2.2377114e+00, -3.0000000e+01, -2.0953391e+00, +-3.0000000e+01, -1.9483870e+00, 3.0000000e+01, 1.6678938e+00, -2.0604692e+00, +-3.0000000e+01, 3.0000000e+01, 1.4607834e+00, -3.0000000e+01, 1.7136118e+00, +-2.1169480e+00, 1.6172667e+00, 3.0000000e+01, 1.5149956e+00, -1.8715830e+00, +1.5894631e+00, -1.9635780e+00, 1.5035024e+00, -1.8573847e+00, 1.4207708e+00, +3.0000000e+01, 1.3148224e+00, -1.6242947e+00, 1.2469793e+00, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 5.5943680e+00, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 4.9274050e+00, -6.0871778e+00, 5.9377393e+00, 3.0000000e+01, +5.5923108e+00, 3.0000000e+01, 5.2486125e+00, 3.0000000e+01, 5.2856540e+00, +3.0000000e+01, 4.9801580e+00, -6.1523474e+00, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 9.1383290e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 9.5756569e+00, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -5.4464788e+00, 3.0000000e+01, -2.5821883e+00, -3.0000000e+01, +3.0000000e+01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.2920777e+00, 4.0669404e+00, -3.0769136e+00, 3.8011327e+00, +3.0000000e+01, -3.0000000e+01, -3.9196804e+00, -3.0000000e+01, -3.6547656e+00, +3.0000000e+01, -1.2467036e-01, -3.0000000e+01, -1.0514253e-01, 3.0000000e+01, +-9.5068259e-02, 1.1744466e-01, -2.4245252e-01, -3.0000000e+01, -2.1305034e-01, +2.6319640e-01, -1.8456136e-01, 3.0000000e+01, -7.7218343e-01, -3.0000000e+01, +-7.1023890e-01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.2422172e+00, +-4.0053442e+00, -3.0000000e+01, 3.0000000e+01, 2.8664279e+00, -3.5411046e+00, +3.5219333e+00, -4.3508976e+00, 3.3275489e+00, 3.0000000e+01, 3.1302912e+00, +3.0000000e+01, 2.9907429e+00, -3.6946798e+00, 2.8289988e+00, -3.4948657e+00, +-3.0000000e+01, 3.0000000e+01, 7.9379602e+00, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 7.0168247e+00, 3.0000000e+01, 7.7792671e+00, 3.0000000e+01, +7.3327762e+00, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -1.7955880e+00, 2.2182191e+00, +-1.6645618e+00, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -1.6963948e+00, +3.0000000e+01, -1.5825300e+00, 1.9550131e+00, 3.0000000e+01, -3.0000000e+01, +-2.5371228e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 1.4441660e+00, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 1.2909582e+00, -1.5948135e+00, +1.7181011e+00, -3.0000000e+01, 1.6364983e+00, 3.0000000e+01, 1.5485846e+00, +3.0000000e+01, 1.1991136e+00, -3.0000000e+01, 1.1495962e+00, -1.4201789e+00, +-3.0000000e+01, 3.0000000e+01, 5.2379373e+00, -6.4708007e+00, -3.0000000e+01, +3.0000000e+01, 4.6483190e+00, 3.0000000e+01, 5.1086242e+00, -6.3110510e+00, +4.8282165e+00, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 9.9795922e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-1.2841140e+09, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, -3.2153802e+08, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -4.2564978e-01, +5.2583579e-01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.6017534e-02, 3.0000000e+01, 5.1591655e-02, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -1.9308683e-01, 2.3853405e-01, +3.0000000e+01, -3.0000000e+01, -1.2841143e+09, -3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.4960128e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +3.1202736e+00, 3.0000000e+01, 3.3663248e+00, -3.0000000e+01, 3.1942680e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 6.9817364e+00, -8.6250411e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -5.0832974e+08, +6.2797629e+08, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-1.2728415e+08, 1.5724326e+08, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -5.0832984e+08, 6.2797642e+08, +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 1.6130791e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 1.6381611e+00, 3.0000000e+01, 5.3227337e+00, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-1.2841141e+09, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, -3.2153809e+08, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -1.2841142e+09, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01 }; + diff --git a/examples/BicopShield/BicopShield_LQ/BicopShield_LQ.ino b/examples/BicopShield/BicopShield_LQ/BicopShield_LQ.ino new file mode 100644 index 00000000..a101a582 --- /dev/null +++ b/examples/BicopShield/BicopShield_LQ/BicopShield_LQ.ino @@ -0,0 +1,125 @@ + +/* + BicopShield LQI control example. + + + The following code is an example of BicopShield API in use with + two modes of reference value setting. + + This code is part of the AutomationShield hardware and software + ecosystem. Visit http://www.automationshield.com for more + details. This code is licensed under a Creative Commons + Attribution-NonCommercial 4.0 International License. + + Created by Martin Nemček, Ján Boldocký. + Last update: 30.4.2024 +*/ +#include //--Include API +#include + + +#define TS 10.0 //--Defining Sample period in milliseconds +#define AUTO 1 //--Defining reference Mode # MANUAL / AUTO +#define USE_KALMAN 0 // Use kalman filter for state estimation + +float r = 0.0; //--Reference + +float R[]={0.8,1.0,0.35,1.3,1.0,0.35,0.8,1.2,0.0}; //--Input trajectory +//float R[]={0.8,0.8,0.8,0.8,0.8,0.8,0.8,0.8,0.8}; //--Input trajectory +float y = 0.0; //--Output +float u1 = 0.0; //--Input +float u2 = 0.0; //--Input +float yprev = 0; + +bool realTimeViolation = false; +bool nextStep = false; +unsigned int k = 0; //--Sample index +int T = 1000; //--Section length +int i = 0; //--Section counter +float BaseU = 50.0; //--Base setpoint of motor inputs +float y_out = 0.0; +float counter =0.0; + + +BLA::Matrix<3, 1> X = {0, 0, 0}; //--Estimated state vector +BLA::Matrix<2, 3> K = {47.01, 15.25, -67.85, -58.08, -18.84, 83.83}; //--LQ gain with integrator, see MATLAB example +//BLA::Matrix<2, 3> K = {100.65, 21.78, -161.71, -124.34, -26.91, 199.77}; //--LQ gain with integrator, see MATLAB example +BLA::Matrix<3, 1> Xr = {0, 0, 0}; //--Initial state reference +BLA::Matrix<2, 1> U = {0, 0}; + +void setup() { + Serial.begin(115200); //--Initialize serial communication # 2 Mbaud + BicopShield.begin(); //--Initialize MotoShield + delay(1000); + BicopShield.calibrate(); // Calibrate BicopShield board + store the 0° value of the pendulum + Serial.println("r, y, u"); //--Print header + Sampling.period(TS*1000.0); + Sampling.interrupt(stepEnable); + //delay(1000); +} + +void loop(){ + if (y > M_PI) { // If pendulum agle too big + BicopShield.actuatorWrite(0.0,0.0); // Turn off motor + while (1); // Stop program + } + if (nextStep) { //--Running the algorithm once every sample + step(); + + nextStep = false; //--Setting the flag to false # built-in ISR sets flag to true at the end of each sample + } +} + +void stepEnable() { // ISR + if(nextStep) { // If previous sample still running + realTimeViolation = true; // Real-time has been violated + Serial.println("Real-time samples violated."); // Print error message + BicopShield.actuatorWrite(0.0,0.0); // Turn off the fan + while(1); // Stop program execution + } + nextStep = true; // Enable step flag +} + + +void step(){ //--Algorithm ran once per sample + #if !AUTO + r = AutomationShield.mapFloat(BicopShield.referenceRead(),0,100,0,M_PI_2); //--Sensing Pot reference + #elif AUTO + if(i >= sizeof(R)/sizeof(float)){ //--If trajectory ended + BicopShield.actuatorWrite(0.0,0.0); //--Stop the Motor + while(true); //--End of program execution + } + if (k % (T*i) == 0){ //--Moving through trajectory values + //r = R[i]; + Xr(0) = R[i]; + i++; //--Change input value after defined amount of samples + } + k++; //--Increment + #endif + +BLA::Matrix<2,1> U = -(K*(X-Xr)); // LQ computation + +u1=U(0); +u2=U(1); +u1=constrain(u1,-30.0,30.0); // Saturation +u2=constrain(u2,-30.0,30.0); +u1=BaseU+u1; // Final Values +u2=BaseU+u2; +y = BicopShield.sensorReadRadian(); // Angle in radians + +BicopShield.actuatorWrite(u1,u2); +X(0) = y; +X(1) = (y-yprev)/(TS/1000.0); + +X(2) = X(2) + 0.01*(Xr(0) - X(0)); // Integracna zlozka +yprev=y; +y_out=BicopShield.sensorRead(); + + Serial.print(Xr(0),3); //--Printing reference + Serial.print(", "); + Serial.print(y,3); //--Printing output + Serial.print(", "); + Serial.print(u1,3); // Printing motor1 input + Serial.print(", "); + Serial.println(u2,3); // Printing motor2 input +} diff --git a/examples/BicopShield/BicopShield_PID/BicopShield_PID.ino b/examples/BicopShield/BicopShield_PID/BicopShield_PID.ino new file mode 100644 index 00000000..bc8fd375 --- /dev/null +++ b/examples/BicopShield/BicopShield_PID/BicopShield_PID.ino @@ -0,0 +1,78 @@ +/* + BicopShield PID control example. + The following code is an example of BicopShield API in use with + two modes of reference value setting. + + This code is part of the AutomationShield hardware and software + ecosystem. Visit http://www.automationshield.com for more + details. This code is licensed under a Creative Commons + Attribution-NonCommercial 4.0 International License. + + Created by Martin Nemček. + Last update: 30.4.2024 +*/ + + +#include "BicopShield.h" // Include BicopShield header +#include // Include Sampling header +#define MANUAL 0 + +#define KP 1.5 // PID Kp constant +#define TI 2.0 // PID Ti constant +#define TD 0.5 // PID Td constant + + +const float Ts=10; // Sampling period +float R1[]={45.0, 55.0, 20.0, 65.0, 55.0, 20.0, 45.0, 70.0, 10.0, 50.0}; // Reference matrix +unsigned long k = 0; // Cycle counter +unsigned long i; // Counter for going through trajectory values +float u; // Variable for PID output (system input) +float BaseU=50.0; // Base input for both motors +float u1=0.0; // Input value 1 +float u2=0.0; // Input value 2 +float e; // Error +float y; // Output +float r; // Variable for actual value of reference + + +void setup() { +Serial.begin(115200); // Serial initialization +BicopShield.begin(); // BicopShield initialization +delay(1000); +BicopShield.calibrate(); // Sensor calibration +Sampling.period(Ts * 1000); // Set sampling period (need to be in microseconds) + PIDAbs.setKp(KP); // Set Proportional constant + PIDAbs.setTi(TI); // Set Integral constant + PIDAbs.setTd(TD); // Set Derivative constant + PIDAbs.setTs(Sampling.samplingPeriod); // Set sampling period for PID + Serial.print('y, r, u1, u2, u'); +} + +void loop() { + if (k % 2000 == 0){ // Moving through trajectory values + r= R1[i]; // Choosing reference point + i++;} // Change reference value after defined amount of samples + k++; // Add 1 to cycle counter + +y=BicopShield.sensorRead(); // Read actual angle value +u=PIDAbs.compute(r-y,-(100-BaseU),(100-BaseU),-100,100); //PID computing + if(i>12){ // Set i> count of reference points in R1 matrix + u1=0; // Turn off motor1 + u2=0; // Turn off motor2 + BicopShield.actuatorWrite(u1,u2); // Write turn off values + while(1){} // Stop executing program + } + u1=BaseU+(u/2); // Compute final motor1 value + u2=BaseU-(u/2); // Compute final motor2 value +BicopShield.actuatorWrite(u1,u2); // Write computed values on motors + +Serial.print(y); // Print actual angle +Serial.print(", "); +Serial.print(r); // Print reference +Serial.print(", "); +Serial.print(u1); // Print value for motor1 +Serial.print(", "); +Serial.print(u2); // Print value for motor2 +Serial.print(", "); +Serial.println(u); // Print computed PID value +} diff --git a/examples/BicopShield/BicopShield_TOF_PID/BicopShield_TOF_PID.ino b/examples/BicopShield/BicopShield_TOF_PID/BicopShield_TOF_PID.ino new file mode 100644 index 00000000..f11c4c23 --- /dev/null +++ b/examples/BicopShield/BicopShield_TOF_PID/BicopShield_TOF_PID.ino @@ -0,0 +1,97 @@ +/* + BicopShield PID control example with BoB module. + The following code is an example of BicopShield API in use with + Ball-on-Beam module. + + This code is part of the AutomationShield hardware and software + ecosystem. Visit http://www.automationshield.com for more + details. This code is licensed under a Creative Commons + Attribution-NonCommercial 4.0 International License. + + Created by Martin Nemček, Ján Boldocký. + Last update: 30.4.2024 +*/ + +#include "BicopShield.h" // Include BicopShield header +#include // Include Sampling header +#define MANUAL 0 +//Parameters for primary PID controller +#define KP 1.0 // PID Kp constant +#define TI 0.001 // PID Ti constant +#define TD 0.001 // PID Td constant +//Parameters for secondary PID controller +#define KP2 2.5 // PID Kp constant +#define TI2 2.5 // PID Ti constant +#define TD2 0.5 // PID Td constant + + + +const float Ts=10; // Sampling period +//float R1[]={45.0, 55.0, 30.0, 45.0, 35.0}; // Reference matrix +float R_TOF=40.0; +unsigned long k = 0; // Cycle counter +unsigned long i; // Counter for going through trajectory values +float u; // Variable for PID output (system input) +float U; // Variable for PID output (system input) +float BaseU=50.0; // Base input for both motors +float u1=0.0; // Input value 1 +float u2=0.0; // Input value 2 +float e; // Error +float y; // Output +float r; // Variable for actual value of reference +float TOF; + +PIDAbsClass PIDAbs2; + + +void setup() { + // put your setup code here, to run once: +Serial.begin(115200); // Serial initialization +BicopShield.begin(); // BicopShield initialization +delay(1000); +BicopShield.TOFinitialize(); +BicopShield.TOFcalibration(); +delay(1000); +BicopShield.calibrate(); // Sensor calibration +delay(1000); + +Sampling.period(Ts * 1000); // Set sampling period (need to be in microseconds) + PIDAbs.setKp(KP); // Set Proportional constant + PIDAbs.setTi(TI); // Set Integral constant + PIDAbs.setTd(TD); // Set Derivative constant + PIDAbs.setTs(Sampling.samplingPeriod); // Set sampling period for PID + PIDAbs2.setKp(KP2); // Set Proportional constant 2 + PIDAbs2.setTi(TI2); // Set Integral constant 2 + PIDAbs2.setTd(TD2); // Set derivative constat 2 + PIDAbs2.setTs(Sampling.samplingPeriod); // Set sampling period for PID 2 + Serial.print('y, r, u1, u2, u'); +} + +void loop() { +// put your main code here, to run repeatedly: +//if (k % 5000 == 0){ // Moving through trajectory values + //r= R1[i]; // Choosing reference point + // i++;} // Change reference value after defined amount of samples + //k++; // Add 1 to cycle counter +TOF=BicopShield.TOFsensorRead(); +y=BicopShield.sensorRead(); // Read actual angle value + +U=PIDAbs.compute(R_TOF-TOF,0,80,-60,60); //PID computing +U=map(U,0,80,50,35); +u=PIDAbs2.compute(U-y,-(60),60,-100,100); //PID computing + u1=BaseU+(u/2); // Compute final motor1 value + u2=BaseU-(u/2); // Compute final motor2 value +BicopShield.actuatorWrite(u1,u2); // Write computed values on motors + + + +Serial.print(y); // Print actual angle +Serial.print(", "); +Serial.print(U); // Print reference +Serial.print(", "); +Serial.print(u1); // Print value for motor1 +Serial.print(", "); +Serial.print(u2); // Print value for motor2 +Serial.print(", "); +Serial.println(TOF); // Print computed PID value +} diff --git a/matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC_Export.m b/matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC_Export.m new file mode 100644 index 00000000..7ea7f654 --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC_Export.m @@ -0,0 +1,51 @@ +clear all; close all; clc; +%% +load BicopShield_GreyboxModel_LinearSS.mat % Include linearized state-space model + +Ts=0.01; % [s] Sampling for discrete control +N=5; % [steps] Prediction horizon +ul=[-30;-30]; % [V] Adjust lower input constraint +uh=[30;30]; % [V] Adjust upper input constraint + + +%% Model discretization +modeld=c2d(model,Ts); % Discretized linear state-space model +A=modeld.a; % Extract A +B=modeld.b; % Extract B +C=[1 0]; % C for introducing an integration component + +%% Model augmentation by the integrator +[ny, ~]=size(C); % Sizing C +[nx, nu]=size(B); % Sizing B +Ai=[eye(ny,ny) -C; % Augmenting A by an integrator + zeros(nx,ny) A]; +Bi=[zeros(ny,nu); B]; % Augmenting B by the integrator +Ci=[zeros(ny,ny) C]; % Augmenting C by the integrator + +%% MPC Penalty +Qmpc=diag([1 10 1]); % State penalty matrix +Rmpc=diag([1e-2, 1e-2]); % Input penalty matrix + +%% Model and EMPC controller using the MPT 3.0 +model = LTISystem('A', Ai, 'B', Bi, 'C', Ci, 'Ts', Ts); % LTI model by the MPT 3.0 +model.u.min = [ul]; % [V] Lower input constraint for the MPT +model.u.max = [uh]; % [V] Upper input constraint for the MPT +model.x.penalty = QuadFunction(Qmpc); % State penalty for the MPT +model.u.penalty = QuadFunction(Rmpc); % Input penalty for the MPT +PA = model.LQRPenalty; % Compute LQ penalty by the MPT +model.x.with('terminalPenalty'); % Enable terminal penalty in the MPT +model.x.terminalPenalty = PA; % Define for the MPT + +%% Compute controller +ctrl = MPCController(model, N) % Create an MPC controller by the MPT +ectrl = ctrl.toExplicit(); % Transform it to EMPC by the MPT + +%% Export controller +ectrl.exportToC('ectrl','empc') % Export to Simulink mex function + cd empc; + mex ectrl_sfunc.c; + +empcToC(ectrl,'AVR'); % Export to code, for ARM MCU use 'generic', for AVR use 'AVR' +empcToPython(ectrl); % Export to code suitable for Python + +empcMemory(ectrl,'float') % This many bytes for the optimizer matrices \ No newline at end of file diff --git a/matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC_Simulation.m b/matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC_Simulation.m new file mode 100644 index 00000000..6f6dbb60 --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC_Simulation.m @@ -0,0 +1,175 @@ +clear all; close all; clc; +%% + +load BicopShield_GreyboxModel_LinearSS.mat % Include linearized state-space model + + +filter = 'model'; % Select state estimation method: 'Kalman', 'model', 'difference' +exportempc = 1; % Would you like to export this controller right away? + + +Ts=0.01; % [s] sampling for discrete control +N=3; % [steps] prediction horizon +ul=[-30; -30] % [V] Adjust lower input constraint for linearization +uh=[30; 30] % [V] Adjust upper input constraint for linearization + +R=[0.8,1.0,0.35,1.3,1.0,0.35,0.8,1.2]'; % [rad] Reference levels for the simulation +T=1000; % [samples] Section length for each reference level + +t=0:Ts:(T*length(R)-1)*Ts; % [s] Time vector for the simulation +i=1; % [-] Section counter for the simulation +r=R(1); % [mm] First reference to start simulation + +%% Discretization +modeld=c2d(model,Ts); % Discretized linear state-space model +A=modeld.a; % Extract A +B=modeld.b; % Extract B +C=[1 0]; % C for introducing an integration component + +Q_Kalman = diag([0.01, 10]); % Process noise covariance matrix +R_Kalman = diag([1e0]); % Measurement noise covariance matrix + + +%% Model augmentation by integration +[ny, ~]=size(C); % Sizing C +[nx, nu]=size(B); % Sizing B +Ai=[eye(ny,ny) -C; % Augmenting A by an integrator + zeros(nx,ny) A]; +Bi=[zeros(ny,nu); B]; % Augmenting B by the integrator +Ci=[zeros(ny,ny) C]; % Augmenting C by the integrator + +%% MPC penalty +Qmpc=diag([1 10 1]); % State penalty matrix +Rmpc=diag([1e-2, 1e-2]); % Input penalty matrix + +%% Model and EMPC controller using the MPT 3.0 +modelEMPC = LTISystem('A', Ai, 'B', Bi, 'C', Ci, 'Ts', Ts); % LTI model by the MPT 3.0 +modelEMPC.u.min = ul; % [V] Lower input constraint for the MPT +modelEMPC.u.max = uh; % [V] Upper input constraint for the MPT +modelEMPC.x.penalty = QuadFunction(Qmpc); % State penalty for the MPT +modelEMPC.u.penalty = QuadFunction(Rmpc); % Input penalty for the MPT +PA = modelEMPC.LQRPenalty; % Compute LQ penalty by the MPT +modelEMPC.x.with('terminalPenalty'); % Enable terminal penalty in the MPT +modelEMPC.x.terminalPenalty = PA; % Define for the MPT +% Compute controller +ctrl = MPCController(modelEMPC, N) % Create an MPC controller by the MPT +ectrl = ctrl.toExplicit(); % Transform it to EMPC by the MPT + +%% Simulation +U=[0;0] +x0=[0 0]'; % Initial condition +X=x0; % State logging (initialization) +xI=0; % Integrator initialization +y=[0]'; % Output logging (initialization) +Xhat=[0;0]; +x1p=0; % Previous state +xICWhole = [0;0]; % Initial conditions for Kalman filter + +xhat = zeros(2,1); % States estimated by Kalman filter +yhat = zeros(1,1); % Outputs estimated by Kalman filter +Y = zeros(1,1); +%kalmanrychlost=zeros(1,length(measuredOutput)); +disp('Simulating...') +for k=1:length(t)-1 + Rr(k)=R(i); % Original reference, just for logging + % Experiment (simulation) profile + if (mod(k,(T*i)) == 0) % At each section change + i = i + 1; % we move to the next index + r = R(i); % and use the actual reference + end + + % Measurement, primitively reconstructing system states from "measurements" + x1=X(1,k); + x2=X(2,k); + Y(1,1) = x1; % Y is used to pass variable x1 to estimateKalmanState function + + +%State estimation based on user option +if strcmp(filter,'Kalman') + % Ukal(:,k)=inputFull(k,:); + % Y=measuredOutput(k); + [xhat, yhat] = estimateKalmanState(U(:,k), Y, A, B, C, Q_Kalman, R_Kalman, xICWhole); + kalmanrychlost(k)=yhat(1,1); +elseif strcmp(filter,'model') + xhat = [X(1,k); X(2,k)]; +elseif strcmp(filter,'difference') + x2 = (x1 - x1p)/Ts; + x1p=x1; + xhat = [x1; x2]; +end + % Control + xI(k+1)=xI(k)+(r-x1); % Integrator state + U(:,k+1)=ectrl.evaluate([xI(k); xhat]); % EMPC compensated by the linearization point + + % Model + X(:,k+1)=A*X(:,k)+B*(U(:,k+1)); % System model +% X(1,k+1)=constrain(X(1,k+1),-pi,pi); % angle limits + y(1,k+1)=X(1,k); % Position measurement on the real system + Xhat(:,k+1)=xhat; % Estimated state vector for logging +end +disp('...done.') + +%% Plotting + +figure(1); % New figure + +subplot(2,1,1) % Top subplot +plot(t(1:end-1),Rr); % Plot reference +hold on % Draw on top of this +plot(t(1:end-1),y(1,1:end-1),'LineWidth',1.5); % Plot the output (position) +grid on % Grid is enabled +xlabel('Time [s]') % X axis label +ylabel('Angle [rad]') % Y axis label +legend('Reference','Measured angle') +title('Simulation - EMPC') + +subplot(2,1,2) % Bottom subplot +plot(t(1:end),U,'LineWidth',1.5); % Plot inputs +grid on % Allow grid +xlabel('Time [s]') % X axis label +ylabel('Input [%]') % Y axis label +legend('Input motor 1','Input motor 2') + +% if kalman filter is used print comparison between system state and estimated state +if strcmp(filter,'Kalman') + figure(2); + + subplot(2,1,1) % Top subplot + plot(t,X(1,:),'LineWidth',1.5); % Plot reference + hold on % Draw on top of this + plot(t,Xhat(1,:),'LineWidth',1.5); % Plot the output (position) + hold off + grid on % Grid is enabled + xlabel('Time [s]') % X axis label + ylabel('Anlge [rad]') % Y axis label + legend('State 1 - Kalman filter','State 1 - sim without filter') + + subplot(2,1,2) % Bottom subplot + plot(t,X(2,:),'LineWidth',1.5); % Plot reference + hold on % Draw on top of this + plot(t,Xhat(2,:),'LineWidth',1.5); % Plot the output (position) + hold off + grid on % Grid is enabled + legend('State 2 with Kalman filter','State 2 - without Kalman filter') + xlabel('Time [s]') % X axis label + ylabel('Angular speed [rad/s]') % Y axis label + + +% % Print matrices in specific format to be used in Arduino example + disp(' ') + disp('Discrete SS Matrices: ') + printSSMatrix(A, 'A') + printSSMatrix(B, 'B') + printSSMatrix(C, 'C') + printSSMatrix(Q_Kalman, 'Q_Kalman') + printSSMatrix(R_Kalman, 'R_Kalman') +end + +%% export controller files for usage in arduino example and Python +if exportempc + ectrl.exportToC('ectrl','cmpc') % Export to C + empcToC(ectrl,'generic'); % Export to code, for ARM MCU use 'generic', for AVR use 'AVR' + % empcToPython(ectrl); % Export to code suitable for Python +end + + diff --git a/matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_GreyboxModel_LinearSS.mat b/matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_GreyboxModel_LinearSS.mat new file mode 100644 index 00000000..6e330b26 Binary files /dev/null and b/matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_GreyboxModel_LinearSS.mat differ diff --git a/matlab/examples/BicopShield/BicopShield_EMPC/ectrl.h b/matlab/examples/BicopShield/BicopShield_EMPC/ectrl.h new file mode 100644 index 00000000..0130b96b --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_EMPC/ectrl.h @@ -0,0 +1,98 @@ +/* + MATRICES FOR EXPLICIT MPC POLYTOPES AND CORRESPONDING PWA LAWS + + The automatically generated set of matrices have been adapted from + the C code auto-generation routine of the Multi-Parametric Toolbox 3 + MPT3) of Kvasnica et al. for MATLAB. Please see http://www.mpt3.org + for more information. Please see the original "toC.m" for more details + in the MPT3. + + The following C code has been slightly adapted to perform microcontroller + architecutre-specific changes for AVR and ARM Cortex-A devices. + + The list of changes from the original are as follows: + - Changed "static" modifiers to "const" so microcontrollers will + prefer to use ROM instead of RAM. + - Added PROGMEM functionality for the AVR architecture, and calling + the necessary headers. + - Removed the possibility to use PWQ, this only handles PWA. + - Removed matrix export for the tie-breaking function. + + Usage: include alongside with the empcSequential.h header to your + example. + + This code snippet has been altered for the needs of the + the AutomationShield hardware and software ecosystem. + Visit http://www.automationshield.com for more details. + + + Copyright (C) 2005 by Michal Kvasnica (michal.kvasnica@stuba.sk) + Revised in 2012-2013 by Martin Herceg (herceg@control.ee.ethz.ch) + Adapted for MCU use by Gergely Tak�cs in 2020 (gergely.takacs@stuba.sk) +*/ +#include + +#define MPT_NR 5 +#define MPT_DOMAIN 3 +#define MPT_RANGE 2 +#define MPT_ABSTOL 1.000000e-08 + +const float MPT_A[] PROGMEM = { +2.9635436e-02, -9.8775575e-01, -1.5316764e-01, -7.0710678e-01, 7.0710678e-01, +0.0000000e+00, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, 2.9635436e-02, -9.8775575e-01, -1.5316764e-01, +-2.9635436e-02, 9.8775575e-01, 1.5316764e-01, 2.9635436e-02, -9.8775575e-01, +-1.5316764e-01, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, 0.0000000e+00, -9.9995024e-01, +-9.9758962e-03, 0.0000000e+00, -1.0000000e+00, 0.0000000e+00, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, +0.0000000e+00, 9.9995024e-01, 9.9758962e-03, 0.0000000e+00, 1.0000000e+00, +0.0000000e+00, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 2.9635436e-02, -9.8775575e-01, +-1.5316764e-01 }; + +const float MPT_B[] PROGMEM = { +1.2172140e-01, 7.0710678e+03, 7.0710678e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, 1.2172140e-01, 7.0710678e+03, 7.0710678e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.4834728e-01, +-1.2172140e-01, -1.2172140e-01, 1.4834728e-01, 7.0710678e+03, 7.0710678e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, -1.4834728e-01, +7.0710678e+03, 9.9996259e+03, 1.0000000e+04, 7.0710678e+03, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 7.0710678e+03, 7.0710678e+03, +9.9996259e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.4834728e-01 }; + +const int MPT_NC[] PROGMEM = { +8, 8, 8, 9, 9 +}; + + +const float MPT_F[] PROGMEM = { +5.9124557e+00, -1.9706348e+02, -3.0557908e+01, -7.3040818e+00, 2.4344669e+02, +3.7750381e+01, 6.3618820e+00, -2.1204296e+02, -3.2880720e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1204296e+02, -3.2880720e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00 +}; + + +const float MPT_G[] PROGMEM = { +-3.5527137e-15, 0.0000000e+00, -1.8459251e+00, -3.0000000e+01, 1.8459251e+00, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01 +}; + diff --git a/matlab/examples/BicopShield/BicopShield_EMPC/ectrl_due.h b/matlab/examples/BicopShield/BicopShield_EMPC/ectrl_due.h new file mode 100644 index 00000000..db74230c --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_EMPC/ectrl_due.h @@ -0,0 +1,1366 @@ +/* + MATRICES FOR EXPLICIT MPC POLYTOPES AND CORRESPONDING PWA LAWS + + The automatically generated set of matrices have been adapted from + the C code auto-generation routine of the Multi-Parametric Toolbox 3 + MPT3) of Kvasnica et al. for MATLAB. Please see http://www.mpt3.org + for more information. Please see the original "toC.m" for more details + in the MPT3. + + The following C code has been slightly adapted to perform microcontroller + architecutre-specific changes for AVR and ARM Cortex-A devices. + + The list of changes from the original are as follows: + - Changed "static" modifiers to "const" so microcontrollers will + prefer to use ROM instead of RAM. + - Added PROGMEM functionality for the AVR architecture, and calling + the necessary headers. + - Removed the possibility to use PWQ, this only handles PWA. + - Removed matrix export for the tie-breaking function. + + Usage: include alongside with the empcSequential.h header to your + example. + + This code snippet has been altered for the needs of the + the AutomationShield hardware and software ecosystem. + Visit http://www.automationshield.com for more details. + + + Copyright (C) 2005 by Michal Kvasnica (michal.kvasnica@stuba.sk) + Revised in 2012-2013 by Martin Herceg (herceg@control.ee.ethz.ch) + Adapted for MCU use by Gergely Tak�cs in 2020 (gergely.takacs@stuba.sk) +*/ +#define MPT_NR 129 +#define MPT_DOMAIN 3 +#define MPT_RANGE 6 +#define MPT_ABSTOL 1.000000e-08 + +const float MPT_A[] = { +-2.7941309e-02, 9.8641862e-01, 1.6185672e-01, -2.8670865e-02, 9.8702068e-01, +1.5801315e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, +8.9441719e-01, 4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9361501e-02, +-9.8754664e-01, -1.5456238e-01, -2.8707816e-02, 9.8705077e-01, 1.5781835e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7941309e-02, -9.8641862e-01, +-1.6185672e-01, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, -2.7941309e-02, +9.8641862e-01, 1.6185672e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -3.1638477e-01, 9.4858479e-01, 9.3580493e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, -2.8670865e-02, +9.8702068e-01, 1.5801315e-01, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 3.1621947e-01, -9.4863900e-01, +-9.4490605e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, 3.1638477e-01, +-9.4858479e-01, -9.3580493e-03, -2.7841079e-02, 9.8633695e-01, 1.6237087e-01, +-2.8623413e-02, 9.8698410e-01, 1.5825010e-01, 2.9361501e-02, -9.8754664e-01, +-1.5456238e-01, -2.9361501e-02, 9.8754664e-01, 1.5456238e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, -4.4755899e-01, 8.9424397e-01, 4.3207198e-03, +-3.1693421e-01, 9.4840421e-01, 9.0639411e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.8707816e-02, -9.8705077e-01, +-1.5781835e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.8707816e-02, +9.8705077e-01, 1.5781835e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +-2.8660499e-02, 9.8701434e-01, 1.5805462e-01, 2.9431206e-02, -9.8760061e-01, +-1.5420392e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.7841079e-02, -9.8633695e-01, -1.6237087e-01, +-2.7841079e-02, 9.8633695e-01, 1.6237087e-01, -2.8763969e-02, 9.8709643e-01, +1.5752230e-01, 2.7941309e-02, -9.8641862e-01, -1.6185672e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, +-2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9401253e-02, -9.8757655e-01, +-1.5436364e-01, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, +-2.8623413e-02, 9.8698410e-01, 1.5825010e-01, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, 2.8670865e-02, -9.8702068e-01, -1.5801315e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, +-3.1660445e-01, 9.4851268e-01, 9.2370891e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.8670865e-02, 9.8702068e-01, 1.5801315e-01, +2.9461666e-02, -9.8762191e-01, -1.5406159e-01, 3.1621947e-01, -9.4863900e-01, +-9.4490605e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -5.1465432e-01, +8.5739605e-01, 1.7123568e-03, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +3.1693421e-01, -9.4840421e-01, -9.0639411e-03, 3.1621947e-01, -9.4863900e-01, +-9.4490605e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, +3.1660445e-01, -9.4851268e-01, -9.2370891e-03, -2.7686827e-02, 9.8621074e-01, +1.6316196e-01, -2.8550707e-02, 9.8692793e-01, 1.5861313e-01, 2.9361501e-02, +-9.8754664e-01, -1.5456238e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, +-4.4801347e-01, 8.9401724e-01, 4.1366262e-03, -3.1787210e-01, 9.4809498e-01, +8.5583910e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.9361501e-02, 9.8754664e-01, 1.5456238e-01, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 4.4755899e-01, -8.9424397e-01, +-4.3207198e-03, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, +2.8660499e-02, -9.8701434e-01, -1.5805462e-01, -2.8660499e-02, 9.8701434e-01, +1.5805462e-01, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.8707816e-02, +-9.8705077e-01, -1.5781835e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7828592e-02, -9.8632425e-01, -1.6245013e-01, -2.8707816e-02, 9.8705077e-01, +1.5781835e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, -2.7828592e-02, +9.8632425e-01, 1.6245013e-01, 2.7896798e-02, -9.8638139e-01, -1.6209107e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8763969e-02, -9.8709643e-01, +-1.5752230e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, -2.8763969e-02, +9.8709643e-01, 1.5752230e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, +2.9431206e-02, -9.8760061e-01, -1.5420392e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 2.7686827e-02, -9.8621074e-01, -1.6316196e-01, -2.9431206e-02, +9.8760061e-01, 1.5420392e-01, -2.7686827e-02, 9.8621074e-01, 1.6316196e-01, +-2.8716859e-02, 9.8706023e-01, 1.5775753e-01, 2.9536735e-02, -9.8768205e-01, +-1.5366115e-01, -2.9536735e-02, 9.8768205e-01, 1.5366115e-01, 2.7841079e-02, +-9.8633695e-01, -1.6237087e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7641502e-02, 9.8617252e-01, 1.6340044e-01, 2.9401253e-02, -9.8757655e-01, +-1.5436364e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8550707e-02, +-9.8692793e-01, -1.5861313e-01, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, +-2.8550707e-02, 9.8692793e-01, 1.5861313e-01, -2.7727550e-02, 9.8624160e-01, +1.6296839e-01, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, -2.9461666e-02, +9.8762191e-01, 1.5406159e-01, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8623413e-02, 9.8698410e-01, +1.5825010e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, 2.8670865e-02, +-9.8702068e-01, -1.5801315e-01, -2.8670865e-02, 9.8702068e-01, 1.5801315e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -3.1638477e-01, 9.4858479e-01, 9.3580493e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9401253e-02, -9.8757655e-01, +-1.5436364e-01, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -5.1465432e-01, +8.5739605e-01, 1.7123568e-03, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +-3.1621947e-01, 9.4863900e-01, 9.4490605e-03, 3.1787210e-01, -9.4809498e-01, +-8.5583910e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -3.1621947e-01, +9.4863900e-01, 9.4490605e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 3.1638477e-01, -9.4858479e-01, +-9.3580493e-03, -2.7841079e-02, 9.8633695e-01, 1.6237087e-01, -2.8623413e-02, +9.8698410e-01, 1.5825010e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, +-4.4755899e-01, 8.9424397e-01, 4.3207198e-03, -3.1693421e-01, 9.4840421e-01, +9.0639411e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.9361501e-02, -9.8754664e-01, -1.5456238e-01, -2.9361501e-02, 9.8754664e-01, +1.5456238e-01, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, 4.4801347e-01, -8.9401724e-01, -4.1366262e-03, 2.9470725e-02, +-9.8763026e-01, -1.5400634e-01, 2.7641502e-02, -9.8617252e-01, -1.6340044e-01, +2.8588002e-02, -9.8695841e-01, -1.5841660e-01, -2.9470725e-02, 9.8763026e-01, +1.5400634e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.7641502e-02, +9.8617252e-01, 1.6340044e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, +-2.9530786e-02, 9.8767524e-01, 1.5370603e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, 2.7727550e-02, -9.8624160e-01, -1.6296839e-01, -2.8660499e-02, +9.8701434e-01, 1.5805462e-01, -2.7727550e-02, 9.8624160e-01, 1.6296839e-01, +2.9575905e-02, -9.8771133e-01, -1.5346531e-01, -2.9575905e-02, 9.8771133e-01, +1.5346531e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, +2.8716859e-02, -9.8706023e-01, -1.5775753e-01, -2.8716859e-02, 9.8706023e-01, +1.5775753e-01, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, -2.8707816e-02, +9.8705077e-01, 1.5781835e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.9470725e-02, -9.8763026e-01, +-1.5400634e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, 2.8763969e-02, +-9.8709643e-01, -1.5752230e-01, 2.7828592e-02, -9.8632425e-01, -1.6245013e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, -2.8763969e-02, 9.8709643e-01, 1.5752230e-01, 2.9635436e-02, +-9.8775575e-01, -1.5316764e-01, -2.8660499e-02, 9.8701434e-01, 1.5805462e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7841079e-02, -9.8633695e-01, +-1.6237087e-01, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, -2.9431206e-02, +9.8760061e-01, 1.5420392e-01, -2.7841079e-02, 9.8633695e-01, 1.6237087e-01, +-2.8644678e-02, 9.8700467e-01, 1.5811791e-01, 2.9536735e-02, -9.8768205e-01, +-1.5366115e-01, 2.7686827e-02, -9.8621074e-01, -1.6316196e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.7686827e-02, 9.8621074e-01, 1.6316196e-01, +-2.9536735e-02, 9.8768205e-01, 1.5366115e-01, -2.7796248e-02, 9.8629934e-01, +1.6260684e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8623413e-02, +-9.8698410e-01, -1.5825010e-01, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, +-2.9401253e-02, 9.8757655e-01, 1.5436364e-01, -2.8623413e-02, 9.8698410e-01, +1.5825010e-01, -2.7572044e-02, 9.8611385e-01, 1.6376585e-01, 2.9461666e-02, +-9.8762191e-01, -1.5406159e-01, 2.8550707e-02, -9.8692793e-01, -1.5861313e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8550707e-02, 9.8692793e-01, +1.5861313e-01, -2.9461666e-02, 9.8762191e-01, 1.5406159e-01, -2.7796248e-02, +9.8629934e-01, 1.6260684e-01, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, +2.9401253e-02, -9.8757655e-01, -1.5436364e-01, -2.9401253e-02, 9.8757655e-01, +1.5436364e-01, -2.8623413e-02, 9.8698410e-01, 1.5825010e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9361501e-02, -9.8754664e-01, +-1.5456238e-01, 2.8670865e-02, -9.8702068e-01, -1.5801315e-01, -5.1465432e-01, +8.5739605e-01, 1.7123568e-03, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, 3.1693421e-01, -9.4840421e-01, -9.0639411e-03, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, 4.4755899e-01, +-8.9424397e-01, -4.3207198e-03, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, +-2.8670865e-02, 9.8702068e-01, 1.5801315e-01, -2.9361501e-02, 9.8754664e-01, +1.5456238e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, +8.9441719e-01, 4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, +7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 2.8660499e-02, +-9.8701434e-01, -1.5805462e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, +-2.9470725e-02, 9.8763026e-01, 1.5400634e-01, -2.8660499e-02, 9.8701434e-01, +1.5805462e-01, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9530786e-02, +-9.8767524e-01, -1.5370603e-01, 2.8588002e-02, -9.8695841e-01, -1.5841660e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7572044e-02, -9.8611385e-01, +-1.6376585e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.9530786e-02, +9.8767524e-01, 1.5370603e-01, -2.7572044e-02, 9.8611385e-01, 1.6376585e-01, +2.9575905e-02, -9.8771133e-01, -1.5346531e-01, 2.7641502e-02, -9.8617252e-01, +-1.6340044e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7641502e-02, +9.8617252e-01, 1.6340044e-01, 2.8644678e-02, -9.8700467e-01, -1.5811791e-01, +-2.9575905e-02, 9.8771133e-01, 1.5346531e-01, -2.8644678e-02, 9.8700467e-01, +1.5811791e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, 2.9470725e-02, +-9.8763026e-01, -1.5400634e-01, -2.9470725e-02, 9.8763026e-01, 1.5400634e-01, +-2.8660499e-02, 9.8701434e-01, 1.5805462e-01, 2.7796248e-02, -9.8629934e-01, +-1.6260684e-01, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9635436e-02, +-9.8775575e-01, -1.5316764e-01, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, +2.8716859e-02, -9.8706023e-01, -1.5775753e-01, 2.7727550e-02, -9.8624160e-01, +-1.6296839e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7727550e-02, +9.8624160e-01, 1.6296839e-01, -2.8716859e-02, 9.8706023e-01, 1.5775753e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 2.9470725e-02, -9.8763026e-01, +-1.5400634e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8660499e-02, +9.8701434e-01, 1.5805462e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, +-4.4721134e-01, 8.9441719e-01, 4.4615011e-03, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, -1.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7941309e-02, -9.8641862e-01, -1.6185672e-01, 2.9431206e-02, -9.8760061e-01, +-1.5420392e-01, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, -2.7941309e-02, +9.8641862e-01, 1.6185672e-01, 2.8763969e-02, -9.8709643e-01, -1.5752230e-01, +-2.8763969e-02, 9.8709643e-01, 1.5752230e-01, 2.7896798e-02, -9.8638139e-01, +-1.6209107e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7896798e-02, +9.8638139e-01, 1.6209107e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, +2.7828592e-02, -9.8632425e-01, -1.6245013e-01, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8707816e-02, +9.8705077e-01, 1.5781835e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, +-2.8707816e-02, 9.8705077e-01, 1.5781835e-01, -2.9431206e-02, 9.8760061e-01, +1.5420392e-01, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, +-8.9441719e-01, -4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 2.7941309e-02, +-9.8641862e-01, -1.6185672e-01, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, +-2.8716859e-02, 9.8706023e-01, 1.5775753e-01, 2.7841079e-02, -9.8633695e-01, +-1.6237087e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7841079e-02, +9.8633695e-01, 1.6237087e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, +-2.9536735e-02, 9.8768205e-01, 1.5366115e-01, 2.7686827e-02, -9.8621074e-01, +-1.6316196e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.7686827e-02, +9.8621074e-01, 1.6316196e-01, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7896798e-02, 9.8638139e-01, +1.6209107e-01, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.8670865e-02, -9.8702068e-01, -1.5801315e-01, +-2.8670865e-02, 9.8702068e-01, 1.5801315e-01, -2.7727550e-02, 9.8624160e-01, +1.6296839e-01, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, +-2.9461666e-02, 9.8762191e-01, 1.5406159e-01, -2.7641502e-02, 9.8617252e-01, +1.6340044e-01, 2.8550707e-02, -9.8692793e-01, -1.5861313e-01, -2.8550707e-02, +9.8692793e-01, 1.5861313e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.9401253e-02, 9.8757655e-01, 1.5436364e-01, -2.7841079e-02, 9.8633695e-01, +1.6237087e-01, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, -2.9361501e-02, +9.8754664e-01, 1.5456238e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.8623413e-02, -9.8698410e-01, -1.5825010e-01, -2.9470725e-02, 9.8763026e-01, +1.5400634e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7896798e-02, +-9.8638139e-01, -1.6209107e-01, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, +-2.8707816e-02, 9.8705077e-01, 1.5781835e-01, -2.7896798e-02, 9.8638139e-01, +1.6209107e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.7727550e-02, -9.8624160e-01, -1.6296839e-01, +-2.8660499e-02, 9.8701434e-01, 1.5805462e-01, 2.9530786e-02, -9.8767524e-01, +-1.5370603e-01, -2.9530786e-02, 9.8767524e-01, 1.5370603e-01, -2.7727550e-02, +9.8624160e-01, 1.6296839e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, +-2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.8716859e-02, -9.8706023e-01, +-1.5775753e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, -2.9575905e-02, +9.8771133e-01, 1.5346531e-01, -2.8716859e-02, 9.8706023e-01, 1.5775753e-01, +2.8588002e-02, -9.8695841e-01, -1.5841660e-01, -2.8588002e-02, 9.8695841e-01, +1.5841660e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.7641502e-02, -9.8617252e-01, -1.6340044e-01, +-2.9470725e-02, 9.8763026e-01, 1.5400634e-01, -2.7641502e-02, 9.8617252e-01, +1.6340044e-01, 2.9635436e-02, -9.8775575e-01, -1.5316764e-01, 2.8644678e-02, +-9.8700467e-01, -1.5811791e-01, 2.7572044e-02, -9.8611385e-01, -1.6376585e-01, +-2.7572044e-02, 9.8611385e-01, 1.6376585e-01, -2.8644678e-02, 9.8700467e-01, +1.5811791e-01, -2.9635436e-02, 9.8775575e-01, 1.5316764e-01, 2.7641502e-02, +-9.8617252e-01, -1.6340044e-01, -2.7641502e-02, 9.8617252e-01, 1.6340044e-01, +2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 2.8588002e-02, -9.8695841e-01, -1.5841660e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, +2.9431206e-02, -9.8760061e-01, -1.5420392e-01, -2.9431206e-02, 9.8760061e-01, +1.5420392e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7841079e-02, +-9.8633695e-01, -1.6237087e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, +-2.7841079e-02, 9.8633695e-01, 1.6237087e-01, 2.8716859e-02, -9.8706023e-01, +-1.5775753e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, -2.9575905e-02, +9.8771133e-01, 1.5346531e-01, -2.8716859e-02, 9.8706023e-01, 1.5775753e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, -2.7796248e-02, 9.8629934e-01, +1.6260684e-01, 2.7727550e-02, -9.8624160e-01, -1.6296839e-01, 2.9530786e-02, +-9.8767524e-01, -1.5370603e-01, -2.9530786e-02, 9.8767524e-01, 1.5370603e-01, +-2.7727550e-02, 9.8624160e-01, 1.6296839e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8660499e-02, +9.8701434e-01, 1.5805462e-01, 2.7941309e-02, -9.8641862e-01, -1.6185672e-01, +-7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7941309e-02, 9.8641862e-01, +1.6185672e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, 2.8763969e-02, +-9.8709643e-01, -1.5752230e-01, 2.7896798e-02, -9.8638139e-01, -1.6209107e-01, +2.8707816e-02, -9.8705077e-01, -1.5781835e-01, -2.8707816e-02, 9.8705077e-01, +1.5781835e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8670865e-02, 9.8702068e-01, +1.5801315e-01, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, 2.7828592e-02, +-9.8632425e-01, -1.6245013e-01, -2.8763969e-02, 9.8709643e-01, 1.5752230e-01, +-2.9536735e-02, 9.8768205e-01, 1.5366115e-01, 2.7941309e-02, -9.8641862e-01, +-1.6185672e-01, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, +-8.9441719e-01, -4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -2.7941309e-02, +9.8641862e-01, 1.6185672e-01, 2.7841079e-02, -9.8633695e-01, -1.6237087e-01, +-2.8660499e-02, 9.8701434e-01, 1.5805462e-01, -2.7841079e-02, 9.8633695e-01, +1.6237087e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9431206e-02, +-9.8760061e-01, -1.5420392e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, +-2.8550707e-02, 9.8692793e-01, 1.5861313e-01, 2.9361501e-02, -9.8754664e-01, +-1.5456238e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7686827e-02, +-9.8621074e-01, -1.6316196e-01, -2.7828592e-02, 9.8632425e-01, 1.6245013e-01, +-2.9461666e-02, 9.8762191e-01, 1.5406159e-01, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7686827e-02, +9.8621074e-01, 1.6316196e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.9361501e-02, 9.8754664e-01, 1.5456238e-01, 2.8550707e-02, -9.8692793e-01, +-1.5861313e-01, -2.9530786e-02, 9.8767524e-01, 1.5370603e-01, 2.8707816e-02, +-9.8705077e-01, -1.5781835e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.7828592e-02, -9.8632425e-01, -1.6245013e-01, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, -2.9575905e-02, 9.8771133e-01, 1.5346531e-01, 2.7896798e-02, +-9.8638139e-01, -1.6209107e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7896798e-02, 9.8638139e-01, 1.6209107e-01, 2.8763969e-02, -9.8709643e-01, +-1.5752230e-01, -2.8763969e-02, 9.8709643e-01, 1.5752230e-01, 2.8660499e-02, +-9.8701434e-01, -1.5805462e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.9470725e-02, 9.8763026e-01, 1.5400634e-01, -2.7796248e-02, 9.8629934e-01, +1.6260684e-01, 2.8716859e-02, -9.8706023e-01, -1.5775753e-01, 2.7727550e-02, +-9.8624160e-01, -1.6296839e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7727550e-02, 9.8624160e-01, 1.6296839e-01, -2.8716859e-02, 9.8706023e-01, +1.5775753e-01, 2.9635436e-02, -9.8775575e-01, -1.5316764e-01, -2.9635436e-02, +9.8775575e-01, 1.5316764e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, +-2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, -2.8660499e-02, 9.8701434e-01, 1.5805462e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7686827e-02, -9.8621074e-01, +-1.6316196e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, 2.8588002e-02, +-9.8695841e-01, -1.5841660e-01, -2.7686827e-02, 9.8621074e-01, 1.6316196e-01, +2.8644678e-02, -9.8700467e-01, -1.5811791e-01, -2.8644678e-02, 9.8700467e-01, +1.5811791e-01, 2.9575905e-02, -9.8771133e-01, -1.5346531e-01, 2.7641502e-02, +-9.8617252e-01, -1.6340044e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7641502e-02, 9.8617252e-01, 1.6340044e-01, -2.9575905e-02, 9.8771133e-01, +1.5346531e-01, 2.7572044e-02, -9.8611385e-01, -1.6376585e-01, -2.7572044e-02, +9.8611385e-01, 1.6376585e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, +2.8588002e-02, -9.8695841e-01, -1.5841660e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, -2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.9530786e-02, +9.8767524e-01, 1.5370603e-01, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8550707e-02, -9.8692793e-01, +-1.5861313e-01, 2.7641502e-02, -9.8617252e-01, -1.6340044e-01, -2.8550707e-02, +9.8692793e-01, 1.5861313e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, +-2.9536735e-02, 9.8768205e-01, 1.5366115e-01, 2.7841079e-02, -9.8633695e-01, +-1.6237087e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7841079e-02, +9.8633695e-01, 1.6237087e-01, 2.8716859e-02, -9.8706023e-01, -1.5775753e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, -2.8660499e-02, 9.8701434e-01, 1.5805462e-01, +-2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9461666e-02, -9.8762191e-01, +-1.5406159e-01, -2.9461666e-02, 9.8762191e-01, 1.5406159e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.8623413e-02, 9.8698410e-01, 1.5825010e-01, +2.7727550e-02, -9.8624160e-01, -1.6296839e-01, 2.7941309e-02, -9.8641862e-01, +-1.6185672e-01, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, -7.0710678e-01, +7.0710678e-01, 0.0000000e+00, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, +-3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, +2.8707816e-02, -9.8705077e-01, -1.5781835e-01, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, -2.8670865e-02, 9.8702068e-01, 1.5801315e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, +2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.7941309e-02, -9.8641862e-01, +-1.6185672e-01, -2.8707816e-02, 9.8705077e-01, 1.5781835e-01, -2.9431206e-02, +9.8760061e-01, 1.5420392e-01, -2.7941309e-02, 9.8641862e-01, 1.6185672e-01, +7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -2.8623413e-02, 9.8698410e-01, +1.5825010e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9361501e-02, +-9.8754664e-01, -1.5456238e-01, 2.7841079e-02, -9.8633695e-01, -1.6237087e-01, +-2.9361501e-02, 9.8754664e-01, 1.5456238e-01, -2.9635436e-02, 9.8775575e-01, +1.5316764e-01, 2.8763969e-02, -9.8709643e-01, -1.5752230e-01, 2.7828592e-02, +-9.8632425e-01, -1.6245013e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7828592e-02, 9.8632425e-01, 1.6245013e-01, -2.8763969e-02, 9.8709643e-01, +1.5752230e-01, 2.7896798e-02, -9.8638139e-01, -1.6209107e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.8707816e-02, -9.8705077e-01, +-1.5781835e-01, -2.8707816e-02, 9.8705077e-01, 1.5781835e-01, 2.8716859e-02, +-9.8706023e-01, -1.5775753e-01, -2.8716859e-02, 9.8706023e-01, 1.5775753e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, -2.7796248e-02, 9.8629934e-01, 1.6260684e-01, 2.9575905e-02, +-9.8771133e-01, -1.5346531e-01, -2.9575905e-02, 9.8771133e-01, 1.5346531e-01, +2.7727550e-02, -9.8624160e-01, -1.6296839e-01, -2.7727550e-02, 9.8624160e-01, +1.6296839e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, -2.8660499e-02, +9.8701434e-01, 1.5805462e-01, 2.9530786e-02, -9.8767524e-01, -1.5370603e-01, +-2.9530786e-02, 9.8767524e-01, 1.5370603e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, 2.9401253e-02, +-9.8757655e-01, -1.5436364e-01, 2.7796248e-02, -9.8629934e-01, -1.6260684e-01, +-2.9401253e-02, 9.8757655e-01, 1.5436364e-01, -2.8623413e-02, 9.8698410e-01, +1.5825010e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, 2.7686827e-02, +-9.8621074e-01, -1.6316196e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +-2.7686827e-02, 9.8621074e-01, 1.6316196e-01, -2.9536735e-02, 9.8768205e-01, +1.5366115e-01, 2.8644678e-02, -9.8700467e-01, -1.5811791e-01, 2.7641502e-02, +-9.8617252e-01, -1.6340044e-01, 2.8588002e-02, -9.8695841e-01, -1.5841660e-01, +-2.8588002e-02, 9.8695841e-01, 1.5841660e-01, -2.7641502e-02, 9.8617252e-01, +1.6340044e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, -2.9470725e-02, +9.8763026e-01, 1.5400634e-01, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, +2.8550707e-02, -9.8692793e-01, -1.5861313e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, -2.8550707e-02, 9.8692793e-01, 1.5861313e-01, -2.9461666e-02, +9.8762191e-01, 1.5406159e-01, 2.7572044e-02, -9.8611385e-01, -1.6376585e-01, +2.7841079e-02, -9.8633695e-01, -1.6237087e-01, 2.9431206e-02, -9.8760061e-01, +-1.5420392e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, -2.7841079e-02, +9.8633695e-01, 1.6237087e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +2.8660499e-02, -9.8701434e-01, -1.5805462e-01, 2.8623413e-02, -9.8698410e-01, +-1.5825010e-01, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, -2.9401253e-02, +9.8757655e-01, 1.5436364e-01, -2.8623413e-02, 9.8698410e-01, 1.5825010e-01, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.7796248e-02, -9.8629934e-01, +-1.6260684e-01, -7.0710678e-01, 7.0710678e-01, 0.0000000e+00, -4.4721134e-01, +8.9441719e-01, 4.4615011e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, +7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, -1.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, 2.8670865e-02, +-9.8702068e-01, -1.5801315e-01, 2.7941309e-02, -9.8641862e-01, -1.6185672e-01, +-2.8670865e-02, 9.8702068e-01, 1.5801315e-01, -2.9361501e-02, 9.8754664e-01, +1.5456238e-01, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, +-8.9441719e-01, -4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 2.7941309e-02, +-9.8641862e-01, -1.6185672e-01, 2.7828592e-02, -9.8632425e-01, -1.6245013e-01, +-2.9530786e-02, 9.8767524e-01, 1.5370603e-01, -2.7828592e-02, 9.8632425e-01, +1.6245013e-01, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.8707816e-02, 9.8705077e-01, 1.5781835e-01, +2.8763969e-02, -9.8709643e-01, -1.5752230e-01, -2.9575905e-02, 9.8771133e-01, +1.5346531e-01, -2.8763969e-02, 9.8709643e-01, 1.5752230e-01, 1.0000000e+00, +0.0000000e+00, 0.0000000e+00, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +-2.9401253e-02, 9.8757655e-01, 1.5436364e-01, 7.0710678e-01, -7.0710678e-01, +0.0000000e+00, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, 3.1638477e-01, +-9.4858479e-01, -9.3580493e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.8670865e-02, -9.8702068e-01, -1.5801315e-01, 2.7896798e-02, +-9.8638139e-01, -1.6209107e-01, -2.8670865e-02, 9.8702068e-01, 1.5801315e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7841079e-02, 9.8633695e-01, +1.6237087e-01, 2.9536735e-02, -9.8768205e-01, -1.5366115e-01, 2.8716859e-02, +-9.8706023e-01, -1.5775753e-01, -2.9536735e-02, 9.8768205e-01, 1.5366115e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, 2.8660499e-02, -9.8701434e-01, +-1.5805462e-01, -2.8660499e-02, 9.8701434e-01, 1.5805462e-01, -2.7796248e-02, +9.8629934e-01, 1.6260684e-01, 2.9470725e-02, -9.8763026e-01, -1.5400634e-01, +-2.9470725e-02, 9.8763026e-01, 1.5400634e-01, 2.8623413e-02, -9.8698410e-01, +-1.5825010e-01, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.8623413e-02, +9.8698410e-01, 1.5825010e-01, 2.9461666e-02, -9.8762191e-01, -1.5406159e-01, +2.7727550e-02, -9.8624160e-01, -1.6296839e-01, -2.9461666e-02, 9.8762191e-01, +1.5406159e-01, 2.7686827e-02, -9.8621074e-01, -1.6316196e-01, -2.7686827e-02, +9.8621074e-01, 1.6316196e-01, 2.9431206e-02, -9.8760061e-01, -1.5420392e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.9431206e-02, 9.8760061e-01, +1.5420392e-01, 2.8588002e-02, -9.8695841e-01, -1.5841660e-01, 2.8550707e-02, +-9.8692793e-01, -1.5861313e-01, -2.8550707e-02, 9.8692793e-01, 1.5861313e-01, +2.9401253e-02, -9.8757655e-01, -1.5436364e-01, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, 2.7641502e-02, +-9.8617252e-01, -1.6340044e-01, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, +-2.9361501e-02, 9.8754664e-01, 1.5456238e-01, 7.0710678e-01, -7.0710678e-01, +0.0000000e+00, 4.4755899e-01, -8.9424397e-01, -4.3207198e-03, 3.1693421e-01, +-9.4840421e-01, -9.0639411e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.8623413e-02, -9.8698410e-01, -1.5825010e-01, 2.7841079e-02, +-9.8633695e-01, -1.6237087e-01, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, +-4.4721134e-01, 8.9441719e-01, 4.4615011e-03, 7.0710678e-01, -7.0710678e-01, +0.0000000e+00, -5.1465432e-01, 8.5739605e-01, 1.7123568e-03, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, -4.4755899e-01, 8.9424397e-01, 4.3207198e-03, +3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, -3.1693421e-01, 9.4840421e-01, 9.0639411e-03, +-2.9461666e-02, 9.8762191e-01, 1.5406159e-01, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, 7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, +-8.9441719e-01, -4.4615011e-03, 3.1660445e-01, -9.4851268e-01, -9.2370891e-03, +-1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -2.8670865e-02, +9.8702068e-01, 1.5801315e-01, 2.7828592e-02, -9.8632425e-01, -1.6245013e-01, +2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.8707816e-02, -9.8705077e-01, +-1.5781835e-01, -2.9470725e-02, 9.8763026e-01, 1.5400634e-01, -2.8707816e-02, +9.8705077e-01, 1.5781835e-01, -2.7896798e-02, 9.8638139e-01, 1.6209107e-01, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.9536735e-02, 9.8768205e-01, +1.5366115e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, -2.7941309e-02, +9.8641862e-01, 1.6185672e-01, 2.8763969e-02, -9.8709643e-01, -1.5752230e-01, +4.4721134e-01, -8.9441719e-01, -4.4615011e-03, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -3.1621947e-01, +9.4863900e-01, 9.4490605e-03, -3.1638477e-01, 9.4858479e-01, 9.3580493e-03, +2.7841079e-02, -9.8633695e-01, -1.6237087e-01, -2.7841079e-02, 9.8633695e-01, +1.6237087e-01, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 2.9431206e-02, +-9.8760061e-01, -1.5420392e-01, 2.8660499e-02, -9.8701434e-01, -1.5805462e-01, +-2.9431206e-02, 9.8760061e-01, 1.5420392e-01, 2.8623413e-02, -9.8698410e-01, +-1.5825010e-01, -2.8623413e-02, 9.8698410e-01, 1.5825010e-01, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 2.9401253e-02, -9.8757655e-01, -1.5436364e-01, +2.7796248e-02, -9.8629934e-01, -1.6260684e-01, -2.9401253e-02, 9.8757655e-01, +1.5436364e-01, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, 4.4801347e-01, -8.9401724e-01, -4.1366262e-03, +3.1787210e-01, -9.4809498e-01, -8.5583910e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, -2.9361501e-02, 9.8754664e-01, 1.5456238e-01, +2.8550707e-02, -9.8692793e-01, -1.5861313e-01, 2.7686827e-02, -9.8621074e-01, +-1.6316196e-01, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, -5.1465432e-01, 8.5739605e-01, 1.7123568e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -4.4721134e-01, 8.9441719e-01, +4.4615011e-03, -4.4801347e-01, 8.9401724e-01, 4.1366262e-03, 3.1621947e-01, +-9.4863900e-01, -9.4490605e-03, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, -3.1787210e-01, 9.4809498e-01, 8.5583910e-03, 3.1621947e-01, +-9.4863900e-01, -9.4490605e-03, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -3.1621947e-01, 9.4863900e-01, +9.4490605e-03, -3.1660445e-01, 9.4851268e-01, 9.2370891e-03, 2.8670865e-02, +-9.8702068e-01, -1.5801315e-01, -2.9401253e-02, 9.8757655e-01, 1.5436364e-01, +-2.8670865e-02, 9.8702068e-01, 1.5801315e-01, 7.0710678e-01, -7.0710678e-01, +0.0000000e+00, 4.4721134e-01, -8.9441719e-01, -4.4615011e-03, 3.1638477e-01, +-9.4858479e-01, -9.3580493e-03, -1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.0000000e+00, 2.7896798e-02, -9.8638139e-01, -1.6209107e-01, 2.7941309e-02, +-9.8641862e-01, -1.6185672e-01, -2.9431206e-02, 9.8760061e-01, 1.5420392e-01, +-2.7941309e-02, 9.8641862e-01, 1.6185672e-01, 1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 2.8707816e-02, -9.8705077e-01, -1.5781835e-01, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, 4.4755899e-01, -8.9424397e-01, -4.3207198e-03, +3.1693421e-01, -9.4840421e-01, -9.0639411e-03, -1.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.0000000e+00, 2.9361501e-02, -9.8754664e-01, -1.5456238e-01, +2.8623413e-02, -9.8698410e-01, -1.5825010e-01, 2.7841079e-02, -9.8633695e-01, +-1.6237087e-01, -2.9361501e-02, 9.8754664e-01, 1.5456238e-01, 7.0710678e-01, +-7.0710678e-01, 0.0000000e+00, -5.1465432e-01, 8.5739605e-01, 1.7123568e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, -4.4721134e-01, 8.9441719e-01, 4.4615011e-03, -4.4755899e-01, +8.9424397e-01, 4.3207198e-03, 5.1465432e-01, -8.5739605e-01, -1.7123568e-03, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 3.1621947e-01, -9.4863900e-01, +-9.4490605e-03, -3.1621947e-01, 9.4863900e-01, 9.4490605e-03, -3.1693421e-01, +9.4840421e-01, 9.0639411e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, +-3.1621947e-01, 9.4863900e-01, 9.4490605e-03, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00, -3.1638477e-01, +9.4858479e-01, 9.3580493e-03, -2.9361501e-02, 9.8754664e-01, 1.5456238e-01, +7.0710678e-01, -7.0710678e-01, 0.0000000e+00, 4.4721134e-01, -8.9441719e-01, +-4.4615011e-03, 3.1621947e-01, -9.4863900e-01, -9.4490605e-03, -1.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.0000000e+00, 2.8670865e-02, -9.8702068e-01, +-1.5801315e-01, 2.7941309e-02, -9.8641862e-01, -1.6185672e-01 }; + +const float MPT_B[] = { +-1.3895442e-01, -1.2758139e-01, 7.0710678e+03, 4.4721137e+03, 3.1621952e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, -9.1989026e-02, -1.2700513e-01, +1.0000000e+04, 1.3895442e-01, -1.0333071e-01, -1.1385063e-01, -1.3964801e-01, +7.0710678e+03, 4.4721137e+03, 3.1640234e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.2758139e-01, -1.0463051e-01, -1.0451399e-01, 4.4721137e+03, +1.0000000e+04, -3.1621952e+03, 3.1621952e+03, -3.1640234e+03, -1.5524321e-01, +-1.4266334e-01, -7.0682278e-02, 9.1989026e-02, 7.0710678e+03, 4.4758646e+03, +3.1701189e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +1.3964801e-01, 1.2700513e-01, -1.1591788e-01, -1.0283622e-01, -1.1308694e-01, +-1.4206672e-01, -8.1046541e-02, 1.0333071e-01, 1.0000000e+04, 1.5524321e-01, +-1.2845172e-01, -1.2796905e-01, 1.1385063e-01, 1.0000000e+04, -1.1872361e-01, +-1.5596377e-01, -8.2175907e-02, 1.0463051e-01, 1.0000000e+04, 1.4266334e-01, +-1.1809773e-01, -1.4274260e-01, 1.0451399e-01, 7.0710678e+03, 4.4721137e+03, +3.1664528e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0824316e-01, +-1.2193486e-01, -3.1621952e+03, 3.1621952e+03, 5.1465433e+03, 1.0000000e+04, +-3.1701189e+03, -3.1621952e+03, 4.4721137e+03, 1.0000000e+04, 3.1621955e+03, +-3.1664528e+03, -1.7814849e-01, -1.6367246e-01, 1.2772450e-01, 7.0710678e+03, +4.4807683e+03, 3.1805169e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +7.0682278e-02, -4.4721137e+03, 4.4721137e+03, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, -4.4758646e+03, -9.2490697e-02, 1.1591788e-01, 1.5596377e-01, +1.4206672e-01, -1.1639930e-01, -1.2770703e-01, 1.0283622e-01, 1.0000000e+04, +1.4274260e-01, 1.1925800e-01, -1.3314513e-01, -1.1394861e-01, 1.1308694e-01, +1.0000000e+04, 1.2796905e-01, -1.3123181e-01, -1.0212614e-01, -1.6304718e-01, +1.2562400e-01, 1.0000000e+04, 1.7814849e-01, 8.1046541e-02, -1.4875994e-01, +-1.4300339e-01, -9.4959558e-02, 1.1872361e-01, 1.2845172e-01, 1.0000000e+04, +-1.7890763e-01, 1.2596141e-01, 1.0000000e+04, 1.6367246e-01, 8.2175907e-02, +-1.3681143e-01, -1.5910730e-01, -9.7735705e-02, 1.2193486e-01, 1.1809773e-01, +1.0000000e+04, 1.0742179e-01, -1.2242478e-01, -1.0824316e-01, 1.3131057e-01, +7.0710678e+03, 4.4721137e+03, 3.1640235e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.2088866e-01, -3.1621940e+03, 5.1465433e+03, 1.0000000e+04, +3.1621952e+03, -3.1805169e+03, -3.1621955e+03, 3.1621956e+03, 4.4721137e+03, +1.0000000e+04, -3.1640235e+03, -1.7350735e-01, -1.6044994e-01, 7.0710678e+03, +4.4758643e+03, 3.1701183e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +1.4903125e-01, -1.2772450e-01, -4.4721132e+03, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, 4.4721137e+03, -4.4807683e+03, 1.2386938e-01, 1.7890763e-01, +1.6304718e-01, 9.2490697e-02, -1.3508390e-01, -1.4804153e-01, -1.0798073e-01, +1.3314513e-01, 1.1639930e-01, 1.5910730e-01, 1.1845977e-01, -1.2860539e-01, +-1.0633205e-01, 1.3123181e-01, 1.2770703e-01, 1.0000000e+04, 1.2871086e-01, +1.4300339e-01, -1.1566153e-01, -1.1925800e-01, 1.4342692e-01, 1.0000000e+04, +1.2242478e-01, -1.3213141e-01, -9.5863716e-02, 1.0212614e-01, 1.1394861e-01, +1.0000000e+04, 1.4701368e-01, 1.3415792e-01, -1.4834728e-01, -1.5983067e-01, +1.0000000e+04, 1.7350735e-01, 1.4790817e-01, -1.2562400e-01, -1.4671586e-01, +-1.6394595e-01, 1.2422293e-01, 1.4875994e-01, 1.0000000e+04, 1.1734926e-01, +9.4959558e-02, -1.7425525e-01, 1.0000000e+04, 1.6044994e-01, 1.4841602e-01, +-1.2596141e-01, -1.3588434e-01, -1.8212204e-01, 1.2519039e-01, 1.3681143e-01, +1.0000000e+04, 1.0826153e-01, 9.7735705e-02, -1.3867612e-01, -1.0742179e-01, +-9.8434055e-02, 1.2088866e-01, 1.3198740e-01, 1.0000000e+04, -1.0783877e-01, +7.0710678e+03, 4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.2145607e-01, -1.3131057e-01, 5.1465433e+03, 1.0000000e+04, +-3.1621939e+03, 3.1621940e+03, -3.1701183e+03, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, -4.4721132e+03, 4.4721132e+03, -4.4758643e+03, -1.7189507e-01, +-1.5971609e-01, -1.4903125e-01, 7.0710678e+03, 4.4721132e+03, 3.1621939e+03, +7.0710678e+03, 4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, 1.7425525e-01, 1.5983067e-01, 1.4729656e-01, +-1.2386938e-01, -1.3416325e-01, -1.4599851e-01, 1.2310596e-01, 1.3508390e-01, +1.0000000e+04, 1.8212204e-01, 1.1933228e-01, 1.0798073e-01, -1.4899185e-01, +1.2247802e-01, 1.4804153e-01, 1.0000000e+04, 1.3065475e-01, 1.6394595e-01, +1.0633205e-01, -1.3430757e-01, -1.1845977e-01, -1.0870423e-01, 1.3213141e-01, +1.4412718e-01, 1.3867612e-01, -1.1041938e-01, -1.2172140e-01, 1.4834728e-01, +1.1566153e-01, 1.2860539e-01, 1.0000000e+04, 1.4693877e-01, 1.3339106e-01, +-1.2871086e-01, -1.0765585e-01, 1.0000000e+04, -1.0069582e-01, 7.0710678e+03, +4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, +1.0783877e-01, -1.3271674e-01, -1.4342692e-01, -8.2734975e-02, -1.3415792e-01, +1.6000083e-01, 9.5863716e-02, 1.0000000e+04, 1.4607673e-01, -1.4737777e-01, +-1.4701368e-01, 1.7580768e-01, 1.0000000e+04, 1.3493007e-01, -1.4827035e-01, +-1.5909898e-01, -1.4790817e-01, 7.0710678e+03, 4.4721137e+03, 3.1621956e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.7189507e-01, -1.4679127e-01, +-1.6073291e-01, 1.4671586e-01, 1.0000000e+04, 9.7219855e-02, 1.4798698e-01, +-1.2422293e-01, -1.1734926e-01, -1.4729556e-01, 1.4673781e-01, 1.1043258e-01, +1.0000000e+04, -1.7263779e-01, -1.4841602e-01, 1.0000000e+04, 1.5971609e-01, +-1.3664868e-01, -1.7744068e-01, 1.3588434e-01, 1.0000000e+04, 1.4938955e-01, +-1.2519039e-01, -1.6152086e-01, -1.0826153e-01, 1.3512256e-01, 1.0000000e+04, +9.8434055e-02, -1.2401135e-01, -1.0014932e-01, 1.2145607e-01, 1.0000000e+04, +-1.3198740e-01, -1.4729656e-01, 1.0000000e+04, 1.7263779e-01, 1.5909898e-01, +-1.3493007e-01, -1.4607673e-01, 1.3416325e-01, 1.0000000e+04, 1.7744068e-01, +1.0069582e-01, 1.4827035e-01, -1.2310596e-01, -1.4693877e-01, 1.4599851e-01, +1.1041938e-01, 1.6073291e-01, 1.4737777e-01, -1.2247802e-01, -1.3339106e-01, +-1.1933228e-01, 1.4729556e-01, 1.0765585e-01, 1.0000000e+04, 1.6152086e-01, +1.0870423e-01, -1.3065475e-01, 1.2172140e-01, 1.3430757e-01, 1.4899185e-01, +1.4899185e-01, 1.3430757e-01, 1.2172140e-01, -1.3065475e-01, 1.6152086e-01, +1.0870423e-01, 1.0000000e+04, 1.4729556e-01, 1.0765585e-01, -1.1933228e-01, +-1.1043258e-01, 1.3271674e-01, 1.0000000e+04, 1.2401135e-01, -1.4412718e-01, +-9.7219855e-02, -1.3339106e-01, -1.2247802e-01, 1.4737777e-01, 1.6073291e-01, +1.1041938e-01, 1.4599851e-01, -1.4693877e-01, -1.2310596e-01, 1.4827035e-01, +1.7744068e-01, 1.0069582e-01, 1.0000000e+04, 1.3416325e-01, 8.2734975e-02, +7.0710678e+03, 4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.4679127e-01, -1.4798698e-01, -1.6000083e-01, -1.4607673e-01, +-1.3493007e-01, 1.5909898e-01, 1.7263779e-01, 1.0000000e+04, -1.4729656e-01, +1.0000000e+04, 1.3664868e-01, -1.4938955e-01, -1.7580768e-01, -1.6000083e-01, +-1.4798698e-01, 1.4679127e-01, 7.0710678e+03, 4.4721137e+03, 3.1621956e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 8.2734975e-02, -9.7219855e-02, +-1.4412718e-01, 1.2401135e-01, 1.0000000e+04, 1.3271674e-01, -1.1043258e-01, +-1.3512256e-01, 1.0014932e-01, 1.0000000e+04, -1.4673781e-01, -1.7580768e-01, +-1.4938955e-01, 1.3664868e-01, 1.0000000e+04, -1.4673781e-01, 1.0000000e+04, +1.0014932e-01, -1.3512256e-01, -1.4827035e-01, 1.3493007e-01, 1.0000000e+04, +1.7580768e-01, -1.4701368e-01, -1.4737777e-01, 1.4607673e-01, 1.0000000e+04, +9.5863716e-02, 1.6000083e-01, -1.3415792e-01, -1.0069582e-01, 1.0000000e+04, +-1.0765585e-01, -1.2871086e-01, 1.3339106e-01, 1.4693877e-01, 1.0000000e+04, +1.2860539e-01, 1.1566153e-01, 1.4834728e-01, -1.2172140e-01, -1.1041938e-01, +1.3867612e-01, 1.4412718e-01, 1.3213141e-01, -1.0870423e-01, -1.1845977e-01, +1.0000000e+04, 1.4673781e-01, 1.1043258e-01, -1.4729556e-01, -1.1734926e-01, +-1.3430757e-01, 1.6394595e-01, 1.0633205e-01, 1.3065475e-01, 1.0000000e+04, +1.4804153e-01, 1.2247802e-01, -1.4899185e-01, 1.8212204e-01, 1.0798073e-01, +1.1933228e-01, 1.0000000e+04, 1.3508390e-01, 1.2310596e-01, 9.8434055e-02, +1.0000000e+04, 1.3512256e-01, -1.6152086e-01, -1.0826153e-01, -1.2422293e-01, +1.4798698e-01, 9.7219855e-02, 1.0000000e+04, 1.4671586e-01, -1.6073291e-01, +-1.4599851e-01, -1.3416325e-01, -1.2386938e-01, 1.4729656e-01, 1.5983067e-01, +1.7425525e-01, -1.2519039e-01, 1.4938955e-01, 1.0000000e+04, 1.3588434e-01, +-1.7744068e-01, -1.4679127e-01, 1.7189507e-01, 7.0710678e+03, 4.4721137e+03, +3.1621956e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, -1.4790817e-01, +-1.5909898e-01, -1.3664868e-01, 1.5971609e-01, 1.0000000e+04, -1.4841602e-01, +-1.7263779e-01, -8.2734975e-02, -1.4342692e-01, -1.3271674e-01, 1.0783877e-01, +7.0710678e+03, 4.4721137e+03, 3.1621956e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.3198740e-01, 1.0000000e+04, 1.2145607e-01, -1.2401135e-01, +-1.0014932e-01, -1.4834728e-01, 1.3415792e-01, 1.4701368e-01, 1.0000000e+04, +1.1394861e-01, 1.0212614e-01, -9.5863716e-02, -1.3213141e-01, 1.2242478e-01, +1.0000000e+04, 1.4342692e-01, -1.1925800e-01, -1.1566153e-01, 1.4300339e-01, +1.2871086e-01, 1.0000000e+04, 1.2770703e-01, 1.3123181e-01, -1.0633205e-01, +-1.2860539e-01, 1.5910730e-01, 1.1845977e-01, 1.1639930e-01, 1.3314513e-01, +-1.0798073e-01, 1.0000000e+04, 1.3198740e-01, 1.2088866e-01, -1.3867612e-01, +-9.8434055e-02, -1.0742179e-01, 9.4959558e-02, 1.1734926e-01, 1.0000000e+04, +1.4875994e-01, 1.2422293e-01, -1.6394595e-01, -1.4804153e-01, -1.3508390e-01, +1.6304718e-01, 1.7890763e-01, 9.2490697e-02, 1.2386938e-01, 9.7735705e-02, +1.0826153e-01, 1.0000000e+04, 1.3681143e-01, 1.2519039e-01, -1.8212204e-01, +-1.4671586e-01, -1.2562400e-01, 1.4790817e-01, 1.7350735e-01, 1.0000000e+04, +-1.5983067e-01, -1.3588434e-01, -1.2596141e-01, 1.4841602e-01, 1.6044994e-01, +1.0000000e+04, -1.7425525e-01, 7.0710678e+03, 4.4721137e+03, 3.1621956e+03, +7.0710678e+03, 4.4721132e+03, 3.1621939e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, -1.4903125e-01, -1.5971609e-01, -1.7189507e-01, +-1.3131057e-01, -1.2145607e-01, 7.0710678e+03, 4.4721137e+03, 3.1621956e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, -1.0783877e-01, -1.1394861e-01, +-1.3314513e-01, 1.4274260e-01, 1.1925800e-01, 1.0000000e+04, 1.0283622e-01, +-1.0212614e-01, -1.3123181e-01, 1.2796905e-01, 1.0000000e+04, 1.1308694e-01, +-1.2088866e-01, 7.0710678e+03, 4.4721137e+03, 3.1640235e+03, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, 1.3131057e-01, -1.2242478e-01, -1.0824316e-01, +1.0000000e+04, 1.2845172e-01, 1.1872361e-01, -1.4300339e-01, -9.4959558e-02, +-1.2770703e-01, -1.1639930e-01, 1.4206672e-01, 1.5596377e-01, 1.1591788e-01, +-9.2490697e-02, 1.0742179e-01, 1.0000000e+04, 1.1809773e-01, 1.2193486e-01, +-1.5910730e-01, -9.7735705e-02, -1.4875994e-01, 1.7814849e-01, 8.1046541e-02, +1.0000000e+04, 1.2562400e-01, -1.6304718e-01, -1.3681143e-01, 1.6367246e-01, +8.2175907e-02, 1.0000000e+04, 1.2596141e-01, -1.7890763e-01, -1.2772450e-01, +1.4903125e-01, 7.0710678e+03, 4.4758643e+03, 3.1701183e+03, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, -1.6044994e-01, -1.7350735e-01, 4.4721132e+03, +-4.4721132e+03, 7.0710678e+03, -5.1465433e+03, 1.0000000e+04, -4.4758643e+03, +3.1621940e+03, -3.1621939e+03, 5.1465433e+03, 1.0000000e+04, -3.1701183e+03, +-1.2193486e-01, 1.0824316e-01, 7.0710678e+03, 4.4721137e+03, 3.1664528e+03, +1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.0451399e-01, -1.4274260e-01, +-1.1308694e-01, -1.0283622e-01, -1.1591788e-01, 1.2700513e-01, 1.3964801e-01, +1.0000000e+04, -1.1872361e-01, 1.0000000e+04, 1.1385063e-01, -1.2796905e-01, +4.4721137e+03, 1.0000000e+04, 3.1621956e+03, -3.1621955e+03, -3.1640235e+03, +-1.2845172e-01, 1.5524321e-01, 1.0000000e+04, 1.0333071e-01, -1.4206672e-01, +-8.1046541e-02, -1.1809773e-01, 1.4266334e-01, 1.0000000e+04, 1.0463051e-01, +-1.5596377e-01, -8.2175907e-02, 7.0682278e-02, 7.0710678e+03, 4.4807683e+03, +3.1805169e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 1.2772450e-01, +-1.6367246e-01, -1.7814849e-01, 4.4721137e+03, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, -4.4721132e+03, -4.4807683e+03, 3.1621952e+03, 5.1465433e+03, +1.0000000e+04, -3.1621940e+03, -3.1805169e+03, 3.1621955e+03, 4.4721137e+03, +1.0000000e+04, -3.1621952e+03, -3.1664528e+03, -1.0451399e-01, -1.0463051e-01, +1.2758139e-01, 7.0710678e+03, 4.4721137e+03, 3.1640234e+03, 1.0000000e+04, +1.0000000e+04, 1.0000000e+04, -1.3964801e-01, -1.1385063e-01, -1.0333071e-01, +1.3895442e-01, 1.0000000e+04, -1.2700513e-01, 7.0710678e+03, 4.4758646e+03, +3.1701189e+03, 1.0000000e+04, 1.0000000e+04, 1.0000000e+04, 9.1989026e-02, +-1.4266334e-01, -1.5524321e-01, -7.0682278e-02, 7.0710678e+03, -5.1465433e+03, +1.0000000e+04, 4.4721137e+03, -4.4721137e+03, -4.4758646e+03, 5.1465433e+03, +1.0000000e+04, 3.1621952e+03, -3.1621952e+03, -3.1701189e+03, 3.1621952e+03, +-3.1621952e+03, 4.4721137e+03, 1.0000000e+04, -3.1640234e+03, -9.1989026e-02, +7.0710678e+03, 4.4721137e+03, 3.1621952e+03, 1.0000000e+04, 1.0000000e+04, +1.0000000e+04, -1.2758139e-01, -1.3895442e-01 }; + +const int MPT_NC[] = { +9, 5, 10, 5, 10, +6, 6, 4, 6, 10, +5, 5, 10, 6, 6, +6, 5, 6, 5, 6, +6, 10, 5, 5, 10, +6, 6, 6, 7, 6, +6, 6, 6, 6, 6, +6, 9, 5, 6, 13, +6, 7, 7, 6, 7, +4, 10, 6, 5, 10, +6, 5, 5, 5, 5, +5, 6, 7, 6, 7, +6, 7, 6, 6, 7, +10, 6, 4, 10, 6, +4, 4, 4, 5, 6, +4, 7, 6, 5, 7, +7, 5, 6, 6, 5, +10, 5, 10, 5, 6, +6, 7, 6, 6, 6, +6, 6, 6, 6, 13, +9, 6, 5, 10, 5, +6, 6, 6, 6, 10, +6, 5, 10, 6, 4, +5, 6, 6, 10, 6, +5, 5, 10, 5, 10, +6, 5, 5, 9 }; + + +const float MPT_F[] = { +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.3618820e+00, -2.2459502e+02, -3.6852726e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1042831e+00, -2.4457143e+02, -3.9153690e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2841140e+05, -3.8522632e+05, -3.8371043e+03, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.8766090e+00, -2.6492238e+02, -4.1463390e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.7892413e+00, -2.3343210e+02, -3.7323176e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.0032591e+00, -2.1226462e+02, -3.4881232e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.5490076e+00, -2.5331631e+02, +-3.9552799e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.9397388e+00, -2.1042948e+02, -3.4640919e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9124557e+00, -2.0872882e+02, +-3.4249316e+01, -7.3040818e+00, 2.5785773e+02, 4.2310644e+01, 7.4840827e+00, +-2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.5450076e+00, -2.2531786e+02, +-3.6071366e+01, -8.0855186e+00, 2.7835135e+02, 4.4561553e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +3.2153807e+04, -9.6459448e+04, -9.6079874e+02, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.0832974e+04, +-1.5249580e+05, -1.5189572e+03, -6.2797629e+04, 1.8838903e+05, 1.8764771e+03, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.1874573e+00, -2.4174341e+02, -3.7835615e+01, -8.8791830e+00, +2.9864302e+02, 4.6741057e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.2841140e+05, +-2.5682122e+05, -1.2810668e+03, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1903322e+00, -2.4096420e+02, -3.7574805e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3823383e+00, -2.1979587e+02, +-3.5196807e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6226667e+00, +-1.9951011e+02, -3.2892355e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.2779292e+00, -2.1585184e+02, -3.4512289e+01, -7.7555776e+00, +2.6665731e+02, 4.2635513e+01, 5.5241768e+00, -1.9579250e+02, -3.2247525e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, +-2.1832144e+02, -3.4840055e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.6001466e+00, -1.9801127e+02, -3.2538994e+01, -6.9182639e+00, 2.4461757e+02, +4.0197760e+01, 6.9164460e+00, -2.3208992e+02, -3.6238511e+01, -8.5443832e+00, +2.8671738e+02, 4.4768040e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.3848450e+00, -1.9180933e+02, +-3.1733570e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.1042831e+00, +-2.3756088e+02, -3.6959139e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.5432465e+00, -1.9638280e+02, -3.2328552e+01, -6.8479712e+00, +2.4260579e+02, 3.9937786e+01, 6.8607153e+00, -2.3044873e+02, -3.6020404e+01, +-8.4755351e+00, 2.8468990e+02, 4.4498595e+01, 6.0753667e+00, -2.1001053e+02, +-3.3751631e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.9588145e+00, -2.3327526e+02, -3.6389185e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.1643997e+00, -2.1255901e+02, -3.4081082e+01, -7.6153263e+00, +2.6258944e+02, 4.2102813e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.1042831e+00, +-2.4457143e+02, -3.9153690e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.2728415e+04, -3.8184464e+04, -3.8034206e+02, -1.5724327e+04, +4.7172015e+04, 4.6986391e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2841140e+05, -3.8522632e+05, -3.8371043e+03, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.8766090e+00, -2.6492238e+02, -4.1463390e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.0832974e+04, -1.0166532e+05, -5.0712347e+02, -6.2797629e+04, 1.2559449e+05, +6.2648610e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.6155691e+00, -2.2170260e+02, +-3.4571242e+01, -8.1726884e+00, 2.7388516e+02, 4.2708342e+01, 5.8435113e+00, +-2.0173857e+02, -3.2381037e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.1186804e+00, -1.8262040e+02, -3.0258654e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.7075935e+00, -2.2433958e+02, -3.4912636e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.9269319e+00, -2.0411252e+02, -3.2685368e+01, +-7.3219653e+00, 2.5215488e+02, 4.0378586e+01, 5.1959216e+00, -1.8481380e+02, +-3.0538976e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.2673222e+02, -3.5228440e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.0634493e+02, -3.2979210e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.2649152e+00, -1.8681595e+02, -3.0799524e+01, -6.5041284e+00, +2.3078718e+02, 3.8048868e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, -2.3343210e+02, +-3.7323176e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.0032591e+00, +-2.1226462e+02, -3.4881232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.9124557e+00, -2.0289842e+02, -3.2378828e+01, -7.3040818e+00, +2.5065502e+02, 3.9999895e+01, 5.1792514e+00, -1.8356736e+02, -3.0234014e+01, +-6.3983018e+00, 2.2677397e+02, 3.7350252e+01, 7.5490076e+00, -2.5331631e+02, +-3.9552799e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.9397388e+00, -2.1042948e+02, -3.4640919e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.5450076e+00, -2.1885921e+02, -3.4049578e+01, -8.0855186e+00, +2.7037252e+02, 4.2063893e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.0532039e+00, -1.7999621e+02, +-2.9779167e+01, -6.2425863e+00, 2.2236226e+02, 3.6788347e+01, 7.4840827e+00, +-2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.4187419e+00, -2.1517080e+02, -3.3565025e+01, +-7.9295336e+00, 2.6581596e+02, 4.1465290e+01, 5.6581569e+00, -1.9558861e+02, +-3.1433826e+01, -6.9899282e+00, 2.4162467e+02, 3.8832467e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.4840827e+00, -2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 3.2153807e+04, -9.6459448e+04, -9.6079874e+02, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.2841140e+05, +-2.5682122e+05, -1.2810668e+03, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.2065976e+00, -2.0758346e+02, +-3.2304982e+01, -7.6674565e+00, 2.5644278e+02, 3.9908667e+01, 5.4574857e+00, +-1.8841160e+02, -3.0241928e+01, -6.7420246e+00, 2.3275841e+02, 3.7360029e+01, +4.7568922e+00, -1.7013019e+02, -2.8253853e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.2779292e+00, -2.0965654e+02, -3.2575312e+01, -7.7555776e+00, +2.5900380e+02, 4.0242627e+01, 5.5241768e+00, -1.9034559e+02, -3.0493318e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 4.8170813e+00, -1.7186017e+02, +-2.8475776e+01, -5.9508870e+00, 2.1231123e+02, 3.5178174e+01, 7.1903322e+00, +-2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1204296e+02, -3.2880720e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, -1.9248909e+02, +-3.0764691e+01, -6.9182639e+00, 2.3779562e+02, 3.8005836e+01, 4.8873543e+00, +-1.7383837e+02, -2.8725374e+01, -6.0377003e+00, 2.1475504e+02, 3.5486521e+01, +7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.3618820e+00, -2.2459502e+02, -3.6852726e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1832144e+02, -3.4840055e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, -1.9801127e+02, +-3.2538994e+01, -6.9182639e+00, 2.4461757e+02, 4.0197760e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.2779292e+00, -2.1585184e+02, -3.4512289e+01, -7.7555776e+00, 2.6665731e+02, +4.2635513e+01, 5.5241768e+00, -1.9579250e+02, -3.2247525e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, +-2.2459502e+02, -3.6852726e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.1042831e+00, -2.3756088e+02, -3.6959139e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.5432465e+00, -1.9638280e+02, -3.2328552e+01, +-6.8479712e+00, 2.4260579e+02, 3.9937786e+01, 6.9164460e+00, -2.3208992e+02, +-3.6238511e+01, -8.5443832e+00, 2.8671738e+02, 4.4768040e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.3848450e+00, -1.9180933e+02, -3.1733570e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1042831e+00, -2.4457143e+02, -3.9153690e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.9588145e+00, +-2.3327526e+02, -3.6389185e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.1643997e+00, -2.1255901e+02, -3.4081082e+01, -7.6153263e+00, 2.6258944e+02, +4.2102813e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.8607153e+00, -2.3044873e+02, -3.6020404e+01, +-8.4755351e+00, 2.8468990e+02, 4.4498595e+01, 6.0753667e+00, -2.1001053e+02, +-3.3751631e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.8766090e+00, -2.6492238e+02, -4.1463390e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.3343210e+02, -3.7323176e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.1226462e+02, -3.4881232e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.7075935e+00, -2.2433958e+02, -3.4912636e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.9269319e+00, -2.0411252e+02, -3.2685368e+01, +-7.3219653e+00, 2.5215488e+02, 4.0378586e+01, 5.1959216e+00, -1.8481380e+02, +-3.0538976e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.2673222e+02, -3.5228440e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.0634493e+02, -3.2979210e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.2649152e+00, -1.8681595e+02, -3.0799524e+01, -6.5041284e+00, +2.3078718e+02, 3.8048868e+01, 6.6155691e+00, -2.2170260e+02, -3.4571242e+01, +-8.1726884e+00, 2.7388516e+02, 4.2708342e+01, 5.8435113e+00, -2.0173857e+02, +-3.2381037e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.1186804e+00, +-1.8262040e+02, -3.0258654e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.9124557e+00, -1.9706348e+02, -3.0557908e+01, -7.3040818e+00, 2.4344669e+02, +3.7750381e+01, 5.1792514e+00, -1.7846056e+02, -2.8589338e+01, -6.3983018e+00, +2.2046517e+02, 3.5318466e+01, 4.4939680e+00, -1.6072671e+02, -2.6692199e+01, +-5.5517219e+00, 1.9855727e+02, 3.2974793e+01, 6.6155691e+00, -2.2170260e+02, +-3.4571242e+01, -8.1726884e+00, 2.7388516e+02, 4.2708342e+01, 5.8435113e+00, +-2.0173857e+02, -3.2381037e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.1186804e+00, -1.8262040e+02, -3.0258654e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.5490076e+00, -2.5331631e+02, -3.9552799e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9397388e+00, -2.1042948e+02, +-3.4640919e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.2673222e+02, -3.5228440e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.0634493e+02, -3.2979210e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.2649152e+00, -1.8681595e+02, -3.0799524e+01, -6.5041284e+00, +2.3078718e+02, 3.8048868e+01, 6.7075935e+00, -2.2433958e+02, -3.4912636e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9269319e+00, -2.0411252e+02, +-3.2685368e+01, -7.3219653e+00, 2.5215488e+02, 4.0378586e+01, 5.1959216e+00, +-1.8481380e+02, -3.0538976e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.9124557e+00, -2.0872882e+02, -3.4249316e+01, +-7.3040818e+00, 2.5785773e+02, 4.2310644e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, +-2.3343210e+02, -3.7323176e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.0032591e+00, -2.1226462e+02, -3.4881232e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.5450076e+00, -2.2531786e+02, -3.6071366e+01, +-8.0855186e+00, 2.7835135e+02, 4.4561553e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.9124557e+00, -2.0872882e+02, -3.4249316e+01, -7.3040818e+00, +2.5785773e+02, 4.2310644e+01, 7.5490076e+00, -2.5331631e+02, -3.9552799e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9397388e+00, +-2.1042948e+02, -3.4640919e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.1874573e+00, -2.4174341e+02, -3.7835615e+01, -8.8791830e+00, 2.9864302e+02, +4.6741057e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.5450076e+00, +-2.2531786e+02, -3.6071366e+01, -8.0855186e+00, 2.7835135e+02, 4.4561553e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.1874573e+00, -2.4174341e+02, -3.7835615e+01, -8.8791830e+00, +2.9864302e+02, 4.6741057e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.2779292e+00, -2.1585184e+02, -3.4512289e+01, -7.7555776e+00, 2.6665731e+02, +4.2635513e+01, 5.5241768e+00, -1.9579250e+02, -3.2247525e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1832144e+02, +-3.4840055e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, +-1.9801127e+02, -3.2538994e+01, -6.9182639e+00, 2.4461757e+02, 4.0197760e+01, +7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1204296e+02, +-3.2880720e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, +-1.9248909e+02, -3.0764691e+01, -6.9182639e+00, 2.3779562e+02, 3.8005836e+01, +4.8873543e+00, -1.7383837e+02, -2.8725374e+01, -6.0377003e+00, 2.1475504e+02, +3.5486521e+01, 7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, +-3.2892355e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.9164460e+00, +-2.3208992e+02, -3.6238511e+01, -8.5443832e+00, 2.8671738e+02, 4.4768040e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.3848450e+00, -1.9180933e+02, -3.1733570e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.2779292e+00, -2.0965654e+02, -3.2575312e+01, +-7.7555776e+00, 2.5900380e+02, 4.0242627e+01, 5.5241768e+00, -1.9034559e+02, +-3.0493318e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 4.8170813e+00, +-1.7186017e+02, -2.8475776e+01, -5.9508870e+00, 2.1231123e+02, 3.5178174e+01, +6.2065976e+00, -2.0758346e+02, -3.2304982e+01, -7.6674565e+00, 2.5644278e+02, +3.9908667e+01, 5.4574857e+00, -1.8841160e+02, -3.0241928e+01, -6.7420246e+00, +2.3275841e+02, 3.7360029e+01, 4.7568922e+00, -1.7013019e+02, -2.8253853e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.8607153e+00, -2.3044873e+02, +-3.6020404e+01, -8.4755351e+00, 2.8468990e+02, 4.4498595e+01, 6.0753667e+00, +-2.1001053e+02, -3.3751631e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.1042831e+00, -2.3756088e+02, -3.6959139e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.5432465e+00, -1.9638280e+02, +-3.2328552e+01, -6.8479712e+00, 2.4260579e+02, 3.9937786e+01, 7.1903322e+00, +-2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.9588145e+00, -2.3327526e+02, -3.6389185e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.1643997e+00, -2.1255901e+02, +-3.4081082e+01, -7.6153263e+00, 2.6258944e+02, 4.2102813e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.2459502e+02, -3.6852726e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.1042831e+00, +-2.4457143e+02, -3.9153690e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.2459502e+02, +-3.6852726e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.8766090e+00, +-2.6492238e+02, -4.1463390e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9124557e+00, -2.0289842e+02, +-3.2378828e+01, -7.3040818e+00, 2.5065502e+02, 3.9999895e+01, 5.1792514e+00, +-1.8356736e+02, -3.0234014e+01, -6.3983018e+00, 2.2677397e+02, 3.7350252e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.7892413e+00, -2.3343210e+02, -3.7323176e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.0032591e+00, -2.1226462e+02, -3.4881232e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.7892413e+00, -2.2673222e+02, +-3.5228440e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.0032591e+00, +-2.0634493e+02, -3.2979210e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.2649152e+00, -1.8681595e+02, -3.0799524e+01, -6.5041284e+00, 2.3078718e+02, +3.8048868e+01, 6.7075935e+00, -2.2433958e+02, -3.4912636e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.9269319e+00, -2.0411252e+02, -3.2685368e+01, +-7.3219653e+00, 2.5215488e+02, 4.0378586e+01, 5.1959216e+00, -1.8481380e+02, +-3.0538976e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.4840827e+00, +-2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.5450076e+00, -2.1885921e+02, -3.4049578e+01, +-8.0855186e+00, 2.7037252e+02, 4.2063893e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.0532039e+00, +-1.7999621e+02, -2.9779167e+01, -6.2425863e+00, 2.2236226e+02, 3.6788347e+01, +6.6155691e+00, -2.2170260e+02, -3.4571242e+01, -8.1726884e+00, 2.7388516e+02, +4.2708342e+01, 5.8435113e+00, -2.0173857e+02, -3.2381037e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.1186804e+00, -1.8262040e+02, -3.0258654e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.4187419e+00, -2.1517080e+02, +-3.3565025e+01, -7.9295336e+00, 2.6581596e+02, 4.1465290e+01, 5.6581569e+00, +-1.9558861e+02, -3.1433826e+01, -6.9899282e+00, 2.4162467e+02, 3.8832467e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.5490076e+00, -2.5331631e+02, -3.9552799e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9397388e+00, -2.1042948e+02, +-3.4640919e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.4840827e+00, +-2.5138740e+02, -3.9293232e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.6599679e+00, -2.2964705e+02, -3.6820928e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.2779292e+00, +-2.1585184e+02, -3.4512289e+01, -7.7555776e+00, 2.6665731e+02, 4.2635513e+01, +5.5241768e+00, -1.9579250e+02, -3.2247525e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.3618820e+00, -2.1832144e+02, -3.4840055e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.6001466e+00, -1.9801127e+02, +-3.2538994e+01, -6.9182639e+00, 2.4461757e+02, 4.0197760e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +7.1042831e+00, -2.4457143e+02, -3.9153690e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1042831e+00, -2.3756088e+02, -3.6959139e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.5432465e+00, +-1.9638280e+02, -3.2328552e+01, -6.8479712e+00, 2.4260579e+02, 3.9937786e+01, +7.1903322e+00, -2.4096420e+02, -3.7574805e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3823383e+00, -2.1979587e+02, -3.5196807e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.6226667e+00, -1.9951011e+02, -3.2892355e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.9588145e+00, -2.3327526e+02, +-3.6389185e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.1643997e+00, +-2.1255901e+02, -3.4081082e+01, -7.6153263e+00, 2.6258944e+02, 4.2102813e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.9164460e+00, -2.3208992e+02, -3.6238511e+01, -8.5443832e+00, +2.8671738e+02, 4.4768040e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.3848450e+00, -1.9180933e+02, +-3.1733570e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 6.8607153e+00, +-2.3044873e+02, -3.6020404e+01, -8.4755351e+00, 2.8468990e+02, 4.4498595e+01, +6.0753667e+00, -2.1001053e+02, -3.3751631e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.8766090e+00, -2.6492238e+02, -4.1463390e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2841140e+05, -2.5682122e+05, -1.2810668e+03, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 3.2153807e+04, -9.6459448e+04, +-9.6079874e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.5450076e+00, -2.2531786e+02, -3.6071366e+01, +-8.0855186e+00, 2.7835135e+02, 4.4561553e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +6.7892413e+00, -2.3343210e+02, -3.7323176e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.0032591e+00, -2.1226462e+02, -3.4881232e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.9124557e+00, +-2.0872882e+02, -3.4249316e+01, -7.3040818e+00, 2.5785773e+02, 4.2310644e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 1.2841140e+05, -3.8522632e+05, -3.8371043e+03, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.5490076e+00, -2.5331631e+02, +-3.9552799e+01, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +5.9397388e+00, -2.1042948e+02, -3.4640919e+01, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 7.4840827e+00, -2.5138740e+02, -3.9293232e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 6.6599679e+00, -2.2964705e+02, -3.6820928e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 7.1874573e+00, +-2.4174341e+02, -3.7835615e+01, -8.8791830e+00, 2.9864302e+02, 4.6741057e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 5.0832974e+04, -1.0166532e+05, -5.0712347e+02, +-6.2797629e+04, 1.2559449e+05, 6.2648610e+02, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2728415e+04, -3.8184464e+04, -3.8034206e+02, -1.5724327e+04, 4.7172015e+04, +4.6986391e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 5.0832974e+04, +-1.5249580e+05, -1.5189572e+03, -6.2797629e+04, 1.8838903e+05, 1.8764771e+03, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.1042831e+00, -2.4457143e+02, -3.9153690e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 6.3618820e+00, -2.2459502e+02, -3.6852726e+01, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 7.8766090e+00, -2.6492238e+02, -4.1463390e+01, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +1.2841140e+05, -2.5682122e+05, -1.2810668e+03, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 3.2153807e+04, -9.6459448e+04, +-9.6079874e+02, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 1.2841140e+05, -3.8522632e+05, -3.8371043e+03, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00 }; + + +const float MPT_G[] = { +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-1.6381611e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -1.6130791e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +1.2841142e+09, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -5.3227337e+00, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.6017534e-02, -3.0000000e+01, -5.1591655e-02, +-3.0000000e+01, -3.4960128e+00, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-3.1202736e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 1.9308683e-01, -2.3853405e-01, -3.3663248e+00, 3.0000000e+01, +-3.1942680e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 4.2564978e-01, -5.2583579e-01, 3.0000000e+01, -3.0000000e+01, +3.2153809e+08, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 5.0832984e+08, -6.2797642e+08, +3.0000000e+01, -3.0000000e+01, -6.9817364e+00, 8.6250411e+00, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 1.2841141e+09, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -1.7181011e+00, +3.0000000e+01, -1.6364983e+00, -3.0000000e+01, -1.5485846e+00, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 1.7955880e+00, -2.2182191e+00, 1.6645618e+00, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 1.6963948e+00, -3.0000000e+01, +1.5825300e+00, -1.9550131e+00, -5.2379373e+00, 6.4708007e+00, 3.0000000e+01, +-3.0000000e+01, -4.6483190e+00, -3.0000000e+01, -1.4441660e+00, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, -1.2909582e+00, 1.5948135e+00, -5.1086242e+00, +6.3110510e+00, -4.8282165e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-1.1991136e+00, 3.0000000e+01, -1.1495962e+00, 1.4201789e+00, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 2.5371228e+00, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 1.2728415e+08, -1.5724326e+08, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +1.2841143e+09, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -9.9795922e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +5.0832974e+08, -6.2797629e+08, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.5219333e+00, 4.3508976e+00, -3.3275489e+00, -3.0000000e+01, +-3.1302912e+00, -3.0000000e+01, 2.4245252e-01, 3.0000000e+01, 2.1305034e-01, +-2.6319640e-01, 1.8456136e-01, -3.0000000e+01, 1.2467036e-01, 3.0000000e+01, +1.0514253e-01, -3.0000000e+01, 9.5068259e-02, -1.1744466e-01, -3.0000000e+01, +3.0000000e+01, 3.9196804e+00, 3.0000000e+01, 3.6547656e+00, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 3.2920777e+00, -4.0669404e+00, 3.0769136e+00, +-3.8011327e+00, -7.9379602e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-7.0168247e+00, -3.0000000e+01, -3.2422172e+00, 4.0053442e+00, 3.0000000e+01, +-3.0000000e+01, -2.8664279e+00, 3.5411046e+00, -7.7792671e+00, -3.0000000e+01, +-7.3327762e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -2.9907429e+00, +3.6946798e+00, -2.8289988e+00, 3.4948657e+00, 3.0000000e+01, -3.0000000e+01, +7.7218343e-01, 3.0000000e+01, 7.1023890e-01, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.2153802e+08, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 1.2841140e+09, -3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-5.9377393e+00, -3.0000000e+01, -5.5923108e+00, -3.0000000e+01, -5.2486125e+00, +-3.0000000e+01, -1.5894631e+00, 1.9635780e+00, -1.5035024e+00, 1.8573847e+00, +-1.4207708e+00, -3.0000000e+01, -1.7136118e+00, 2.1169480e+00, -1.6172667e+00, +-3.0000000e+01, -1.5149956e+00, 1.8715830e+00, 2.2377114e+00, 3.0000000e+01, +2.0953391e+00, 3.0000000e+01, 1.9483870e+00, -3.0000000e+01, 1.8459251e+00, +3.0000000e+01, 1.7287396e+00, -2.1356364e+00, 1.6157524e+00, -1.9960552e+00, +1.9819268e+00, 3.0000000e+01, 1.8604734e+00, -3.0000000e+01, 1.7516409e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +5.4464788e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 5.3882451e+00, +3.0000000e+01, 5.0400093e+00, -6.2262860e+00, -3.0000000e+01, 3.0000000e+01, +5.2228117e+00, -6.4521150e+00, 4.8990951e+00, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -9.1383290e+00, -3.0000000e+01, +-5.5943680e+00, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -4.9274050e+00, +6.0871778e+00, -1.6678938e+00, 2.0604692e+00, 3.0000000e+01, -3.0000000e+01, +-1.4607834e+00, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -9.5756569e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -5.2856540e+00, -3.0000000e+01, +-4.9801580e+00, 6.1523474e+00, 3.0000000e+01, -3.0000000e+01, -1.3148224e+00, +1.6242947e+00, -1.2469793e+00, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +2.5821883e+00, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -7.6260377e+00, -3.0000000e+01, +-7.1508378e+00, -3.0000000e+01, -3.6779812e+00, -3.0000000e+01, -3.4604985e+00, +4.2750027e+00, -3.2509673e+00, -3.0000000e+01, -3.8310276e+00, -3.0000000e+01, +-3.6012147e+00, -3.0000000e+01, -3.3695393e+00, 4.1626342e+00, 1.1766914e-01, +-1.4536516e-01, 1.0784894e-01, 3.0000000e+01, 8.9408793e-02, -3.0000000e+01, +-3.5527137e-15, 0.0000000e+00, 7.1054274e-15, 0.0000000e+00, -3.5527137e-15, +0.0000000e+00, -1.1766914e-01, 1.4536516e-01, -1.0784894e-01, -3.0000000e+01, +-8.9408793e-02, 3.0000000e+01, 4.0414091e+00, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.5428710e+00, -3.0000000e+01, 3.8310276e+00, 3.0000000e+01, +3.6012147e+00, 3.0000000e+01, 3.3695393e+00, -4.1626342e+00, 3.6779812e+00, +3.0000000e+01, 3.4604985e+00, -4.2750027e+00, 3.2509673e+00, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 6.7772422e+00, +-8.3724148e+00, -3.0000000e+01, 3.0000000e+01, 7.6260377e+00, 3.0000000e+01, +7.1508378e+00, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 6.9100842e+00, +-8.5365241e+00, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, -3.0000000e+01, -6.7772422e+00, 8.3724148e+00, -4.0414091e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.5428710e+00, 3.0000000e+01, +-2.3155684e-01, 2.8605882e-01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -6.9100842e+00, 8.5365241e+00, +3.0000000e+01, -3.0000000e+01, 2.3155684e-01, -2.8605882e-01, -3.0000000e+01, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-5.2228117e+00, 6.4521150e+00, -4.8990951e+00, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -5.3882451e+00, -3.0000000e+01, -5.0400093e+00, 6.2262860e+00, +-1.9819268e+00, -3.0000000e+01, -1.8604734e+00, 3.0000000e+01, -1.7516409e+00, +-3.0000000e+01, -1.8459251e+00, -3.0000000e+01, -1.7287396e+00, 2.1356364e+00, +-1.6157524e+00, 1.9960552e+00, -2.2377114e+00, -3.0000000e+01, -2.0953391e+00, +-3.0000000e+01, -1.9483870e+00, 3.0000000e+01, 1.6678938e+00, -2.0604692e+00, +-3.0000000e+01, 3.0000000e+01, 1.4607834e+00, -3.0000000e+01, 1.7136118e+00, +-2.1169480e+00, 1.6172667e+00, 3.0000000e+01, 1.5149956e+00, -1.8715830e+00, +1.5894631e+00, -1.9635780e+00, 1.5035024e+00, -1.8573847e+00, 1.4207708e+00, +3.0000000e+01, 1.3148224e+00, -1.6242947e+00, 1.2469793e+00, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 5.5943680e+00, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 4.9274050e+00, -6.0871778e+00, 5.9377393e+00, 3.0000000e+01, +5.5923108e+00, 3.0000000e+01, 5.2486125e+00, 3.0000000e+01, 5.2856540e+00, +3.0000000e+01, 4.9801580e+00, -6.1523474e+00, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 9.1383290e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 9.5756569e+00, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -5.4464788e+00, 3.0000000e+01, -2.5821883e+00, -3.0000000e+01, +3.0000000e+01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.2920777e+00, 4.0669404e+00, -3.0769136e+00, 3.8011327e+00, +3.0000000e+01, -3.0000000e+01, -3.9196804e+00, -3.0000000e+01, -3.6547656e+00, +3.0000000e+01, -1.2467036e-01, -3.0000000e+01, -1.0514253e-01, 3.0000000e+01, +-9.5068259e-02, 1.1744466e-01, -2.4245252e-01, -3.0000000e+01, -2.1305034e-01, +2.6319640e-01, -1.8456136e-01, 3.0000000e+01, -7.7218343e-01, -3.0000000e+01, +-7.1023890e-01, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.2422172e+00, +-4.0053442e+00, -3.0000000e+01, 3.0000000e+01, 2.8664279e+00, -3.5411046e+00, +3.5219333e+00, -4.3508976e+00, 3.3275489e+00, 3.0000000e+01, 3.1302912e+00, +3.0000000e+01, 2.9907429e+00, -3.6946798e+00, 2.8289988e+00, -3.4948657e+00, +-3.0000000e+01, 3.0000000e+01, 7.9379602e+00, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 7.0168247e+00, 3.0000000e+01, 7.7792671e+00, 3.0000000e+01, +7.3327762e+00, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -1.7955880e+00, 2.2182191e+00, +-1.6645618e+00, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -1.6963948e+00, +3.0000000e+01, -1.5825300e+00, 1.9550131e+00, 3.0000000e+01, -3.0000000e+01, +-2.5371228e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 1.4441660e+00, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 1.2909582e+00, -1.5948135e+00, +1.7181011e+00, -3.0000000e+01, 1.6364983e+00, 3.0000000e+01, 1.5485846e+00, +3.0000000e+01, 1.1991136e+00, -3.0000000e+01, 1.1495962e+00, -1.4201789e+00, +-3.0000000e+01, 3.0000000e+01, 5.2379373e+00, -6.4708007e+00, -3.0000000e+01, +3.0000000e+01, 4.6483190e+00, 3.0000000e+01, 5.1086242e+00, -6.3110510e+00, +4.8282165e+00, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 9.9795922e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-1.2841140e+09, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, -3.2153802e+08, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -4.2564978e-01, +5.2583579e-01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.6017534e-02, 3.0000000e+01, 5.1591655e-02, 3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -1.9308683e-01, 2.3853405e-01, +3.0000000e+01, -3.0000000e+01, -1.2841143e+09, -3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.4960128e+00, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +3.1202736e+00, 3.0000000e+01, 3.3663248e+00, -3.0000000e+01, 3.1942680e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 6.9817364e+00, -8.6250411e+00, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -5.0832974e+08, +6.2797629e+08, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-1.2728415e+08, 1.5724326e+08, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -5.0832984e+08, 6.2797642e+08, +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 1.6130791e+00, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 1.6381611e+00, 3.0000000e+01, 5.3227337e+00, +-3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-1.2841141e+09, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +3.0000000e+01, -3.2153809e+08, -3.0000000e+01, -3.0000000e+01, 3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, -1.2841142e+09, +3.0000000e+01, -3.0000000e+01, 3.0000000e+01, 3.0000000e+01, -3.0000000e+01, +-3.0000000e+01, 3.0000000e+01, -3.0000000e+01, 3.0000000e+01 }; + diff --git a/matlab/examples/BicopShield/BicopShield_Ident/BicopShield_GreyboxModel_LinearSS.mat b/matlab/examples/BicopShield/BicopShield_Ident/BicopShield_GreyboxModel_LinearSS.mat new file mode 100644 index 00000000..6e330b26 Binary files /dev/null and b/matlab/examples/BicopShield/BicopShield_Ident/BicopShield_GreyboxModel_LinearSS.mat differ diff --git a/matlab/examples/BicopShield/BicopShield_Ident/BicopShield_Ident.m b/matlab/examples/BicopShield/BicopShield_Ident/BicopShield_Ident.m new file mode 100644 index 00000000..b7482751 --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_Ident/BicopShield_Ident.m @@ -0,0 +1,85 @@ +clear all; close all; clc; +%% Data preprocessing +readtable pid1.csv ; %_Load data +down_const = 5; +y=downsample(ans.Var1,down_const); % Output +ref=ans.Var2; % Reference +u1=downsample(ans.Var3,down_const); % motor1 input +u2=downsample(ans.Var4,down_const); % motor2 input +u=ans.Var5; % PID output + +u1=0.05*u1; +u2=0.05*u2; + +Ts = 0.01*down_const; %_Sample time +y_rad=deg2rad(y); +y_v=gradient(y_rad,Ts); +%% +data = iddata([lowpass(y_rad,0.001), lowpass(y_v,0.001)],[lowpass(u1.^2,0.001),lowpass(u2.^2,0.001)],Ts,'Name','Experiment'); %_Identification data object +data = data(2600:3000); +% data.InputName = {'Input Voltage Motor 1','Input Volage Motor 2'}; %_Input name +% data.InputUnit = {'V','V'}; %_Input unit +% data.OutputName = {'Angle'}; %_Output name +% data.OutputUnit = {'Degree'}; %_Output unit +% data.Tstart = 0; %_Starting time +% data.TimeUnit = 's'; %_Time unit + +%% Initial guess of model parameters +J = 0.5; %_Moment of inertia +b = 0.23; %_Viscous friction constant +l1= 0.125; % Length of arm 1 +l2= 0.125; % Length of arm 2 +k=0.12 ; % Wire +k1 = 0.28; % Motor constant + + %_StateSpace Model + A = [0 1; % State-transition matrix + k/J -b/J]; + + B = [ 0 0; + k1*l1/J -k1*l2/J]; % Input matrix + + C = [1 0; 0 1]; % Output matrix + D = [0 0; 0 0]; % No direct feed-through + K = zeros(2,2); % Disturbance + x0 = [0,0]; %_Initial condition + disp('Initial guess:') + sys = idss(A,B,C,D,K,x0,0.0); %continuous %_Initial State Space Model + sys.Structure.A.Free = [0 0; %_A variables - free + 1 1]; + sys.Structure.B.Free = [0 0; + 1 1]; %_B variables + sys.Structure.C.Free = false; %_C fixed + sys.Structure.D.Free = false; %_D fixed + sys.Structure.A.Minimum = [0 0 ; + -inf -10]; + sys.Structure.B.Minimum = [0 0; + 0.0 -inf]; + sys.DisturbanceModel = 'none'; % Estimate disturbance model + sys.InitialState = 'estimate'; % Estimate initial states + compare(data,sys) + %% + Options = ssestOptions; % State-space estimation options + Options.InputInterSample = 'zoh'; + Options.EnforceStability = true; + Options.Display = 'on'; % Show progress + Options.Focus = 'simulation'; % Focus on simulation + Options.SearchOptions.MaxIterations = 300; % Max iterations + Options.SearchMethod = 'auto'; + Options.InitialState = 'auto'; % Estimate initial condition + + Options.N4Weight = 'MOESP'; + Options.N4Horizon = [50 50 50]; + disp('Estimated model:') + model = ssest(data,sys,Options); % Identified Model + %% +comopt = compareOptions('InitialCondition','z'); +figure +compare(data,model) % Data/Model Comparison +grid on + +save BicopShield_GreyboxModel_LinearSS model +%% + + +[xhat, yhat] = estimateKalmanState(U(:,k), Y, A, B, C, Q_Kalman, R_Kalman, xICWhole); \ No newline at end of file diff --git a/matlab/examples/BicopShield/BicopShield_Ident/pid1.csv b/matlab/examples/BicopShield/BicopShield_Ident/pid1.csv new file mode 100644 index 00000000..48c77ebf --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_Ident/pid1.csv @@ -0,0 +1,23999 @@ +0.00, 10.00, 57.58, 42.43, 15.15 +0.00, 10.00, 57.61, 42.39, 15.23 +0.00, 10.00, 57.65, 42.35, 15.30 +0.00, 10.00, 57.69, 42.31, 15.38 +0.00, 10.00, 57.72, 42.28, 15.45 +0.00, 10.00, 57.76, 42.24, 15.52 +0.00, 10.00, 57.80, 42.20, 15.60 +0.00, 10.00, 57.84, 42.16, 15.68 +0.00, 10.00, 57.88, 42.13, 15.75 +0.00, 10.00, 57.91, 42.09, 15.82 +0.00, 10.00, 57.95, 42.05, 15.90 +0.00, 10.00, 57.99, 42.01, 15.98 +0.07, 10.00, 55.50, 44.50, 11.01 +0.07, 10.00, 58.01, 41.99, 16.03 +0.00, 10.00, 60.57, 39.43, 21.14 +0.00, 10.00, 58.14, 41.86, 16.27 +0.00, 10.00, 58.17, 41.83, 16.35 +0.00, 10.00, 58.21, 41.79, 16.42 +0.00, 10.00, 58.25, 41.75, 16.50 +0.00, 10.00, 58.29, 41.71, 16.57 +0.00, 10.00, 58.32, 41.68, 16.65 +0.00, 10.00, 58.36, 41.64, 16.72 +0.00, 10.00, 58.40, 41.60, 16.80 +0.07, 10.00, 55.92, 44.08, 11.83 +0.07, 10.00, 58.42, 41.58, 16.85 +0.07, 10.00, 58.46, 41.54, 16.92 +0.07, 10.00, 58.50, 41.50, 17.00 +0.07, 10.00, 58.54, 41.46, 17.07 +0.07, 10.00, 58.57, 41.43, 17.15 +0.07, 10.00, 58.61, 41.39, 17.22 +0.07, 10.00, 58.65, 41.35, 17.30 +0.07, 10.00, 58.69, 41.31, 17.37 +0.07, 10.00, 58.72, 41.28, 17.45 +0.07, 10.00, 58.76, 41.24, 17.52 +0.07, 10.00, 58.80, 41.20, 17.59 +0.07, 10.00, 58.83, 41.17, 17.67 +0.07, 10.00, 58.87, 41.13, 17.74 +0.07, 10.00, 58.91, 41.09, 17.82 +0.07, 10.00, 58.95, 41.05, 17.89 +0.13, 10.00, 56.46, 43.54, 12.92 +0.13, 10.00, 58.97, 41.03, 17.94 +0.13, 10.00, 59.01, 40.99, 18.02 +0.13, 10.00, 59.04, 40.96, 18.09 +0.13, 10.00, 59.08, 40.92, 18.16 +0.13, 10.00, 59.12, 40.88, 18.24 +0.26, 10.00, 54.11, 45.89, 8.22 +0.26, 10.00, 59.09, 40.91, 18.19 +0.33, 10.00, 56.61, 43.39, 13.22 +0.33, 10.00, 59.12, 40.88, 18.23 +0.40, 10.00, 56.63, 43.37, 13.26 +0.40, 10.00, 59.14, 40.86, 18.28 +0.53, 10.00, 54.13, 45.87, 8.26 +0.53, 10.00, 59.11, 40.89, 18.22 +0.59, 10.00, 56.62, 43.38, 13.25 +0.66, 10.00, 56.61, 43.39, 13.22 +0.79, 10.00, 54.07, 45.93, 8.15 +0.86, 10.00, 56.53, 43.47, 13.06 +0.92, 10.00, 56.52, 43.48, 13.03 +1.05, 10.00, 53.98, 46.02, 7.96 +1.12, 10.00, 56.43, 43.57, 12.87 +1.32, 10.00, 51.37, 48.63, 2.75 +1.38, 10.00, 56.30, 43.70, 12.60 +1.45, 10.00, 56.28, 43.72, 12.57 +1.65, 10.00, 51.22, 48.78, 2.45 +1.71, 10.00, 56.15, 43.85, 12.30 +1.91, 10.00, 51.09, 48.91, 2.17 +1.98, 10.00, 56.01, 43.99, 12.02 +2.18, 10.00, 50.95, 49.05, 1.90 +2.37, 10.00, 50.83, 49.17, 1.66 +2.44, 10.00, 55.75, 44.25, 11.50 +2.64, 10.00, 50.69, 49.31, 1.37 +2.77, 10.00, 53.09, 46.91, 6.17 +2.97, 10.00, 50.49, 49.51, 0.99 +3.03, 10.00, 55.41, 44.59, 10.83 +3.23, 10.00, 50.35, 49.65, 0.69 +3.43, 10.00, 50.22, 49.78, 0.45 +3.69, 10.00, 47.58, 52.42, -4.85 +3.76, 10.00, 54.97, 45.03, 9.93 +4.02, 10.00, 47.38, 52.62, -5.25 +4.09, 10.00, 54.76, 45.24, 9.53 +4.28, 10.00, 49.69, 50.31, -0.61 +4.55, 10.00, 47.04, 52.96, -5.91 +4.75, 10.00, 49.39, 50.61, -1.23 +4.88, 10.00, 51.78, 48.22, 3.56 +5.08, 10.00, 49.18, 50.82, -1.64 +5.27, 10.00, 49.05, 50.95, -1.91 +5.41, 10.00, 51.44, 48.56, 2.88 +5.60, 10.00, 48.83, 51.17, -2.33 +5.80, 10.00, 48.70, 51.30, -2.60 +5.93, 10.00, 51.09, 48.91, 2.18 +6.13, 10.00, 48.48, 51.52, -3.03 +6.33, 10.00, 48.35, 51.65, -3.30 +6.46, 10.00, 50.74, 49.26, 1.47 +6.66, 10.00, 48.13, 51.87, -3.74 +6.86, 10.00, 47.99, 52.01, -4.02 +6.99, 10.00, 50.38, 49.62, 0.75 +7.19, 10.00, 47.77, 52.23, -4.47 +7.38, 10.00, 47.63, 52.37, -4.74 +7.51, 10.00, 50.01, 49.99, 0.02 +7.71, 10.00, 47.40, 52.60, -5.20 +7.91, 10.00, 47.26, 52.74, -5.48 +8.04, 10.00, 49.64, 50.36, -0.72 +8.24, 10.00, 47.02, 52.98, -5.95 +8.31, 10.00, 51.93, 48.07, 3.85 +8.50, 10.00, 46.84, 53.16, -6.32 +8.70, 10.00, 46.70, 53.30, -6.61 +8.77, 10.00, 51.59, 48.41, 3.19 +8.96, 10.00, 46.51, 53.49, -6.99 +9.03, 10.00, 51.40, 48.60, 2.81 +9.23, 10.00, 46.31, 53.69, -7.37 +9.36, 10.00, 48.69, 51.31, -2.62 +9.49, 10.00, 48.59, 51.41, -2.81 +9.62, 10.00, 48.50, 51.50, -3.01 +9.76, 10.00, 48.40, 51.60, -3.20 +9.89, 10.00, 48.30, 51.70, -3.40 +10.02, 10.00, 48.20, 51.80, -3.60 +10.09, 10.00, 50.62, 49.38, 1.25 +10.28, 10.00, 45.53, 54.47, -8.94 +10.35, 10.00, 50.42, 49.58, 0.84 +10.42, 10.00, 50.37, 49.63, 0.74 +10.55, 10.00, 47.80, 52.20, -4.40 +10.61, 10.00, 50.22, 49.78, 0.44 +10.68, 10.00, 50.17, 49.83, 0.33 +10.81, 10.00, 47.59, 52.41, -4.81 +10.88, 10.00, 50.01, 49.99, 0.02 +10.94, 10.00, 49.96, 50.04, -0.08 +11.07, 10.00, 47.38, 52.62, -5.23 +11.14, 10.00, 49.80, 50.20, -0.39 +11.21, 10.00, 49.75, 50.25, -0.50 +11.34, 10.00, 47.17, 52.83, -5.65 +11.40, 10.00, 49.59, 50.41, -0.82 +11.47, 10.00, 49.54, 50.46, -0.93 +11.47, 10.00, 52.00, 48.00, 4.00 +11.60, 10.00, 46.95, 53.05, -6.09 +11.67, 10.00, 49.37, 50.63, -1.26 +11.73, 10.00, 49.31, 50.69, -1.37 +11.73, 10.00, 51.78, 48.22, 3.56 +11.87, 10.00, 46.73, 53.27, -6.54 +11.87, 10.00, 51.67, 48.33, 3.33 +11.87, 10.00, 51.66, 48.34, 3.32 +11.93, 10.00, 49.13, 50.87, -1.74 +11.93, 10.00, 51.59, 48.41, 3.19 +12.00, 10.00, 49.07, 50.93, -1.87 +12.00, 10.00, 51.53, 48.47, 3.06 +12.00, 10.00, 51.52, 48.48, 3.05 +12.13, 10.00, 46.47, 53.53, -7.06 +12.13, 10.00, 51.41, 48.59, 2.82 +12.13, 10.00, 51.40, 48.60, 2.80 +12.13, 10.00, 51.39, 48.61, 2.78 +12.19, 10.00, 48.86, 51.14, -2.28 +12.19, 10.00, 51.33, 48.67, 2.65 +12.19, 10.00, 51.32, 48.68, 2.64 +12.19, 10.00, 51.31, 48.69, 2.62 +12.19, 10.00, 51.30, 48.70, 2.60 +12.19, 10.00, 51.29, 48.71, 2.59 +12.19, 10.00, 51.28, 48.72, 2.57 +12.19, 10.00, 51.28, 48.72, 2.55 +12.13, 10.00, 53.79, 46.21, 7.58 +12.13, 10.00, 51.31, 48.69, 2.62 +12.13, 10.00, 51.30, 48.70, 2.60 +12.13, 10.00, 51.29, 48.71, 2.59 +12.13, 10.00, 51.29, 48.71, 2.57 +12.13, 10.00, 51.28, 48.72, 2.56 +12.13, 10.00, 51.27, 48.73, 2.54 +12.00, 10.00, 56.31, 43.69, 12.61 +12.00, 10.00, 51.35, 48.65, 2.71 +12.00, 10.00, 51.35, 48.65, 2.69 +12.00, 10.00, 51.34, 48.66, 2.68 +11.93, 10.00, 53.85, 46.15, 7.71 +11.93, 10.00, 51.37, 48.63, 2.75 +11.93, 10.00, 51.37, 48.63, 2.73 +11.93, 10.00, 51.36, 48.64, 2.72 +11.87, 10.00, 53.87, 46.13, 7.75 +11.87, 10.00, 51.40, 48.60, 2.79 +11.87, 10.00, 51.39, 48.61, 2.78 +11.73, 10.00, 56.42, 43.58, 12.85 +11.73, 10.00, 51.47, 48.53, 2.95 +11.67, 10.00, 53.99, 46.01, 7.98 +11.67, 10.00, 51.51, 48.49, 3.02 +11.60, 10.00, 54.03, 45.97, 8.05 +11.60, 10.00, 51.55, 48.45, 3.10 +11.47, 10.00, 56.59, 43.41, 13.17 +11.47, 10.00, 51.64, 48.36, 3.27 +11.47, 10.00, 51.63, 48.37, 3.26 +11.40, 10.00, 54.15, 45.85, 8.29 +11.40, 10.00, 51.67, 48.33, 3.34 +11.40, 10.00, 51.66, 48.34, 3.33 +11.34, 10.00, 54.18, 45.82, 8.36 +11.34, 10.00, 51.70, 48.30, 3.41 +11.21, 10.00, 56.74, 43.26, 13.48 +11.21, 10.00, 51.79, 48.21, 3.59 +11.14, 10.00, 54.31, 45.69, 8.62 +11.14, 10.00, 51.83, 48.17, 3.67 +11.07, 10.00, 54.35, 45.65, 8.70 +11.07, 10.00, 51.88, 48.12, 3.75 +10.94, 10.00, 56.92, 43.08, 13.83 +10.94, 10.00, 51.97, 48.03, 3.94 +10.88, 10.00, 54.49, 45.51, 8.97 +10.88, 10.00, 52.01, 47.99, 4.02 +10.81, 10.00, 54.53, 45.47, 9.06 +10.81, 10.00, 52.05, 47.95, 4.11 +10.81, 10.00, 52.05, 47.95, 4.10 +10.68, 10.00, 57.09, 42.91, 14.18 +10.68, 10.00, 52.14, 47.86, 4.29 +10.68, 10.00, 52.14, 47.86, 4.28 +10.68, 10.00, 52.14, 47.86, 4.28 +10.61, 10.00, 54.66, 45.34, 9.32 +10.61, 10.00, 52.18, 47.82, 4.37 +10.61, 10.00, 52.18, 47.82, 4.36 +10.55, 10.00, 54.70, 45.30, 9.40 +10.55, 10.00, 52.23, 47.77, 4.45 +10.55, 10.00, 52.23, 47.77, 4.45 +10.42, 10.00, 57.27, 42.73, 14.53 +10.42, 10.00, 52.32, 47.68, 4.64 +10.35, 10.00, 54.84, 45.16, 9.68 +10.35, 10.00, 52.37, 47.63, 4.74 +10.28, 10.00, 54.89, 45.11, 9.78 +10.28, 10.00, 52.42, 47.58, 4.83 +10.28, 10.00, 52.41, 47.59, 4.83 +10.15, 10.00, 57.46, 42.54, 14.91 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.09, 10.00, 55.03, 44.97, 10.06 +10.09, 10.00, 52.56, 47.44, 5.12 +10.09, 10.00, 52.56, 47.44, 5.12 +10.02, 10.00, 55.08, 44.92, 10.16 +10.02, 10.00, 52.61, 47.39, 5.21 +10.02, 10.00, 52.61, 47.39, 5.21 +10.02, 10.00, 52.61, 47.39, 5.21 +9.89, 10.00, 57.65, 42.35, 15.30 +9.89, 10.00, 52.71, 47.29, 5.41 +9.89, 10.00, 52.71, 47.29, 5.41 +9.89, 10.00, 52.71, 47.29, 5.41 +9.82, 10.00, 55.23, 44.77, 10.46 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.53 +9.82, 10.00, 52.76, 47.24, 5.53 +9.82, 10.00, 52.76, 47.24, 5.53 +9.82, 10.00, 52.76, 47.24, 5.53 +9.82, 10.00, 52.77, 47.23, 5.53 +9.82, 10.00, 52.77, 47.23, 5.53 +9.82, 10.00, 52.77, 47.23, 5.53 +9.82, 10.00, 52.77, 47.23, 5.53 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.55 +9.82, 10.00, 52.77, 47.23, 5.55 +9.82, 10.00, 52.77, 47.23, 5.55 +9.82, 10.00, 52.77, 47.23, 5.55 +9.82, 10.00, 52.78, 47.22, 5.55 +9.89, 10.00, 50.25, 49.75, 0.51 +9.89, 10.00, 52.73, 47.27, 5.45 +9.89, 10.00, 52.73, 47.27, 5.45 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +10.02, 10.00, 47.69, 52.31, -4.63 +9.89, 10.00, 57.67, 42.33, 15.35 +10.02, 10.00, 47.69, 52.31, -4.62 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.09, 10.00, 50.11, 49.89, 0.22 +10.09, 10.00, 52.58, 47.42, 5.16 +10.09, 10.00, 52.58, 47.42, 5.16 +10.09, 10.00, 52.58, 47.42, 5.16 +10.09, 10.00, 52.58, 47.42, 5.16 +10.15, 10.00, 50.06, 49.94, 0.12 +10.15, 10.00, 52.53, 47.47, 5.06 +10.15, 10.00, 52.53, 47.47, 5.06 +10.15, 10.00, 52.53, 47.47, 5.06 +10.15, 10.00, 52.53, 47.47, 5.06 +10.28, 10.00, 47.48, 52.52, -5.03 +10.28, 10.00, 52.43, 47.57, 4.85 +10.28, 10.00, 52.43, 47.57, 4.85 +10.28, 10.00, 52.42, 47.58, 4.85 +10.28, 10.00, 52.42, 47.58, 4.85 +10.35, 10.00, 49.90, 50.10, -0.20 +10.35, 10.00, 52.37, 47.63, 4.74 +10.35, 10.00, 52.37, 47.63, 4.74 +10.35, 10.00, 52.37, 47.63, 4.74 +10.35, 10.00, 52.37, 47.63, 4.74 +10.35, 10.00, 52.37, 47.63, 4.73 +10.35, 10.00, 52.37, 47.63, 4.73 +10.35, 10.00, 52.36, 47.64, 4.73 +10.42, 10.00, 49.84, 50.16, -0.32 +10.42, 10.00, 52.31, 47.69, 4.62 +10.42, 10.00, 52.31, 47.69, 4.62 +10.42, 10.00, 52.31, 47.69, 4.62 +10.42, 10.00, 52.31, 47.69, 4.61 +10.55, 10.00, 47.26, 52.74, -5.48 +10.55, 10.00, 52.20, 47.80, 4.41 +10.55, 10.00, 52.20, 47.80, 4.40 +10.55, 10.00, 52.20, 47.80, 4.40 +10.55, 10.00, 52.20, 47.80, 4.39 +10.55, 10.00, 52.20, 47.80, 4.39 +10.55, 10.00, 52.19, 47.81, 4.39 +10.55, 10.00, 52.19, 47.81, 4.38 +10.55, 10.00, 52.19, 47.81, 4.38 +10.61, 10.00, 49.67, 50.33, -0.67 +10.55, 10.00, 54.66, 45.34, 9.31 +10.55, 10.00, 52.18, 47.82, 4.37 +10.61, 10.00, 49.66, 50.34, -0.68 +10.61, 10.00, 52.13, 47.87, 4.26 +10.61, 10.00, 52.13, 47.87, 4.25 +10.61, 10.00, 52.12, 47.88, 4.25 +10.61, 10.00, 52.12, 47.88, 4.24 +10.68, 10.00, 49.60, 50.40, -0.80 +10.68, 10.00, 52.07, 47.93, 4.13 +10.68, 10.00, 52.06, 47.94, 4.13 +10.81, 10.00, 47.02, 52.98, -5.96 +10.81, 10.00, 51.96, 48.04, 3.92 +10.81, 10.00, 51.96, 48.04, 3.91 +10.81, 10.00, 51.95, 48.05, 3.91 +10.81, 10.00, 51.95, 48.05, 3.90 +10.81, 10.00, 51.95, 48.05, 3.90 +10.81, 10.00, 51.94, 48.06, 3.89 +10.81, 10.00, 51.94, 48.06, 3.88 +10.81, 10.00, 51.94, 48.06, 3.88 +10.81, 10.00, 51.94, 48.06, 3.87 +10.68, 10.00, 56.98, 43.02, 13.95 +10.68, 10.00, 52.03, 47.97, 4.06 +10.81, 10.00, 46.98, 53.02, -6.03 +10.68, 10.00, 56.97, 43.03, 13.94 +10.81, 10.00, 46.98, 53.02, -6.04 +10.81, 10.00, 51.92, 48.08, 3.84 +10.81, 10.00, 51.92, 48.08, 3.83 +10.88, 10.00, 49.39, 50.61, -1.22 +10.88, 10.00, 51.86, 48.14, 3.72 +10.88, 10.00, 51.86, 48.14, 3.71 +10.88, 10.00, 51.85, 48.15, 3.71 +10.94, 10.00, 49.33, 50.67, -1.34 +10.94, 10.00, 51.80, 48.20, 3.59 +10.94, 10.00, 51.79, 48.21, 3.59 +10.94, 10.00, 51.79, 48.21, 3.58 +10.94, 10.00, 51.79, 48.21, 3.57 +10.88, 10.00, 54.30, 45.70, 8.61 +10.88, 10.00, 51.83, 48.17, 3.66 +10.88, 10.00, 51.83, 48.17, 3.65 +10.88, 10.00, 51.82, 48.18, 3.64 +10.88, 10.00, 51.82, 48.18, 3.64 +10.88, 10.00, 51.82, 48.18, 3.63 +10.88, 10.00, 51.81, 48.19, 3.62 +10.88, 10.00, 51.81, 48.19, 3.62 +10.94, 10.00, 49.28, 50.72, -1.43 +10.94, 10.00, 51.75, 48.25, 3.51 +10.94, 10.00, 51.75, 48.25, 3.50 +10.94, 10.00, 51.75, 48.25, 3.49 +10.94, 10.00, 51.74, 48.26, 3.48 +10.94, 10.00, 51.74, 48.26, 3.48 +10.94, 10.00, 51.74, 48.26, 3.47 +11.07, 10.00, 46.69, 53.31, -6.62 +11.07, 10.00, 51.63, 48.37, 3.26 +11.07, 10.00, 51.62, 48.38, 3.25 +11.07, 10.00, 51.62, 48.38, 3.24 +11.07, 10.00, 51.62, 48.38, 3.23 +11.07, 10.00, 51.61, 48.39, 3.22 +11.07, 10.00, 51.61, 48.39, 3.22 +10.94, 10.00, 56.65, 43.35, 13.29 +11.07, 10.00, 46.66, 53.34, -6.69 +10.94, 10.00, 56.64, 43.36, 13.28 +10.94, 10.00, 51.69, 48.31, 3.38 +11.07, 10.00, 46.65, 53.35, -6.71 +10.94, 10.00, 56.63, 43.37, 13.26 +11.07, 10.00, 46.64, 53.36, -6.72 +11.07, 10.00, 51.58, 48.42, 3.16 +11.07, 10.00, 51.57, 48.43, 3.15 +11.07, 10.00, 51.57, 48.43, 3.14 +11.07, 10.00, 51.57, 48.43, 3.13 +11.07, 10.00, 51.56, 48.44, 3.12 +11.14, 10.00, 49.04, 50.96, -1.93 +11.14, 10.00, 51.50, 48.50, 3.01 +11.14, 10.00, 51.50, 48.50, 3.00 +11.14, 10.00, 51.50, 48.50, 2.99 +11.14, 10.00, 51.49, 48.51, 2.98 +11.14, 10.00, 51.49, 48.51, 2.97 +11.14, 10.00, 51.48, 48.52, 2.96 +11.14, 10.00, 51.48, 48.52, 2.96 +11.14, 10.00, 51.47, 48.53, 2.95 +11.14, 10.00, 51.47, 48.53, 2.94 +11.14, 10.00, 51.47, 48.53, 2.93 +11.14, 10.00, 51.46, 48.54, 2.92 +11.14, 10.00, 51.46, 48.54, 2.91 +11.14, 10.00, 51.45, 48.55, 2.90 +11.14, 10.00, 51.45, 48.55, 2.90 +11.14, 10.00, 51.44, 48.56, 2.89 +11.14, 10.00, 51.44, 48.56, 2.88 +11.14, 10.00, 51.44, 48.56, 2.87 +11.14, 10.00, 51.43, 48.57, 2.86 +11.14, 10.00, 51.43, 48.57, 2.85 +11.14, 10.00, 51.42, 48.58, 2.84 +11.21, 10.00, 48.90, 51.10, -2.21 +11.14, 10.00, 53.89, 46.11, 7.77 +11.21, 10.00, 48.89, 51.11, -2.22 +11.21, 10.00, 51.36, 48.64, 2.71 +11.21, 10.00, 51.35, 48.65, 2.70 +11.21, 10.00, 51.35, 48.65, 2.69 +11.21, 10.00, 51.34, 48.66, 2.68 +11.21, 10.00, 51.34, 48.66, 2.67 +11.21, 10.00, 51.33, 48.67, 2.66 +11.21, 10.00, 51.33, 48.67, 2.66 +11.21, 10.00, 51.32, 48.68, 2.65 +11.21, 10.00, 51.32, 48.68, 2.64 +11.21, 10.00, 51.31, 48.69, 2.63 +11.34, 10.00, 46.27, 53.73, -7.47 +11.34, 10.00, 51.21, 48.79, 2.41 +11.34, 10.00, 51.20, 48.80, 2.40 +11.34, 10.00, 51.20, 48.80, 2.39 +11.34, 10.00, 51.19, 48.81, 2.38 +11.34, 10.00, 51.19, 48.81, 2.37 +11.34, 10.00, 51.18, 48.82, 2.36 +11.34, 10.00, 51.18, 48.82, 2.35 +11.34, 10.00, 51.17, 48.83, 2.34 +11.34, 10.00, 51.17, 48.83, 2.33 +11.34, 10.00, 51.16, 48.84, 2.32 +11.34, 10.00, 51.16, 48.84, 2.31 +11.34, 10.00, 51.15, 48.85, 2.30 +11.34, 10.00, 51.15, 48.85, 2.29 +11.34, 10.00, 51.14, 48.86, 2.28 +11.34, 10.00, 51.14, 48.86, 2.27 +11.34, 10.00, 51.13, 48.87, 2.26 +11.34, 10.00, 51.13, 48.87, 2.25 +11.34, 10.00, 51.12, 48.88, 2.24 +11.34, 10.00, 51.12, 48.88, 2.23 +11.34, 10.00, 51.11, 48.89, 2.22 +11.21, 10.00, 56.15, 43.85, 12.30 +11.21, 10.00, 51.20, 48.80, 2.40 +11.21, 10.00, 51.20, 48.80, 2.39 +11.21, 10.00, 51.19, 48.81, 2.38 +11.21, 10.00, 51.19, 48.81, 2.37 +11.14, 10.00, 53.70, 46.30, 7.41 +11.14, 10.00, 51.23, 48.77, 2.45 +11.14, 10.00, 51.22, 48.78, 2.45 +11.14, 10.00, 51.22, 48.78, 2.44 +11.14, 10.00, 51.21, 48.79, 2.43 +11.14, 10.00, 51.21, 48.79, 2.42 +11.14, 10.00, 51.21, 48.79, 2.41 +11.14, 10.00, 51.20, 48.80, 2.40 +11.14, 10.00, 51.20, 48.80, 2.39 +11.14, 10.00, 51.19, 48.81, 2.39 +11.14, 10.00, 51.19, 48.81, 2.38 +11.07, 10.00, 53.71, 46.29, 7.41 +11.07, 10.00, 51.23, 48.77, 2.46 +11.07, 10.00, 51.23, 48.77, 2.45 +11.07, 10.00, 51.22, 48.78, 2.44 +11.07, 10.00, 51.22, 48.78, 2.44 +10.94, 10.00, 56.26, 43.74, 12.51 +10.94, 10.00, 51.31, 48.69, 2.62 +10.94, 10.00, 51.31, 48.69, 2.61 +10.88, 10.00, 53.82, 46.18, 7.65 +10.88, 10.00, 51.35, 48.65, 2.70 +10.88, 10.00, 51.35, 48.65, 2.69 +10.88, 10.00, 51.34, 48.66, 2.69 +10.88, 10.00, 51.34, 48.66, 2.68 +10.81, 10.00, 53.86, 46.14, 7.72 +10.81, 10.00, 51.38, 48.62, 2.77 +10.81, 10.00, 51.38, 48.62, 2.76 +10.81, 10.00, 51.38, 48.62, 2.75 +10.81, 10.00, 51.37, 48.63, 2.75 +10.81, 10.00, 51.37, 48.63, 2.74 +10.68, 10.00, 56.41, 43.59, 12.82 +10.68, 10.00, 51.46, 48.54, 2.93 +10.68, 10.00, 51.46, 48.54, 2.92 +10.61, 10.00, 53.98, 46.02, 7.96 +10.61, 10.00, 51.51, 48.49, 3.01 +10.61, 10.00, 51.50, 48.50, 3.01 +10.55, 10.00, 54.02, 45.98, 8.05 +10.55, 10.00, 51.55, 48.45, 3.10 +10.55, 10.00, 51.55, 48.45, 3.10 +10.55, 10.00, 51.55, 48.45, 3.09 +10.55, 10.00, 51.54, 48.46, 3.09 +10.42, 10.00, 56.58, 43.42, 13.17 +10.42, 10.00, 51.64, 48.36, 3.28 +10.42, 10.00, 51.64, 48.36, 3.28 +10.42, 10.00, 51.64, 48.36, 3.27 +10.35, 10.00, 54.16, 45.84, 8.31 +10.35, 10.00, 51.68, 48.32, 3.37 +10.35, 10.00, 51.68, 48.32, 3.36 +10.35, 10.00, 51.68, 48.32, 3.36 +10.35, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 54.20, 45.80, 8.40 +10.28, 10.00, 51.73, 48.27, 3.45 +10.28, 10.00, 51.73, 48.27, 3.45 +10.28, 10.00, 51.72, 48.28, 3.45 +10.28, 10.00, 51.72, 48.28, 3.45 +10.15, 10.00, 56.77, 43.23, 13.53 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.09, 10.00, 54.34, 45.66, 8.68 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.02, 10.00, 54.39, 45.61, 8.78 +10.09, 10.00, 49.39, 50.61, -1.21 +10.02, 10.00, 54.39, 45.61, 8.77 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +9.89, 10.00, 56.96, 43.04, 13.91 +9.89, 10.00, 52.01, 47.99, 4.03 +9.89, 10.00, 52.01, 47.99, 4.03 +9.89, 10.00, 52.01, 47.99, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +10.02, 10.00, 46.98, 53.02, -6.05 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +9.89, 10.00, 56.96, 43.04, 13.92 +9.89, 10.00, 52.02, 47.98, 4.03 +10.02, 10.00, 46.97, 53.03, -6.05 +9.89, 10.00, 56.96, 43.04, 13.92 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.05 +9.89, 10.00, 52.02, 47.98, 4.05 +9.89, 10.00, 52.02, 47.98, 4.05 +9.89, 10.00, 52.02, 47.98, 4.05 +9.89, 10.00, 52.02, 47.98, 4.05 +9.82, 10.00, 54.55, 45.45, 9.09 +9.82, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 52.08, 47.92, 4.16 +9.82, 10.00, 52.08, 47.92, 4.16 +9.82, 10.00, 52.08, 47.92, 4.16 +9.82, 10.00, 52.08, 47.92, 4.16 +9.82, 10.00, 52.08, 47.92, 4.16 +9.89, 10.00, 49.56, 50.44, -0.88 +9.89, 10.00, 52.03, 47.97, 4.06 +9.89, 10.00, 52.03, 47.97, 4.06 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.04, 47.96, 4.07 +9.89, 10.00, 52.04, 47.96, 4.07 +9.89, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 54.56, 45.44, 9.12 +9.82, 10.00, 52.09, 47.91, 4.17 +9.82, 10.00, 52.09, 47.91, 4.18 +9.82, 10.00, 52.09, 47.91, 4.18 +9.82, 10.00, 52.09, 47.91, 4.18 +9.82, 10.00, 52.09, 47.91, 4.18 +9.82, 10.00, 52.09, 47.91, 4.18 +9.89, 10.00, 49.57, 50.43, -0.86 +9.89, 10.00, 52.04, 47.96, 4.08 +9.89, 10.00, 52.04, 47.96, 4.08 +9.89, 10.00, 52.04, 47.96, 4.09 +9.89, 10.00, 52.04, 47.96, 4.09 +10.02, 10.00, 47.00, 53.00, -6.00 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.09, 10.00, 49.42, 50.58, -1.16 +10.09, 10.00, 51.89, 48.11, 3.79 +10.09, 10.00, 51.89, 48.11, 3.78 +10.09, 10.00, 51.89, 48.11, 3.78 +10.09, 10.00, 51.89, 48.11, 3.78 +10.15, 10.00, 49.37, 50.63, -1.26 +10.15, 10.00, 51.84, 48.16, 3.68 +10.15, 10.00, 51.84, 48.16, 3.68 +10.15, 10.00, 51.84, 48.16, 3.68 +10.09, 10.00, 54.36, 45.64, 8.72 +10.15, 10.00, 49.37, 50.63, -1.27 +10.15, 10.00, 51.84, 48.16, 3.68 +10.09, 10.00, 54.36, 45.64, 8.72 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.15, 10.00, 49.36, 50.64, -1.27 +10.15, 10.00, 51.84, 48.16, 3.67 +10.15, 10.00, 51.83, 48.17, 3.67 +10.15, 10.00, 51.83, 48.17, 3.67 +10.15, 10.00, 51.83, 48.17, 3.67 +10.15, 10.00, 51.83, 48.17, 3.67 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.65 +10.09, 10.00, 54.35, 45.65, 8.70 +10.09, 10.00, 51.88, 48.12, 3.75 +10.09, 10.00, 51.88, 48.12, 3.75 +10.09, 10.00, 51.88, 48.12, 3.75 +10.09, 10.00, 51.88, 48.12, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.02, 10.00, 54.39, 45.61, 8.79 +10.02, 10.00, 51.92, 48.08, 3.85 +10.02, 10.00, 51.92, 48.08, 3.85 +10.02, 10.00, 51.92, 48.08, 3.85 +10.02, 10.00, 51.92, 48.08, 3.85 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.09, 10.00, 49.40, 50.60, -1.20 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.74 +10.15, 10.00, 49.35, 50.65, -1.30 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.09, 10.00, 54.34, 45.66, 8.68 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.73 +10.02, 10.00, 54.39, 45.61, 8.78 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.92, 48.08, 3.83 +10.09, 10.00, 49.39, 50.61, -1.21 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.15, 10.00, 49.34, 50.66, -1.31 +10.15, 10.00, 51.81, 48.19, 3.63 +10.15, 10.00, 51.81, 48.19, 3.63 +10.15, 10.00, 51.81, 48.19, 3.63 +10.15, 10.00, 51.81, 48.19, 3.63 +10.09, 10.00, 54.33, 45.67, 8.67 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.15, 10.00, 49.34, 50.66, -1.33 +10.15, 10.00, 51.81, 48.19, 3.62 +10.15, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.59 +10.15, 10.00, 51.80, 48.20, 3.59 +10.15, 10.00, 51.80, 48.20, 3.59 +10.15, 10.00, 51.80, 48.20, 3.59 +10.28, 10.00, 46.75, 53.25, -6.50 +10.28, 10.00, 51.69, 48.31, 3.39 +10.28, 10.00, 51.69, 48.31, 3.39 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.68, 48.32, 3.37 +10.28, 10.00, 51.68, 48.32, 3.37 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.35 +10.15, 10.00, 56.72, 43.28, 13.44 +10.15, 10.00, 51.77, 48.23, 3.55 +10.15, 10.00, 51.77, 48.23, 3.55 +10.15, 10.00, 51.77, 48.23, 3.55 +10.15, 10.00, 51.77, 48.23, 3.55 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 54.29, 45.71, 8.57 +10.09, 10.00, 51.81, 48.19, 3.63 +10.09, 10.00, 51.81, 48.19, 3.63 +10.09, 10.00, 51.81, 48.19, 3.63 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 54.33, 45.67, 8.67 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 49.34, 50.66, -1.32 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 54.33, 45.67, 8.66 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +9.89, 10.00, 56.90, 43.10, 13.80 +9.89, 10.00, 51.96, 48.04, 3.91 +9.89, 10.00, 51.96, 48.04, 3.91 +9.89, 10.00, 51.96, 48.04, 3.91 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +10.02, 10.00, 46.92, 53.08, -6.17 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +9.89, 10.00, 56.90, 43.10, 13.81 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.93 +10.02, 10.00, 46.92, 53.08, -6.16 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.09, 10.00, 49.34, 50.66, -1.32 +10.02, 10.00, 54.33, 45.67, 8.67 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.09, 10.00, 49.34, 50.66, -1.32 +10.02, 10.00, 54.33, 45.67, 8.67 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 49.34, 50.66, -1.32 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 54.33, 45.67, 8.66 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 49.34, 50.66, -1.32 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.61 +10.09, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 54.33, 45.67, 8.66 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +9.89, 10.00, 56.90, 43.10, 13.80 +10.02, 10.00, 46.91, 53.09, -6.18 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.09, 10.00, 49.33, 50.67, -1.33 +10.09, 10.00, 51.80, 48.20, 3.61 +10.09, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 49.28, 50.72, -1.44 +10.15, 10.00, 51.75, 48.25, 3.51 +10.15, 10.00, 51.75, 48.25, 3.51 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.28, 10.00, 46.70, 53.30, -6.59 +10.28, 10.00, 51.65, 48.35, 3.29 +10.28, 10.00, 51.65, 48.35, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.35, 10.00, 49.12, 50.88, -1.76 +10.35, 10.00, 51.59, 48.41, 3.19 +10.35, 10.00, 51.59, 48.41, 3.18 +10.35, 10.00, 51.59, 48.41, 3.18 +10.42, 10.00, 49.07, 50.93, -1.87 +10.35, 10.00, 54.06, 45.94, 8.12 +10.42, 10.00, 49.06, 50.94, -1.87 +10.42, 10.00, 51.53, 48.47, 3.07 +10.42, 10.00, 51.53, 48.47, 3.07 +10.42, 10.00, 51.53, 48.47, 3.06 +10.42, 10.00, 51.53, 48.47, 3.06 +10.42, 10.00, 51.53, 48.47, 3.06 +10.42, 10.00, 51.53, 48.47, 3.05 +10.42, 10.00, 51.53, 48.47, 3.05 +10.55, 10.00, 46.48, 53.52, -7.04 +10.55, 10.00, 51.42, 48.58, 2.84 +10.55, 10.00, 51.42, 48.58, 2.84 +10.55, 10.00, 51.42, 48.58, 2.84 +10.55, 10.00, 51.42, 48.58, 2.83 +10.55, 10.00, 51.41, 48.59, 2.83 +10.55, 10.00, 51.41, 48.59, 2.82 +10.55, 10.00, 51.41, 48.59, 2.82 +10.55, 10.00, 51.41, 48.59, 2.82 +10.55, 10.00, 51.41, 48.59, 2.81 +10.55, 10.00, 51.40, 48.60, 2.81 +10.55, 10.00, 51.40, 48.60, 2.80 +10.55, 10.00, 51.40, 48.60, 2.80 +10.55, 10.00, 51.40, 48.60, 2.80 +10.55, 10.00, 51.40, 48.60, 2.79 +10.55, 10.00, 51.39, 48.61, 2.79 +10.55, 10.00, 51.39, 48.61, 2.78 +10.55, 10.00, 51.39, 48.61, 2.78 +10.55, 10.00, 51.39, 48.61, 2.77 +10.55, 10.00, 51.39, 48.61, 2.77 +10.55, 10.00, 51.38, 48.62, 2.77 +10.55, 10.00, 51.38, 48.62, 2.76 +10.55, 10.00, 51.38, 48.62, 2.76 +10.61, 10.00, 48.86, 51.14, -2.29 +10.61, 10.00, 51.33, 48.67, 2.65 +10.61, 10.00, 51.32, 48.68, 2.65 +10.61, 10.00, 51.32, 48.68, 2.64 +10.61, 10.00, 51.32, 48.68, 2.64 +10.61, 10.00, 51.32, 48.68, 2.63 +10.61, 10.00, 51.31, 48.69, 2.63 +10.55, 10.00, 53.83, 46.17, 7.67 +10.55, 10.00, 51.36, 48.64, 2.72 +10.55, 10.00, 51.36, 48.64, 2.71 +10.55, 10.00, 51.36, 48.64, 2.71 +10.55, 10.00, 51.35, 48.65, 2.71 +10.55, 10.00, 51.35, 48.65, 2.70 +10.55, 10.00, 51.35, 48.65, 2.70 +10.55, 10.00, 51.35, 48.65, 2.69 +10.55, 10.00, 51.34, 48.66, 2.69 +10.55, 10.00, 51.34, 48.66, 2.69 +10.55, 10.00, 51.34, 48.66, 2.68 +10.55, 10.00, 51.34, 48.66, 2.68 +10.55, 10.00, 51.34, 48.66, 2.67 +10.55, 10.00, 51.33, 48.67, 2.67 +10.55, 10.00, 51.33, 48.67, 2.66 +10.55, 10.00, 51.33, 48.67, 2.66 +10.55, 10.00, 51.33, 48.67, 2.66 +10.55, 10.00, 51.33, 48.67, 2.65 +10.55, 10.00, 51.32, 48.68, 2.65 +10.55, 10.00, 51.32, 48.68, 2.64 +10.42, 10.00, 56.36, 43.64, 12.73 +10.42, 10.00, 51.42, 48.58, 2.84 +10.42, 10.00, 51.42, 48.58, 2.83 +10.42, 10.00, 51.41, 48.59, 2.83 +10.35, 10.00, 53.93, 46.07, 7.87 +10.35, 10.00, 51.46, 48.54, 2.92 +10.35, 10.00, 51.46, 48.54, 2.92 +10.35, 10.00, 51.46, 48.54, 2.92 +10.35, 10.00, 51.46, 48.54, 2.92 +10.35, 10.00, 51.46, 48.54, 2.91 +10.35, 10.00, 51.46, 48.54, 2.91 +10.35, 10.00, 51.45, 48.55, 2.91 +10.35, 10.00, 51.45, 48.55, 2.91 +10.35, 10.00, 51.45, 48.55, 2.90 +10.35, 10.00, 51.45, 48.55, 2.90 +10.35, 10.00, 51.45, 48.55, 2.90 +10.35, 10.00, 51.45, 48.55, 2.89 +10.28, 10.00, 53.97, 46.03, 7.94 +10.28, 10.00, 51.49, 48.51, 2.99 +10.28, 10.00, 51.49, 48.51, 2.99 +10.15, 10.00, 56.54, 43.46, 13.07 +10.15, 10.00, 51.59, 48.41, 3.18 +10.15, 10.00, 51.59, 48.41, 3.18 +10.09, 10.00, 54.11, 45.89, 8.22 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.02, 10.00, 54.16, 45.84, 8.32 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +9.89, 10.00, 56.73, 43.27, 13.46 +9.89, 10.00, 51.79, 48.21, 3.57 +9.89, 10.00, 51.79, 48.21, 3.57 +9.82, 10.00, 54.31, 45.69, 8.62 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.69 +9.82, 10.00, 51.84, 48.16, 3.69 +9.82, 10.00, 51.84, 48.16, 3.69 +9.82, 10.00, 51.84, 48.16, 3.69 +9.76, 10.00, 54.37, 45.63, 8.73 +9.76, 10.00, 51.90, 48.10, 3.79 +9.76, 10.00, 51.90, 48.10, 3.79 +9.62, 10.00, 56.94, 43.06, 13.88 +9.62, 10.00, 52.00, 48.00, 4.00 +9.62, 10.00, 52.00, 48.00, 4.00 +9.62, 10.00, 52.00, 48.00, 4.00 +9.56, 10.00, 54.52, 45.48, 9.05 +9.56, 10.00, 52.05, 47.95, 4.11 +9.56, 10.00, 52.06, 47.94, 4.11 +9.56, 10.00, 52.06, 47.94, 4.12 +9.56, 10.00, 52.06, 47.94, 4.12 +9.56, 10.00, 52.06, 47.94, 4.12 +9.56, 10.00, 52.06, 47.94, 4.13 +9.62, 10.00, 49.54, 50.46, -0.91 +9.62, 10.00, 52.02, 47.98, 4.03 +9.62, 10.00, 52.02, 47.98, 4.03 +9.62, 10.00, 52.02, 47.98, 4.04 +9.62, 10.00, 52.02, 47.98, 4.04 +9.62, 10.00, 52.02, 47.98, 4.04 +9.62, 10.00, 52.02, 47.98, 4.05 +9.62, 10.00, 52.02, 47.98, 4.05 +9.62, 10.00, 52.03, 47.97, 4.05 +9.62, 10.00, 52.03, 47.97, 4.05 +9.62, 10.00, 52.03, 47.97, 4.06 +9.56, 10.00, 54.55, 45.45, 9.10 +9.62, 10.00, 49.56, 50.44, -0.88 +9.62, 10.00, 52.03, 47.97, 4.07 +9.62, 10.00, 52.03, 47.97, 4.07 +9.62, 10.00, 52.04, 47.96, 4.07 +9.62, 10.00, 52.04, 47.96, 4.07 +9.62, 10.00, 52.04, 47.96, 4.08 +9.62, 10.00, 52.04, 47.96, 4.08 +9.62, 10.00, 52.04, 47.96, 4.08 +9.62, 10.00, 52.04, 47.96, 4.09 +9.62, 10.00, 52.04, 47.96, 4.09 +9.62, 10.00, 52.05, 47.95, 4.09 +9.62, 10.00, 52.05, 47.95, 4.09 +9.62, 10.00, 52.05, 47.95, 4.10 +9.62, 10.00, 52.05, 47.95, 4.10 +9.62, 10.00, 52.05, 47.95, 4.10 +9.62, 10.00, 52.05, 47.95, 4.11 +9.62, 10.00, 52.05, 47.95, 4.11 +9.62, 10.00, 52.06, 47.94, 4.11 +9.62, 10.00, 52.06, 47.94, 4.11 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.13 +9.76, 10.00, 47.02, 52.98, -5.96 +9.76, 10.00, 51.97, 48.03, 3.93 +9.76, 10.00, 51.97, 48.03, 3.93 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.95 +9.76, 10.00, 51.97, 48.03, 3.95 +9.76, 10.00, 51.97, 48.03, 3.95 +9.76, 10.00, 51.98, 48.02, 3.95 +9.62, 10.00, 57.02, 42.98, 14.04 +9.76, 10.00, 47.03, 52.97, -5.93 +9.76, 10.00, 51.98, 48.02, 3.96 +9.76, 10.00, 51.98, 48.02, 3.96 +9.76, 10.00, 51.98, 48.02, 3.96 +9.76, 10.00, 51.98, 48.02, 3.96 +9.82, 10.00, 49.46, 50.54, -1.08 +9.82, 10.00, 51.93, 48.07, 3.87 +9.82, 10.00, 51.93, 48.07, 3.87 +9.82, 10.00, 51.94, 48.06, 3.87 +9.82, 10.00, 51.94, 48.06, 3.87 +9.82, 10.00, 51.94, 48.06, 3.87 +9.82, 10.00, 51.94, 48.06, 3.87 +9.82, 10.00, 51.94, 48.06, 3.88 +9.82, 10.00, 51.94, 48.06, 3.88 +9.82, 10.00, 51.94, 48.06, 3.88 +9.82, 10.00, 51.94, 48.06, 3.88 +9.82, 10.00, 51.94, 48.06, 3.88 +9.76, 10.00, 54.46, 45.54, 8.93 +9.76, 10.00, 51.99, 48.01, 3.98 +9.76, 10.00, 51.99, 48.01, 3.99 +9.76, 10.00, 51.99, 48.01, 3.99 +9.76, 10.00, 51.99, 48.01, 3.99 +9.76, 10.00, 52.00, 48.00, 3.99 +9.82, 10.00, 49.47, 50.53, -1.05 +9.82, 10.00, 51.95, 48.05, 3.89 +9.82, 10.00, 51.95, 48.05, 3.90 +9.82, 10.00, 51.95, 48.05, 3.90 +9.89, 10.00, 49.43, 50.57, -1.14 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +10.02, 10.00, 46.86, 53.14, -6.27 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.09, 10.00, 49.29, 50.71, -1.43 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.02, 10.00, 54.27, 45.73, 8.53 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +9.89, 10.00, 56.84, 43.16, 13.67 +10.02, 10.00, 46.85, 53.15, -6.30 +9.89, 10.00, 56.84, 43.16, 13.67 +9.89, 10.00, 51.89, 48.11, 3.79 +9.89, 10.00, 51.89, 48.11, 3.79 +9.89, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 54.42, 45.58, 8.83 +9.89, 10.00, 49.42, 50.58, -1.15 +9.89, 10.00, 51.90, 48.10, 3.79 +9.89, 10.00, 51.90, 48.10, 3.79 +9.89, 10.00, 51.90, 48.10, 3.79 +9.89, 10.00, 51.90, 48.10, 3.79 +10.02, 10.00, 46.85, 53.15, -6.29 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +9.89, 10.00, 56.84, 43.16, 13.68 +9.89, 10.00, 51.90, 48.10, 3.79 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.82, 10.00, 54.42, 45.58, 8.84 +9.82, 10.00, 51.95, 48.05, 3.90 +9.82, 10.00, 51.95, 48.05, 3.90 +9.82, 10.00, 51.95, 48.05, 3.90 +9.89, 10.00, 49.43, 50.57, -1.14 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +10.02, 10.00, 46.86, 53.14, -6.28 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +9.89, 10.00, 56.85, 43.15, 13.69 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.82, 10.00, 54.43, 45.57, 8.85 +9.82, 10.00, 51.95, 48.05, 3.91 +9.82, 10.00, 51.96, 48.04, 3.91 +9.82, 10.00, 51.96, 48.04, 3.91 +9.82, 10.00, 51.96, 48.04, 3.91 +9.89, 10.00, 49.44, 50.56, -1.13 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +10.02, 10.00, 46.87, 53.13, -6.27 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +9.89, 10.00, 56.85, 43.15, 13.70 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.82, 10.00, 54.43, 45.57, 8.86 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.93 +9.82, 10.00, 51.96, 48.04, 3.93 +9.89, 10.00, 49.44, 50.56, -1.11 +9.89, 10.00, 51.91, 48.09, 3.83 +9.89, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 46.87, 53.13, -6.25 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +9.89, 10.00, 56.86, 43.14, 13.72 +9.89, 10.00, 51.92, 48.08, 3.83 +9.89, 10.00, 51.92, 48.08, 3.83 +9.89, 10.00, 51.92, 48.08, 3.83 +9.82, 10.00, 54.44, 45.56, 8.88 +9.82, 10.00, 51.97, 48.03, 3.93 +9.82, 10.00, 51.97, 48.03, 3.94 +9.82, 10.00, 51.97, 48.03, 3.94 +9.82, 10.00, 51.97, 48.03, 3.94 +9.89, 10.00, 49.45, 50.55, -1.10 +9.89, 10.00, 51.92, 48.08, 3.84 +9.89, 10.00, 51.92, 48.08, 3.84 +9.89, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 46.88, 53.12, -6.24 +10.02, 10.00, 51.82, 48.18, 3.65 +10.02, 10.00, 51.82, 48.18, 3.65 +10.02, 10.00, 51.82, 48.18, 3.65 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +9.89, 10.00, 56.87, 43.13, 13.73 +10.02, 10.00, 46.88, 53.12, -6.24 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.09, 10.00, 49.30, 50.70, -1.40 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 49.25, 50.75, -1.51 +10.15, 10.00, 51.72, 48.28, 3.43 +10.15, 10.00, 51.72, 48.28, 3.43 +10.15, 10.00, 51.72, 48.28, 3.43 +10.28, 10.00, 46.67, 53.33, -6.66 +10.28, 10.00, 51.61, 48.39, 3.23 +10.28, 10.00, 51.61, 48.39, 3.23 +10.28, 10.00, 51.61, 48.39, 3.23 +10.28, 10.00, 51.61, 48.39, 3.22 +10.28, 10.00, 51.61, 48.39, 3.22 +10.28, 10.00, 51.61, 48.39, 3.22 +10.28, 10.00, 51.61, 48.39, 3.22 +10.28, 10.00, 51.61, 48.39, 3.21 +10.28, 10.00, 51.61, 48.39, 3.21 +10.28, 10.00, 51.61, 48.39, 3.21 +10.28, 10.00, 51.60, 48.40, 3.21 +10.28, 10.00, 51.60, 48.40, 3.21 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.19 +10.35, 10.00, 49.07, 50.93, -1.85 +10.35, 10.00, 51.54, 48.46, 3.09 +10.35, 10.00, 51.54, 48.46, 3.09 +10.35, 10.00, 51.54, 48.46, 3.08 +10.35, 10.00, 51.54, 48.46, 3.08 +10.35, 10.00, 51.54, 48.46, 3.08 +10.35, 10.00, 51.54, 48.46, 3.08 +10.35, 10.00, 51.54, 48.46, 3.07 +10.28, 10.00, 54.06, 45.94, 8.11 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.15 +10.15, 10.00, 56.62, 43.38, 13.24 +10.15, 10.00, 51.67, 48.33, 3.35 +10.15, 10.00, 51.67, 48.33, 3.35 +10.15, 10.00, 51.67, 48.33, 3.35 +10.15, 10.00, 51.67, 48.33, 3.35 +10.15, 10.00, 51.67, 48.33, 3.34 +10.15, 10.00, 51.67, 48.33, 3.34 +10.15, 10.00, 51.67, 48.33, 3.34 +10.09, 10.00, 54.19, 45.81, 8.38 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.02, 10.00, 54.24, 45.76, 8.48 +10.02, 10.00, 51.77, 48.23, 3.53 +10.02, 10.00, 51.77, 48.23, 3.53 +10.02, 10.00, 51.77, 48.23, 3.53 +10.02, 10.00, 51.77, 48.23, 3.53 +9.89, 10.00, 56.81, 43.19, 13.62 +9.89, 10.00, 51.87, 48.13, 3.73 +9.89, 10.00, 51.87, 48.13, 3.73 +9.89, 10.00, 51.87, 48.13, 3.73 +9.82, 10.00, 54.39, 45.61, 8.78 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.85 +9.82, 10.00, 51.92, 48.08, 3.85 +9.82, 10.00, 51.92, 48.08, 3.85 +9.82, 10.00, 51.92, 48.08, 3.85 +9.76, 10.00, 54.45, 45.55, 8.89 +9.76, 10.00, 51.98, 48.02, 3.95 +9.76, 10.00, 51.98, 48.02, 3.95 +9.62, 10.00, 57.02, 42.98, 14.04 +9.62, 10.00, 52.08, 47.92, 4.16 +9.62, 10.00, 52.08, 47.92, 4.16 +9.62, 10.00, 52.08, 47.92, 4.16 +9.62, 10.00, 52.08, 47.92, 4.17 +9.62, 10.00, 52.08, 47.92, 4.17 +9.62, 10.00, 52.09, 47.91, 4.17 +9.62, 10.00, 52.09, 47.91, 4.17 +9.62, 10.00, 52.09, 47.91, 4.18 +9.62, 10.00, 52.09, 47.91, 4.18 +9.62, 10.00, 52.09, 47.91, 4.18 +9.62, 10.00, 52.09, 47.91, 4.19 +9.62, 10.00, 52.09, 47.91, 4.19 +9.62, 10.00, 52.10, 47.90, 4.19 +9.62, 10.00, 52.10, 47.90, 4.19 +9.56, 10.00, 54.62, 45.38, 9.24 +9.56, 10.00, 52.15, 47.85, 4.30 +9.56, 10.00, 52.15, 47.85, 4.30 +9.49, 10.00, 54.67, 45.33, 9.35 +9.56, 10.00, 49.68, 50.32, -0.63 +9.56, 10.00, 52.16, 47.84, 4.31 +9.49, 10.00, 54.68, 45.32, 9.36 +9.56, 10.00, 49.69, 50.31, -0.62 +9.49, 10.00, 54.68, 45.32, 9.37 +9.56, 10.00, 49.69, 50.31, -0.62 +9.56, 10.00, 52.17, 47.83, 4.33 +9.56, 10.00, 52.17, 47.83, 4.33 +9.56, 10.00, 52.17, 47.83, 4.34 +9.62, 10.00, 49.65, 50.35, -0.70 +9.62, 10.00, 52.12, 47.88, 4.24 +9.62, 10.00, 52.12, 47.88, 4.25 +9.62, 10.00, 52.12, 47.88, 4.25 +9.56, 10.00, 54.65, 45.35, 9.30 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.37 +9.56, 10.00, 52.18, 47.82, 4.37 +9.56, 10.00, 52.19, 47.81, 4.37 +9.56, 10.00, 52.19, 47.81, 4.38 +9.56, 10.00, 52.19, 47.81, 4.38 +9.56, 10.00, 52.19, 47.81, 4.38 +9.62, 10.00, 49.67, 50.33, -0.66 +9.62, 10.00, 52.14, 47.86, 4.29 +9.62, 10.00, 52.15, 47.85, 4.29 +9.76, 10.00, 47.10, 52.90, -5.79 +9.76, 10.00, 52.05, 47.95, 4.10 +9.82, 10.00, 49.53, 50.47, -0.94 +9.82, 10.00, 52.00, 48.00, 4.00 +9.82, 10.00, 52.00, 48.00, 4.00 +9.82, 10.00, 52.00, 48.00, 4.00 +9.82, 10.00, 52.00, 48.00, 4.01 +9.82, 10.00, 52.00, 48.00, 4.01 +9.82, 10.00, 52.00, 48.00, 4.01 +9.82, 10.00, 52.00, 48.00, 4.01 +9.82, 10.00, 52.01, 47.99, 4.01 +9.82, 10.00, 52.01, 47.99, 4.01 +9.82, 10.00, 52.01, 47.99, 4.01 +9.82, 10.00, 52.01, 47.99, 4.01 +9.82, 10.00, 52.01, 47.99, 4.02 +9.82, 10.00, 52.01, 47.99, 4.02 +9.89, 10.00, 49.49, 50.51, -1.02 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +10.02, 10.00, 46.92, 53.08, -6.16 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 49.34, 50.66, -1.32 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.61 +10.09, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 49.29, 50.71, -1.43 +10.15, 10.00, 51.76, 48.24, 3.51 +10.15, 10.00, 51.76, 48.24, 3.51 +10.15, 10.00, 51.76, 48.24, 3.51 +10.28, 10.00, 46.71, 53.29, -6.58 +10.28, 10.00, 51.65, 48.35, 3.31 +10.28, 10.00, 51.65, 48.35, 3.31 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.29 +10.28, 10.00, 51.65, 48.35, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.27 +10.28, 10.00, 51.64, 48.36, 3.27 +10.28, 10.00, 51.64, 48.36, 3.27 +10.35, 10.00, 49.11, 50.89, -1.78 +10.35, 10.00, 51.58, 48.42, 3.17 +10.35, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 51.58, 48.42, 3.15 +10.35, 10.00, 51.58, 48.42, 3.15 +10.35, 10.00, 51.57, 48.43, 3.15 +10.35, 10.00, 51.57, 48.43, 3.15 +10.35, 10.00, 51.57, 48.43, 3.14 +10.28, 10.00, 54.09, 45.91, 8.18 +10.28, 10.00, 51.62, 48.38, 3.24 +10.28, 10.00, 51.62, 48.38, 3.24 +10.28, 10.00, 51.62, 48.38, 3.23 +10.28, 10.00, 51.62, 48.38, 3.23 +10.35, 10.00, 49.09, 50.91, -1.81 +10.35, 10.00, 51.56, 48.44, 3.13 +10.35, 10.00, 51.56, 48.44, 3.12 +10.35, 10.00, 51.56, 48.44, 3.12 +10.35, 10.00, 51.56, 48.44, 3.12 +10.35, 10.00, 51.56, 48.44, 3.12 +10.35, 10.00, 51.56, 48.44, 3.11 +10.35, 10.00, 51.56, 48.44, 3.11 +10.35, 10.00, 51.55, 48.45, 3.11 +10.35, 10.00, 51.55, 48.45, 3.11 +10.35, 10.00, 51.55, 48.45, 3.10 +10.35, 10.00, 51.55, 48.45, 3.10 +10.35, 10.00, 51.55, 48.45, 3.10 +10.35, 10.00, 51.55, 48.45, 3.10 +10.35, 10.00, 51.55, 48.45, 3.09 +10.35, 10.00, 51.55, 48.45, 3.09 +10.28, 10.00, 54.07, 45.93, 8.13 +10.28, 10.00, 51.59, 48.41, 3.18 +10.35, 10.00, 49.07, 50.93, -1.86 +10.28, 10.00, 54.06, 45.94, 8.12 +10.28, 10.00, 51.59, 48.41, 3.18 +10.28, 10.00, 51.59, 48.41, 3.18 +10.28, 10.00, 51.59, 48.41, 3.17 +10.28, 10.00, 51.59, 48.41, 3.17 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 49.06, 50.94, -1.89 +10.35, 10.00, 51.53, 48.47, 3.05 +10.35, 10.00, 51.53, 48.47, 3.05 +10.35, 10.00, 51.52, 48.48, 3.05 +10.35, 10.00, 51.52, 48.48, 3.05 +10.35, 10.00, 51.52, 48.48, 3.04 +10.35, 10.00, 51.52, 48.48, 3.04 +10.35, 10.00, 51.52, 48.48, 3.04 +10.35, 10.00, 51.52, 48.48, 3.04 +10.28, 10.00, 54.04, 45.96, 8.08 +10.28, 10.00, 51.57, 48.43, 3.13 +10.28, 10.00, 51.56, 48.44, 3.13 +10.28, 10.00, 51.56, 48.44, 3.13 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.11 +10.28, 10.00, 51.56, 48.44, 3.11 +10.28, 10.00, 51.55, 48.45, 3.11 +10.28, 10.00, 51.55, 48.45, 3.11 +10.28, 10.00, 51.55, 48.45, 3.11 +10.28, 10.00, 51.55, 48.45, 3.10 +10.28, 10.00, 51.55, 48.45, 3.10 +10.15, 10.00, 56.59, 43.41, 13.19 +10.28, 10.00, 46.61, 53.39, -6.79 +10.15, 10.00, 56.59, 43.41, 13.18 +10.15, 10.00, 51.65, 48.35, 3.29 +10.15, 10.00, 51.65, 48.35, 3.29 +10.15, 10.00, 51.65, 48.35, 3.29 +10.15, 10.00, 51.65, 48.35, 3.29 +10.15, 10.00, 51.64, 48.36, 3.29 +10.15, 10.00, 51.64, 48.36, 3.29 +10.15, 10.00, 51.64, 48.36, 3.29 +10.15, 10.00, 51.64, 48.36, 3.29 +10.15, 10.00, 51.64, 48.36, 3.28 +10.15, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 54.16, 45.84, 8.33 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.02, 10.00, 54.21, 45.79, 8.42 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.47 +10.02, 10.00, 51.74, 48.26, 3.47 +10.02, 10.00, 51.74, 48.26, 3.47 +10.02, 10.00, 51.74, 48.26, 3.47 +9.89, 10.00, 56.78, 43.22, 13.56 +9.89, 10.00, 51.84, 48.16, 3.67 +9.89, 10.00, 51.84, 48.16, 3.67 +9.89, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 54.36, 45.64, 8.72 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 51.90, 48.10, 3.79 +9.82, 10.00, 51.90, 48.10, 3.79 +9.82, 10.00, 51.90, 48.10, 3.79 +9.82, 10.00, 51.90, 48.10, 3.79 +9.76, 10.00, 54.42, 45.58, 8.84 +9.76, 10.00, 51.95, 48.05, 3.90 +9.76, 10.00, 51.95, 48.05, 3.90 +9.76, 10.00, 51.95, 48.05, 3.90 +9.76, 10.00, 51.95, 48.05, 3.90 +9.62, 10.00, 57.00, 43.00, 13.99 +9.62, 10.00, 52.05, 47.95, 4.11 +9.62, 10.00, 52.05, 47.95, 4.11 +9.62, 10.00, 52.06, 47.94, 4.11 +9.62, 10.00, 52.06, 47.94, 4.11 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.13 +9.62, 10.00, 52.06, 47.94, 4.13 +9.62, 10.00, 52.07, 47.93, 4.13 +9.62, 10.00, 52.07, 47.93, 4.13 +9.62, 10.00, 52.07, 47.93, 4.14 +9.62, 10.00, 52.07, 47.93, 4.14 +9.62, 10.00, 52.07, 47.93, 4.14 +9.62, 10.00, 52.07, 47.93, 4.15 +9.62, 10.00, 52.07, 47.93, 4.15 +9.62, 10.00, 52.08, 47.92, 4.15 +9.62, 10.00, 52.08, 47.92, 4.15 +9.62, 10.00, 52.08, 47.92, 4.16 +9.56, 10.00, 54.60, 45.40, 9.20 +9.56, 10.00, 52.13, 47.87, 4.26 +9.56, 10.00, 52.13, 47.87, 4.27 +9.56, 10.00, 52.13, 47.87, 4.27 +9.56, 10.00, 52.14, 47.86, 4.27 +9.56, 10.00, 52.14, 47.86, 4.28 +9.56, 10.00, 52.14, 47.86, 4.28 +9.56, 10.00, 52.14, 47.86, 4.28 +9.56, 10.00, 52.14, 47.86, 4.29 +9.56, 10.00, 52.14, 47.86, 4.29 +9.56, 10.00, 52.15, 47.85, 4.29 +9.56, 10.00, 52.15, 47.85, 4.30 +9.56, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 49.63, 50.37, -0.74 +9.62, 10.00, 52.10, 47.90, 4.21 +9.56, 10.00, 54.63, 45.37, 9.25 +9.62, 10.00, 49.63, 50.37, -0.73 +9.62, 10.00, 52.11, 47.89, 4.21 +9.62, 10.00, 52.11, 47.89, 4.22 +9.62, 10.00, 52.11, 47.89, 4.22 +9.56, 10.00, 54.63, 45.37, 9.27 +9.56, 10.00, 52.16, 47.84, 4.33 +9.56, 10.00, 52.16, 47.84, 4.33 +9.56, 10.00, 52.17, 47.83, 4.33 +9.56, 10.00, 52.17, 47.83, 4.34 +9.56, 10.00, 52.17, 47.83, 4.34 +9.56, 10.00, 52.17, 47.83, 4.34 +9.56, 10.00, 52.17, 47.83, 4.35 +9.56, 10.00, 52.17, 47.83, 4.35 +9.56, 10.00, 52.18, 47.82, 4.35 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.36 +9.62, 10.00, 49.66, 50.34, -0.68 +9.62, 10.00, 52.13, 47.87, 4.27 +9.62, 10.00, 52.14, 47.86, 4.27 +9.62, 10.00, 52.14, 47.86, 4.27 +9.62, 10.00, 52.14, 47.86, 4.28 +9.76, 10.00, 47.10, 52.90, -5.81 +9.76, 10.00, 52.04, 47.96, 4.08 +9.76, 10.00, 52.04, 47.96, 4.08 +9.76, 10.00, 52.04, 47.96, 4.09 +9.62, 10.00, 57.09, 42.91, 14.18 +9.62, 10.00, 52.15, 47.85, 4.29 +9.62, 10.00, 52.15, 47.85, 4.29 +9.62, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 52.15, 47.85, 4.31 +9.62, 10.00, 52.15, 47.85, 4.31 +9.62, 10.00, 52.16, 47.84, 4.31 +9.62, 10.00, 52.16, 47.84, 4.32 +9.76, 10.00, 47.12, 52.88, -5.77 +9.76, 10.00, 52.06, 47.94, 4.12 +9.76, 10.00, 52.06, 47.94, 4.12 +9.76, 10.00, 52.06, 47.94, 4.13 +9.82, 10.00, 49.54, 50.46, -0.92 +9.82, 10.00, 52.01, 47.99, 4.03 +9.82, 10.00, 52.02, 47.98, 4.03 +9.82, 10.00, 52.02, 47.98, 4.03 +9.82, 10.00, 52.02, 47.98, 4.03 +9.82, 10.00, 52.02, 47.98, 4.03 +9.82, 10.00, 52.02, 47.98, 4.04 +9.82, 10.00, 52.02, 47.98, 4.04 +9.82, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 54.54, 45.46, 9.08 +9.76, 10.00, 52.07, 47.93, 4.14 +9.76, 10.00, 52.07, 47.93, 4.14 +9.76, 10.00, 52.07, 47.93, 4.14 +9.76, 10.00, 52.07, 47.93, 4.15 +9.76, 10.00, 52.07, 47.93, 4.15 +9.76, 10.00, 52.07, 47.93, 4.15 +9.76, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 49.56, 50.44, -0.89 +9.82, 10.00, 52.03, 47.97, 4.06 +9.82, 10.00, 52.03, 47.97, 4.06 +9.82, 10.00, 52.03, 47.97, 4.06 +9.82, 10.00, 52.03, 47.97, 4.06 +9.89, 10.00, 49.51, 50.49, -0.98 +9.82, 10.00, 54.50, 45.50, 9.01 +9.89, 10.00, 49.51, 50.49, -0.98 +9.89, 10.00, 51.98, 48.02, 3.96 +9.89, 10.00, 51.98, 48.02, 3.97 +9.82, 10.00, 54.50, 45.50, 9.01 +9.89, 10.00, 49.51, 50.49, -0.98 +9.82, 10.00, 54.51, 45.49, 9.01 +9.82, 10.00, 52.03, 47.97, 4.07 +9.82, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 52.04, 47.96, 4.08 +9.82, 10.00, 52.04, 47.96, 4.08 +9.82, 10.00, 52.04, 47.96, 4.08 +9.89, 10.00, 49.52, 50.48, -0.96 +9.89, 10.00, 51.99, 48.01, 3.98 +9.89, 10.00, 51.99, 48.01, 3.98 +9.89, 10.00, 51.99, 48.01, 3.98 +10.02, 10.00, 46.95, 53.05, -6.10 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.09, 10.00, 49.37, 50.63, -1.26 +10.09, 10.00, 51.84, 48.16, 3.68 +10.09, 10.00, 51.84, 48.16, 3.68 +10.15, 10.00, 49.32, 50.68, -1.36 +10.15, 10.00, 51.79, 48.21, 3.58 +10.15, 10.00, 51.79, 48.21, 3.58 +10.15, 10.00, 51.79, 48.21, 3.58 +10.28, 10.00, 46.75, 53.25, -6.51 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.68, 48.32, 3.37 +10.28, 10.00, 51.68, 48.32, 3.37 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.35 +10.28, 10.00, 51.68, 48.32, 3.35 +10.28, 10.00, 51.67, 48.33, 3.35 +10.28, 10.00, 51.67, 48.33, 3.35 +10.35, 10.00, 49.15, 50.85, -1.70 +10.35, 10.00, 51.62, 48.38, 3.24 +10.35, 10.00, 51.62, 48.38, 3.24 +10.42, 10.00, 49.10, 50.90, -1.81 +10.42, 10.00, 51.57, 48.43, 3.13 +10.42, 10.00, 51.57, 48.43, 3.13 +10.42, 10.00, 51.56, 48.44, 3.13 +10.42, 10.00, 51.56, 48.44, 3.13 +10.42, 10.00, 51.56, 48.44, 3.12 +10.42, 10.00, 51.56, 48.44, 3.12 +10.42, 10.00, 51.56, 48.44, 3.12 +10.42, 10.00, 51.56, 48.44, 3.11 +10.42, 10.00, 51.56, 48.44, 3.11 +10.35, 10.00, 54.08, 45.92, 8.15 +10.35, 10.00, 51.60, 48.40, 3.20 +10.35, 10.00, 51.60, 48.40, 3.20 +10.35, 10.00, 51.60, 48.40, 3.20 +10.35, 10.00, 51.60, 48.40, 3.20 +10.35, 10.00, 51.60, 48.40, 3.19 +10.28, 10.00, 54.12, 45.88, 8.23 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.35, 10.00, 49.11, 50.89, -1.77 +10.35, 10.00, 51.59, 48.41, 3.17 +10.28, 10.00, 54.11, 45.89, 8.21 +10.35, 10.00, 49.11, 50.89, -1.78 +10.28, 10.00, 54.10, 45.90, 8.21 +10.28, 10.00, 51.63, 48.37, 3.26 +10.28, 10.00, 51.63, 48.37, 3.26 +10.28, 10.00, 51.63, 48.37, 3.26 +10.28, 10.00, 51.63, 48.37, 3.25 +10.15, 10.00, 56.67, 43.33, 13.34 +10.15, 10.00, 51.72, 48.28, 3.45 +10.15, 10.00, 51.72, 48.28, 3.45 +10.09, 10.00, 54.25, 45.75, 8.49 +10.09, 10.00, 51.77, 48.23, 3.55 +10.09, 10.00, 51.77, 48.23, 3.55 +10.09, 10.00, 51.77, 48.23, 3.55 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 49.25, 50.75, -1.50 +10.15, 10.00, 51.72, 48.28, 3.44 +10.15, 10.00, 51.72, 48.28, 3.44 +10.15, 10.00, 51.72, 48.28, 3.44 +10.15, 10.00, 51.72, 48.28, 3.44 +10.15, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 54.24, 45.76, 8.48 +10.09, 10.00, 51.77, 48.23, 3.53 +10.09, 10.00, 51.77, 48.23, 3.53 +10.09, 10.00, 51.77, 48.23, 3.53 +10.02, 10.00, 54.29, 45.71, 8.58 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.09, 10.00, 49.29, 50.71, -1.41 +10.09, 10.00, 51.77, 48.23, 3.53 +10.09, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 51.76, 48.24, 3.53 +10.15, 10.00, 49.24, 50.76, -1.52 +10.09, 10.00, 54.24, 45.76, 8.47 +10.09, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.02, 10.00, 54.28, 45.72, 8.57 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 49.29, 50.71, -1.42 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.02, 10.00, 54.28, 45.72, 8.56 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +9.89, 10.00, 56.85, 43.15, 13.70 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.82, 10.00, 54.43, 45.57, 8.86 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.93 +9.82, 10.00, 51.96, 48.04, 3.93 +9.82, 10.00, 51.96, 48.04, 3.93 +9.82, 10.00, 51.96, 48.04, 3.93 +9.76, 10.00, 54.49, 45.51, 8.97 +9.76, 10.00, 52.02, 47.98, 4.03 +9.76, 10.00, 52.02, 47.98, 4.03 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.05 +9.76, 10.00, 52.02, 47.98, 4.05 +9.76, 10.00, 52.03, 47.97, 4.05 +9.76, 10.00, 52.03, 47.97, 4.05 +9.76, 10.00, 52.03, 47.97, 4.05 +9.76, 10.00, 52.03, 47.97, 4.06 +9.76, 10.00, 52.03, 47.97, 4.06 +9.76, -10.00, 25.00, 75.00, -50.00 +9.76, -10.00, 36.88, 63.12, -26.24 +9.76, -10.00, 36.81, 63.19, -26.39 +9.76, -10.00, 36.73, 63.27, -26.54 +9.76, -10.00, 36.66, 63.34, -26.68 +9.62, -10.00, 41.63, 58.37, -16.75 +9.62, -10.00, 36.61, 63.39, -26.78 +9.62, -10.00, 36.54, 63.46, -26.93 +9.62, -10.00, 36.46, 63.54, -27.07 +9.62, -10.00, 36.39, 63.61, -27.22 +9.62, -10.00, 36.32, 63.68, -27.37 +9.62, -10.00, 36.24, 63.76, -27.52 +9.56, -10.00, 38.69, 61.31, -22.62 +9.49, -10.00, 38.67, 61.33, -22.67 +9.49, -10.00, 36.12, 63.88, -27.76 +9.36, -10.00, 41.09, 58.91, -17.82 +9.29, -10.00, 38.60, 61.40, -22.81 +9.23, -10.00, 38.57, 61.43, -22.85 +9.10, -10.00, 41.07, 58.93, -17.85 +9.03, -10.00, 38.58, 61.42, -22.84 +8.96, -10.00, 38.56, 61.44, -22.88 +8.83, -10.00, 41.06, 58.94, -17.88 +8.70, -10.00, 41.09, 58.91, -17.83 +8.57, -10.00, 41.12, 58.88, -17.77 +8.44, -10.00, 41.15, 58.85, -17.71 +8.31, -10.00, 41.18, 58.82, -17.65 +8.17, -10.00, 41.21, 58.79, -17.59 +8.04, -10.00, 41.24, 58.76, -17.52 +7.91, -10.00, 41.27, 58.73, -17.46 +7.71, -10.00, 43.82, 56.18, -12.35 +7.45, -10.00, 46.43, 53.57, -7.14 +7.25, -10.00, 44.04, 55.96, -11.92 +7.12, -10.00, 41.60, 58.40, -16.80 +6.92, -10.00, 44.16, 55.84, -11.68 +6.66, -10.00, 46.77, 53.23, -6.47 +6.46, -10.00, 44.38, 55.62, -11.24 +6.20, -10.00, 46.99, 53.01, -6.02 +5.93, -10.00, 47.13, 52.87, -5.74 +5.67, -10.00, 47.27, 52.73, -5.47 +5.54, -10.00, 42.36, 57.64, -15.27 +5.27, -10.00, 47.45, 52.55, -5.10 +5.01, -10.00, 47.59, 52.41, -4.82 +4.75, -10.00, 47.73, 52.27, -4.54 +4.48, -10.00, 47.88, 52.12, -4.25 +4.22, -10.00, 48.02, 51.98, -3.96 +3.96, -10.00, 48.16, 51.84, -3.67 +3.69, -10.00, 48.31, 51.69, -3.38 +3.43, -10.00, 48.46, 51.54, -3.08 +3.03, -10.00, 53.65, 46.35, 7.30 +2.77, -10.00, 48.86, 51.14, -2.29 +2.44, -10.00, 51.53, 48.47, 3.06 +2.18, -10.00, 49.21, 50.79, -1.58 +1.85, -10.00, 51.88, 48.12, 3.77 +1.58, -10.00, 49.57, 50.43, -0.87 +1.19, -10.00, 54.76, 45.24, 9.53 +0.92, -10.00, 49.98, 50.02, -0.04 +0.59, -10.00, 52.66, 47.34, 5.31 +0.26, -10.00, 52.87, 47.13, 5.73 +0.00, -10.00, 50.55, 49.45, 1.11 +-0.40, -10.00, 55.76, 44.24, 11.52 +-0.73, -10.00, 53.50, 46.50, 7.00 +-0.99, -10.00, 51.19, 48.81, 2.38 +-1.32, -10.00, 53.88, 46.12, 7.76 +-1.71, -10.00, 56.62, 43.38, 13.23 +-1.98, -10.00, 51.84, 48.16, 3.68 +-2.31, -10.00, 54.53, 45.47, 9.06 +-2.64, -10.00, 54.75, 45.25, 9.50 +-3.03, -10.00, 57.49, 42.51, 14.98 +-3.30, -10.00, 52.72, 47.28, 5.44 +-3.63, -10.00, 55.42, 44.58, 10.83 +-3.96, -10.00, 55.64, 44.36, 11.28 +-4.35, -10.00, 58.39, 41.61, 16.77 +-4.61, -10.00, 53.62, 46.38, 7.24 +-4.94, -10.00, 56.32, 43.68, 12.64 +-5.21, -10.00, 54.03, 45.97, 8.06 +-5.54, -10.00, 56.73, 43.27, 13.46 +-5.80, -10.00, 54.44, 45.56, 8.88 +-6.06, -10.00, 54.62, 45.38, 9.25 +-6.46, -10.00, 59.85, 40.15, 19.70 +-6.79, -10.00, 57.61, 42.39, 15.23 +-7.05, -10.00, 55.33, 44.67, 10.66 +-7.32, -10.00, 55.52, 44.48, 11.03 +-7.58, -10.00, 55.71, 44.29, 11.41 +-7.91, -10.00, 58.42, 41.58, 16.83 +-8.17, -10.00, 56.14, 43.86, 12.27 +-8.44, -10.00, 56.33, 43.67, 12.66 +-8.70, -10.00, 56.52, 43.48, 13.04 +-9.10, -10.00, 61.76, 38.24, 23.52 +-9.36, -10.00, 57.01, 42.99, 14.02 +-9.62, -10.00, 57.21, 42.79, 14.41 +-9.89, -10.00, 57.40, 42.60, 14.81 +-10.15, -10.00, 57.60, 42.40, 15.20 +-10.42, -10.00, 57.80, 42.20, 15.60 +-10.55, -10.00, 52.96, 47.04, 5.92 +-10.81, -10.00, 58.10, 41.90, 16.20 +-11.07, -10.00, 58.30, 41.70, 16.61 +-11.27, -10.00, 55.99, 44.01, 11.97 +-11.60, -10.00, 61.18, 38.82, 22.36 +-11.80, -10.00, 56.39, 43.61, 12.79 +-12.00, -10.00, 56.55, 43.45, 13.10 +-12.26, -10.00, 59.23, 40.77, 18.46 +-12.52, -10.00, 59.43, 40.57, 18.87 +-12.66, -10.00, 54.60, 45.40, 9.20 +-12.85, -10.00, 57.23, 42.77, 14.46 +-13.05, -10.00, 57.39, 42.61, 14.78 +-13.32, -10.00, 60.07, 39.93, 20.15 +-13.45, -10.00, 55.24, 44.76, 10.48 +-13.65, -10.00, 57.87, 42.13, 15.75 +-13.84, -10.00, 58.04, 41.96, 16.07 +-13.97, -10.00, 55.68, 44.32, 11.36 +-14.17, -10.00, 58.31, 41.69, 16.63 +-14.24, -10.00, 53.44, 46.56, 6.87 +-14.44, -10.00, 58.55, 41.45, 17.09 +-14.63, -10.00, 58.71, 41.29, 17.42 +-14.77, -10.00, 56.36, 43.64, 12.71 +-14.90, -10.00, 56.47, 43.53, 12.95 +-14.96, -10.00, 54.07, 45.93, 8.14 +-15.16, -10.00, 59.18, 40.82, 18.36 +-15.29, -10.00, 56.83, 43.17, 13.65 +-15.42, -10.00, 56.95, 43.05, 13.89 +-15.49, -10.00, 54.54, 45.46, 9.09 +-15.56, -10.00, 54.62, 45.38, 9.23 +-15.69, -10.00, 57.21, 42.79, 14.41 +-15.82, -10.00, 57.33, 42.67, 14.66 +-15.95, -10.00, 57.45, 42.55, 14.90 +-16.02, -10.00, 55.05, 44.95, 10.10 +-16.08, -10.00, 55.12, 44.88, 10.24 +-16.08, -10.00, 52.67, 47.33, 5.34 +-16.22, -10.00, 57.74, 42.26, 15.48 +-16.28, -10.00, 55.34, 44.66, 10.68 +-16.35, -10.00, 55.41, 44.59, 10.83 +-16.48, -10.00, 58.01, 41.99, 16.02 +-16.48, -10.00, 53.09, 46.91, 6.18 +-16.48, -10.00, 53.11, 46.89, 6.22 +-16.55, -10.00, 55.66, 44.34, 11.32 +-16.55, -10.00, 53.21, 46.79, 6.42 +-16.61, -10.00, 55.76, 44.24, 11.51 +-16.61, -10.00, 53.31, 46.69, 6.62 +-16.61, -10.00, 53.33, 46.67, 6.67 +-16.61, -10.00, 53.36, 46.64, 6.72 +-16.74, -10.00, 58.43, 41.57, 16.86 +-16.74, -10.00, 53.51, 46.49, 7.02 +-16.74, -10.00, 53.53, 46.47, 7.07 +-16.74, -10.00, 53.56, 46.44, 7.12 +-16.74, -10.00, 53.58, 46.42, 7.17 +-16.74, -10.00, 53.61, 46.39, 7.22 +-16.74, -10.00, 53.64, 46.36, 7.27 +-16.74, -10.00, 53.66, 46.34, 7.32 +-16.74, -10.00, 53.69, 46.31, 7.37 +-16.74, -10.00, 53.71, 46.29, 7.42 +-16.74, -10.00, 53.74, 46.26, 7.47 +-16.74, -10.00, 53.76, 46.24, 7.52 +-16.74, -10.00, 53.79, 46.21, 7.57 +-16.61, -10.00, 48.77, 51.23, -2.46 +-16.61, -10.00, 53.74, 46.26, 7.48 +-16.61, -10.00, 53.76, 46.24, 7.53 +-16.61, -10.00, 53.79, 46.21, 7.58 +-16.61, -10.00, 53.81, 46.19, 7.62 +-16.61, -10.00, 53.84, 46.16, 7.67 +-16.61, -10.00, 53.86, 46.14, 7.72 +-16.55, -10.00, 51.37, 48.63, 2.73 +-16.55, -10.00, 53.86, 46.14, 7.72 +-16.55, -10.00, 53.89, 46.11, 7.77 +-16.48, -10.00, 51.39, 48.61, 2.78 +-16.48, -10.00, 53.89, 46.11, 7.77 +-16.48, -10.00, 53.91, 46.09, 7.82 +-16.35, -10.00, 48.89, 51.11, -2.22 +-16.35, -10.00, 53.86, 46.14, 7.72 +-16.35, -10.00, 53.88, 46.12, 7.76 +-16.28, -10.00, 51.38, 48.62, 2.77 +-16.28, -10.00, 53.88, 46.12, 7.76 +-16.22, -10.00, 51.38, 48.62, 2.76 +-16.22, -10.00, 53.88, 46.12, 7.75 +-16.22, -10.00, 53.90, 46.10, 7.80 +-16.08, -10.00, 48.88, 51.12, -2.24 +-16.08, -10.00, 53.85, 46.15, 7.69 +-16.08, -10.00, 53.87, 46.13, 7.74 +-16.02, -10.00, 51.37, 48.63, 2.74 +-16.02, -10.00, 53.87, 46.13, 7.73 +-15.95, -10.00, 51.37, 48.63, 2.73 +-15.95, -10.00, 53.86, 46.14, 7.72 +-15.82, -10.00, 48.84, 51.16, -2.32 +-15.82, -10.00, 53.81, 46.19, 7.61 +-15.75, -10.00, 51.31, 48.69, 2.61 +-15.75, -10.00, 53.80, 46.20, 7.60 +-15.69, -10.00, 51.30, 48.70, 2.60 +-15.69, -10.00, 53.79, 46.21, 7.58 +-15.56, -10.00, 48.77, 51.23, -2.46 +-15.56, -10.00, 53.74, 46.26, 7.47 +-15.49, -10.00, 51.23, 48.77, 2.47 +-15.49, -10.00, 53.73, 46.27, 7.45 +-15.42, -10.00, 51.23, 48.77, 2.45 +-15.42, -10.00, 53.72, 46.28, 7.44 +-15.42, -10.00, 53.74, 46.26, 7.48 +-15.29, -10.00, 48.72, 51.28, -2.57 +-15.29, -10.00, 53.68, 46.32, 7.36 +-15.23, -10.00, 51.18, 48.82, 2.36 +-15.16, -10.00, 51.15, 48.85, 2.30 +-15.16, -10.00, 53.64, 46.36, 7.28 +-15.03, -10.00, 48.61, 51.39, -2.77 +-15.03, -10.00, 53.58, 46.42, 7.16 +-14.96, -10.00, 51.07, 48.93, 2.15 +-14.96, -10.00, 53.57, 46.43, 7.13 +-14.90, -10.00, 51.06, 48.94, 2.12 +-14.90, -10.00, 53.55, 46.45, 7.11 +-14.90, -10.00, 53.57, 46.43, 7.14 +-14.77, -10.00, 48.55, 51.45, -2.91 +-14.77, -10.00, 53.51, 46.49, 7.02 +-14.70, -10.00, 51.00, 49.00, 2.01 +-14.63, -10.00, 50.97, 49.03, 1.94 +-14.63, -10.00, 53.46, 46.54, 6.92 +-14.63, -10.00, 53.48, 46.52, 6.96 +-14.50, -10.00, 48.45, 51.55, -3.09 +-14.50, -10.00, 53.41, 46.59, 6.83 +-14.44, -10.00, 50.91, 49.09, 1.82 +-14.37, -10.00, 50.88, 49.12, 1.75 +-14.37, -10.00, 53.36, 46.64, 6.73 +-14.24, -10.00, 48.34, 51.66, -3.33 +-14.24, -10.00, 53.30, 46.70, 6.59 +-14.24, -10.00, 53.31, 46.69, 6.63 +-14.17, -10.00, 50.81, 49.19, 1.61 +-14.17, -10.00, 53.29, 46.71, 6.59 +-14.11, -10.00, 50.79, 49.21, 1.58 +-14.11, -10.00, 53.28, 46.72, 6.55 +-13.97, -10.00, 48.25, 51.75, -3.50 +-13.97, -10.00, 53.21, 46.79, 6.41 +-13.97, -10.00, 53.22, 46.78, 6.44 +-13.91, -10.00, 50.72, 49.28, 1.43 +-13.91, -10.00, 53.20, 46.80, 6.40 +-13.84, -10.00, 50.70, 49.30, 1.39 +-13.84, -10.00, 53.18, 46.82, 6.36 +-13.71, -10.00, 48.15, 51.85, -3.69 +-13.71, -10.00, 53.11, 46.89, 6.22 +-13.71, -10.00, 53.12, 46.88, 6.25 +-13.65, -10.00, 50.62, 49.38, 1.23 +-13.65, -10.00, 53.10, 46.90, 6.20 +-13.58, -10.00, 50.59, 49.41, 1.19 +-13.58, -10.00, 53.08, 46.92, 6.16 +-13.58, -10.00, 53.09, 46.91, 6.19 +-13.45, -10.00, 48.06, 51.94, -3.87 +-13.45, -10.00, 53.02, 46.98, 6.04 +-13.45, -10.00, 53.03, 46.97, 6.07 +-13.38, -10.00, 50.52, 49.48, 1.05 +-13.38, -10.00, 53.01, 46.99, 6.02 +-13.32, -10.00, 50.50, 49.50, 1.00 +-13.32, -10.00, 52.98, 47.02, 5.97 +-13.18, -10.00, 47.95, 52.05, -4.09 +-13.18, -10.00, 52.91, 47.09, 5.82 +-13.18, -10.00, 52.92, 47.08, 5.84 +-13.12, -10.00, 50.41, 49.59, 0.82 +-13.12, -10.00, 52.90, 47.10, 5.79 +-13.05, -10.00, 50.39, 49.61, 0.77 +-13.05, -10.00, 52.87, 47.13, 5.74 +-13.05, -10.00, 52.88, 47.12, 5.76 +-13.05, -10.00, 52.89, 47.11, 5.78 +-12.92, -10.00, 47.86, 52.14, -4.28 +-12.92, -10.00, 52.81, 47.19, 5.63 +-12.92, -10.00, 52.83, 47.17, 5.65 +-12.85, -10.00, 50.31, 49.69, 0.63 +-12.85, -10.00, 52.80, 47.20, 5.59 +-12.85, -10.00, 52.81, 47.19, 5.62 +-12.85, -10.00, 52.82, 47.18, 5.64 +-12.79, -10.00, 50.31, 49.69, 0.62 +-12.79, -10.00, 52.79, 47.21, 5.58 +-12.79, -10.00, 52.80, 47.20, 5.60 +-12.66, -10.00, 47.77, 52.23, -4.46 +-12.66, -10.00, 52.72, 47.28, 5.44 +-12.66, -10.00, 52.73, 47.27, 5.46 +-12.66, -10.00, 52.74, 47.26, 5.48 +-12.59, -10.00, 50.23, 49.77, 0.46 +-12.59, -10.00, 52.71, 47.29, 5.42 +-12.59, -10.00, 52.72, 47.28, 5.44 +-12.59, -10.00, 52.73, 47.27, 5.46 +-12.59, -10.00, 52.74, 47.26, 5.48 +-12.52, -10.00, 50.23, 49.77, 0.46 +-12.52, -10.00, 52.71, 47.29, 5.42 +-12.52, -10.00, 52.72, 47.28, 5.44 +-12.52, -10.00, 52.73, 47.27, 5.46 +-12.52, -10.00, 52.74, 47.26, 5.48 +-12.52, -10.00, 52.75, 47.25, 5.50 +-12.52, -10.00, 52.76, 47.24, 5.52 +-12.52, -10.00, 52.77, 47.23, 5.53 +-12.39, -10.00, 47.73, 52.27, -4.53 +-12.39, -10.00, 52.69, 47.31, 5.37 +-12.39, -10.00, 52.70, 47.30, 5.39 +-12.39, -10.00, 52.70, 47.30, 5.41 +-12.39, -10.00, 52.71, 47.29, 5.43 +-12.39, -10.00, 52.72, 47.28, 5.44 +-12.39, -10.00, 52.73, 47.27, 5.46 +-12.39, -10.00, 52.74, 47.26, 5.48 +-12.39, -10.00, 52.75, 47.25, 5.50 +-12.39, -10.00, 52.76, 47.24, 5.52 +-12.39, -10.00, 52.77, 47.23, 5.53 +-12.39, -10.00, 52.78, 47.22, 5.55 +-12.39, -10.00, 52.78, 47.22, 5.57 +-12.33, -10.00, 50.27, 49.73, 0.54 +-12.33, -10.00, 52.75, 47.25, 5.51 +-12.33, -10.00, 52.76, 47.24, 5.52 +-12.33, -10.00, 52.77, 47.23, 5.54 +-12.33, -10.00, 52.78, 47.22, 5.56 +-12.33, -10.00, 52.79, 47.21, 5.58 +-12.33, -10.00, 52.80, 47.20, 5.59 +-12.33, -10.00, 52.81, 47.19, 5.61 +-12.33, -10.00, 52.81, 47.19, 5.63 +-12.33, -10.00, 52.82, 47.18, 5.65 +-12.33, -10.00, 52.83, 47.17, 5.66 +-12.26, -10.00, 50.32, 49.68, 0.64 +-12.33, -10.00, 55.32, 44.68, 10.64 +-12.26, -10.00, 50.34, 49.66, 0.67 +-12.26, -10.00, 52.82, 47.18, 5.63 +-12.26, -10.00, 52.82, 47.18, 5.65 +-12.26, -10.00, 52.83, 47.17, 5.67 +-12.26, -10.00, 52.84, 47.16, 5.68 +-12.26, -10.00, 52.85, 47.15, 5.70 +-12.26, -10.00, 52.86, 47.14, 5.72 +-12.26, -10.00, 52.87, 47.13, 5.73 +-12.13, -10.00, 47.83, 52.17, -4.34 +-12.13, -10.00, 52.78, 47.22, 5.57 +-12.13, -10.00, 52.79, 47.21, 5.58 +-12.13, -10.00, 52.80, 47.20, 5.60 +-12.13, -10.00, 52.81, 47.19, 5.62 +-12.13, -10.00, 52.82, 47.18, 5.63 +-12.06, -10.00, 50.30, 49.70, 0.60 +-12.06, -10.00, 52.78, 47.22, 5.56 +-12.06, -10.00, 52.79, 47.21, 5.58 +-12.06, -10.00, 52.80, 47.20, 5.60 +-12.06, -10.00, 52.81, 47.19, 5.61 +-12.06, -10.00, 52.81, 47.19, 5.63 +-12.06, -10.00, 52.82, 47.18, 5.64 +-12.00, -10.00, 50.31, 49.69, 0.61 +-12.00, -10.00, 52.79, 47.21, 5.57 +-12.00, -10.00, 52.79, 47.21, 5.59 +-12.00, -10.00, 52.80, 47.20, 5.60 +-12.00, -10.00, 52.81, 47.19, 5.62 +-11.87, -10.00, 47.77, 52.23, -4.45 +-11.87, -10.00, 52.72, 47.28, 5.45 +-11.87, -10.00, 52.73, 47.27, 5.46 +-11.87, -10.00, 52.74, 47.26, 5.48 +-11.87, -10.00, 52.74, 47.26, 5.49 +-11.87, -10.00, 52.75, 47.25, 5.50 +-11.80, -10.00, 50.24, 49.76, 0.47 +-11.80, -10.00, 52.72, 47.28, 5.43 +-11.80, -10.00, 52.72, 47.28, 5.45 +-11.80, -10.00, 52.73, 47.27, 5.46 +-11.73, -10.00, 50.21, 49.79, 0.43 +-11.73, -10.00, 52.69, 47.31, 5.39 +-11.73, -10.00, 52.70, 47.30, 5.40 +-11.73, -10.00, 52.71, 47.29, 5.41 +-11.73, -10.00, 52.71, 47.29, 5.42 +-11.73, -10.00, 52.72, 47.28, 5.44 +-11.60, -10.00, 47.68, 52.32, -4.64 +-11.60, -10.00, 52.63, 47.37, 5.26 +-11.60, -10.00, 52.64, 47.36, 5.28 +-11.60, -10.00, 52.64, 47.36, 5.29 +-11.54, -10.00, 50.13, 49.87, 0.26 +-11.54, -10.00, 52.61, 47.39, 5.21 +-11.54, -10.00, 52.61, 47.39, 5.22 +-11.54, -10.00, 52.62, 47.38, 5.24 +-11.47, -10.00, 50.10, 49.90, 0.20 +-11.47, -10.00, 52.58, 47.42, 5.16 +-11.47, -10.00, 52.58, 47.42, 5.17 +-11.47, -10.00, 52.59, 47.41, 5.18 +-11.47, -10.00, 52.60, 47.40, 5.19 +-11.34, -10.00, 47.56, 52.44, -4.88 +-11.34, -10.00, 52.51, 47.49, 5.01 +-11.34, -10.00, 52.51, 47.49, 5.02 +-11.34, -10.00, 52.52, 47.48, 5.03 +-11.34, -10.00, 52.52, 47.48, 5.04 +-11.27, -10.00, 50.01, 49.99, 0.01 +-11.27, -10.00, 52.48, 47.52, 4.96 +-11.27, -10.00, 52.49, 47.51, 4.97 +-11.27, -10.00, 52.49, 47.51, 4.98 +-11.27, -10.00, 52.50, 47.50, 4.99 +-11.21, -10.00, 49.98, 50.02, -0.04 +-11.21, -10.00, 52.46, 47.54, 4.91 +-11.21, -10.00, 52.46, 47.54, 4.92 +-11.21, -10.00, 52.47, 47.53, 4.93 +-11.21, -10.00, 52.47, 47.53, 4.94 +-11.21, -10.00, 52.47, 47.53, 4.95 +-11.07, -10.00, 47.44, 52.56, -5.13 +-11.07, -10.00, 52.38, 47.62, 4.77 +-11.07, -10.00, 52.39, 47.61, 4.77 +-11.07, -10.00, 52.39, 47.61, 4.78 +-11.07, -10.00, 52.40, 47.60, 4.79 +-11.07, -10.00, 52.40, 47.60, 4.80 +-11.01, -10.00, 49.88, 50.12, -0.24 +-11.01, -10.00, 52.36, 47.64, 4.72 +-11.01, -10.00, 52.36, 47.64, 4.72 +-11.01, -10.00, 52.37, 47.63, 4.73 +-10.94, -10.00, 49.85, 50.15, -0.31 +-10.94, -10.00, 52.32, 47.68, 4.65 +-10.94, -10.00, 52.33, 47.67, 4.65 +-10.94, -10.00, 52.33, 47.67, 4.66 +-10.94, -10.00, 52.33, 47.67, 4.67 +-10.81, -10.00, 47.29, 52.71, -5.41 +-10.94, -10.00, 57.28, 42.72, 14.57 +-10.81, -10.00, 47.30, 52.70, -5.40 +-10.81, -10.00, 52.25, 47.75, 4.49 +-10.81, -10.00, 52.25, 47.75, 4.50 +-10.81, -10.00, 52.25, 47.75, 4.51 +-10.81, -10.00, 52.26, 47.74, 4.51 +-10.81, -10.00, 52.26, 47.74, 4.52 +-10.81, -10.00, 52.26, 47.74, 4.52 +-10.81, -10.00, 52.27, 47.73, 4.53 +-10.74, -10.00, 49.75, 50.25, -0.51 +-10.74, -10.00, 52.22, 47.78, 4.44 +-10.74, -10.00, 52.22, 47.78, 4.45 +-10.74, -10.00, 52.23, 47.77, 4.45 +-10.74, -10.00, 52.23, 47.77, 4.46 +-10.74, -10.00, 52.23, 47.77, 4.47 +-10.74, -10.00, 52.24, 47.76, 4.47 +-10.74, -10.00, 52.24, 47.76, 4.48 +-10.74, -10.00, 52.24, 47.76, 4.48 +-10.74, -10.00, 52.24, 47.76, 4.49 +-10.74, -10.00, 52.25, 47.75, 4.49 +-10.74, -10.00, 52.25, 47.75, 4.50 +-10.74, -10.00, 52.25, 47.75, 4.50 +-10.74, -10.00, 52.26, 47.74, 4.51 +-10.74, -10.00, 52.26, 47.74, 4.52 +-10.74, -10.00, 52.26, 47.74, 4.52 +-10.74, -10.00, 52.26, 47.74, 4.53 +-10.74, -10.00, 52.27, 47.73, 4.53 +-10.74, -10.00, 52.27, 47.73, 4.54 +-10.74, -10.00, 52.27, 47.73, 4.54 +-10.74, -10.00, 52.27, 47.73, 4.55 +-10.74, -10.00, 52.28, 47.72, 4.55 +-10.74, -10.00, 52.28, 47.72, 4.56 +-10.74, -10.00, 52.28, 47.72, 4.57 +-10.74, -10.00, 52.29, 47.71, 4.57 +-10.74, -10.00, 52.29, 47.71, 4.58 +-10.74, -10.00, 52.29, 47.71, 4.58 +-10.74, -10.00, 52.29, 47.71, 4.59 +-10.74, -10.00, 52.30, 47.70, 4.59 +-10.74, -10.00, 52.30, 47.70, 4.60 +-10.74, -10.00, 52.30, 47.70, 4.60 +-10.74, -10.00, 52.31, 47.69, 4.61 +-10.68, -10.00, 49.79, 50.21, -0.43 +-10.74, -10.00, 54.78, 45.22, 9.57 +-10.74, -10.00, 52.31, 47.69, 4.63 +-10.74, -10.00, 52.32, 47.68, 4.63 +-10.74, -10.00, 52.32, 47.68, 4.64 +-10.68, -10.00, 49.80, 50.20, -0.40 +-10.74, -10.00, 54.80, 45.20, 9.59 +-10.68, -10.00, 49.81, 50.19, -0.39 +-10.74, -10.00, 54.80, 45.20, 9.60 +-10.74, -10.00, 52.33, 47.67, 4.66 +-10.68, -10.00, 49.81, 50.19, -0.37 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.59 +-10.74, -10.00, 54.82, 45.18, 9.64 +-10.74, -10.00, 52.35, 47.65, 4.70 +-10.74, -10.00, 52.35, 47.65, 4.71 +-10.74, -10.00, 52.36, 47.64, 4.71 +-10.74, -10.00, 52.36, 47.64, 4.72 +-10.74, -10.00, 52.36, 47.64, 4.72 +-10.74, -10.00, 52.36, 47.64, 4.73 +-10.74, -10.00, 52.37, 47.63, 4.74 +-10.74, -10.00, 52.37, 47.63, 4.74 +-10.74, -10.00, 52.37, 47.63, 4.75 +-10.74, -10.00, 52.38, 47.62, 4.75 +-10.74, -10.00, 52.38, 47.62, 4.76 +-10.81, -10.00, 54.90, 45.10, 9.81 +-10.81, -10.00, 52.43, 47.57, 4.87 +-10.81, -10.00, 52.44, 47.56, 4.87 +-10.81, -10.00, 52.44, 47.56, 4.88 +-10.81, -10.00, 52.44, 47.56, 4.89 +-10.81, -10.00, 52.45, 47.55, 4.89 +-10.81, -10.00, 52.45, 47.55, 4.90 +-10.81, -10.00, 52.45, 47.55, 4.90 +-10.81, -10.00, 52.46, 47.54, 4.91 +-10.81, -10.00, 52.46, 47.54, 4.92 +-10.94, -10.00, 57.50, 42.50, 15.01 +-10.94, -10.00, 52.56, 47.44, 5.13 +-10.94, -10.00, 52.57, 47.43, 5.14 +-10.94, -10.00, 52.57, 47.43, 5.14 +-10.94, -10.00, 52.58, 47.42, 5.15 +-10.94, -10.00, 52.58, 47.42, 5.16 +-10.94, -10.00, 52.58, 47.42, 5.16 +-10.94, -10.00, 52.59, 47.41, 5.17 +-10.94, -10.00, 52.59, 47.41, 5.18 +-10.94, -10.00, 52.59, 47.41, 5.19 +-11.01, -10.00, 55.12, 44.88, 10.24 +-11.01, -10.00, 52.65, 47.35, 5.30 +-11.01, -10.00, 52.65, 47.35, 5.31 +-11.01, -10.00, 52.66, 47.34, 5.31 +-11.01, -10.00, 52.66, 47.34, 5.32 +-11.01, -10.00, 52.66, 47.34, 5.33 +-11.01, -10.00, 52.67, 47.33, 5.34 +-11.01, -10.00, 52.67, 47.33, 5.34 +-11.01, -10.00, 52.68, 47.32, 5.35 +-11.01, -10.00, 52.68, 47.32, 5.36 +-11.01, -10.00, 52.68, 47.32, 5.37 +-11.07, -10.00, 55.21, 44.79, 10.42 +-11.07, -10.00, 52.74, 47.26, 5.48 +-11.07, -10.00, 52.75, 47.25, 5.49 +-11.07, -10.00, 52.75, 47.25, 5.50 +-11.07, -10.00, 52.75, 47.25, 5.51 +-11.07, -10.00, 52.76, 47.24, 5.51 +-11.07, -10.00, 52.76, 47.24, 5.52 +-11.07, -10.00, 52.77, 47.23, 5.53 +-11.07, -10.00, 52.77, 47.23, 5.54 +-11.07, -10.00, 52.77, 47.23, 5.55 +-11.21, -10.00, 57.82, 42.18, 15.64 +-11.21, -10.00, 52.88, 47.12, 5.76 +-11.21, -10.00, 52.89, 47.11, 5.77 +-11.21, -10.00, 52.89, 47.11, 5.78 +-11.21, -10.00, 52.89, 47.11, 5.79 +-11.21, -10.00, 52.90, 47.10, 5.80 +-11.21, -10.00, 52.90, 47.10, 5.81 +-11.21, -10.00, 52.91, 47.09, 5.82 +-11.21, -10.00, 52.91, 47.09, 5.83 +-11.21, -10.00, 52.92, 47.08, 5.84 +-11.21, -10.00, 52.92, 47.08, 5.84 +-11.21, -10.00, 52.93, 47.07, 5.85 +-11.21, -10.00, 52.93, 47.07, 5.86 +-11.21, -10.00, 52.94, 47.06, 5.87 +-11.21, -10.00, 52.94, 47.06, 5.88 +-11.21, -10.00, 52.94, 47.06, 5.89 +-11.21, -10.00, 52.95, 47.05, 5.90 +-11.21, -10.00, 52.95, 47.05, 5.91 +-11.21, -10.00, 52.96, 47.04, 5.92 +-11.21, -10.00, 52.96, 47.04, 5.93 +-11.21, -10.00, 52.97, 47.03, 5.93 +-11.21, -10.00, 52.97, 47.03, 5.94 +-11.21, -10.00, 52.98, 47.02, 5.95 +-11.21, -10.00, 52.98, 47.02, 5.96 +-11.21, -10.00, 52.99, 47.01, 5.97 +-11.21, -10.00, 52.99, 47.01, 5.98 +-11.21, -10.00, 52.99, 47.01, 5.99 +-11.21, -10.00, 53.00, 47.00, 6.00 +-11.21, -10.00, 53.00, 47.00, 6.01 +-11.21, -10.00, 53.01, 46.99, 6.02 +-11.21, -10.00, 53.01, 46.99, 6.03 +-11.21, -10.00, 53.02, 46.98, 6.03 +-11.21, -10.00, 53.02, 46.98, 6.04 +-11.21, -10.00, 53.03, 46.97, 6.05 +-11.21, -10.00, 53.03, 46.97, 6.06 +-11.21, -10.00, 53.04, 46.96, 6.07 +-11.21, -10.00, 53.04, 46.96, 6.08 +-11.21, -10.00, 53.04, 46.96, 6.09 +-11.21, -10.00, 53.05, 46.95, 6.10 +-11.21, -10.00, 53.05, 46.95, 6.11 +-11.21, -10.00, 53.06, 46.94, 6.12 +-11.21, -10.00, 53.06, 46.94, 6.12 +-11.21, -10.00, 53.07, 46.93, 6.13 +-11.21, -10.00, 53.07, 46.93, 6.14 +-11.21, -10.00, 53.08, 46.92, 6.15 +-11.21, -10.00, 53.08, 46.92, 6.16 +-11.21, -10.00, 53.08, 46.92, 6.17 +-11.21, -10.00, 53.09, 46.91, 6.18 +-11.21, -10.00, 53.09, 46.91, 6.19 +-11.21, -10.00, 53.10, 46.90, 6.20 +-11.21, -10.00, 53.10, 46.90, 6.21 +-11.21, -10.00, 53.11, 46.89, 6.22 +-11.21, -10.00, 53.11, 46.89, 6.22 +-11.21, -10.00, 53.12, 46.88, 6.23 +-11.21, -10.00, 53.12, 46.88, 6.24 +-11.21, -10.00, 53.13, 46.87, 6.25 +-11.21, -10.00, 53.13, 46.87, 6.26 +-11.21, -10.00, 53.13, 46.87, 6.27 +-11.21, -10.00, 53.14, 46.86, 6.28 +-11.21, -10.00, 53.14, 46.86, 6.29 +-11.07, -10.00, 48.11, 51.89, -3.79 +-11.21, -10.00, 58.10, 41.90, 16.19 +-11.07, -10.00, 48.11, 51.89, -3.77 +-11.07, -10.00, 53.06, 46.94, 6.12 +-11.07, -10.00, 53.07, 46.93, 6.13 +-11.07, -10.00, 53.07, 46.93, 6.14 +-11.07, -10.00, 53.07, 46.93, 6.15 +-11.01, -10.00, 50.56, 49.44, 1.11 +-11.01, -10.00, 53.03, 46.97, 6.06 +-11.01, -10.00, 53.04, 46.96, 6.07 +-11.01, -10.00, 53.04, 46.96, 6.08 +-11.01, -10.00, 53.04, 46.96, 6.09 +-11.01, -10.00, 53.05, 46.95, 6.09 +-10.94, -10.00, 50.53, 49.47, 1.06 +-10.94, -10.00, 53.00, 47.00, 6.01 +-10.94, -10.00, 53.01, 46.99, 6.02 +-10.94, -10.00, 53.01, 46.99, 6.02 +-10.81, -10.00, 47.97, 52.03, -4.06 +-10.81, -10.00, 52.92, 47.08, 5.84 +-10.81, -10.00, 52.92, 47.08, 5.84 +-10.81, -10.00, 52.92, 47.08, 5.85 +-10.81, -10.00, 52.93, 47.07, 5.86 +-10.81, -10.00, 52.93, 47.07, 5.86 +-10.81, -10.00, 52.93, 47.07, 5.87 +-10.74, -10.00, 50.42, 49.58, 0.83 +-10.74, -10.00, 52.89, 47.11, 5.78 +-10.74, -10.00, 52.89, 47.11, 5.79 +-10.74, -10.00, 52.90, 47.10, 5.79 +-10.74, -10.00, 52.90, 47.10, 5.80 +-10.68, -10.00, 50.38, 49.62, 0.76 +-10.68, -10.00, 52.85, 47.15, 5.71 +-10.68, -10.00, 52.86, 47.14, 5.71 +-10.68, -10.00, 52.86, 47.14, 5.72 +-10.68, -10.00, 52.86, 47.14, 5.72 +-10.68, -10.00, 52.86, 47.14, 5.73 +-10.68, -10.00, 52.87, 47.13, 5.73 +-10.68, -10.00, 52.87, 47.13, 5.74 +-10.55, -10.00, 47.83, 52.17, -4.34 +-10.55, -10.00, 52.77, 47.23, 5.55 +-10.55, -10.00, 52.78, 47.22, 5.55 +-10.55, -10.00, 52.78, 47.22, 5.56 +-10.55, -10.00, 52.78, 47.22, 5.56 +-10.55, -10.00, 52.78, 47.22, 5.57 +-10.55, -10.00, 52.78, 47.22, 5.57 +-10.55, -10.00, 52.79, 47.21, 5.57 +-10.55, -10.00, 52.79, 47.21, 5.58 +-10.55, -10.00, 52.79, 47.21, 5.58 +-10.55, -10.00, 52.79, 47.21, 5.59 +-10.48, -10.00, 50.27, 49.73, 0.55 +-10.55, -10.00, 55.27, 44.73, 10.54 +-10.48, -10.00, 50.28, 49.72, 0.55 +-10.48, -10.00, 52.75, 47.25, 5.50 +-10.48, -10.00, 52.75, 47.25, 5.51 +-10.48, -10.00, 52.75, 47.25, 5.51 +-10.48, -10.00, 52.76, 47.24, 5.51 +-10.48, -10.00, 52.76, 47.24, 5.52 +-10.48, -10.00, 52.76, 47.24, 5.52 +-10.48, -10.00, 52.76, 47.24, 5.52 +-10.48, -10.00, 52.76, 47.24, 5.53 +-10.48, -10.00, 52.77, 47.23, 5.53 +-10.48, -10.00, 52.77, 47.23, 5.53 +-10.48, -10.00, 52.77, 47.23, 5.54 +-10.48, -10.00, 52.77, 47.23, 5.54 +-10.48, -10.00, 52.77, 47.23, 5.55 +-10.42, -10.00, 50.25, 49.75, 0.51 +-10.48, -10.00, 55.25, 44.75, 10.50 +-10.42, -10.00, 50.26, 49.74, 0.51 +-10.42, -10.00, 52.73, 47.27, 5.46 +-10.42, -10.00, 52.73, 47.27, 5.46 +-10.42, -10.00, 52.73, 47.27, 5.47 +-10.42, -10.00, 52.73, 47.27, 5.47 +-10.42, -10.00, 52.74, 47.26, 5.47 +-10.42, -10.00, 52.74, 47.26, 5.48 +-10.42, -10.00, 52.74, 47.26, 5.48 +-10.28, -10.00, 47.70, 52.30, -4.61 +-10.28, -10.00, 52.64, 47.36, 5.28 +-10.28, -10.00, 52.64, 47.36, 5.29 +-10.28, -10.00, 52.64, 47.36, 5.29 +-10.28, -10.00, 52.65, 47.35, 5.29 +-10.28, -10.00, 52.65, 47.35, 5.29 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.31 +-10.28, -10.00, 52.65, 47.35, 5.31 +-10.28, -10.00, 52.66, 47.34, 5.31 +-10.28, -10.00, 52.66, 47.34, 5.31 +-10.28, -10.00, 52.66, 47.34, 5.31 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.42, -10.00, 57.71, 42.29, 15.41 +-10.42, -10.00, 52.76, 47.24, 5.53 +-10.42, -10.00, 52.77, 47.23, 5.53 +-10.42, -10.00, 52.77, 47.23, 5.54 +-10.42, -10.00, 52.77, 47.23, 5.54 +-10.42, -10.00, 52.77, 47.23, 5.54 +-10.42, -10.00, 52.77, 47.23, 5.54 +-10.42, -10.00, 52.77, 47.23, 5.55 +-10.42, -10.00, 52.78, 47.22, 5.55 +-10.48, -10.00, 55.30, 44.70, 10.60 +-10.48, -10.00, 52.83, 47.17, 5.66 +-10.48, -10.00, 52.83, 47.17, 5.66 +-10.48, -10.00, 52.83, 47.17, 5.66 +-10.48, -10.00, 52.83, 47.17, 5.67 +-10.48, -10.00, 52.84, 47.16, 5.67 +-10.48, -10.00, 52.84, 47.16, 5.67 +-10.48, -10.00, 52.84, 47.16, 5.68 +-10.48, -10.00, 52.84, 47.16, 5.68 +-10.55, -10.00, 55.36, 44.64, 10.73 +-10.55, -10.00, 52.89, 47.11, 5.79 +-10.55, -10.00, 52.90, 47.10, 5.79 +-10.55, -10.00, 52.90, 47.10, 5.80 +-10.55, -10.00, 52.90, 47.10, 5.80 +-10.55, -10.00, 52.90, 47.10, 5.81 +-10.55, -10.00, 52.90, 47.10, 5.81 +-10.55, -10.00, 52.91, 47.09, 5.81 +-10.55, -10.00, 52.91, 47.09, 5.82 +-10.68, -10.00, 57.95, 42.05, 15.91 +-10.68, -10.00, 53.01, 46.99, 6.03 +-10.68, -10.00, 53.02, 46.98, 6.03 +-10.68, -10.00, 53.02, 46.98, 6.04 +-10.68, -10.00, 53.02, 46.98, 6.04 +-10.68, -10.00, 53.02, 46.98, 6.05 +-10.68, -10.00, 53.03, 46.97, 6.05 +-10.68, -10.00, 53.03, 46.97, 6.06 +-10.68, -10.00, 53.03, 46.97, 6.06 +-10.68, -10.00, 53.03, 46.97, 6.07 +-10.68, -10.00, 53.04, 46.96, 6.07 +-10.68, -10.00, 53.04, 46.96, 6.08 +-10.68, -10.00, 53.04, 46.96, 6.08 +-10.74, -10.00, 55.57, 44.43, 11.13 +-10.68, -10.00, 50.57, 49.43, 1.15 +-10.68, -10.00, 53.05, 46.95, 6.10 +-10.74, -10.00, 55.57, 44.43, 11.15 +-10.74, -10.00, 53.10, 46.90, 6.21 +-10.68, -10.00, 50.58, 49.42, 1.17 +-10.68, -10.00, 53.06, 46.94, 6.12 +-10.68, -10.00, 53.06, 46.94, 6.12 +-10.68, -10.00, 53.06, 46.94, 6.13 +-10.68, -10.00, 53.07, 46.93, 6.13 +-10.68, -10.00, 53.07, 46.93, 6.14 +-10.68, -10.00, 53.07, 46.93, 6.14 +-10.55, -10.00, 48.03, 51.97, -3.94 +-10.55, -10.00, 52.98, 47.02, 5.95 +-10.55, -10.00, 52.98, 47.02, 5.96 +-10.55, -10.00, 52.98, 47.02, 5.96 +-10.55, -10.00, 52.98, 47.02, 5.97 +-10.55, -10.00, 52.99, 47.01, 5.97 +-10.48, -10.00, 50.47, 49.53, 0.93 +-10.48, -10.00, 52.94, 47.06, 5.88 +-10.48, -10.00, 52.94, 47.06, 5.88 +-10.48, -10.00, 52.94, 47.06, 5.89 +-10.48, -10.00, 52.95, 47.05, 5.89 +-10.42, -10.00, 50.43, 49.57, 0.85 +-10.42, -10.00, 52.90, 47.10, 5.80 +-10.42, -10.00, 52.90, 47.10, 5.80 +-10.28, -10.00, 47.86, 52.14, -4.28 +-10.28, -10.00, 52.80, 47.20, 5.61 +-10.28, -10.00, 52.80, 47.20, 5.61 +-10.22, -10.00, 50.28, 49.72, 0.57 +-10.22, -10.00, 52.76, 47.24, 5.51 +-10.22, -10.00, 52.76, 47.24, 5.52 +-10.22, -10.00, 52.76, 47.24, 5.52 +-10.22, -10.00, 52.76, 47.24, 5.52 +-10.15, -10.00, 50.24, 49.76, 0.48 +-10.15, -10.00, 52.71, 47.29, 5.42 +-10.15, -10.00, 52.71, 47.29, 5.42 +-10.15, -10.00, 52.71, 47.29, 5.42 +-10.02, -10.00, 47.67, 52.33, -4.66 +-10.02, -10.00, 52.61, 47.39, 5.23 +-10.02, -10.00, 52.61, 47.39, 5.23 +-10.02, -10.00, 52.61, 47.39, 5.23 +-10.02, -10.00, 52.61, 47.39, 5.23 +-9.95, -10.00, 50.09, 49.91, 0.18 +-9.95, -10.00, 52.56, 47.44, 5.13 +-9.89, -10.00, 50.04, 49.96, 0.08 +-9.89, -10.00, 52.51, 47.49, 5.03 +-9.89, -10.00, 52.51, 47.49, 5.03 +-9.89, -10.00, 52.51, 47.49, 5.03 +-9.76, -10.00, 47.47, 52.53, -5.06 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.81 +-9.76, -10.00, 52.41, 47.59, 4.81 +-9.69, -10.00, 49.88, 50.12, -0.23 +-9.76, -10.00, 54.88, 45.12, 9.75 +-9.76, -10.00, 52.40, 47.60, 4.81 +-9.69, -10.00, 49.88, 50.12, -0.24 +-9.69, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 52.35, 47.65, 4.69 +-9.69, -10.00, 52.35, 47.65, 4.69 +-9.62, -10.00, 49.82, 50.18, -0.35 +-9.62, -10.00, 52.29, 47.71, 4.59 +-9.62, -10.00, 52.29, 47.71, 4.58 +-9.62, -10.00, 52.29, 47.71, 4.58 +-9.62, -10.00, 52.29, 47.71, 4.58 +-9.62, -10.00, 52.29, 47.71, 4.58 +-9.62, -10.00, 52.29, 47.71, 4.57 +-9.62, -10.00, 52.29, 47.71, 4.57 +-9.62, -10.00, 52.28, 47.72, 4.57 +-9.62, -10.00, 52.28, 47.72, 4.56 +-9.62, -10.00, 52.28, 47.72, 4.56 +-9.62, -10.00, 52.28, 47.72, 4.56 +-9.62, -10.00, 52.28, 47.72, 4.56 +-9.62, -10.00, 52.28, 47.72, 4.55 +-9.62, -10.00, 52.28, 47.72, 4.55 +-9.62, -10.00, 52.27, 47.73, 4.55 +-9.62, -10.00, 52.27, 47.73, 4.55 +-9.49, -10.00, 47.23, 52.77, -5.54 +-9.62, -10.00, 57.21, 42.79, 14.43 +-9.49, -10.00, 47.22, 52.78, -5.55 +-9.49, -10.00, 52.17, 47.83, 4.33 +-9.62, -10.00, 57.21, 42.79, 14.42 +-9.62, -10.00, 52.26, 47.74, 4.53 +-9.62, -10.00, 52.26, 47.74, 4.52 +-9.62, -10.00, 52.26, 47.74, 4.52 +-9.62, -10.00, 52.26, 47.74, 4.52 +-9.62, -10.00, 52.26, 47.74, 4.51 +-9.62, -10.00, 52.26, 47.74, 4.51 +-9.62, -10.00, 52.25, 47.75, 4.51 +-9.62, -10.00, 52.25, 47.75, 4.51 +-9.62, -10.00, 52.25, 47.75, 4.50 +-9.69, -10.00, 54.77, 45.23, 9.54 +-9.69, -10.00, 52.30, 47.70, 4.60 +-9.69, -10.00, 52.30, 47.70, 4.59 +-9.69, -10.00, 52.30, 47.70, 4.59 +-9.69, -10.00, 52.30, 47.70, 4.59 +-9.69, -10.00, 52.29, 47.71, 4.59 +-9.69, -10.00, 52.29, 47.71, 4.59 +-9.76, -10.00, 54.81, 45.19, 9.63 +-9.76, -10.00, 52.34, 47.66, 4.68 +-9.76, -10.00, 52.34, 47.66, 4.68 +-9.76, -10.00, 52.34, 47.66, 4.68 +-9.76, -10.00, 52.34, 47.66, 4.68 +-9.76, -10.00, 52.34, 47.66, 4.67 +-9.76, -10.00, 52.34, 47.66, 4.67 +-9.76, -10.00, 52.33, 47.67, 4.67 +-9.76, -10.00, 52.33, 47.67, 4.67 +-9.89, -10.00, 57.38, 42.62, 14.75 +-9.89, -10.00, 52.43, 47.57, 4.86 +-9.89, -10.00, 52.43, 47.57, 4.86 +-9.89, -10.00, 52.43, 47.57, 4.86 +-9.95, -10.00, 54.95, 45.05, 9.90 +-9.95, -10.00, 52.48, 47.52, 4.96 +-9.95, -10.00, 52.48, 47.52, 4.96 +-9.95, -10.00, 52.48, 47.52, 4.96 +-10.02, -10.00, 55.00, 45.00, 10.00 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.15, -10.00, 57.57, 42.43, 15.15 +-10.15, -10.00, 52.63, 47.37, 5.26 +-10.15, -10.00, 52.63, 47.37, 5.26 +-10.15, -10.00, 52.63, 47.37, 5.26 +-10.22, -10.00, 55.15, 44.85, 10.31 +-10.22, -10.00, 52.68, 47.32, 5.36 +-10.22, -10.00, 52.68, 47.32, 5.37 +-10.22, -10.00, 52.68, 47.32, 5.37 +-10.28, -10.00, 55.21, 44.79, 10.41 +-10.28, -10.00, 52.74, 47.26, 5.47 +-10.28, -10.00, 52.74, 47.26, 5.47 +-10.28, -10.00, 52.74, 47.26, 5.47 +-10.42, -10.00, 57.78, 42.22, 15.56 +-10.42, -10.00, 52.84, 47.16, 5.68 +-10.42, -10.00, 52.84, 47.16, 5.68 +-10.42, -10.00, 52.84, 47.16, 5.68 +-10.42, -10.00, 52.84, 47.16, 5.69 +-10.48, -10.00, 55.37, 44.63, 10.73 +-10.48, -10.00, 52.90, 47.10, 5.79 +-10.48, -10.00, 52.90, 47.10, 5.80 +-10.55, -10.00, 55.42, 44.58, 10.84 +-10.55, -10.00, 52.95, 47.05, 5.90 +-10.55, -10.00, 52.95, 47.05, 5.91 +-10.55, -10.00, 52.96, 47.04, 5.91 +-10.68, -10.00, 58.00, 42.00, 16.00 +-10.68, -10.00, 53.06, 46.94, 6.12 +-10.68, -10.00, 53.06, 46.94, 6.13 +-10.74, -10.00, 55.59, 44.41, 11.17 +-10.74, -10.00, 53.12, 46.88, 6.24 +-10.81, -10.00, 55.64, 44.36, 11.28 +-10.81, -10.00, 53.17, 46.83, 6.35 +-10.81, -10.00, 53.18, 46.82, 6.35 +-10.94, -10.00, 58.22, 41.78, 16.45 +-10.94, -10.00, 53.28, 46.72, 6.56 +-10.94, -10.00, 53.29, 46.71, 6.57 +-11.01, -10.00, 55.81, 44.19, 11.62 +-11.01, -10.00, 53.34, 46.66, 6.69 +-11.07, -10.00, 55.87, 44.13, 11.74 +-11.07, -10.00, 53.40, 46.60, 6.80 +-11.07, -10.00, 53.40, 46.60, 6.81 +-11.21, -10.00, 58.45, 41.55, 16.90 +-11.21, -10.00, 53.51, 46.49, 7.02 +-11.21, -10.00, 53.52, 46.48, 7.03 +-11.21, -10.00, 53.52, 46.48, 7.04 +-11.27, -10.00, 56.05, 43.95, 12.10 +-11.27, -10.00, 53.58, 46.42, 7.16 +-11.34, -10.00, 56.11, 43.89, 12.21 +-11.34, -10.00, 53.64, 46.36, 7.28 +-11.34, -10.00, 53.64, 46.36, 7.29 +-11.47, -10.00, 58.69, 41.31, 17.39 +-11.47, -10.00, 53.75, 46.25, 7.51 +-11.47, -10.00, 53.76, 46.24, 7.52 +-11.47, -10.00, 53.77, 46.23, 7.53 +-11.54, -10.00, 56.29, 43.71, 12.59 +-11.54, -10.00, 53.83, 46.17, 7.65 +-11.60, -10.00, 56.35, 43.65, 12.71 +-11.60, -10.00, 53.89, 46.11, 7.78 +-11.60, -10.00, 53.89, 46.11, 7.79 +-11.60, -10.00, 53.90, 46.10, 7.80 +-11.73, -10.00, 58.95, 41.05, 17.90 +-11.73, -10.00, 54.01, 45.99, 8.02 +-11.73, -10.00, 54.02, 45.98, 8.04 +-11.73, -10.00, 54.03, 45.97, 8.05 +-11.73, -10.00, 54.03, 45.97, 8.06 +-11.73, -10.00, 54.04, 45.96, 8.08 +-11.80, -10.00, 56.57, 43.43, 13.13 +-11.80, -10.00, 54.10, 45.90, 8.20 +-11.80, -10.00, 54.11, 45.89, 8.22 +-11.87, -10.00, 56.64, 43.36, 13.27 +-11.87, -10.00, 54.17, 45.83, 8.34 +-11.87, -10.00, 54.18, 45.82, 8.36 +-11.87, -10.00, 54.19, 45.81, 8.37 +-11.87, -10.00, 54.19, 45.81, 8.38 +-11.87, -10.00, 54.20, 45.80, 8.40 +-11.87, -10.00, 54.21, 45.79, 8.41 +-11.87, -10.00, 54.21, 45.79, 8.43 +-11.87, -10.00, 54.22, 45.78, 8.44 +-11.87, -10.00, 54.23, 45.77, 8.45 +-11.87, -10.00, 54.23, 45.77, 8.47 +-11.87, -10.00, 54.24, 45.76, 8.48 +-11.87, -10.00, 54.25, 45.75, 8.50 +-11.87, -10.00, 54.26, 45.74, 8.51 +-12.00, -10.00, 59.31, 40.69, 18.61 +-11.87, -10.00, 49.33, 50.67, -1.35 +-11.87, -10.00, 54.28, 45.72, 8.55 +-11.87, -10.00, 54.28, 45.72, 8.57 +-11.87, -10.00, 54.29, 45.71, 8.58 +-11.87, -10.00, 54.30, 45.70, 8.60 +-11.87, -10.00, 54.30, 45.70, 8.61 +-11.87, -10.00, 54.31, 45.69, 8.62 +-11.87, -10.00, 54.32, 45.68, 8.64 +-11.87, -10.00, 54.33, 45.67, 8.65 +-11.87, -10.00, 54.33, 45.67, 8.67 +-11.87, -10.00, 54.34, 45.66, 8.68 +-11.87, -10.00, 54.35, 45.65, 8.69 +-11.87, -10.00, 54.35, 45.65, 8.71 +-11.87, -10.00, 54.36, 45.64, 8.72 +-11.87, -10.00, 54.37, 45.63, 8.74 +-11.87, -10.00, 54.37, 45.63, 8.75 +-11.87, -10.00, 54.38, 45.62, 8.76 +-11.87, -10.00, 54.39, 45.61, 8.78 +-11.87, -10.00, 54.40, 45.60, 8.79 +-11.87, -10.00, 54.40, 45.60, 8.81 +-11.87, -10.00, 54.41, 45.59, 8.82 +-11.87, -10.00, 54.42, 45.58, 8.83 +-11.87, -10.00, 54.42, 45.58, 8.85 +-11.87, -10.00, 54.43, 45.57, 8.86 +-11.80, -10.00, 51.92, 48.08, 3.83 +-11.80, -10.00, 54.39, 45.61, 8.79 +-11.80, -10.00, 54.40, 45.60, 8.80 +-11.80, -10.00, 54.41, 45.59, 8.82 +-11.80, -10.00, 54.41, 45.59, 8.83 +-11.73, -10.00, 51.90, 48.10, 3.80 +-11.73, -10.00, 54.38, 45.62, 8.76 +-11.73, -10.00, 54.38, 45.62, 8.77 +-11.73, -10.00, 54.39, 45.61, 8.78 +-11.73, -10.00, 54.40, 45.60, 8.80 +-11.73, -10.00, 54.40, 45.60, 8.81 +-11.73, -10.00, 54.41, 45.59, 8.82 +-11.73, -10.00, 54.42, 45.58, 8.83 +-11.60, -10.00, 49.38, 50.62, -1.24 +-11.60, -10.00, 54.33, 45.67, 8.66 +-11.60, -10.00, 54.34, 45.66, 8.67 +-11.60, -10.00, 54.34, 45.66, 8.69 +-11.54, -10.00, 51.83, 48.17, 3.65 +-11.54, -10.00, 54.30, 45.70, 8.61 +-11.47, -10.00, 51.79, 48.21, 3.58 +-11.47, -10.00, 54.27, 45.73, 8.53 +-11.47, -10.00, 54.27, 45.73, 8.54 +-11.47, -10.00, 54.28, 45.72, 8.55 +-11.34, -10.00, 49.24, 50.76, -1.52 +-11.34, -10.00, 54.19, 45.81, 8.38 +-11.27, -10.00, 51.67, 48.33, 3.34 +-11.27, -10.00, 54.15, 45.85, 8.30 +-11.27, -10.00, 54.15, 45.85, 8.31 +-11.21, -10.00, 51.64, 48.36, 3.27 +-11.21, -10.00, 54.11, 45.89, 8.23 +-11.21, -10.00, 54.12, 45.88, 8.23 +-11.21, -10.00, 54.12, 45.88, 8.24 +-11.07, -10.00, 49.08, 50.92, -1.83 +-11.07, -10.00, 54.03, 45.97, 8.06 +-11.01, -10.00, 51.51, 48.49, 3.03 +-11.01, -10.00, 53.99, 46.01, 7.98 +-11.01, -10.00, 53.99, 46.01, 7.99 +-10.94, -10.00, 51.48, 48.52, 2.95 +-10.94, -10.00, 53.95, 46.05, 7.90 +-10.81, -10.00, 48.91, 51.09, -2.18 +-10.81, -10.00, 53.86, 46.14, 7.72 +-10.74, -10.00, 51.34, 48.66, 2.68 +-10.74, -10.00, 53.81, 46.19, 7.63 +-10.74, -10.00, 53.82, 46.18, 7.63 +-10.68, -10.00, 51.30, 48.70, 2.60 +-10.68, -10.00, 53.77, 46.23, 7.54 +-10.68, -10.00, 53.77, 46.23, 7.55 +-10.55, -10.00, 48.73, 51.27, -2.53 +-10.55, -10.00, 53.68, 46.32, 7.36 +-10.55, -10.00, 53.68, 46.32, 7.36 +-10.55, -10.00, 53.68, 46.32, 7.37 +-10.55, -10.00, 53.69, 46.31, 7.37 +-10.48, -10.00, 51.17, 48.83, 2.33 +-10.48, -10.00, 53.64, 46.36, 7.28 +-10.48, -10.00, 53.64, 46.36, 7.28 +-10.48, -10.00, 53.64, 46.36, 7.29 +-10.48, -10.00, 53.65, 46.35, 7.29 +-10.42, -10.00, 51.13, 48.87, 2.25 +-10.42, -10.00, 53.60, 46.40, 7.20 +-10.42, -10.00, 53.60, 46.40, 7.20 +-10.42, -10.00, 53.60, 46.40, 7.21 +-10.42, -10.00, 53.60, 46.40, 7.21 +-10.42, -10.00, 53.61, 46.39, 7.21 +-10.42, -10.00, 53.61, 46.39, 7.21 +-10.28, -10.00, 48.57, 51.43, -2.87 +-10.28, -10.00, 53.51, 46.49, 7.02 +-10.28, -10.00, 53.51, 46.49, 7.02 +-10.28, -10.00, 53.51, 46.49, 7.03 +-10.28, -10.00, 53.51, 46.49, 7.03 +-10.28, -10.00, 53.51, 46.49, 7.03 +-10.28, -10.00, 53.52, 46.48, 7.03 +-10.28, -10.00, 53.52, 46.48, 7.03 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.05 +-10.28, -10.00, 53.52, 46.48, 7.05 +-10.28, -10.00, 53.53, 46.47, 7.05 +-10.28, -10.00, 53.53, 46.47, 7.05 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.07 +-10.28, -10.00, 53.53, 46.47, 7.07 +-10.28, -10.00, 53.54, 46.46, 7.07 +-10.28, -10.00, 53.54, 46.46, 7.07 +-10.28, -10.00, 53.54, 46.46, 7.07 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.09 +-10.28, -10.00, 53.54, 46.46, 7.09 +-10.28, -10.00, 53.55, 46.45, 7.09 +-10.28, -10.00, 53.55, 46.45, 7.09 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.11 +-10.28, -10.00, 53.55, 46.45, 7.11 +-10.22, -10.00, 51.03, 48.97, 2.07 +-10.22, -10.00, 53.51, 46.49, 7.01 +-10.22, -10.00, 53.51, 46.49, 7.01 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.15, -10.00, 50.99, 49.01, 1.98 +-10.15, -10.00, 53.46, 46.54, 6.93 +-10.15, -10.00, 53.46, 46.54, 6.93 +-10.15, -10.00, 53.46, 46.54, 6.93 +-10.02, -10.00, 48.42, 51.58, -3.16 +-10.02, -10.00, 53.37, 46.63, 6.73 +-10.02, -10.00, 53.37, 46.63, 6.73 +-10.02, -10.00, 53.37, 46.63, 6.73 +-10.02, -10.00, 53.37, 46.63, 6.73 +-10.02, -10.00, 53.37, 46.63, 6.73 +-9.95, -10.00, 50.84, 49.16, 1.69 +-9.95, -10.00, 53.32, 46.68, 6.63 +-9.89, -10.00, 50.79, 49.21, 1.59 +-9.89, -10.00, 53.27, 46.73, 6.53 +-9.89, -10.00, 53.27, 46.73, 6.53 +-9.76, -10.00, 48.22, 51.78, -3.56 +-9.76, -10.00, 53.16, 46.84, 6.33 +-9.76, -10.00, 53.16, 46.84, 6.33 +-9.76, -10.00, 53.16, 46.84, 6.33 +-9.69, -10.00, 50.64, 49.36, 1.28 +-9.69, -10.00, 53.11, 46.89, 6.22 +-9.62, -10.00, 50.59, 49.41, 1.18 +-9.62, -10.00, 53.06, 46.94, 6.12 +-9.62, -10.00, 53.06, 46.94, 6.11 +-9.49, -10.00, 48.01, 51.99, -3.97 +-9.49, -10.00, 52.95, 47.05, 5.91 +-9.43, -10.00, 50.43, 49.57, 0.86 +-9.43, -10.00, 52.90, 47.10, 5.80 +-9.43, -10.00, 52.90, 47.10, 5.80 +-9.36, -10.00, 50.37, 49.63, 0.75 +-9.36, -10.00, 52.84, 47.16, 5.69 +-9.23, -10.00, 47.80, 52.20, -4.40 +-9.23, -10.00, 52.74, 47.26, 5.48 +-9.23, -10.00, 52.74, 47.26, 5.47 +-9.23, -10.00, 52.73, 47.27, 5.47 +-9.16, -10.00, 50.21, 49.79, 0.42 +-9.16, -10.00, 52.68, 47.32, 5.36 +-9.10, -10.00, 50.15, 49.85, 0.31 +-9.10, -10.00, 52.62, 47.38, 5.24 +-9.10, -10.00, 52.62, 47.38, 5.24 +-8.96, -10.00, 47.57, 52.43, -4.86 +-8.96, -10.00, 52.51, 47.49, 5.02 +-8.96, -10.00, 52.51, 47.49, 5.02 +-8.90, -10.00, 49.98, 50.02, -0.03 +-8.90, -10.00, 52.45, 47.55, 4.90 +-8.90, -10.00, 52.45, 47.55, 4.89 +-8.83, -10.00, 49.92, 50.08, -0.16 +-8.83, -10.00, 52.39, 47.61, 4.78 +-8.83, -10.00, 52.38, 47.62, 4.77 +-8.70, -10.00, 47.34, 52.66, -5.33 +-8.70, -10.00, 52.28, 47.72, 4.55 +-8.70, -10.00, 52.27, 47.73, 4.54 +-8.64, -10.00, 49.74, 50.26, -0.51 +-8.64, -10.00, 52.21, 47.79, 4.42 +-8.64, -10.00, 52.21, 47.79, 4.41 +-8.64, -10.00, 52.20, 47.80, 4.40 +-8.57, -10.00, 49.67, 50.33, -0.65 +-8.57, -10.00, 52.14, 47.86, 4.28 +-8.57, -10.00, 52.13, 47.87, 4.27 +-8.44, -10.00, 47.09, 52.91, -5.83 +-8.44, -10.00, 52.02, 47.98, 4.05 +-8.37, -10.00, 49.50, 50.50, -1.01 +-8.37, -10.00, 51.96, 48.04, 3.92 +-8.37, -10.00, 51.96, 48.04, 3.91 +-8.31, -10.00, 49.43, 50.57, -1.14 +-8.31, -10.00, 51.89, 48.11, 3.79 +-8.31, -10.00, 51.89, 48.11, 3.78 +-8.31, -10.00, 51.88, 48.12, 3.76 +-8.17, -10.00, 46.83, 53.17, -6.34 +-8.17, -10.00, 51.77, 48.23, 3.54 +-8.17, -10.00, 51.76, 48.24, 3.52 +-8.17, -10.00, 51.76, 48.24, 3.51 +-8.11, -10.00, 49.23, 50.77, -1.55 +-8.11, -10.00, 51.69, 48.31, 3.38 +-8.04, -10.00, 49.16, 50.84, -1.67 +-8.04, -10.00, 51.63, 48.37, 3.26 +-8.04, -10.00, 51.62, 48.38, 3.24 +-8.04, -10.00, 51.61, 48.39, 3.23 +-8.04, -10.00, 51.61, 48.39, 3.21 +-7.91, -10.00, 46.55, 53.45, -6.89 +-7.91, -10.00, 51.49, 48.51, 2.98 +-7.91, -10.00, 51.48, 48.52, 2.97 +-7.84, -10.00, 48.95, 51.05, -2.09 +-7.84, -10.00, 51.42, 48.58, 2.83 +-7.84, -10.00, 51.41, 48.59, 2.82 +-7.84, -10.00, 51.40, 48.60, 2.80 +-7.84, -10.00, 51.39, 48.61, 2.79 +-7.84, -10.00, 51.39, 48.61, 2.77 +-7.84, -10.00, 51.38, 48.62, 2.75 +-7.84, -10.00, 51.37, 48.63, 2.74 +-7.84, -10.00, 51.36, 48.64, 2.72 +-7.84, -10.00, 51.35, 48.65, 2.71 +-7.84, -10.00, 51.34, 48.66, 2.69 +-7.84, -10.00, 51.34, 48.66, 2.67 +-7.91, -10.00, 53.85, 46.15, 7.70 +-7.91, -10.00, 51.37, 48.63, 2.74 +-7.91, -10.00, 51.36, 48.64, 2.73 +-7.91, -10.00, 51.35, 48.65, 2.71 +-7.91, -10.00, 51.35, 48.65, 2.69 +-7.91, -10.00, 51.34, 48.66, 2.68 +-8.04, -10.00, 56.37, 43.63, 12.75 +-8.04, -10.00, 51.42, 48.58, 2.85 +-8.04, -10.00, 51.42, 48.58, 2.83 +-8.04, -10.00, 51.41, 48.59, 2.82 +-8.04, -10.00, 51.40, 48.60, 2.80 +-8.04, -10.00, 51.39, 48.61, 2.79 +-8.11, -10.00, 53.91, 46.09, 7.82 +-8.11, -10.00, 51.43, 48.57, 2.86 +-8.11, -10.00, 51.42, 48.58, 2.84 +-8.11, -10.00, 51.41, 48.59, 2.83 +-8.11, -10.00, 51.41, 48.59, 2.82 +-8.17, -10.00, 53.92, 46.08, 7.84 +-8.17, -10.00, 51.44, 48.56, 2.89 +-8.17, -10.00, 51.44, 48.56, 2.87 +-8.17, -10.00, 51.43, 48.57, 2.86 +-8.31, -10.00, 56.47, 43.53, 12.93 +-8.31, -10.00, 51.52, 48.48, 3.03 +-8.31, -10.00, 51.51, 48.49, 3.02 +-8.37, -10.00, 54.02, 45.98, 8.05 +-8.37, -10.00, 51.55, 48.45, 3.09 +-8.44, -10.00, 54.06, 45.94, 8.12 +-8.44, -10.00, 51.58, 48.42, 3.17 +-8.44, -10.00, 51.58, 48.42, 3.16 +-8.44, -10.00, 51.57, 48.43, 3.15 +-8.57, -10.00, 56.61, 43.39, 13.22 +-8.57, -10.00, 51.66, 48.34, 3.32 +-8.57, -10.00, 51.66, 48.34, 3.31 +-8.64, -10.00, 54.17, 45.83, 8.34 +-8.64, -10.00, 51.69, 48.31, 3.39 +-8.64, -10.00, 51.69, 48.31, 3.38 +-8.64, -10.00, 51.68, 48.32, 3.37 +-8.64, -10.00, 51.68, 48.32, 3.36 +-8.70, -10.00, 54.20, 45.80, 8.39 +-8.70, -10.00, 51.72, 48.28, 3.44 +-8.70, -10.00, 51.71, 48.29, 3.43 +-8.70, -10.00, 51.71, 48.29, 3.42 +-8.83, -10.00, 56.75, 43.25, 13.50 +-8.83, -10.00, 51.80, 48.20, 3.60 +-8.83, -10.00, 51.80, 48.20, 3.59 +-8.83, -10.00, 51.79, 48.21, 3.58 +-8.90, -10.00, 54.31, 45.69, 8.62 +-8.90, -10.00, 51.83, 48.17, 3.66 +-8.90, -10.00, 51.83, 48.17, 3.66 +-8.90, -10.00, 51.82, 48.18, 3.65 +-8.96, -10.00, 54.34, 45.66, 8.68 +-8.96, -10.00, 51.87, 48.13, 3.73 +-8.96, -10.00, 51.86, 48.14, 3.72 +-8.96, -10.00, 51.86, 48.14, 3.72 +-8.96, -10.00, 51.85, 48.15, 3.71 +-8.96, -10.00, 51.85, 48.15, 3.70 +-9.10, -10.00, 56.89, 43.11, 13.78 +-9.10, -10.00, 51.94, 48.06, 3.88 +-9.10, -10.00, 51.94, 48.06, 3.88 +-9.10, -10.00, 51.94, 48.06, 3.87 +-9.10, -10.00, 51.93, 48.07, 3.86 +-9.10, -10.00, 51.93, 48.07, 3.86 +-9.10, -10.00, 51.93, 48.07, 3.85 +-9.16, -10.00, 54.44, 45.56, 8.89 +-9.16, -10.00, 51.97, 48.03, 3.94 +-9.16, -10.00, 51.97, 48.03, 3.93 +-9.16, -10.00, 51.96, 48.04, 3.92 +-9.16, -10.00, 51.96, 48.04, 3.92 +-9.16, -10.00, 51.96, 48.04, 3.91 +-9.23, -10.00, 54.47, 45.53, 8.95 +-9.23, -10.00, 52.00, 48.00, 4.00 +-9.23, -10.00, 52.00, 48.00, 3.99 +-9.23, -10.00, 51.99, 48.01, 3.99 +-9.23, -10.00, 51.99, 48.01, 3.98 +-9.36, -10.00, 57.03, 42.97, 14.06 +-9.36, -10.00, 52.08, 47.92, 4.17 +-9.36, -10.00, 52.08, 47.92, 4.16 +-9.36, -10.00, 52.08, 47.92, 4.16 +-9.43, -10.00, 54.60, 45.40, 9.20 +-9.43, -10.00, 52.13, 47.87, 4.25 +-9.43, -10.00, 52.12, 47.88, 4.25 +-9.49, -10.00, 54.64, 45.36, 9.28 +-9.49, -10.00, 52.17, 47.83, 4.34 +-9.49, -10.00, 52.17, 47.83, 4.33 +-9.62, -10.00, 57.21, 42.79, 14.42 +-9.62, -10.00, 52.26, 47.74, 4.53 +-9.62, -10.00, 52.26, 47.74, 4.52 +-9.69, -10.00, 54.78, 45.22, 9.56 +-9.69, -10.00, 52.31, 47.69, 4.62 +-9.69, -10.00, 52.31, 47.69, 4.61 +-9.76, -10.00, 54.83, 45.17, 9.66 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.89, -10.00, 57.40, 42.60, 14.79 +-9.89, -10.00, 52.45, 47.55, 4.90 +-9.89, -10.00, 52.45, 47.55, 4.90 +-9.89, -10.00, 52.45, 47.55, 4.90 +-9.89, -10.00, 52.45, 47.55, 4.90 +-9.95, -10.00, 54.97, 45.03, 9.94 +-9.95, -10.00, 52.50, 47.50, 5.00 +-10.02, -10.00, 55.02, 44.98, 10.04 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.15, -10.00, 57.59, 42.41, 15.19 +-10.02, -10.00, 47.61, 52.39, -4.79 +-10.15, -10.00, 57.59, 42.41, 15.19 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.31 +-10.15, -10.00, 52.65, 47.35, 5.31 +-10.15, -10.00, 52.65, 47.35, 5.31 +-10.15, -10.00, 52.65, 47.35, 5.31 +-10.02, -10.00, 47.61, 52.39, -4.78 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-9.95, -10.00, 50.03, 49.97, 0.07 +-9.95, -10.00, 52.51, 47.49, 5.01 +-9.95, -10.00, 52.51, 47.49, 5.01 +-9.89, -10.00, 49.98, 50.02, -0.03 +-9.89, -10.00, 52.46, 47.54, 4.91 +-9.89, -10.00, 52.46, 47.54, 4.91 +-9.89, -10.00, 52.46, 47.54, 4.91 +-9.89, -10.00, 52.45, 47.55, 4.91 +-9.76, -10.00, 47.41, 52.59, -5.18 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.76, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 49.83, 50.17, -0.34 +-9.69, -10.00, 52.30, 47.70, 4.60 +-9.69, -10.00, 52.30, 47.70, 4.60 +-9.62, -10.00, 49.78, 50.22, -0.45 +-9.62, -10.00, 52.25, 47.75, 4.49 +-9.62, -10.00, 52.25, 47.75, 4.49 +-9.62, -10.00, 52.24, 47.76, 4.49 +-9.49, -10.00, 47.20, 52.80, -5.60 +-9.49, -10.00, 52.14, 47.86, 4.28 +-9.49, -10.00, 52.14, 47.86, 4.28 +-9.49, -10.00, 52.14, 47.86, 4.28 +-9.49, -10.00, 52.14, 47.86, 4.27 +-9.43, -10.00, 49.61, 50.39, -0.78 +-9.43, -10.00, 52.08, 47.92, 4.16 +-9.43, -10.00, 52.08, 47.92, 4.16 +-9.43, -10.00, 52.08, 47.92, 4.16 +-9.43, -10.00, 52.08, 47.92, 4.15 +-9.43, -10.00, 52.07, 47.93, 4.15 +-9.43, -10.00, 52.07, 47.93, 4.14 +-9.36, -10.00, 49.55, 50.45, -0.90 +-9.36, -10.00, 52.02, 47.98, 4.03 +-9.36, -10.00, 52.01, 47.99, 4.03 +-9.36, -10.00, 52.01, 47.99, 4.02 +-9.36, -10.00, 52.01, 47.99, 4.02 +-9.36, -10.00, 52.01, 47.99, 4.02 +-9.23, -10.00, 46.96, 53.04, -6.08 +-9.23, -10.00, 51.90, 48.10, 3.81 +-9.23, -10.00, 51.90, 48.10, 3.80 +-9.23, -10.00, 51.90, 48.10, 3.79 +-9.23, -10.00, 51.89, 48.11, 3.79 +-9.23, -10.00, 51.89, 48.11, 3.78 +-9.23, -10.00, 51.89, 48.11, 3.78 +-9.23, -10.00, 51.89, 48.11, 3.77 +-9.23, -10.00, 51.88, 48.12, 3.77 +-9.23, -10.00, 51.88, 48.12, 3.76 +-9.23, -10.00, 51.88, 48.12, 3.75 +-9.23, -10.00, 51.87, 48.13, 3.75 +-9.23, -10.00, 51.87, 48.13, 3.74 +-9.23, -10.00, 51.87, 48.13, 3.74 +-9.23, -10.00, 51.87, 48.13, 3.73 +-9.23, -10.00, 51.86, 48.14, 3.72 +-9.23, -10.00, 51.86, 48.14, 3.72 +-9.16, -10.00, 49.33, 50.67, -1.33 +-9.16, -10.00, 51.80, 48.20, 3.61 +-9.23, -10.00, 54.32, 45.68, 8.64 +-9.23, -10.00, 51.85, 48.15, 3.69 +-9.23, -10.00, 51.84, 48.16, 3.69 +-9.23, -10.00, 51.84, 48.16, 3.68 +-9.16, -10.00, 49.32, 50.68, -1.37 +-9.16, -10.00, 51.79, 48.21, 3.57 +-9.16, -10.00, 51.78, 48.22, 3.57 +-9.16, -10.00, 51.78, 48.22, 3.56 +-9.16, -10.00, 51.78, 48.22, 3.55 +-9.16, -10.00, 51.77, 48.23, 3.55 +-9.16, -10.00, 51.77, 48.23, 3.54 +-9.16, -10.00, 51.77, 48.23, 3.53 +-9.16, -10.00, 51.76, 48.24, 3.53 +-9.23, -10.00, 54.28, 45.72, 8.56 +-9.23, -10.00, 51.81, 48.19, 3.62 +-9.16, -10.00, 49.28, 50.72, -1.43 +-9.16, -10.00, 51.75, 48.25, 3.50 +-9.16, -10.00, 51.75, 48.25, 3.50 +-9.16, -10.00, 51.75, 48.25, 3.49 +-9.23, -10.00, 54.26, 45.74, 8.53 +-9.23, -10.00, 51.79, 48.21, 3.58 +-9.23, -10.00, 51.79, 48.21, 3.57 +-9.23, -10.00, 51.78, 48.22, 3.57 +-9.23, -10.00, 51.78, 48.22, 3.56 +-9.23, -10.00, 51.78, 48.22, 3.56 +-9.23, -10.00, 51.77, 48.23, 3.55 +-9.23, -10.00, 51.77, 48.23, 3.54 +-9.23, -10.00, 51.77, 48.23, 3.54 +-9.23, -10.00, 51.77, 48.23, 3.53 +-9.23, -10.00, 51.76, 48.24, 3.53 +-9.23, -10.00, 51.76, 48.24, 3.52 +-9.23, -10.00, 51.76, 48.24, 3.51 +-9.23, -10.00, 51.75, 48.25, 3.51 +-9.23, -10.00, 51.75, 48.25, 3.50 +-9.23, -10.00, 51.75, 48.25, 3.50 +-9.23, -10.00, 51.75, 48.25, 3.49 +-9.23, -10.00, 51.74, 48.26, 3.49 +-9.23, -10.00, 51.74, 48.26, 3.48 +-9.23, -10.00, 51.74, 48.26, 3.47 +-9.23, -10.00, 51.73, 48.27, 3.47 +-9.36, -10.00, 56.77, 43.23, 13.55 +-9.36, -10.00, 51.83, 48.17, 3.66 +-9.36, -10.00, 51.83, 48.17, 3.65 +-9.36, -10.00, 51.82, 48.18, 3.65 +-9.36, -10.00, 51.82, 48.18, 3.64 +-9.36, -10.00, 51.82, 48.18, 3.64 +-9.36, -10.00, 51.82, 48.18, 3.63 +-9.36, -10.00, 51.81, 48.19, 3.63 +-9.36, -10.00, 51.81, 48.19, 3.62 +-9.43, -10.00, 54.33, 45.67, 8.66 +-9.43, -10.00, 51.86, 48.14, 3.71 +-9.43, -10.00, 51.85, 48.15, 3.71 +-9.43, -10.00, 51.85, 48.15, 3.70 +-9.43, -10.00, 51.85, 48.15, 3.70 +-9.43, -10.00, 51.85, 48.15, 3.70 +-9.43, -10.00, 51.85, 48.15, 3.69 +-9.43, -10.00, 51.84, 48.16, 3.69 +-9.43, -10.00, 51.84, 48.16, 3.68 +-9.49, -10.00, 54.36, 45.64, 8.72 +-9.49, -10.00, 51.89, 48.11, 3.77 +-9.49, -10.00, 51.89, 48.11, 3.77 +-9.49, -10.00, 51.88, 48.12, 3.77 +-9.49, -10.00, 51.88, 48.12, 3.76 +-9.49, -10.00, 51.88, 48.12, 3.76 +-9.49, -10.00, 51.88, 48.12, 3.76 +-9.49, -10.00, 51.88, 48.12, 3.75 +-9.62, -10.00, 56.92, 43.08, 13.83 +-9.62, -10.00, 51.97, 48.03, 3.94 +-9.62, -10.00, 51.97, 48.03, 3.94 +-9.62, -10.00, 51.97, 48.03, 3.94 +-9.62, -10.00, 51.97, 48.03, 3.94 +-9.62, -10.00, 51.97, 48.03, 3.93 +-9.62, -10.00, 51.96, 48.04, 3.93 +-9.62, -10.00, 51.96, 48.04, 3.93 +-9.62, -10.00, 51.96, 48.04, 3.92 +-9.62, -10.00, 51.96, 48.04, 3.92 +-9.62, -10.00, 51.96, 48.04, 3.92 +-9.62, -10.00, 51.96, 48.04, 3.92 +-9.62, -10.00, 51.96, 48.04, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.90 +-9.62, -10.00, 51.95, 48.05, 3.90 +-9.62, -10.00, 51.95, 48.05, 3.90 +-9.69, -10.00, 54.47, 45.53, 8.94 +-9.69, -10.00, 52.00, 48.00, 3.99 +-9.69, -10.00, 52.00, 48.00, 3.99 +-9.69, -10.00, 51.99, 48.01, 3.99 +-9.62, -10.00, 49.47, 50.53, -1.06 +-9.62, -10.00, 51.94, 48.06, 3.88 +-9.62, -10.00, 51.94, 48.06, 3.88 +-9.62, -10.00, 51.94, 48.06, 3.88 +-9.62, -10.00, 51.94, 48.06, 3.88 +-9.62, -10.00, 51.94, 48.06, 3.87 +-9.62, -10.00, 51.93, 48.07, 3.87 +-9.62, -10.00, 51.93, 48.07, 3.87 +-9.49, -10.00, 46.89, 53.11, -6.22 +-9.49, -10.00, 51.83, 48.17, 3.66 +-9.49, -10.00, 51.83, 48.17, 3.66 +-9.49, -10.00, 51.83, 48.17, 3.65 +-9.49, -10.00, 51.82, 48.18, 3.65 +-9.49, -10.00, 51.82, 48.18, 3.65 +-9.43, -10.00, 49.30, 50.70, -1.40 +-9.43, -10.00, 51.77, 48.23, 3.54 +-9.43, -10.00, 51.77, 48.23, 3.53 +-9.43, -10.00, 51.77, 48.23, 3.53 +-9.43, -10.00, 51.76, 48.24, 3.53 +-9.36, -10.00, 49.24, 50.76, -1.52 +-9.36, -10.00, 51.71, 48.29, 3.42 +-9.36, -10.00, 51.71, 48.29, 3.41 +-9.23, -10.00, 46.66, 53.34, -6.68 +-9.23, -10.00, 51.60, 48.40, 3.20 +-9.23, -10.00, 51.60, 48.40, 3.20 +-9.23, -10.00, 51.60, 48.40, 3.19 +-9.16, -10.00, 49.07, 50.93, -1.86 +-9.16, -10.00, 51.54, 48.46, 3.08 +-9.10, -10.00, 49.02, 50.98, -1.97 +-9.10, -10.00, 51.48, 48.52, 2.97 +-9.10, -10.00, 51.48, 48.52, 2.96 +-8.96, -10.00, 46.43, 53.57, -7.13 +-8.96, -10.00, 51.37, 48.63, 2.75 +-8.96, -10.00, 51.37, 48.63, 2.74 +-8.90, -10.00, 48.84, 51.16, -2.31 +-8.90, -10.00, 51.31, 48.69, 2.62 +-8.90, -10.00, 51.31, 48.69, 2.62 +-8.83, -10.00, 48.78, 51.22, -2.44 +-8.83, -10.00, 51.25, 48.75, 2.50 +-8.83, -10.00, 51.25, 48.75, 2.49 +-8.70, -10.00, 46.20, 53.80, -7.60 +-8.70, -10.00, 51.14, 48.86, 2.27 +-8.64, -10.00, 48.61, 51.39, -2.78 +-8.64, -10.00, 51.08, 48.92, 2.15 +-8.64, -10.00, 51.07, 48.93, 2.14 +-8.64, -10.00, 51.07, 48.93, 2.13 +-8.57, -10.00, 48.54, 51.46, -2.92 +-8.57, -10.00, 51.01, 48.99, 2.01 +-8.57, -10.00, 51.00, 49.00, 2.00 +-8.57, -10.00, 51.00, 49.00, 1.99 +-8.44, -10.00, 45.95, 54.05, -8.10 +-8.44, -10.00, 50.89, 49.11, 1.77 +-8.44, -10.00, 50.88, 49.12, 1.76 +-8.44, -10.00, 50.87, 49.13, 1.75 +-8.37, -10.00, 48.35, 51.65, -3.31 +-8.37, -10.00, 50.81, 49.19, 1.62 +-8.37, -10.00, 50.81, 49.19, 1.61 +-8.37, -10.00, 50.80, 49.20, 1.60 +-8.37, -10.00, 50.79, 49.21, 1.59 +-8.31, -10.00, 48.27, 51.73, -3.47 +-8.31, -10.00, 50.73, 49.27, 1.46 +-8.31, -10.00, 50.73, 49.27, 1.45 +-8.31, -10.00, 50.72, 49.28, 1.44 +-8.31, -10.00, 50.71, 49.29, 1.43 +-8.31, -10.00, 50.71, 49.29, 1.41 +-8.31, -10.00, 50.70, 49.30, 1.40 +-8.31, -10.00, 50.69, 49.31, 1.39 +-8.17, -10.00, 45.64, 54.36, -8.71 +-8.17, -10.00, 50.58, 49.42, 1.16 +-8.31, -10.00, 55.62, 44.38, 11.23 +-8.31, -10.00, 50.67, 49.33, 1.33 +-8.31, -10.00, 50.66, 49.34, 1.32 +-8.31, -10.00, 50.65, 49.35, 1.31 +-8.31, -10.00, 50.65, 49.35, 1.30 +-8.31, -10.00, 50.64, 49.36, 1.28 +-8.31, -10.00, 50.64, 49.36, 1.27 +-8.31, -10.00, 50.63, 49.37, 1.26 +-8.31, -10.00, 50.62, 49.38, 1.25 +-8.37, -10.00, 53.14, 46.86, 6.28 +-8.37, -10.00, 50.66, 49.34, 1.32 +-8.37, -10.00, 50.65, 49.35, 1.31 +-8.37, -10.00, 50.65, 49.35, 1.30 +-8.37, -10.00, 50.64, 49.36, 1.28 +-8.44, -10.00, 53.16, 46.84, 6.31 +-8.44, -10.00, 50.68, 49.32, 1.36 +-8.44, -10.00, 50.67, 49.33, 1.35 +-8.44, -10.00, 50.67, 49.33, 1.34 +-8.57, -10.00, 55.70, 44.30, 11.41 +-8.57, -10.00, 50.76, 49.24, 1.51 +-8.57, -10.00, 50.75, 49.25, 1.50 +-8.64, -10.00, 53.27, 46.73, 6.53 +-8.64, -10.00, 50.79, 49.21, 1.58 +-8.64, -10.00, 50.78, 49.22, 1.57 +-8.70, -10.00, 53.30, 46.70, 6.60 +-8.70, -10.00, 50.82, 49.18, 1.65 +-8.70, -10.00, 50.82, 49.18, 1.64 +-8.83, -10.00, 55.86, 44.14, 11.72 +-8.83, -10.00, 50.91, 49.09, 1.82 +-8.90, -10.00, 53.43, 46.57, 6.85 +-8.90, -10.00, 50.95, 49.05, 1.90 +-8.90, -10.00, 50.95, 49.05, 1.89 +-8.96, -10.00, 53.46, 46.54, 6.93 +-8.96, -10.00, 50.99, 49.01, 1.98 +-8.96, -10.00, 50.98, 49.02, 1.97 +-9.10, -10.00, 56.02, 43.98, 12.05 +-9.10, -10.00, 51.08, 48.92, 2.15 +-9.10, -10.00, 51.07, 48.93, 2.15 +-9.16, -10.00, 53.59, 46.41, 7.18 +-9.16, -10.00, 51.12, 48.88, 2.23 +-9.16, -10.00, 51.11, 48.89, 2.23 +-9.23, -10.00, 53.63, 46.37, 7.26 +-9.23, -10.00, 51.16, 48.84, 2.31 +-9.23, -10.00, 51.15, 48.85, 2.31 +-9.23, -10.00, 51.15, 48.85, 2.30 +-9.23, -10.00, 51.15, 48.85, 2.30 +-9.36, -10.00, 56.19, 43.81, 12.38 +-9.36, -10.00, 51.24, 48.76, 2.48 +-9.36, -10.00, 51.24, 48.76, 2.48 +-9.43, -10.00, 53.76, 46.24, 7.52 +-9.43, -10.00, 51.28, 48.72, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.56 +-9.49, -10.00, 53.80, 46.20, 7.60 +-9.49, -10.00, 51.33, 48.67, 2.65 +-9.49, -10.00, 51.32, 48.68, 2.65 +-9.49, -10.00, 51.32, 48.68, 2.64 +-9.62, -10.00, 56.36, 43.64, 12.73 +-9.62, -10.00, 51.42, 48.58, 2.84 +-9.62, -10.00, 51.42, 48.58, 2.83 +-9.62, -10.00, 51.42, 48.58, 2.83 +-9.62, -10.00, 51.41, 48.59, 2.83 +-9.69, -10.00, 53.93, 46.07, 7.87 +-9.69, -10.00, 51.46, 48.54, 2.92 +-9.69, -10.00, 51.46, 48.54, 2.92 +-9.69, -10.00, 51.46, 48.54, 2.92 +-9.76, -10.00, 53.98, 46.02, 7.96 +-9.76, -10.00, 51.51, 48.49, 3.01 +-9.76, -10.00, 51.51, 48.49, 3.01 +-9.76, -10.00, 51.50, 48.50, 3.01 +-9.76, -10.00, 51.50, 48.50, 3.01 +-9.76, -10.00, 51.50, 48.50, 3.01 +-9.76, -10.00, 51.50, 48.50, 3.00 +-9.76, -10.00, 51.50, 48.50, 3.00 +-9.76, -10.00, 51.50, 48.50, 3.00 +-9.89, -10.00, 56.54, 43.46, 13.08 +-9.76, -10.00, 46.55, 53.45, -6.89 +-9.89, -10.00, 56.54, 43.46, 13.08 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.95, -10.00, 54.11, 45.89, 8.23 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.89, -10.00, 49.12, 50.88, -1.77 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.16 +-9.76, -10.00, 46.54, 53.46, -6.92 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.95 +-9.76, -10.00, 51.48, 48.52, 2.95 +-9.76, -10.00, 51.48, 48.52, 2.95 +-9.76, -10.00, 51.47, 48.53, 2.95 +-9.76, -10.00, 51.47, 48.53, 2.95 +-9.69, -10.00, 48.95, 51.05, -2.10 +-9.69, -10.00, 51.42, 48.58, 2.84 +-9.69, -10.00, 51.42, 48.58, 2.84 +-9.69, -10.00, 51.42, 48.58, 2.84 +-9.62, -10.00, 48.90, 51.10, -2.21 +-9.62, -10.00, 51.37, 48.63, 2.73 +-9.62, -10.00, 51.37, 48.63, 2.73 +-9.62, -10.00, 51.36, 48.64, 2.73 +-9.49, -10.00, 46.32, 53.68, -7.36 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.51 +-9.49, -10.00, 51.25, 48.75, 2.51 +-9.43, -10.00, 48.73, 51.27, -2.54 +-9.43, -10.00, 51.20, 48.80, 2.40 +-9.43, -10.00, 51.20, 48.80, 2.40 +-9.43, -10.00, 51.20, 48.80, 2.39 +-9.43, -10.00, 51.19, 48.81, 2.39 +-9.43, -10.00, 51.19, 48.81, 2.38 +-9.43, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 48.67, 51.33, -2.67 +-9.36, -10.00, 51.14, 48.86, 2.27 +-9.36, -10.00, 51.13, 48.87, 2.27 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.25 +-9.36, -10.00, 51.12, 48.88, 2.25 +-9.36, -10.00, 51.12, 48.88, 2.24 +-9.36, -10.00, 51.12, 48.88, 2.24 +-9.36, -10.00, 51.12, 48.88, 2.23 +-9.23, -10.00, 46.07, 53.93, -7.86 +-9.36, -10.00, 56.05, 43.95, 12.11 +-9.36, -10.00, 51.11, 48.89, 2.22 +-9.23, -10.00, 46.06, 53.94, -7.87 +-9.23, -10.00, 51.00, 49.00, 2.01 +-9.23, -10.00, 51.00, 49.00, 2.00 +-9.23, -10.00, 51.00, 49.00, 2.00 +-9.23, -10.00, 51.00, 49.00, 1.99 +-9.23, -10.00, 50.99, 49.01, 1.98 +-9.23, -10.00, 50.99, 49.01, 1.98 +-9.23, -10.00, 50.99, 49.01, 1.97 +-9.23, -10.00, 50.98, 49.02, 1.97 +-9.23, -10.00, 50.98, 49.02, 1.96 +-9.23, -10.00, 50.98, 49.02, 1.96 +-9.23, -10.00, 50.97, 49.03, 1.95 +-9.23, -10.00, 50.97, 49.03, 1.94 +-9.23, -10.00, 50.97, 49.03, 1.94 +-9.23, -10.00, 50.97, 49.03, 1.93 +-9.23, -10.00, 50.96, 49.04, 1.93 +-9.23, -10.00, 50.96, 49.04, 1.92 +-9.23, -10.00, 50.96, 49.04, 1.91 +-9.23, -10.00, 50.95, 49.05, 1.91 +-9.23, -10.00, 50.95, 49.05, 1.90 +-9.23, -10.00, 50.95, 49.05, 1.90 +-9.23, -10.00, 50.95, 49.05, 1.89 +-9.23, -10.00, 50.94, 49.06, 1.89 +-9.36, -10.00, 55.98, 44.02, 11.97 +-9.23, -10.00, 45.99, 54.01, -8.01 +-9.36, -10.00, 55.98, 44.02, 11.96 +-9.36, -10.00, 51.03, 48.97, 2.06 +-9.36, -10.00, 51.03, 48.97, 2.06 +-9.36, -10.00, 51.03, 48.97, 2.05 +-9.36, -10.00, 51.02, 48.98, 2.05 +-9.36, -10.00, 51.02, 48.98, 2.04 +-9.36, -10.00, 51.02, 48.98, 2.04 +-9.43, -10.00, 53.54, 46.46, 7.08 +-9.43, -10.00, 51.06, 48.94, 2.13 +-9.43, -10.00, 51.06, 48.94, 2.13 +-9.43, -10.00, 51.06, 48.94, 2.12 +-9.43, -10.00, 51.06, 48.94, 2.12 +-9.43, -10.00, 51.06, 48.94, 2.11 +-9.43, -10.00, 51.05, 48.95, 2.11 +-9.43, -10.00, 51.05, 48.95, 2.10 +-9.49, -10.00, 53.57, 46.43, 7.14 +-9.49, -10.00, 51.10, 48.90, 2.20 +-9.49, -10.00, 51.10, 48.90, 2.19 +-9.49, -10.00, 51.09, 48.91, 2.19 +-9.49, -10.00, 51.09, 48.91, 2.18 +-9.49, -10.00, 51.09, 48.91, 2.18 +-9.62, -10.00, 56.13, 43.87, 12.26 +-9.62, -10.00, 51.19, 48.81, 2.37 +-9.62, -10.00, 51.18, 48.82, 2.37 +-9.62, -10.00, 51.18, 48.82, 2.37 +-9.62, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 53.70, 46.30, 7.40 +-9.69, -10.00, 51.23, 48.77, 2.46 +-9.69, -10.00, 51.23, 48.77, 2.46 +-9.69, -10.00, 51.23, 48.77, 2.45 +-9.69, -10.00, 51.23, 48.77, 2.45 +-9.76, -10.00, 53.75, 46.25, 7.49 +-9.76, -10.00, 51.27, 48.73, 2.55 +-9.76, -10.00, 51.27, 48.73, 2.54 +-9.76, -10.00, 51.27, 48.73, 2.54 +-9.76, -10.00, 51.27, 48.73, 2.54 +-9.76, -10.00, 51.27, 48.73, 2.54 +-9.89, -10.00, 56.31, 43.69, 12.62 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.95, -10.00, 53.89, 46.11, 7.77 +-9.95, -10.00, 51.41, 48.59, 2.83 +-9.95, -10.00, 51.41, 48.59, 2.83 +-9.95, -10.00, 51.41, 48.59, 2.83 +-10.02, -10.00, 53.94, 46.06, 7.87 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.15, -10.00, 56.51, 43.49, 13.02 +-10.15, -10.00, 51.56, 48.44, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.22, -10.00, 54.09, 45.91, 8.18 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.28, -10.00, 54.14, 45.86, 8.29 +-10.28, -10.00, 51.67, 48.33, 3.35 +-10.28, -10.00, 51.67, 48.33, 3.35 +-10.28, -10.00, 51.68, 48.32, 3.35 +-10.28, -10.00, 51.68, 48.32, 3.35 +-10.42, -10.00, 56.72, 43.28, 13.44 +-10.42, -10.00, 51.78, 48.22, 3.56 +-10.42, -10.00, 51.78, 48.22, 3.56 +-10.42, -10.00, 51.78, 48.22, 3.56 +-10.42, -10.00, 51.78, 48.22, 3.57 +-10.42, -10.00, 51.78, 48.22, 3.57 +-10.42, -10.00, 51.79, 48.21, 3.57 +-10.42, -10.00, 51.79, 48.21, 3.58 +-10.42, -10.00, 51.79, 48.21, 3.58 +-10.42, -10.00, 51.79, 48.21, 3.58 +-10.42, -10.00, 51.79, 48.21, 3.58 +-10.42, -10.00, 51.79, 48.21, 3.59 +-10.48, -10.00, 54.32, 45.68, 8.63 +-10.48, -10.00, 51.85, 48.15, 3.69 +-10.48, -10.00, 51.85, 48.15, 3.70 +-10.48, -10.00, 51.85, 48.15, 3.70 +-10.48, -10.00, 51.85, 48.15, 3.70 +-10.48, -10.00, 51.85, 48.15, 3.71 +-10.48, -10.00, 51.86, 48.14, 3.71 +-10.48, -10.00, 51.86, 48.14, 3.72 +-10.48, -10.00, 51.86, 48.14, 3.72 +-10.48, -10.00, 51.86, 48.14, 3.72 +-10.48, -10.00, 51.86, 48.14, 3.73 +-10.48, -10.00, 51.87, 48.13, 3.73 +-10.48, -10.00, 51.87, 48.13, 3.73 +-10.48, -10.00, 51.87, 48.13, 3.74 +-10.55, -10.00, 54.39, 45.61, 8.78 +-10.55, -10.00, 51.92, 48.08, 3.84 +-10.55, -10.00, 51.92, 48.08, 3.85 +-10.55, -10.00, 51.93, 48.07, 3.85 +-10.55, -10.00, 51.93, 48.07, 3.86 +-10.55, -10.00, 51.93, 48.07, 3.86 +-10.55, -10.00, 51.93, 48.07, 3.86 +-10.55, -10.00, 51.93, 48.07, 3.87 +-10.55, -10.00, 51.94, 48.06, 3.87 +-10.55, -10.00, 51.94, 48.06, 3.88 +-10.55, -10.00, 51.94, 48.06, 3.88 +-10.68, -10.00, 56.99, 43.01, 13.97 +-10.68, -10.00, 52.04, 47.96, 4.09 +-10.68, -10.00, 52.05, 47.95, 4.09 +-10.68, -10.00, 52.05, 47.95, 4.10 +-10.55, -10.00, 47.01, 52.99, -5.98 +-10.55, -10.00, 51.95, 48.05, 3.91 +-10.68, -10.00, 57.00, 43.00, 14.00 +-10.55, -10.00, 47.02, 52.98, -5.97 +-10.68, -10.00, 57.00, 43.00, 14.01 +-10.55, -10.00, 47.02, 52.98, -5.96 +-10.68, -10.00, 57.01, 42.99, 14.02 +-10.68, -10.00, 52.07, 47.93, 4.14 +-10.68, -10.00, 52.07, 47.93, 4.14 +-10.68, -10.00, 52.07, 47.93, 4.15 +-10.68, -10.00, 52.08, 47.92, 4.15 +-10.68, -10.00, 52.08, 47.92, 4.16 +-10.68, -10.00, 52.08, 47.92, 4.16 +-10.68, -10.00, 52.08, 47.92, 4.17 +-10.68, -10.00, 52.09, 47.91, 4.17 +-10.68, -10.00, 52.09, 47.91, 4.18 +-10.68, -10.00, 52.09, 47.91, 4.18 +-10.68, -10.00, 52.09, 47.91, 4.19 +-10.55, -10.00, 47.05, 52.95, -5.89 +-10.55, -10.00, 52.00, 48.00, 4.00 +-10.55, -10.00, 52.00, 48.00, 4.00 +-10.55, -10.00, 52.00, 48.00, 4.01 +-10.55, -10.00, 52.00, 48.00, 4.01 +-10.55, -10.00, 52.01, 47.99, 4.01 +-10.55, -10.00, 52.01, 47.99, 4.02 +-10.55, -10.00, 52.01, 47.99, 4.02 +-10.55, -10.00, 52.01, 47.99, 4.03 +-10.55, -10.00, 52.02, 47.98, 4.03 +-10.55, -10.00, 52.02, 47.98, 4.03 +-10.55, -10.00, 52.02, 47.98, 4.04 +-10.55, -10.00, 52.02, 47.98, 4.04 +-10.55, -10.00, 52.02, 47.98, 4.05 +-10.55, -10.00, 52.03, 47.97, 4.05 +-10.55, -10.00, 52.03, 47.97, 4.05 +-10.55, -10.00, 52.03, 47.97, 4.06 +-10.55, -10.00, 52.03, 47.97, 4.06 +-10.55, -10.00, 52.03, 47.97, 4.07 +-10.55, -10.00, 52.04, 47.96, 4.07 +-10.55, -10.00, 52.04, 47.96, 4.08 +-10.68, -10.00, 57.08, 42.92, 14.17 +-10.55, -10.00, 47.10, 52.90, -5.80 +-10.68, -10.00, 57.09, 42.91, 14.18 +-10.68, -10.00, 52.15, 47.85, 4.29 +-10.68, -10.00, 52.15, 47.85, 4.30 +-10.68, -10.00, 52.15, 47.85, 4.30 +-10.68, -10.00, 52.15, 47.85, 4.31 +-10.68, -10.00, 52.16, 47.84, 4.31 +-10.68, -10.00, 52.16, 47.84, 4.32 +-10.68, -10.00, 52.16, 47.84, 4.32 +-10.68, -10.00, 52.16, 47.84, 4.33 +-10.68, -10.00, 52.17, 47.83, 4.33 +-10.68, -10.00, 52.17, 47.83, 4.34 +-10.68, -10.00, 52.17, 47.83, 4.34 +-10.68, -10.00, 52.17, 47.83, 4.35 +-10.68, -10.00, 52.18, 47.82, 4.35 +-10.68, -10.00, 52.18, 47.82, 4.36 +-10.68, -10.00, 52.18, 47.82, 4.36 +-10.68, -10.00, 52.18, 47.82, 4.37 +-10.68, -10.00, 52.19, 47.81, 4.37 +-10.68, -10.00, 52.19, 47.81, 4.38 +-10.68, -10.00, 52.19, 47.81, 4.38 +-10.68, -10.00, 52.19, 47.81, 4.39 +-10.68, -10.00, 52.20, 47.80, 4.39 +-10.68, -10.00, 52.20, 47.80, 4.40 +-10.74, -10.00, 54.72, 45.28, 9.45 +-10.74, -10.00, 52.25, 47.75, 4.51 +-10.74, -10.00, 52.26, 47.74, 4.52 +-10.68, -10.00, 49.74, 50.26, -0.52 +-10.68, -10.00, 52.21, 47.79, 4.43 +-10.68, -10.00, 52.22, 47.78, 4.43 +-10.68, -10.00, 52.22, 47.78, 4.44 +-10.68, -10.00, 52.22, 47.78, 4.44 +-10.68, -10.00, 52.22, 47.78, 4.45 +-10.68, -10.00, 52.23, 47.77, 4.45 +-10.68, -10.00, 52.23, 47.77, 4.46 +-10.68, -10.00, 52.23, 47.77, 4.46 +-10.68, -10.00, 52.23, 47.77, 4.47 +-10.68, -10.00, 52.24, 47.76, 4.47 +-10.68, -10.00, 52.24, 47.76, 4.48 +-10.68, -10.00, 52.24, 47.76, 4.48 +-10.68, -10.00, 52.24, 47.76, 4.49 +-10.68, -10.00, 52.25, 47.75, 4.49 +-10.68, -10.00, 52.25, 47.75, 4.50 +-10.68, -10.00, 52.25, 47.75, 4.50 +-10.68, -10.00, 52.25, 47.75, 4.51 +-10.68, -10.00, 52.26, 47.74, 4.51 +-10.68, -10.00, 52.26, 47.74, 4.52 +-10.55, -10.00, 47.22, 52.78, -5.56 +-10.68, -10.00, 57.21, 42.79, 14.41 +-10.68, -10.00, 52.27, 47.73, 4.53 +-10.55, -10.00, 47.23, 52.77, -5.55 +-10.55, -10.00, 52.17, 47.83, 4.34 +-10.55, -10.00, 52.17, 47.83, 4.35 +-10.55, -10.00, 52.18, 47.82, 4.35 +-10.55, -10.00, 52.18, 47.82, 4.36 +-10.55, -10.00, 52.18, 47.82, 4.36 +-10.55, -10.00, 52.18, 47.82, 4.36 +-10.55, -10.00, 52.18, 47.82, 4.37 +-10.55, -10.00, 52.19, 47.81, 4.37 +-10.55, -10.00, 52.19, 47.81, 4.38 +-10.68, -10.00, 57.23, 42.77, 14.47 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.60 +-10.68, -10.00, 52.30, 47.70, 4.60 +-10.68, -10.00, 52.30, 47.70, 4.61 +-10.68, -10.00, 52.31, 47.69, 4.61 +-10.68, -10.00, 52.31, 47.69, 4.62 +-10.68, -10.00, 52.31, 47.69, 4.62 +-10.68, -10.00, 52.31, 47.69, 4.63 +-10.68, -10.00, 52.32, 47.68, 4.63 +-10.68, -10.00, 52.32, 47.68, 4.64 +-10.68, -10.00, 52.32, 47.68, 4.64 +-10.68, -10.00, 52.32, 47.68, 4.65 +-10.68, -10.00, 52.33, 47.67, 4.65 +-10.68, -10.00, 52.33, 47.67, 4.66 +-10.68, -10.00, 52.33, 47.67, 4.66 +-10.68, -10.00, 52.34, 47.66, 4.67 +-10.74, -10.00, 54.86, 45.14, 9.72 +-10.74, -10.00, 52.39, 47.61, 4.78 +-10.74, -10.00, 52.39, 47.61, 4.79 +-10.74, -10.00, 52.40, 47.60, 4.79 +-10.74, -10.00, 52.40, 47.60, 4.80 +-10.74, -10.00, 52.40, 47.60, 4.80 +-10.74, -10.00, 52.40, 47.60, 4.81 +-10.81, -10.00, 54.93, 45.07, 9.86 +-10.81, -10.00, 52.46, 47.54, 4.92 +-10.81, -10.00, 52.46, 47.54, 4.93 +-10.81, -10.00, 52.47, 47.53, 4.93 +-10.81, -10.00, 52.47, 47.53, 4.94 +-10.81, -10.00, 52.47, 47.53, 4.94 +-10.94, -10.00, 57.52, 42.48, 15.04 +-10.94, -10.00, 52.58, 47.42, 5.16 +-10.94, -10.00, 52.58, 47.42, 5.16 +-10.94, -10.00, 52.58, 47.42, 5.17 +-10.94, -10.00, 52.59, 47.41, 5.18 +-10.94, -10.00, 52.59, 47.41, 5.18 +-10.94, -10.00, 52.60, 47.40, 5.19 +-11.01, -10.00, 55.12, 44.88, 10.24 +-11.01, -10.00, 52.65, 47.35, 5.30 +-11.01, -10.00, 52.66, 47.34, 5.31 +-11.01, -10.00, 52.66, 47.34, 5.32 +-11.01, -10.00, 52.66, 47.34, 5.33 +-11.01, -10.00, 52.67, 47.33, 5.33 +-11.01, -10.00, 52.67, 47.33, 5.34 +-11.07, -10.00, 55.20, 44.80, 10.39 +-11.07, -10.00, 52.73, 47.27, 5.46 +-11.07, -10.00, 52.73, 47.27, 5.47 +-11.07, -10.00, 52.74, 47.26, 5.47 +-11.07, -10.00, 52.74, 47.26, 5.48 +-11.07, -10.00, 52.74, 47.26, 5.49 +-11.21, -10.00, 57.79, 42.21, 15.58 +-11.21, -10.00, 52.85, 47.15, 5.71 +-11.21, -10.00, 52.86, 47.14, 5.71 +-11.21, -10.00, 52.86, 47.14, 5.72 +-11.21, -10.00, 52.87, 47.13, 5.73 +-11.21, -10.00, 52.87, 47.13, 5.74 +-11.21, -10.00, 52.88, 47.12, 5.75 +-11.21, -10.00, 52.88, 47.12, 5.76 +-11.21, -10.00, 52.88, 47.12, 5.77 +-11.21, -10.00, 52.89, 47.11, 5.78 +-11.21, -10.00, 52.89, 47.11, 5.79 +-11.21, -10.00, 52.90, 47.10, 5.80 +-11.21, -10.00, 52.90, 47.10, 5.80 +-11.21, -10.00, 52.91, 47.09, 5.81 +-11.21, -10.00, 52.91, 47.09, 5.82 +-11.21, -10.00, 52.92, 47.08, 5.83 +-11.21, -10.00, 52.92, 47.08, 5.84 +-11.21, -10.00, 52.93, 47.07, 5.85 +-11.21, -10.00, 52.93, 47.07, 5.86 +-11.21, -10.00, 52.93, 47.07, 5.87 +-11.21, -10.00, 52.94, 47.06, 5.88 +-11.21, -10.00, 52.94, 47.06, 5.89 +-11.21, -10.00, 52.95, 47.05, 5.90 +-11.21, -10.00, 52.95, 47.05, 5.90 +-11.21, -10.00, 52.96, 47.04, 5.91 +-11.21, -10.00, 52.96, 47.04, 5.92 +-11.07, -10.00, 47.92, 52.08, -4.15 +-11.07, -10.00, 52.87, 47.13, 5.74 +-11.07, -10.00, 52.87, 47.13, 5.75 +-11.07, -10.00, 52.88, 47.12, 5.76 +-11.07, -10.00, 52.88, 47.12, 5.77 +-11.01, -10.00, 50.36, 49.64, 0.73 +-11.01, -10.00, 52.84, 47.16, 5.68 +-11.01, -10.00, 52.84, 47.16, 5.69 +-11.01, -10.00, 52.85, 47.15, 5.70 +-11.01, -10.00, 52.85, 47.15, 5.70 +-11.01, -10.00, 52.86, 47.14, 5.71 +-10.94, -10.00, 50.34, 49.66, 0.68 +-10.94, -10.00, 52.81, 47.19, 5.63 +-10.94, -10.00, 52.82, 47.18, 5.63 +-10.94, -10.00, 52.82, 47.18, 5.64 +-10.81, -10.00, 47.78, 52.22, -4.44 +-10.81, -10.00, 52.73, 47.27, 5.46 +-10.81, -10.00, 52.73, 47.27, 5.46 +-10.81, -10.00, 52.73, 47.27, 5.47 +-10.74, -10.00, 50.22, 49.78, 0.43 +-10.74, -10.00, 52.69, 47.31, 5.38 +-10.74, -10.00, 52.69, 47.31, 5.39 +-10.74, -10.00, 52.70, 47.30, 5.39 +-10.74, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 52.70, 47.30, 5.41 +-10.68, -10.00, 50.19, 49.81, 0.37 +-10.68, -10.00, 52.66, 47.34, 5.32 +-10.68, -10.00, 52.66, 47.34, 5.32 +-10.68, 20.00, 75.00, 25.00, 50.00 +-10.68, 20.00, 75.00, 25.00, 50.00 +-10.68, 20.00, 75.00, 25.00, 50.00 +-10.68, 20.00, 75.00, 25.00, 50.00 +-10.55, 20.00, 70.69, 29.31, 41.39 +-10.55, 20.00, 75.00, 25.00, 50.00 +-10.55, 20.00, 75.00, 25.00, 50.00 +-10.55, 20.00, 75.00, 25.00, 50.00 +-10.48, 20.00, 73.57, 26.43, 47.15 +-10.42, 20.00, 73.64, 26.36, 47.28 +-10.42, 20.00, 75.00, 25.00, 50.00 +-10.28, 20.00, 71.30, 28.70, 42.59 +-10.22, 20.00, 73.83, 26.17, 47.66 +-10.15, 20.00, 73.90, 26.10, 47.79 +-10.02, 20.00, 71.44, 28.56, 42.87 +-9.95, 20.00, 73.97, 26.03, 47.94 +-9.89, 20.00, 74.03, 25.97, 48.07 +-9.69, 20.00, 69.05, 30.95, 38.11 +-9.62, 20.00, 74.06, 25.94, 48.12 +-9.43, 20.00, 69.08, 30.92, 38.15 +-9.23, 20.00, 69.04, 30.96, 38.08 +-9.10, 20.00, 71.52, 28.48, 43.04 +-8.90, 20.00, 69.01, 30.99, 38.02 +-8.70, 20.00, 68.97, 31.03, 37.94 +-8.44, 20.00, 66.41, 33.59, 32.81 +-8.31, 20.00, 71.36, 28.64, 42.71 +-8.04, 20.00, 66.32, 33.68, 32.64 +-7.78, 20.00, 66.23, 33.77, 32.45 +-7.51, 20.00, 66.13, 33.87, 32.26 +-7.25, 20.00, 66.04, 33.96, 32.07 +-6.99, 20.00, 65.94, 34.06, 31.88 +-6.72, 20.00, 65.84, 34.16, 31.68 +-6.33, 20.00, 60.70, 39.30, 21.40 +-6.06, 20.00, 65.54, 34.46, 31.09 +-5.73, 20.00, 62.92, 37.08, 25.84 +-5.41, 20.00, 62.77, 37.23, 25.54 +-5.01, 20.00, 60.09, 39.91, 20.19 +-4.68, 20.00, 62.41, 37.59, 24.82 +-4.35, 20.00, 62.26, 37.74, 24.51 +-3.96, 20.00, 59.58, 40.42, 19.16 +-3.56, 20.00, 59.37, 40.63, 18.74 +-3.16, 20.00, 59.16, 40.84, 18.32 +-2.77, 20.00, 58.95, 41.05, 17.90 +-2.31, 20.00, 56.21, 43.79, 12.43 +-1.85, 20.00, 55.95, 44.05, 11.90 +-1.45, 20.00, 58.21, 41.79, 16.41 +-1.05, 20.00, 57.99, 42.01, 15.98 +-0.53, 20.00, 52.73, 47.27, 5.45 +-0.13, 20.00, 57.45, 42.55, 14.90 +0.33, 20.00, 54.70, 45.30, 9.41 +0.86, 20.00, 51.91, 48.09, 3.82 +1.32, 20.00, 54.10, 45.90, 8.21 +1.85, 20.00, 51.30, 48.70, 2.61 +2.24, 20.00, 56.02, 43.98, 12.04 +2.70, 20.00, 53.27, 46.73, 6.53 +3.23, 20.00, 50.46, 49.54, 0.92 +3.69, 20.00, 52.65, 47.35, 5.30 +4.22, 20.00, 49.84, 50.16, -0.32 +4.61, 20.00, 54.54, 45.46, 9.09 +5.08, 20.00, 51.78, 48.22, 3.57 +5.54, 20.00, 51.49, 48.51, 2.98 +6.06, 20.00, 48.68, 51.32, -2.65 +6.46, 20.00, 53.37, 46.63, 6.75 +6.99, 20.00, 48.08, 51.92, -3.83 +7.45, 20.00, 50.26, 49.74, 0.51 +7.98, 20.00, 47.43, 52.57, -5.13 +8.50, 20.00, 47.08, 52.92, -5.84 +8.96, 20.00, 49.25, 50.75, -1.50 +9.49, 20.00, 46.42, 53.58, -7.16 +9.89, 20.00, 51.11, 48.89, 2.21 +10.42, 20.00, 45.80, 54.20, -8.40 +10.94, 20.00, 45.44, 54.56, -9.12 +11.40, 20.00, 47.60, 52.40, -4.80 +11.87, 20.00, 47.28, 52.72, -5.43 +12.26, 20.00, 49.49, 50.51, -1.02 +12.72, 20.00, 46.70, 53.30, -6.61 +13.18, 20.00, 46.38, 53.62, -7.25 +13.58, 20.00, 48.58, 51.42, -2.85 +14.04, 20.00, 45.78, 54.22, -8.44 +14.50, 20.00, 45.45, 54.55, -9.09 +14.90, 20.00, 47.65, 52.35, -4.70 +15.36, 20.00, 44.85, 55.15, -10.30 +15.82, 20.00, 44.52, 55.48, -10.96 +16.22, 20.00, 46.71, 53.29, -6.58 +16.68, 20.00, 43.90, 56.10, -12.20 +17.14, 20.00, 43.57, 56.43, -12.87 +17.47, 20.00, 48.27, 51.73, -3.45 +17.93, 20.00, 42.99, 57.01, -14.02 +18.33, 20.00, 45.17, 54.83, -9.66 +18.72, 20.00, 44.88, 55.12, -10.24 +19.12, 20.00, 44.59, 55.41, -10.83 +19.51, 20.00, 44.29, 55.71, -11.42 +19.84, 20.00, 46.52, 53.48, -6.96 +20.17, 20.00, 46.27, 53.73, -7.46 +20.57, 20.00, 43.50, 56.50, -13.00 +20.90, 20.00, 45.72, 54.28, -8.56 +21.16, 20.00, 47.99, 52.01, -4.02 +21.49, 20.00, 45.27, 54.73, -9.47 +21.75, 20.00, 47.53, 52.47, -4.93 +22.15, 20.00, 42.28, 57.72, -15.43 +22.48, 20.00, 44.50, 55.50, -11.00 +22.74, 20.00, 46.76, 53.24, -6.47 +23.07, 20.00, 44.03, 55.97, -11.93 +23.33, 20.00, 46.30, 53.70, -7.41 +23.53, 20.00, 48.61, 51.39, -2.79 +23.80, 20.00, 45.92, 54.08, -8.16 +23.99, 20.00, 48.23, 51.77, -3.54 +24.26, 20.00, 45.54, 54.46, -8.91 +24.39, 20.00, 50.37, 49.63, 0.75 +24.65, 20.00, 45.21, 54.79, -9.57 +24.79, 20.00, 50.04, 49.96, 0.08 +25.05, 20.00, 44.88, 55.12, -10.24 +25.18, 20.00, 49.71, 50.29, -0.59 +25.38, 20.00, 47.07, 52.93, -5.87 +25.58, 20.00, 46.90, 53.10, -6.21 +25.71, 20.00, 49.25, 50.75, -1.50 +25.91, 20.00, 46.61, 53.39, -6.79 +26.17, 20.00, 43.91, 56.09, -12.17 +26.24, 20.00, 51.26, 48.74, 2.51 +26.43, 20.00, 46.14, 53.86, -7.72 +26.63, 20.00, 45.97, 54.03, -8.07 +26.70, 20.00, 50.84, 49.16, 1.67 +26.76, 20.00, 50.76, 49.24, 1.52 +26.89, 20.00, 48.16, 51.84, -3.67 +26.96, 20.00, 50.56, 49.44, 1.12 +27.03, 20.00, 50.48, 49.52, 0.97 +27.03, 20.00, 52.93, 47.07, 5.86 +27.16, 20.00, 47.86, 52.14, -4.28 +27.16, 20.00, 52.78, 47.22, 5.56 +27.22, 20.00, 50.23, 49.77, 0.46 +27.22, 20.00, 52.67, 47.33, 5.35 +27.29, 20.00, 50.13, 49.87, 0.25 +27.29, 20.00, 52.57, 47.43, 5.14 +27.29, 20.00, 52.54, 47.46, 5.09 +27.29, 20.00, 52.52, 47.48, 5.03 +27.42, 20.00, 47.44, 52.56, -5.11 +27.42, 20.00, 52.36, 47.64, 4.72 +27.42, 20.00, 52.33, 47.67, 4.67 +27.42, 20.00, 52.31, 47.69, 4.61 +27.42, 20.00, 52.28, 47.72, 4.55 +27.42, 20.00, 52.25, 47.75, 4.50 +27.42, 20.00, 52.22, 47.78, 4.44 +27.42, 20.00, 52.19, 47.81, 4.39 +27.42, 20.00, 52.17, 47.83, 4.33 +27.29, 20.00, 57.18, 42.82, 14.36 +27.29, 20.00, 52.21, 47.79, 4.42 +27.22, 20.00, 54.70, 45.30, 9.41 +27.16, 20.00, 54.73, 45.27, 9.45 +27.16, 20.00, 52.23, 47.77, 4.46 +27.03, 20.00, 57.24, 42.76, 14.49 +26.96, 20.00, 54.80, 45.20, 9.59 +26.89, 20.00, 54.82, 45.18, 9.64 +26.89, 20.00, 52.32, 47.68, 4.64 +26.76, 20.00, 57.34, 42.66, 14.68 +26.76, 20.00, 52.37, 47.63, 4.74 +26.70, 20.00, 54.87, 45.13, 9.73 +26.63, 20.00, 54.89, 45.11, 9.78 +26.63, 20.00, 52.39, 47.61, 4.79 +26.50, 20.00, 57.41, 42.59, 14.82 +26.43, 20.00, 54.97, 45.03, 9.93 +26.37, 20.00, 54.99, 45.01, 9.98 +26.24, 20.00, 57.54, 42.46, 15.08 +26.17, 20.00, 55.09, 44.91, 10.19 +26.17, 20.00, 52.60, 47.40, 5.20 +26.10, 20.00, 55.10, 44.90, 10.19 +25.91, 20.00, 60.17, 39.83, 20.33 +25.84, 20.00, 55.25, 44.75, 10.50 +25.71, 20.00, 57.80, 42.20, 15.60 +25.64, 20.00, 55.36, 44.64, 10.71 +25.58, 20.00, 55.38, 44.62, 10.77 +25.44, 20.00, 57.93, 42.07, 15.87 +25.38, 20.00, 55.49, 44.51, 10.98 +25.38, 20.00, 53.00, 47.00, 6.00 +25.18, 20.00, 60.54, 39.46, 21.09 +25.18, 20.00, 53.11, 46.89, 6.22 +25.11, 20.00, 55.61, 44.39, 11.22 +25.05, 20.00, 55.64, 44.36, 11.28 +24.92, 20.00, 58.19, 41.81, 16.39 +24.92, 20.00, 53.23, 46.77, 6.46 +24.85, 20.00, 55.74, 44.26, 11.47 +24.79, 20.00, 55.77, 44.23, 11.53 +24.65, 20.00, 58.32, 41.68, 16.64 +24.65, 20.00, 53.36, 46.64, 6.72 +24.59, 20.00, 55.86, 44.14, 11.73 +24.52, 20.00, 55.90, 44.10, 11.79 +24.39, 20.00, 58.45, 41.55, 16.90 +24.39, 20.00, 53.49, 46.51, 6.98 +24.32, 20.00, 55.99, 44.01, 11.99 +24.26, 20.00, 56.03, 43.97, 12.06 +24.26, 20.00, 53.54, 46.46, 7.08 +24.26, 20.00, 53.52, 46.48, 7.05 +24.13, 20.00, 58.55, 41.45, 17.10 +24.13, 20.00, 53.59, 46.41, 7.18 +24.13, 20.00, 53.58, 46.42, 7.15 +24.06, 20.00, 56.08, 43.92, 12.17 +24.06, 20.00, 53.60, 46.40, 7.19 +24.06, 20.00, 53.58, 46.42, 7.16 +23.99, 20.00, 56.09, 43.91, 12.17 +23.99, 20.00, 53.60, 46.40, 7.20 +23.99, 20.00, 53.59, 46.41, 7.17 +23.86, 20.00, 58.61, 41.39, 17.23 +23.86, 20.00, 53.66, 46.34, 7.31 +23.86, 20.00, 53.64, 46.36, 7.28 +23.80, 20.00, 56.15, 43.85, 12.30 +23.80, 20.00, 53.66, 46.34, 7.32 +23.73, 20.00, 56.17, 43.83, 12.34 +23.73, 20.00, 53.68, 46.32, 7.37 +23.73, 20.00, 53.67, 46.33, 7.34 +23.73, 20.00, 53.66, 46.34, 7.31 +23.73, 20.00, 53.64, 46.36, 7.28 +23.73, 20.00, 53.63, 46.37, 7.25 +23.73, 20.00, 53.61, 46.39, 7.23 +23.73, 20.00, 53.60, 46.40, 7.20 +23.73, 20.00, 53.59, 46.41, 7.17 +23.73, 20.00, 53.57, 46.43, 7.14 +23.73, 20.00, 53.56, 46.44, 7.11 +23.73, 20.00, 53.54, 46.46, 7.09 +23.73, 20.00, 53.53, 46.47, 7.06 +23.73, 20.00, 53.52, 46.48, 7.03 +23.73, 20.00, 53.50, 46.50, 7.00 +23.73, 20.00, 53.49, 46.51, 6.97 +23.73, 20.00, 53.47, 46.53, 6.95 +23.73, 20.00, 53.46, 46.54, 6.92 +23.73, 20.00, 53.45, 46.55, 6.89 +23.73, 20.00, 53.43, 46.57, 6.86 +23.73, 20.00, 53.42, 46.58, 6.83 +23.80, 20.00, 50.88, 49.12, 1.76 +23.80, 20.00, 53.34, 46.66, 6.68 +23.80, 20.00, 53.33, 46.67, 6.65 +23.80, 20.00, 53.31, 46.69, 6.62 +23.86, 20.00, 50.78, 49.22, 1.55 +23.86, 20.00, 53.23, 46.77, 6.47 +23.99, 20.00, 48.17, 51.83, -3.65 +23.99, 20.00, 53.10, 46.90, 6.21 +23.99, 20.00, 53.09, 46.91, 6.18 +24.06, 20.00, 50.55, 49.45, 1.10 +24.06, 20.00, 53.01, 46.99, 6.02 +24.13, 20.00, 50.47, 49.53, 0.94 +24.13, 20.00, 52.93, 47.07, 5.86 +24.13, 20.00, 52.91, 47.09, 5.83 +24.26, 20.00, 47.85, 52.15, -4.29 +24.26, 20.00, 52.78, 47.22, 5.56 +24.26, 20.00, 52.77, 47.23, 5.53 +24.26, 20.00, 52.75, 47.25, 5.50 +24.32, 20.00, 50.21, 49.79, 0.43 +24.39, 20.00, 50.15, 49.85, 0.29 +24.39, 20.00, 52.60, 47.40, 5.20 +24.52, 20.00, 47.54, 52.46, -4.91 +24.59, 20.00, 49.95, 50.05, -0.10 +24.59, 20.00, 52.40, 47.60, 4.81 +24.65, 20.00, 49.86, 50.14, -0.27 +24.79, 20.00, 47.27, 52.73, -5.45 +24.79, 20.00, 52.20, 47.80, 4.40 +24.85, 20.00, 49.66, 50.34, -0.68 +24.85, 20.00, 52.12, 47.88, 4.23 +24.85, 20.00, 52.10, 47.90, 4.19 +24.92, 20.00, 49.56, 50.44, -0.89 +24.92, 20.00, 52.01, 47.99, 4.02 +24.92, 20.00, 51.99, 48.01, 3.98 +25.05, 20.00, 46.93, 53.07, -6.14 +25.05, 20.00, 51.86, 48.14, 3.71 +25.05, 20.00, 51.84, 48.16, 3.67 +25.11, 20.00, 49.30, 50.70, -1.41 +25.11, 20.00, 51.75, 48.25, 3.50 +25.18, 20.00, 49.21, 50.79, -1.58 +25.18, 20.00, 51.66, 48.34, 3.32 +25.31, 20.00, 46.60, 53.40, -6.80 +25.31, 20.00, 51.52, 48.48, 3.04 +25.38, 20.00, 48.98, 51.02, -2.04 +25.38, 20.00, 51.43, 48.57, 2.86 +25.38, 20.00, 51.41, 48.59, 2.82 +25.44, 20.00, 48.87, 51.13, -2.26 +25.44, 20.00, 51.32, 48.68, 2.64 +25.44, 20.00, 51.30, 48.70, 2.60 +25.44, 20.00, 51.28, 48.72, 2.56 +25.58, 20.00, 46.22, 53.78, -7.57 +25.58, 20.00, 51.14, 48.86, 2.28 +25.58, 20.00, 51.12, 48.88, 2.24 +25.58, 20.00, 51.10, 48.90, 2.20 +25.58, 20.00, 51.08, 48.92, 2.15 +25.58, 20.00, 51.06, 48.94, 2.11 +25.58, 20.00, 51.04, 48.96, 2.07 +25.58, 20.00, 51.01, 48.99, 2.03 +25.58, 20.00, 50.99, 49.01, 1.99 +25.58, 20.00, 50.97, 49.03, 1.95 +25.58, 20.00, 50.95, 49.05, 1.90 +25.58, 20.00, 50.93, 49.07, 1.86 +25.58, 20.00, 50.91, 49.09, 1.82 +25.58, 20.00, 50.89, 49.11, 1.78 +25.58, 20.00, 50.87, 49.13, 1.74 +25.58, 20.00, 50.85, 49.15, 1.69 +25.58, 20.00, 50.83, 49.17, 1.65 +25.44, 20.00, 55.85, 44.15, 11.70 +25.44, 20.00, 50.88, 49.12, 1.77 +25.44, 20.00, 50.86, 49.14, 1.73 +25.38, 20.00, 53.37, 46.63, 6.73 +25.38, 20.00, 50.87, 49.13, 1.75 +25.38, 20.00, 50.85, 49.15, 1.71 +25.31, 20.00, 53.35, 46.65, 6.71 +25.31, 20.00, 50.86, 49.14, 1.72 +25.18, 20.00, 55.89, 44.11, 11.77 +25.18, 20.00, 50.92, 49.08, 1.84 +25.11, 20.00, 53.42, 46.58, 6.85 +25.11, 20.00, 50.93, 49.07, 1.87 +25.05, 20.00, 53.44, 46.56, 6.87 +25.05, 20.00, 50.95, 49.05, 1.89 +24.92, 20.00, 55.97, 44.03, 11.94 +24.92, 20.00, 51.01, 48.99, 2.01 +24.92, 20.00, 50.99, 49.01, 1.98 +24.85, 20.00, 53.49, 46.51, 6.98 +24.85, 20.00, 51.00, 49.00, 2.00 +24.85, 20.00, 50.98, 49.02, 1.97 +24.79, 20.00, 53.49, 46.51, 6.97 +24.79, 20.00, 51.00, 49.00, 1.99 +24.79, 20.00, 50.98, 49.02, 1.96 +24.65, 20.00, 56.00, 44.00, 12.01 +24.65, 20.00, 51.04, 48.96, 2.09 +24.59, 20.00, 53.55, 46.45, 7.09 +24.59, 20.00, 51.06, 48.94, 2.12 +24.59, 20.00, 51.04, 48.96, 2.08 +24.52, 20.00, 53.55, 46.45, 7.09 +24.52, 20.00, 51.06, 48.94, 2.11 +24.39, 20.00, 56.08, 43.92, 12.17 +24.39, 20.00, 51.12, 48.88, 2.24 +24.32, 20.00, 53.63, 46.37, 7.26 +24.32, 20.00, 51.14, 48.86, 2.28 +24.26, 20.00, 53.64, 46.36, 7.29 +24.26, 20.00, 51.16, 48.84, 2.31 +24.26, 20.00, 51.14, 48.86, 2.28 +24.13, 20.00, 56.17, 43.83, 12.34 +24.13, 20.00, 51.21, 48.79, 2.42 +24.13, 20.00, 51.19, 48.81, 2.39 +24.13, 20.00, 51.18, 48.82, 2.36 +24.13, 20.00, 51.16, 48.84, 2.32 +24.06, 20.00, 53.67, 46.33, 7.34 +24.06, 20.00, 51.18, 48.82, 2.36 +24.06, 20.00, 51.17, 48.83, 2.33 +24.06, 20.00, 51.15, 48.85, 2.30 +24.06, 20.00, 51.14, 48.86, 2.27 +24.06, 20.00, 51.12, 48.88, 2.24 +23.99, 20.00, 53.63, 46.37, 7.25 +23.99, 20.00, 51.14, 48.86, 2.28 +23.99, 20.00, 51.13, 48.87, 2.25 +23.99, 20.00, 51.11, 48.89, 2.22 +23.99, 20.00, 51.10, 48.90, 2.19 +23.86, 20.00, 56.12, 43.88, 12.25 +23.86, 20.00, 51.16, 48.84, 2.33 +23.86, 20.00, 51.15, 48.85, 2.30 +23.80, 20.00, 53.66, 46.34, 7.32 +23.80, 20.00, 51.17, 48.83, 2.34 +23.80, 20.00, 51.16, 48.84, 2.31 +23.80, 20.00, 51.14, 48.86, 2.29 +23.80, 20.00, 51.13, 48.87, 2.26 +23.80, 20.00, 51.11, 48.89, 2.23 +23.80, 20.00, 51.10, 48.90, 2.20 +23.80, 20.00, 51.09, 48.91, 2.17 +23.80, 20.00, 51.07, 48.93, 2.14 +23.80, 20.00, 51.06, 48.94, 2.12 +23.80, 20.00, 51.04, 48.96, 2.09 +23.80, 20.00, 51.03, 48.97, 2.06 +23.80, 20.00, 51.01, 48.99, 2.03 +23.80, 20.00, 51.00, 49.00, 2.00 +23.80, 20.00, 50.99, 49.01, 1.97 +23.80, 20.00, 50.97, 49.03, 1.94 +23.80, 20.00, 50.96, 49.04, 1.92 +23.80, 20.00, 50.94, 49.06, 1.89 +23.80, 20.00, 50.93, 49.07, 1.86 +23.80, 20.00, 50.92, 49.08, 1.83 +23.86, 20.00, 48.38, 51.62, -3.24 +23.80, 20.00, 53.36, 46.64, 6.72 +23.80, 20.00, 50.87, 49.13, 1.74 +23.86, 20.00, 48.34, 51.66, -3.33 +23.86, 20.00, 50.79, 49.21, 1.59 +23.86, 20.00, 50.78, 49.22, 1.56 +23.86, 20.00, 50.76, 49.24, 1.53 +23.86, 20.00, 50.75, 49.25, 1.50 +23.86, 20.00, 50.74, 49.26, 1.47 +23.86, 20.00, 50.72, 49.28, 1.44 +23.86, 20.00, 50.71, 49.29, 1.41 +23.86, 20.00, 50.69, 49.31, 1.38 +23.99, 20.00, 45.63, 54.37, -8.73 +23.99, 20.00, 50.56, 49.44, 1.13 +23.99, 20.00, 50.55, 49.45, 1.10 +23.99, 20.00, 50.53, 49.47, 1.07 +23.99, 20.00, 50.52, 49.48, 1.04 +23.99, 20.00, 50.50, 49.50, 1.01 +24.06, 20.00, 47.97, 52.03, -4.07 +24.06, 20.00, 50.42, 49.58, 0.85 +24.06, 20.00, 50.41, 49.59, 0.82 +24.06, 20.00, 50.39, 49.61, 0.79 +24.06, 20.00, 50.38, 49.62, 0.76 +24.06, 20.00, 50.36, 49.64, 0.73 +24.06, 20.00, 50.35, 49.65, 0.70 +24.06, 20.00, 50.33, 49.67, 0.66 +24.13, 20.00, 47.80, 52.20, -4.41 +24.13, 20.00, 50.25, 49.75, 0.50 +24.13, 20.00, 50.24, 49.76, 0.47 +24.13, 20.00, 50.22, 49.78, 0.44 +24.13, 20.00, 50.21, 49.79, 0.41 +24.13, 20.00, 50.19, 49.81, 0.38 +24.13, 20.00, 50.17, 49.83, 0.35 +24.13, 20.00, 50.16, 49.84, 0.32 +24.26, 20.00, 45.10, 54.90, -9.80 +24.13, 20.00, 55.07, 44.93, 10.14 +24.13, 20.00, 50.11, 49.89, 0.22 +24.13, 20.00, 50.10, 49.90, 0.19 +24.13, 20.00, 50.08, 49.92, 0.16 +24.13, 20.00, 50.07, 49.93, 0.13 +24.13, 20.00, 50.05, 49.95, 0.10 +24.13, 20.00, 50.03, 49.97, 0.07 +24.13, 20.00, 50.02, 49.98, 0.04 +24.13, 20.00, 50.00, 50.00, 0.01 +24.13, 20.00, 49.99, 50.01, -0.02 +24.13, 20.00, 49.97, 50.03, -0.05 +24.26, 20.00, 44.91, 55.09, -10.17 +24.13, 20.00, 54.89, 45.11, 9.77 +24.13, 20.00, 49.93, 50.07, -0.15 +24.13, 20.00, 49.91, 50.09, -0.18 +24.13, 20.00, 49.90, 50.10, -0.21 +24.13, 20.00, 49.88, 50.12, -0.24 +24.13, 20.00, 49.86, 50.14, -0.27 +24.06, 20.00, 52.37, 47.63, 4.74 +24.06, 20.00, 49.88, 50.12, -0.23 +24.06, 20.00, 49.87, 50.13, -0.26 +23.99, 20.00, 52.37, 47.63, 4.75 +23.99, 20.00, 49.89, 50.11, -0.22 +23.99, 20.00, 49.87, 50.13, -0.25 +23.99, 20.00, 49.86, 50.14, -0.28 +23.99, 20.00, 49.84, 50.16, -0.31 +23.99, 20.00, 49.83, 50.17, -0.34 +23.86, 20.00, 54.86, 45.14, 9.71 +23.86, 20.00, 49.90, 50.10, -0.20 +23.86, 20.00, 49.88, 50.12, -0.23 +23.86, 20.00, 49.87, 50.13, -0.26 +23.86, 20.00, 49.85, 50.15, -0.29 +23.86, 20.00, 49.84, 50.16, -0.32 +23.80, 20.00, 52.35, 47.65, 4.69 +23.80, 20.00, 49.86, 50.14, -0.28 +23.80, 20.00, 49.85, 50.15, -0.31 +23.73, 20.00, 52.35, 47.65, 4.71 +23.73, 20.00, 49.87, 50.13, -0.26 +23.73, 20.00, 49.85, 50.15, -0.29 +23.60, 20.00, 54.88, 45.12, 9.77 +23.60, 20.00, 49.93, 50.07, -0.15 +23.60, 20.00, 49.91, 50.09, -0.18 +23.60, 20.00, 49.90, 50.10, -0.20 +23.60, 20.00, 49.89, 50.11, -0.23 +23.60, 20.00, 49.87, 50.13, -0.26 +23.60, 20.00, 49.86, 50.14, -0.28 +23.53, 20.00, 52.37, 47.63, 4.73 +23.60, 20.00, 47.36, 52.64, -5.28 +23.53, 20.00, 52.34, 47.66, 4.68 +23.53, 20.00, 49.85, 50.15, -0.29 +23.53, 20.00, 49.84, 50.16, -0.32 +23.53, 20.00, 49.83, 50.17, -0.34 +23.53, 20.00, 49.81, 50.19, -0.37 +23.53, 20.00, 49.80, 50.20, -0.40 +23.47, 20.00, 52.31, 47.69, 4.62 +23.47, 20.00, 49.82, 50.18, -0.35 +23.47, 20.00, 49.81, 50.19, -0.38 +23.47, 20.00, 49.80, 50.20, -0.40 +23.47, 20.00, 49.79, 50.21, -0.43 +23.33, 20.00, 54.82, 45.18, 9.63 +23.33, 20.00, 49.86, 50.14, -0.28 +23.47, 20.00, 44.80, 55.20, -10.39 +23.33, 20.00, 54.78, 45.22, 9.56 +23.33, 20.00, 49.82, 50.18, -0.36 +23.33, 20.00, 49.81, 50.19, -0.38 +23.33, 20.00, 49.80, 50.20, -0.41 +23.33, 20.00, 49.78, 50.22, -0.43 +23.33, 20.00, 49.77, 50.23, -0.46 +23.33, 20.00, 49.76, 50.24, -0.48 +23.33, 20.00, 49.75, 50.25, -0.51 +23.27, 20.00, 52.26, 47.74, 4.51 +23.27, 20.00, 49.77, 50.23, -0.46 +23.27, 20.00, 49.76, 50.24, -0.48 +23.20, 20.00, 52.27, 47.73, 4.54 +23.20, 20.00, 49.78, 50.22, -0.43 +23.20, 20.00, 49.77, 50.23, -0.45 +23.20, 20.00, 49.76, 50.24, -0.48 +23.20, 20.00, 49.75, 50.25, -0.50 +23.20, 20.00, 49.74, 50.26, -0.53 +23.20, 20.00, 49.72, 50.28, -0.55 +23.20, 20.00, 49.71, 50.29, -0.57 +23.20, 20.00, 49.70, 50.30, -0.60 +23.20, 20.00, 49.69, 50.31, -0.62 +23.20, 20.00, 49.68, 50.32, -0.65 +23.07, 20.00, 54.71, 45.29, 9.42 +23.07, 20.00, 49.75, 50.25, -0.50 +23.07, 20.00, 49.74, 50.26, -0.52 +23.01, 20.00, 52.25, 47.75, 4.50 +23.01, 20.00, 49.77, 50.23, -0.46 +23.01, 20.00, 49.76, 50.24, -0.49 +23.01, 20.00, 49.75, 50.25, -0.51 +22.94, 20.00, 52.26, 47.74, 4.51 +22.94, 20.00, 49.77, 50.23, -0.45 +22.94, 20.00, 49.76, 50.24, -0.48 +22.94, 20.00, 49.75, 50.25, -0.50 +22.81, 20.00, 54.78, 45.22, 9.57 +22.94, 20.00, 44.79, 55.21, -10.43 +22.94, 20.00, 49.72, 50.28, -0.56 +22.81, 20.00, 54.75, 45.25, 9.50 +22.94, 20.00, 44.75, 55.25, -10.49 +22.81, 20.00, 54.73, 45.27, 9.46 +22.81, 20.00, 49.77, 50.23, -0.45 +22.81, 20.00, 49.76, 50.24, -0.47 +22.81, 20.00, 49.75, 50.25, -0.49 +22.74, 20.00, 52.26, 47.74, 4.53 +22.74, 20.00, 49.78, 50.22, -0.44 +22.74, 20.00, 49.77, 50.23, -0.46 +22.68, 20.00, 52.28, 47.72, 4.57 +22.68, 20.00, 49.80, 50.20, -0.40 +22.68, 20.00, 49.79, 50.21, -0.42 +22.54, 20.00, 54.82, 45.18, 9.65 +22.68, 20.00, 44.83, 55.17, -10.34 +22.54, 20.00, 54.80, 45.20, 9.61 +22.68, 20.00, 44.81, 55.19, -10.38 +22.68, 20.00, 49.74, 50.26, -0.52 +22.68, 20.00, 49.73, 50.27, -0.54 +22.68, 20.00, 49.72, 50.28, -0.56 +22.68, 20.00, 49.71, 50.29, -0.58 +22.68, 20.00, 49.70, 50.30, -0.60 +22.68, 20.00, 49.69, 50.31, -0.62 +22.68, 20.00, 49.68, 50.32, -0.64 +22.68, 20.00, 49.67, 50.33, -0.66 +22.68, 20.00, 49.66, 50.34, -0.68 +22.54, 20.00, 54.69, 45.31, 9.39 +22.54, 20.00, 49.74, 50.26, -0.52 +22.48, 20.00, 52.25, 47.75, 4.51 +22.48, 20.00, 49.77, 50.23, -0.46 +22.48, 20.00, 49.76, 50.24, -0.47 +22.41, 20.00, 52.28, 47.72, 4.55 +22.41, 20.00, 49.79, 50.21, -0.41 +22.41, 20.00, 49.79, 50.21, -0.43 +22.41, 20.00, 49.78, 50.22, -0.45 +22.41, 20.00, 49.77, 50.23, -0.47 +22.41, 20.00, 49.76, 50.24, -0.48 +22.41, 20.00, 49.75, 50.25, -0.50 +22.41, 20.00, 49.74, 50.26, -0.52 +22.41, 20.00, 49.73, 50.27, -0.54 +22.28, 20.00, 54.77, 45.23, 9.53 +22.28, 20.00, 49.81, 50.19, -0.37 +22.28, 20.00, 49.80, 50.20, -0.39 +22.28, 20.00, 49.80, 50.20, -0.41 +22.21, 20.00, 52.31, 47.69, 4.62 +22.21, 20.00, 49.83, 50.17, -0.34 +22.21, 20.00, 49.82, 50.18, -0.36 +22.21, 20.00, 49.81, 50.19, -0.38 +22.15, 20.00, 52.33, 47.67, 4.65 +22.15, 20.00, 49.85, 50.15, -0.31 +22.15, 20.00, 49.84, 50.16, -0.33 +22.15, 20.00, 49.83, 50.17, -0.34 +22.15, 20.00, 49.82, 50.18, -0.36 +22.15, 20.00, 49.81, 50.19, -0.37 +22.15, 20.00, 49.81, 50.19, -0.39 +22.15, 20.00, 49.80, 50.20, -0.41 +22.15, 20.00, 49.79, 50.21, -0.42 +22.02, 20.00, 54.82, 45.18, 9.65 +22.02, 20.00, 49.87, 50.13, -0.25 +22.02, 20.00, 49.87, 50.13, -0.27 +22.02, 20.00, 49.86, 50.14, -0.28 +21.95, 20.00, 52.37, 47.63, 4.74 +21.95, 20.00, 49.89, 50.11, -0.22 +21.95, 20.00, 49.89, 50.11, -0.23 +21.95, 20.00, 49.88, 50.12, -0.24 +21.95, 20.00, 49.87, 50.13, -0.26 +21.95, 20.00, 49.86, 50.14, -0.27 +21.95, 20.00, 49.86, 50.14, -0.29 +21.95, 20.00, 49.85, 50.15, -0.30 +21.95, 20.00, 49.84, 50.16, -0.32 +21.95, 20.00, 49.83, 50.17, -0.33 +21.95, 20.00, 49.83, 50.17, -0.35 +21.95, 20.00, 49.82, 50.18, -0.36 +21.95, 20.00, 49.81, 50.19, -0.38 +21.95, 20.00, 49.80, 50.20, -0.39 +21.95, 20.00, 49.80, 50.20, -0.41 +21.95, 20.00, 49.79, 50.21, -0.42 +21.88, 20.00, 52.30, 47.70, 4.61 +21.95, 20.00, 47.30, 52.70, -5.39 +21.88, 20.00, 52.29, 47.71, 4.58 +21.88, 20.00, 49.81, 50.19, -0.38 +21.88, 20.00, 49.80, 50.20, -0.39 +21.88, 20.00, 49.80, 50.20, -0.41 +21.88, 20.00, 49.79, 50.21, -0.42 +21.88, 20.00, 49.78, 50.22, -0.43 +21.88, 20.00, 49.78, 50.22, -0.45 +21.88, 20.00, 49.77, 50.23, -0.46 +21.88, 20.00, 49.76, 50.24, -0.48 +21.88, 20.00, 49.75, 50.25, -0.49 +21.88, 20.00, 49.75, 50.25, -0.51 +21.88, 20.00, 49.74, 50.26, -0.52 +21.88, 20.00, 49.73, 50.27, -0.53 +21.88, 20.00, 49.73, 50.27, -0.55 +21.88, 20.00, 49.72, 50.28, -0.56 +21.88, 20.00, 49.71, 50.29, -0.58 +21.88, 20.00, 49.70, 50.30, -0.59 +21.88, 20.00, 49.70, 50.30, -0.60 +21.88, 20.00, 49.69, 50.31, -0.62 +21.88, 20.00, 49.68, 50.32, -0.63 +21.88, 20.00, 49.68, 50.32, -0.65 +21.88, 20.00, 49.67, 50.33, -0.66 +21.75, 20.00, 54.71, 45.29, 9.41 +21.75, 20.00, 49.76, 50.24, -0.49 +21.75, 20.00, 49.75, 50.25, -0.50 +21.75, 20.00, 49.74, 50.26, -0.52 +21.75, 20.00, 49.74, 50.26, -0.53 +21.69, 20.00, 52.25, 47.75, 4.50 +21.75, 20.00, 47.25, 52.75, -5.50 +21.75, 20.00, 49.72, 50.28, -0.57 +21.75, 20.00, 49.71, 50.29, -0.58 +21.75, 20.00, 49.70, 50.30, -0.59 +21.75, 20.00, 49.70, 50.30, -0.61 +21.75, 20.00, 49.69, 50.31, -0.62 +21.75, 20.00, 49.68, 50.32, -0.63 +21.75, 20.00, 49.68, 50.32, -0.65 +21.75, 20.00, 49.67, 50.33, -0.66 +21.75, 20.00, 49.66, 50.34, -0.67 +21.75, 20.00, 49.66, 50.34, -0.69 +21.75, 20.00, 49.65, 50.35, -0.70 +21.69, 20.00, 52.17, 47.83, 4.33 +21.69, 20.00, 49.69, 50.31, -0.63 +21.69, 20.00, 49.68, 50.32, -0.64 +21.69, 20.00, 49.67, 50.33, -0.65 +21.69, 20.00, 49.67, 50.33, -0.66 +21.69, 20.00, 49.66, 50.34, -0.68 +21.69, 20.00, 49.66, 50.34, -0.69 +21.69, 20.00, 49.65, 50.35, -0.70 +21.69, 20.00, 49.64, 50.36, -0.71 +21.69, 20.00, 49.64, 50.36, -0.73 +21.69, 20.00, 49.63, 50.37, -0.74 +21.69, 20.00, 49.62, 50.38, -0.75 +21.69, 20.00, 49.62, 50.38, -0.76 +21.69, 20.00, 49.61, 50.39, -0.78 +21.69, 20.00, 49.60, 50.40, -0.79 +21.69, 20.00, 49.60, 50.40, -0.80 +21.69, 20.00, 49.59, 50.41, -0.82 +21.69, 20.00, 49.59, 50.41, -0.83 +21.69, 20.00, 49.58, 50.42, -0.84 +21.69, 20.00, 49.57, 50.43, -0.85 +21.69, 20.00, 49.57, 50.43, -0.87 +21.69, 20.00, 49.56, 50.44, -0.88 +21.69, 20.00, 49.55, 50.45, -0.89 +21.69, 20.00, 49.55, 50.45, -0.90 +21.69, 20.00, 49.54, 50.46, -0.92 +21.69, 20.00, 49.54, 50.46, -0.93 +21.69, 20.00, 49.53, 50.47, -0.94 +21.69, 20.00, 49.52, 50.48, -0.95 +21.69, 20.00, 49.52, 50.48, -0.97 +21.69, 20.00, 49.51, 50.49, -0.98 +21.69, 20.00, 49.50, 50.50, -0.99 +21.69, 20.00, 49.50, 50.50, -1.01 +21.69, 20.00, 49.49, 50.51, -1.02 +21.69, 20.00, 49.48, 50.52, -1.03 +21.69, 20.00, 49.48, 50.52, -1.04 +21.69, 20.00, 49.47, 50.53, -1.06 +21.69, 20.00, 49.47, 50.53, -1.07 +21.69, 20.00, 49.46, 50.54, -1.08 +21.69, 20.00, 49.45, 50.55, -1.09 +21.69, 20.00, 49.45, 50.55, -1.11 +21.69, 20.00, 49.44, 50.56, -1.12 +21.69, 20.00, 49.43, 50.57, -1.13 +21.69, 20.00, 49.43, 50.57, -1.14 +21.69, 20.00, 49.42, 50.58, -1.16 +21.62, 20.00, 51.94, 48.06, 3.87 +21.62, 20.00, 49.46, 50.54, -1.08 +21.62, 20.00, 49.45, 50.55, -1.09 +21.62, 20.00, 49.45, 50.55, -1.11 +21.62, 20.00, 49.44, 50.56, -1.12 +21.49, 20.00, 54.48, 45.52, 8.96 +21.49, 20.00, 49.53, 50.47, -0.94 +21.49, 20.00, 49.52, 50.48, -0.95 +21.49, 20.00, 49.52, 50.48, -0.97 +21.49, 20.00, 49.51, 50.49, -0.98 +21.49, 20.00, 49.51, 50.49, -0.99 +21.49, 20.00, 49.50, 50.50, -1.00 +21.49, 20.00, 49.49, 50.51, -1.01 +21.42, 20.00, 52.01, 47.99, 4.02 +21.42, 20.00, 49.53, 50.47, -0.93 +21.42, 20.00, 49.53, 50.47, -0.94 +21.42, 20.00, 49.52, 50.48, -0.95 +21.42, 20.00, 49.52, 50.48, -0.97 +21.36, 20.00, 52.03, 47.97, 4.07 +21.36, 20.00, 49.56, 50.44, -0.89 +21.36, 20.00, 49.55, 50.45, -0.90 +21.36, 20.00, 49.55, 50.45, -0.91 +21.36, 20.00, 49.54, 50.46, -0.92 +21.36, 20.00, 49.54, 50.46, -0.93 +21.36, 20.00, 49.53, 50.47, -0.94 +21.36, 20.00, 49.53, 50.47, -0.95 +21.23, 20.00, 54.56, 45.44, 9.13 +21.23, 20.00, 49.62, 50.38, -0.77 +21.23, 20.00, 49.61, 50.39, -0.78 +21.23, 20.00, 49.61, 50.39, -0.79 +21.23, 20.00, 49.60, 50.40, -0.80 +21.23, 20.00, 49.60, 50.40, -0.81 +21.16, 20.00, 52.11, 47.89, 4.23 +21.16, 20.00, 49.64, 50.36, -0.72 +21.16, 20.00, 49.63, 50.37, -0.73 +21.09, 20.00, 52.15, 47.85, 4.30 +21.16, 20.00, 47.15, 52.85, -5.69 +21.09, 20.00, 52.14, 47.86, 4.29 +21.09, 20.00, 49.67, 50.33, -0.67 +21.16, 20.00, 47.14, 52.86, -5.72 +21.09, 20.00, 52.13, 47.87, 4.26 +21.09, 20.00, 49.65, 50.35, -0.69 +21.09, 20.00, 49.65, 50.35, -0.70 +21.09, 20.00, 49.65, 50.35, -0.71 +21.09, 20.00, 49.64, 50.36, -0.72 +21.09, 20.00, 49.64, 50.36, -0.72 +20.96, 20.00, 54.68, 45.32, 9.35 +21.09, 20.00, 44.69, 55.31, -10.63 +21.09, 20.00, 49.63, 50.37, -0.75 +21.09, 20.00, 49.62, 50.38, -0.76 +21.09, 20.00, 49.62, 50.38, -0.76 +21.09, 20.00, 49.61, 50.39, -0.77 +21.09, 20.00, 49.61, 50.39, -0.78 +21.09, 20.00, 49.61, 50.39, -0.79 +21.09, 20.00, 49.60, 50.40, -0.80 +21.09, 20.00, 49.60, 50.40, -0.81 +21.09, 20.00, 49.59, 50.41, -0.81 +21.09, 20.00, 49.59, 50.41, -0.82 +21.09, 20.00, 49.58, 50.42, -0.83 +21.09, 20.00, 49.58, 50.42, -0.84 +21.09, 20.00, 49.58, 50.42, -0.85 +21.09, 20.00, 49.57, 50.43, -0.85 +21.09, 20.00, 49.57, 50.43, -0.86 +21.09, 20.00, 49.56, 50.44, -0.87 +21.09, 20.00, 49.56, 50.44, -0.88 +21.09, 20.00, 49.56, 50.44, -0.89 +21.09, 20.00, 49.55, 50.45, -0.90 +21.09, 20.00, 49.55, 50.45, -0.90 +21.09, 20.00, 49.54, 50.46, -0.91 +21.09, 20.00, 49.54, 50.46, -0.92 +21.09, 20.00, 49.54, 50.46, -0.93 +21.09, 20.00, 49.53, 50.47, -0.94 +21.09, 20.00, 49.53, 50.47, -0.95 +21.09, 20.00, 49.52, 50.48, -0.95 +21.09, 20.00, 49.52, 50.48, -0.96 +21.09, 20.00, 49.52, 50.48, -0.97 +20.96, 20.00, 54.55, 45.45, 9.11 +21.09, 20.00, 44.56, 55.44, -10.87 +21.09, 20.00, 49.50, 50.50, -0.99 +21.09, 20.00, 49.50, 50.50, -1.00 +21.09, 20.00, 49.50, 50.50, -1.01 +21.09, 20.00, 49.49, 50.51, -1.02 +21.09, 20.00, 49.49, 50.51, -1.03 +21.09, 20.00, 49.48, 50.52, -1.03 +21.09, 20.00, 49.48, 50.52, -1.04 +21.09, 20.00, 49.47, 50.53, -1.05 +21.09, 20.00, 49.47, 50.53, -1.06 +21.09, 20.00, 49.47, 50.53, -1.07 +21.09, 20.00, 49.46, 50.54, -1.08 +21.09, 20.00, 49.46, 50.54, -1.08 +20.96, 20.00, 54.50, 45.50, 8.99 +20.96, 20.00, 49.55, 50.45, -0.90 +20.96, 20.00, 49.55, 50.45, -0.91 +20.96, 20.00, 49.54, 50.46, -0.91 +20.90, 20.00, 52.06, 47.94, 4.12 +20.90, 20.00, 49.59, 50.41, -0.83 +20.90, 20.00, 49.58, 50.42, -0.84 +20.90, 20.00, 49.58, 50.42, -0.84 +20.90, 20.00, 49.58, 50.42, -0.85 +20.90, 20.00, 49.57, 50.43, -0.86 +20.90, 20.00, 49.57, 50.43, -0.86 +20.90, 20.00, 49.57, 50.43, -0.87 +20.83, 20.00, 52.08, 47.92, 4.17 +20.83, 20.00, 49.61, 50.39, -0.78 +20.83, 20.00, 49.61, 50.39, -0.79 +20.83, 20.00, 49.60, 50.40, -0.80 +20.70, 20.00, 54.64, 45.36, 9.28 +20.70, 20.00, 49.70, 50.30, -0.61 +20.70, 20.00, 49.69, 50.31, -0.61 +20.70, 20.00, 49.69, 50.31, -0.62 +20.63, 20.00, 52.21, 47.79, 4.42 +20.63, 20.00, 49.74, 50.26, -0.53 +20.63, 20.00, 49.73, 50.27, -0.53 +20.57, 20.00, 52.25, 47.75, 4.50 +20.57, 20.00, 49.78, 50.22, -0.44 +20.57, 20.00, 49.78, 50.22, -0.45 +20.57, 20.00, 49.77, 50.23, -0.45 +20.43, 20.00, 54.81, 45.19, 9.63 +20.43, 20.00, 49.87, 50.13, -0.26 +20.43, 20.00, 49.87, 50.13, -0.26 +20.37, 20.00, 52.39, 47.61, 4.78 +20.37, 20.00, 49.91, 50.09, -0.17 +20.30, 20.00, 52.43, 47.57, 4.87 +20.37, 20.00, 47.44, 52.56, -5.12 +20.30, 20.00, 52.43, 47.57, 4.86 +20.30, 20.00, 49.96, 50.04, -0.08 +20.17, 20.00, 55.00, 45.00, 10.00 +20.17, 20.00, 50.06, 49.94, 0.11 +20.17, 20.00, 50.06, 49.94, 0.11 +20.17, 20.00, 50.06, 49.94, 0.11 +20.17, 20.00, 50.05, 49.95, 0.11 +20.10, 20.00, 52.58, 47.42, 5.15 +20.17, 20.00, 47.58, 52.42, -4.84 +20.17, 20.00, 50.05, 49.95, 0.11 +20.10, 20.00, 52.57, 47.43, 5.15 +20.10, 20.00, 50.10, 49.90, 0.20 +20.10, 20.00, 50.10, 49.90, 0.20 +20.10, 20.00, 50.10, 49.90, 0.20 +20.04, 20.00, 52.62, 47.38, 5.24 +20.04, 20.00, 50.15, 49.85, 0.30 +20.04, 20.00, 50.15, 49.85, 0.30 +19.91, 20.00, 55.19, 44.81, 10.39 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.84, 20.00, 52.77, 47.23, 5.55 +19.84, 20.00, 50.30, 49.70, 0.61 +19.84, 20.00, 50.30, 49.70, 0.61 +19.84, 20.00, 50.30, 49.70, 0.61 +19.78, 20.00, 52.83, 47.17, 5.65 +19.78, 20.00, 50.36, 49.64, 0.71 +19.78, 20.00, 50.36, 49.64, 0.71 +19.64, 20.00, 55.40, 44.60, 10.80 +19.64, 20.00, 50.46, 49.54, 0.92 +19.64, 20.00, 50.46, 49.54, 0.92 +19.64, 20.00, 50.46, 49.54, 0.92 +19.64, 20.00, 50.46, 49.54, 0.92 +19.64, 20.00, 50.46, 49.54, 0.93 +19.64, 20.00, 50.46, 49.54, 0.93 +19.64, 20.00, 50.47, 49.53, 0.93 +19.64, 20.00, 50.47, 49.53, 0.93 +19.64, 20.00, 50.47, 49.53, 0.94 +19.64, 20.00, 50.47, 49.53, 0.94 +19.64, 20.00, 50.47, 49.53, 0.94 +19.64, 20.00, 50.47, 49.53, 0.94 +19.64, 20.00, 50.47, 49.53, 0.95 +19.64, 20.00, 50.48, 49.52, 0.95 +19.64, 20.00, 50.48, 49.52, 0.95 +19.58, 20.00, 53.00, 47.00, 6.00 +19.58, 20.00, 50.53, 49.47, 1.06 +19.58, 20.00, 50.53, 49.47, 1.06 +19.58, 20.00, 50.53, 49.47, 1.06 +19.58, 20.00, 50.53, 49.47, 1.07 +19.58, 20.00, 50.54, 49.46, 1.07 +19.51, 20.00, 53.06, 46.94, 6.12 +19.58, 20.00, 48.07, 51.93, -3.87 +19.58, 20.00, 50.54, 49.46, 1.08 +19.58, 20.00, 50.54, 49.46, 1.08 +19.58, 20.00, 50.54, 49.46, 1.09 +19.58, 20.00, 50.55, 49.45, 1.09 +19.58, 20.00, 50.55, 49.45, 1.09 +19.58, 20.00, 50.55, 49.45, 1.10 +19.51, 20.00, 53.07, 46.93, 6.14 +19.51, 20.00, 50.60, 49.40, 1.20 +19.51, 20.00, 50.60, 49.40, 1.21 +19.51, 20.00, 50.61, 49.39, 1.21 +19.51, 20.00, 50.61, 49.39, 1.21 +19.51, 20.00, 50.61, 49.39, 1.22 +19.51, 20.00, 50.61, 49.39, 1.22 +19.51, 20.00, 50.61, 49.39, 1.22 +19.51, 20.00, 50.61, 49.39, 1.23 +19.51, 20.00, 50.62, 49.38, 1.23 +19.51, 20.00, 50.62, 49.38, 1.24 +19.51, 20.00, 50.62, 49.38, 1.24 +19.51, 20.00, 50.62, 49.38, 1.24 +19.51, 20.00, 50.62, 49.38, 1.25 +19.51, 20.00, 50.63, 49.37, 1.25 +19.51, 20.00, 50.63, 49.37, 1.25 +19.51, 20.00, 50.63, 49.37, 1.26 +19.51, 20.00, 50.63, 49.37, 1.26 +19.51, 20.00, 50.63, 49.37, 1.27 +19.58, 20.00, 48.11, 51.89, -3.77 +19.58, 20.00, 50.59, 49.41, 1.17 +19.58, 20.00, 50.59, 49.41, 1.18 +19.51, 20.00, 53.11, 46.89, 6.22 +19.51, 20.00, 50.64, 49.36, 1.28 +19.51, 20.00, 50.64, 49.36, 1.29 +19.51, 20.00, 50.64, 49.36, 1.29 +19.58, 20.00, 48.12, 51.88, -3.75 +19.51, 20.00, 53.12, 46.88, 6.24 +19.58, 20.00, 48.13, 51.87, -3.74 +19.58, 20.00, 50.60, 49.40, 1.20 +19.58, 20.00, 50.60, 49.40, 1.21 +19.58, 20.00, 50.60, 49.40, 1.21 +19.58, 20.00, 50.61, 49.39, 1.21 +19.64, 20.00, 48.09, 51.91, -3.83 +19.64, 20.00, 50.56, 49.44, 1.12 +19.64, 20.00, 50.56, 49.44, 1.12 +19.64, 20.00, 50.56, 49.44, 1.12 +19.64, 20.00, 50.56, 49.44, 1.13 +19.64, 20.00, 50.57, 49.43, 1.13 +19.64, 20.00, 50.57, 49.43, 1.13 +19.64, 20.00, 50.57, 49.43, 1.14 +19.64, 20.00, 50.57, 49.43, 1.14 +19.64, 20.00, 50.57, 49.43, 1.14 +19.64, 20.00, 50.57, 49.43, 1.14 +19.64, 20.00, 50.57, 49.43, 1.15 +19.64, 20.00, 50.57, 49.43, 1.15 +19.64, 20.00, 50.58, 49.42, 1.15 +19.64, 20.00, 50.58, 49.42, 1.15 +19.64, 20.00, 50.58, 49.42, 1.16 +19.64, 20.00, 50.58, 49.42, 1.16 +19.64, 20.00, 50.58, 49.42, 1.16 +19.64, 20.00, 50.58, 49.42, 1.16 +19.64, 20.00, 50.58, 49.42, 1.17 +19.64, 20.00, 50.59, 49.41, 1.17 +19.64, 20.00, 50.59, 49.41, 1.17 +19.64, 20.00, 50.59, 49.41, 1.18 +19.64, 20.00, 50.59, 49.41, 1.18 +19.64, 20.00, 50.59, 49.41, 1.18 +19.58, 20.00, 53.11, 46.89, 6.23 +19.58, 20.00, 50.64, 49.36, 1.29 +19.58, 20.00, 50.64, 49.36, 1.29 +19.58, 20.00, 50.65, 49.35, 1.29 +19.58, 20.00, 50.65, 49.35, 1.30 +19.51, 20.00, 53.17, 46.83, 6.34 +19.58, 20.00, 48.18, 51.82, -3.64 +19.58, 20.00, 50.65, 49.35, 1.31 +19.58, 20.00, 50.65, 49.35, 1.31 +19.58, 20.00, 50.66, 49.34, 1.31 +19.58, 20.00, 50.66, 49.34, 1.32 +19.58, 20.00, 50.66, 49.34, 1.32 +19.58, 20.00, 50.66, 49.34, 1.32 +19.58, 20.00, 50.66, 49.34, 1.32 +19.58, 20.00, 50.66, 49.34, 1.33 +19.58, 20.00, 50.67, 49.33, 1.33 +19.51, 20.00, 53.19, 46.81, 6.38 +19.51, 20.00, 50.72, 49.28, 1.44 +19.51, 20.00, 50.72, 49.28, 1.44 +19.51, 20.00, 50.72, 49.28, 1.44 +19.51, 20.00, 50.72, 49.28, 1.45 +19.51, 20.00, 50.73, 49.27, 1.45 +19.51, 20.00, 50.73, 49.27, 1.46 +19.51, 20.00, 50.73, 49.27, 1.46 +19.51, 20.00, 50.73, 49.27, 1.46 +19.58, 20.00, 48.21, 51.79, -3.58 +19.58, 20.00, 50.69, 49.31, 1.37 +19.58, 20.00, 50.69, 49.31, 1.37 +19.58, 20.00, 50.69, 49.31, 1.38 +19.58, 20.00, 50.69, 49.31, 1.38 +19.64, 20.00, 48.17, 51.83, -3.66 +19.64, 20.00, 50.64, 49.36, 1.29 +19.64, 20.00, 50.64, 49.36, 1.29 +19.58, 20.00, 53.17, 46.83, 6.33 +19.58, 20.00, 50.70, 49.30, 1.39 +19.58, 20.00, 50.70, 49.30, 1.40 +19.58, 20.00, 50.70, 49.30, 1.40 +19.58, 20.00, 50.70, 49.30, 1.40 +19.58, 20.00, 50.70, 49.30, 1.41 +19.58, 20.00, 50.71, 49.29, 1.41 +19.58, 20.00, 50.71, 49.29, 1.41 +19.58, 20.00, 50.71, 49.29, 1.42 +19.64, 20.00, 48.19, 51.81, -3.62 +19.64, 20.00, 50.66, 49.34, 1.32 +19.64, 20.00, 50.66, 49.34, 1.33 +19.64, 20.00, 50.66, 49.34, 1.33 +19.64, 20.00, 50.67, 49.33, 1.33 +19.78, 20.00, 45.62, 54.38, -8.75 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.15 +19.78, 20.00, 50.57, 49.43, 1.15 +19.78, 20.00, 50.57, 49.43, 1.15 +19.78, 20.00, 50.58, 49.42, 1.15 +19.78, 20.00, 50.58, 49.42, 1.15 +19.78, 20.00, 50.58, 49.42, 1.16 +19.84, 20.00, 48.06, 51.94, -3.89 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.07 +19.84, 20.00, 50.53, 49.47, 1.07 +19.84, 20.00, 50.53, 49.47, 1.07 +19.84, 20.00, 50.53, 49.47, 1.07 +19.78, 20.00, 53.06, 46.94, 6.11 +19.78, 20.00, 50.59, 49.41, 1.17 +19.78, 20.00, 50.59, 49.41, 1.17 +19.78, 20.00, 50.59, 49.41, 1.17 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.19 +19.78, 20.00, 50.59, 49.41, 1.19 +19.78, 20.00, 50.60, 49.40, 1.19 +19.78, 20.00, 50.60, 49.40, 1.19 +19.78, 20.00, 50.60, 49.40, 1.19 +19.64, 20.00, 55.64, 44.36, 11.28 +19.64, 20.00, 50.70, 49.30, 1.40 +19.64, 20.00, 50.70, 49.30, 1.40 +19.64, 20.00, 50.70, 49.30, 1.40 +19.64, 20.00, 50.70, 49.30, 1.40 +19.64, 20.00, 50.70, 49.30, 1.41 +19.58, 20.00, 53.23, 46.77, 6.45 +19.58, 20.00, 50.76, 49.24, 1.51 +19.58, 20.00, 50.76, 49.24, 1.52 +19.58, 20.00, 50.76, 49.24, 1.52 +19.58, 20.00, 50.76, 49.24, 1.52 +19.58, 20.00, 50.76, 49.24, 1.53 +19.58, 20.00, 50.76, 49.24, 1.53 +19.58, 20.00, 50.77, 49.23, 1.53 +19.58, 20.00, 50.77, 49.23, 1.53 +19.58, 20.00, 50.77, 49.23, 1.54 +19.51, 20.00, 53.29, 46.71, 6.58 +19.51, 20.00, 50.82, 49.18, 1.64 +19.51, 20.00, 50.82, 49.18, 1.65 +19.51, 20.00, 50.83, 49.17, 1.65 +19.51, 20.00, 50.83, 49.17, 1.65 +19.51, 20.00, 50.83, 49.17, 1.66 +19.51, 20.00, 50.83, 49.17, 1.66 +19.38, 20.00, 55.88, 44.12, 11.75 +19.38, 20.00, 50.93, 49.07, 1.87 +19.38, 20.00, 50.94, 49.06, 1.87 +19.38, 20.00, 50.94, 49.06, 1.88 +19.38, 20.00, 50.94, 49.06, 1.88 +19.38, 20.00, 50.94, 49.06, 1.89 +19.38, 20.00, 50.95, 49.05, 1.89 +19.38, 20.00, 50.95, 49.05, 1.90 +19.38, 20.00, 50.95, 49.05, 1.90 +19.38, 20.00, 50.95, 49.05, 1.91 +19.31, 20.00, 53.48, 46.52, 6.95 +19.31, 20.00, 51.01, 48.99, 2.02 +19.31, 20.00, 51.01, 48.99, 2.02 +19.31, 20.00, 51.01, 48.99, 2.03 +19.31, 20.00, 51.02, 48.98, 2.03 +19.31, 20.00, 51.02, 48.98, 2.04 +19.31, 20.00, 51.02, 48.98, 2.04 +19.31, 20.00, 51.02, 48.98, 2.05 +19.25, 20.00, 53.55, 46.45, 7.09 +19.25, 20.00, 51.08, 48.92, 2.16 +19.25, 20.00, 51.08, 48.92, 2.16 +19.25, 20.00, 51.08, 48.92, 2.17 +19.25, 20.00, 51.09, 48.91, 2.17 +19.12, 20.00, 56.13, 43.87, 12.27 +19.12, 20.00, 51.19, 48.81, 2.38 +19.12, 20.00, 51.20, 48.80, 2.39 +19.05, 20.00, 53.72, 46.28, 7.44 +19.05, 20.00, 51.25, 48.75, 2.50 +19.05, 20.00, 51.26, 48.74, 2.51 +18.98, 20.00, 53.78, 46.22, 7.56 +18.98, 20.00, 51.31, 48.69, 2.63 +18.85, 20.00, 56.36, 43.64, 12.72 +18.85, 20.00, 51.42, 48.58, 2.84 +18.85, 20.00, 51.42, 48.58, 2.85 +18.85, 20.00, 51.43, 48.57, 2.86 +18.85, 20.00, 51.43, 48.57, 2.87 +18.85, 20.00, 51.44, 48.56, 2.87 +18.85, 20.00, 51.44, 48.56, 2.88 +18.85, 20.00, 51.45, 48.55, 2.89 +18.79, 20.00, 53.97, 46.03, 7.94 +18.79, 20.00, 51.50, 48.50, 3.01 +18.79, 20.00, 51.51, 48.49, 3.02 +18.79, 20.00, 51.51, 48.49, 3.03 +18.79, 20.00, 51.52, 48.48, 3.04 +18.79, 20.00, 51.52, 48.48, 3.05 +18.72, 20.00, 54.05, 45.95, 8.10 +18.72, 20.00, 51.58, 48.42, 3.16 +18.72, 20.00, 51.59, 48.41, 3.17 +18.72, 20.00, 51.59, 48.41, 3.18 +18.59, 20.00, 56.64, 43.36, 13.28 +18.59, 20.00, 51.70, 48.30, 3.40 +18.59, 20.00, 51.71, 48.29, 3.41 +18.52, 20.00, 54.23, 45.77, 8.47 +18.59, 20.00, 49.25, 50.75, -1.51 +18.59, 20.00, 51.72, 48.28, 3.44 +18.59, 20.00, 51.73, 48.27, 3.46 +18.59, 20.00, 51.73, 48.27, 3.47 +18.59, 20.00, 51.74, 48.26, 3.48 +18.59, 20.00, 51.74, 48.26, 3.49 +18.59, 20.00, 51.75, 48.25, 3.50 +18.59, 20.00, 51.75, 48.25, 3.51 +18.59, 20.00, 51.76, 48.24, 3.52 +18.52, 20.00, 54.29, 45.71, 8.57 +18.52, 20.00, 51.82, 48.18, 3.64 +18.52, 20.00, 51.83, 48.17, 3.65 +18.52, 20.00, 51.83, 48.17, 3.66 +18.52, 20.00, 51.84, 48.16, 3.67 +18.46, 20.00, 54.36, 45.64, 8.73 +18.46, 20.00, 51.90, 48.10, 3.80 +18.46, 20.00, 51.90, 48.10, 3.81 +18.46, 20.00, 51.91, 48.09, 3.82 +18.46, 20.00, 51.91, 48.09, 3.83 +18.46, 20.00, 51.92, 48.08, 3.84 +18.52, 20.00, 49.40, 50.60, -1.19 +18.52, 20.00, 51.88, 48.12, 3.76 +18.52, 20.00, 51.89, 48.11, 3.78 +18.52, 20.00, 51.89, 48.11, 3.79 +18.52, 20.00, 51.90, 48.10, 3.80 +18.52, 20.00, 51.90, 48.10, 3.81 +18.52, 20.00, 51.91, 48.09, 3.82 +18.52, 20.00, 51.92, 48.08, 3.83 +18.52, 20.00, 51.92, 48.08, 3.84 +18.52, 20.00, 51.93, 48.07, 3.85 +18.52, 20.00, 51.93, 48.07, 3.86 +18.52, 20.00, 51.94, 48.06, 3.88 +18.46, 20.00, 54.46, 45.54, 8.93 +18.46, 20.00, 52.00, 48.00, 4.00 +18.46, 20.00, 52.00, 48.00, 4.01 +18.52, 20.00, 49.49, 50.51, -1.02 +18.52, 20.00, 51.97, 48.03, 3.93 +18.52, 20.00, 51.97, 48.03, 3.94 +18.59, 20.00, 49.46, 50.54, -1.09 +18.59, 20.00, 51.93, 48.07, 3.87 +18.72, 20.00, 46.89, 53.11, -6.21 +18.79, 20.00, 49.32, 50.68, -1.36 +18.79, 20.00, 51.80, 48.20, 3.60 +18.79, 20.00, 51.80, 48.20, 3.61 +18.79, 20.00, 51.81, 48.19, 3.62 +18.79, 20.00, 51.81, 48.19, 3.62 +18.79, 20.00, 51.82, 48.18, 3.63 +18.79, 20.00, 51.82, 48.18, 3.64 +18.72, 20.00, 54.35, 45.65, 8.69 +18.72, 20.00, 51.88, 48.12, 3.76 +18.72, 20.00, 51.88, 48.12, 3.77 +18.72, 20.00, 51.89, 48.11, 3.78 +18.72, 20.00, 51.89, 48.11, 3.79 +18.79, 20.00, 49.38, 50.62, -1.24 +18.79, 20.00, 51.85, 48.15, 3.71 +18.79, 20.00, 51.86, 48.14, 3.72 +18.85, 20.00, 49.34, 50.66, -1.32 +18.85, 20.00, 51.82, 48.18, 3.64 +18.98, 20.00, 46.78, 53.22, -6.44 +19.05, 20.00, 49.21, 50.79, -1.59 +19.05, 20.00, 51.68, 48.32, 3.36 +19.05, 20.00, 51.68, 48.32, 3.37 +19.05, 20.00, 51.69, 48.31, 3.38 +19.12, 20.00, 49.17, 50.83, -1.66 +19.12, 20.00, 51.64, 48.36, 3.29 +19.12, 20.00, 51.65, 48.35, 3.30 +19.12, 20.00, 51.65, 48.35, 3.30 +19.12, 20.00, 51.65, 48.35, 3.31 +19.12, 20.00, 51.66, 48.34, 3.32 +19.12, 20.00, 51.66, 48.34, 3.32 +19.12, 20.00, 51.66, 48.34, 3.33 +19.12, 20.00, 51.67, 48.33, 3.34 +19.25, 20.00, 46.63, 53.37, -6.74 +19.25, 20.00, 51.57, 48.43, 3.15 +19.31, 20.00, 49.06, 50.94, -1.89 +19.31, 20.00, 51.53, 48.47, 3.06 +19.31, 20.00, 51.53, 48.47, 3.07 +19.38, 20.00, 49.01, 50.99, -1.97 +19.38, 20.00, 51.49, 48.51, 2.98 +19.51, 20.00, 46.45, 53.55, -7.11 +19.38, 20.00, 56.44, 43.56, 12.87 +19.51, 20.00, 46.45, 53.55, -7.10 +19.51, 20.00, 51.40, 48.60, 2.79 +19.51, 20.00, 51.40, 48.60, 2.80 +19.51, 20.00, 51.40, 48.60, 2.80 +19.51, 20.00, 51.40, 48.60, 2.81 +19.51, 20.00, 51.40, 48.60, 2.81 +19.58, 20.00, 48.88, 51.12, -2.23 +19.58, 20.00, 51.36, 48.64, 2.72 +19.64, 20.00, 48.84, 51.16, -2.32 +19.64, 20.00, 51.31, 48.69, 2.62 +19.64, 20.00, 51.31, 48.69, 2.63 +19.78, 20.00, 46.27, 53.73, -7.46 +19.78, 20.00, 51.22, 48.78, 2.43 +19.78, 20.00, 51.22, 48.78, 2.43 +19.84, 20.00, 48.70, 51.30, -2.61 +19.84, 20.00, 51.17, 48.83, 2.34 +19.84, 20.00, 51.17, 48.83, 2.34 +19.91, 20.00, 48.65, 51.35, -2.70 +19.91, 20.00, 51.12, 48.88, 2.24 +19.91, 20.00, 51.12, 48.88, 2.24 +19.91, 20.00, 51.12, 48.88, 2.24 +19.91, 20.00, 51.12, 48.88, 2.24 +20.04, 20.00, 46.08, 53.92, -7.84 +19.91, 20.00, 56.07, 43.93, 12.13 +20.04, 20.00, 46.08, 53.92, -7.84 +20.04, 20.00, 51.02, 48.98, 2.04 +20.04, 20.00, 51.02, 48.98, 2.04 +20.10, 20.00, 48.50, 51.50, -3.00 +20.10, 20.00, 50.97, 49.03, 1.94 +20.10, 20.00, 50.97, 49.03, 1.94 +20.10, 20.00, 50.97, 49.03, 1.94 +20.17, 20.00, 48.45, 51.55, -3.10 +20.17, 20.00, 50.92, 49.08, 1.84 +20.17, 20.00, 50.92, 49.08, 1.84 +20.17, 20.00, 50.92, 49.08, 1.84 +20.30, 20.00, 45.88, 54.12, -8.25 +20.30, 20.00, 50.82, 49.18, 1.64 +20.17, 20.00, 55.86, 44.14, 11.72 +20.30, 20.00, 45.87, 54.13, -8.26 +20.30, 20.00, 50.82, 49.18, 1.63 +20.30, 20.00, 50.81, 49.19, 1.63 +20.30, 20.00, 50.81, 49.19, 1.63 +20.37, 20.00, 48.29, 51.71, -3.42 +20.37, 20.00, 50.76, 49.24, 1.52 +20.37, 20.00, 50.76, 49.24, 1.52 +20.37, 20.00, 50.76, 49.24, 1.52 +20.37, 20.00, 50.76, 49.24, 1.51 +20.43, 20.00, 48.23, 51.77, -3.53 +20.37, 20.00, 53.23, 46.77, 6.45 +20.43, 20.00, 48.23, 51.77, -3.54 +20.43, 20.00, 50.70, 49.30, 1.40 +20.37, 20.00, 53.22, 46.78, 6.44 +20.37, 20.00, 50.75, 49.25, 1.49 +20.37, 20.00, 50.75, 49.25, 1.49 +20.37, 20.00, 50.74, 49.26, 1.49 +20.37, 20.00, 50.74, 49.26, 1.49 +20.37, 20.00, 50.74, 49.26, 1.48 +20.37, 20.00, 50.74, 49.26, 1.48 +20.37, 20.00, 50.74, 49.26, 1.48 +20.37, 20.00, 50.74, 49.26, 1.48 +20.37, 20.00, 50.74, 49.26, 1.47 +20.37, 20.00, 50.73, 49.27, 1.47 +20.30, 20.00, 53.26, 46.74, 6.51 +20.37, 20.00, 48.26, 51.74, -3.48 +20.30, 20.00, 53.25, 46.75, 6.51 +20.30, 20.00, 50.78, 49.22, 1.56 +20.30, 20.00, 50.78, 49.22, 1.56 +20.30, 20.00, 50.78, 49.22, 1.55 +20.30, 20.00, 50.78, 49.22, 1.55 +20.30, 20.00, 50.78, 49.22, 1.55 +20.17, 20.00, 55.82, 44.18, 11.63 +20.17, 20.00, 50.87, 49.13, 1.75 +20.17, 20.00, 50.87, 49.13, 1.74 +20.17, 20.00, 50.87, 49.13, 1.74 +20.10, 20.00, 53.39, 46.61, 6.78 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.04, 20.00, 53.44, 46.56, 6.88 +20.04, 20.00, 50.97, 49.03, 1.94 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +19.91, 20.00, 56.01, 43.99, 12.02 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.84, 20.00, 53.59, 46.41, 7.18 +19.91, 20.00, 48.60, 51.40, -2.80 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.08, 48.92, 2.15 +19.91, 20.00, 51.08, 48.92, 2.15 +19.91, 20.00, 51.08, 48.92, 2.15 +19.91, 20.00, 51.08, 48.92, 2.15 +20.04, 20.00, 46.03, 53.97, -7.93 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +19.91, 20.00, 56.02, 43.98, 12.04 +20.04, 20.00, 46.03, 53.97, -7.94 +19.91, 20.00, 56.02, 43.98, 12.04 +19.91, 20.00, 51.08, 48.92, 2.15 +20.04, 20.00, 46.03, 53.97, -7.93 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.10, 20.00, 48.45, 51.55, -3.09 +20.04, 20.00, 53.45, 46.55, 6.89 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.10, 20.00, 48.45, 51.55, -3.10 +20.04, 20.00, 53.45, 46.55, 6.89 +20.10, 20.00, 48.45, 51.55, -3.10 +20.10, 20.00, 50.92, 49.08, 1.85 +20.10, 20.00, 50.92, 49.08, 1.85 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.04, 20.00, 53.44, 46.56, 6.88 +20.10, 20.00, 48.45, 51.55, -3.11 +20.04, 20.00, 53.44, 46.56, 6.88 +20.10, 20.00, 48.45, 51.55, -3.11 +20.04, 20.00, 53.44, 46.56, 6.88 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.96, 49.04, 1.93 +19.91, 20.00, 56.01, 43.99, 12.02 +19.91, 20.00, 51.06, 48.94, 2.13 +19.91, 20.00, 51.06, 48.94, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.84, 20.00, 53.59, 46.41, 7.18 +19.84, 20.00, 51.12, 48.88, 2.24 +19.84, 20.00, 51.12, 48.88, 2.24 +19.84, 20.00, 51.12, 48.88, 2.24 +19.78, 20.00, 53.64, 46.36, 7.28 +19.78, 20.00, 51.17, 48.83, 2.34 +19.78, 20.00, 51.17, 48.83, 2.34 +19.64, 20.00, 56.22, 43.78, 12.43 +19.78, 20.00, 46.23, 53.77, -7.54 +19.64, 20.00, 56.22, 43.78, 12.44 +19.64, 20.00, 51.28, 48.72, 2.55 +19.78, 20.00, 46.23, 53.77, -7.53 +19.64, 20.00, 56.22, 43.78, 12.44 +19.78, 20.00, 46.24, 53.76, -7.53 +19.78, 20.00, 51.18, 48.82, 2.36 +19.64, 20.00, 56.22, 43.78, 12.45 +19.78, 20.00, 46.24, 53.76, -7.52 +19.64, 20.00, 56.23, 43.77, 12.45 +19.64, 20.00, 51.28, 48.72, 2.57 +19.64, 20.00, 51.29, 48.71, 2.57 +19.64, 20.00, 51.29, 48.71, 2.57 +19.64, 20.00, 51.29, 48.71, 2.58 +19.64, 20.00, 51.29, 48.71, 2.58 +19.64, 20.00, 51.29, 48.71, 2.58 +19.64, 20.00, 51.29, 48.71, 2.59 +19.64, 20.00, 51.29, 48.71, 2.59 +19.64, 20.00, 51.30, 48.70, 2.59 +19.64, 20.00, 51.30, 48.70, 2.59 +19.64, 20.00, 51.30, 48.70, 2.60 +19.64, 20.00, 51.30, 48.70, 2.60 +19.64, 20.00, 51.30, 48.70, 2.60 +19.64, 20.00, 51.30, 48.70, 2.60 +19.64, 20.00, 51.30, 48.70, 2.61 +19.64, 20.00, 51.30, 48.70, 2.61 +19.58, 20.00, 53.83, 46.17, 7.66 +19.58, 20.00, 51.36, 48.64, 2.71 +19.58, 20.00, 51.36, 48.64, 2.72 +19.58, 20.00, 51.36, 48.64, 2.72 +19.51, 20.00, 53.88, 46.12, 7.77 +19.51, 20.00, 51.41, 48.59, 2.83 +19.58, 20.00, 48.89, 51.11, -2.21 +19.58, 20.00, 51.37, 48.63, 2.73 +19.51, 20.00, 53.89, 46.11, 7.78 +19.58, 20.00, 48.90, 51.10, -2.20 +19.58, 20.00, 51.37, 48.63, 2.74 +19.58, 20.00, 51.37, 48.63, 2.75 +19.58, 20.00, 51.38, 48.62, 2.75 +19.58, 20.00, 51.38, 48.62, 2.75 +19.58, 20.00, 51.38, 48.62, 2.76 +19.58, 20.00, 51.38, 48.62, 2.76 +19.58, 20.00, 51.38, 48.62, 2.76 +19.51, 20.00, 53.90, 46.10, 7.81 +19.51, 20.00, 51.43, 48.57, 2.87 +19.38, 20.00, 56.48, 43.52, 12.96 +19.38, 20.00, 51.54, 48.46, 3.08 +19.38, 20.00, 51.54, 48.46, 3.08 +19.31, 20.00, 54.06, 45.94, 8.13 +19.31, 20.00, 51.60, 48.40, 3.19 +19.31, 20.00, 51.60, 48.40, 3.20 +19.31, 20.00, 51.60, 48.40, 3.20 +19.31, 20.00, 51.60, 48.40, 3.21 +19.31, 20.00, 51.61, 48.39, 3.21 +19.31, 20.00, 51.61, 48.39, 3.22 +19.31, 20.00, 51.61, 48.39, 3.22 +19.31, 20.00, 51.61, 48.39, 3.23 +19.31, 20.00, 51.62, 48.38, 3.23 +19.31, 20.00, 51.62, 48.38, 3.24 +19.31, 20.00, 51.62, 48.38, 3.24 +19.31, 20.00, 51.62, 48.38, 3.25 +19.31, 20.00, 51.63, 48.37, 3.25 +19.25, 20.00, 54.15, 45.85, 8.30 +19.25, 20.00, 51.68, 48.32, 3.36 +19.25, 20.00, 51.68, 48.32, 3.37 +19.25, 20.00, 51.69, 48.31, 3.37 +19.25, 20.00, 51.69, 48.31, 3.38 +19.12, 20.00, 56.74, 43.26, 13.47 +19.12, 20.00, 51.80, 48.20, 3.59 +19.25, 20.00, 46.76, 53.24, -6.49 +19.25, 20.00, 51.70, 48.30, 3.40 +19.25, 20.00, 51.70, 48.30, 3.41 +19.25, 20.00, 51.71, 48.29, 3.42 +19.25, 20.00, 51.71, 48.29, 3.42 +19.25, 20.00, 51.71, 48.29, 3.43 +19.25, 20.00, 51.72, 48.28, 3.43 +19.25, 20.00, 51.72, 48.28, 3.44 +19.25, 20.00, 51.72, 48.28, 3.44 +19.25, 20.00, 51.72, 48.28, 3.45 +19.25, 20.00, 51.73, 48.27, 3.45 +19.12, 20.00, 56.77, 43.23, 13.55 +19.12, 20.00, 51.83, 48.17, 3.67 +19.12, 20.00, 51.84, 48.16, 3.67 +19.12, 20.00, 51.84, 48.16, 3.68 +19.12, 20.00, 51.84, 48.16, 3.69 +19.25, 20.00, 46.80, 53.20, -6.39 +19.25, 20.00, 51.75, 48.25, 3.50 +19.25, 20.00, 51.75, 48.25, 3.50 +19.25, 20.00, 51.76, 48.24, 3.51 +19.31, 20.00, 49.24, 50.76, -1.53 +19.31, 20.00, 51.71, 48.29, 3.42 +19.31, 20.00, 51.71, 48.29, 3.43 +19.31, 20.00, 51.72, 48.28, 3.43 +19.31, 20.00, 51.72, 48.28, 3.44 +19.31, 20.00, 51.72, 48.28, 3.44 +19.31, 20.00, 51.72, 48.28, 3.45 +19.25, 20.00, 54.25, 45.75, 8.50 +19.25, 20.00, 51.78, 48.22, 3.56 +19.25, 20.00, 51.78, 48.22, 3.56 +19.25, 20.00, 51.78, 48.22, 3.57 +19.25, 20.00, 51.79, 48.21, 3.57 +19.25, 20.00, 51.79, 48.21, 3.58 +19.31, 20.00, 49.27, 50.73, -1.46 +19.31, 20.00, 51.75, 48.25, 3.49 +19.31, 20.00, 51.75, 48.25, 3.50 +19.38, 20.00, 49.23, 50.77, -1.54 +19.38, 20.00, 51.70, 48.30, 3.41 +19.38, 20.00, 51.71, 48.29, 3.41 +19.38, 20.00, 51.71, 48.29, 3.42 +19.38, 20.00, 51.71, 48.29, 3.42 +19.38, 20.00, 51.71, 48.29, 3.43 +19.31, 20.00, 54.24, 45.76, 8.47 +19.38, 20.00, 49.25, 50.75, -1.51 +19.31, 20.00, 54.24, 45.76, 8.48 +19.31, 20.00, 51.77, 48.23, 3.54 +19.31, 20.00, 51.77, 48.23, 3.55 +19.31, 20.00, 51.78, 48.22, 3.56 +19.31, 20.00, 51.78, 48.22, 3.56 +19.31, 20.00, 51.78, 48.22, 3.57 +19.38, 20.00, 49.26, 50.74, -1.47 +19.38, 20.00, 51.74, 48.26, 3.48 +19.51, 20.00, 46.70, 53.30, -6.61 +19.51, 20.00, 51.64, 48.36, 3.29 +19.51, 20.00, 51.64, 48.36, 3.29 +19.51, 20.00, 51.65, 48.35, 3.29 +19.51, 20.00, 51.65, 48.35, 3.30 +19.38, 20.00, 56.69, 43.31, 13.39 +19.38, 20.00, 51.75, 48.25, 3.50 +19.38, 20.00, 51.75, 48.25, 3.51 +19.38, 20.00, 51.76, 48.24, 3.51 +19.38, 20.00, 51.76, 48.24, 3.52 +19.31, 20.00, 54.28, 45.72, 8.57 +19.38, 20.00, 49.29, 50.71, -1.42 +19.38, 20.00, 51.77, 48.23, 3.53 +19.38, 20.00, 51.77, 48.23, 3.54 +19.38, 20.00, 51.77, 48.23, 3.54 +19.38, 20.00, 51.77, 48.23, 3.55 +19.51, 20.00, 46.73, 53.27, -6.54 +19.51, 20.00, 51.68, 48.32, 3.36 +19.51, 20.00, 51.68, 48.32, 3.36 +19.51, 20.00, 51.68, 48.32, 3.36 +19.51, 20.00, 51.68, 48.32, 3.37 +19.51, 20.00, 51.69, 48.31, 3.37 +19.38, 20.00, 56.73, 43.27, 13.46 +19.38, 20.00, 51.79, 48.21, 3.58 +19.31, 20.00, 54.31, 45.69, 8.62 +19.38, 20.00, 49.32, 50.68, -1.36 +19.31, 20.00, 54.32, 45.68, 8.63 +19.31, 20.00, 51.85, 48.15, 3.70 +19.31, 20.00, 51.85, 48.15, 3.70 +19.31, 20.00, 51.85, 48.15, 3.71 +19.38, 20.00, 49.33, 50.67, -1.33 +19.38, 20.00, 51.81, 48.19, 3.62 +19.38, 20.00, 51.81, 48.19, 3.62 +19.51, 20.00, 46.77, 53.23, -6.46 +19.51, 20.00, 51.72, 48.28, 3.43 +19.58, 20.00, 49.20, 50.80, -1.61 +19.58, 20.00, 51.67, 48.33, 3.34 +19.58, 20.00, 51.67, 48.33, 3.34 +19.58, 20.00, 51.67, 48.33, 3.34 +19.51, 20.00, 54.20, 45.80, 8.39 +19.51, 20.00, 51.73, 48.27, 3.45 +19.51, 20.00, 51.73, 48.27, 3.45 +19.38, 20.00, 56.77, 43.23, 13.54 +19.51, 20.00, 46.79, 53.21, -6.42 +19.51, 20.00, 51.73, 48.27, 3.47 +19.51, 20.00, 51.74, 48.26, 3.47 +19.51, 20.00, 51.74, 48.26, 3.47 +19.51, 20.00, 51.74, 48.26, 3.48 +19.58, 20.00, 49.22, 50.78, -1.56 +19.64, 20.00, 49.17, 50.83, -1.66 +19.64, 20.00, 51.64, 48.36, 3.29 +19.78, 20.00, 46.60, 53.40, -6.80 +19.78, 20.00, 51.55, 48.45, 3.09 +19.84, 20.00, 49.03, 50.97, -1.95 +19.84, 20.00, 51.50, 48.50, 3.00 +19.84, 20.00, 51.50, 48.50, 3.00 +19.84, 20.00, 51.50, 48.50, 3.00 +19.84, 20.00, 51.50, 48.50, 3.00 +19.78, 20.00, 54.02, 45.98, 8.05 +19.78, 20.00, 51.55, 48.45, 3.10 +19.78, 20.00, 51.55, 48.45, 3.10 +19.64, 20.00, 56.60, 43.40, 13.19 +19.64, 20.00, 51.65, 48.35, 3.31 +19.64, 20.00, 51.66, 48.34, 3.31 +19.64, 20.00, 51.66, 48.34, 3.31 +19.78, 20.00, 46.61, 53.39, -6.77 +19.78, 20.00, 51.56, 48.44, 3.12 +19.84, 20.00, 49.04, 50.96, -1.92 +19.84, 20.00, 51.51, 48.49, 3.02 +19.91, 20.00, 48.99, 51.01, -2.02 +19.91, 20.00, 51.46, 48.54, 2.93 +19.91, 20.00, 51.46, 48.54, 2.93 +19.91, 20.00, 51.46, 48.54, 2.93 +20.04, 20.00, 46.42, 53.58, -7.16 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +19.91, 20.00, 56.41, 43.59, 12.81 +19.91, 20.00, 51.46, 48.54, 2.93 +19.91, 20.00, 51.46, 48.54, 2.93 +19.91, 20.00, 51.46, 48.54, 2.93 +20.04, 20.00, 46.42, 53.58, -7.16 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.10, 20.00, 48.84, 51.16, -2.31 +20.10, 20.00, 51.31, 48.69, 2.63 +20.10, 20.00, 51.31, 48.69, 2.63 +20.10, 20.00, 51.31, 48.69, 2.63 +20.10, 20.00, 51.31, 48.69, 2.63 +20.10, 20.00, 51.31, 48.69, 2.62 +20.04, 20.00, 53.83, 46.17, 7.67 +20.04, 20.00, 51.36, 48.64, 2.72 +20.04, 20.00, 51.36, 48.64, 2.72 +20.04, 20.00, 51.36, 48.64, 2.72 +20.04, 20.00, 51.36, 48.64, 2.72 +20.10, 20.00, 48.84, 51.16, -2.32 +20.04, 20.00, 53.83, 46.17, 7.67 +20.10, 20.00, 48.84, 51.16, -2.32 +20.10, 20.00, 51.31, 48.69, 2.62 +20.10, 20.00, 51.31, 48.69, 2.62 +20.10, 20.00, 51.31, 48.69, 2.62 +20.10, 20.00, 51.31, 48.69, 2.62 +20.17, 20.00, 48.79, 51.21, -2.43 +20.17, 20.00, 51.26, 48.74, 2.52 +20.17, 20.00, 51.26, 48.74, 2.52 +20.17, 20.00, 51.26, 48.74, 2.51 +20.17, 20.00, 51.26, 48.74, 2.51 +20.17, 20.00, 51.26, 48.74, 2.51 +20.17, 20.00, 51.26, 48.74, 2.51 +20.17, 20.00, 51.25, 48.75, 2.51 +20.17, 20.00, 51.25, 48.75, 2.51 +20.17, 20.00, 51.25, 48.75, 2.51 +20.17, 20.00, 51.25, 48.75, 2.51 +20.17, 20.00, 51.25, 48.75, 2.50 +20.17, 20.00, 51.25, 48.75, 2.50 +20.17, 20.00, 51.25, 48.75, 2.50 +20.17, 20.00, 51.25, 48.75, 2.50 +20.17, 20.00, 51.25, 48.75, 2.50 +20.30, 20.00, 46.21, 53.79, -7.59 +20.30, 20.00, 51.15, 48.85, 2.30 +20.30, 20.00, 51.15, 48.85, 2.29 +20.30, 20.00, 51.15, 48.85, 2.29 +20.30, 20.00, 51.14, 48.86, 2.29 +20.17, 20.00, 56.19, 43.81, 12.37 +20.17, 20.00, 51.24, 48.76, 2.49 +20.17, 20.00, 51.24, 48.76, 2.48 +20.10, 20.00, 53.76, 46.24, 7.53 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.04, 20.00, 53.81, 46.19, 7.62 +20.04, 20.00, 51.34, 48.66, 2.68 +20.10, 20.00, 48.82, 51.18, -2.37 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.28, 48.72, 2.57 +20.10, 20.00, 51.28, 48.72, 2.57 +20.10, 20.00, 51.28, 48.72, 2.57 +20.04, 20.00, 53.81, 46.19, 7.61 +20.04, 20.00, 51.33, 48.67, 2.67 +20.04, 20.00, 51.33, 48.67, 2.67 +20.04, 20.00, 51.33, 48.67, 2.67 +19.91, 20.00, 56.38, 43.62, 12.75 +19.91, 20.00, 51.43, 48.57, 2.86 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.84, 20.00, 53.96, 46.04, 7.91 +19.84, 20.00, 51.49, 48.51, 2.97 +19.84, 20.00, 51.49, 48.51, 2.97 +19.84, 20.00, 51.49, 48.51, 2.97 +19.84, 20.00, 51.49, 48.51, 2.97 +19.84, 20.00, 51.49, 48.51, 2.98 +19.78, 20.00, 54.01, 45.99, 8.02 +19.78, 20.00, 51.54, 48.46, 3.08 +19.78, 20.00, 51.54, 48.46, 3.08 +19.78, 20.00, 51.54, 48.46, 3.08 +19.64, 20.00, 56.58, 43.42, 13.17 +19.64, 20.00, 51.64, 48.36, 3.28 +19.64, 20.00, 51.64, 48.36, 3.29 +19.64, 20.00, 51.64, 48.36, 3.29 +19.64, 20.00, 51.65, 48.35, 3.29 +19.64, 20.00, 51.65, 48.35, 3.29 +19.58, 20.00, 54.17, 45.83, 8.34 +19.58, 20.00, 51.70, 48.30, 3.40 +19.58, 20.00, 51.70, 48.30, 3.40 +19.58, 20.00, 51.70, 48.30, 3.41 +19.58, 20.00, 51.70, 48.30, 3.41 +19.58, 20.00, 51.71, 48.29, 3.41 +19.58, 20.00, 51.71, 48.29, 3.42 +19.58, 20.00, 51.71, 48.29, 3.42 +19.58, 20.00, 51.71, 48.29, 3.42 +19.51, 20.00, 54.23, 45.77, 8.47 +19.51, 20.00, 51.76, 48.24, 3.53 +19.51, 20.00, 51.77, 48.23, 3.53 +19.51, 20.00, 51.77, 48.23, 3.54 +19.38, 20.00, 56.81, 43.19, 13.63 +19.38, 20.00, 51.87, 48.13, 3.74 +19.38, 20.00, 51.87, 48.13, 3.75 +19.38, 20.00, 51.88, 48.12, 3.75 +19.38, 20.00, 51.88, 48.12, 3.76 +19.38, 20.00, 51.88, 48.12, 3.76 +19.51, 20.00, 46.84, 53.16, -6.32 +19.51, 20.00, 51.79, 48.21, 3.57 +19.51, 20.00, 51.79, 48.21, 3.57 +19.51, 20.00, 51.79, 48.21, 3.58 +19.51, 20.00, 51.79, 48.21, 3.58 +19.51, 20.00, 51.79, 48.21, 3.59 +19.51, 20.00, 51.79, 48.21, 3.59 +19.38, 20.00, 56.84, 43.16, 13.68 +19.38, 20.00, 51.90, 48.10, 3.80 +19.38, 20.00, 51.90, 48.10, 3.80 +19.38, 20.00, 51.90, 48.10, 3.81 +19.38, 20.00, 51.90, 48.10, 3.81 +19.31, 20.00, 54.43, 45.57, 8.86 +19.31, 20.00, 51.96, 48.04, 3.92 +19.38, 20.00, 49.44, 50.56, -1.12 +19.38, 20.00, 51.91, 48.09, 3.83 +19.38, 20.00, 51.92, 48.08, 3.83 +19.51, 20.00, 46.88, 53.12, -6.25 +19.51, 20.00, 51.82, 48.18, 3.64 +19.58, 20.00, 49.30, 50.70, -1.40 +19.58, 20.00, 51.78, 48.22, 3.55 +19.58, 20.00, 51.78, 48.22, 3.55 +19.64, 20.00, 49.26, 50.74, -1.49 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.47 +19.64, 20.00, 51.73, 48.27, 3.47 +19.64, 20.00, 51.74, 48.26, 3.47 +19.64, 20.00, 51.74, 48.26, 3.47 +19.64, 20.00, 51.74, 48.26, 3.48 +19.64, 20.00, 51.74, 48.26, 3.48 +19.78, 20.00, 46.70, 53.30, -6.60 +19.78, 20.00, 51.64, 48.36, 3.29 +19.84, 20.00, 49.12, 50.88, -1.76 +19.84, 20.00, 51.59, 48.41, 3.19 +19.84, 20.00, 51.59, 48.41, 3.19 +19.91, 20.00, 49.07, 50.93, -1.85 +19.91, 20.00, 51.55, 48.45, 3.09 +20.04, 20.00, 46.50, 53.50, -6.99 +20.04, 20.00, 51.45, 48.55, 2.89 +20.10, 20.00, 48.93, 51.07, -2.15 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.17, 20.00, 48.87, 51.13, -2.26 +20.17, 20.00, 51.34, 48.66, 2.69 +20.17, 20.00, 51.34, 48.66, 2.69 +20.30, 20.00, 46.30, 53.70, -7.40 +20.30, 20.00, 51.24, 48.76, 2.48 +20.30, 20.00, 51.24, 48.76, 2.48 +20.30, 20.00, 51.24, 48.76, 2.48 +20.37, 20.00, 48.72, 51.28, -2.57 +20.37, 20.00, 51.19, 48.81, 2.37 +20.37, 20.00, 51.19, 48.81, 2.37 +20.37, 20.00, 51.18, 48.82, 2.37 +20.37, 20.00, 51.18, 48.82, 2.37 +20.37, 20.00, 51.18, 48.82, 2.36 +20.37, 20.00, 51.18, 48.82, 2.36 +20.37, 20.00, 51.18, 48.82, 2.36 +20.37, 20.00, 51.18, 48.82, 2.36 +20.37, 20.00, 51.18, 48.82, 2.35 +20.37, 20.00, 51.17, 48.83, 2.35 +20.37, 20.00, 51.17, 48.83, 2.35 +20.37, 20.00, 51.17, 48.83, 2.34 +20.37, 20.00, 51.17, 48.83, 2.34 +20.37, 20.00, 51.17, 48.83, 2.34 +20.37, 20.00, 51.17, 48.83, 2.34 +20.37, 20.00, 51.17, 48.83, 2.33 +20.37, 20.00, 51.17, 48.83, 2.33 +20.37, 20.00, 51.16, 48.84, 2.33 +20.37, 20.00, 51.16, 48.84, 2.33 +20.37, 20.00, 51.16, 48.84, 2.32 +20.37, 20.00, 51.16, 48.84, 2.32 +20.37, 20.00, 51.16, 48.84, 2.32 +20.37, 20.00, 51.16, 48.84, 2.31 +20.37, 20.00, 51.16, 48.84, 2.31 +20.37, 20.00, 51.15, 48.85, 2.31 +20.37, 20.00, 51.15, 48.85, 2.31 +20.30, 20.00, 53.67, 46.33, 7.35 +20.30, 20.00, 51.20, 48.80, 2.40 +20.30, 20.00, 51.20, 48.80, 2.40 +20.30, 20.00, 51.20, 48.80, 2.40 +20.17, 20.00, 56.24, 43.76, 12.48 +20.17, 20.00, 51.30, 48.70, 2.59 +20.17, 20.00, 51.29, 48.71, 2.59 +20.17, 20.00, 51.29, 48.71, 2.59 +20.10, 20.00, 53.82, 46.18, 7.63 +20.10, 20.00, 51.34, 48.66, 2.69 +20.10, 20.00, 51.34, 48.66, 2.68 +20.10, 20.00, 51.34, 48.66, 2.68 +20.10, 20.00, 51.34, 48.66, 2.68 +20.10, 20.00, 51.34, 48.66, 2.68 +20.04, 20.00, 53.86, 46.14, 7.72 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +19.91, 20.00, 56.43, 43.57, 12.87 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.84, 20.00, 54.01, 45.99, 8.03 +19.84, 20.00, 51.54, 48.46, 3.08 +19.84, 20.00, 51.54, 48.46, 3.08 +19.84, 20.00, 51.54, 48.46, 3.09 +19.84, 20.00, 51.54, 48.46, 3.09 +19.78, 20.00, 54.07, 45.93, 8.13 +19.84, 20.00, 49.07, 50.93, -1.85 +19.78, 20.00, 54.07, 45.93, 8.13 +19.78, 20.00, 51.60, 48.40, 3.19 +19.78, 20.00, 51.60, 48.40, 3.19 +19.78, 20.00, 51.60, 48.40, 3.19 +19.78, 20.00, 51.60, 48.40, 3.20 +19.78, 20.00, 51.60, 48.40, 3.20 +19.78, 20.00, 51.60, 48.40, 3.20 +19.78, 20.00, 51.60, 48.40, 3.20 +19.78, 20.00, 51.60, 48.40, 3.20 +19.64, 20.00, 56.65, 43.35, 13.29 +19.64, 20.00, 51.70, 48.30, 3.41 +19.64, 20.00, 51.70, 48.30, 3.41 +19.64, 20.00, 51.71, 48.29, 3.41 +19.64, 20.00, 51.71, 48.29, 3.41 +19.64, 20.00, 51.71, 48.29, 3.42 +19.64, 20.00, 51.71, 48.29, 3.42 +19.64, 20.00, 51.71, 48.29, 3.42 +19.64, 20.00, 51.71, 48.29, 3.43 +19.64, 20.00, 51.71, 48.29, 3.43 +19.64, 20.00, 51.72, 48.28, 3.43 +19.78, 20.00, 46.67, 53.33, -6.65 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.25 +19.78, 20.00, 51.62, 48.38, 3.25 +19.78, 20.00, 51.62, 48.38, 3.25 +19.64, 20.00, 56.67, 43.33, 13.34 +19.64, 20.00, 51.73, 48.27, 3.45 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.78, 20.00, 46.69, 53.31, -6.62 +19.64, 20.00, 56.68, 43.32, 13.35 +19.78, 20.00, 46.69, 53.31, -6.62 +19.78, 20.00, 51.64, 48.36, 3.27 +19.84, 20.00, 49.11, 50.89, -1.77 +19.84, 20.00, 51.59, 48.41, 3.17 +19.84, 20.00, 51.59, 48.41, 3.18 +19.84, 20.00, 51.59, 48.41, 3.18 +19.84, 20.00, 51.59, 48.41, 3.18 +19.91, 20.00, 49.07, 50.93, -1.86 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.09 +19.91, 20.00, 51.54, 48.46, 3.09 +19.91, 20.00, 51.54, 48.46, 3.09 +19.91, 20.00, 51.54, 48.46, 3.09 +19.91, 20.00, 51.54, 48.46, 3.09 +20.04, 20.00, 46.50, 53.50, -7.00 +20.04, 20.00, 51.44, 48.56, 2.89 +20.10, 20.00, 48.92, 51.08, -2.15 +20.10, 20.00, 51.39, 48.61, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.17, 20.00, 48.87, 51.13, -2.26 +20.10, 20.00, 53.86, 46.14, 7.73 +20.10, 20.00, 51.39, 48.61, 2.78 +20.10, 20.00, 51.39, 48.61, 2.78 +20.17, 20.00, 48.87, 51.13, -2.26 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.67 +20.30, 20.00, 46.29, 53.71, -7.41 +20.30, 20.00, 51.24, 48.76, 2.47 +20.30, 20.00, 51.23, 48.77, 2.47 +20.30, 20.00, 51.23, 48.77, 2.47 +20.30, 20.00, 51.23, 48.77, 2.46 +20.17, 20.00, 56.27, 43.73, 12.55 +20.17, 20.00, 51.33, 48.67, 2.66 +20.17, 20.00, 51.33, 48.67, 2.66 +20.17, 20.00, 51.33, 48.67, 2.66 +20.10, 20.00, 53.85, 46.15, 7.70 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.37, 48.63, 2.75 +20.10, 20.00, 51.37, 48.63, 2.75 +20.17, 20.00, 48.85, 51.15, -2.29 +20.10, 20.00, 53.85, 46.15, 7.69 +20.17, 20.00, 48.85, 51.15, -2.30 +20.17, 20.00, 51.32, 48.68, 2.65 +20.17, 20.00, 51.32, 48.68, 2.64 +20.10, 20.00, 53.84, 46.16, 7.69 +20.10, 20.00, 51.37, 48.63, 2.74 +20.10, 20.00, 51.37, 48.63, 2.74 +20.10, 20.00, 51.37, 48.63, 2.74 +20.04, 20.00, 53.89, 46.11, 7.78 +20.04, 20.00, 51.42, 48.58, 2.84 +20.04, 20.00, 51.42, 48.58, 2.84 +20.04, 20.00, 51.42, 48.58, 2.84 +19.91, 20.00, 56.46, 43.54, 12.92 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.84, 20.00, 54.04, 45.96, 8.09 +19.84, 20.00, 51.57, 48.43, 3.14 +19.84, 20.00, 51.57, 48.43, 3.14 +19.84, 20.00, 51.57, 48.43, 3.15 +19.84, 20.00, 51.57, 48.43, 3.15 +19.78, 20.00, 54.10, 45.90, 8.19 +19.78, 20.00, 51.62, 48.38, 3.25 +19.78, 20.00, 51.63, 48.37, 3.25 +19.78, 20.00, 51.63, 48.37, 3.25 +19.64, 20.00, 56.67, 43.33, 13.34 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.58, 20.00, 54.25, 45.75, 8.51 +19.58, 20.00, 51.78, 48.22, 3.57 +19.58, 20.00, 51.78, 48.22, 3.57 +19.58, 20.00, 51.79, 48.21, 3.57 +19.58, 20.00, 51.79, 48.21, 3.58 +19.58, 20.00, 51.79, 48.21, 3.58 +19.58, 20.00, 51.79, 48.21, 3.58 +19.58, 20.00, 51.79, 48.21, 3.58 +19.58, 20.00, 51.79, 48.21, 3.59 +19.51, 20.00, 54.32, 45.68, 8.63 +19.51, 20.00, 51.85, 48.15, 3.69 +19.51, 20.00, 51.85, 48.15, 3.70 +19.51, 20.00, 51.85, 48.15, 3.70 +19.51, 20.00, 51.85, 48.15, 3.71 +19.51, 20.00, 51.85, 48.15, 3.71 +19.38, 20.00, 56.90, 43.10, 13.80 +19.38, 20.00, 51.96, 48.04, 3.92 +19.38, 20.00, 51.96, 48.04, 3.92 +19.38, 20.00, 51.96, 48.04, 3.93 +19.38, 20.00, 51.96, 48.04, 3.93 +19.38, 20.00, 51.97, 48.03, 3.93 +19.38, 20.00, 51.97, 48.03, 3.94 +19.38, 20.00, 51.97, 48.03, 3.94 +19.51, 20.00, 46.93, 53.07, -6.14 +19.38, 20.00, 56.92, 43.08, 13.84 +19.38, 20.00, 51.98, 48.02, 3.96 +19.38, 20.00, 51.98, 48.02, 3.96 +19.38, 20.00, 51.98, 48.02, 3.97 +19.38, 20.00, 51.99, 48.01, 3.97 +19.38, 20.00, 51.99, 48.01, 3.98 +19.38, 20.00, 51.99, 48.01, 3.98 +19.38, 20.00, 51.99, 48.01, 3.98 +19.38, 20.00, 51.99, 48.01, 3.99 +19.38, 20.00, 52.00, 48.00, 3.99 +19.38, 20.00, 52.00, 48.00, 4.00 +19.38, 20.00, 52.00, 48.00, 4.00 +19.38, 20.00, 52.00, 48.00, 4.01 +19.38, 20.00, 52.01, 47.99, 4.01 +19.38, 20.00, 52.01, 47.99, 4.02 +19.38, 20.00, 52.01, 47.99, 4.02 +19.38, 20.00, 52.01, 47.99, 4.03 +19.51, 20.00, 46.97, 53.03, -6.06 +19.51, 20.00, 51.92, 48.08, 3.84 +19.38, 20.00, 56.96, 43.04, 13.93 +19.51, 20.00, 46.98, 53.02, -6.04 +19.38, 20.00, 56.97, 43.03, 13.93 +19.38, 20.00, 52.03, 47.97, 4.05 +19.38, 20.00, 52.03, 47.97, 4.06 +19.38, 20.00, 52.03, 47.97, 4.06 +19.38, 20.00, 52.03, 47.97, 4.07 +19.51, 20.00, 46.99, 53.01, -6.02 +19.51, 20.00, 51.94, 48.06, 3.88 +19.51, 20.00, 51.94, 48.06, 3.88 +19.58, 20.00, 49.42, 50.58, -1.16 +19.58, 20.00, 51.89, 48.11, 3.79 +19.58, 20.00, 51.89, 48.11, 3.79 +19.58, 20.00, 51.90, 48.10, 3.79 +19.58, 20.00, 51.90, 48.10, 3.80 +19.58, 20.00, 51.90, 48.10, 3.80 +19.58, 20.00, 51.90, 48.10, 3.80 +19.58, 20.00, 51.90, 48.10, 3.81 +19.64, 20.00, 49.38, 50.62, -1.23 +19.58, 20.00, 54.38, 45.62, 8.75 +19.64, 20.00, 49.39, 50.61, -1.23 +19.64, 20.00, 51.86, 48.14, 3.72 +19.64, 20.00, 51.86, 48.14, 3.72 +19.64, 20.00, 51.86, 48.14, 3.72 +19.64, 20.00, 51.86, 48.14, 3.73 +19.64, 20.00, 51.86, 48.14, 3.73 +19.64, 20.00, 51.87, 48.13, 3.73 +19.64, 20.00, 51.87, 48.13, 3.73 +19.78, 20.00, 46.82, 53.18, -6.35 +19.78, 20.00, 51.77, 48.23, 3.54 +19.78, 20.00, 51.77, 48.23, 3.54 +19.78, 20.00, 51.77, 48.23, 3.54 +19.78, 20.00, 51.77, 48.23, 3.54 +19.78, 20.00, 51.77, 48.23, 3.55 +19.78, 20.00, 51.77, 48.23, 3.55 +19.78, 20.00, 51.77, 48.23, 3.55 +19.78, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.08, 74.92, -49.83 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.78, -15.00, 26.56, 73.44, -46.88 +19.64, -15.00, 29.00, 71.00, -42.00 +19.64, -15.00, 25.00, 75.00, -50.00 +19.58, -15.00, 26.32, 73.68, -47.36 +19.38, -15.00, 31.28, 68.72, -37.44 +19.31, -15.00, 26.26, 73.74, -47.48 +19.25, -15.00, 26.18, 73.82, -47.64 +19.12, -15.00, 28.62, 71.38, -42.75 +18.98, -15.00, 28.59, 71.41, -42.81 +18.85, -15.00, 28.57, 71.43, -42.87 +18.59, -15.00, 33.58, 66.42, -32.84 +18.52, -15.00, 26.09, 73.91, -47.82 +18.26, -15.00, 33.58, 66.42, -32.84 +18.06, -15.00, 31.13, 68.87, -37.74 +17.93, -15.00, 28.63, 71.37, -42.73 +17.53, -15.00, 38.70, 61.30, -22.61 +17.40, -15.00, 28.79, 71.21, -42.43 +17.14, -15.00, 33.81, 66.19, -32.39 +16.74, -15.00, 38.93, 61.07, -22.14 +16.48, -15.00, 34.06, 65.94, -31.87 +16.15, -15.00, 36.67, 63.33, -26.67 +15.89, -15.00, 34.28, 65.72, -31.45 +15.42, -15.00, 41.92, 58.08, -16.15 +15.16, -15.00, 34.59, 65.41, -30.81 +14.77, -15.00, 39.72, 60.28, -20.55 +14.30, -15.00, 42.43, 57.57, -15.14 +13.97, -15.00, 37.63, 62.37, -24.75 +13.58, -15.00, 40.29, 59.71, -19.43 +13.18, -15.00, 40.48, 59.52, -19.04 +12.72, -15.00, 43.19, 56.81, -13.62 +12.26, -15.00, 43.44, 56.56, -13.13 +11.87, -15.00, 41.16, 58.84, -17.68 +11.34, -15.00, 46.40, 53.60, -7.20 +10.88, -15.00, 44.18, 55.82, -11.65 +10.35, -15.00, 46.95, 53.05, -6.10 +9.89, -15.00, 44.73, 55.27, -10.54 +9.36, -15.00, 47.51, 52.49, -4.99 +8.83, -15.00, 47.81, 52.19, -4.37 +8.31, -15.00, 48.12, 51.88, -3.76 +7.78, -15.00, 48.43, 51.57, -3.14 +7.25, -15.00, 48.74, 51.26, -2.51 +6.66, -15.00, 51.58, 48.42, 3.16 +6.13, -15.00, 49.42, 50.58, -1.15 +5.60, -15.00, 49.74, 50.26, -0.52 +5.01, -15.00, 52.58, 47.42, 5.17 +4.48, -15.00, 50.43, 49.57, 0.87 +3.96, -15.00, 50.76, 49.24, 1.52 +3.43, -15.00, 51.08, 48.92, 2.17 +2.77, -15.00, 56.46, 43.54, 12.91 +2.24, -15.00, 51.84, 48.16, 3.69 +1.65, -15.00, 54.70, 45.30, 9.39 +1.12, -15.00, 52.56, 47.44, 5.12 +0.53, -15.00, 55.42, 44.58, 10.84 +-0.13, -15.00, 58.33, 41.67, 16.66 +-0.73, -15.00, 56.25, 43.75, 12.50 +-1.45, -15.00, 61.69, 38.31, 23.37 +-2.04, -15.00, 57.14, 42.86, 14.28 +-2.77, -15.00, 62.58, 37.42, 25.16 +-3.36, -15.00, 58.04, 41.96, 16.08 +-4.09, -15.00, 63.48, 36.52, 26.97 +-4.75, -15.00, 61.47, 38.53, 22.94 +-5.27, -15.00, 56.88, 43.12, 13.77 +-6.00, -15.00, 64.81, 35.19, 29.62 +-6.59, -15.00, 60.28, 39.72, 20.56 +-7.25, -15.00, 63.22, 36.78, 26.43 +-7.84, -15.00, 61.16, 38.84, 22.33 +-8.44, -15.00, 61.58, 38.42, 23.17 +-9.10, -15.00, 64.53, 35.47, 29.05 +-9.62, -15.00, 59.96, 40.04, 19.92 +-10.28, -15.00, 65.38, 34.62, 30.76 +-10.81, -15.00, 60.82, 39.18, 21.63 +-11.47, -15.00, 66.24, 33.76, 32.48 +-12.06, -15.00, 64.20, 35.80, 28.40 +-12.66, -15.00, 64.64, 35.36, 29.28 +-13.18, -15.00, 62.56, 37.44, 25.11 +-13.84, -15.00, 67.99, 32.01, 35.98 +-14.37, -15.00, 63.44, 36.56, 26.88 +-14.96, -15.00, 66.35, 33.65, 32.71 +-15.56, -15.00, 66.80, 33.20, 33.60 +-16.08, -15.00, 64.73, 35.27, 29.46 +-16.61, -15.00, 65.13, 34.87, 30.26 +-17.14, -15.00, 65.53, 34.47, 31.07 +-17.67, -15.00, 65.94, 34.06, 31.88 +-18.19, -15.00, 66.35, 33.65, 32.70 +-18.65, -15.00, 64.24, 35.76, 28.47 +-19.18, -15.00, 67.12, 32.88, 34.24 +-19.71, -15.00, 67.53, 32.47, 35.06 +-20.24, -15.00, 67.95, 32.05, 35.89 +-20.70, -15.00, 65.84, 34.16, 31.68 +-21.09, -15.00, 63.69, 36.31, 27.38 +-21.56, -15.00, 66.53, 33.47, 33.07 +-22.02, -15.00, 66.90, 33.09, 33.81 +-22.41, -15.00, 64.76, 35.24, 29.52 +-22.87, -15.00, 67.61, 32.39, 35.21 +-23.20, -15.00, 62.94, 37.06, 25.88 +-23.60, -15.00, 65.74, 34.26, 31.48 +-23.99, -15.00, 66.07, 33.93, 32.14 +-24.39, -15.00, 66.40, 33.60, 32.80 +-24.72, -15.00, 64.21, 35.79, 28.43 +-25.05, -15.00, 64.50, 35.50, 29.00 +-25.44, -15.00, 67.31, 32.69, 34.61 +-25.71, -15.00, 62.60, 37.40, 25.20 +-26.04, -15.00, 65.36, 34.64, 30.72 +-26.30, -15.00, 63.13, 36.87, 26.26 +-26.63, -15.00, 65.89, 34.11, 31.78 +-26.89, -15.00, 63.66, 36.34, 27.32 +-27.16, -15.00, 63.91, 36.09, 27.81 +-27.42, -15.00, 64.15, 35.85, 28.30 +-27.69, -15.00, 64.40, 35.60, 28.79 +-27.95, -15.00, 64.64, 35.36, 29.28 +-28.15, -15.00, 62.37, 37.63, 24.73 +-28.41, -15.00, 65.09, 34.91, 30.17 +-28.48, -15.00, 57.77, 42.23, 15.54 +-28.74, -15.00, 65.44, 34.56, 30.87 +-28.87, -15.00, 60.64, 39.36, 21.29 +-29.00, -15.00, 60.80, 39.20, 21.59 +-29.14, -15.00, 60.95, 39.05, 21.89 +-29.27, -15.00, 61.10, 38.90, 22.20 +-29.40, -15.00, 61.25, 38.75, 22.50 +-29.53, -15.00, 61.41, 38.59, 22.81 +-29.66, -15.00, 61.56, 38.44, 23.12 +-29.73, -15.00, 59.19, 40.81, 18.38 +-29.79, -15.00, 59.30, 40.70, 18.59 +-29.79, -15.00, 56.88, 43.12, 13.76 +-29.93, -15.00, 61.98, 38.02, 23.96 +-29.99, -15.00, 59.61, 40.39, 19.23 +-29.99, -15.00, 57.20, 42.80, 14.39 +-30.06, -15.00, 59.78, 40.22, 19.55 +-30.06, -15.00, 57.36, 42.64, 14.72 +-30.06, -15.00, 57.42, 42.58, 14.83 +-30.06, -15.00, 57.47, 42.53, 14.95 +-30.06, -15.00, 57.53, 42.47, 15.06 +-30.06, -15.00, 57.59, 42.41, 15.17 +-29.99, -15.00, 55.12, 44.88, 10.24 +-29.99, -15.00, 57.65, 42.35, 15.30 +-29.99, -15.00, 57.70, 42.30, 15.41 +-29.99, -15.00, 57.76, 42.24, 15.52 +-29.93, -15.00, 55.30, 44.70, 10.59 +-29.79, -15.00, 52.78, 47.22, 5.56 +-29.79, -15.00, 57.78, 42.22, 15.56 +-29.73, -15.00, 55.31, 44.69, 10.63 +-29.66, -15.00, 55.32, 44.68, 10.64 +-29.53, -15.00, 52.80, 47.20, 5.61 +-29.53, -15.00, 57.80, 42.20, 15.60 +-29.40, -15.00, 52.81, 47.19, 5.62 +-29.27, -15.00, 52.77, 47.23, 5.53 +-29.20, -15.00, 55.24, 44.76, 10.49 +-29.14, -15.00, 55.25, 44.75, 10.49 +-29.00, -15.00, 52.73, 47.27, 5.46 +-28.87, -15.00, 52.68, 47.32, 5.36 +-28.74, -15.00, 52.63, 47.37, 5.27 +-28.67, -15.00, 55.11, 44.89, 10.22 +-28.48, -15.00, 50.07, 49.93, 0.13 +-28.41, -15.00, 55.01, 44.99, 10.02 +-28.34, -15.00, 55.01, 44.99, 10.02 +-28.21, -15.00, 52.49, 47.51, 4.98 +-28.08, -15.00, 52.44, 47.56, 4.88 +-27.95, -15.00, 52.39, 47.61, 4.78 +-27.82, -15.00, 52.34, 47.66, 4.68 +-27.62, -15.00, 49.77, 50.23, -0.47 +-27.55, -15.00, 54.71, 45.29, 9.42 +-27.36, -15.00, 49.66, 50.34, -0.68 +-27.29, -15.00, 54.60, 45.40, 9.20 +-27.09, -15.00, 49.56, 50.44, -0.89 +-26.89, -15.00, 49.45, 50.55, -1.10 +-26.76, -15.00, 51.87, 48.13, 3.74 +-26.56, -15.00, 49.29, 50.71, -1.42 +-26.50, -15.00, 54.23, 45.77, 8.46 +-26.30, -15.00, 49.18, 50.82, -1.64 +-26.10, -15.00, 49.07, 50.93, -1.85 +-26.04, -15.00, 54.01, 45.99, 8.02 +-25.97, -15.00, 54.00, 46.00, 8.00 +-25.77, -15.00, 48.95, 51.05, -2.10 +-25.58, -15.00, 48.84, 51.16, -2.32 +-25.44, -15.00, 51.25, 48.75, 2.51 +-25.31, -15.00, 51.19, 48.81, 2.38 +-25.18, -15.00, 51.13, 48.87, 2.26 +-24.98, -15.00, 48.55, 51.45, -2.90 +-24.92, -15.00, 53.48, 46.52, 6.96 +-24.72, -15.00, 48.42, 51.58, -3.15 +-24.52, -15.00, 48.31, 51.69, -3.38 +-24.46, -15.00, 53.24, 46.76, 6.48 +-24.26, -15.00, 48.18, 51.82, -3.63 +-24.13, -15.00, 50.59, 49.41, 1.18 +-23.99, -15.00, 50.53, 49.47, 1.05 +-23.93, -15.00, 52.98, 47.02, 5.97 +-23.73, -15.00, 47.92, 52.08, -4.15 +-23.60, -15.00, 50.33, 49.67, 0.66 +-23.47, -15.00, 50.26, 49.74, 0.52 +-23.33, -15.00, 50.19, 49.81, 0.39 +-23.20, -15.00, 50.13, 49.87, 0.25 +-23.07, -15.00, 50.06, 49.94, 0.11 +-22.94, -15.00, 49.99, 50.01, -0.02 +-22.87, -15.00, 52.44, 47.56, 4.88 +-22.68, -15.00, 47.38, 52.62, -5.25 +-22.54, -15.00, 49.78, 50.22, -0.44 +-22.41, -15.00, 49.71, 50.29, -0.59 +-22.35, -15.00, 52.16, 47.84, 4.31 +-22.28, -15.00, 52.13, 47.87, 4.27 +-22.15, -15.00, 49.59, 50.41, -0.82 +-22.02, -15.00, 49.52, 50.48, -0.96 +-21.88, -15.00, 49.45, 50.55, -1.11 +-21.82, -15.00, 51.89, 48.11, 3.79 +-21.75, -15.00, 51.87, 48.13, 3.74 +-21.62, -15.00, 49.32, 50.68, -1.35 +-21.56, -15.00, 51.77, 48.23, 3.54 +-21.49, -15.00, 51.74, 48.26, 3.49 +-21.36, -15.00, 49.20, 50.80, -1.60 +-21.29, -15.00, 51.64, 48.36, 3.29 +-21.23, -15.00, 51.62, 48.38, 3.24 +-21.09, -15.00, 49.07, 50.93, -1.86 +-21.03, -15.00, 51.52, 48.48, 3.03 +-20.96, -15.00, 51.49, 48.51, 2.98 +-20.83, -15.00, 48.94, 51.06, -2.12 +-20.76, -15.00, 51.38, 48.62, 2.77 +-20.70, -15.00, 51.36, 48.64, 2.71 +-20.70, -15.00, 53.85, 46.15, 7.70 +-20.57, -15.00, 48.83, 51.17, -2.35 +-20.50, -15.00, 51.27, 48.73, 2.54 +-20.43, -15.00, 51.24, 48.76, 2.48 +-20.43, -15.00, 53.73, 46.27, 7.47 +-20.30, -15.00, 48.71, 51.29, -2.58 +-20.30, -15.00, 53.67, 46.33, 7.35 +-20.24, -15.00, 51.17, 48.83, 2.34 +-20.24, -15.00, 53.66, 46.34, 7.33 +-20.17, -15.00, 51.16, 48.84, 2.32 +-20.04, -15.00, 48.61, 51.39, -2.78 +-20.04, -15.00, 53.57, 46.43, 7.15 +-19.97, -15.00, 51.07, 48.93, 2.14 +-19.97, -15.00, 53.56, 46.44, 7.12 +-19.91, -15.00, 51.06, 48.94, 2.11 +-19.91, -15.00, 53.55, 46.45, 7.10 +-19.91, -15.00, 53.57, 46.43, 7.13 +-19.78, -15.00, 48.54, 51.46, -2.92 +-19.78, -15.00, 53.50, 46.50, 7.01 +-19.71, -15.00, 51.00, 49.00, 2.00 +-19.71, -15.00, 53.49, 46.51, 6.98 +-19.71, -15.00, 53.51, 46.49, 7.01 +-19.64, -15.00, 51.00, 49.00, 2.01 +-19.64, -15.00, 53.49, 46.51, 6.98 +-19.51, -15.00, 48.47, 51.53, -3.07 +-19.51, -15.00, 53.43, 46.57, 6.85 +-19.51, -15.00, 53.44, 46.56, 6.89 +-19.51, -15.00, 53.46, 46.54, 6.92 +-19.45, -15.00, 50.96, 49.04, 1.91 +-19.45, -15.00, 53.44, 46.56, 6.89 +-19.45, -15.00, 53.46, 46.54, 6.92 +-19.45, -15.00, 53.48, 46.52, 6.96 +-19.45, -15.00, 53.49, 46.51, 6.99 +-19.38, -15.00, 50.99, 49.01, 1.98 +-19.38, -15.00, 53.48, 46.52, 6.96 +-19.38, -15.00, 53.49, 46.51, 6.99 +-19.38, -15.00, 53.51, 46.49, 7.02 +-19.25, -15.00, 48.48, 51.52, -3.03 +-19.25, -15.00, 53.44, 46.56, 6.89 +-19.25, -15.00, 53.46, 46.54, 6.92 +-19.25, -15.00, 53.48, 46.52, 6.95 +-19.25, -15.00, 53.49, 46.51, 6.98 +-19.25, -15.00, 53.51, 46.49, 7.02 +-19.25, -15.00, 53.52, 46.48, 7.05 +-19.25, -15.00, 53.54, 46.46, 7.08 +-19.25, -15.00, 53.56, 46.44, 7.11 +-19.18, -15.00, 51.05, 48.95, 2.10 +-19.18, -15.00, 53.54, 46.46, 7.07 +-19.18, -15.00, 53.55, 46.45, 7.11 +-19.18, -15.00, 53.57, 46.43, 7.14 +-19.12, -15.00, 51.06, 48.94, 2.13 +-19.12, -15.00, 53.55, 46.45, 7.10 +-19.12, -15.00, 53.57, 46.43, 7.13 +-19.12, -15.00, 53.58, 46.42, 7.16 +-19.12, -15.00, 53.60, 46.40, 7.19 +-19.12, -15.00, 53.61, 46.39, 7.22 +-19.12, -15.00, 53.63, 46.37, 7.25 +-19.12, -15.00, 53.64, 46.36, 7.29 +-18.98, -15.00, 48.62, 51.38, -2.77 +-18.98, -15.00, 53.57, 46.43, 7.15 +-18.98, -15.00, 53.59, 46.41, 7.18 +-18.98, -15.00, 53.60, 46.40, 7.21 +-18.98, -15.00, 53.62, 46.38, 7.24 +-18.92, -15.00, 51.11, 48.89, 2.22 +-18.92, -15.00, 53.60, 46.40, 7.20 +-18.92, -15.00, 53.61, 46.39, 7.23 +-18.92, -15.00, 53.63, 46.37, 7.26 +-18.92, -15.00, 53.64, 46.36, 7.29 +-18.92, -15.00, 53.66, 46.34, 7.31 +-18.92, -15.00, 53.67, 46.33, 7.34 +-18.92, -15.00, 53.69, 46.31, 7.37 +-18.92, -15.00, 53.70, 46.30, 7.40 +-18.85, -15.00, 51.19, 48.81, 2.39 +-18.85, -15.00, 53.68, 46.32, 7.36 +-18.85, -15.00, 53.70, 46.30, 7.39 +-18.85, -15.00, 53.71, 46.29, 7.42 +-18.85, -15.00, 53.72, 46.28, 7.45 +-18.85, -15.00, 53.74, 46.26, 7.48 +-18.85, -15.00, 53.75, 46.25, 7.51 +-18.85, -15.00, 53.77, 46.23, 7.54 +-18.85, -15.00, 53.78, 46.22, 7.56 +-18.85, -15.00, 53.80, 46.20, 7.59 +-18.85, -15.00, 53.81, 46.19, 7.62 +-18.72, -15.00, 48.78, 51.22, -2.44 +-18.72, -15.00, 53.74, 46.26, 7.48 +-18.72, -15.00, 53.75, 46.25, 7.51 +-18.72, -15.00, 53.77, 46.23, 7.54 +-18.72, -15.00, 53.78, 46.22, 7.56 +-18.72, -15.00, 53.80, 46.20, 7.59 +-18.72, -15.00, 53.81, 46.19, 7.62 +-18.72, -15.00, 53.82, 46.18, 7.65 +-18.72, -15.00, 53.84, 46.16, 7.68 +-18.65, -15.00, 51.33, 48.67, 2.66 +-18.65, -15.00, 53.82, 46.18, 7.63 +-18.65, -15.00, 53.83, 46.17, 7.66 +-18.59, -15.00, 51.32, 48.68, 2.64 +-18.59, -15.00, 53.81, 46.19, 7.61 +-18.59, -15.00, 53.82, 46.18, 7.64 +-18.59, -15.00, 53.83, 46.17, 7.67 +-18.65, -15.00, 56.37, 43.63, 12.74 +-18.59, -15.00, 51.39, 48.61, 2.78 +-18.59, -15.00, 53.87, 46.13, 7.75 +-18.59, -15.00, 53.89, 46.11, 7.78 +-18.59, -15.00, 53.90, 46.10, 7.80 +-18.59, -15.00, 53.91, 46.09, 7.83 +-18.59, -15.00, 53.93, 46.07, 7.86 +-18.59, -15.00, 53.94, 46.06, 7.88 +-18.59, -15.00, 53.96, 46.04, 7.91 +-18.59, -15.00, 53.97, 46.03, 7.94 +-18.59, -15.00, 53.98, 46.02, 7.96 +-18.59, -15.00, 54.00, 46.00, 7.99 +-18.59, -15.00, 54.01, 45.99, 8.02 +-18.46, -15.00, 48.98, 51.02, -2.04 +-18.46, -15.00, 53.94, 46.06, 7.87 +-18.46, -15.00, 53.95, 46.05, 7.90 +-18.46, -15.00, 53.96, 46.04, 7.92 +-18.46, -15.00, 53.97, 46.03, 7.95 +-18.46, -15.00, 53.99, 46.01, 7.98 +-18.39, -15.00, 51.48, 48.52, 2.96 +-18.39, -15.00, 53.96, 46.04, 7.93 +-18.39, -15.00, 53.98, 46.02, 7.95 +-18.39, -15.00, 53.99, 46.01, 7.98 +-18.39, -15.00, 54.00, 46.00, 8.00 +-18.39, -15.00, 54.01, 45.99, 8.03 +-18.39, -15.00, 54.03, 45.97, 8.05 +-18.39, -15.00, 54.04, 45.96, 8.08 +-18.33, -15.00, 51.53, 48.47, 3.06 +-18.39, -15.00, 56.54, 43.46, 13.07 +-18.39, -15.00, 54.08, 45.92, 8.16 +-18.39, -15.00, 54.09, 45.91, 8.18 +-18.39, -15.00, 54.10, 45.90, 8.21 +-18.33, -15.00, 51.59, 48.41, 3.19 +-18.33, -15.00, 54.08, 45.92, 8.16 +-18.33, -15.00, 54.09, 45.91, 8.18 +-18.33, -15.00, 54.10, 45.90, 8.21 +-18.33, -15.00, 54.12, 45.88, 8.23 +-18.33, -15.00, 54.13, 45.87, 8.26 +-18.33, -15.00, 54.14, 45.86, 8.28 +-18.33, -15.00, 54.15, 45.85, 8.31 +-18.33, -15.00, 54.17, 45.83, 8.33 +-18.33, -15.00, 54.18, 45.82, 8.36 +-18.33, -15.00, 54.19, 45.81, 8.38 +-18.33, -15.00, 54.20, 45.80, 8.41 +-18.19, -15.00, 49.17, 50.83, -1.65 +-18.33, -15.00, 59.17, 40.83, 18.34 +-18.19, -15.00, 49.20, 50.80, -1.61 +-18.33, -15.00, 59.20, 40.80, 18.39 +-18.33, -15.00, 54.27, 45.73, 8.53 +-18.19, -15.00, 49.23, 50.77, -1.53 +-18.19, -15.00, 54.19, 45.81, 8.38 +-18.19, -15.00, 54.20, 45.80, 8.40 +-18.19, -15.00, 54.21, 45.79, 8.43 +-18.19, -15.00, 54.23, 45.77, 8.45 +-18.19, -15.00, 54.24, 45.76, 8.48 +-18.19, -15.00, 54.25, 45.75, 8.50 +-18.19, -15.00, 54.26, 45.74, 8.52 +-18.19, -15.00, 54.27, 45.73, 8.55 +-18.13, -15.00, 51.76, 48.24, 3.53 +-18.13, -15.00, 54.25, 45.75, 8.50 +-18.13, -15.00, 54.26, 45.74, 8.52 +-18.13, -15.00, 54.27, 45.73, 8.54 +-18.13, -15.00, 54.28, 45.72, 8.57 +-18.13, -15.00, 54.29, 45.71, 8.59 +-18.13, -15.00, 54.31, 45.69, 8.61 +-18.06, -15.00, 51.80, 48.20, 3.59 +-18.06, -15.00, 54.28, 45.72, 8.56 +-18.06, -15.00, 54.29, 45.71, 8.58 +-17.93, -15.00, 49.26, 50.74, -1.48 +-17.93, -15.00, 54.21, 45.79, 8.43 +-17.93, -15.00, 54.23, 45.77, 8.45 +-17.93, -15.00, 54.24, 45.76, 8.47 +-17.93, -15.00, 54.25, 45.75, 8.50 +-17.93, -15.00, 54.26, 45.74, 8.52 +-17.93, -15.00, 54.27, 45.73, 8.54 +-17.86, -15.00, 51.76, 48.24, 3.52 +-17.86, -15.00, 54.24, 45.76, 8.48 +-17.80, -15.00, 51.73, 48.27, 3.46 +-17.80, -15.00, 54.21, 45.79, 8.43 +-17.80, -15.00, 54.22, 45.78, 8.45 +-17.80, -15.00, 54.23, 45.77, 8.47 +-17.67, -15.00, 49.20, 50.80, -1.60 +-17.67, -15.00, 54.16, 45.84, 8.31 +-17.67, -15.00, 54.17, 45.83, 8.33 +-17.60, -15.00, 51.65, 48.35, 3.31 +-17.60, -15.00, 54.14, 45.86, 8.27 +-17.53, -15.00, 51.62, 48.38, 3.25 +-17.40, -15.00, 49.06, 50.94, -1.88 +-17.40, -15.00, 54.01, 45.99, 8.03 +-17.40, -15.00, 54.02, 45.98, 8.05 +-17.40, -15.00, 54.03, 45.97, 8.07 +-17.34, -15.00, 51.52, 48.48, 3.04 +-17.34, -15.00, 54.00, 46.00, 8.00 +-17.27, -15.00, 51.49, 48.51, 2.98 +-17.27, -15.00, 53.97, 46.03, 7.94 +-17.14, -15.00, 48.93, 51.07, -2.13 +-17.14, -15.00, 53.89, 46.11, 7.77 +-17.07, -15.00, 51.37, 48.63, 2.74 +-17.07, -15.00, 53.85, 46.15, 7.70 +-17.01, -15.00, 51.34, 48.66, 2.68 +-17.01, -15.00, 53.82, 46.18, 7.63 +-16.87, -15.00, 48.78, 51.22, -2.44 +-16.87, -15.00, 53.73, 46.27, 7.46 +-16.87, -15.00, 53.74, 46.26, 7.48 +-16.81, -15.00, 51.22, 48.78, 2.45 +-16.81, -15.00, 53.70, 46.30, 7.41 +-16.74, -15.00, 51.19, 48.81, 2.38 +-16.61, -15.00, 48.62, 51.38, -2.75 +-16.61, -15.00, 53.57, 46.43, 7.15 +-16.61, -15.00, 53.58, 46.42, 7.16 +-16.55, -15.00, 51.06, 48.94, 2.13 +-16.48, -15.00, 51.02, 48.98, 2.04 +-16.48, -15.00, 53.50, 46.50, 7.00 +-16.48, -15.00, 53.50, 46.50, 7.01 +-16.35, -15.00, 48.47, 51.53, -3.07 +-16.28, -15.00, 50.89, 49.11, 1.79 +-16.28, -15.00, 53.37, 46.63, 6.74 +-16.28, -15.00, 53.37, 46.63, 6.75 +-16.22, -15.00, 50.86, 49.14, 1.72 +-16.22, -15.00, 53.33, 46.67, 6.67 +-16.08, -15.00, 48.30, 51.70, -3.41 +-16.08, -15.00, 53.24, 46.76, 6.49 +-16.08, -15.00, 53.25, 46.75, 6.50 +-16.02, -15.00, 50.73, 49.27, 1.46 +-16.02, -15.00, 53.21, 46.79, 6.41 +-15.95, -15.00, 50.69, 49.31, 1.38 +-15.95, -15.00, 53.16, 46.84, 6.33 +-15.82, -15.00, 48.12, 51.88, -3.75 +-15.82, -15.00, 53.07, 46.93, 6.14 +-15.82, -15.00, 53.07, 46.93, 6.15 +-15.75, -15.00, 50.56, 49.44, 1.11 +-15.75, -15.00, 53.03, 46.97, 6.06 +-15.75, -15.00, 53.03, 46.97, 6.07 +-15.69, -15.00, 50.51, 49.49, 1.03 +-15.69, -15.00, 52.99, 47.01, 5.98 +-15.69, -15.00, 52.99, 47.01, 5.98 +-15.56, -15.00, 47.95, 52.05, -4.10 +-15.56, -15.00, 52.90, 47.10, 5.79 +-15.56, -15.00, 52.90, 47.10, 5.80 +-15.56, -15.00, 52.90, 47.10, 5.80 +-15.49, -15.00, 50.38, 49.62, 0.76 +-15.49, -15.00, 52.85, 47.15, 5.71 +-15.49, -15.00, 52.86, 47.14, 5.71 +-15.49, -15.00, 52.86, 47.14, 5.72 +-15.42, -15.00, 50.34, 49.66, 0.68 +-15.42, -15.00, 52.81, 47.19, 5.62 +-15.42, -15.00, 52.81, 47.19, 5.63 +-15.42, -15.00, 52.82, 47.18, 5.63 +-15.42, -15.00, 52.82, 47.18, 5.63 +-15.42, -15.00, 52.82, 47.18, 5.64 +-15.29, -15.00, 47.78, 52.22, -4.45 +-15.29, -15.00, 52.72, 47.28, 5.44 +-15.29, -15.00, 52.72, 47.28, 5.45 +-15.29, -15.00, 52.72, 47.28, 5.45 +-15.29, -15.00, 52.73, 47.27, 5.45 +-15.23, -15.00, 50.20, 49.80, 0.41 +-15.23, -15.00, 52.68, 47.32, 5.36 +-15.23, -15.00, 52.68, 47.32, 5.36 +-15.23, -15.00, 52.68, 47.32, 5.36 +-15.23, -15.00, 52.68, 47.32, 5.36 +-15.16, -15.00, 50.16, 49.84, 0.32 +-15.16, -15.00, 52.63, 47.37, 5.26 +-15.16, -15.00, 52.63, 47.37, 5.26 +-15.16, -15.00, 52.63, 47.37, 5.27 +-15.16, -15.00, 52.63, 47.37, 5.27 +-15.16, -15.00, 52.63, 47.37, 5.27 +-15.16, -15.00, 52.63, 47.37, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.03, -15.00, 47.60, 52.40, -4.81 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.09 +-15.03, -15.00, 52.54, 47.46, 5.09 +-15.16, -15.00, 57.59, 42.41, 15.17 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.23, -15.00, 55.17, 44.83, 10.35 +-15.16, -15.00, 50.18, 49.82, 0.36 +-15.23, -15.00, 55.17, 44.83, 10.35 +-15.23, -15.00, 52.70, 47.30, 5.41 +-15.23, -15.00, 52.70, 47.30, 5.41 +-15.23, -15.00, 52.70, 47.30, 5.41 +-15.23, -15.00, 52.71, 47.29, 5.41 +-15.23, -15.00, 52.71, 47.29, 5.41 +-15.23, -15.00, 52.71, 47.29, 5.41 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.43 +-15.23, -15.00, 52.71, 47.29, 5.43 +-15.23, -15.00, 52.71, 47.29, 5.43 +-15.23, -15.00, 52.72, 47.28, 5.43 +-15.23, -15.00, 52.72, 47.28, 5.43 +-15.23, -15.00, 52.72, 47.28, 5.43 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.29, -15.00, 55.24, 44.76, 10.49 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.78, 47.22, 5.55 +-15.29, -15.00, 52.78, 47.22, 5.55 +-15.23, -15.00, 50.26, 49.74, 0.51 +-15.23, -15.00, 52.73, 47.27, 5.46 +-15.23, -15.00, 52.73, 47.27, 5.46 +-15.23, -15.00, 52.73, 47.27, 5.46 +-15.23, -15.00, 52.73, 47.27, 5.46 +-15.23, -15.00, 52.73, 47.27, 5.47 +-15.23, -15.00, 52.73, 47.27, 5.47 +-15.23, -15.00, 52.73, 47.27, 5.47 +-15.23, -15.00, 52.74, 47.26, 5.47 +-15.23, -15.00, 52.74, 47.26, 5.47 +-15.23, -15.00, 52.74, 47.26, 5.47 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.16, -15.00, 50.22, 49.78, 0.44 +-15.16, -15.00, 52.69, 47.31, 5.38 +-15.16, -15.00, 52.69, 47.31, 5.39 +-15.16, -15.00, 52.69, 47.31, 5.39 +-15.16, -15.00, 52.69, 47.31, 5.39 +-15.16, -15.00, 52.69, 47.31, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.03, -15.00, 47.66, 52.34, -4.69 +-15.03, -15.00, 52.60, 47.40, 5.20 +-15.03, -15.00, 52.60, 47.40, 5.20 +-15.03, -15.00, 52.60, 47.40, 5.20 +-14.96, -15.00, 50.08, 49.92, 0.16 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.90, -15.00, 50.03, 49.97, 0.05 +-14.96, -15.00, 55.02, 44.98, 10.04 +-14.90, -15.00, 50.03, 49.97, 0.05 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.77, -15.00, 47.45, 52.55, -5.10 +-14.77, -15.00, 52.40, 47.60, 4.79 +-14.77, -15.00, 52.39, 47.61, 4.79 +-14.77, -15.00, 52.39, 47.61, 4.79 +-14.77, -15.00, 52.39, 47.61, 4.79 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.77 +-14.77, -15.00, 52.39, 47.61, 4.77 +-14.70, -15.00, 49.86, 50.14, -0.27 +-14.77, -15.00, 54.86, 45.14, 9.71 +-14.77, -15.00, 52.38, 47.62, 4.77 +-14.70, -15.00, 49.86, 50.14, -0.28 +-14.70, -15.00, 52.33, 47.67, 4.66 +-14.70, -15.00, 52.33, 47.67, 4.66 +-14.70, -15.00, 52.33, 47.67, 4.66 +-14.70, -15.00, 52.33, 47.67, 4.66 +-14.70, -15.00, 52.33, 47.67, 4.65 +-14.70, -15.00, 52.33, 47.67, 4.65 +-14.70, -15.00, 52.33, 47.67, 4.65 +-14.70, -15.00, 52.32, 47.68, 4.65 +-14.70, -15.00, 52.32, 47.68, 4.65 +-14.70, -15.00, 52.32, 47.68, 4.64 +-14.70, -15.00, 52.32, 47.68, 4.64 +-14.77, -15.00, 54.84, 45.16, 9.68 +-14.77, -15.00, 52.37, 47.63, 4.74 +-14.77, -15.00, 52.37, 47.63, 4.73 +-14.77, -15.00, 52.37, 47.63, 4.73 +-14.77, -15.00, 52.37, 47.63, 4.73 +-14.70, -15.00, 49.84, 50.16, -0.31 +-14.77, -15.00, 54.84, 45.16, 9.67 +-14.77, -15.00, 52.36, 47.64, 4.73 +-14.70, -15.00, 49.84, 50.16, -0.32 +-14.77, -15.00, 54.83, 45.17, 9.67 +-14.77, -15.00, 52.36, 47.64, 4.72 +-14.77, -15.00, 52.36, 47.64, 4.72 +-14.77, -15.00, 52.36, 47.64, 4.72 +-14.77, -15.00, 52.36, 47.64, 4.71 +-14.77, -15.00, 52.36, 47.64, 4.71 +-14.77, -15.00, 52.36, 47.64, 4.71 +-14.77, -15.00, 52.35, 47.65, 4.71 +-14.77, -15.00, 52.35, 47.65, 4.71 +-14.77, -15.00, 52.35, 47.65, 4.71 +-14.90, -15.00, 57.40, 42.60, 14.79 +-14.77, -15.00, 47.41, 52.59, -5.18 +-14.77, -15.00, 52.35, 47.65, 4.70 +-14.90, -15.00, 57.39, 42.61, 14.79 +-14.90, -15.00, 52.45, 47.55, 4.90 +-14.90, -15.00, 52.45, 47.55, 4.90 +-14.90, -15.00, 52.45, 47.55, 4.90 +-14.90, -15.00, 52.45, 47.55, 4.90 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.44, 47.56, 4.89 +-14.90, -15.00, 52.44, 47.56, 4.89 +-14.90, -15.00, 52.44, 47.56, 4.89 +-14.90, -15.00, 52.44, 47.56, 4.89 +-14.96, -15.00, 54.96, 45.04, 9.93 +-14.96, -15.00, 52.49, 47.51, 4.99 +-14.96, -15.00, 52.49, 47.51, 4.99 +-14.96, -15.00, 52.49, 47.51, 4.99 +-14.96, -15.00, 52.49, 47.51, 4.99 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-15.03, -15.00, 55.01, 44.99, 10.03 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.16, -15.00, 57.59, 42.42, 15.17 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.23, -15.00, 55.17, 44.83, 10.33 +-15.23, -15.00, 52.69, 47.31, 5.39 +-15.23, -15.00, 52.70, 47.30, 5.39 +-15.23, -15.00, 52.70, 47.30, 5.39 +-15.23, -15.00, 52.70, 47.30, 5.39 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.29, -15.00, 55.22, 44.78, 10.45 +-15.29, -15.00, 52.75, 47.25, 5.51 +-15.29, -15.00, 52.75, 47.25, 5.51 +-15.29, -15.00, 52.76, 47.24, 5.51 +-15.29, -15.00, 52.76, 47.24, 5.51 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.53 +-15.29, -15.00, 52.76, 47.24, 5.53 +-15.29, -15.00, 52.77, 47.23, 5.53 +-15.29, -15.00, 52.77, 47.23, 5.53 +-15.29, -15.00, 52.77, 47.23, 5.53 +-15.29, -15.00, 52.77, 47.23, 5.54 +-15.29, -15.00, 52.77, 47.23, 5.54 +-15.29, -15.00, 52.77, 47.23, 5.54 +-15.29, -15.00, 52.77, 47.23, 5.54 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.78, 47.22, 5.55 +-15.42, -15.00, 57.82, 42.18, 15.64 +-15.29, -15.00, 47.83, 52.17, -4.33 +-15.29, -15.00, 52.78, 47.22, 5.56 +-15.29, -15.00, 52.78, 47.22, 5.56 +-15.29, -15.00, 52.78, 47.22, 5.56 +-15.29, -15.00, 52.78, 47.22, 5.56 +-15.29, -15.00, 52.78, 47.22, 5.57 +-15.29, -15.00, 52.78, 47.22, 5.57 +-15.29, -15.00, 52.79, 47.21, 5.57 +-15.29, -15.00, 52.79, 47.21, 5.57 +-15.29, -15.00, 52.79, 47.21, 5.58 +-15.29, -15.00, 52.79, 47.21, 5.58 +-15.23, -15.00, 50.27, 49.73, 0.54 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.49 +-15.23, -15.00, 52.74, 47.26, 5.49 +-15.23, -15.00, 52.74, 47.26, 5.49 +-15.23, -15.00, 52.75, 47.25, 5.49 +-15.23, -15.00, 52.75, 47.25, 5.49 +-15.16, -15.00, 50.23, 49.77, 0.45 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.03, -15.00, 47.66, 52.34, -4.68 +-15.03, -15.00, 52.60, 47.40, 5.21 +-15.03, -15.00, 52.60, 47.40, 5.21 +-14.96, -15.00, 50.08, 49.92, 0.16 +-14.96, -15.00, 52.55, 47.45, 5.11 +-14.96, -15.00, 52.55, 47.45, 5.11 +-14.96, -15.00, 52.55, 47.45, 5.11 +-14.96, -15.00, 52.55, 47.45, 5.11 +-14.90, -15.00, 50.03, 49.97, 0.06 +-14.90, -15.00, 52.50, 47.50, 5.01 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.77, -15.00, 47.46, 52.54, -5.09 +-14.77, -15.00, 52.40, 47.60, 4.80 +-14.77, -15.00, 52.40, 47.60, 4.80 +-14.70, -15.00, 49.88, 50.12, -0.25 +-14.70, -15.00, 52.35, 47.65, 4.70 +-14.70, -15.00, 52.35, 47.65, 4.69 +-14.70, -15.00, 52.35, 47.65, 4.69 +-14.70, -15.00, 52.34, 47.66, 4.69 +-14.70, -15.00, 52.34, 47.66, 4.69 +-14.63, -15.00, 49.82, 50.18, -0.36 +-14.63, -15.00, 52.29, 47.71, 4.58 +-14.63, -15.00, 52.29, 47.71, 4.58 +-14.63, -15.00, 52.29, 47.71, 4.58 +-14.63, -15.00, 52.29, 47.71, 4.57 +-14.63, -15.00, 52.29, 47.71, 4.57 +-14.50, -15.00, 47.24, 52.76, -5.52 +-14.50, -15.00, 52.18, 47.82, 4.37 +-14.50, -15.00, 52.18, 47.82, 4.36 +-14.50, -15.00, 52.18, 47.82, 4.36 +-14.50, -15.00, 52.18, 47.82, 4.35 +-14.44, -15.00, 49.65, 50.35, -0.69 +-14.44, -15.00, 52.12, 47.88, 4.25 +-14.44, -15.00, 52.12, 47.88, 4.24 +-14.44, -15.00, 52.12, 47.88, 4.24 +-14.44, -15.00, 52.12, 47.88, 4.23 +-14.44, -15.00, 52.12, 47.88, 4.23 +-14.44, -15.00, 52.11, 47.89, 4.23 +-14.44, -15.00, 52.11, 47.89, 4.22 +-14.44, -15.00, 52.11, 47.89, 4.22 +-14.44, -15.00, 52.11, 47.89, 4.21 +-14.44, -15.00, 52.10, 47.90, 4.21 +-14.44, -15.00, 52.10, 47.90, 4.20 +-14.44, -15.00, 52.10, 47.90, 4.20 +-14.44, -15.00, 52.10, 47.90, 4.20 +-14.44, -15.00, 52.10, 47.90, 4.19 +-14.37, -15.00, 49.57, 50.43, -0.86 +-14.37, -15.00, 52.04, 47.96, 4.08 +-14.37, -15.00, 52.04, 47.96, 4.08 +-14.37, -15.00, 52.04, 47.96, 4.07 +-14.37, -15.00, 52.03, 47.97, 4.07 +-14.37, -15.00, 52.03, 47.97, 4.06 +-14.37, -15.00, 52.03, 47.97, 4.06 +-14.37, -15.00, 52.03, 47.97, 4.06 +-14.37, -15.00, 52.03, 47.97, 4.05 +-14.37, -15.00, 52.02, 47.98, 4.05 +-14.37, -15.00, 52.02, 47.98, 4.04 +-14.37, -15.00, 52.02, 47.98, 4.04 +-14.37, -15.00, 52.02, 47.98, 4.03 +-14.37, -15.00, 52.01, 47.99, 4.03 +-14.37, -15.00, 52.01, 47.99, 4.02 +-14.37, -15.00, 52.01, 47.99, 4.02 +-14.37, -15.00, 52.01, 47.99, 4.01 +-14.37, -15.00, 52.00, 48.00, 4.01 +-14.37, -15.00, 52.00, 48.00, 4.00 +-14.37, -15.00, 52.00, 48.00, 4.00 +-14.24, -15.00, 46.95, 53.05, -6.09 +-14.24, -15.00, 51.89, 48.11, 3.79 +-14.24, -15.00, 51.89, 48.11, 3.78 +-14.24, -15.00, 51.89, 48.11, 3.78 +-14.24, -15.00, 51.89, 48.11, 3.77 +-14.24, -15.00, 51.88, 48.12, 3.77 +-14.24, -15.00, 51.88, 48.12, 3.76 +-14.24, -15.00, 51.88, 48.12, 3.76 +-14.24, -15.00, 51.87, 48.13, 3.75 +-14.24, -15.00, 51.87, 48.13, 3.74 +-14.24, -15.00, 51.87, 48.13, 3.74 +-14.24, -15.00, 51.87, 48.13, 3.73 +-14.24, -15.00, 51.86, 48.14, 3.73 +-14.24, -15.00, 51.86, 48.14, 3.72 +-14.24, -15.00, 51.86, 48.14, 3.72 +-14.24, -15.00, 51.85, 48.15, 3.71 +-14.24, -15.00, 51.85, 48.15, 3.70 +-14.24, -15.00, 51.85, 48.15, 3.70 +-14.24, -15.00, 51.85, 48.15, 3.69 +-14.24, -15.00, 51.84, 48.16, 3.69 +-14.24, -15.00, 51.84, 48.16, 3.68 +-14.24, -15.00, 51.84, 48.16, 3.68 +-14.24, -15.00, 51.83, 48.17, 3.67 +-14.24, -15.00, 51.83, 48.17, 3.66 +-14.24, -15.00, 51.83, 48.17, 3.66 +-14.24, -15.00, 51.83, 48.17, 3.65 +-14.24, -15.00, 51.82, 48.18, 3.65 +-14.24, -15.00, 51.82, 48.18, 3.64 +-14.24, -15.00, 51.82, 48.18, 3.64 +-14.24, -15.00, 51.81, 48.19, 3.63 +-14.24, -15.00, 51.81, 48.19, 3.62 +-14.24, -15.00, 51.81, 48.19, 3.62 +-14.24, -15.00, 51.81, 48.19, 3.61 +-14.24, -15.00, 51.80, 48.20, 3.61 +-14.24, -15.00, 51.80, 48.20, 3.60 +-14.24, -15.00, 51.80, 48.20, 3.60 +-14.24, -15.00, 51.79, 48.21, 3.59 +-14.37, -15.00, 56.84, 43.16, 13.67 +-14.37, -15.00, 51.89, 48.11, 3.78 +-14.37, -15.00, 51.89, 48.11, 3.77 +-14.37, -15.00, 51.88, 48.12, 3.77 +-14.37, -15.00, 51.88, 48.12, 3.76 +-14.37, -15.00, 51.88, 48.12, 3.76 +-14.37, -15.00, 51.88, 48.12, 3.75 +-14.37, -15.00, 51.87, 48.13, 3.75 +-14.37, -15.00, 51.87, 48.13, 3.74 +-14.44, -15.00, 54.39, 45.61, 8.78 +-14.44, -15.00, 51.92, 48.08, 3.84 +-14.44, -15.00, 51.92, 48.08, 3.83 +-14.44, -15.00, 51.91, 48.09, 3.83 +-14.44, -15.00, 51.91, 48.09, 3.82 +-14.50, -15.00, 54.43, 45.57, 8.86 +-14.50, -15.00, 51.96, 48.04, 3.91 +-14.50, -15.00, 51.96, 48.04, 3.91 +-14.50, -15.00, 51.95, 48.05, 3.91 +-14.50, -15.00, 51.95, 48.05, 3.90 +-14.50, -15.00, 51.95, 48.05, 3.90 +-14.50, -15.00, 51.95, 48.05, 3.90 +-14.63, -15.00, 56.99, 43.01, 13.98 +-14.63, -15.00, 52.04, 47.96, 4.09 +-14.63, -15.00, 52.04, 47.96, 4.08 +-14.70, -15.00, 54.56, 45.44, 9.13 +-14.70, -15.00, 52.09, 47.91, 4.18 +-14.70, -15.00, 52.09, 47.91, 4.18 +-14.70, -15.00, 52.09, 47.91, 4.17 +-14.77, -15.00, 54.61, 45.39, 9.22 +-14.77, -15.00, 52.13, 47.87, 4.27 +-14.77, -15.00, 52.13, 47.87, 4.27 +-14.77, -15.00, 52.13, 47.87, 4.27 +-14.77, -15.00, 52.13, 47.87, 4.26 +-14.77, -15.00, 52.13, 47.87, 4.26 +-14.90, -15.00, 57.17, 42.83, 14.35 +-14.90, -15.00, 52.23, 47.77, 4.46 +-14.90, -15.00, 52.23, 47.77, 4.46 +-14.90, -15.00, 52.23, 47.77, 4.46 +-14.90, -15.00, 52.23, 47.77, 4.46 +-14.96, -15.00, 54.75, 45.25, 9.50 +-14.96, -15.00, 52.28, 47.72, 4.56 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-15.03, -15.00, 54.80, 45.20, 9.60 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-14.96, -15.00, 49.81, 50.19, -0.39 +-15.03, -15.00, 54.80, 45.20, 9.60 +-15.03, -15.00, 52.33, 47.67, 4.65 +-14.96, -15.00, 49.81, 50.19, -0.39 +-15.03, -15.00, 54.80, 45.20, 9.60 +-14.96, -15.00, 49.81, 50.19, -0.39 +-14.96, -15.00, 52.28, 47.72, 4.56 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.90, -15.00, 49.75, 50.25, -0.49 +-14.90, -15.00, 52.23, 47.77, 4.45 +-14.90, -15.00, 52.23, 47.77, 4.45 +-14.90, -15.00, 52.23, 47.77, 4.45 +-14.90, -15.00, 52.23, 47.77, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.77, -15.00, 47.18, 52.82, -5.64 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.70, -15.00, 49.60, 50.40, -0.81 +-14.70, -15.00, 52.07, 47.93, 4.13 +-14.70, -15.00, 52.07, 47.93, 4.13 +-14.70, -15.00, 52.06, 47.94, 4.13 +-14.70, -15.00, 52.06, 47.94, 4.13 +-14.70, -15.00, 52.06, 47.94, 4.12 +-14.63, -15.00, 49.54, 50.46, -0.92 +-14.70, -15.00, 54.53, 45.47, 9.06 +-14.63, -15.00, 49.54, 50.46, -0.93 +-14.63, -15.00, 52.01, 47.99, 4.02 +-14.63, -15.00, 52.01, 47.99, 4.01 +-14.63, -15.00, 52.00, 48.00, 4.01 +-14.63, -15.00, 52.00, 48.00, 4.01 +-14.63, -15.00, 52.00, 48.00, 4.00 +-14.50, -15.00, 46.96, 53.04, -6.09 +-14.50, -15.00, 51.90, 48.10, 3.80 +-14.50, -15.00, 51.90, 48.10, 3.80 +-14.50, -15.00, 51.90, 48.10, 3.79 +-14.50, -15.00, 51.89, 48.11, 3.79 +-14.50, -15.00, 51.89, 48.11, 3.78 +-14.50, -15.00, 51.89, 48.11, 3.78 +-14.50, -15.00, 51.89, 48.11, 3.78 +-14.50, -15.00, 51.89, 48.11, 3.77 +-14.50, -15.00, 51.88, 48.12, 3.77 +-14.50, -15.00, 51.88, 48.12, 3.77 +-14.50, -15.00, 51.88, 48.12, 3.76 +-14.50, -15.00, 51.88, 48.12, 3.76 +-14.44, -15.00, 49.36, 50.64, -1.29 +-14.50, -15.00, 54.35, 45.65, 8.69 +-14.50, -15.00, 51.87, 48.13, 3.75 +-14.50, -15.00, 51.87, 48.13, 3.74 +-14.44, -15.00, 49.35, 50.65, -1.30 +-14.50, -15.00, 54.34, 45.66, 8.68 +-14.44, -15.00, 49.34, 50.66, -1.31 +-14.44, -15.00, 51.81, 48.19, 3.63 +-14.44, -15.00, 51.81, 48.19, 3.62 +-14.44, -15.00, 51.81, 48.19, 3.62 +-14.44, -15.00, 51.81, 48.19, 3.61 +-14.44, -15.00, 51.81, 48.19, 3.61 +-14.44, -15.00, 51.80, 48.20, 3.61 +-14.44, -15.00, 51.80, 48.20, 3.60 +-14.44, -15.00, 51.80, 48.20, 3.60 +-14.44, -15.00, 51.80, 48.20, 3.59 +-14.44, -15.00, 51.79, 48.21, 3.59 +-14.44, -15.00, 51.79, 48.21, 3.58 +-14.44, -15.00, 51.79, 48.21, 3.58 +-14.44, -15.00, 51.79, 48.21, 3.58 +-14.44, -15.00, 51.79, 48.21, 3.57 +-14.44, -15.00, 51.78, 48.22, 3.57 +-14.44, -15.00, 51.78, 48.22, 3.56 +-14.44, -15.00, 51.78, 48.22, 3.56 +-14.44, -15.00, 51.78, 48.22, 3.56 +-14.44, -15.00, 51.78, 48.22, 3.55 +-14.44, -15.00, 51.77, 48.23, 3.55 +-14.44, -15.00, 51.77, 48.23, 3.54 +-14.44, -15.00, 51.77, 48.23, 3.54 +-14.44, -15.00, 51.77, 48.23, 3.53 +-14.44, -15.00, 51.76, 48.24, 3.53 +-14.44, -15.00, 51.76, 48.24, 3.53 +-14.44, -15.00, 51.76, 48.24, 3.52 +-14.44, -15.00, 51.76, 48.24, 3.52 +-14.44, -15.00, 51.76, 48.24, 3.51 +-14.44, -15.00, 51.75, 48.25, 3.51 +-14.44, -15.00, 51.75, 48.25, 3.50 +-14.44, -15.00, 51.75, 48.25, 3.50 +-14.44, -15.00, 51.75, 48.25, 3.50 +-14.44, -15.00, 51.75, 48.25, 3.49 +-14.44, -15.00, 51.74, 48.26, 3.49 +-14.44, -15.00, 51.74, 48.26, 3.48 +-14.44, -15.00, 51.74, 48.26, 3.48 +-14.44, -15.00, 51.74, 48.26, 3.47 +-14.44, -15.00, 51.74, 48.26, 3.47 +-14.44, -15.00, 51.73, 48.27, 3.47 +-14.44, -15.00, 51.73, 48.27, 3.46 +-14.44, -15.00, 51.73, 48.27, 3.46 +-14.44, -15.00, 51.73, 48.27, 3.45 +-14.44, -15.00, 51.72, 48.28, 3.45 +-14.44, -15.00, 51.72, 48.28, 3.45 +-14.44, -15.00, 51.72, 48.28, 3.44 +-14.50, -15.00, 54.24, 45.76, 8.48 +-14.50, -15.00, 51.77, 48.23, 3.53 +-14.50, -15.00, 51.76, 48.24, 3.53 +-14.50, -15.00, 51.76, 48.24, 3.52 +-14.50, -15.00, 51.76, 48.24, 3.52 +-14.50, -15.00, 51.76, 48.24, 3.52 +-14.50, -15.00, 51.76, 48.24, 3.51 +-14.50, -15.00, 51.75, 48.25, 3.51 +-14.50, -15.00, 51.75, 48.25, 3.51 +-14.63, -15.00, 56.79, 43.21, 13.59 +-14.63, -15.00, 51.85, 48.15, 3.70 +-14.63, -15.00, 51.85, 48.15, 3.70 +-14.63, -15.00, 51.85, 48.15, 3.69 +-14.63, -15.00, 51.85, 48.15, 3.69 +-14.70, -15.00, 54.37, 45.63, 8.73 +-14.70, -15.00, 51.89, 48.11, 3.78 +-14.70, -15.00, 51.89, 48.11, 3.78 +-14.70, -15.00, 51.89, 48.11, 3.78 +-14.77, -15.00, 54.41, 45.59, 8.82 +-14.77, -15.00, 51.94, 48.06, 3.88 +-14.77, -15.00, 51.94, 48.06, 3.87 +-14.77, -15.00, 51.94, 48.06, 3.87 +-14.77, -15.00, 51.94, 48.06, 3.87 +-14.77, -15.00, 51.93, 48.07, 3.87 +-14.90, -15.00, 56.98, 43.02, 13.95 +-14.90, -15.00, 52.03, 47.97, 4.06 +-14.90, -15.00, 52.03, 47.97, 4.06 +-14.90, -15.00, 52.03, 47.97, 4.06 +-14.96, -15.00, 54.55, 45.45, 9.11 +-14.96, -15.00, 52.08, 47.92, 4.16 +-14.96, -15.00, 52.08, 47.92, 4.16 +-14.96, -15.00, 52.08, 47.92, 4.16 +-14.96, -15.00, 52.08, 47.92, 4.16 +-15.03, -15.00, 54.60, 45.40, 9.20 +-15.03, -15.00, 52.13, 47.87, 4.26 +-15.03, -15.00, 52.13, 47.87, 4.26 +-15.03, -15.00, 52.13, 47.87, 4.26 +-15.03, -15.00, 52.13, 47.87, 4.26 +-15.16, -15.00, 57.17, 42.83, 14.35 +-15.16, -15.00, 52.23, 47.77, 4.46 +-15.16, -15.00, 52.23, 47.77, 4.46 +-15.16, -15.00, 52.23, 47.77, 4.46 +-15.16, -15.00, 52.23, 47.77, 4.46 +-15.16, -15.00, 52.23, 47.77, 4.47 +-15.23, -15.00, 54.75, 45.25, 9.51 +-15.23, -15.00, 52.28, 47.72, 4.57 +-15.23, -15.00, 52.28, 47.72, 4.57 +-15.23, -15.00, 52.29, 47.71, 4.57 +-15.23, -15.00, 52.29, 47.71, 4.57 +-15.23, -15.00, 52.29, 47.71, 4.57 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.59 +-15.23, -15.00, 52.29, 47.71, 4.59 +-15.23, -15.00, 52.29, 47.71, 4.59 +-15.23, -15.00, 52.30, 47.70, 4.59 +-15.23, -15.00, 52.30, 47.70, 4.59 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.61 +-15.23, -15.00, 52.30, 47.70, 4.61 +-15.23, -15.00, 52.30, 47.70, 4.61 +-15.23, -15.00, 52.31, 47.69, 4.61 +-15.23, -15.00, 52.31, 47.69, 4.61 +-15.16, -15.00, 49.79, 50.21, -0.43 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.03, -15.00, 47.22, 52.78, -5.56 +-15.03, -15.00, 52.16, 47.84, 4.32 +-15.03, -15.00, 52.16, 47.84, 4.32 +-15.03, -15.00, 52.16, 47.84, 4.32 +-14.96, -15.00, 49.64, 50.36, -0.72 +-14.96, -15.00, 52.11, 47.89, 4.22 +-14.96, -15.00, 52.11, 47.89, 4.22 +-14.96, -15.00, 52.11, 47.89, 4.22 +-14.90, -15.00, 49.59, 50.41, -0.82 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.77, -15.00, 47.02, 52.98, -5.97 +-14.77, -15.00, 51.96, 48.04, 3.92 +-14.77, -15.00, 51.96, 48.04, 3.92 +-14.77, -15.00, 51.96, 48.04, 3.92 +-14.70, -15.00, 49.44, 50.56, -1.13 +-14.70, -15.00, 51.91, 48.09, 3.81 +-14.70, -15.00, 51.90, 48.10, 3.81 +-14.63, -15.00, 49.38, 50.62, -1.24 +-14.63, -15.00, 51.85, 48.15, 3.71 +-14.63, -15.00, 51.85, 48.15, 3.70 +-14.50, -15.00, 46.81, 53.19, -6.39 +-14.50, -15.00, 51.75, 48.25, 3.50 +-14.50, -15.00, 51.75, 48.25, 3.49 +-14.44, -15.00, 49.22, 50.78, -1.55 +-14.44, -15.00, 51.69, 48.31, 3.39 +-14.44, -15.00, 51.69, 48.31, 3.38 +-14.37, -15.00, 49.17, 50.83, -1.67 +-14.37, -15.00, 51.64, 48.36, 3.27 +-14.37, -15.00, 51.63, 48.37, 3.27 +-14.37, -15.00, 51.63, 48.37, 3.26 +-14.24, -15.00, 46.59, 53.41, -6.83 +-14.24, -15.00, 51.53, 48.47, 3.06 +-14.24, -15.00, 51.52, 48.48, 3.05 +-14.24, -15.00, 51.52, 48.48, 3.04 +-14.17, -15.00, 49.00, 51.00, -2.01 +-14.17, -15.00, 51.47, 48.53, 2.93 +-14.17, -15.00, 51.46, 48.54, 2.93 +-14.17, -15.00, 51.46, 48.54, 2.92 +-14.11, -15.00, 48.94, 51.06, -2.13 +-14.11, -15.00, 51.40, 48.60, 2.81 +-14.11, -15.00, 51.40, 48.60, 2.80 +-14.11, -15.00, 51.40, 48.60, 2.79 +-14.11, -15.00, 51.39, 48.61, 2.79 +-13.97, -15.00, 46.35, 53.65, -7.31 +-13.97, -15.00, 51.29, 48.71, 2.57 +-13.97, -15.00, 51.28, 48.72, 2.57 +-13.97, -15.00, 51.28, 48.72, 2.56 +-13.97, -15.00, 51.28, 48.72, 2.55 +-13.97, -15.00, 51.27, 48.73, 2.54 +-13.97, -15.00, 51.27, 48.73, 2.54 +-13.97, -15.00, 51.26, 48.74, 2.53 +-13.91, -15.00, 48.74, 51.26, -2.52 +-13.91, -15.00, 51.21, 48.79, 2.41 +-13.91, -15.00, 51.20, 48.80, 2.40 +-13.91, -15.00, 51.20, 48.80, 2.40 +-13.91, -15.00, 51.19, 48.81, 2.39 +-13.91, -15.00, 51.19, 48.81, 2.38 +-13.91, -15.00, 51.19, 48.81, 2.37 +-13.91, -15.00, 51.18, 48.82, 2.36 +-13.91, -15.00, 51.18, 48.82, 2.36 +-13.91, -15.00, 51.17, 48.83, 2.35 +-13.91, -15.00, 51.17, 48.83, 2.34 +-13.91, -15.00, 51.17, 48.83, 2.33 +-13.91, -15.00, 51.16, 48.84, 2.32 +-13.91, -15.00, 51.16, 48.84, 2.31 +-13.91, -15.00, 51.15, 48.85, 2.31 +-13.91, -15.00, 51.15, 48.85, 2.30 +-13.91, -15.00, 51.15, 48.85, 2.29 +-13.91, -15.00, 51.14, 48.86, 2.28 +-13.91, -15.00, 51.14, 48.86, 2.27 +-13.91, -15.00, 51.13, 48.87, 2.27 +-13.91, -15.00, 51.13, 48.87, 2.26 +-13.91, -15.00, 51.12, 48.88, 2.25 +-13.91, -15.00, 51.12, 48.88, 2.24 +-13.97, -15.00, 53.64, 46.36, 7.28 +-13.91, -15.00, 48.64, 51.36, -2.72 +-13.97, -15.00, 53.63, 46.37, 7.26 +-13.97, -15.00, 51.15, 48.85, 2.31 +-13.97, -15.00, 51.15, 48.85, 2.30 +-13.97, -15.00, 51.15, 48.85, 2.29 +-13.97, -15.00, 51.14, 48.86, 2.29 +-13.97, -15.00, 51.14, 48.86, 2.28 +-13.97, -15.00, 51.14, 48.86, 2.27 +-13.97, -15.00, 51.13, 48.87, 2.26 +-13.97, -15.00, 51.13, 48.87, 2.25 +-13.97, -15.00, 51.12, 48.88, 2.25 +-14.11, -15.00, 56.16, 43.84, 12.33 +-14.11, -15.00, 51.22, 48.78, 2.43 +-14.11, -15.00, 51.21, 48.79, 2.42 +-14.11, -15.00, 51.21, 48.79, 2.42 +-14.11, -15.00, 51.21, 48.79, 2.41 +-14.11, -15.00, 51.20, 48.80, 2.40 +-14.11, -15.00, 51.20, 48.80, 2.40 +-14.11, -15.00, 51.20, 48.80, 2.39 +-14.11, -15.00, 51.19, 48.81, 2.38 +-14.11, -15.00, 51.19, 48.81, 2.38 +-14.17, -15.00, 53.71, 46.29, 7.41 +-14.17, -15.00, 51.23, 48.77, 2.46 +-14.17, -15.00, 51.23, 48.77, 2.46 +-14.17, -15.00, 51.23, 48.77, 2.45 +-14.17, -15.00, 51.22, 48.78, 2.45 +-14.17, -15.00, 51.22, 48.78, 2.44 +-14.17, -15.00, 51.22, 48.78, 2.43 +-14.24, -15.00, 53.74, 46.26, 7.47 +-14.24, -15.00, 51.26, 48.74, 2.52 +-14.24, -15.00, 51.26, 48.74, 2.52 +-14.24, -15.00, 51.25, 48.75, 2.51 +-14.24, -15.00, 51.25, 48.75, 2.50 +-14.24, -15.00, 51.25, 48.75, 2.50 +-14.24, -15.00, 51.25, 48.75, 2.49 +-14.24, -15.00, 51.24, 48.76, 2.49 +-14.37, -15.00, 56.28, 43.72, 12.57 +-14.37, -15.00, 51.34, 48.66, 2.67 +-14.37, -15.00, 51.34, 48.66, 2.67 +-14.37, -15.00, 51.33, 48.67, 2.67 +-14.44, -15.00, 53.85, 46.15, 7.70 +-14.44, -15.00, 51.38, 48.62, 2.76 +-14.44, -15.00, 51.38, 48.62, 2.75 +-14.44, -15.00, 51.37, 48.63, 2.75 +-14.44, -15.00, 51.37, 48.63, 2.74 +-14.44, -15.00, 51.37, 48.63, 2.74 +-14.50, -15.00, 53.89, 46.11, 7.78 +-14.50, -15.00, 51.42, 48.58, 2.83 +-14.50, -15.00, 51.41, 48.59, 2.83 +-14.50, -15.00, 51.41, 48.59, 2.82 +-14.50, -15.00, 51.41, 48.59, 2.82 +-14.50, -15.00, 51.41, 48.59, 2.82 +-14.63, -15.00, 56.45, 43.55, 12.90 +-14.63, -15.00, 51.50, 48.50, 3.01 +-14.63, -15.00, 51.50, 48.50, 3.00 +-14.63, -15.00, 51.50, 48.50, 3.00 +-14.70, -15.00, 54.02, 45.98, 8.04 +-14.70, -15.00, 51.55, 48.45, 3.10 +-14.70, -15.00, 51.55, 48.45, 3.09 +-14.70, -15.00, 51.55, 48.45, 3.09 +-14.70, -15.00, 51.54, 48.46, 3.09 +-14.77, -15.00, 54.07, 45.93, 8.13 +-14.77, -15.00, 51.59, 48.41, 3.19 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.90, -15.00, 56.63, 43.37, 13.26 +-14.90, -15.00, 51.69, 48.31, 3.37 +-14.90, -15.00, 51.69, 48.31, 3.37 +-14.90, -15.00, 51.69, 48.31, 3.37 +-14.90, -15.00, 51.69, 48.31, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.96, -15.00, 54.20, 45.80, 8.41 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-15.03, -15.00, 54.25, 45.75, 8.50 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.57 +-15.03, -15.00, 51.78, 48.22, 3.57 +-15.03, -15.00, 51.78, 48.22, 3.57 +-14.96, -15.00, 49.26, 50.74, -1.48 +-14.96, -15.00, 51.73, 48.27, 3.47 +-14.96, -15.00, 51.73, 48.27, 3.47 +-14.96, -15.00, 51.73, 48.27, 3.47 +-14.96, -15.00, 51.73, 48.27, 3.47 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 49.21, 50.79, -1.58 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.67, 48.33, 3.35 +-14.77, -15.00, 46.63, 53.37, -6.74 +-14.90, -15.00, 56.62, 43.38, 13.23 +-14.77, -15.00, 46.63, 53.37, -6.74 +-14.77, -15.00, 51.57, 48.43, 3.15 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.13 +-14.90, -15.00, 56.61, 43.39, 13.22 +-14.77, -15.00, 46.62, 53.38, -6.76 +-14.77, -15.00, 51.57, 48.43, 3.13 +-14.77, -15.00, 51.56, 48.44, 3.13 +-14.77, -15.00, 51.56, 48.44, 3.13 +-14.77, -15.00, 51.56, 48.44, 3.13 +-14.90, -15.00, 56.61, 43.39, 13.21 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.96, -15.00, 54.17, 45.83, 8.34 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.90, -15.00, 49.18, 50.82, -1.64 +-14.96, -15.00, 54.17, 45.83, 8.34 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-15.03, -15.00, 54.22, 45.78, 8.43 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.16, -15.00, 56.79, 43.21, 13.58 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.03, -15.00, 46.80, 53.20, -6.39 +-15.03, -15.00, 51.75, 48.25, 3.50 +-15.16, -15.00, 56.79, 43.21, 13.58 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.71 +-15.16, -15.00, 51.85, 48.15, 3.71 +-15.23, -15.00, 54.38, 45.62, 8.75 +-15.23, -15.00, 51.90, 48.10, 3.81 +-15.23, -15.00, 51.91, 48.09, 3.81 +-15.23, -15.00, 51.91, 48.09, 3.81 +-15.23, -15.00, 51.91, 48.09, 3.81 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.83 +-15.23, -15.00, 51.91, 48.09, 3.83 +-15.23, -15.00, 51.91, 48.09, 3.83 +-15.23, -15.00, 51.92, 48.08, 3.83 +-15.23, -15.00, 51.92, 48.08, 3.83 +-15.23, -15.00, 51.92, 48.08, 3.83 +-15.23, -15.00, 51.92, 48.08, 3.84 +-15.29, -15.00, 54.44, 45.56, 8.88 +-15.29, -15.00, 51.97, 48.03, 3.94 +-15.29, -15.00, 51.97, 48.03, 3.94 +-15.23, -15.00, 49.45, 50.55, -1.10 +-15.29, -15.00, 54.44, 45.56, 8.89 +-15.29, -15.00, 51.97, 48.03, 3.95 +-15.29, -15.00, 51.98, 48.02, 3.95 +-15.29, -15.00, 51.98, 48.02, 3.95 +-15.29, -15.00, 51.98, 48.02, 3.95 +-15.29, -15.00, 51.98, 48.02, 3.96 +-15.29, -15.00, 51.98, 48.02, 3.96 +-15.29, -15.00, 51.98, 48.02, 3.96 +-15.29, -15.00, 51.98, 48.02, 3.96 +-15.29, -15.00, 51.98, 48.02, 3.97 +-15.29, -15.00, 51.98, 48.02, 3.97 +-15.29, -15.00, 51.98, 48.02, 3.97 +-15.29, -15.00, 51.99, 48.01, 3.97 +-15.29, -15.00, 51.99, 48.01, 3.97 +-15.29, -15.00, 51.99, 48.01, 3.98 +-15.29, -15.00, 51.99, 48.01, 3.98 +-15.29, -15.00, 51.99, 48.01, 3.98 +-15.29, -15.00, 51.99, 48.01, 3.98 +-15.29, -15.00, 51.99, 48.01, 3.99 +-15.29, -15.00, 51.99, 48.01, 3.99 +-15.29, -15.00, 51.99, 48.01, 3.99 +-15.29, -15.00, 52.00, 48.00, 3.99 +-15.29, -15.00, 52.00, 48.00, 3.99 +-15.29, -15.00, 52.00, 48.00, 4.00 +-15.29, -15.00, 52.00, 48.00, 4.00 +-15.29, -15.00, 52.00, 48.00, 4.00 +-15.29, -15.00, 52.00, 48.00, 4.00 +-15.29, -15.00, 52.00, 48.00, 4.01 +-15.29, -15.00, 52.00, 48.00, 4.01 +-15.29, -15.00, 52.00, 48.00, 4.01 +-15.29, -15.00, 52.01, 47.99, 4.01 +-15.29, -15.00, 52.01, 47.99, 4.01 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.03 +-15.29, -15.00, 52.01, 47.99, 4.03 +-15.29, -15.00, 52.02, 47.98, 4.03 +-15.29, -15.00, 52.02, 47.98, 4.03 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.05 +-15.29, -15.00, 52.02, 47.98, 4.05 +-15.29, -15.00, 52.03, 47.97, 4.05 +-15.23, -15.00, 49.51, 50.49, -0.99 +-15.29, -15.00, 54.50, 45.50, 9.00 +-15.29, -15.00, 52.03, 47.97, 4.06 +-15.23, -15.00, 49.51, 50.49, -0.98 +-15.23, -15.00, 51.98, 48.02, 3.96 +-15.23, -15.00, 51.98, 48.02, 3.96 +-15.23, -15.00, 51.98, 48.02, 3.97 +-15.23, -15.00, 51.98, 48.02, 3.97 +-15.23, -15.00, 51.98, 48.02, 3.97 +-15.23, -15.00, 51.99, 48.01, 3.97 +-15.23, -15.00, 51.99, 48.01, 3.97 +-15.23, -15.00, 51.99, 48.01, 3.97 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.99 +-15.23, -15.00, 51.99, 48.01, 3.99 +-15.23, -15.00, 51.99, 48.01, 3.99 +-15.23, -15.00, 52.00, 48.00, 3.99 +-15.23, -15.00, 52.00, 48.00, 3.99 +-15.23, -15.00, 52.00, 48.00, 3.99 +-15.23, -15.00, 52.00, 48.00, 4.00 +-15.23, -15.00, 52.00, 48.00, 4.00 +-15.23, -15.00, 52.00, 48.00, 4.00 +-15.16, -15.00, 49.48, 50.52, -1.04 +-15.16, -15.00, 51.95, 48.05, 3.90 +-15.16, -15.00, 51.95, 48.05, 3.90 +-15.16, -15.00, 51.95, 48.05, 3.91 +-15.16, -15.00, 51.95, 48.05, 3.91 +-15.16, -15.00, 51.95, 48.05, 3.91 +-15.16, -15.00, 51.95, 48.05, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.93 +-15.16, -15.00, 51.96, 48.04, 3.93 +-15.16, -15.00, 51.96, 48.04, 3.93 +-15.16, -15.00, 51.96, 48.04, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.97 +-15.16, -15.00, 51.98, 48.02, 3.97 +-15.16, -15.00, 51.98, 48.02, 3.97 +-15.16, -15.00, 51.98, 48.02, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.03, -15.00, 46.95, 53.05, -6.10 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-14.96, -15.00, 49.37, 50.63, -1.26 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.90, -15.00, 49.32, 50.68, -1.36 +-14.90, -15.00, 51.79, 48.21, 3.59 +-14.90, -15.00, 51.79, 48.21, 3.59 +-14.90, -15.00, 51.79, 48.21, 3.59 +-14.90, -15.00, 51.79, 48.21, 3.58 +-14.90, -15.00, 51.79, 48.21, 3.58 +-14.90, -15.00, 51.79, 48.21, 3.58 +-14.90, -15.00, 51.79, 48.21, 3.58 +-14.77, -15.00, 46.75, 53.25, -6.50 +-14.77, -15.00, 51.69, 48.31, 3.38 +-14.77, -15.00, 51.69, 48.31, 3.38 +-14.77, -15.00, 51.69, 48.31, 3.38 +-14.77, -15.00, 51.69, 48.31, 3.38 +-14.77, -15.00, 51.69, 48.31, 3.37 +-14.70, -15.00, 49.16, 50.84, -1.67 +-14.70, -15.00, 51.64, 48.36, 3.27 +-14.70, -15.00, 51.63, 48.37, 3.27 +-14.70, -15.00, 51.63, 48.37, 3.27 +-14.70, -15.00, 51.63, 48.37, 3.26 +-14.70, -15.00, 51.63, 48.37, 3.26 +-14.70, -15.00, 51.63, 48.37, 3.26 +-14.63, -15.00, 49.11, 50.89, -1.79 +-14.63, -15.00, 51.58, 48.42, 3.15 +-14.63, -15.00, 51.58, 48.42, 3.15 +-14.63, -15.00, 51.57, 48.43, 3.15 +-14.63, -15.00, 51.57, 48.43, 3.15 +-14.63, -15.00, 51.57, 48.43, 3.14 +-14.63, -15.00, 51.57, 48.43, 3.14 +-14.63, -15.00, 51.57, 48.43, 3.14 +-14.63, -15.00, 51.57, 48.43, 3.14 +-14.50, -15.00, 46.52, 53.48, -6.95 +-14.50, -15.00, 51.47, 48.53, 2.93 +-14.63, -15.00, 56.51, 43.49, 13.01 +-14.63, -15.00, 51.56, 48.44, 3.12 +-14.63, -15.00, 51.56, 48.44, 3.12 +-14.63, -15.00, 51.56, 48.44, 3.12 +-14.50, -15.00, 46.51, 53.49, -6.97 +-14.63, -15.00, 56.50, 43.50, 13.00 +-14.63, -15.00, 51.55, 48.45, 3.11 +-14.63, -15.00, 51.55, 48.45, 3.11 +-14.63, -15.00, 51.55, 48.45, 3.10 +-14.63, -15.00, 51.55, 48.45, 3.10 +-14.63, -15.00, 51.55, 48.45, 3.10 +-14.63, -15.00, 51.55, 48.45, 3.09 +-14.63, -15.00, 51.55, 48.45, 3.09 +-14.63, -15.00, 51.54, 48.46, 3.09 +-14.70, -15.00, 54.06, 45.94, 8.13 +-14.70, -15.00, 51.59, 48.41, 3.18 +-14.70, -15.00, 51.59, 48.41, 3.18 +-14.70, -15.00, 51.59, 48.41, 3.18 +-14.70, -15.00, 51.59, 48.41, 3.18 +-14.70, -15.00, 51.59, 48.41, 3.17 +-14.77, -15.00, 54.11, 45.89, 8.22 +-14.77, -15.00, 51.63, 48.37, 3.27 +-14.77, -15.00, 51.63, 48.37, 3.27 +-14.77, -15.00, 51.63, 48.37, 3.27 +-14.77, -15.00, 51.63, 48.37, 3.26 +-14.77, -15.00, 51.63, 48.37, 3.26 +-14.90, -15.00, 56.67, 43.33, 13.35 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.96, -15.00, 54.25, 45.75, 8.50 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.77, 48.23, 3.55 +-14.96, -15.00, 51.77, 48.23, 3.55 +-15.03, -15.00, 54.30, 45.70, 8.59 +-14.96, -15.00, 49.30, 50.70, -1.39 +-15.03, -15.00, 54.30, 45.70, 8.59 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.66 +-15.03, -15.00, 51.83, 48.17, 3.66 +-15.03, -15.00, 51.83, 48.17, 3.66 +-14.96, -15.00, 49.31, 50.69, -1.39 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.90, -15.00, 49.26, 50.74, -1.49 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.72, 48.28, 3.45 +-14.90, -15.00, 51.72, 48.28, 3.45 +-14.77, -15.00, 46.68, 53.32, -6.64 +-14.77, -15.00, 51.62, 48.38, 3.25 +-14.77, -15.00, 51.62, 48.38, 3.25 +-14.77, -15.00, 51.62, 48.38, 3.24 +-14.77, -15.00, 51.62, 48.38, 3.24 +-14.77, -15.00, 51.62, 48.38, 3.24 +-14.70, -15.00, 49.10, 50.90, -1.80 +-14.70, -15.00, 51.57, 48.43, 3.14 +-14.70, -15.00, 51.57, 48.43, 3.14 +-14.70, -15.00, 51.57, 48.43, 3.13 +-14.70, -15.00, 51.57, 48.43, 3.13 +-14.70, -15.00, 51.56, 48.44, 3.13 +-14.70, -15.00, 51.56, 48.44, 3.13 +-14.63, -15.00, 49.04, 50.96, -1.92 +-14.63, -15.00, 51.51, 48.49, 3.02 +-14.63, -15.00, 51.51, 48.49, 3.02 +-14.63, -15.00, 51.51, 48.49, 3.02 +-14.63, -15.00, 51.51, 48.49, 3.01 +-14.63, -15.00, 51.51, 48.49, 3.01 +-14.63, -15.00, 51.50, 48.50, 3.01 +-14.63, -15.00, 51.50, 48.50, 3.01 +-14.63, -15.00, 51.50, 48.50, 3.00 +-14.50, -15.00, 46.46, 53.54, -7.09 +-14.50, -15.00, 51.40, 48.60, 2.80 +-14.50, -15.00, 51.40, 48.60, 2.79 +-14.50, -15.00, 51.39, 48.61, 2.79 +-14.50, -15.00, 51.39, 48.61, 2.79 +-14.50, -15.00, 51.39, 48.61, 2.78 +-14.50, -15.00, 51.39, 48.61, 2.78 +-14.50, -15.00, 51.39, 48.61, 2.78 +-14.50, -15.00, 51.39, 48.61, 2.77 +-14.50, -15.00, 51.38, 48.62, 2.77 +-14.50, -15.00, 51.38, 48.62, 2.76 +-14.50, -15.00, 51.38, 48.62, 2.76 +-14.50, -15.00, 51.38, 48.62, 2.76 +-14.50, -15.00, 51.38, 48.62, 2.75 +-14.50, -15.00, 51.37, 48.63, 2.75 +-14.50, -15.00, 51.37, 48.63, 2.75 +-14.50, -15.00, 51.37, 48.63, 2.74 +-14.50, -15.00, 51.37, 48.63, 2.74 +-14.50, -15.00, 51.37, 48.63, 2.73 +-14.50, -15.00, 51.37, 48.63, 2.73 +-14.50, -15.00, 51.36, 48.64, 2.73 +-14.50, -15.00, 51.36, 48.64, 2.72 +-14.50, -15.00, 51.36, 48.64, 2.72 +-14.50, -15.00, 51.36, 48.64, 2.72 +-14.50, -15.00, 51.36, 48.64, 2.71 +-14.50, -15.00, 51.35, 48.65, 2.71 +-14.50, -15.00, 51.35, 48.65, 2.70 +-14.50, -15.00, 51.35, 48.65, 2.70 +-14.63, -15.00, 56.39, 43.61, 12.78 +-14.63, -15.00, 51.45, 48.55, 2.89 +-14.63, -15.00, 51.44, 48.56, 2.89 +-14.63, -15.00, 51.44, 48.56, 2.89 +-14.63, -15.00, 51.44, 48.56, 2.88 +-14.63, -15.00, 51.44, 48.56, 2.88 +-14.63, -15.00, 51.44, 48.56, 2.88 +-14.63, -15.00, 51.44, 48.56, 2.88 +-14.63, -15.00, 51.44, 48.56, 2.87 +-14.70, -15.00, 53.96, 46.04, 7.91 +-14.70, -15.00, 51.48, 48.52, 2.97 +-14.70, -15.00, 51.48, 48.52, 2.97 +-14.70, -15.00, 51.48, 48.52, 2.96 +-14.70, -15.00, 51.48, 48.52, 2.96 +-14.70, -15.00, 51.48, 48.52, 2.96 +-14.70, -15.00, 51.48, 48.52, 2.96 +-14.70, -15.00, 51.48, 48.52, 2.95 +-14.70, -15.00, 51.48, 48.52, 2.95 +-14.77, -15.00, 54.00, 46.00, 7.99 +-14.77, -15.00, 51.52, 48.48, 3.05 +-14.77, -15.00, 51.52, 48.48, 3.05 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.03 +-14.90, -15.00, 56.56, 43.44, 13.12 +-14.77, -15.00, 46.57, 53.43, -6.86 +-14.90, -15.00, 56.56, 43.44, 13.12 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.96, -15.00, 54.13, 45.87, 8.26 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-15.03, -15.00, 54.18, 45.82, 8.36 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.16, -15.00, 56.75, 43.25, 13.50 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.63 +-15.16, -15.00, 51.81, 48.19, 3.63 +-15.16, -15.00, 51.81, 48.19, 3.63 +-15.16, -15.00, 51.81, 48.19, 3.63 +-15.16, -15.00, 51.82, 48.18, 3.63 +-15.23, -15.00, 54.34, 45.66, 8.67 +-15.23, -15.00, 51.87, 48.13, 3.73 +-15.23, -15.00, 51.87, 48.13, 3.73 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.75 +-15.23, -15.00, 51.87, 48.13, 3.75 +-15.23, -15.00, 51.87, 48.13, 3.75 +-15.16, -15.00, 49.35, 50.65, -1.29 +-15.16, -15.00, 51.83, 48.17, 3.65 +-15.16, -15.00, 51.83, 48.17, 3.65 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.67 +-15.16, -15.00, 51.83, 48.17, 3.67 +-15.16, -15.00, 51.83, 48.17, 3.67 +-15.16, -15.00, 51.83, 48.17, 3.67 +-15.16, -15.00, 51.84, 48.16, 3.67 +-15.16, -15.00, 51.84, 48.16, 3.67 +-15.16, -15.00, 51.84, 48.16, 3.67 +-15.16, -15.00, 51.84, 48.16, 3.67 +-15.03, -15.00, 46.79, 53.21, -6.41 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.16, -15.00, 56.78, 43.22, 13.57 +-15.16, -15.00, 51.84, 48.16, 3.68 +-15.16, -15.00, 51.84, 48.16, 3.68 +-15.16, -15.00, 51.84, 48.16, 3.68 +-15.16, -15.00, 51.84, 48.16, 3.68 +-15.16, -15.00, 51.84, 48.16, 3.69 +-15.16, -15.00, 51.84, 48.16, 3.69 +-15.16, -15.00, 51.84, 48.16, 3.69 +-15.16, -15.00, 51.84, 48.16, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.23, -15.00, 54.37, 45.63, 8.74 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.81 +-15.23, -15.00, 51.90, 48.10, 3.81 +-15.16, -15.00, 49.38, 50.62, -1.23 +-15.23, 0.00, 75.00, 25.00, 50.00 +-15.23, 0.00, 63.27, 36.73, 26.54 +-15.23, 0.00, 63.33, 36.67, 26.65 +-15.16, 0.00, 60.86, 39.14, 21.72 +-15.16, 0.00, 63.39, 36.61, 26.78 +-15.16, 0.00, 63.45, 36.55, 26.89 +-15.16, 0.00, 63.50, 36.50, 27.01 +-15.16, 0.00, 63.56, 36.44, 27.12 +-15.16, 0.00, 63.62, 36.38, 27.24 +-15.03, 0.00, 58.63, 41.37, 17.26 +-15.03, 0.00, 63.63, 36.37, 27.26 +-15.03, 0.00, 63.69, 36.31, 27.38 +-14.96, 0.00, 61.22, 38.78, 22.45 +-14.90, 0.00, 61.23, 38.77, 22.46 +-14.90, 0.00, 63.76, 36.24, 27.51 +-14.90, 0.00, 63.81, 36.19, 27.63 +-14.77, 0.00, 58.83, 41.17, 17.65 +-14.70, 0.00, 61.30, 38.70, 22.61 +-14.63, 0.00, 61.31, 38.69, 22.62 +-14.50, 0.00, 58.79, 41.21, 17.58 +-14.44, 0.00, 61.27, 38.73, 22.54 +-14.37, 0.00, 61.27, 38.73, 22.55 +-14.24, 0.00, 58.76, 41.24, 17.51 +-14.17, 0.00, 61.23, 38.77, 22.46 +-14.11, 0.00, 61.23, 38.77, 22.47 +-13.91, 0.00, 56.19, 43.81, 12.39 +-13.84, 0.00, 61.14, 38.86, 22.28 +-13.65, 0.00, 56.10, 43.90, 12.20 +-13.58, 0.00, 61.05, 38.95, 22.09 +-13.38, 0.00, 56.00, 44.00, 12.01 +-13.18, 0.00, 55.90, 44.10, 11.81 +-13.05, 0.00, 58.33, 41.67, 16.65 +-12.92, 0.00, 58.28, 41.72, 16.55 +-12.79, 0.00, 58.23, 41.77, 16.45 +-12.59, 0.00, 55.65, 44.35, 11.30 +-12.39, 0.00, 55.55, 44.45, 11.10 +-12.26, 0.00, 57.97, 42.03, 15.94 +-12.06, 0.00, 55.39, 44.61, 10.79 +-11.87, 0.00, 55.29, 44.71, 10.58 +-11.73, 0.00, 57.71, 42.29, 15.42 +-11.47, 0.00, 52.61, 47.39, 5.22 +-11.27, 0.00, 54.97, 45.03, 9.95 +-11.01, 0.00, 52.35, 47.65, 4.69 +-10.81, 0.00, 54.71, 45.29, 9.42 +-10.68, 0.00, 57.12, 42.88, 14.25 +-10.42, 0.00, 52.02, 47.98, 4.04 +-10.22, 0.00, 54.38, 45.62, 8.77 +-9.95, 0.00, 51.75, 48.25, 3.50 +-9.76, 0.00, 54.11, 45.89, 8.22 +-9.49, 0.00, 51.48, 48.52, 2.95 +-9.23, 0.00, 51.31, 48.69, 2.63 +-9.10, 0.00, 56.19, 43.81, 12.39 +-8.83, 0.00, 51.08, 48.92, 2.17 +-8.64, 0.00, 53.44, 46.56, 6.88 +-8.37, 0.00, 50.80, 49.20, 1.60 +-8.17, 0.00, 53.16, 46.84, 6.31 +-7.91, 0.00, 50.52, 49.48, 1.03 +-7.65, 0.00, 50.35, 49.65, 0.69 +-7.38, 0.00, 50.18, 49.82, 0.35 +-7.25, 0.00, 55.05, 44.95, 10.10 +-6.99, 0.00, 49.93, 50.07, -0.13 +-6.72, 0.00, 49.76, 50.24, -0.48 +-6.53, 0.00, 52.11, 47.89, 4.22 +-6.26, 0.00, 49.46, 50.54, -1.07 +-6.00, 0.00, 49.29, 50.71, -1.42 +-5.80, 0.00, 51.63, 48.37, 3.27 +-5.54, 0.00, 48.98, 51.02, -2.03 +-5.27, 0.00, 48.81, 51.19, -2.39 +-5.01, 0.00, 48.63, 51.37, -2.74 +-4.88, 0.00, 53.49, 46.51, 6.98 +-4.61, 0.00, 48.37, 51.63, -3.27 +-4.35, 0.00, 48.19, 51.81, -3.63 +-4.15, 0.00, 50.52, 49.48, 1.05 +-3.89, 0.00, 47.87, 52.13, -4.26 +-3.63, 0.00, 47.68, 52.32, -4.63 +-3.43, 0.00, 50.02, 49.98, 0.04 +-3.16, 0.00, 47.36, 52.64, -5.27 +-3.03, 0.00, 52.22, 47.78, 4.44 +-2.77, 0.00, 47.09, 52.91, -5.82 +-2.50, 0.00, 46.90, 53.10, -6.20 +-2.31, 0.00, 49.23, 50.77, -1.53 +-2.04, 0.00, 46.57, 53.43, -6.86 +-1.85, 0.00, 48.90, 51.10, -2.20 +-1.58, 0.00, 46.24, 53.76, -7.53 +-1.45, 0.00, 51.09, 48.91, 2.18 +-1.25, 0.00, 48.47, 51.53, -3.06 +-0.99, 0.00, 45.81, 54.19, -8.39 +-0.79, 0.00, 48.13, 51.87, -3.73 +-0.66, 0.00, 50.51, 49.49, 1.02 +-0.40, 0.00, 45.37, 54.63, -9.26 +-0.20, 0.00, 47.69, 52.31, -4.61 +0.00, 0.00, 47.54, 52.46, -4.91 +0.13, 0.00, 49.92, 50.08, -0.17 +0.40, 0.00, 44.77, 55.23, -10.45 +0.59, 0.00, 47.10, 52.90, -5.81 +0.79, 0.00, 46.94, 53.06, -6.11 +0.92, 0.00, 49.31, 50.69, -1.37 +1.12, 0.00, 46.69, 53.31, -6.62 +1.32, 0.00, 46.54, 53.46, -6.93 +1.45, 0.00, 48.90, 51.10, -2.19 +1.65, 0.00, 46.28, 53.72, -7.45 +1.85, 0.00, 46.12, 53.88, -7.76 +1.91, 0.00, 51.01, 48.99, 2.02 +2.11, 0.00, 45.91, 54.09, -8.18 +2.24, 0.00, 48.27, 51.73, -3.45 +2.44, 0.00, 45.64, 54.36, -8.71 +2.50, 0.00, 50.53, 49.47, 1.06 +2.64, 0.00, 47.95, 52.05, -4.10 +2.77, 0.00, 47.84, 52.16, -4.32 +2.97, 0.00, 45.21, 54.79, -9.58 +3.03, 0.00, 50.09, 49.91, 0.18 +3.23, 0.00, 44.99, 55.01, -10.03 +3.30, 0.00, 49.87, 50.13, -0.26 +3.43, 0.00, 47.29, 52.71, -5.43 +3.56, 0.00, 47.17, 52.83, -5.65 +3.69, 0.00, 47.06, 52.94, -5.88 +3.76, 0.00, 49.47, 50.53, -1.06 +3.96, 0.00, 44.36, 55.64, -11.28 +4.02, 0.00, 49.24, 50.76, -1.52 +4.09, 0.00, 49.18, 50.82, -1.65 +4.22, 0.00, 46.59, 53.41, -6.82 +4.28, 0.00, 49.00, 51.00, -2.01 +4.35, 0.00, 48.93, 51.07, -2.14 +4.48, 0.00, 46.34, 53.66, -7.32 +4.55, 0.00, 48.75, 51.25, -2.50 +4.61, 0.00, 48.68, 51.32, -2.64 +4.75, 0.00, 46.09, 53.91, -7.81 +4.75, 0.00, 51.02, 48.98, 2.04 +4.81, 0.00, 48.48, 51.52, -3.04 +4.88, 0.00, 48.41, 51.59, -3.18 +5.01, 0.00, 45.82, 54.18, -8.36 +5.01, 0.00, 50.75, 49.25, 1.49 +5.08, 0.00, 48.21, 51.79, -3.59 +5.08, 0.00, 50.66, 49.34, 1.32 +5.14, 0.00, 48.12, 51.88, -3.76 +5.14, 0.00, 50.57, 49.43, 1.14 +5.14, 0.00, 50.55, 49.45, 1.10 +5.27, 0.00, 45.49, 54.51, -9.02 +5.27, 0.00, 50.41, 49.59, 0.83 +5.27, 0.00, 50.39, 49.61, 0.79 +5.34, 0.00, 47.85, 52.15, -4.29 +5.34, 0.00, 50.30, 49.70, 0.61 +5.34, 0.00, 50.28, 49.72, 0.57 +5.34, 0.00, 50.26, 49.74, 0.53 +5.34, 0.00, 50.24, 49.76, 0.49 +5.34, 0.00, 50.22, 49.78, 0.45 +5.34, 0.00, 50.20, 49.80, 0.41 +5.34, 0.00, 50.18, 49.82, 0.37 +5.27, 0.00, 52.69, 47.31, 5.37 +5.27, 0.00, 50.19, 49.81, 0.39 +5.27, 0.00, 50.17, 49.83, 0.35 +5.27, 0.00, 50.15, 49.85, 0.31 +5.27, 0.00, 50.13, 49.87, 0.27 +5.27, 0.00, 50.12, 49.88, 0.23 +5.27, 0.00, 50.10, 49.90, 0.19 +5.14, 0.00, 55.12, 44.88, 10.24 +5.14, 0.00, 50.16, 49.84, 0.31 +5.14, 0.00, 50.14, 49.86, 0.27 +5.08, 0.00, 52.64, 47.36, 5.28 +5.08, 0.00, 50.15, 49.85, 0.30 +5.08, 0.00, 50.13, 49.87, 0.26 +5.08, 0.00, 50.11, 49.89, 0.22 +5.01, 0.00, 52.61, 47.39, 5.22 +5.01, 0.00, 50.12, 49.88, 0.24 +4.88, 0.00, 55.15, 44.85, 10.29 +4.88, 0.00, 50.18, 49.82, 0.37 +4.81, 0.00, 52.69, 47.31, 5.37 +4.81, 0.00, 50.20, 49.80, 0.39 +4.75, 0.00, 52.70, 47.30, 5.40 +4.75, 0.00, 50.21, 49.79, 0.42 +4.75, 0.00, 50.19, 49.81, 0.39 +4.61, 0.00, 55.22, 44.78, 10.44 +4.61, 0.00, 50.26, 49.74, 0.52 +4.55, 0.00, 52.76, 47.24, 5.52 +4.55, 0.00, 50.27, 49.73, 0.55 +4.48, 0.00, 52.78, 47.22, 5.55 +4.48, 0.00, 50.29, 49.71, 0.58 +4.48, 0.00, 50.27, 49.73, 0.54 +4.35, 0.00, 55.30, 44.70, 10.60 +4.28, 0.00, 52.86, 47.14, 5.72 +4.28, 0.00, 50.37, 49.63, 0.74 +4.22, 0.00, 52.88, 47.12, 5.75 +4.22, 0.00, 50.39, 49.61, 0.78 +4.09, 0.00, 55.42, 44.58, 10.83 +4.09, 0.00, 50.46, 49.54, 0.92 +4.02, 0.00, 52.96, 47.04, 5.93 +3.96, 0.00, 53.00, 47.00, 6.00 +3.96, 0.00, 50.51, 49.49, 1.02 +3.82, 0.00, 55.54, 44.46, 11.08 +3.82, 0.00, 50.58, 49.42, 1.16 +3.76, 0.00, 53.09, 46.91, 6.18 +3.76, 0.00, 50.60, 49.40, 1.21 +3.69, 0.00, 53.11, 46.89, 6.22 +3.69, 0.00, 50.63, 49.37, 1.25 +3.69, 0.00, 50.61, 49.39, 1.22 +3.69, 0.00, 50.60, 49.40, 1.19 +3.56, 0.00, 55.63, 44.37, 11.25 +3.56, 0.00, 50.67, 49.33, 1.34 +3.49, 0.00, 53.18, 46.82, 6.36 +3.49, 0.00, 50.69, 49.31, 1.39 +3.43, 0.00, 53.20, 46.80, 6.40 +3.43, 0.00, 50.72, 49.28, 1.43 +3.30, 0.00, 55.75, 44.25, 11.49 +3.30, 0.00, 50.79, 49.21, 1.58 +3.23, 0.00, 53.30, 46.70, 6.60 +3.23, 0.00, 50.82, 49.18, 1.63 +3.23, 0.00, 50.80, 49.20, 1.61 +3.16, 0.00, 53.31, 46.69, 6.63 +3.16, 0.00, 50.83, 49.17, 1.66 +3.03, 0.00, 55.86, 44.14, 11.72 +3.03, 0.00, 50.91, 49.09, 1.81 +3.03, 0.00, 50.89, 49.11, 1.79 +3.03, 0.00, 50.88, 49.12, 1.77 +3.03, 0.00, 50.87, 49.13, 1.74 +2.97, 0.00, 53.38, 46.62, 6.76 +2.97, 0.00, 50.90, 49.10, 1.80 +2.97, 0.00, 50.89, 49.11, 1.78 +2.90, 0.00, 53.40, 46.60, 6.80 +2.90, 0.00, 50.92, 49.08, 1.83 +2.77, 0.00, 55.95, 44.05, 11.90 +2.77, 0.00, 50.99, 49.01, 1.99 +2.77, 0.00, 50.98, 49.02, 1.97 +2.70, 0.00, 53.49, 46.51, 6.99 +2.70, 0.00, 51.01, 48.99, 2.02 +2.64, 0.00, 53.52, 46.48, 7.05 +2.64, 0.00, 51.04, 48.96, 2.08 +2.64, 0.00, 51.03, 48.97, 2.06 +2.50, 0.00, 56.07, 43.93, 12.13 +2.50, 0.00, 51.11, 48.89, 2.22 +2.50, 0.00, 51.10, 48.90, 2.21 +2.50, 0.00, 51.09, 48.91, 2.19 +2.50, 0.00, 51.08, 48.92, 2.17 +2.50, 0.00, 51.07, 48.93, 2.15 +2.44, 0.00, 53.59, 46.41, 7.17 +2.44, 0.00, 51.11, 48.89, 2.21 +2.44, 0.00, 51.10, 48.90, 2.19 +2.44, 0.00, 51.09, 48.91, 2.17 +2.44, 0.00, 51.08, 48.92, 2.16 +2.44, 0.00, 51.07, 48.93, 2.14 +2.37, 0.00, 53.58, 46.42, 7.16 +2.37, 0.00, 51.10, 48.90, 2.20 +2.37, 0.00, 51.09, 48.91, 2.18 +2.37, 0.00, 51.08, 48.92, 2.17 +2.37, 0.00, 51.07, 48.93, 2.15 +2.24, 0.00, 56.11, 43.89, 12.22 +2.24, 0.00, 51.16, 48.84, 2.31 +2.24, 0.00, 51.15, 48.85, 2.30 +2.24, 0.00, 51.14, 48.86, 2.28 +2.24, 0.00, 51.13, 48.87, 2.26 +2.24, 0.00, 51.12, 48.88, 2.24 +2.24, 0.00, 51.11, 48.89, 2.23 +2.24, 0.00, 51.11, 48.89, 2.21 +2.18, 0.00, 53.62, 46.38, 7.24 +2.24, 0.00, 48.62, 51.38, -2.77 +2.18, 0.00, 53.60, 46.40, 7.20 +2.18, 0.00, 51.12, 48.88, 2.24 +2.18, 0.00, 51.11, 48.89, 2.23 +2.18, 0.00, 51.11, 48.89, 2.21 +2.18, 0.00, 51.10, 48.90, 2.20 +2.11, 0.00, 53.61, 46.39, 7.22 +2.11, 0.00, 51.13, 48.87, 2.26 +2.11, 0.00, 51.12, 48.88, 2.25 +2.11, 0.00, 51.12, 48.88, 2.23 +2.11, 0.00, 51.11, 48.89, 2.22 +2.11, 0.00, 51.10, 48.90, 2.20 +2.11, 0.00, 51.09, 48.91, 2.18 +2.11, 0.00, 51.08, 48.92, 2.17 +1.98, 0.00, 56.12, 43.88, 12.24 +1.98, 0.00, 51.17, 48.83, 2.34 +1.98, 0.00, 51.16, 48.84, 2.32 +1.98, 0.00, 51.15, 48.85, 2.31 +1.98, 0.00, 51.15, 48.85, 2.29 +1.98, 0.00, 51.14, 48.86, 2.28 +1.98, 0.00, 51.13, 48.87, 2.26 +1.91, 0.00, 53.65, 46.35, 7.29 +1.91, 0.00, 51.17, 48.83, 2.33 +1.91, 0.00, 51.16, 48.84, 2.32 +1.91, 0.00, 51.15, 48.85, 2.30 +1.91, 0.00, 51.14, 48.86, 2.29 +1.91, 0.00, 51.14, 48.86, 2.27 +1.91, 0.00, 51.13, 48.87, 2.26 +1.91, 0.00, 51.12, 48.88, 2.25 +1.91, 0.00, 51.12, 48.88, 2.23 +1.91, 0.00, 51.11, 48.89, 2.22 +1.91, 0.00, 51.10, 48.90, 2.20 +1.91, 0.00, 51.09, 48.91, 2.19 +1.91, 0.00, 51.09, 48.91, 2.17 +1.91, 0.00, 51.08, 48.92, 2.16 +1.91, 0.00, 51.07, 48.93, 2.15 +1.91, 0.00, 51.07, 48.93, 2.13 +1.91, 0.00, 51.06, 48.94, 2.12 +1.91, 0.00, 51.05, 48.95, 2.10 +1.91, 0.00, 51.04, 48.96, 2.09 +1.91, 0.00, 51.04, 48.96, 2.07 +1.91, 0.00, 51.03, 48.97, 2.06 +1.91, 0.00, 51.02, 48.98, 2.05 +1.91, 0.00, 51.02, 48.98, 2.03 +1.85, 0.00, 53.53, 46.47, 7.06 +1.85, 0.00, 51.05, 48.95, 2.10 +1.85, 0.00, 51.04, 48.96, 2.09 +1.85, 0.00, 51.04, 48.96, 2.07 +1.85, 0.00, 51.03, 48.97, 2.06 +1.85, 0.00, 51.02, 48.98, 2.05 +1.85, 0.00, 51.02, 48.98, 2.03 +1.85, 0.00, 51.01, 48.99, 2.02 +1.85, 0.00, 51.00, 49.00, 2.01 +1.85, 0.00, 51.00, 49.00, 1.99 +1.85, 0.00, 50.99, 49.01, 1.98 +1.85, 0.00, 50.98, 49.02, 1.96 +1.85, 0.00, 50.97, 49.03, 1.95 +1.85, 0.00, 50.97, 49.03, 1.94 +1.91, 0.00, 48.44, 51.56, -3.12 +1.91, 0.00, 50.90, 49.10, 1.81 +1.91, 0.00, 50.90, 49.10, 1.79 +1.91, 0.00, 50.89, 49.11, 1.78 +1.91, 0.00, 50.88, 49.12, 1.77 +1.85, 0.00, 53.40, 46.60, 6.79 +1.85, 0.00, 50.92, 49.08, 1.84 +1.85, 0.00, 50.91, 49.09, 1.82 +1.85, 0.00, 50.90, 49.10, 1.81 +1.85, 0.00, 50.90, 49.10, 1.79 +1.85, 0.00, 50.89, 49.11, 1.78 +1.85, 0.00, 50.88, 49.12, 1.77 +1.85, 0.00, 50.88, 49.12, 1.75 +1.85, 0.00, 50.87, 49.13, 1.74 +1.85, 0.00, 50.86, 49.14, 1.73 +1.91, 0.00, 48.33, 51.67, -3.33 +1.91, 0.00, 50.80, 49.20, 1.60 +1.91, 0.00, 50.79, 49.21, 1.58 +1.91, 0.00, 50.78, 49.22, 1.57 +1.91, 0.00, 50.78, 49.22, 1.56 +1.91, 0.00, 50.77, 49.23, 1.54 +1.91, 0.00, 50.76, 49.24, 1.53 +1.91, 0.00, 50.76, 49.24, 1.51 +1.98, 0.00, 48.23, 51.77, -3.55 +1.98, 0.00, 50.69, 49.31, 1.38 +1.98, 0.00, 50.68, 49.32, 1.37 +1.98, 0.00, 50.68, 49.32, 1.35 +1.98, 0.00, 50.67, 49.33, 1.34 +1.98, 0.00, 50.66, 49.34, 1.32 +1.98, 0.00, 50.65, 49.35, 1.31 +1.98, 0.00, 50.65, 49.35, 1.29 +1.98, 0.00, 50.64, 49.36, 1.28 +1.98, 0.00, 50.63, 49.37, 1.26 +1.98, 0.00, 50.63, 49.37, 1.25 +1.98, 0.00, 50.62, 49.38, 1.24 +1.98, 0.00, 50.61, 49.39, 1.22 +1.98, 0.00, 50.60, 49.40, 1.21 +1.98, 0.00, 50.60, 49.40, 1.19 +1.98, 0.00, 50.59, 49.41, 1.18 +1.98, 0.00, 50.58, 49.42, 1.16 +1.98, 0.00, 50.57, 49.43, 1.15 +1.98, 0.00, 50.57, 49.43, 1.13 +1.98, 0.00, 50.56, 49.44, 1.12 +1.98, 0.00, 50.55, 49.45, 1.10 +1.98, 0.00, 50.54, 49.46, 1.09 +1.98, 0.00, 50.54, 49.46, 1.07 +1.98, 0.00, 50.53, 49.47, 1.06 +1.98, 0.00, 50.52, 49.48, 1.04 +1.98, 0.00, 50.51, 49.49, 1.03 +1.98, 0.00, 50.51, 49.49, 1.01 +1.98, 0.00, 50.50, 49.50, 1.00 +1.98, 0.00, 50.49, 49.51, 0.98 +1.98, 0.00, 50.48, 49.52, 0.97 +1.98, 0.00, 50.48, 49.52, 0.95 +1.98, 0.00, 50.47, 49.53, 0.94 +1.98, 0.00, 50.46, 49.54, 0.92 +1.98, 0.00, 50.45, 49.55, 0.91 +1.98, 0.00, 50.45, 49.55, 0.89 +1.98, 0.00, 50.44, 49.56, 0.88 +1.98, 0.00, 50.43, 49.57, 0.86 +1.98, 0.00, 50.42, 49.58, 0.85 +1.91, 0.00, 52.94, 47.06, 5.88 +1.91, 0.00, 50.46, 49.54, 0.92 +1.91, 0.00, 50.45, 49.55, 0.91 +1.91, 0.00, 50.45, 49.55, 0.89 +1.91, 0.00, 50.44, 49.56, 0.88 +1.91, 0.00, 50.43, 49.57, 0.86 +1.91, 0.00, 50.42, 49.58, 0.85 +1.91, 0.00, 50.42, 49.58, 0.83 +1.91, 0.00, 50.41, 49.59, 0.82 +1.91, 0.00, 50.40, 49.60, 0.81 +1.91, 0.00, 50.40, 49.60, 0.79 +1.91, 0.00, 50.39, 49.61, 0.78 +1.91, 0.00, 50.38, 49.62, 0.76 +1.91, 0.00, 50.37, 49.63, 0.75 +1.91, 0.00, 50.37, 49.63, 0.73 +1.91, 0.00, 50.36, 49.64, 0.72 +1.91, 0.00, 50.35, 49.65, 0.70 +1.91, 0.00, 50.35, 49.65, 0.69 +1.91, 0.00, 50.34, 49.66, 0.68 +1.91, 0.00, 50.33, 49.67, 0.66 +1.91, 0.00, 50.32, 49.68, 0.65 +1.85, 0.00, 52.84, 47.16, 5.68 +1.85, 0.00, 50.36, 49.64, 0.72 +1.85, 0.00, 50.35, 49.65, 0.70 +1.85, 0.00, 50.35, 49.65, 0.69 +1.85, 0.00, 50.34, 49.66, 0.68 +1.85, 0.00, 50.33, 49.67, 0.66 +1.85, 0.00, 50.32, 49.68, 0.65 +1.85, 0.00, 50.32, 49.68, 0.64 +1.85, 0.00, 50.31, 49.69, 0.62 +1.85, 0.00, 50.30, 49.70, 0.61 +1.85, 0.00, 50.30, 49.70, 0.59 +1.85, 0.00, 50.29, 49.71, 0.58 +1.85, 0.00, 50.28, 49.72, 0.57 +1.85, 0.00, 50.28, 49.72, 0.55 +1.85, 0.00, 50.27, 49.73, 0.54 +1.85, 0.00, 50.26, 49.74, 0.52 +1.85, 0.00, 50.26, 49.74, 0.51 +1.85, 0.00, 50.25, 49.75, 0.50 +1.85, 0.00, 50.24, 49.76, 0.48 +1.85, 0.00, 50.23, 49.77, 0.47 +1.71, 0.00, 55.27, 44.73, 10.54 +1.71, 0.00, 50.32, 49.68, 0.64 +1.71, 0.00, 50.31, 49.69, 0.63 +1.71, 0.00, 50.31, 49.69, 0.62 +1.71, 0.00, 50.30, 49.70, 0.60 +1.71, 0.00, 50.30, 49.70, 0.59 +1.65, 0.00, 52.81, 47.19, 5.62 +1.65, 0.00, 50.33, 49.67, 0.66 +1.71, 0.00, 47.80, 52.20, -4.39 +1.71, 0.00, 50.27, 49.73, 0.54 +1.71, 0.00, 50.26, 49.74, 0.53 +1.71, 0.00, 50.26, 49.74, 0.51 +1.71, 0.00, 50.25, 49.75, 0.50 +1.65, 0.00, 52.77, 47.23, 5.53 +1.71, 0.00, 47.77, 52.23, -4.47 +1.65, 0.00, 52.75, 47.25, 5.51 +1.65, 0.00, 50.28, 49.72, 0.55 +1.65, 0.00, 50.27, 49.73, 0.54 +1.65, 0.00, 50.26, 49.74, 0.53 +1.65, 0.00, 50.26, 49.74, 0.51 +1.65, 0.00, 50.25, 49.75, 0.50 +1.65, 0.00, 50.24, 49.76, 0.49 +1.65, 0.00, 50.24, 49.76, 0.48 +1.58, 0.00, 52.75, 47.25, 5.51 +1.58, 0.00, 50.28, 49.72, 0.55 +1.58, 0.00, 50.27, 49.73, 0.54 +1.58, 0.00, 50.26, 49.74, 0.53 +1.58, 0.00, 50.26, 49.74, 0.52 +1.58, 0.00, 50.25, 49.75, 0.50 +1.58, 0.00, 50.25, 49.75, 0.49 +1.58, 0.00, 50.24, 49.76, 0.48 +1.58, 0.00, 50.23, 49.77, 0.47 +1.58, 0.00, 50.23, 49.77, 0.46 +1.58, 0.00, 50.22, 49.78, 0.44 +1.58, 0.00, 50.22, 49.78, 0.43 +1.58, 0.00, 50.21, 49.79, 0.42 +1.58, 0.00, 50.20, 49.80, 0.41 +1.58, 0.00, 50.20, 49.80, 0.40 +1.58, 0.00, 50.19, 49.81, 0.38 +1.58, 0.00, 50.19, 49.81, 0.37 +1.58, 0.00, 50.18, 49.82, 0.36 +1.58, 0.00, 50.17, 49.83, 0.35 +1.58, 0.00, 50.17, 49.83, 0.34 +1.58, 0.00, 50.16, 49.84, 0.33 +1.58, 0.00, 50.16, 49.84, 0.31 +1.58, 0.00, 50.15, 49.85, 0.30 +1.58, 0.00, 50.15, 49.85, 0.29 +1.58, 0.00, 50.14, 49.86, 0.28 +1.58, 0.00, 50.13, 49.87, 0.27 +1.58, 0.00, 50.13, 49.87, 0.25 +1.58, 0.00, 50.12, 49.88, 0.24 +1.58, 0.00, 50.12, 49.88, 0.23 +1.58, 0.00, 50.11, 49.89, 0.22 +1.58, 0.00, 50.10, 49.90, 0.21 +1.58, 0.00, 50.10, 49.90, 0.20 +1.58, 0.00, 50.09, 49.91, 0.18 +1.58, 0.00, 50.09, 49.91, 0.17 +1.58, 0.00, 50.08, 49.92, 0.16 +1.58, 0.00, 50.07, 49.93, 0.15 +1.58, 0.00, 50.07, 49.93, 0.14 +1.58, 0.00, 50.06, 49.94, 0.12 +1.58, 0.00, 50.06, 49.94, 0.11 +1.58, 0.00, 50.05, 49.95, 0.10 +1.58, 0.00, 50.04, 49.96, 0.09 +1.58, 0.00, 50.04, 49.96, 0.08 +1.58, 0.00, 50.03, 49.97, 0.06 +1.58, 0.00, 50.03, 49.97, 0.05 +1.58, 0.00, 50.02, 49.98, 0.04 +1.58, 0.00, 50.01, 49.99, 0.03 +1.58, 0.00, 50.01, 49.99, 0.02 +1.58, 0.00, 50.00, 50.00, 0.01 +1.58, 0.00, 50.00, 50.00, -0.01 +1.58, 0.00, 49.99, 50.01, -0.02 +1.58, 0.00, 49.98, 50.02, -0.03 +1.58, 0.00, 49.98, 50.02, -0.04 +1.58, 0.00, 49.97, 50.03, -0.05 +1.45, 0.00, 55.01, 44.99, 10.02 +1.45, 0.00, 50.06, 49.94, 0.12 +1.45, 0.00, 50.06, 49.94, 0.11 +1.45, 0.00, 50.05, 49.95, 0.10 +1.45, 0.00, 50.04, 49.96, 0.09 +1.45, 0.00, 50.04, 49.96, 0.08 +1.45, 0.00, 50.03, 49.97, 0.07 +1.45, 0.00, 50.03, 49.97, 0.06 +1.45, 0.00, 50.02, 49.98, 0.05 +1.45, 0.00, 50.02, 49.98, 0.03 +1.45, 0.00, 50.01, 49.99, 0.02 +1.45, 0.00, 50.01, 49.99, 0.01 +1.45, 0.00, 50.00, 50.00, 0.00 +1.45, 0.00, 50.00, 50.00, -0.01 +1.45, 0.00, 49.99, 50.01, -0.02 +1.38, 0.00, 52.51, 47.49, 5.01 +1.38, 0.00, 50.03, 49.97, 0.06 +1.38, 0.00, 50.02, 49.98, 0.05 +1.38, 0.00, 50.02, 49.98, 0.04 +1.32, 0.00, 52.54, 47.46, 5.07 +1.32, 0.00, 50.06, 49.94, 0.12 +1.32, 0.00, 50.05, 49.95, 0.11 +1.32, 0.00, 50.05, 49.95, 0.10 +1.32, 0.00, 50.04, 49.96, 0.09 +1.32, 0.00, 50.04, 49.96, 0.08 +1.32, 0.00, 50.03, 49.97, 0.07 +1.32, 0.00, 50.03, 49.97, 0.06 +1.32, 0.00, 50.02, 49.98, 0.05 +1.32, 0.00, 50.02, 49.98, 0.04 +1.32, 0.00, 50.01, 49.99, 0.03 +1.32, 0.00, 50.01, 49.99, 0.02 +1.19, 0.00, 55.05, 44.95, 10.09 +1.19, 0.00, 50.10, 49.90, 0.20 +1.19, 0.00, 50.09, 49.91, 0.19 +1.19, 0.00, 50.09, 49.91, 0.18 +1.19, 0.00, 50.09, 49.91, 0.17 +1.19, 0.00, 50.08, 49.92, 0.16 +1.19, 0.00, 50.08, 49.92, 0.15 +1.19, 0.00, 50.07, 49.93, 0.14 +1.12, 0.00, 52.59, 47.41, 5.18 +1.12, 0.00, 50.11, 49.89, 0.23 +1.12, 0.00, 50.11, 49.89, 0.22 +1.12, 0.00, 50.10, 49.90, 0.21 +1.05, 0.00, 52.62, 47.38, 5.24 +1.05, 0.00, 50.15, 49.85, 0.29 +1.05, 0.00, 50.14, 49.86, 0.29 +1.05, 0.00, 50.14, 49.86, 0.28 +1.05, 0.00, 50.13, 49.87, 0.27 +1.05, 0.00, 50.13, 49.87, 0.26 +1.05, 0.00, 50.13, 49.87, 0.25 +1.05, 0.00, 50.12, 49.88, 0.25 +0.92, 0.00, 55.16, 44.84, 10.32 +0.92, 0.00, 50.21, 49.79, 0.43 +0.92, 0.00, 50.21, 49.79, 0.42 +0.92, 0.00, 50.21, 49.79, 0.42 +0.92, 0.00, 50.20, 49.80, 0.41 +0.86, 0.00, 52.72, 47.28, 5.45 +0.86, 0.00, 50.25, 49.75, 0.49 +0.86, 0.00, 50.24, 49.76, 0.49 +0.79, 0.00, 52.76, 47.24, 5.53 +0.79, 0.00, 50.29, 49.71, 0.58 +0.79, 0.00, 50.28, 49.72, 0.57 +0.79, 0.00, 50.28, 49.72, 0.56 +0.66, 0.00, 55.32, 44.68, 10.64 +0.66, 0.00, 50.38, 49.62, 0.75 +0.66, 0.00, 50.37, 49.63, 0.75 +0.66, 0.00, 50.37, 49.63, 0.74 +0.66, 0.00, 50.37, 49.63, 0.74 +0.66, 0.00, 50.37, 49.63, 0.73 +0.66, 0.00, 50.36, 49.64, 0.73 +0.66, 0.00, 50.36, 49.64, 0.72 +0.66, 0.00, 50.36, 49.64, 0.72 +0.59, 0.00, 52.88, 47.12, 5.75 +0.59, 0.00, 50.40, 49.60, 0.81 +0.59, 0.00, 50.40, 49.60, 0.80 +0.59, 0.00, 50.40, 49.60, 0.80 +0.59, 0.00, 50.40, 49.60, 0.79 +0.53, 0.00, 52.92, 47.08, 5.83 +0.53, 0.00, 50.44, 49.56, 0.88 +0.53, 0.00, 50.44, 49.56, 0.88 +0.53, 0.00, 50.44, 49.56, 0.88 +0.40, 0.00, 55.48, 44.52, 10.96 +0.40, 0.00, 50.53, 49.47, 1.07 +0.40, 0.00, 50.53, 49.47, 1.07 +0.40, 0.00, 50.53, 49.47, 1.06 +0.40, 0.00, 50.53, 49.47, 1.06 +0.33, 0.00, 53.05, 46.95, 6.10 +0.33, 0.00, 50.58, 49.42, 1.15 +0.33, 0.00, 50.58, 49.42, 1.15 +0.33, 0.00, 50.57, 49.43, 1.15 +0.33, 0.00, 50.57, 49.43, 1.15 +0.26, 0.00, 53.09, 46.91, 6.19 +0.26, 0.00, 50.62, 49.38, 1.24 +0.26, 0.00, 50.62, 49.38, 1.24 +0.13, 0.00, 55.66, 44.34, 11.32 +0.13, 0.00, 50.72, 49.28, 1.43 +0.07, 0.00, 53.24, 46.76, 6.48 +0.07, 0.00, 50.77, 49.23, 1.53 +0.07, 0.00, 50.77, 49.23, 1.53 +0.00, 0.00, 53.29, 46.71, 6.57 +0.00, 0.00, 50.82, 49.18, 1.63 +0.00, 0.00, 50.82, 49.18, 1.63 +0.00, 0.00, 50.82, 49.18, 1.63 +-0.13, 0.00, 55.86, 44.14, 11.72 +-0.13, 0.00, 50.92, 49.08, 1.83 +-0.13, 0.00, 50.92, 49.08, 1.83 +-0.20, 0.00, 53.44, 46.56, 6.88 +-0.20, 0.00, 50.97, 49.03, 1.93 +-0.20, 0.00, 50.97, 49.03, 1.93 +-0.20, 0.00, 50.97, 49.03, 1.94 +-0.26, 0.00, 53.49, 46.51, 6.98 +-0.26, 0.00, 51.02, 48.98, 2.04 +-0.26, 0.00, 51.02, 48.98, 2.04 +-0.40, 0.00, 56.06, 43.94, 12.13 +-0.40, 0.00, 51.12, 48.88, 2.24 +-0.40, 0.00, 51.12, 48.88, 2.25 +-0.46, 0.00, 53.65, 46.35, 7.29 +-0.46, 0.00, 51.18, 48.82, 2.35 +-0.53, 0.00, 53.70, 46.30, 7.40 +-0.53, 0.00, 51.23, 48.77, 2.46 +-0.53, 0.00, 51.23, 48.77, 2.46 +-0.66, 0.00, 56.28, 43.72, 12.55 +-0.66, 0.00, 51.34, 48.66, 2.67 +-0.66, 0.00, 51.34, 48.66, 2.68 +-0.66, 0.00, 51.34, 48.66, 2.68 +-0.66, 0.00, 51.34, 48.66, 2.69 +-0.73, 0.00, 53.87, 46.13, 7.73 +-0.73, 0.00, 51.40, 48.60, 2.80 +-0.73, 0.00, 51.40, 48.60, 2.80 +-0.79, 0.00, 53.93, 46.07, 7.85 +-0.79, 0.00, 51.46, 48.54, 2.91 +-0.79, 0.00, 51.46, 48.54, 2.92 +-0.92, 0.00, 56.51, 43.49, 13.01 +-0.92, 0.00, 51.57, 48.43, 3.13 +-0.92, 0.00, 51.57, 48.43, 3.14 +-0.99, 0.00, 54.09, 45.91, 8.19 +-0.99, 0.00, 51.63, 48.37, 3.25 +-0.99, 0.00, 51.63, 48.37, 3.26 +-0.99, 0.00, 51.63, 48.37, 3.27 +-1.05, 0.00, 54.16, 45.84, 8.32 +-1.05, 0.00, 51.69, 48.31, 3.38 +-1.05, 0.00, 51.69, 48.31, 3.39 +-1.05, 0.00, 51.70, 48.30, 3.40 +-1.05, 0.00, 51.70, 48.30, 3.40 +-1.19, 0.00, 56.75, 43.25, 13.50 +-1.19, 0.00, 51.81, 48.19, 3.62 +-1.19, 0.00, 51.81, 48.19, 3.63 +-1.19, 0.00, 51.82, 48.18, 3.64 +-1.19, 0.00, 51.82, 48.18, 3.65 +-1.25, 0.00, 54.35, 45.65, 8.70 +-1.25, 0.00, 51.88, 48.12, 3.76 +-1.25, 0.00, 51.89, 48.11, 3.77 +-1.25, 0.00, 51.89, 48.11, 3.78 +-1.25, 0.00, 51.90, 48.10, 3.79 +-1.25, 0.00, 51.90, 48.10, 3.80 +-1.25, 0.00, 51.91, 48.09, 3.81 +-1.32, 0.00, 54.43, 45.57, 8.86 +-1.32, 0.00, 51.96, 48.04, 3.93 +-1.32, 0.00, 51.97, 48.03, 3.94 +-1.32, 0.00, 51.97, 48.03, 3.95 +-1.32, 0.00, 51.98, 48.02, 3.96 +-1.32, 0.00, 51.98, 48.02, 3.97 +-1.32, 0.00, 51.99, 48.01, 3.98 +-1.32, 0.00, 51.99, 48.01, 3.99 +-1.32, 0.00, 52.00, 48.00, 4.00 +-1.32, 0.00, 52.00, 48.00, 4.01 +-1.32, 0.00, 52.01, 47.99, 4.02 +-1.32, 0.00, 52.01, 47.99, 4.03 +-1.32, 0.00, 52.02, 47.98, 4.04 +-1.32, 0.00, 52.02, 47.98, 4.05 +-1.32, 0.00, 52.03, 47.97, 4.06 +-1.32, 0.00, 52.03, 47.97, 4.07 +-1.32, 0.00, 52.04, 47.96, 4.08 +-1.32, 0.00, 52.04, 47.96, 4.09 +-1.32, 0.00, 52.05, 47.95, 4.10 +-1.32, 0.00, 52.05, 47.95, 4.11 +-1.25, 0.00, 49.54, 50.46, -0.93 +-1.25, 0.00, 52.01, 47.99, 4.03 +-1.25, 0.00, 52.02, 47.98, 4.04 +-1.25, 0.00, 52.02, 47.98, 4.05 +-1.25, 0.00, 52.03, 47.97, 4.06 +-1.25, 0.00, 52.03, 47.97, 4.07 +-1.25, 0.00, 52.04, 47.96, 4.07 +-1.25, 0.00, 52.04, 47.96, 4.08 +-1.19, 0.00, 49.53, 50.47, -0.95 +-1.19, 0.00, 52.00, 48.00, 4.00 +-1.25, 0.00, 54.53, 45.47, 9.06 +-1.19, 0.00, 49.54, 50.46, -0.92 +-1.19, 0.00, 52.02, 47.98, 4.03 +-1.19, 0.00, 52.02, 47.98, 4.04 +-1.19, 0.00, 52.02, 47.98, 4.05 +-1.05, 0.00, 46.99, 53.01, -6.03 +-1.05, 0.00, 51.93, 48.07, 3.87 +-1.05, 0.00, 51.94, 48.06, 3.87 +-1.05, 0.00, 51.94, 48.06, 3.88 +-0.99, 0.00, 49.42, 50.58, -1.15 +-0.99, 0.00, 51.90, 48.10, 3.80 +-0.99, 0.00, 51.90, 48.10, 3.81 +-0.92, 0.00, 49.38, 50.62, -1.23 +-0.92, 0.00, 51.86, 48.14, 3.72 +-0.92, 0.00, 51.86, 48.14, 3.73 +-0.92, 0.00, 51.87, 48.13, 3.73 +-0.92, 0.00, 51.87, 48.13, 3.74 +-0.92, 0.00, 51.87, 48.13, 3.75 +-0.92, 0.00, 51.88, 48.12, 3.75 +-0.92, 0.00, 51.88, 48.12, 3.76 +-0.92, 0.00, 51.88, 48.12, 3.77 +-0.92, 0.00, 51.89, 48.11, 3.78 +-0.79, 0.00, 46.85, 53.15, -6.30 +-0.79, 0.00, 51.79, 48.21, 3.59 +-0.79, 0.00, 51.80, 48.20, 3.60 +-0.79, 0.00, 51.80, 48.20, 3.60 +-0.79, 0.00, 51.80, 48.20, 3.61 +-0.79, 0.00, 51.81, 48.19, 3.61 +-0.73, 0.00, 49.29, 50.71, -1.42 +-0.73, 0.00, 51.76, 48.24, 3.53 +-0.73, 0.00, 51.77, 48.23, 3.53 +-0.73, 0.00, 51.77, 48.23, 3.54 +-0.66, 0.00, 49.25, 50.75, -1.50 +-0.66, 0.00, 51.72, 48.28, 3.45 +-0.66, 0.00, 51.73, 48.27, 3.45 +-0.66, 0.00, 51.73, 48.27, 3.46 +-0.66, 0.00, 51.73, 48.27, 3.46 +-0.66, 0.00, 51.73, 48.27, 3.47 +-0.66, 0.00, 51.74, 48.26, 3.47 +-0.66, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 51.74, 48.26, 3.49 +-0.66, 0.00, 51.75, 48.25, 3.49 +-0.66, 0.00, 51.75, 48.25, 3.50 +-0.53, 0.00, 46.71, 53.29, -6.58 +-0.53, 0.00, 51.65, 48.35, 3.31 +-0.53, 0.00, 51.66, 48.34, 3.31 +-0.53, 0.00, 51.66, 48.34, 3.31 +-0.53, 0.00, 51.66, 48.34, 3.32 +-0.53, 0.00, 51.66, 48.34, 3.32 +-0.46, 0.00, 49.14, 50.86, -1.72 +-0.46, 0.00, 51.62, 48.38, 3.23 +-0.46, 0.00, 51.62, 48.38, 3.23 +-0.46, 0.00, 51.62, 48.38, 3.24 +-0.46, 0.00, 51.62, 48.38, 3.24 +-0.46, 0.00, 51.62, 48.38, 3.24 +-0.46, 0.00, 51.62, 48.38, 3.25 +-0.46, 0.00, 51.63, 48.37, 3.25 +-0.40, 0.00, 49.11, 50.89, -1.79 +-0.40, 0.00, 51.58, 48.42, 3.16 +-0.40, 0.00, 51.58, 48.42, 3.16 +-0.40, 0.00, 51.58, 48.42, 3.16 +-0.40, 0.00, 51.58, 48.42, 3.17 +-0.40, 0.00, 51.59, 48.41, 3.17 +-0.26, 0.00, 46.54, 53.46, -6.91 +-0.26, 0.00, 51.49, 48.51, 2.98 +-0.26, 0.00, 51.49, 48.51, 2.98 +-0.26, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 48.97, 51.03, -2.06 +-0.20, 0.00, 51.44, 48.56, 2.88 +-0.20, 0.00, 51.44, 48.56, 2.89 +-0.20, 0.00, 51.44, 48.56, 2.89 +-0.20, 0.00, 51.44, 48.56, 2.89 +-0.20, 0.00, 51.45, 48.55, 2.89 +-0.13, 0.00, 48.92, 51.08, -2.15 +-0.13, 0.00, 51.40, 48.60, 2.79 +-0.13, 0.00, 51.40, 48.60, 2.79 +-0.13, 0.00, 51.40, 48.60, 2.80 +0.00, 0.00, 46.36, 53.64, -7.29 +0.00, 0.00, 51.30, 48.70, 2.60 +0.00, 0.00, 51.30, 48.70, 2.60 +0.00, 0.00, 51.30, 48.70, 2.60 +0.00, 0.00, 51.30, 48.70, 2.60 +0.00, 0.00, 51.30, 48.70, 2.60 +0.07, 0.00, 48.78, 51.22, -2.45 +0.07, 0.00, 51.25, 48.75, 2.50 +0.07, 0.00, 51.25, 48.75, 2.50 +0.13, 0.00, 48.73, 51.27, -2.55 +0.13, 0.00, 51.20, 48.80, 2.40 +0.13, 0.00, 51.20, 48.80, 2.40 +0.13, 0.00, 51.20, 48.80, 2.39 +0.26, 0.00, 46.15, 53.85, -7.69 +0.26, 0.00, 51.10, 48.90, 2.19 +0.26, 0.00, 51.10, 48.90, 2.19 +0.26, 0.00, 51.09, 48.91, 2.19 +0.33, 0.00, 48.57, 51.43, -2.86 +0.33, 0.00, 51.04, 48.96, 2.09 +0.33, 0.00, 51.04, 48.96, 2.08 +0.33, 0.00, 51.04, 48.96, 2.08 +0.40, 0.00, 48.52, 51.48, -2.97 +0.40, 0.00, 50.99, 49.01, 1.98 +0.40, 0.00, 50.99, 49.01, 1.97 +0.40, 0.00, 50.98, 49.02, 1.97 +0.40, 0.00, 50.98, 49.02, 1.97 +0.53, 0.00, 45.94, 54.06, -8.12 +0.53, 0.00, 50.88, 49.12, 1.76 +0.53, 0.00, 50.88, 49.12, 1.76 +0.53, 0.00, 50.88, 49.12, 1.75 +0.59, 0.00, 48.35, 51.65, -3.29 +0.59, 0.00, 50.82, 49.18, 1.65 +0.59, 0.00, 50.82, 49.18, 1.64 +0.59, 0.00, 50.82, 49.18, 1.64 +0.59, 0.00, 50.82, 49.18, 1.63 +0.59, 0.00, 50.81, 49.19, 1.63 +0.59, 0.00, 50.81, 49.19, 1.62 +0.59, 0.00, 50.81, 49.19, 1.62 +0.66, 0.00, 48.29, 51.71, -3.43 +0.66, 0.00, 50.75, 49.25, 1.51 +0.66, 0.00, 50.75, 49.25, 1.50 +0.66, 0.00, 50.75, 49.25, 1.50 +0.66, 0.00, 50.75, 49.25, 1.49 +0.66, 0.00, 50.74, 49.26, 1.49 +0.66, 0.00, 50.74, 49.26, 1.48 +0.66, 0.00, 50.74, 49.26, 1.48 +0.66, 0.00, 50.74, 49.26, 1.48 +0.66, 0.00, 50.74, 49.26, 1.47 +0.66, 0.00, 50.73, 49.27, 1.47 +0.66, 0.00, 50.73, 49.27, 1.46 +0.66, 0.00, 50.73, 49.27, 1.46 +0.66, 0.00, 50.73, 49.27, 1.45 +0.66, 0.00, 50.72, 49.28, 1.45 +0.79, 0.00, 45.68, 54.32, -8.65 +0.66, 0.00, 55.66, 44.34, 11.32 +0.79, 0.00, 45.67, 54.33, -8.66 +0.79, 0.00, 50.61, 49.39, 1.22 +0.79, 0.00, 50.61, 49.39, 1.22 +0.79, 0.00, 50.61, 49.39, 1.21 +0.79, 0.00, 50.60, 49.40, 1.21 +0.79, 0.00, 50.60, 49.40, 1.20 +0.66, 0.00, 55.64, 44.36, 11.28 +0.66, 0.00, 50.69, 49.31, 1.39 +0.66, 0.00, 50.69, 49.31, 1.38 +0.66, 0.00, 50.69, 49.31, 1.38 +0.66, 0.00, 50.69, 49.31, 1.37 +0.66, 0.00, 50.68, 49.32, 1.37 +0.66, 0.00, 50.68, 49.32, 1.36 +0.66, 0.00, 50.68, 49.32, 1.36 +0.66, 0.00, 50.68, 49.32, 1.35 +0.66, 0.00, 50.67, 49.33, 1.35 +0.66, 0.00, 50.67, 49.33, 1.34 +0.59, 0.00, 53.19, 46.81, 6.38 +0.59, 0.00, 50.72, 49.28, 1.43 +0.59, 0.00, 50.72, 49.28, 1.43 +0.59, 0.00, 50.71, 49.29, 1.43 +0.59, 0.00, 50.71, 49.29, 1.42 +0.59, 0.00, 50.71, 49.29, 1.42 +0.59, 0.00, 50.71, 49.29, 1.41 +0.59, 0.00, 50.70, 49.30, 1.41 +0.59, 0.00, 50.70, 49.30, 1.40 +0.53, 0.00, 53.22, 46.78, 6.44 +0.53, 0.00, 50.75, 49.25, 1.49 +0.53, 0.00, 50.75, 49.25, 1.49 +0.53, 0.00, 50.74, 49.26, 1.49 +0.53, 0.00, 50.74, 49.26, 1.48 +0.53, 0.00, 50.74, 49.26, 1.48 +0.53, 0.00, 50.74, 49.26, 1.47 +0.53, 0.00, 50.74, 49.26, 1.47 +0.53, 0.00, 50.73, 49.27, 1.47 +0.53, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 55.77, 44.23, 11.55 +0.40, 0.00, 50.83, 49.17, 1.65 +0.40, 0.00, 50.83, 49.17, 1.65 +0.40, 0.00, 50.82, 49.18, 1.65 +0.40, 0.00, 50.82, 49.18, 1.65 +0.40, 0.00, 50.82, 49.18, 1.64 +0.40, 0.00, 50.82, 49.18, 1.64 +0.40, 0.00, 50.82, 49.18, 1.64 +0.40, 0.00, 50.82, 49.18, 1.63 +0.40, 0.00, 50.82, 49.18, 1.63 +0.40, 0.00, 50.81, 49.19, 1.63 +0.40, 0.00, 50.81, 49.19, 1.62 +0.33, 0.00, 53.33, 46.67, 6.67 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.71 +0.33, 0.00, 50.86, 49.14, 1.71 +0.40, 0.00, 48.33, 51.67, -3.33 +0.33, 0.00, 53.32, 46.68, 6.65 +0.40, 0.00, 48.33, 51.67, -3.34 +0.33, 0.00, 53.32, 46.68, 6.64 +0.33, 0.00, 50.85, 49.15, 1.70 +0.33, 0.00, 50.85, 49.15, 1.70 +0.33, 0.00, 50.85, 49.15, 1.69 +0.33, 0.00, 50.85, 49.15, 1.69 +0.33, 0.00, 50.84, 49.16, 1.69 +0.33, 0.00, 50.84, 49.16, 1.69 +0.33, 0.00, 50.84, 49.16, 1.68 +0.26, 0.00, 53.36, 46.64, 6.72 +0.26, 0.00, 50.89, 49.11, 1.78 +0.26, 0.00, 50.89, 49.11, 1.78 +0.26, 0.00, 50.89, 49.11, 1.77 +0.26, 0.00, 50.89, 49.11, 1.77 +0.26, 0.00, 50.89, 49.11, 1.77 +0.26, 0.00, 50.88, 49.12, 1.77 +0.26, 0.00, 50.88, 49.12, 1.77 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.75 +0.13, 0.00, 55.92, 44.08, 11.84 +0.13, 0.00, 50.98, 49.02, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.93 +0.13, 0.00, 50.97, 49.03, 1.93 +0.13, 0.00, 50.97, 49.03, 1.93 +0.13, 0.00, 50.97, 49.03, 1.93 +0.07, 0.00, 53.49, 46.51, 6.97 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.13, 0.00, 48.49, 51.51, -3.02 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.26, 0.00, 45.91, 54.09, -8.18 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.69 +0.26, 0.00, 50.85, 49.15, 1.69 +0.13, 0.00, 55.89, 44.11, 11.78 +0.13, 0.00, 50.94, 49.06, 1.89 +0.13, 0.00, 50.94, 49.06, 1.89 +0.13, 0.00, 50.94, 49.06, 1.89 +0.13, 0.00, 50.94, 49.06, 1.88 +0.13, 0.00, 50.94, 49.06, 1.88 +0.13, 0.00, 50.94, 49.06, 1.88 +0.26, 0.00, 45.90, 54.10, -8.20 +0.26, 0.00, 50.84, 49.16, 1.68 +0.26, 0.00, 50.84, 49.16, 1.68 +0.26, 0.00, 50.84, 49.16, 1.68 +0.26, 0.00, 50.84, 49.16, 1.67 +0.26, 0.00, 50.84, 49.16, 1.67 +0.26, 0.00, 50.84, 49.16, 1.67 +0.26, 0.00, 50.83, 49.17, 1.67 +0.26, 0.00, 50.83, 49.17, 1.67 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 55.87, 44.13, 11.74 +0.26, 0.00, 45.88, 54.12, -8.24 +0.26, 0.00, 50.83, 49.17, 1.65 +0.26, 0.00, 50.82, 49.18, 1.65 +0.26, 0.00, 50.82, 49.18, 1.65 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.63 +0.26, 0.00, 50.82, 49.18, 1.63 +0.26, 0.00, 50.82, 49.18, 1.63 +0.26, 0.00, 50.81, 49.19, 1.63 +0.26, 0.00, 50.81, 49.19, 1.63 +0.26, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 55.85, 44.15, 11.71 +0.13, 0.00, 50.91, 49.09, 1.82 +0.13, 0.00, 50.91, 49.09, 1.82 +0.13, 0.00, 50.91, 49.09, 1.82 +0.13, 0.00, 50.91, 49.09, 1.82 +0.13, 0.00, 50.91, 49.09, 1.82 +0.26, 0.00, 45.86, 54.14, -8.27 +0.13, 0.00, 55.85, 44.15, 11.70 +0.26, 0.00, 45.86, 54.14, -8.27 +0.26, 0.00, 50.81, 49.19, 1.61 +0.26, 0.00, 50.80, 49.20, 1.61 +0.26, 0.00, 50.80, 49.20, 1.61 +0.26, 0.00, 50.80, 49.20, 1.61 +0.26, 0.00, 50.80, 49.20, 1.60 +0.13, 0.00, 55.84, 44.16, 11.69 +0.13, 0.00, 50.90, 49.10, 1.80 +0.13, 0.00, 50.90, 49.10, 1.80 +0.13, 0.00, 50.90, 49.10, 1.80 +0.13, 0.00, 50.90, 49.10, 1.80 +0.07, 0.00, 53.42, 46.58, 6.84 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.94, 49.06, 1.89 +0.07, 0.00, 50.94, 49.06, 1.89 +0.07, 0.00, 50.94, 49.06, 1.89 +0.07, 0.00, 50.94, 49.06, 1.89 +0.00, 0.00, 53.47, 46.53, 6.93 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +-0.13, 0.00, 56.04, 43.96, 12.07 +-0.13, 0.00, 51.09, 48.91, 2.19 +-0.13, 0.00, 51.09, 48.91, 2.19 +0.00, 0.00, 46.05, 53.95, -7.90 +-0.13, 0.00, 56.04, 43.96, 12.08 +-0.13, 0.00, 51.09, 48.91, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.20, 0.00, 53.62, 46.38, 7.24 +-0.13, 0.00, 48.63, 51.37, -2.74 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.20, 0.00, 53.62, 46.38, 7.25 +-0.13, 0.00, 48.63, 51.37, -2.74 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +0.00, 0.00, 46.06, 53.94, -7.87 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +-0.13, 0.00, 56.05, 43.95, 12.10 +-0.13, 0.00, 51.11, 48.89, 2.22 +-0.13, 0.00, 51.11, 48.89, 2.22 +0.00, 0.00, 46.07, 53.93, -7.87 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.07, 0.00, 48.49, 51.51, -3.02 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.00, 0.00, 53.48, 46.52, 6.95 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 56.05, 43.95, 12.10 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.20, 0.00, 53.63, 46.37, 7.26 +-0.20, 0.00, 51.16, 48.84, 2.31 +-0.20, 0.00, 51.16, 48.84, 2.31 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.26, 0.00, 53.68, 46.32, 7.37 +-0.26, 0.00, 51.21, 48.79, 2.43 +-0.26, 0.00, 51.21, 48.79, 2.43 +-0.26, 0.00, 51.22, 48.78, 2.43 +-0.26, 0.00, 51.22, 48.78, 2.43 +-0.26, 0.00, 51.22, 48.78, 2.43 +-0.26, 0.00, 51.22, 48.78, 2.44 +-0.26, 0.00, 51.22, 48.78, 2.44 +-0.40, 0.00, 56.26, 43.74, 12.53 +-0.40, 0.00, 51.32, 48.68, 2.64 +-0.40, 0.00, 51.32, 48.68, 2.64 +-0.40, 0.00, 51.32, 48.68, 2.65 +-0.40, 0.00, 51.33, 48.67, 2.65 +-0.40, 0.00, 51.33, 48.67, 2.65 +-0.40, 0.00, 51.33, 48.67, 2.66 +-0.40, 0.00, 51.33, 48.67, 2.66 +-0.40, 0.00, 51.33, 48.67, 2.66 +-0.40, 0.00, 51.33, 48.67, 2.67 +-0.40, 0.00, 51.33, 48.67, 2.67 +-0.40, 0.00, 51.34, 48.66, 2.67 +-0.40, 0.00, 51.34, 48.66, 2.67 +-0.40, 0.00, 51.34, 48.66, 2.68 +-0.46, 0.00, 53.86, 46.14, 7.72 +-0.46, 0.00, 51.39, 48.61, 2.78 +-0.46, 0.00, 51.39, 48.61, 2.79 +-0.46, 0.00, 51.40, 48.60, 2.79 +-0.46, 0.00, 51.40, 48.60, 2.79 +-0.46, 0.00, 51.40, 48.60, 2.80 +-0.46, 0.00, 51.40, 48.60, 2.80 +-0.46, 0.00, 51.40, 48.60, 2.80 +-0.46, 0.00, 51.40, 48.60, 2.81 +-0.46, 0.00, 51.41, 48.59, 2.81 +-0.46, 0.00, 51.41, 48.59, 2.81 +-0.46, 0.00, 51.41, 48.59, 2.82 +-0.46, 0.00, 51.41, 48.59, 2.82 +-0.46, 0.00, 51.41, 48.59, 2.82 +-0.40, 0.00, 48.89, 51.11, -2.21 +-0.40, 0.00, 51.37, 48.63, 2.73 +-0.40, 0.00, 51.37, 48.63, 2.73 +-0.40, 0.00, 51.37, 48.63, 2.74 +-0.40, 0.00, 51.37, 48.63, 2.74 +-0.40, 0.00, 51.37, 48.63, 2.74 +-0.46, 0.00, 53.89, 46.11, 7.79 +-0.46, 0.00, 51.42, 48.58, 2.85 +-0.46, 0.00, 51.43, 48.57, 2.85 +-0.46, 0.00, 51.43, 48.57, 2.86 +-0.46, 0.00, 51.43, 48.57, 2.86 +-0.46, 0.00, 51.43, 48.57, 2.86 +-0.46, 0.00, 51.43, 48.57, 2.87 +-0.46, 0.00, 51.44, 48.56, 2.87 +-0.46, 0.00, 51.44, 48.56, 2.87 +-0.46, 0.00, 51.44, 48.56, 2.88 +-0.40, 0.00, 48.92, 51.08, -2.16 +-0.40, 0.00, 51.39, 48.61, 2.78 +-0.40, 0.00, 51.39, 48.61, 2.79 +-0.26, 0.00, 46.35, 53.65, -7.30 +-0.26, 0.00, 51.30, 48.70, 2.59 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.61 +-0.26, 0.00, 51.30, 48.70, 2.61 +-0.26, 0.00, 51.30, 48.70, 2.61 +-0.26, 0.00, 51.31, 48.69, 2.61 +-0.26, 0.00, 51.31, 48.69, 2.61 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.20, 0.00, 48.79, 51.21, -2.42 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.13, 0.00, 48.74, 51.26, -2.51 +-0.13, 0.00, 51.22, 48.78, 2.43 +-0.13, 0.00, 51.22, 48.78, 2.43 +-0.13, 0.00, 51.22, 48.78, 2.43 +-0.13, 0.00, 51.22, 48.78, 2.43 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +0.00, 0.00, 46.18, 53.82, -7.64 +0.00, 0.00, 51.12, 48.88, 2.25 +0.00, 0.00, 51.12, 48.88, 2.25 +0.00, 0.00, 51.12, 48.88, 2.25 +0.07, 0.00, 48.60, 51.40, -2.80 +0.07, 0.00, 51.07, 48.93, 2.15 +0.13, 0.00, 48.55, 51.45, -2.90 +0.13, 0.00, 51.02, 48.98, 2.05 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.03 +0.26, 0.00, 45.97, 54.03, -8.05 +0.26, 0.00, 50.92, 49.08, 1.83 +0.26, 0.00, 50.92, 49.08, 1.83 +0.33, 0.00, 48.39, 51.61, -3.21 +0.33, 0.00, 50.86, 49.14, 1.73 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.40, 0.00, 48.34, 51.66, -3.32 +0.40, 0.00, 50.81, 49.19, 1.62 +0.40, 0.00, 50.81, 49.19, 1.61 +0.40, 0.00, 50.81, 49.19, 1.61 +0.40, 0.00, 50.80, 49.20, 1.61 +0.40, 0.00, 50.80, 49.20, 1.61 +0.40, 0.00, 50.80, 49.20, 1.60 +0.40, 0.00, 50.80, 49.20, 1.60 +0.40, 0.00, 50.80, 49.20, 1.60 +0.40, 0.00, 50.80, 49.20, 1.59 +0.40, 0.00, 50.80, 49.20, 1.59 +0.40, 0.00, 50.79, 49.21, 1.59 +0.40, 0.00, 50.79, 49.21, 1.58 +0.53, 0.00, 45.75, 54.25, -8.50 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.37 +0.59, 0.00, 48.16, 51.84, -3.68 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.25 +0.59, 0.00, 50.63, 49.37, 1.25 +0.59, 0.00, 50.62, 49.38, 1.25 +0.59, 0.00, 50.62, 49.38, 1.24 +0.59, 0.00, 50.62, 49.38, 1.24 +0.59, 0.00, 50.62, 49.38, 1.23 +0.59, 0.00, 50.61, 49.39, 1.23 +0.59, 0.00, 50.61, 49.39, 1.22 +0.59, 0.00, 50.61, 49.39, 1.22 +0.59, 0.00, 50.61, 49.39, 1.21 +0.59, 0.00, 50.61, 49.39, 1.21 +0.59, 0.00, 50.60, 49.40, 1.21 +0.66, 0.00, 48.08, 51.92, -3.84 +0.66, 0.00, 50.55, 49.45, 1.10 +0.66, 0.00, 50.55, 49.45, 1.09 +0.66, 0.00, 50.54, 49.46, 1.09 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.07 +0.79, 0.00, 45.49, 54.51, -9.02 +0.79, 0.00, 50.43, 49.57, 0.86 +0.66, 0.00, 55.47, 44.53, 10.94 +0.66, 0.00, 50.53, 49.47, 1.05 +0.66, 0.00, 50.52, 49.48, 1.05 +0.66, 0.00, 50.52, 49.48, 1.04 +0.66, 0.00, 50.52, 49.48, 1.04 +0.66, 0.00, 50.52, 49.48, 1.03 +0.66, 0.00, 50.51, 49.49, 1.03 +0.66, 0.00, 50.51, 49.49, 1.02 +0.66, 0.00, 50.51, 49.49, 1.02 +0.66, 0.00, 50.51, 49.49, 1.01 +0.66, 0.00, 50.50, 49.50, 1.01 +0.66, 0.00, 50.50, 49.50, 1.00 +0.66, 0.00, 50.50, 49.50, 1.00 +0.79, 0.00, 45.45, 54.55, -9.10 +0.79, 0.00, 50.39, 49.61, 0.79 +0.79, 0.00, 50.39, 49.61, 0.78 +0.79, 0.00, 50.39, 49.61, 0.77 +0.79, 0.00, 50.38, 49.62, 0.77 +0.66, 0.00, 55.42, 44.58, 10.85 +0.66, 0.00, 50.48, 49.52, 0.96 +0.66, 0.00, 50.48, 49.52, 0.95 +0.66, 0.00, 50.47, 49.53, 0.95 +0.66, 0.00, 50.47, 49.53, 0.94 +0.59, 0.00, 52.99, 47.01, 5.98 +0.59, 0.00, 50.52, 49.48, 1.03 +0.59, 0.00, 50.51, 49.49, 1.03 +0.59, 0.00, 50.51, 49.49, 1.02 +0.59, 0.00, 50.51, 49.49, 1.02 +0.59, 0.00, 50.51, 49.49, 1.01 +0.59, 0.00, 50.50, 49.50, 1.01 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 0.99 +0.59, 0.00, 50.49, 49.51, 0.99 +0.59, 0.00, 50.49, 49.51, 0.98 +0.59, 0.00, 50.49, 49.51, 0.98 +0.59, 0.00, 50.49, 49.51, 0.97 +0.53, 0.00, 53.01, 46.99, 6.01 +0.53, 0.00, 50.53, 49.47, 1.06 +0.53, 0.00, 50.53, 49.47, 1.06 +0.53, 0.00, 50.53, 49.47, 1.06 +0.40, 0.00, 55.57, 44.43, 11.14 +0.40, 0.00, 50.62, 49.38, 1.25 +0.40, 0.00, 50.62, 49.38, 1.25 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.23 +0.40, 0.00, 50.62, 49.38, 1.23 +0.40, 0.00, 50.61, 49.39, 1.23 +0.40, 0.00, 50.61, 49.39, 1.22 +0.40, 0.00, 50.61, 49.39, 1.22 +0.40, 0.00, 50.61, 49.39, 1.22 +0.40, 0.00, 50.61, 49.39, 1.22 +0.33, 0.00, 53.13, 46.87, 6.26 +0.33, 0.00, 50.65, 49.35, 1.31 +0.33, 0.00, 50.65, 49.35, 1.31 +0.33, 0.00, 50.65, 49.35, 1.31 +0.33, 0.00, 50.65, 49.35, 1.30 +0.26, 0.00, 53.17, 46.83, 6.34 +0.26, 0.00, 50.70, 49.30, 1.40 +0.26, 0.00, 50.70, 49.30, 1.40 +0.26, 0.00, 50.70, 49.30, 1.39 +0.26, 0.00, 50.70, 49.30, 1.39 +0.26, 0.00, 50.69, 49.31, 1.39 +0.13, 0.00, 55.74, 44.26, 11.47 +0.13, 0.00, 50.79, 49.21, 1.59 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.07, 0.00, 53.31, 46.69, 6.62 +0.07, 0.00, 50.84, 49.16, 1.68 +0.07, 0.00, 50.84, 49.16, 1.68 +0.07, 0.00, 50.84, 49.16, 1.68 +0.00, 0.00, 53.36, 46.64, 6.72 +0.00, 0.00, 50.89, 49.11, 1.77 +0.00, 0.00, 50.89, 49.11, 1.77 +0.00, 0.00, 50.89, 49.11, 1.77 +0.00, 0.00, 50.89, 49.11, 1.77 +0.00, 0.00, 50.89, 49.11, 1.77 +-0.13, 0.00, 55.93, 44.07, 11.86 +-0.13, 0.00, 50.99, 49.01, 1.97 +-0.13, 0.00, 50.99, 49.01, 1.97 +-0.13, 0.00, 50.99, 49.01, 1.98 +-0.13, 0.00, 50.99, 49.01, 1.98 +-0.13, 0.00, 50.99, 49.01, 1.98 +-0.13, 0.00, 50.99, 49.01, 1.98 +-0.20, 0.00, 53.51, 46.49, 7.02 +-0.20, 0.00, 51.04, 48.96, 2.08 +-0.20, 0.00, 51.04, 48.96, 2.08 +-0.20, 0.00, 51.04, 48.96, 2.08 +-0.20, 0.00, 51.04, 48.96, 2.09 +-0.20, 0.00, 51.04, 48.96, 2.09 +-0.26, 0.00, 53.57, 46.43, 7.13 +-0.26, 0.00, 51.09, 48.91, 2.19 +-0.26, 0.00, 51.10, 48.90, 2.19 +-0.40, 0.00, 56.14, 43.86, 12.28 +-0.40, 0.00, 51.20, 48.80, 2.40 +-0.40, 0.00, 51.20, 48.80, 2.40 +-0.40, 0.00, 51.20, 48.80, 2.40 +-0.40, 0.00, 51.20, 48.80, 2.40 +-0.40, 0.00, 51.20, 48.80, 2.41 +-0.40, 0.00, 51.20, 48.80, 2.41 +-0.40, 0.00, 51.21, 48.79, 2.41 +-0.46, 0.00, 53.73, 46.27, 7.46 +-0.46, 0.00, 51.26, 48.74, 2.52 +-0.46, 0.00, 51.26, 48.74, 2.52 +-0.46, 0.00, 51.26, 48.74, 2.53 +-0.46, 0.00, 51.26, 48.74, 2.53 +-0.46, 0.00, 51.27, 48.73, 2.53 +-0.46, 0.00, 51.27, 48.73, 2.54 +-0.46, 0.00, 51.27, 48.73, 2.54 +-0.53, 0.00, 53.79, 46.21, 7.59 +-0.53, 0.00, 51.32, 48.68, 2.65 +-0.53, 0.00, 51.33, 48.67, 2.65 +-0.66, 0.00, 56.37, 43.63, 12.74 +-0.66, 0.00, 51.43, 48.57, 2.86 +-0.66, 0.00, 51.43, 48.57, 2.86 +-0.66, 0.00, 51.43, 48.57, 2.87 +-0.66, 0.00, 51.44, 48.56, 2.87 +-0.73, 0.00, 53.96, 46.04, 7.92 +-0.73, 0.00, 51.49, 48.51, 2.98 +-0.73, 0.00, 51.49, 48.51, 2.99 +-0.73, 0.00, 51.50, 48.50, 2.99 +-0.73, 0.00, 51.50, 48.50, 3.00 +-0.73, 0.00, 51.50, 48.50, 3.00 +-0.73, 0.00, 51.50, 48.50, 3.01 +-0.73, 0.00, 51.51, 48.49, 3.02 +-0.73, 0.00, 51.51, 48.49, 3.02 +-0.73, 0.00, 51.51, 48.49, 3.03 +-0.73, 0.00, 51.52, 48.48, 3.03 +-0.79, 0.00, 54.04, 45.96, 8.08 +-0.79, 0.00, 51.57, 48.43, 3.14 +-0.79, 0.00, 51.57, 48.43, 3.15 +-0.79, 0.00, 51.58, 48.42, 3.15 +-0.79, 0.00, 51.58, 48.42, 3.16 +-0.79, 0.00, 51.58, 48.42, 3.17 +-0.79, 0.00, 51.59, 48.41, 3.17 +-0.79, 0.00, 51.59, 48.41, 3.18 +-0.92, 0.00, 56.64, 43.36, 13.27 +-0.92, 0.00, 51.69, 48.31, 3.39 +-0.92, 0.00, 51.70, 48.30, 3.40 +-0.92, 0.00, 51.70, 48.30, 3.40 +-0.92, 0.00, 51.71, 48.29, 3.41 +-0.92, 0.00, 51.71, 48.29, 3.42 +-0.92, 0.00, 51.71, 48.29, 3.42 +-0.92, 0.00, 51.72, 48.28, 3.43 +-0.92, 0.00, 51.72, 48.28, 3.44 +-0.79, 0.00, 46.68, 53.32, -6.64 +-0.79, 0.00, 51.63, 48.37, 3.25 +-0.79, 0.00, 51.63, 48.37, 3.26 +-0.79, 0.00, 51.63, 48.37, 3.26 +-0.79, 0.00, 51.63, 48.37, 3.27 +-0.79, 0.00, 51.64, 48.36, 3.28 +-0.79, 0.00, 51.64, 48.36, 3.28 +-0.79, 0.00, 51.64, 48.36, 3.29 +-0.79, 0.00, 51.65, 48.35, 3.29 +-0.79, 0.00, 51.65, 48.35, 3.30 +-0.79, 0.00, 51.65, 48.35, 3.31 +-0.92, 0.00, 56.70, 43.30, 13.40 +-0.92, 0.00, 51.76, 48.24, 3.52 +-0.92, 0.00, 51.76, 48.24, 3.52 +-0.92, 0.00, 51.77, 48.23, 3.53 +-0.79, 0.00, 46.73, 53.27, -6.55 +-0.79, 0.00, 51.67, 48.33, 3.34 +-0.79, 0.00, 51.68, 48.32, 3.35 +-0.79, 0.00, 51.68, 48.32, 3.36 +-0.79, 0.00, 51.68, 48.32, 3.36 +-0.73, 0.00, 49.16, 50.84, -1.67 +-0.73, 0.00, 51.64, 48.36, 3.27 +-0.73, 0.00, 51.64, 48.36, 3.28 +-0.73, 0.00, 51.64, 48.36, 3.29 +-0.73, 0.00, 51.65, 48.35, 3.29 +-0.73, 0.00, 51.65, 48.35, 3.30 +-0.73, 0.00, 51.65, 48.35, 3.30 +-0.73, 0.00, 51.65, 48.35, 3.31 +-0.73, 0.00, 51.66, 48.34, 3.31 +-0.73, 0.00, 51.66, 48.34, 3.32 +-0.73, 0.00, 51.66, 48.34, 3.32 +-0.73, 0.00, 51.66, 48.34, 3.33 +-0.73, 0.00, 51.67, 48.33, 3.33 +-0.73, 0.00, 51.67, 48.33, 3.34 +-0.73, 0.00, 51.67, 48.33, 3.35 +-0.73, 0.00, 51.68, 48.32, 3.35 +-0.73, 0.00, 51.68, 48.32, 3.36 +-0.73, 0.00, 51.68, 48.32, 3.36 +-0.66, 0.00, 49.16, 50.84, -1.68 +-0.66, 0.00, 51.64, 48.36, 3.27 +-0.66, 0.00, 51.64, 48.36, 3.28 +-0.66, 0.00, 51.64, 48.36, 3.28 +-0.66, 0.00, 51.64, 48.36, 3.29 +-0.66, 0.00, 51.65, 48.35, 3.29 +-0.66, 0.00, 51.65, 48.35, 3.30 +-0.66, 0.00, 51.65, 48.35, 3.30 +-0.66, 0.00, 51.65, 48.35, 3.31 +-0.66, 0.00, 51.66, 48.34, 3.31 +-0.66, 0.00, 51.66, 48.34, 3.32 +-0.66, 0.00, 51.66, 48.34, 3.32 +-0.66, 0.00, 51.66, 48.34, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.34 +-0.66, 0.00, 51.67, 48.33, 3.34 +-0.66, 0.00, 51.67, 48.33, 3.35 +-0.66, 0.00, 51.68, 48.32, 3.35 +-0.66, 0.00, 51.68, 48.32, 3.36 +-0.66, 0.00, 51.68, 48.32, 3.36 +-0.66, 0.00, 51.68, 48.32, 3.37 +-0.53, 0.00, 46.64, 53.36, -6.71 +-0.53, 0.00, 51.59, 48.41, 3.18 +-0.53, 0.00, 51.59, 48.41, 3.18 +-0.46, 0.00, 49.07, 50.93, -1.86 +-0.53, 0.00, 54.07, 45.93, 8.13 +-0.53, 0.00, 51.60, 48.40, 3.19 +-0.46, 0.00, 49.08, 50.92, -1.85 +-0.53, 0.00, 54.07, 45.93, 8.14 +-0.53, 0.00, 51.60, 48.40, 3.20 +-0.53, 0.00, 51.60, 48.40, 3.21 +-0.53, 0.00, 51.61, 48.39, 3.21 +-0.53, 0.00, 51.61, 48.39, 3.22 +-0.53, 0.00, 51.61, 48.39, 3.22 +-0.53, 0.00, 51.61, 48.39, 3.22 +-0.53, 0.00, 51.61, 48.39, 3.23 +-0.53, 0.00, 51.62, 48.38, 3.23 +-0.53, 0.00, 51.62, 48.38, 3.24 +-0.53, 0.00, 51.62, 48.38, 3.24 +-0.46, 0.00, 49.10, 50.90, -1.80 +-0.46, 0.00, 51.57, 48.43, 3.15 +-0.46, 0.00, 51.58, 48.42, 3.15 +-0.46, 0.00, 51.58, 48.42, 3.15 +-0.40, 0.00, 49.06, 50.94, -1.89 +-0.40, 0.00, 51.53, 48.47, 3.06 +-0.40, 0.00, 51.53, 48.47, 3.06 +-0.40, 0.00, 51.53, 48.47, 3.07 +-0.40, 0.00, 51.53, 48.47, 3.07 +-0.40, 0.00, 51.54, 48.46, 3.07 +-0.40, 0.00, 51.54, 48.46, 3.08 +-0.40, 0.00, 51.54, 48.46, 3.08 +-0.40, 0.00, 51.54, 48.46, 3.08 +-0.40, 0.00, 51.54, 48.46, 3.08 +-0.46, 0.00, 54.07, 45.93, 8.13 +-0.40, 0.00, 49.07, 50.93, -1.85 +-0.46, 0.00, 54.07, 45.93, 8.14 +-0.40, 0.00, 49.08, 50.92, -1.85 +-0.40, 0.00, 51.55, 48.45, 3.10 +-0.40, 0.00, 51.55, 48.45, 3.10 +-0.26, 0.00, 46.51, 53.49, -6.98 +-0.26, 0.00, 51.45, 48.55, 2.91 +-0.26, 0.00, 51.46, 48.54, 2.91 +-0.26, 0.00, 51.46, 48.54, 2.91 +-0.26, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 48.94, 51.06, -2.13 +-0.20, 0.00, 51.41, 48.59, 2.82 +-0.20, 0.00, 51.41, 48.59, 2.82 +-0.20, 0.00, 51.41, 48.59, 2.82 +-0.20, 0.00, 51.41, 48.59, 2.82 +-0.20, 0.00, 51.41, 48.59, 2.83 +-0.20, 0.00, 51.41, 48.59, 2.83 +-0.20, 0.00, 51.41, 48.59, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.13, 0.00, 48.90, 51.10, -2.20 +-0.13, 0.00, 51.37, 48.63, 2.75 +-0.13, 0.00, 51.37, 48.63, 2.75 +-0.13, 0.00, 51.37, 48.63, 2.75 +-0.13, 0.00, 51.37, 48.63, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.39, 48.61, 2.77 +-0.13, 0.00, 51.39, 48.61, 2.77 +-0.13, 0.00, 51.39, 48.61, 2.77 +-0.13, 0.00, 51.39, 48.61, 2.77 +0.00, 0.00, 46.34, 53.66, -7.31 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +-0.13, 0.00, 56.33, 43.67, 12.66 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.40, 48.60, 2.79 +-0.20, 0.00, 53.92, 46.08, 7.83 +-0.20, 0.00, 51.45, 48.55, 2.89 +-0.20, 0.00, 51.45, 48.55, 2.89 +-0.20, 0.00, 51.45, 48.55, 2.89 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.91 +-0.20, 0.00, 51.45, 48.55, 2.91 +-0.20, 0.00, 51.45, 48.55, 2.91 +-0.20, 0.00, 51.45, 48.55, 2.91 +-0.20, 0.00, 51.46, 48.54, 2.91 +-0.20, 0.00, 51.46, 48.54, 2.91 +-0.20, 0.00, 51.46, 48.54, 2.91 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.26, 0.00, 53.98, 46.02, 7.97 +-0.26, 0.00, 51.51, 48.49, 3.03 +-0.26, 0.00, 51.51, 48.49, 3.03 +-0.26, 0.00, 51.51, 48.49, 3.03 +-0.26, 0.00, 51.52, 48.48, 3.03 +-0.26, 0.00, 51.52, 48.48, 3.03 +-0.26, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 49.00, 51.00, -2.01 +-0.20, 0.00, 51.47, 48.53, 2.94 +-0.20, 0.00, 51.47, 48.53, 2.94 +-0.20, 0.00, 51.47, 48.53, 2.94 +-0.20, 0.00, 51.47, 48.53, 2.94 +-0.20, 0.00, 51.47, 48.53, 2.95 +-0.20, 0.00, 51.47, 48.53, 2.95 +-0.20, 0.00, 51.47, 48.53, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.96 +-0.26, 0.00, 54.00, 46.00, 8.00 +-0.20, 0.00, 49.01, 50.99, -1.98 +-0.26, 0.00, 54.00, 46.00, 8.00 +-0.26, 0.00, 51.53, 48.47, 3.06 +-0.26, 0.00, 51.53, 48.47, 3.06 +-0.26, 0.00, 51.53, 48.47, 3.07 +-0.20, 0.00, 49.01, 50.99, -1.97 +-0.20, 0.00, 51.49, 48.51, 2.97 +-0.20, 0.00, 51.49, 48.51, 2.97 +-0.20, 0.00, 51.49, 48.51, 2.97 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.99 +-0.20, 0.00, 51.49, 48.51, 2.99 +-0.20, 0.00, 51.49, 48.51, 2.99 +-0.20, 0.00, 51.49, 48.51, 2.99 +-0.20, 0.00, 51.50, 48.50, 2.99 +-0.26, 0.00, 54.02, 45.98, 8.04 +-0.26, 0.00, 51.55, 48.45, 3.09 +-0.26, 0.00, 51.55, 48.45, 3.10 +-0.26, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 49.03, 50.97, -1.94 +-0.20, 0.00, 51.50, 48.50, 3.00 +-0.20, 0.00, 51.50, 48.50, 3.00 +-0.20, 0.00, 51.50, 48.50, 3.01 +-0.20, 0.00, 51.50, 48.50, 3.01 +-0.20, 0.00, 51.50, 48.50, 3.01 +-0.20, 0.00, 51.50, 48.50, 3.01 +-0.20, 0.00, 51.51, 48.49, 3.01 +-0.20, 0.00, 51.51, 48.49, 3.01 +-0.20, 0.00, 51.51, 48.49, 3.01 +-0.20, 0.00, 51.51, 48.49, 3.02 +-0.20, 0.00, 51.51, 48.49, 3.02 +-0.20, 0.00, 51.51, 48.49, 3.02 +-0.26, 0.00, 54.03, 45.97, 8.06 +-0.26, 0.00, 51.56, 48.44, 3.12 +-0.26, 0.00, 51.56, 48.44, 3.12 +-0.26, 0.00, 51.56, 48.44, 3.13 +-0.26, 0.00, 51.56, 48.44, 3.13 +-0.26, 0.00, 51.56, 48.44, 3.13 +-0.26, 0.00, 51.57, 48.43, 3.13 +-0.26, 0.00, 51.57, 48.43, 3.13 +-0.20, 0.00, 49.05, 50.95, -1.91 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.05 +-0.20, 0.00, 51.52, 48.48, 3.05 +-0.26, 0.00, 54.05, 45.95, 8.09 +-0.26, 0.00, 51.58, 48.42, 3.15 +-0.26, 0.00, 51.58, 48.42, 3.15 +-0.26, 0.00, 51.58, 48.42, 3.15 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.17 +-0.20, 0.00, 49.06, 50.94, -1.87 +-0.20, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.09 +-0.20, 0.00, 51.54, 48.46, 3.09 +-0.20, 0.00, 51.54, 48.46, 3.09 +-0.20, 0.00, 51.54, 48.46, 3.09 +-0.20, 0.00, 51.55, 48.45, 3.09 +-0.20, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 49.03, 50.97, -1.95 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.51, 48.49, 3.01 +0.00, 0.00, 46.46, 53.54, -7.07 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.07, 0.00, 48.88, 51.12, -2.23 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.13, 0.00, 48.83, 51.17, -2.34 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.58 +0.13, 0.00, 51.29, 48.71, 2.58 +0.26, 0.00, 46.25, 53.75, -7.50 +0.26, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 51.19, 48.81, 2.37 +0.26, 0.00, 51.19, 48.81, 2.37 +0.26, 0.00, 51.18, 48.82, 2.37 +0.26, 0.00, 51.18, 48.82, 2.37 +0.26, 0.00, 51.18, 48.82, 2.37 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.35 +0.26, 0.00, 51.18, 48.82, 2.35 +0.26, 0.00, 51.18, 48.82, 2.35 +0.26, 0.00, 51.17, 48.83, 2.35 +0.33, 0.00, 48.65, 51.35, -2.70 +0.26, 0.00, 53.64, 46.36, 7.29 +0.33, 0.00, 48.65, 51.35, -2.70 +0.33, 0.00, 51.12, 48.88, 2.24 +0.26, 0.00, 53.64, 46.36, 7.28 +0.26, 0.00, 51.17, 48.83, 2.33 +0.26, 0.00, 51.17, 48.83, 2.33 +0.26, 0.00, 51.17, 48.83, 2.33 +0.26, 0.00, 51.16, 48.84, 2.33 +0.26, 0.00, 51.16, 48.84, 2.33 +0.26, 0.00, 51.16, 48.84, 2.32 +0.33, 0.00, 48.64, 51.36, -2.72 +0.26, 0.00, 53.63, 46.37, 7.26 +0.33, 0.00, 48.64, 51.36, -2.72 +0.33, 0.00, 51.11, 48.89, 2.22 +0.33, 0.00, 51.11, 48.89, 2.21 +0.33, 0.00, 51.11, 48.89, 2.21 +0.33, 0.00, 51.10, 48.90, 2.21 +0.33, 0.00, 51.10, 48.90, 2.21 +0.33, 0.00, 51.10, 48.90, 2.20 +0.33, 0.00, 51.10, 48.90, 2.20 +0.33, 0.00, 51.10, 48.90, 2.20 +0.33, 0.00, 51.10, 48.90, 2.20 +0.33, 0.00, 51.10, 48.90, 2.19 +0.33, 0.00, 51.10, 48.90, 2.19 +0.33, 0.00, 51.09, 48.91, 2.19 +0.33, 0.00, 51.09, 48.91, 2.19 +0.33, 0.00, 51.09, 48.91, 2.18 +0.33, 0.00, 51.09, 48.91, 2.18 +0.33, 0.00, 51.09, 48.91, 2.18 +0.33, 0.00, 51.09, 48.91, 2.18 +0.33, 0.00, 51.09, 48.91, 2.17 +0.33, 0.00, 51.09, 48.91, 2.17 +0.33, 0.00, 51.08, 48.92, 2.17 +0.33, 0.00, 51.08, 48.92, 2.17 +0.33, 0.00, 51.08, 48.92, 2.16 +0.33, 0.00, 51.08, 48.92, 2.16 +0.33, 0.00, 51.08, 48.92, 2.16 +0.40, 0.00, 48.56, 51.44, -2.89 +0.40, 0.00, 51.03, 48.97, 2.06 +0.40, 0.00, 51.03, 48.97, 2.05 +0.40, 0.00, 51.02, 48.98, 2.05 +0.40, 0.00, 51.02, 48.98, 2.05 +0.40, 0.00, 51.02, 48.98, 2.04 +0.40, 0.00, 51.02, 48.98, 2.04 +0.40, 0.00, 51.02, 48.98, 2.04 +0.40, 0.00, 51.02, 48.98, 2.03 +0.40, 0.00, 51.02, 48.98, 2.03 +0.53, 0.00, 45.97, 54.03, -8.06 +0.53, 0.00, 50.91, 49.09, 1.83 +0.53, 0.00, 50.91, 49.09, 1.82 +0.53, 0.00, 50.91, 49.09, 1.82 +0.53, 0.00, 50.91, 49.09, 1.81 +0.59, 0.00, 48.38, 51.62, -3.23 +0.59, 0.00, 50.85, 49.15, 1.71 +0.59, 0.00, 50.85, 49.15, 1.70 +0.59, 0.00, 50.85, 49.15, 1.70 +0.59, 0.00, 50.85, 49.15, 1.69 +0.66, 0.00, 48.32, 51.68, -3.36 +0.66, 0.00, 50.79, 49.21, 1.58 +0.66, 0.00, 50.79, 49.21, 1.58 +0.66, 0.00, 50.79, 49.21, 1.57 +0.66, 0.00, 50.78, 49.22, 1.57 +0.66, 0.00, 50.78, 49.22, 1.56 +0.79, 0.00, 45.74, 54.26, -8.53 +0.79, 0.00, 50.68, 49.32, 1.35 +0.79, 0.00, 50.67, 49.33, 1.35 +0.79, 0.00, 50.67, 49.33, 1.34 +0.79, 0.00, 50.67, 49.33, 1.34 +0.79, 0.00, 50.67, 49.33, 1.33 +0.79, 0.00, 50.66, 49.34, 1.32 +0.86, 0.00, 48.14, 51.86, -3.72 +0.86, 0.00, 50.61, 49.39, 1.21 +0.86, 0.00, 50.60, 49.40, 1.21 +0.86, 0.00, 50.60, 49.40, 1.20 +0.86, 0.00, 50.60, 49.40, 1.19 +0.86, 0.00, 50.59, 49.41, 1.19 +0.86, 0.00, 50.59, 49.41, 1.18 +0.86, 0.00, 50.59, 49.41, 1.17 +0.92, 0.00, 48.06, 51.94, -3.88 +0.92, 0.00, 50.53, 49.47, 1.06 +0.92, 0.00, 50.53, 49.47, 1.05 +0.92, 0.00, 50.52, 49.48, 1.05 +0.92, 0.00, 50.52, 49.48, 1.04 +0.92, 0.00, 50.52, 49.48, 1.03 +0.92, 0.00, 50.51, 49.49, 1.03 +0.92, 0.00, 50.51, 49.49, 1.02 +0.92, 0.00, 50.51, 49.49, 1.01 +0.92, 0.00, 50.50, 49.50, 1.01 +0.92, 0.00, 50.50, 49.50, 1.00 +0.92, 0.00, 50.50, 49.50, 0.99 +0.92, 0.00, 50.49, 49.51, 0.99 +0.92, 0.00, 50.49, 49.51, 0.98 +0.92, 0.00, 50.49, 49.51, 0.97 +0.92, 0.00, 50.48, 49.52, 0.96 +0.92, 0.00, 50.48, 49.52, 0.96 +0.92, 0.00, 50.48, 49.52, 0.95 +0.92, 0.00, 50.47, 49.53, 0.94 +0.92, 0.00, 50.47, 49.53, 0.94 +0.92, 0.00, 50.47, 49.53, 0.93 +0.86, 0.00, 52.98, 47.02, 5.97 +0.86, 0.00, 50.51, 49.49, 1.02 +0.86, 0.00, 50.50, 49.50, 1.01 +0.86, 0.00, 50.50, 49.50, 1.00 +0.86, 0.00, 50.50, 49.50, 1.00 +0.86, 0.00, 50.50, 49.50, 0.99 +0.79, 0.00, 53.01, 46.99, 6.03 +0.79, 0.00, 50.54, 49.46, 1.08 +0.79, 0.00, 50.54, 49.46, 1.07 +0.79, 0.00, 50.53, 49.47, 1.07 +0.79, 0.00, 50.53, 49.47, 1.06 +0.79, 0.00, 50.53, 49.47, 1.05 +0.66, 0.00, 55.57, 44.43, 11.13 +0.66, 0.00, 50.62, 49.38, 1.24 +0.66, 0.00, 50.62, 49.38, 1.24 +0.66, 0.00, 50.62, 49.38, 1.23 +0.66, 0.00, 50.61, 49.39, 1.23 +0.66, 0.00, 50.61, 49.39, 1.22 +0.66, 0.00, 50.61, 49.39, 1.22 +0.66, 0.00, 50.61, 49.39, 1.21 +0.66, 0.00, 50.60, 49.40, 1.21 +0.66, 0.00, 50.60, 49.40, 1.20 +0.66, 0.00, 50.60, 49.40, 1.20 +0.59, 0.00, 53.12, 46.88, 6.24 +0.59, 0.00, 50.64, 49.36, 1.29 +0.59, 0.00, 50.64, 49.36, 1.28 +0.59, 0.00, 50.64, 49.36, 1.28 +0.59, 0.00, 50.64, 49.36, 1.27 +0.59, 0.00, 50.63, 49.37, 1.27 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.25 +0.53, 0.00, 53.15, 46.85, 6.29 +0.53, 0.00, 50.67, 49.33, 1.34 +0.53, 0.00, 50.67, 49.33, 1.34 +0.53, 0.00, 50.67, 49.33, 1.33 +0.53, 0.00, 50.67, 49.33, 1.33 +0.53, 0.00, 50.66, 49.34, 1.33 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.31 +0.53, 0.00, 50.66, 49.34, 1.31 +0.59, 0.00, 48.13, 51.87, -3.74 +0.53, 0.00, 53.12, 46.88, 6.25 +0.53, 0.00, 50.65, 49.35, 1.30 +0.53, 0.00, 50.65, 49.35, 1.29 +0.53, 0.00, 50.65, 49.35, 1.29 +0.53, 0.00, 50.64, 49.36, 1.29 +0.53, 0.00, 50.64, 49.36, 1.28 +0.40, 0.00, 55.68, 44.32, 11.37 +0.40, 0.00, 50.74, 49.26, 1.47 +0.40, 0.00, 50.74, 49.26, 1.47 +0.40, 0.00, 50.73, 49.27, 1.47 +0.40, 0.00, 50.73, 49.27, 1.47 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.45 +0.40, 0.00, 50.73, 49.27, 1.45 +0.53, 0.00, 45.68, 54.32, -8.64 +0.53, 0.00, 50.62, 49.38, 1.25 +0.53, 0.00, 50.62, 49.38, 1.24 +0.53, 0.00, 50.62, 49.38, 1.24 +0.53, 0.00, 50.62, 49.38, 1.23 +0.53, 0.00, 50.61, 49.39, 1.23 +0.40, 0.00, 55.66, 44.34, 11.31 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.41 +0.40, 0.00, 50.70, 49.30, 1.41 +0.33, 0.00, 53.22, 46.78, 6.45 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.49 +0.33, 0.00, 50.75, 49.25, 1.49 +0.40, 0.00, 48.22, 51.78, -3.55 +0.33, 0.00, 53.21, 46.79, 6.43 +0.40, 0.00, 48.22, 51.78, -3.56 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.37 +0.40, 0.00, 50.69, 49.31, 1.37 +0.40, 0.00, 50.68, 49.32, 1.37 +0.33, 0.00, 53.20, 46.80, 6.41 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.45 +0.33, 0.00, 50.73, 49.27, 1.45 +0.33, 0.00, 50.72, 49.28, 1.45 +0.33, 0.00, 50.72, 49.28, 1.45 +0.33, 0.00, 50.72, 49.28, 1.44 +0.33, 0.00, 50.72, 49.28, 1.44 +0.33, 0.00, 50.72, 49.28, 1.44 +0.33, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 48.19, 51.81, -3.61 +0.33, 0.00, 53.19, 46.81, 6.37 +0.33, 0.00, 50.71, 49.29, 1.43 +0.33, 0.00, 50.71, 49.29, 1.43 +0.33, 0.00, 50.71, 49.29, 1.42 +0.33, 0.00, 50.71, 49.29, 1.42 +0.33, 0.00, 50.71, 49.29, 1.42 +0.33, 0.00, 50.71, 49.29, 1.42 +0.26, 0.00, 53.23, 46.77, 6.46 +0.26, 0.00, 50.76, 49.24, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.49 +0.26, 0.00, 50.75, 49.25, 1.49 +0.26, 0.00, 50.75, 49.25, 1.49 +0.26, 0.00, 50.74, 49.26, 1.49 +0.26, 0.00, 50.74, 49.26, 1.49 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.47 +0.26, 0.00, 50.74, 49.26, 1.47 +0.26, 0.00, 50.74, 49.26, 1.47 +0.26, 0.00, 50.73, 49.27, 1.47 +0.26, 0.00, 50.73, 49.27, 1.47 +0.26, 0.00, 50.73, 49.27, 1.46 +0.13, 0.00, 55.77, 44.23, 11.55 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.65 +0.13, 0.00, 50.83, 49.17, 1.65 +0.13, 0.00, 50.83, 49.17, 1.65 +0.13, 0.00, 50.83, 49.17, 1.65 +0.26, 0.00, 45.78, 54.22, -8.44 +0.26, 0.00, 50.72, 49.28, 1.45 +0.13, 0.00, 55.77, 44.23, 11.53 +0.13, 0.00, 50.82, 49.18, 1.65 +0.13, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 45.78, 54.22, -8.44 +0.26, 0.00, 50.72, 49.28, 1.44 +0.13, 0.00, 55.76, 44.24, 11.53 +0.13, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 45.78, 54.22, -8.45 +0.13, 0.00, 55.76, 44.24, 11.52 +0.13, 0.00, 50.82, 49.18, 1.63 +0.26, 0.00, 45.77, 54.23, -8.45 +0.13, 0.00, 55.76, 44.24, 11.52 +0.26, 0.00, 45.77, 54.23, -8.46 +0.26, 0.00, 50.72, 49.28, 1.43 +0.13, 0.00, 55.76, 44.24, 11.51 +0.13, 0.00, 50.81, 49.19, 1.63 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.07, 0.00, 53.33, 46.67, 6.66 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.85, 49.15, 1.71 +0.07, 0.00, 50.85, 49.15, 1.71 +0.07, 0.00, 50.85, 49.15, 1.71 +0.00, 0.00, 53.38, 46.62, 6.75 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +-0.13, 0.00, 55.95, 44.05, 11.89 +-0.13, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 51.01, 48.99, 2.01 +-0.13, 0.00, 51.01, 48.99, 2.01 +-0.20, 0.00, 53.53, 46.47, 7.06 +-0.20, 0.00, 51.06, 48.94, 2.11 +-0.20, 0.00, 51.06, 48.94, 2.11 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.26, 0.00, 53.58, 46.42, 7.17 +-0.26, 0.00, 51.11, 48.89, 2.23 +-0.26, 0.00, 51.11, 48.89, 2.23 +-0.26, 0.00, 51.12, 48.88, 2.23 +-0.26, 0.00, 51.12, 48.88, 2.23 +-0.26, 0.00, 51.12, 48.88, 2.23 +-0.40, 0.00, 56.16, 43.84, 12.32 +-0.40, 0.00, 51.22, 48.78, 2.44 +-0.40, 0.00, 51.22, 48.78, 2.44 +-0.40, 0.00, 51.22, 48.78, 2.44 +-0.40, 0.00, 51.22, 48.78, 2.45 +-0.40, 0.00, 51.23, 48.77, 2.45 +-0.40, 0.00, 51.23, 48.77, 2.45 +-0.46, 0.00, 53.75, 46.25, 7.50 +-0.46, 0.00, 51.28, 48.72, 2.56 +-0.46, 0.00, 51.28, 48.72, 2.56 +-0.46, 0.00, 51.28, 48.72, 2.57 +-0.46, 0.00, 51.28, 48.72, 2.57 +-0.46, 0.00, 51.29, 48.71, 2.57 +-0.46, 0.00, 51.29, 48.71, 2.58 +-0.46, 0.00, 51.29, 48.71, 2.58 +-0.46, 0.00, 51.29, 48.71, 2.58 +-0.46, 0.00, 51.29, 48.71, 2.59 +-0.46, 0.00, 51.29, 48.71, 2.59 +-0.46, 0.00, 51.30, 48.70, 2.59 +-0.46, 0.00, 51.30, 48.70, 2.60 +-0.46, 0.00, 51.30, 48.70, 2.60 +-0.46, 0.00, 51.30, 48.70, 2.60 +-0.46, 0.00, 51.30, 48.70, 2.61 +-0.46, 0.00, 51.31, 48.69, 2.61 +-0.46, 0.00, 51.31, 48.69, 2.61 +-0.46, 0.00, 51.31, 48.69, 2.62 +-0.46, 0.00, 51.31, 48.69, 2.62 +-0.46, 0.00, 51.31, 48.69, 2.62 +-0.46, 0.00, 51.31, 48.69, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.65 +-0.46, 0.00, 51.32, 48.68, 2.65 +-0.46, 0.00, 51.33, 48.67, 2.65 +-0.46, 0.00, 51.33, 48.67, 2.66 +-0.46, 0.00, 51.33, 48.67, 2.66 +-0.46, 0.00, 51.33, 48.67, 2.66 +-0.46, 0.00, 51.33, 48.67, 2.67 +-0.46, 0.00, 51.33, 48.67, 2.67 +-0.53, 0.00, 53.86, 46.14, 7.72 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.46, 0.00, 48.87, 51.13, -2.26 +-0.53, 0.00, 53.87, 46.13, 7.74 +-0.53, 0.00, 51.40, 48.60, 2.80 +-0.46, 0.00, 48.88, 51.12, -2.24 +-0.46, 0.00, 51.35, 48.65, 2.70 +-0.46, 0.00, 51.35, 48.65, 2.71 +-0.46, 0.00, 51.36, 48.64, 2.71 +-0.46, 0.00, 51.36, 48.64, 2.71 +-0.46, 0.00, 51.36, 48.64, 2.72 +-0.46, 0.00, 51.36, 48.64, 2.72 +-0.46, 0.00, 51.36, 48.64, 2.72 +-0.46, 0.00, 51.36, 48.64, 2.73 +-0.46, 0.00, 51.37, 48.63, 2.73 +-0.46, 0.00, 51.37, 48.63, 2.73 +-0.53, 0.00, 53.89, 46.11, 7.78 +-0.53, 0.00, 51.42, 48.58, 2.84 +-0.53, 0.00, 51.42, 48.58, 2.85 +-0.53, 0.00, 51.42, 48.58, 2.85 +-0.53, 0.00, 51.43, 48.57, 2.85 +-0.53, 0.00, 51.43, 48.57, 2.86 +-0.53, 0.00, 51.43, 48.57, 2.86 +-0.53, 0.00, 51.43, 48.57, 2.87 +-0.53, 0.00, 51.43, 48.57, 2.87 +-0.53, 0.00, 51.44, 48.56, 2.87 +-0.53, 0.00, 51.44, 48.56, 2.88 +-0.53, 0.00, 51.44, 48.56, 2.88 +-0.53, 0.00, 51.44, 48.56, 2.89 +-0.53, 0.00, 51.44, 48.56, 2.89 +-0.53, 0.00, 51.45, 48.55, 2.89 +-0.53, 0.00, 51.45, 48.55, 2.90 +-0.53, 0.00, 51.45, 48.55, 2.90 +-0.53, 0.00, 51.45, 48.55, 2.90 +-0.53, 0.00, 51.45, 48.55, 2.91 +-0.53, 0.00, 51.46, 48.54, 2.91 +-0.53, 0.00, 51.46, 48.54, 2.92 +-0.53, 0.00, 51.46, 48.54, 2.92 +-0.53, 0.00, 51.46, 48.54, 2.92 +-0.66, 0.00, 56.51, 43.49, 13.02 +-0.66, 0.00, 51.57, 48.43, 3.13 +-0.66, 0.00, 51.57, 48.43, 3.14 +-0.66, 0.00, 51.57, 48.43, 3.14 +-0.66, 0.00, 51.57, 48.43, 3.15 +-0.66, 0.00, 51.58, 48.42, 3.15 +-0.66, 0.00, 51.58, 48.42, 3.16 +-0.66, 0.00, 51.58, 48.42, 3.16 +-0.66, 0.00, 51.58, 48.42, 3.17 +-0.66, 0.00, 51.59, 48.41, 3.17 +-0.66, 0.00, 51.59, 48.41, 3.18 +-0.66, 0.00, 51.59, 48.41, 3.18 +-0.53, 0.00, 46.55, 53.45, -6.90 +-0.53, 0.00, 51.50, 48.50, 2.99 +-0.53, 0.00, 51.50, 48.50, 3.00 +-0.53, 0.00, 51.50, 48.50, 3.00 +-0.53, 0.00, 51.50, 48.50, 3.00 +-0.53, 0.00, 51.50, 48.50, 3.01 +-0.53, 0.00, 51.51, 48.49, 3.01 +-0.53, 0.00, 51.51, 48.49, 3.02 +-0.53, 0.00, 51.51, 48.49, 3.02 +-0.53, 0.00, 51.51, 48.49, 3.02 +-0.66, 0.00, 56.56, 43.44, 13.11 +-0.66, 0.00, 51.62, 48.38, 3.23 +-0.66, 0.00, 51.62, 48.38, 3.24 +-0.66, 0.00, 51.62, 48.38, 3.24 +-0.66, 0.00, 51.62, 48.38, 3.25 +-0.66, 0.00, 51.63, 48.37, 3.25 +-0.66, 0.00, 51.63, 48.37, 3.26 +-0.53, 0.00, 46.59, 53.41, -6.83 +-0.53, 0.00, 51.53, 48.47, 3.07 +-0.53, 0.00, 51.53, 48.47, 3.07 +-0.53, 0.00, 51.54, 48.46, 3.07 +-0.53, 0.00, 51.54, 48.46, 3.08 +-0.53, 0.00, 51.54, 48.46, 3.08 +-0.53, 0.00, 51.54, 48.46, 3.09 +-0.53, 0.00, 51.54, 48.46, 3.09 +-0.53, 0.00, 51.55, 48.45, 3.09 +-0.53, 0.00, 51.55, 48.45, 3.10 +-0.53, 0.00, 51.55, 48.45, 3.10 +-0.53, 0.00, 51.55, 48.45, 3.11 +-0.53, 0.00, 51.55, 48.45, 3.11 +-0.53, 0.00, 51.56, 48.44, 3.11 +-0.53, 0.00, 51.56, 48.44, 3.12 +-0.66, 0.00, 56.60, 43.40, 13.21 +-0.66, 0.00, 51.66, 48.34, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.34 +-0.66, 0.00, 51.67, 48.33, 3.34 +-0.66, 0.00, 51.67, 48.33, 3.35 +-0.53, 0.00, 46.63, 53.37, -6.73 +-0.66, 0.00, 56.62, 43.38, 13.25 +-0.66, 0.00, 51.68, 48.32, 3.36 +-0.53, 0.00, 46.64, 53.36, -6.72 +-0.53, 0.00, 51.59, 48.41, 3.17 +-0.53, 0.00, 51.59, 48.41, 3.18 +-0.53, 0.00, 51.59, 48.41, 3.18 +-0.53, 0.00, 51.59, 48.41, 3.19 +-0.66, 0.00, 56.64, 43.36, 13.28 +-0.53, 0.00, 46.65, 53.35, -6.69 +-0.66, 0.00, 56.64, 43.36, 13.28 +-0.66, 0.00, 51.70, 48.30, 3.40 +-0.66, 0.00, 51.70, 48.30, 3.41 +-0.66, 0.00, 51.71, 48.29, 3.41 +-0.66, 0.00, 51.71, 48.29, 3.42 +-0.66, 0.00, 51.71, 48.29, 3.42 +-0.66, 0.00, 51.71, 48.29, 3.43 +-0.66, 0.00, 51.72, 48.28, 3.43 +-0.66, 0.00, 51.72, 48.28, 3.44 +-0.66, 0.00, 51.72, 48.28, 3.44 +-0.66, 0.00, 51.72, 48.28, 3.45 +-0.73, 0.00, 54.25, 45.75, 8.49 +-0.73, 0.00, 51.78, 48.22, 3.56 +-0.73, 0.00, 51.78, 48.22, 3.56 +-0.73, 0.00, 51.78, 48.22, 3.57 +-0.73, 0.00, 51.79, 48.21, 3.57 +-0.73, 0.00, 51.79, 48.21, 3.58 +-0.73, 0.00, 51.79, 48.21, 3.58 +-0.73, 0.00, 51.79, 48.21, 3.59 +-0.73, 0.00, 51.80, 48.20, 3.59 +-0.73, 0.00, 51.80, 48.20, 3.60 +-0.73, 0.00, 51.80, 48.20, 3.61 +-0.73, 0.00, 51.81, 48.19, 3.61 +-0.73, 0.00, 51.81, 48.19, 3.62 +-0.73, 0.00, 51.81, 48.19, 3.62 +-0.73, 0.00, 51.81, 48.19, 3.63 +-0.79, 0.00, 54.34, 45.66, 8.68 +-0.79, 0.00, 51.87, 48.13, 3.74 +-0.79, 0.00, 51.87, 48.13, 3.74 +-0.79, 0.00, 51.87, 48.13, 3.75 +-0.79, 0.00, 51.88, 48.12, 3.76 +-0.79, 0.00, 51.88, 48.12, 3.76 +-0.92, 0.00, 56.93, 43.07, 13.85 +-0.79, 0.00, 46.94, 53.06, -6.11 +-0.92, 0.00, 56.93, 43.07, 13.87 +-0.92, 0.00, 51.99, 48.01, 3.99 +-0.92, 0.00, 52.00, 48.00, 3.99 +-0.92, 0.00, 52.00, 48.00, 4.00 +-0.92, 0.00, 52.00, 48.00, 4.01 +-0.92, 0.00, 52.01, 47.99, 4.01 +-0.92, 0.00, 52.01, 47.99, 4.02 +-0.92, 0.00, 52.01, 47.99, 4.03 +-0.99, 0.00, 54.54, 45.46, 9.08 +-0.92, 0.00, 49.55, 50.45, -0.90 +-0.99, 0.00, 54.55, 45.45, 9.09 +-0.99, 0.00, 52.08, 47.92, 4.16 +-0.99, 0.00, 52.08, 47.92, 4.16 +-0.99, 0.00, 52.09, 47.91, 4.17 +-0.99, 0.00, 52.09, 47.91, 4.18 +-0.99, 0.00, 52.09, 47.91, 4.19 +-0.99, 0.00, 52.10, 47.90, 4.19 +-0.99, 0.00, 52.10, 47.90, 4.20 +-0.99, 0.00, 52.10, 47.90, 4.21 +-0.99, 0.00, 52.11, 47.89, 4.21 +-0.99, 0.00, 52.11, 47.89, 4.22 +-0.99, 0.00, 52.11, 47.89, 4.23 +-0.99, 0.00, 52.12, 47.88, 4.24 +-0.99, 0.00, 52.12, 47.88, 4.24 +-0.99, 0.00, 52.13, 47.87, 4.25 +-0.99, 0.00, 52.13, 47.87, 4.26 +-0.99, 0.00, 52.13, 47.87, 4.27 +-0.99, 0.00, 52.14, 47.86, 4.27 +-0.99, 0.00, 52.14, 47.86, 4.28 +-0.99, 0.00, 52.14, 47.86, 4.29 +-0.99, 0.00, 52.15, 47.85, 4.30 +-1.05, 0.00, 54.67, 45.33, 9.35 +-1.05, 0.00, 52.21, 47.79, 4.41 +-1.05, 0.00, 52.21, 47.79, 4.42 +-1.05, 0.00, 52.21, 47.79, 4.43 +-1.05, 0.00, 52.22, 47.78, 4.43 +-1.05, 0.00, 52.22, 47.78, 4.44 +-1.05, 0.00, 52.23, 47.77, 4.45 +-1.05, 0.00, 52.23, 47.77, 4.46 +-1.05, 0.00, 52.23, 47.77, 4.47 +-1.05, 0.00, 52.24, 47.76, 4.47 +-1.05, 0.00, 52.24, 47.76, 4.48 +-0.99, 0.00, 49.72, 50.28, -0.55 +-0.99, 0.00, 52.20, 47.80, 4.40 +-0.99, 0.00, 52.20, 47.80, 4.41 +-0.99, 0.00, 52.21, 47.79, 4.41 +-0.99, 0.00, 52.21, 47.79, 4.42 +-0.99, 0.00, 52.21, 47.79, 4.43 +-0.99, 0.00, 52.22, 47.78, 4.44 +-0.99, 0.00, 52.22, 47.78, 4.44 +-0.99, 0.00, 52.23, 47.77, 4.45 +-0.99, 0.00, 52.23, 47.77, 4.46 +-0.99, 0.00, 52.23, 47.77, 4.47 +-0.99, 0.00, 52.24, 47.76, 4.47 +-0.99, 0.00, 52.24, 47.76, 4.48 +-0.92, 0.00, 49.72, 50.28, -0.56 +-0.92, 0.00, 52.20, 47.80, 4.39 +-0.92, 0.00, 52.20, 47.80, 4.40 +-0.92, 0.00, 52.20, 47.80, 4.41 +-0.92, 0.00, 52.21, 47.79, 4.42 +-0.92, 0.00, 52.21, 47.79, 4.42 +-0.79, 0.00, 47.17, 52.83, -5.66 +-0.79, 0.00, 52.12, 47.88, 4.24 +-0.79, 0.00, 52.12, 47.88, 4.24 +-0.79, 0.00, 52.12, 47.88, 4.25 +-0.79, 0.00, 52.13, 47.87, 4.25 +-0.79, 0.00, 52.13, 47.87, 4.26 +-0.73, 0.00, 49.61, 50.39, -0.78 +-0.73, 0.00, 52.09, 47.91, 4.17 +-0.73, 0.00, 52.09, 47.91, 4.18 +-0.73, 0.00, 52.09, 47.91, 4.18 +-0.66, 0.00, 49.57, 50.43, -0.85 +-0.66, 0.00, 52.05, 47.95, 4.09 +-0.66, 0.00, 52.05, 47.95, 4.10 +-0.66, 0.00, 52.05, 47.95, 4.10 +-0.66, 0.00, 52.05, 47.95, 4.11 +-0.66, 0.00, 52.06, 47.94, 4.11 +-0.53, 0.00, 47.02, 52.98, -5.97 +-0.53, 0.00, 51.96, 48.04, 3.92 +-0.53, 0.00, 51.96, 48.04, 3.93 +-0.53, 0.00, 51.97, 48.03, 3.93 +-0.53, 0.00, 51.97, 48.03, 3.94 +-0.53, 0.00, 51.97, 48.03, 3.94 +-0.46, 0.00, 49.45, 50.55, -1.10 +-0.46, 0.00, 51.92, 48.08, 3.85 +-0.46, 0.00, 51.93, 48.07, 3.85 +-0.46, 0.00, 51.93, 48.07, 3.86 +-0.46, 0.00, 51.93, 48.07, 3.86 +-0.40, 0.00, 49.41, 50.59, -1.18 +-0.40, 0.00, 51.88, 48.12, 3.77 +-0.40, 0.00, 51.88, 48.12, 3.77 +-0.40, 0.00, 51.89, 48.11, 3.77 +-0.40, 0.00, 51.89, 48.11, 3.77 +-0.26, 0.00, 46.85, 53.15, -6.31 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.59 +-0.26, 0.00, 51.79, 48.21, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.20, 0.00, 49.28, 50.72, -1.45 +-0.26, 0.00, 54.27, 45.73, 8.54 +-0.20, 0.00, 49.28, 50.72, -1.44 +-0.20, 0.00, 51.75, 48.25, 3.50 +-0.20, 0.00, 51.75, 48.25, 3.50 +-0.20, 0.00, 51.75, 48.25, 3.51 +-0.20, 0.00, 51.75, 48.25, 3.51 +-0.20, 0.00, 51.75, 48.25, 3.51 +-0.20, 0.00, 51.75, 48.25, 3.51 +-0.13, 0.00, 49.23, 50.77, -1.53 +-0.13, 0.00, 51.71, 48.29, 3.41 +-0.13, 0.00, 51.71, 48.29, 3.41 +0.00, 0.00, 46.66, 53.34, -6.67 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.07, 0.00, 49.09, 50.91, -1.83 +0.07, 0.00, 51.56, 48.44, 3.12 +0.07, 0.00, 51.56, 48.44, 3.12 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.13, 0.00, 49.03, 50.97, -1.94 +0.13, 0.00, 51.50, 48.50, 3.01 +0.13, 0.00, 51.50, 48.50, 3.01 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 54.02, 45.98, 8.04 +0.07, 0.00, 51.55, 48.45, 3.09 +0.07, 0.00, 51.55, 48.45, 3.09 +0.07, 0.00, 51.55, 48.45, 3.09 +0.13, 0.00, 49.03, 50.97, -1.95 +0.07, 0.00, 54.02, 45.98, 8.04 +0.13, 0.00, 49.02, 50.98, -1.95 +0.13, 0.00, 51.50, 48.50, 2.99 +0.13, 0.00, 51.50, 48.50, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.07, 0.00, 54.00, 46.00, 8.00 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.04 +0.00, 0.00, 54.04, 45.96, 8.09 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +-0.13, 0.00, 56.62, 43.38, 13.23 +-0.13, 0.00, 51.67, 48.33, 3.34 +-0.13, 0.00, 51.67, 48.33, 3.34 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.68, 48.32, 3.35 +-0.20, 0.00, 54.20, 45.80, 8.39 +-0.20, 0.00, 51.73, 48.27, 3.45 +-0.20, 0.00, 51.73, 48.27, 3.45 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.47 +-0.20, 0.00, 51.73, 48.27, 3.47 +-0.20, 0.00, 51.73, 48.27, 3.47 +-0.20, 0.00, 51.73, 48.27, 3.47 +-0.26, 0.00, 54.26, 45.74, 8.51 +-0.26, 0.00, 51.79, 48.21, 3.57 +-0.26, 0.00, 51.79, 48.21, 3.57 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.59 +-0.26, 0.00, 51.79, 48.21, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.61 +-0.26, 0.00, 51.80, 48.20, 3.61 +-0.40, 0.00, 56.85, 43.15, 13.70 +-0.40, 0.00, 51.91, 48.09, 3.81 +-0.40, 0.00, 51.91, 48.09, 3.82 +-0.40, 0.00, 51.91, 48.09, 3.82 +-0.40, 0.00, 51.91, 48.09, 3.82 +-0.26, 0.00, 46.87, 53.13, -6.26 +-0.26, 0.00, 51.81, 48.19, 3.63 +-0.26, 0.00, 51.81, 48.19, 3.63 +-0.26, 0.00, 51.82, 48.18, 3.63 +-0.26, 0.00, 51.82, 48.18, 3.63 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.65 +-0.26, 0.00, 51.82, 48.18, 3.65 +-0.26, 0.00, 51.83, 48.17, 3.65 +-0.26, 0.00, 51.83, 48.17, 3.65 +-0.26, 0.00, 51.83, 48.17, 3.65 +-0.20, 0.00, 49.31, 50.69, -1.39 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.57 +-0.20, 0.00, 51.78, 48.22, 3.57 +-0.20, 0.00, 51.78, 48.22, 3.57 +-0.20, 0.00, 51.79, 48.21, 3.57 +-0.13, 0.00, 49.26, 50.74, -1.47 +-0.13, 0.00, 51.74, 48.26, 3.47 +-0.13, 0.00, 51.74, 48.26, 3.47 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +0.00, 0.00, 46.70, 53.30, -6.60 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 49.12, 50.88, -1.76 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.13, 0.00, 49.07, 50.93, -1.87 +0.13, 0.00, 51.54, 48.46, 3.08 +0.13, 0.00, 51.54, 48.46, 3.08 +0.13, 0.00, 51.54, 48.46, 3.08 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.06 +0.13, 0.00, 51.53, 48.47, 3.06 +0.13, 0.00, 51.53, 48.47, 3.06 +0.13, 0.00, 51.53, 48.47, 3.06 +0.26, 0.00, 46.49, 53.51, -7.03 +0.26, 0.00, 51.43, 48.57, 2.86 +0.26, 0.00, 51.43, 48.57, 2.86 +0.26, 0.00, 51.43, 48.57, 2.86 +0.26, 0.00, 51.43, 48.57, 2.85 +0.26, 0.00, 51.43, 48.57, 2.85 +0.33, 0.00, 48.90, 51.10, -2.19 +0.26, 0.00, 53.90, 46.10, 7.79 +0.33, 0.00, 48.90, 51.10, -2.20 +0.33, 0.00, 51.37, 48.63, 2.74 +0.33, 0.00, 51.37, 48.63, 2.74 +0.33, 0.00, 51.37, 48.63, 2.74 +0.33, 0.00, 51.37, 48.63, 2.74 +0.33, 0.00, 51.37, 48.63, 2.73 +0.33, 0.00, 51.37, 48.63, 2.73 +0.33, 0.00, 51.36, 48.64, 2.73 +0.33, 0.00, 51.36, 48.64, 2.73 +0.33, 0.00, 51.36, 48.64, 2.72 +0.33, 0.00, 51.36, 48.64, 2.72 +0.40, 0.00, 48.84, 51.16, -2.32 +0.40, 0.00, 51.31, 48.69, 2.62 +0.40, 0.00, 51.31, 48.69, 2.61 +0.40, 0.00, 51.31, 48.69, 2.61 +0.40, 0.00, 51.30, 48.70, 2.61 +0.40, 0.00, 51.30, 48.70, 2.60 +0.40, 0.00, 51.30, 48.70, 2.60 +0.40, 0.00, 51.30, 48.70, 2.60 +0.40, 0.00, 51.30, 48.70, 2.60 +0.40, 0.00, 51.30, 48.70, 2.59 +0.40, 0.00, 51.29, 48.71, 2.59 +0.40, 0.00, 51.29, 48.71, 2.59 +0.33, 0.00, 53.81, 46.19, 7.63 +0.33, 0.00, 51.34, 48.66, 2.68 +0.33, 0.00, 51.34, 48.66, 2.68 +0.33, 0.00, 51.34, 48.66, 2.68 +0.33, 0.00, 51.34, 48.66, 2.67 +0.33, 0.00, 51.34, 48.66, 2.67 +0.33, 0.00, 51.33, 48.67, 2.67 +0.33, 0.00, 51.33, 48.67, 2.67 +0.33, 0.00, 51.33, 48.67, 2.66 +0.33, 0.00, 51.33, 48.67, 2.66 +0.33, 0.00, 51.33, 48.67, 2.66 +0.33, 0.00, 51.33, 48.67, 2.66 +0.33, 0.00, 51.33, 48.67, 2.65 +0.33, 0.00, 51.33, 48.67, 2.65 +0.33, 0.00, 51.32, 48.68, 2.65 +0.33, 0.00, 51.32, 48.68, 2.65 +0.26, 0.00, 53.84, 46.16, 7.69 +0.26, 0.00, 51.37, 48.63, 2.74 +0.26, 0.00, 51.37, 48.63, 2.74 +0.26, 0.00, 51.37, 48.63, 2.74 +0.26, 0.00, 51.37, 48.63, 2.74 +0.13, 0.00, 56.41, 43.59, 12.82 +0.13, 0.00, 51.47, 48.53, 2.93 +0.13, 0.00, 51.47, 48.53, 2.93 +0.13, 0.00, 51.46, 48.54, 2.93 +0.13, 0.00, 51.46, 48.54, 2.93 +0.07, 0.00, 53.99, 46.01, 7.97 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.00, 0.00, 54.03, 45.97, 8.06 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +-0.13, 0.00, 56.60, 43.40, 13.21 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.33 +-0.13, 0.00, 51.66, 48.34, 3.33 +0.00, 0.00, 46.62, 53.38, -6.76 +-0.13, 0.00, 56.61, 43.39, 13.21 +0.00, 0.00, 46.62, 53.38, -6.76 +-0.13, 0.00, 56.61, 43.39, 13.22 +0.00, 0.00, 46.62, 53.38, -6.76 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 56.61, 43.39, 13.22 +-0.13, 0.00, 51.67, 48.33, 3.33 +-0.13, 0.00, 51.67, 48.33, 3.33 +-0.13, 0.00, 51.67, 48.33, 3.33 +0.00, 0.00, 46.62, 53.38, -6.75 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.07, 0.00, 49.05, 50.95, -1.91 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.13, 0.00, 48.99, 51.01, -2.02 +0.13, 0.00, 51.46, 48.54, 2.92 +0.07, 0.00, 53.98, 46.02, 7.96 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 48.98, 51.02, -2.05 +0.13, 0.00, 51.45, 48.55, 2.90 +0.13, 0.00, 51.45, 48.55, 2.90 +0.13, 0.00, 51.45, 48.55, 2.90 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.84 +0.13, 0.00, 51.42, 48.58, 2.84 +0.13, 0.00, 51.42, 48.58, 2.84 +0.26, 0.00, 46.38, 53.62, -7.25 +0.26, 0.00, 51.32, 48.68, 2.64 +0.26, 0.00, 51.32, 48.68, 2.64 +0.26, 0.00, 51.32, 48.68, 2.64 +0.26, 0.00, 51.32, 48.68, 2.63 +0.26, 0.00, 51.32, 48.68, 2.63 +0.26, 0.00, 51.32, 48.68, 2.63 +0.26, 0.00, 51.31, 48.69, 2.63 +0.26, 0.00, 51.31, 48.69, 2.63 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.61 +0.26, 0.00, 51.31, 48.69, 2.61 +0.26, 0.00, 51.31, 48.69, 2.61 +0.26, 0.00, 51.30, 48.70, 2.61 +0.26, 0.00, 51.30, 48.70, 2.61 +0.26, 0.00, 51.30, 48.70, 2.60 +0.33, 0.00, 48.78, 51.22, -2.44 +0.26, 0.00, 53.77, 46.23, 7.54 +0.33, 0.00, 48.78, 51.22, -2.44 +0.33, 0.00, 51.25, 48.75, 2.50 +0.26, 0.00, 53.77, 46.23, 7.54 +0.26, 0.00, 51.30, 48.70, 2.59 +0.26, 0.00, 51.29, 48.71, 2.59 +0.26, 0.00, 51.29, 48.71, 2.59 +0.26, 0.00, 51.29, 48.71, 2.59 +0.26, 0.00, 51.29, 48.71, 2.58 +0.26, 0.00, 51.29, 48.71, 2.58 +0.33, 0.00, 48.77, 51.23, -2.46 +0.33, 0.00, 51.24, 48.76, 2.48 +0.33, 0.00, 51.24, 48.76, 2.48 +0.33, 0.00, 51.24, 48.76, 2.47 +0.33, 0.00, 51.24, 48.76, 2.47 +0.33, 0.00, 51.23, 48.77, 2.47 +0.33, 0.00, 51.23, 48.77, 2.47 +0.33, 0.00, 51.23, 48.77, 2.46 +0.33, 0.00, 51.23, 48.77, 2.46 +0.33, 0.00, 51.23, 48.77, 2.46 +0.33, 0.00, 51.23, 48.77, 2.46 +0.33, 0.00, 51.23, 48.77, 2.45 +0.33, 0.00, 51.23, 48.77, 2.45 +0.33, 0.00, 51.22, 48.78, 2.45 +0.33, 0.00, 51.22, 48.78, 2.45 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 53.74, 46.26, 7.48 +0.33, 0.00, 48.74, 51.26, -2.51 +0.33, 0.00, 51.21, 48.79, 2.43 +0.33, 0.00, 51.21, 48.79, 2.43 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.41 +0.33, 0.00, 51.21, 48.79, 2.41 +0.33, 0.00, 51.20, 48.80, 2.41 +0.33, 0.00, 51.20, 48.80, 2.41 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.39 +0.26, 0.00, 53.72, 46.28, 7.43 +0.33, 0.00, 48.72, 51.28, -2.55 +0.33, 0.00, 51.19, 48.81, 2.39 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.37 +0.33, 0.00, 51.19, 48.81, 2.37 +0.33, 0.00, 51.18, 48.82, 2.37 +0.33, 0.00, 51.18, 48.82, 2.37 +0.33, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 53.70, 46.30, 7.41 +0.26, 0.00, 51.23, 48.77, 2.46 +0.26, 0.00, 51.23, 48.77, 2.46 +0.26, 0.00, 51.23, 48.77, 2.46 +0.26, 0.00, 51.23, 48.77, 2.45 +0.26, 0.00, 51.23, 48.77, 2.45 +0.26, 0.00, 51.23, 48.77, 2.45 +0.26, 0.00, 51.22, 48.78, 2.45 +0.26, 0.00, 51.22, 48.78, 2.45 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.43 +0.26, 0.00, 51.22, 48.78, 2.43 +0.26, 0.00, 51.22, 48.78, 2.43 +0.33, 0.00, 48.69, 51.31, -2.61 +0.26, 0.00, 53.68, 46.32, 7.37 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.41 +0.26, 0.00, 51.21, 48.79, 2.41 +0.26, 0.00, 51.20, 48.80, 2.41 +0.26, 0.00, 51.20, 48.80, 2.41 +0.13, 0.00, 56.25, 43.75, 12.49 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.07, 0.00, 53.82, 46.18, 7.64 +0.07, 0.00, 51.35, 48.65, 2.69 +0.07, 0.00, 51.35, 48.65, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.00, 0.00, 53.86, 46.14, 7.73 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 56.44, 43.56, 12.87 +-0.13, 0.00, 51.49, 48.51, 2.98 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.20, 0.00, 54.02, 45.98, 8.04 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.11 +-0.20, 0.00, 51.55, 48.45, 3.11 +-0.20, 0.00, 51.55, 48.45, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.13 +-0.13, 0.00, 49.04, 50.96, -1.92 +-0.20, 0.00, 54.04, 45.96, 8.07 +-0.20, 0.00, 51.56, 48.44, 3.13 +-0.20, 0.00, 51.57, 48.43, 3.13 +-0.20, 0.00, 51.57, 48.43, 3.13 +-0.20, 0.00, 51.57, 48.43, 3.13 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.15 +-0.20, 0.00, 51.57, 48.43, 3.15 +-0.20, 0.00, 51.57, 48.43, 3.15 +-0.20, 0.00, 51.58, 48.42, 3.15 +-0.20, 0.00, 51.58, 48.42, 3.15 +-0.20, 0.00, 51.58, 48.42, 3.15 +-0.20, 0.00, 51.58, 48.42, 3.15 +-0.13, 0.00, 49.06, 50.94, -1.89 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +0.00, 0.00, 46.50, 53.50, -7.01 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +-0.13, 0.00, 56.48, 43.52, 12.97 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.20, 0.00, 54.07, 45.93, 8.14 +-0.20, 0.00, 51.60, 48.40, 3.20 +-0.20, 0.00, 51.60, 48.40, 3.20 +-0.26, 0.00, 54.12, 45.88, 8.24 +-0.26, 0.00, 51.65, 48.35, 3.30 +-0.26, 0.00, 51.65, 48.35, 3.30 +-0.26, 0.00, 51.65, 48.35, 3.30 +-0.26, 0.00, 51.65, 48.35, 3.31 +-0.26, 0.00, 51.65, 48.35, 3.31 +-0.26, 0.00, 51.66, 48.34, 3.31 +-0.26, 0.00, 51.66, 48.34, 3.31 +-0.26, 0.00, 51.66, 48.34, 3.31 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.33 +-0.26, 0.00, 51.66, 48.34, 3.33 +-0.26, 0.00, 51.67, 48.33, 3.33 +-0.26, 0.00, 51.67, 48.33, 3.33 +-0.26, 0.00, 51.67, 48.33, 3.33 +-0.26, 0.00, 51.67, 48.33, 3.34 +-0.40, 0.00, 56.71, 43.29, 13.42 +-0.40, 0.00, 51.77, 48.23, 3.54 +-0.40, 0.00, 51.77, 48.23, 3.54 +-0.26, 0.00, 46.73, 53.27, -6.54 +-0.26, 0.00, 51.67, 48.33, 3.35 +-0.26, 0.00, 51.68, 48.32, 3.35 +-0.26, 0.00, 51.68, 48.32, 3.35 +-0.20, 0.00, 49.16, 50.84, -1.69 +-0.20, 0.00, 51.63, 48.37, 3.26 +-0.20, 0.00, 51.63, 48.37, 3.26 +-0.20, 0.00, 51.63, 48.37, 3.26 +-0.13, 0.00, 49.11, 50.89, -1.78 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.59, 48.41, 3.17 +0.00, 0.00, 46.54, 53.46, -6.91 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.07, 0.00, 48.96, 51.04, -2.07 +0.07, 0.00, 51.44, 48.56, 2.87 +0.07, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 48.91, 51.09, -2.17 +0.13, 0.00, 51.39, 48.61, 2.77 +0.13, 0.00, 51.39, 48.61, 2.77 +0.13, 0.00, 51.38, 48.62, 2.77 +0.26, 0.00, 46.34, 53.66, -7.32 +0.26, 0.00, 51.28, 48.72, 2.57 +0.26, 0.00, 51.28, 48.72, 2.57 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.55 +0.26, 0.00, 51.28, 48.72, 2.55 +0.26, 0.00, 51.28, 48.72, 2.55 +0.26, 0.00, 51.27, 48.73, 2.55 +0.26, 0.00, 51.27, 48.73, 2.55 +0.26, 0.00, 51.27, 48.73, 2.54 +0.33, 0.00, 48.75, 51.25, -2.50 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.43 +0.33, 0.00, 51.22, 48.78, 2.43 +0.33, 0.00, 51.21, 48.79, 2.43 +0.33, 0.00, 51.21, 48.79, 2.43 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 53.73, 46.27, 7.46 +0.26, 0.00, 51.26, 48.74, 2.52 +0.26, 0.00, 51.26, 48.74, 2.51 +0.26, 0.00, 51.26, 48.74, 2.51 +0.26, 0.00, 51.25, 48.75, 2.51 +0.26, 0.00, 51.25, 48.75, 2.51 +0.26, 0.00, 51.25, 48.75, 2.51 +0.26, 0.00, 51.25, 48.75, 2.50 +0.33, 0.00, 48.73, 51.27, -2.54 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.39 +0.33, 0.00, 51.20, 48.80, 2.39 +0.33, 0.00, 51.19, 48.81, 2.39 +0.33, 0.00, 51.19, 48.81, 2.39 +0.33, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 53.71, 46.29, 7.42 +0.26, 0.00, 51.24, 48.76, 2.48 +0.26, 0.00, 51.24, 48.76, 2.48 +0.26, 0.00, 51.24, 48.76, 2.47 +0.13, 0.00, 56.28, 43.72, 12.56 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.66 +0.13, 0.00, 51.33, 48.67, 2.66 +0.13, 0.00, 51.33, 48.67, 2.66 +0.13, 0.00, 51.33, 48.67, 2.66 +0.13, 0.00, 51.33, 48.67, 2.66 +0.07, 0.00, 53.85, 46.15, 7.70 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.00, 0.00, 53.90, 46.10, 7.80 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +-0.13, 0.00, 56.47, 43.53, 12.94 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.20, 0.00, 54.05, 45.95, 8.10 +-0.20, 0.00, 51.58, 48.42, 3.16 +-0.20, 0.00, 51.58, 48.42, 3.16 +-0.20, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 54.10, 45.90, 8.21 +-0.26, 0.00, 51.63, 48.37, 3.26 +-0.26, 0.00, 51.63, 48.37, 3.27 +-0.26, 0.00, 51.63, 48.37, 3.27 +-0.26, 0.00, 51.64, 48.36, 3.27 +-0.26, 0.00, 51.64, 48.36, 3.27 +-0.26, 0.00, 51.64, 48.36, 3.27 +-0.40, 0.00, 56.68, 43.32, 13.36 +-0.40, 0.00, 51.74, 48.26, 3.48 +-0.40, 0.00, 51.74, 48.26, 3.48 +-0.40, 0.00, 51.74, 48.26, 3.48 +-0.40, 0.00, 51.74, 48.26, 3.49 +-0.40, 0.00, 51.75, 48.25, 3.49 +-0.40, 0.00, 51.75, 48.25, 3.49 +-0.40, 0.00, 51.75, 48.25, 3.50 +-0.46, 0.00, 54.27, 45.73, 8.54 +-0.46, 0.00, 51.80, 48.20, 3.60 +-0.46, 0.00, 51.80, 48.20, 3.61 +-0.46, 0.00, 51.80, 48.20, 3.61 +-0.46, 0.00, 51.81, 48.19, 3.61 +-0.53, 0.00, 54.33, 45.67, 8.66 +-0.53, 0.00, 51.86, 48.14, 3.72 +-0.53, 0.00, 51.86, 48.14, 3.72 +-0.53, 0.00, 51.86, 48.14, 3.73 +-0.53, 0.00, 51.87, 48.13, 3.73 +-0.53, 0.00, 51.87, 48.13, 3.73 +-0.53, 0.00, 51.87, 48.13, 3.74 +-0.53, 0.00, 51.87, 48.13, 3.74 +-0.53, 0.00, 51.87, 48.13, 3.75 +-0.53, 0.00, 51.88, 48.12, 3.75 +-0.53, 0.00, 51.88, 48.12, 3.75 +-0.53, 0.00, 51.88, 48.12, 3.76 +-0.53, 0.00, 51.88, 48.12, 3.76 +-0.53, 0.00, 51.88, 48.12, 3.77 +-0.53, 0.00, 51.89, 48.11, 3.77 +-0.66, 0.00, 56.93, 43.07, 13.86 +-0.66, 0.00, 51.99, 48.01, 3.98 +-0.66, 0.00, 51.99, 48.01, 3.98 +-0.66, 0.00, 51.99, 48.01, 3.99 +-0.66, 0.00, 52.00, 48.00, 3.99 +-0.66, 0.00, 52.00, 48.00, 4.00 +-0.66, 0.00, 52.00, 48.00, 4.00 +-0.66, 0.00, 52.00, 48.00, 4.01 +-0.66, 0.00, 52.01, 47.99, 4.01 +-0.53, 0.00, 46.97, 53.03, -6.07 +-0.53, 0.00, 51.91, 48.09, 3.82 +-0.53, 0.00, 51.91, 48.09, 3.83 +-0.53, 0.00, 51.92, 48.08, 3.83 +-0.53, 0.00, 51.92, 48.08, 3.83 +-0.53, 0.00, 51.92, 48.08, 3.84 +-0.53, 0.00, 51.92, 48.08, 3.84 +-0.53, 0.00, 51.92, 48.08, 3.85 +-0.53, 0.00, 51.93, 48.07, 3.85 +-0.53, 0.00, 51.93, 48.07, 3.85 +-0.53, 0.00, 51.93, 48.07, 3.86 +-0.53, 0.00, 51.93, 48.07, 3.86 +-0.53, 0.00, 51.93, 48.07, 3.87 +-0.53, 0.00, 51.94, 48.06, 3.87 +-0.53, 0.00, 51.94, 48.06, 3.87 +-0.53, 0.00, 51.94, 48.06, 3.88 +-0.46, 0.00, 49.42, 50.58, -1.16 +-0.46, 0.00, 51.89, 48.11, 3.79 +-0.46, 0.00, 51.89, 48.11, 3.79 +-0.40, 0.00, 49.38, 50.62, -1.25 +-0.40, 0.00, 51.85, 48.15, 3.70 +-0.40, 0.00, 51.85, 48.15, 3.70 +-0.26, 0.00, 46.81, 53.19, -6.38 +-0.26, 0.00, 51.75, 48.25, 3.51 +-0.26, 0.00, 51.75, 48.25, 3.51 +-0.20, 0.00, 49.23, 50.77, -1.53 +-0.20, 0.00, 51.71, 48.29, 3.41 +-0.20, 0.00, 51.71, 48.29, 3.41 +-0.20, 0.00, 51.71, 48.29, 3.42 +-0.20, 0.00, 51.71, 48.29, 3.42 +-0.20, 0.00, 51.71, 48.29, 3.42 +-0.13, 0.00, 49.19, 50.81, -1.62 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +0.00, 0.00, 46.62, 53.38, -6.76 +0.00, 0.00, 51.56, 48.44, 3.13 +0.00, 0.00, 51.56, 48.44, 3.13 +0.07, 0.00, 49.04, 50.96, -1.92 +0.07, 0.00, 51.51, 48.49, 3.03 +0.13, 0.00, 48.99, 51.01, -2.02 +0.13, 0.00, 51.46, 48.54, 2.93 +0.26, 0.00, 46.42, 53.58, -7.16 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.71 +0.33, 0.00, 48.83, 51.17, -2.33 +0.33, 0.00, 51.31, 48.69, 2.61 +0.33, 0.00, 51.30, 48.70, 2.61 +0.33, 0.00, 51.30, 48.70, 2.61 +0.40, 0.00, 48.78, 51.22, -2.44 +0.40, 0.00, 51.25, 48.75, 2.50 +0.40, 0.00, 51.25, 48.75, 2.50 +0.40, 0.00, 51.25, 48.75, 2.49 +0.53, 0.00, 46.20, 53.80, -7.59 +0.53, 0.00, 51.14, 48.86, 2.29 +0.53, 0.00, 51.14, 48.86, 2.28 +0.53, 0.00, 51.14, 48.86, 2.28 +0.53, 0.00, 51.14, 48.86, 2.28 +0.53, 0.00, 51.14, 48.86, 2.27 +0.59, 0.00, 48.61, 51.39, -2.77 +0.59, 0.00, 51.08, 48.92, 2.17 +0.59, 0.00, 51.08, 48.92, 2.16 +0.53, 0.00, 53.60, 46.40, 7.20 +0.53, 0.00, 51.13, 48.87, 2.25 +0.53, 0.00, 51.12, 48.88, 2.25 +0.53, 0.00, 51.12, 48.88, 2.24 +0.53, 0.00, 51.12, 48.88, 2.24 +0.53, 0.00, 51.12, 48.88, 2.24 +0.53, 0.00, 51.12, 48.88, 2.23 +0.40, 0.00, 56.16, 43.84, 12.31 +0.53, 0.00, 46.17, 53.83, -7.66 +0.40, 0.00, 56.15, 43.85, 12.31 +0.40, 0.00, 51.21, 48.79, 2.42 +0.40, 0.00, 51.21, 48.79, 2.41 +0.40, 0.00, 51.21, 48.79, 2.41 +0.40, 0.00, 51.20, 48.80, 2.41 +0.40, 0.00, 51.20, 48.80, 2.41 +0.40, 0.00, 51.20, 48.80, 2.40 +0.40, 0.00, 51.20, 48.80, 2.40 +0.40, 0.00, 51.20, 48.80, 2.40 +0.40, 0.00, 51.20, 48.80, 2.39 +0.33, 0.00, 53.72, 46.28, 7.43 +0.33, 0.00, 51.24, 48.76, 2.49 +0.26, 0.00, 53.76, 46.24, 7.53 +0.26, 0.00, 51.29, 48.71, 2.58 +0.26, 0.00, 51.29, 48.71, 2.58 +0.13, 0.00, 56.33, 43.67, 12.66 +0.13, 0.00, 51.39, 48.61, 2.78 +0.13, 0.00, 51.39, 48.61, 2.77 +0.07, 0.00, 53.91, 46.09, 7.82 +0.07, 0.00, 51.44, 48.56, 2.87 +0.07, 0.00, 51.44, 48.56, 2.87 +0.07, 0.00, 51.44, 48.56, 2.87 +0.07, 0.00, 51.44, 48.56, 2.87 +0.00, 0.00, 53.96, 46.04, 7.91 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +-0.13, 0.00, 56.53, 43.47, 13.06 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.20, 0.00, 54.11, 45.89, 8.21 +-0.20, 0.00, 51.64, 48.36, 3.27 +-0.20, 0.00, 51.64, 48.36, 3.27 +-0.26, 0.00, 54.16, 45.84, 8.32 +-0.26, 0.00, 51.69, 48.31, 3.38 +-0.40, 0.00, 56.73, 43.27, 13.46 +-0.40, 0.00, 51.79, 48.21, 3.58 +-0.40, 0.00, 51.79, 48.21, 3.58 +-0.46, 0.00, 54.31, 45.69, 8.63 +-0.46, 0.00, 51.84, 48.16, 3.69 +-0.46, 0.00, 51.85, 48.15, 3.69 +-0.53, 0.00, 54.37, 45.63, 8.74 +-0.53, 0.00, 51.90, 48.10, 3.80 +-0.53, 0.00, 51.90, 48.10, 3.80 +-0.53, 0.00, 51.90, 48.10, 3.81 +-0.53, 0.00, 51.91, 48.09, 3.81 +-0.66, 0.00, 56.95, 43.05, 13.90 +-0.66, 0.00, 52.01, 47.99, 4.02 +-0.66, 0.00, 52.01, 47.99, 4.02 +-0.73, 0.00, 54.54, 45.46, 9.07 +-0.73, 0.00, 52.07, 47.93, 4.13 +-0.73, 0.00, 52.07, 47.93, 4.14 +-0.79, 0.00, 54.59, 45.41, 9.19 +-0.79, 0.00, 52.12, 47.88, 4.25 +-0.79, 0.00, 52.13, 47.87, 4.26 +-0.79, 0.00, 52.13, 47.87, 4.26 +-0.92, 0.00, 57.18, 42.82, 14.35 +-0.92, 0.00, 52.24, 47.76, 4.47 +-0.92, 0.00, 52.24, 47.76, 4.48 +-0.92, 0.00, 52.24, 47.76, 4.49 +-0.92, 0.00, 52.25, 47.75, 4.49 +-0.99, 0.00, 54.77, 45.23, 9.54 +-0.99, 0.00, 52.30, 47.70, 4.61 +-0.99, 0.00, 52.31, 47.69, 4.61 +-0.99, 0.00, 52.31, 47.69, 4.62 +-0.99, 0.00, 52.31, 47.69, 4.63 +-0.99, 0.00, 52.32, 47.68, 4.64 +-0.99, 0.00, 52.32, 47.68, 4.64 +-0.99, 0.00, 52.33, 47.67, 4.65 +-0.99, 0.00, 52.33, 47.67, 4.66 +-0.99, 0.00, 52.33, 47.67, 4.67 +-0.99, 0.00, 52.34, 47.66, 4.67 +-0.99, 0.00, 52.34, 47.66, 4.68 +-0.99, 0.00, 52.34, 47.66, 4.69 +-0.99, 0.00, 52.35, 47.65, 4.70 +-0.99, 0.00, 52.35, 47.65, 4.70 +-0.99, 0.00, 52.36, 47.64, 4.71 +-0.99, 0.00, 52.36, 47.64, 4.72 +-0.99, 0.00, 52.36, 47.64, 4.73 +-0.99, 0.00, 52.37, 47.63, 4.73 +-0.99, 0.00, 52.37, 47.63, 4.74 +-0.99, 0.00, 52.37, 47.63, 4.75 +-0.99, 0.00, 52.38, 47.62, 4.76 +-0.99, 0.00, 52.38, 47.62, 4.76 +-0.99, 0.00, 52.39, 47.61, 4.77 +-0.99, 0.00, 52.39, 47.61, 4.78 +-0.99, 0.00, 52.39, 47.61, 4.79 +-0.99, 0.00, 52.40, 47.60, 4.79 +-0.99, 0.00, 52.40, 47.60, 4.80 +-0.99, 0.00, 52.40, 47.60, 4.81 +-0.99, 0.00, 52.41, 47.59, 4.81 +-0.99, 0.00, 52.41, 47.59, 4.82 +-0.99, 0.00, 52.41, 47.59, 4.83 +-0.99, 0.00, 52.42, 47.58, 4.84 +-0.99, 0.00, 52.42, 47.58, 4.84 +-0.92, 0.00, 49.90, 50.10, -0.19 +-0.92, 0.00, 52.38, 47.62, 4.76 +-0.92, 0.00, 52.38, 47.62, 4.77 +-0.92, 0.00, 52.39, 47.61, 4.77 +-0.79, 0.00, 47.35, 52.65, -5.31 +-0.79, 0.00, 52.29, 47.71, 4.59 +-0.79, 0.00, 52.30, 47.70, 4.59 +-0.79, 0.00, 52.30, 47.70, 4.60 +-0.79, 0.00, 52.30, 47.70, 4.61 +-0.79, 0.00, 52.31, 47.69, 4.61 +-0.73, 0.00, 49.79, 50.21, -0.43 +-0.73, 0.00, 52.26, 47.74, 4.52 +-0.73, 0.00, 52.26, 47.74, 4.53 +-0.73, 0.00, 52.27, 47.73, 4.53 +-0.73, 0.00, 52.27, 47.73, 4.54 +-0.73, 0.00, 52.27, 47.73, 4.54 +-0.73, 0.00, 52.28, 47.72, 4.55 +-0.66, 0.00, 49.76, 50.24, -0.49 +-0.66, 0.00, 52.23, 47.77, 4.46 +-0.66, 0.00, 52.23, 47.77, 4.47 +-0.66, 0.00, 52.24, 47.76, 4.47 +-0.66, 0.00, 52.24, 47.76, 4.48 +-0.66, 0.00, 52.24, 47.76, 4.48 +-0.66, 0.00, 52.24, 47.76, 4.49 +-0.66, 0.00, 52.25, 47.75, 4.49 +-0.53, 0.00, 47.20, 52.80, -5.59 +-0.53, 0.00, 52.15, 47.85, 4.30 +-0.53, 0.00, 52.15, 47.85, 4.30 +-0.53, 0.00, 52.15, 47.85, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.33 +-0.46, 0.00, 49.64, 50.36, -0.71 +-0.46, 0.00, 52.12, 47.88, 4.24 +-0.46, 0.00, 52.12, 47.88, 4.24 +-0.46, 0.00, 52.12, 47.88, 4.24 +-0.46, 0.00, 52.12, 47.88, 4.25 +-0.46, 0.00, 52.13, 47.87, 4.25 +-0.46, 0.00, 52.13, 47.87, 4.25 +-0.40, 0.00, 49.61, 50.39, -0.79 +-0.40, 0.00, 52.08, 47.92, 4.16 +-0.40, 0.00, 52.08, 47.92, 4.16 +-0.40, 0.00, 52.08, 47.92, 4.17 +-0.40, 0.00, 52.08, 47.92, 4.17 +-0.40, 0.00, 52.09, 47.91, 4.17 +-0.40, 0.00, 52.09, 47.91, 4.18 +-0.40, 0.00, 52.09, 47.91, 4.18 +-0.40, 0.00, 52.09, 47.91, 4.18 +-0.40, 0.00, 52.09, 47.91, 4.18 +-0.40, 0.00, 52.09, 47.91, 4.19 +-0.40, 0.00, 52.10, 47.90, 4.19 +-0.26, 0.00, 47.05, 52.95, -5.89 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.01 +-0.26, 0.00, 52.00, 48.00, 4.01 +-0.26, 0.00, 52.01, 47.99, 4.01 +-0.26, 0.00, 52.01, 47.99, 4.01 +-0.20, 0.00, 49.49, 50.51, -1.03 +-0.20, 0.00, 51.96, 48.04, 3.92 +-0.20, 0.00, 51.96, 48.04, 3.92 +-0.26, 0.00, 54.48, 45.52, 8.96 +-0.20, 0.00, 49.49, 50.51, -1.02 +-0.26, 0.00, 54.48, 45.52, 8.97 +-0.26, 0.00, 52.01, 47.99, 4.02 +-0.26, 0.00, 52.01, 47.99, 4.03 +-0.26, 0.00, 52.01, 47.99, 4.03 +-0.20, 0.00, 49.49, 50.51, -1.01 +-0.20, 0.00, 51.97, 48.03, 3.93 +-0.20, 0.00, 51.97, 48.03, 3.93 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.95 +-0.20, 0.00, 51.97, 48.03, 3.95 +-0.20, 0.00, 51.97, 48.03, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.13, 0.00, 49.46, 50.54, -1.08 +-0.13, 0.00, 51.93, 48.07, 3.87 +-0.13, 0.00, 51.93, 48.07, 3.87 +-0.13, 0.00, 51.93, 48.07, 3.87 +0.00, 0.00, 46.89, 53.11, -6.22 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.07, 0.00, 49.31, 50.69, -1.37 +0.07, 0.00, 51.78, 48.22, 3.57 +0.13, 0.00, 49.26, 50.74, -1.47 +0.13, 0.00, 51.73, 48.27, 3.47 +0.26, 0.00, 46.69, 53.31, -6.62 +0.26, 0.00, 51.63, 48.37, 3.27 +0.26, 0.00, 51.63, 48.37, 3.27 +0.33, 0.00, 49.11, 50.89, -1.78 +0.33, 0.00, 51.58, 48.42, 3.16 +0.33, 0.00, 51.58, 48.42, 3.16 +0.33, 0.00, 51.58, 48.42, 3.16 +0.40, 0.00, 49.06, 50.94, -1.89 +0.40, 0.00, 51.53, 48.47, 3.05 +0.40, 0.00, 51.52, 48.48, 3.05 +0.40, 0.00, 51.52, 48.48, 3.05 +0.40, 0.00, 51.52, 48.48, 3.04 +0.40, 0.00, 51.52, 48.48, 3.04 +0.40, 0.00, 51.52, 48.48, 3.04 +0.40, 0.00, 51.52, 48.48, 3.03 +0.53, 0.00, 46.47, 53.53, -7.06 +0.53, 0.00, 51.41, 48.59, 2.83 +0.59, 0.00, 48.89, 51.11, -2.22 +0.59, 0.00, 51.36, 48.64, 2.72 +0.59, 0.00, 51.36, 48.64, 2.72 +0.66, 0.00, 48.83, 51.17, -2.33 +0.66, 0.00, 51.30, 48.70, 2.61 +0.79, 0.00, 46.26, 53.74, -7.48 +0.79, 0.00, 51.20, 48.80, 2.40 +0.79, 0.00, 51.20, 48.80, 2.39 +0.79, 0.00, 51.19, 48.81, 2.39 +0.79, 0.00, 51.19, 48.81, 2.38 +0.79, 0.00, 51.19, 48.81, 2.37 +0.79, 0.00, 51.18, 48.82, 2.37 +0.79, 0.00, 51.18, 48.82, 2.36 +0.79, 0.00, 51.18, 48.82, 2.36 +0.79, 0.00, 51.18, 48.82, 2.35 +0.79, 0.00, 51.17, 48.83, 2.34 +0.86, 0.00, 48.65, 51.35, -2.70 +0.86, 0.00, 51.12, 48.88, 2.23 +0.86, 0.00, 51.11, 48.89, 2.23 +0.92, 0.00, 48.59, 51.41, -2.82 +0.92, 0.00, 51.06, 48.94, 2.11 +1.05, 0.00, 46.01, 53.99, -7.98 +1.05, 0.00, 50.95, 49.05, 1.90 +1.05, 0.00, 50.95, 49.05, 1.89 +1.12, 0.00, 48.42, 51.58, -3.16 +1.12, 0.00, 50.89, 49.11, 1.78 +1.12, 0.00, 50.88, 49.12, 1.77 +1.12, 0.00, 50.88, 49.12, 1.76 +1.12, 0.00, 50.88, 49.12, 1.75 +1.12, 0.00, 50.87, 49.13, 1.74 +1.12, 0.00, 50.87, 49.13, 1.73 +1.05, 0.00, 53.38, 46.62, 6.77 +1.12, 0.00, 48.39, 51.61, -3.23 +1.12, 0.00, 50.85, 49.15, 1.71 +1.12, 0.00, 50.85, 49.15, 1.70 +1.12, 0.00, 50.85, 49.15, 1.69 +1.12, 0.00, 50.84, 49.16, 1.68 +1.12, 0.00, 50.84, 49.16, 1.68 +1.19, 0.00, 48.31, 51.69, -3.38 +1.19, 0.00, 50.78, 49.22, 1.56 +1.19, 0.00, 50.78, 49.22, 1.55 +1.19, 0.00, 50.77, 49.23, 1.54 +1.19, 0.00, 50.77, 49.23, 1.53 +1.32, 0.00, 45.72, 54.28, -8.56 +1.32, 0.00, 50.66, 49.34, 1.31 +1.32, 0.00, 50.65, 49.35, 1.31 +1.32, 0.00, 50.65, 49.35, 1.30 +1.19, 0.00, 55.69, 44.31, 11.37 +1.19, 0.00, 50.74, 49.26, 1.48 +1.19, 0.00, 50.73, 49.27, 1.47 +1.19, 0.00, 50.73, 49.27, 1.46 +1.19, 0.00, 50.72, 49.28, 1.45 +1.12, 0.00, 53.24, 46.76, 6.48 +1.12, 0.00, 50.77, 49.23, 1.53 +1.12, 0.00, 50.76, 49.24, 1.52 +1.19, 0.00, 48.24, 51.76, -3.53 +1.19, 0.00, 50.70, 49.30, 1.41 +1.19, 0.00, 50.70, 49.30, 1.40 +1.19, 0.00, 50.69, 49.31, 1.39 +1.19, 0.00, 50.69, 49.31, 1.38 +1.32, 0.00, 45.64, 54.36, -8.72 +1.32, 0.00, 50.58, 49.42, 1.16 +1.32, 0.00, 50.58, 49.42, 1.15 +1.32, 0.00, 50.57, 49.43, 1.14 +1.19, 0.00, 55.61, 44.39, 11.22 +1.19, 0.00, 50.66, 49.34, 1.32 +1.19, 0.00, 50.66, 49.34, 1.31 +1.12, 0.00, 53.17, 46.83, 6.35 +1.12, 0.00, 50.70, 49.30, 1.39 +1.12, 0.00, 50.69, 49.31, 1.39 +1.12, 0.00, 50.69, 49.31, 1.38 +1.05, 0.00, 53.21, 46.79, 6.41 +1.05, 0.00, 50.73, 49.27, 1.46 +1.05, 0.00, 50.73, 49.27, 1.45 +0.92, 0.00, 55.77, 44.23, 11.53 +0.92, 0.00, 50.82, 49.18, 1.64 +0.92, 0.00, 50.81, 49.19, 1.63 +0.92, 0.00, 50.81, 49.19, 1.62 +0.92, 0.00, 50.81, 49.19, 1.62 +0.92, 0.00, 50.80, 49.20, 1.61 +0.92, 0.00, 50.80, 49.20, 1.60 +0.92, 0.00, 50.80, 49.20, 1.60 +0.92, 0.00, 50.79, 49.21, 1.59 +0.86, 0.00, 53.31, 46.69, 6.62 +0.86, 0.00, 50.84, 49.16, 1.67 +0.86, 0.00, 50.83, 49.17, 1.67 +0.86, 0.00, 50.83, 49.17, 1.66 +0.79, 0.00, 53.35, 46.65, 6.70 +0.79, 0.00, 50.87, 49.13, 1.75 +0.79, 0.00, 50.87, 49.13, 1.74 +0.66, 0.00, 55.91, 44.09, 11.82 +0.66, 0.00, 50.97, 49.03, 1.93 +0.59, 0.00, 53.48, 46.52, 6.97 +0.59, 0.00, 51.01, 48.99, 2.02 +0.59, 0.00, 51.01, 48.99, 2.02 +0.53, 0.00, 53.53, 46.47, 7.05 +0.53, 0.00, 51.05, 48.95, 2.11 +0.53, 0.00, 51.05, 48.95, 2.10 +0.53, 0.00, 51.05, 48.95, 2.10 +0.40, 0.00, 56.09, 43.91, 12.18 +0.40, 0.00, 51.15, 48.85, 2.29 +0.40, 0.00, 51.14, 48.86, 2.29 +0.40, 0.00, 51.14, 48.86, 2.28 +0.33, 0.00, 53.66, 46.34, 7.33 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.37 +0.33, 0.00, 51.19, 48.81, 2.37 +0.26, 0.00, 53.71, 46.29, 7.41 +0.26, 0.00, 51.23, 48.77, 2.47 +0.26, 0.00, 51.23, 48.77, 2.46 +0.26, 0.00, 51.23, 48.77, 2.46 +0.13, 0.00, 56.27, 43.73, 12.55 +0.13, 0.00, 51.33, 48.67, 2.66 +0.07, 0.00, 53.85, 46.15, 7.70 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.75 +0.00, 0.00, 53.90, 46.10, 7.80 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +-0.13, 0.00, 56.47, 43.53, 12.94 +-0.13, 0.00, 51.53, 48.47, 3.05 +-0.13, 0.00, 51.53, 48.47, 3.05 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 54.06, 45.94, 8.12 +-0.20, 0.00, 51.59, 48.41, 3.17 +-0.20, 0.00, 51.59, 48.41, 3.17 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.13, 0.00, 49.07, 50.93, -1.86 +-0.20, 0.00, 54.06, 45.94, 8.13 +-0.13, 0.00, 49.07, 50.93, -1.86 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 54.07, 45.93, 8.14 +-0.20, 0.00, 51.60, 48.40, 3.20 +-0.13, 0.00, 49.08, 50.92, -1.84 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 54.08, 45.92, 8.16 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.23 +-0.20, 0.00, 51.61, 48.39, 3.23 +-0.13, 0.00, 49.09, 50.91, -1.82 +-0.13, 0.00, 51.56, 48.44, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.14 +-0.13, 0.00, 51.57, 48.43, 3.14 +-0.13, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 54.09, 45.91, 8.18 +-0.20, 0.00, 51.62, 48.38, 3.24 +-0.20, 0.00, 51.62, 48.38, 3.24 +-0.20, 0.00, 51.62, 48.38, 3.24 +-0.20, 0.00, 51.62, 48.38, 3.24 +-0.20, 0.00, 51.62, 48.38, 3.25 +-0.20, 0.00, 51.62, 48.38, 3.25 +-0.20, 0.00, 51.62, 48.38, 3.25 +-0.20, 0.00, 51.62, 48.38, 3.25 +-0.20, 0.00, 51.63, 48.37, 3.25 +-0.20, 0.00, 51.63, 48.37, 3.25 +-0.13, 0.00, 49.11, 50.89, -1.79 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +0.00, 0.00, 46.54, 53.46, -6.92 +0.00, 0.00, 51.48, 48.52, 2.97 +0.00, 0.00, 51.48, 48.52, 2.97 +0.00, 0.00, 51.48, 48.52, 2.97 +0.00, 0.00, 51.48, 48.52, 2.97 +0.07, 0.00, 48.96, 51.04, -2.07 +0.07, 0.00, 51.43, 48.57, 2.87 +0.07, 0.00, 51.43, 48.57, 2.87 +0.07, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 48.91, 51.09, -2.18 +0.13, 0.00, 51.38, 48.62, 2.77 +0.13, 0.00, 51.38, 48.62, 2.77 +0.13, 0.00, 51.38, 48.62, 2.77 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.26, 0.00, 46.34, 53.66, -7.33 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.55 +0.26, 0.00, 51.28, 48.72, 2.55 +0.33, 0.00, 48.75, 51.25, -2.49 +0.33, 0.00, 51.22, 48.78, 2.45 +0.40, 0.00, 48.70, 51.30, -2.60 +0.40, 0.00, 51.17, 48.83, 2.34 +0.40, 0.00, 51.17, 48.83, 2.34 +0.40, 0.00, 51.17, 48.83, 2.34 +0.40, 0.00, 51.17, 48.83, 2.34 +0.40, 0.00, 51.17, 48.83, 2.33 +0.40, 0.00, 51.16, 48.84, 2.33 +0.53, 0.00, 46.12, 53.88, -7.76 +0.53, 0.00, 51.06, 48.94, 2.12 +0.53, 0.00, 51.06, 48.94, 2.12 +0.53, 0.00, 51.06, 48.94, 2.12 +0.53, 0.00, 51.06, 48.94, 2.11 +0.53, 0.00, 51.05, 48.95, 2.11 +0.59, 0.00, 48.53, 51.47, -2.94 +0.59, 0.00, 51.00, 49.00, 2.00 +0.59, 0.00, 51.00, 49.00, 2.00 +0.59, 0.00, 51.00, 49.00, 1.99 +0.59, 40.00, 75.00, 25.00, 50.00 +0.59, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.79, 40.00, 75.00, 25.00, 50.00 +0.79, 40.00, 75.00, 25.00, 50.00 +0.79, 40.00, 75.00, 25.00, 50.00 +0.86, 40.00, 75.00, 25.00, 50.00 +0.92, 40.00, 75.00, 25.00, 50.00 +0.92, 40.00, 75.00, 25.00, 50.00 +1.12, 40.00, 75.00, 25.00, 50.00 +1.19, 40.00, 75.00, 25.00, 50.00 +1.32, 40.00, 75.00, 25.00, 50.00 +1.38, 40.00, 75.00, 25.00, 50.00 +1.58, 40.00, 75.00, 25.00, 50.00 +1.71, 40.00, 75.00, 25.00, 50.00 +1.85, 40.00, 75.00, 25.00, 50.00 +1.98, 40.00, 75.00, 25.00, 50.00 +2.24, 40.00, 73.23, 26.77, 46.46 +2.44, 40.00, 75.00, 25.00, 50.00 +2.64, 40.00, 75.00, 25.00, 50.00 +2.90, 40.00, 73.16, 26.84, 46.31 +3.03, 40.00, 75.00, 25.00, 50.00 +3.30, 40.00, 73.14, 26.86, 46.27 +3.69, 40.00, 68.03, 31.97, 36.06 +3.82, 40.00, 75.00, 25.00, 50.00 +4.09, 40.00, 72.95, 27.05, 45.90 +4.48, 40.00, 67.84, 32.16, 35.68 +4.81, 40.00, 70.20, 29.80, 40.40 +5.08, 40.00, 72.60, 27.40, 45.21 +5.54, 40.00, 64.97, 35.03, 29.94 +5.80, 40.00, 72.32, 27.68, 44.63 +6.20, 40.00, 67.20, 32.80, 34.41 +6.59, 40.00, 67.03, 32.97, 34.06 +6.92, 40.00, 69.38, 30.62, 38.76 +7.38, 40.00, 64.21, 35.79, 28.43 +7.78, 40.00, 66.51, 33.49, 33.02 +8.24, 40.00, 63.81, 36.19, 27.62 +8.70, 40.00, 63.58, 36.42, 27.16 +9.23, 40.00, 60.83, 39.17, 21.66 +9.62, 40.00, 65.59, 34.41, 31.18 +10.15, 40.00, 60.36, 39.64, 20.73 +10.68, 40.00, 60.08, 39.92, 20.15 +11.21, 40.00, 59.79, 40.21, 19.58 +11.73, 40.00, 59.50, 40.50, 19.00 +12.26, 40.00, 59.21, 40.79, 18.42 +12.72, 40.00, 61.44, 38.56, 22.87 +13.32, 40.00, 56.15, 43.85, 12.30 +13.84, 40.00, 58.32, 41.68, 16.65 +14.37, 40.00, 58.02, 41.98, 16.05 +14.90, 40.00, 57.72, 42.28, 15.44 +15.56, 40.00, 52.38, 47.62, 4.75 +16.08, 40.00, 57.01, 42.99, 14.03 +16.68, 40.00, 54.18, 45.82, 8.37 +17.20, 40.00, 56.35, 43.65, 12.69 +17.80, 40.00, 53.51, 46.49, 7.02 +18.46, 40.00, 50.63, 49.37, 1.25 +19.05, 40.00, 52.73, 47.27, 5.46 +19.64, 40.00, 52.36, 47.64, 4.73 +20.30, 40.00, 49.47, 50.53, -1.06 +20.83, 40.00, 54.09, 45.91, 8.18 +21.42, 40.00, 51.24, 48.76, 2.49 +22.02, 40.00, 50.87, 49.13, 1.73 +22.54, 40.00, 53.01, 46.99, 6.02 +23.07, 40.00, 52.68, 47.32, 5.35 +23.73, 40.00, 47.30, 52.70, -5.40 +24.26, 40.00, 51.91, 48.09, 3.81 +24.79, 40.00, 51.57, 48.43, 3.14 +25.38, 40.00, 48.71, 51.29, -2.59 +25.91, 40.00, 50.84, 49.16, 1.67 +26.50, 40.00, 47.97, 52.03, -4.06 +27.16, 40.00, 45.05, 54.95, -9.90 +27.69, 40.00, 49.65, 50.35, -0.71 +28.28, 40.00, 46.77, 53.23, -6.45 +28.81, 40.00, 48.89, 51.11, -2.22 +29.40, 40.00, 46.01, 53.99, -7.97 +29.93, 40.00, 48.13, 51.87, -3.74 +30.45, 40.00, 47.77, 52.23, -4.46 +30.92, 40.00, 49.93, 50.07, -0.14 +31.44, 40.00, 47.09, 52.91, -5.81 +31.97, 40.00, 46.73, 53.27, -6.54 +32.43, 40.00, 48.88, 51.12, -2.24 +32.83, 40.00, 51.08, 48.92, 2.17 +33.35, 40.00, 45.77, 54.23, -8.46 +33.75, 40.00, 50.44, 49.56, 0.88 +34.15, 40.00, 50.17, 49.83, 0.33 +34.61, 40.00, 47.37, 52.63, -5.26 +35.13, 40.00, 44.52, 55.48, -10.96 +35.60, 40.00, 46.66, 53.34, -6.68 +36.12, 40.00, 43.81, 56.19, -12.38 +36.52, 40.00, 48.47, 51.53, -3.06 +36.98, 40.00, 45.66, 54.34, -8.68 +37.44, 40.00, 45.33, 54.67, -9.35 +37.77, 40.00, 50.03, 49.97, 0.06 +38.23, 40.00, 44.75, 55.25, -10.51 +38.56, 40.00, 49.45, 50.55, -1.10 +38.89, 40.00, 49.21, 50.79, -1.59 +39.16, 40.00, 51.48, 48.52, 2.97 +39.55, 40.00, 46.24, 53.76, -7.51 +39.81, 40.00, 50.99, 49.01, 1.98 +40.08, 40.00, 50.79, 49.21, 1.59 +40.41, 40.00, 48.07, 51.93, -3.85 +40.67, 40.00, 50.34, 49.66, 0.69 +40.94, 40.00, 50.14, 49.86, 0.29 +41.13, 40.00, 52.46, 47.54, 4.92 +41.13, 40.00, 59.87, 40.13, 19.75 +41.13, 40.00, 59.87, 40.13, 19.74 +40.94, 40.00, 67.43, 32.57, 34.86 +40.87, 40.00, 62.53, 37.47, 25.07 +40.74, 40.00, 65.10, 34.90, 30.20 +40.61, 40.00, 65.20, 34.80, 30.39 +40.47, 40.00, 65.29, 34.71, 30.59 +40.67, 40.00, 52.78, 47.22, 5.57 +40.94, 40.00, 50.11, 49.89, 0.22 +40.94, 40.00, 59.99, 40.01, 19.99 +40.87, 40.00, 62.51, 37.49, 25.03 +40.94, 40.00, 57.52, 42.48, 15.03 +40.87, 40.00, 62.51, 37.49, 25.01 +40.74, 40.00, 65.07, 34.93, 30.15 +40.67, 40.00, 62.65, 37.35, 25.30 +40.47, 40.00, 67.74, 32.26, 35.48 +40.34, 40.00, 65.37, 34.63, 30.73 +40.14, 40.00, 67.99, 32.01, 35.97 +39.88, 40.00, 70.66, 29.34, 41.31 +39.62, 40.00, 70.85, 29.15, 41.71 +39.35, 40.00, 71.05, 28.95, 42.11 +39.16, 40.00, 68.73, 31.27, 37.47 +39.02, 40.00, 66.36, 33.64, 32.73 +38.83, 40.00, 68.99, 31.01, 37.98 +38.76, 40.00, 64.10, 35.90, 28.20 +38.63, 40.00, 66.68, 33.32, 33.35 +38.56, 40.00, 64.26, 35.74, 28.52 +38.56, 40.00, 61.79, 38.21, 23.58 +38.56, 40.00, 61.80, 38.20, 23.59 +38.56, 40.00, 61.80, 38.20, 23.61 +38.50, 40.00, 64.33, 35.67, 28.66 +38.50, 40.00, 61.86, 38.14, 23.73 +38.50, 40.00, 61.87, 38.13, 23.74 +38.36, 40.00, 66.92, 33.08, 33.84 +38.30, 40.00, 64.50, 35.50, 29.00 +38.30, 40.00, 62.04, 37.96, 24.07 +38.23, 40.00, 64.56, 35.44, 29.13 +38.10, 40.00, 67.14, 32.86, 34.28 +38.10, 40.00, 62.21, 37.79, 24.41 +38.03, 40.00, 64.73, 35.27, 29.47 +38.03, 40.00, 62.27, 37.73, 24.54 +38.03, 40.00, 62.28, 37.72, 24.55 +38.03, 40.00, 62.28, 37.72, 24.57 +38.10, 40.00, 59.77, 40.23, 19.54 +38.23, 40.00, 57.21, 42.79, 14.41 +38.30, 40.00, 59.63, 40.37, 19.27 +38.36, 40.00, 59.59, 40.41, 19.18 +38.56, 40.00, 54.50, 45.50, 9.01 +38.63, 40.00, 59.40, 40.60, 18.81 +38.76, 40.00, 56.84, 43.16, 13.68 +38.89, 40.00, 56.74, 43.26, 13.49 +38.89, 40.00, 61.69, 38.31, 23.38 +39.02, 40.00, 56.65, 43.35, 13.30 +39.09, 40.00, 59.08, 40.92, 18.16 +39.16, 40.00, 59.03, 40.97, 18.06 +39.29, 40.00, 56.46, 43.54, 12.93 +39.29, 40.00, 61.41, 38.59, 22.82 +39.42, 40.00, 56.37, 43.63, 12.74 +39.55, 40.00, 56.27, 43.73, 12.55 +39.62, 40.00, 58.70, 41.30, 17.39 +39.81, 40.00, 53.61, 46.39, 7.21 +39.88, 40.00, 58.50, 41.50, 17.00 +40.08, 40.00, 53.41, 46.59, 6.82 +40.21, 40.00, 55.78, 44.22, 11.56 +40.41, 40.00, 53.16, 46.84, 6.32 +40.47, 40.00, 58.05, 41.95, 16.10 +40.67, 40.00, 52.96, 47.04, 5.91 +40.87, 40.00, 52.80, 47.20, 5.61 +41.00, 40.00, 55.17, 44.83, 10.35 +41.13, 40.00, 55.07, 44.93, 10.14 +41.20, 40.00, 57.49, 42.51, 14.98 +41.26, 40.00, 57.43, 42.57, 14.87 +41.20, 40.00, 62.42, 37.58, 24.85 +41.20, 40.00, 59.95, 40.05, 19.89 +41.13, 40.00, 62.46, 37.54, 24.93 +41.00, 40.00, 65.03, 34.97, 30.06 +40.94, 40.00, 62.60, 37.40, 25.21 +40.87, 40.00, 62.65, 37.35, 25.30 +40.74, 40.00, 65.22, 34.78, 30.44 +40.74, 40.00, 60.27, 39.73, 20.54 +40.94, 40.00, 52.70, 47.30, 5.41 +40.94, 40.00, 60.12, 39.88, 20.23 +41.00, 40.00, 57.59, 42.41, 15.18 +41.00, 40.00, 60.06, 39.94, 20.12 +41.13, 40.00, 55.01, 44.99, 10.03 +41.13, 40.00, 59.95, 40.05, 19.91 +41.13, 40.00, 59.95, 40.05, 19.90 +41.13, 40.00, 59.94, 40.06, 19.89 +41.00, 40.00, 64.98, 35.02, 29.97 +41.00, 40.00, 60.04, 39.96, 20.07 +40.94, 40.00, 62.55, 37.45, 25.11 +40.74, 40.00, 67.64, 32.36, 35.29 +40.61, 40.00, 65.27, 34.73, 30.54 +40.47, 40.00, 65.36, 34.64, 30.73 +40.41, 40.00, 62.94, 37.06, 25.88 +40.34, 40.00, 62.99, 37.01, 25.98 +40.21, 40.00, 65.56, 34.44, 31.12 +40.21, 40.00, 60.61, 39.39, 21.23 +40.21, 40.00, 60.61, 39.39, 21.23 +40.34, 40.00, 55.57, 44.43, 11.14 +40.34, 40.00, 60.51, 39.49, 21.02 +40.41, 40.00, 57.99, 42.01, 15.98 +40.47, 40.00, 57.94, 42.06, 15.88 +40.61, 40.00, 55.36, 44.64, 10.73 +40.61, 40.00, 60.31, 39.69, 20.61 +40.67, 40.00, 57.78, 42.22, 15.57 +40.74, 40.00, 57.73, 42.27, 15.46 +40.74, 40.00, 60.20, 39.80, 20.40 +40.74, 40.00, 60.20, 39.80, 20.39 +40.74, 40.00, 60.19, 39.81, 20.39 +40.87, 40.00, 55.15, 44.85, 10.30 +40.74, 40.00, 65.13, 34.87, 30.26 +40.87, 40.00, 55.14, 44.86, 10.28 +40.87, 40.00, 60.08, 39.92, 20.17 +40.94, 40.00, 57.56, 42.44, 15.12 +40.94, 40.00, 60.03, 39.97, 20.05 +41.00, 40.00, 57.50, 42.50, 15.00 +41.13, 40.00, 54.93, 45.07, 9.85 +41.20, 40.00, 57.34, 42.66, 14.69 +41.20, 40.00, 59.81, 40.19, 19.62 +41.20, 40.00, 59.81, 40.19, 19.61 +41.20, 40.00, 59.80, 40.20, 19.60 +41.20, 40.00, 59.80, 40.20, 19.60 +41.13, 40.00, 62.32, 37.68, 24.63 +41.13, 40.00, 59.84, 40.16, 19.68 +41.13, 40.00, 59.83, 40.17, 19.67 +41.00, 40.00, 64.87, 35.13, 29.75 +41.13, 40.00, 54.88, 45.12, 9.77 +41.13, 40.00, 59.82, 40.18, 19.64 +41.13, 40.00, 59.82, 40.18, 19.64 +41.13, 40.00, 59.81, 40.19, 19.63 +41.13, 40.00, 59.81, 40.19, 19.62 +41.13, 40.00, 59.81, 40.19, 19.61 +41.13, 40.00, 59.80, 40.20, 19.60 +41.13, 40.00, 59.80, 40.20, 19.59 +41.13, 40.00, 59.79, 40.21, 19.59 +41.13, 40.00, 59.79, 40.21, 19.58 +41.00, 40.00, 64.83, 35.17, 29.65 +40.94, 40.00, 62.40, 37.60, 24.80 +40.94, 40.00, 59.93, 40.07, 19.85 +40.94, 40.00, 59.92, 40.08, 19.84 +40.87, 40.00, 62.44, 37.56, 24.88 +40.74, 40.00, 65.01, 34.99, 30.02 +40.74, 40.00, 60.06, 39.94, 20.12 +40.74, 40.00, 60.06, 39.94, 20.12 +40.74, 40.00, 60.06, 39.94, 20.11 +40.74, 40.00, 60.05, 39.95, 20.11 +40.87, 40.00, 55.01, 44.99, 10.02 +40.94, 40.00, 57.43, 42.57, 14.85 +40.94, 40.00, 59.90, 40.10, 19.79 +40.94, 40.00, 59.89, 40.11, 19.78 +41.00, 40.00, 57.37, 42.63, 14.73 +41.13, 40.00, 54.79, 45.21, 9.58 +41.20, 40.00, 57.21, 42.79, 14.42 +41.26, 40.00, 57.16, 42.84, 14.31 +41.26, 40.00, 59.62, 40.38, 19.24 +41.26, 40.00, 59.62, 40.38, 19.24 +41.20, 40.00, 62.13, 37.87, 24.27 +41.20, 40.00, 59.66, 40.34, 19.32 +41.20, 40.00, 59.65, 40.35, 19.31 +41.13, 40.00, 62.17, 37.83, 24.34 +41.00, 40.00, 64.74, 35.26, 29.48 +41.00, 40.00, 59.79, 40.21, 19.58 +40.94, 40.00, 62.31, 37.69, 24.62 +40.94, 40.00, 59.83, 40.17, 19.67 +41.00, 40.00, 57.31, 42.69, 14.61 +41.00, 40.00, 59.78, 40.22, 19.55 +41.13, 40.00, 54.73, 45.27, 9.46 +41.20, 40.00, 57.15, 42.85, 14.29 +41.20, 40.00, 59.61, 40.39, 19.23 +41.26, 40.00, 57.09, 42.91, 14.18 +41.26, 40.00, 59.56, 40.44, 19.11 +41.26, 40.00, 59.55, 40.45, 19.10 +41.26, 40.00, 59.55, 40.45, 19.09 +41.20, 40.00, 62.06, 37.94, 24.13 +41.20, 40.00, 59.59, 40.41, 19.17 +41.13, 40.00, 62.10, 37.90, 24.21 +41.13, 40.00, 59.63, 40.37, 19.25 +41.00, 40.00, 64.67, 35.33, 29.33 +40.94, 40.00, 62.24, 37.76, 24.48 +40.94, 40.00, 59.76, 40.24, 19.53 +40.94, 40.00, 59.76, 40.24, 19.52 +40.94, 40.00, 59.76, 40.24, 19.52 +40.94, 40.00, 59.75, 40.25, 19.51 +41.00, 40.00, 57.23, 42.77, 14.46 +41.00, 40.00, 59.70, 40.30, 19.39 +41.13, 40.00, 54.65, 45.35, 9.30 +41.20, 40.00, 57.07, 42.93, 14.14 +41.26, 40.00, 57.01, 42.99, 14.03 +41.26, 40.00, 59.48, 40.52, 18.96 +41.26, 40.00, 59.48, 40.52, 18.95 +41.26, 40.00, 59.47, 40.53, 18.94 +41.20, 40.00, 61.99, 38.01, 23.98 +41.20, 40.00, 59.51, 40.49, 19.02 +41.20, 40.00, 59.51, 40.49, 19.02 +41.13, 40.00, 62.02, 37.98, 24.05 +41.13, 40.00, 59.55, 40.45, 19.10 +41.13, 40.00, 59.54, 40.46, 19.09 +41.13, 40.00, 59.54, 40.46, 19.08 +41.13, 40.00, 59.54, 40.46, 19.07 +41.13, 40.00, 59.53, 40.47, 19.06 +41.20, 40.00, 57.01, 42.99, 14.01 +41.20, 40.00, 59.47, 40.53, 18.95 +41.20, 40.00, 59.47, 40.53, 18.94 +41.20, 40.00, 59.46, 40.54, 18.93 +41.26, 40.00, 56.94, 43.06, 13.88 +41.20, 40.00, 61.93, 38.07, 23.85 +41.26, 40.00, 56.93, 43.07, 13.86 +41.20, 40.00, 61.92, 38.08, 23.84 +41.20, 40.00, 59.44, 40.56, 18.88 +41.13, 40.00, 61.96, 38.04, 23.92 +41.13, 40.00, 59.48, 40.52, 18.96 +41.13, 40.00, 59.48, 40.52, 18.96 +41.13, 40.00, 59.47, 40.53, 18.95 +41.13, 40.00, 59.47, 40.53, 18.94 +41.13, 40.00, 59.47, 40.53, 18.93 +41.13, 40.00, 59.46, 40.54, 18.92 +41.13, 40.00, 59.46, 40.54, 18.91 +41.20, 40.00, 56.93, 43.07, 13.86 +41.20, 40.00, 59.40, 40.60, 18.80 +41.20, 40.00, 59.39, 40.61, 18.79 +41.20, 40.00, 59.39, 40.61, 18.78 +41.20, 40.00, 59.38, 40.62, 18.77 +41.20, 40.00, 59.38, 40.62, 18.76 +41.20, 40.00, 59.38, 40.62, 18.75 +41.20, 40.00, 59.37, 40.63, 18.74 +41.13, 40.00, 61.89, 38.11, 23.78 +41.13, 40.00, 59.41, 40.59, 18.82 +41.13, 40.00, 59.41, 40.59, 18.82 +41.13, 40.00, 59.40, 40.60, 18.81 +41.13, 40.00, 59.40, 40.60, 18.80 +41.13, 40.00, 59.40, 40.60, 18.79 +41.13, 40.00, 59.39, 40.61, 18.78 +41.13, 40.00, 59.39, 40.61, 18.77 +41.20, 40.00, 56.86, 43.14, 13.72 +41.20, 40.00, 59.33, 40.67, 18.66 +41.20, 40.00, 59.32, 40.68, 18.65 +41.20, 40.00, 59.32, 40.68, 18.64 +41.20, 40.00, 59.31, 40.69, 18.63 +41.20, 40.00, 59.31, 40.69, 18.62 +41.20, 40.00, 59.31, 40.69, 18.61 +41.20, 40.00, 59.30, 40.70, 18.60 +41.20, 40.00, 59.30, 40.70, 18.59 +41.20, 40.00, 59.29, 40.71, 18.58 +41.13, 40.00, 61.81, 38.19, 23.62 +41.20, 40.00, 56.81, 43.19, 13.62 +41.20, 40.00, 59.28, 40.72, 18.56 +41.20, 40.00, 59.27, 40.73, 18.55 +41.20, 40.00, 59.27, 40.73, 18.54 +41.20, 40.00, 59.27, 40.73, 18.53 +41.20, 40.00, 59.26, 40.74, 18.52 +41.20, 40.00, 59.26, 40.74, 18.51 +41.20, 40.00, 59.25, 40.75, 18.50 +41.20, 40.00, 59.25, 40.75, 18.50 +41.20, 40.00, 59.24, 40.76, 18.49 +41.20, 40.00, 59.24, 40.76, 18.48 +41.20, 40.00, 59.23, 40.77, 18.47 +41.20, 40.00, 59.23, 40.77, 18.46 +41.20, 40.00, 59.23, 40.77, 18.45 +41.20, 40.00, 59.22, 40.78, 18.44 +41.20, 40.00, 59.22, 40.78, 18.43 +41.20, 40.00, 59.21, 40.79, 18.42 +41.20, 40.00, 59.21, 40.79, 18.41 +41.20, 40.00, 59.20, 40.80, 18.41 +41.20, 40.00, 59.20, 40.80, 18.40 +41.20, 40.00, 59.19, 40.81, 18.39 +41.20, 40.00, 59.19, 40.81, 18.38 +41.20, 40.00, 59.18, 40.82, 18.37 +41.20, 40.00, 59.18, 40.82, 18.36 +41.20, 40.00, 59.18, 40.82, 18.35 +41.20, 40.00, 59.17, 40.83, 18.34 +41.20, 40.00, 59.17, 40.83, 18.33 +41.20, 40.00, 59.16, 40.84, 18.32 +41.20, 40.00, 59.16, 40.84, 18.32 +41.20, 40.00, 59.15, 40.85, 18.31 +41.20, 40.00, 59.15, 40.85, 18.30 +41.20, 40.00, 59.14, 40.86, 18.29 +41.20, 40.00, 59.14, 40.86, 18.28 +41.20, 40.00, 59.14, 40.86, 18.27 +41.20, 40.00, 59.13, 40.87, 18.26 +41.20, 40.00, 59.13, 40.87, 18.25 +41.20, 40.00, 59.12, 40.88, 18.24 +41.20, 40.00, 59.12, 40.88, 18.23 +41.20, 40.00, 59.11, 40.89, 18.23 +41.20, 40.00, 59.11, 40.89, 18.22 +41.20, 40.00, 59.10, 40.90, 18.21 +41.20, 40.00, 59.10, 40.90, 18.20 +41.20, 40.00, 59.09, 40.91, 18.19 +41.20, 40.00, 59.09, 40.91, 18.18 +41.20, 40.00, 59.09, 40.91, 18.17 +41.20, 40.00, 59.08, 40.92, 18.16 +41.20, 40.00, 59.08, 40.92, 18.15 +41.20, 40.00, 59.07, 40.93, 18.14 +41.20, 40.00, 59.07, 40.93, 18.14 +41.20, 40.00, 59.06, 40.94, 18.13 +41.20, 40.00, 59.06, 40.94, 18.12 +41.20, 40.00, 59.05, 40.95, 18.11 +41.20, 40.00, 59.05, 40.95, 18.10 +41.20, 40.00, 59.05, 40.95, 18.09 +41.20, 40.00, 59.04, 40.96, 18.08 +41.20, 40.00, 59.04, 40.96, 18.07 +41.20, 40.00, 59.03, 40.97, 18.06 +41.20, 40.00, 59.03, 40.97, 18.05 +41.20, 40.00, 59.02, 40.98, 18.05 +41.20, 40.00, 59.02, 40.98, 18.04 +41.20, 40.00, 59.01, 40.99, 18.03 +41.20, 40.00, 59.01, 40.99, 18.02 +41.20, 40.00, 59.00, 41.00, 18.01 +41.20, 40.00, 59.00, 41.00, 18.00 +41.20, 40.00, 59.00, 41.00, 17.99 +41.20, 40.00, 58.99, 41.01, 17.98 +41.20, 40.00, 58.99, 41.01, 17.97 +41.20, 40.00, 58.98, 41.02, 17.96 +41.20, 40.00, 58.98, 41.02, 17.96 +41.20, 40.00, 58.97, 41.03, 17.95 +41.20, 40.00, 58.97, 41.03, 17.94 +41.13, 40.00, 61.49, 38.51, 22.97 +41.20, 40.00, 56.49, 43.51, 12.98 +41.20, 40.00, 58.96, 41.04, 17.91 +41.20, 40.00, 58.95, 41.05, 17.90 +41.20, 40.00, 58.95, 41.05, 17.89 +41.20, 40.00, 58.94, 41.06, 17.88 +41.20, 40.00, 58.94, 41.06, 17.88 +41.20, 40.00, 58.93, 41.07, 17.87 +41.20, 40.00, 58.93, 41.07, 17.86 +41.20, 40.00, 58.92, 41.08, 17.85 +41.20, 40.00, 58.92, 41.08, 17.84 +41.20, 40.00, 58.92, 41.08, 17.83 +41.20, 40.00, 58.91, 41.09, 17.82 +41.20, 40.00, 58.91, 41.09, 17.81 +41.20, 40.00, 58.90, 41.10, 17.80 +41.20, 40.00, 58.90, 41.10, 17.79 +41.20, 40.00, 58.89, 41.11, 17.79 +41.20, 40.00, 58.89, 41.11, 17.78 +41.20, 40.00, 58.88, 41.12, 17.77 +41.20, 40.00, 58.88, 41.12, 17.76 +41.20, 40.00, 58.87, 41.13, 17.75 +41.20, 40.00, 58.87, 41.13, 17.74 +41.20, 40.00, 58.87, 41.13, 17.73 +41.20, 40.00, 58.86, 41.14, 17.72 +41.20, 40.00, 58.86, 41.14, 17.71 +41.20, 40.00, 58.85, 41.15, 17.70 +41.20, 40.00, 58.85, 41.15, 17.70 +41.20, 40.00, 58.84, 41.16, 17.69 +41.20, 40.00, 58.84, 41.16, 17.68 +41.20, 40.00, 58.83, 41.17, 17.67 +41.20, 40.00, 58.83, 41.17, 17.66 +41.20, 40.00, 58.83, 41.17, 17.65 +41.20, 40.00, 58.82, 41.18, 17.64 +41.20, 40.00, 58.82, 41.18, 17.63 +41.20, 40.00, 58.81, 41.19, 17.62 +41.20, 40.00, 58.81, 41.19, 17.61 +41.20, 40.00, 58.80, 41.20, 17.61 +41.20, 40.00, 58.80, 41.20, 17.60 +41.20, 40.00, 58.79, 41.21, 17.59 +41.20, 40.00, 58.79, 41.21, 17.58 +41.20, 40.00, 58.78, 41.22, 17.57 +41.20, 40.00, 58.78, 41.22, 17.56 +41.20, 40.00, 58.78, 41.22, 17.55 +41.20, 40.00, 58.77, 41.23, 17.54 +41.20, 40.00, 58.77, 41.23, 17.53 +41.20, 40.00, 58.76, 41.24, 17.52 +41.20, 40.00, 58.76, 41.24, 17.52 +41.20, 40.00, 58.75, 41.25, 17.51 +41.20, 40.00, 58.75, 41.25, 17.50 +41.20, 40.00, 58.74, 41.26, 17.49 +41.20, 40.00, 58.74, 41.26, 17.48 +41.20, 40.00, 58.74, 41.26, 17.47 +41.20, 40.00, 58.73, 41.27, 17.46 +41.20, 40.00, 58.73, 41.27, 17.45 +41.20, 40.00, 58.72, 41.28, 17.44 +41.20, 40.00, 58.72, 41.28, 17.43 +41.20, 40.00, 58.71, 41.29, 17.43 +41.20, 40.00, 58.71, 41.29, 17.42 +41.20, 40.00, 58.70, 41.30, 17.41 +41.20, 40.00, 58.70, 41.30, 17.40 +41.20, 40.00, 58.69, 41.31, 17.39 +41.20, 40.00, 58.69, 41.31, 17.38 +41.20, 40.00, 58.69, 41.31, 17.37 +41.20, 40.00, 58.68, 41.32, 17.36 +41.20, 40.00, 58.68, 41.32, 17.35 +41.20, 40.00, 58.67, 41.33, 17.34 +41.20, 40.00, 58.67, 41.33, 17.34 +41.20, 40.00, 58.66, 41.34, 17.33 +41.20, 40.00, 58.66, 41.34, 17.32 +41.20, 40.00, 58.65, 41.35, 17.31 +41.20, 40.00, 58.65, 41.35, 17.30 +41.20, 40.00, 58.65, 41.35, 17.29 +41.20, 40.00, 58.64, 41.36, 17.28 +41.20, 40.00, 58.64, 41.36, 17.27 +41.20, 40.00, 58.63, 41.37, 17.26 +41.20, 40.00, 58.63, 41.37, 17.25 +41.20, 40.00, 58.62, 41.38, 17.25 +41.20, 40.00, 58.62, 41.38, 17.24 +41.20, 40.00, 58.61, 41.39, 17.23 +41.20, 40.00, 58.61, 41.39, 17.22 +41.20, 40.00, 58.61, 41.39, 17.21 +41.20, 40.00, 58.60, 41.40, 17.20 +41.20, 40.00, 58.60, 41.40, 17.19 +41.20, 40.00, 58.59, 41.41, 17.18 +41.20, 40.00, 58.59, 41.41, 17.17 +41.20, 40.00, 58.58, 41.42, 17.17 +41.20, 40.00, 58.58, 41.42, 17.16 +41.20, 40.00, 58.57, 41.43, 17.15 +41.20, 40.00, 58.57, 41.43, 17.14 +41.20, 40.00, 58.56, 41.44, 17.13 +41.20, 40.00, 58.56, 41.44, 17.12 +41.20, 40.00, 58.56, 41.44, 17.11 +41.20, 40.00, 58.55, 41.45, 17.10 +41.20, 40.00, 58.55, 41.45, 17.09 +41.20, 40.00, 58.54, 41.46, 17.08 +41.20, 40.00, 58.54, 41.46, 17.08 +41.20, 40.00, 58.53, 41.47, 17.07 +41.20, 40.00, 58.53, 41.47, 17.06 +41.20, 40.00, 58.52, 41.48, 17.05 +41.20, 40.00, 58.52, 41.48, 17.04 +41.20, 40.00, 58.52, 41.48, 17.03 +41.20, 40.00, 58.51, 41.49, 17.02 +41.20, 40.00, 58.51, 41.49, 17.01 +41.20, 40.00, 58.50, 41.50, 17.00 +41.20, 40.00, 58.50, 41.50, 16.99 +41.20, 40.00, 58.49, 41.51, 16.99 +41.20, 40.00, 58.49, 41.51, 16.98 +41.20, 40.00, 58.48, 41.52, 16.97 +41.20, 40.00, 58.48, 41.52, 16.96 +41.20, 40.00, 58.47, 41.53, 16.95 +41.20, 40.00, 58.47, 41.53, 16.94 +41.13, 40.00, 60.99, 39.01, 21.97 +41.20, 40.00, 55.99, 44.01, 11.98 +41.20, 40.00, 58.46, 41.54, 16.91 +41.20, 40.00, 58.45, 41.55, 16.90 +41.20, 40.00, 58.45, 41.55, 16.90 +41.20, 40.00, 58.44, 41.56, 16.89 +41.20, 40.00, 58.44, 41.56, 16.88 +41.20, 40.00, 58.43, 41.57, 16.87 +41.20, 40.00, 58.43, 41.57, 16.86 +41.20, 40.00, 58.43, 41.57, 16.85 +41.20, 40.00, 58.42, 41.58, 16.84 +41.20, 40.00, 58.42, 41.58, 16.83 +41.20, 40.00, 58.41, 41.59, 16.82 +41.20, 40.00, 58.41, 41.59, 16.81 +41.20, 40.00, 58.40, 41.60, 16.81 +41.20, 40.00, 58.40, 41.60, 16.80 +41.20, 40.00, 58.39, 41.61, 16.79 +41.20, 40.00, 58.39, 41.61, 16.78 +41.20, 40.00, 58.38, 41.62, 16.77 +41.20, 40.00, 58.38, 41.62, 16.76 +41.20, 40.00, 58.38, 41.62, 16.75 +41.20, 40.00, 58.37, 41.63, 16.74 +41.20, 40.00, 58.37, 41.63, 16.73 +41.20, 40.00, 58.36, 41.64, 16.73 +41.20, 40.00, 58.36, 41.64, 16.72 +41.20, 40.00, 58.35, 41.65, 16.71 +41.20, 40.00, 58.35, 41.65, 16.70 +41.20, 40.00, 58.34, 41.66, 16.69 +41.20, 40.00, 58.34, 41.66, 16.68 +41.20, 40.00, 58.34, 41.66, 16.67 +41.20, 40.00, 58.33, 41.67, 16.66 +41.20, 40.00, 58.33, 41.67, 16.65 +41.20, 40.00, 58.32, 41.68, 16.64 +41.20, 40.00, 58.32, 41.68, 16.64 +41.20, 40.00, 58.31, 41.69, 16.63 +41.20, 40.00, 58.31, 41.69, 16.62 +41.20, 40.00, 58.30, 41.70, 16.61 +41.20, 40.00, 58.30, 41.70, 16.60 +41.20, 40.00, 58.30, 41.70, 16.59 +41.20, 40.00, 58.29, 41.71, 16.58 +41.20, 40.00, 58.29, 41.71, 16.57 +41.20, 40.00, 58.28, 41.72, 16.56 +41.20, 40.00, 58.28, 41.72, 16.55 +41.20, 40.00, 58.27, 41.73, 16.55 +41.20, 40.00, 58.27, 41.73, 16.54 +41.20, 40.00, 58.26, 41.74, 16.53 +41.20, 40.00, 58.26, 41.74, 16.52 +41.20, 40.00, 58.25, 41.75, 16.51 +41.20, 40.00, 58.25, 41.75, 16.50 +41.20, 40.00, 58.25, 41.75, 16.49 +41.20, 40.00, 58.24, 41.76, 16.48 +41.20, 40.00, 58.24, 41.76, 16.47 +41.20, 40.00, 58.23, 41.77, 16.46 +41.20, 40.00, 58.23, 41.77, 16.46 +41.20, 40.00, 58.22, 41.78, 16.45 +41.20, 40.00, 58.22, 41.78, 16.44 +41.20, 40.00, 58.21, 41.79, 16.43 +41.20, 40.00, 58.21, 41.79, 16.42 +41.20, 40.00, 58.21, 41.79, 16.41 +41.20, 40.00, 58.20, 41.80, 16.40 +41.20, 40.00, 58.20, 41.80, 16.39 +41.20, 40.00, 58.19, 41.81, 16.38 +41.20, 40.00, 58.19, 41.81, 16.37 +41.20, 40.00, 58.18, 41.82, 16.37 +41.20, 40.00, 58.18, 41.82, 16.36 +41.20, 40.00, 58.17, 41.83, 16.35 +41.20, 40.00, 58.17, 41.83, 16.34 +41.20, 40.00, 58.16, 41.84, 16.33 +41.20, 40.00, 58.16, 41.84, 16.32 +41.20, 40.00, 58.16, 41.84, 16.31 +41.20, 40.00, 58.15, 41.85, 16.30 +41.20, 40.00, 58.15, 41.85, 16.29 +41.20, 40.00, 58.14, 41.86, 16.28 +41.20, 40.00, 58.14, 41.86, 16.28 +41.20, 40.00, 58.13, 41.87, 16.27 +41.20, 40.00, 58.13, 41.87, 16.26 +41.20, 40.00, 58.12, 41.88, 16.25 +41.20, 40.00, 58.12, 41.88, 16.24 +41.20, 40.00, 58.12, 41.88, 16.23 +41.20, 40.00, 58.11, 41.89, 16.22 +41.20, 40.00, 58.11, 41.89, 16.21 +41.20, 40.00, 58.10, 41.90, 16.20 +41.20, 40.00, 58.10, 41.90, 16.19 +41.20, 40.00, 58.09, 41.91, 16.19 +41.20, 40.00, 58.09, 41.91, 16.18 +41.20, 40.00, 58.08, 41.92, 16.17 +41.13, 40.00, 60.60, 39.40, 21.20 +41.13, 40.00, 58.12, 41.88, 16.25 +41.13, 40.00, 58.12, 41.88, 16.24 +41.13, 40.00, 58.12, 41.88, 16.23 +41.13, 40.00, 58.11, 41.89, 16.22 +41.13, 40.00, 58.11, 41.89, 16.22 +41.13, 40.00, 58.10, 41.90, 16.21 +41.20, 40.00, 55.58, 44.42, 11.16 +41.20, 40.00, 58.05, 41.95, 16.09 +41.20, 40.00, 58.04, 41.96, 16.08 +41.20, 40.00, 58.04, 41.96, 16.07 +41.20, 40.00, 58.03, 41.97, 16.06 +41.20, 40.00, 58.03, 41.97, 16.05 +41.20, 40.00, 58.02, 41.98, 16.05 +41.20, 40.00, 58.02, 41.98, 16.04 +41.20, 40.00, 58.01, 41.99, 16.03 +41.20, 40.00, 58.01, 41.99, 16.02 +41.20, 40.00, 58.00, 42.00, 16.01 +41.20, 40.00, 58.00, 42.00, 16.00 +41.13, 40.00, 60.52, 39.48, 21.03 +41.20, 40.00, 55.52, 44.48, 11.04 +41.20, 40.00, 57.99, 42.01, 15.97 +41.20, 40.00, 57.98, 42.02, 15.96 +41.20, 40.00, 57.98, 42.02, 15.96 +41.20, 40.00, 57.97, 42.03, 15.95 +41.20, 40.00, 57.97, 42.03, 15.94 +41.20, 40.00, 57.96, 42.04, 15.93 +41.20, 40.00, 57.96, 42.04, 15.92 +41.20, 40.00, 57.96, 42.04, 15.91 +41.20, 40.00, 57.95, 42.05, 15.90 +41.20, 40.00, 57.95, 42.05, 15.89 +41.20, 40.00, 57.94, 42.06, 15.88 +41.20, 40.00, 57.94, 42.06, 15.87 +41.20, 40.00, 57.93, 42.07, 15.87 +41.20, 40.00, 57.93, 42.07, 15.86 +41.13, 40.00, 60.45, 39.55, 20.89 +41.20, 40.00, 55.45, 44.55, 10.90 +41.13, 40.00, 60.44, 39.56, 20.87 +41.13, 40.00, 57.96, 42.04, 15.92 +41.13, 40.00, 57.96, 42.04, 15.91 +41.20, 40.00, 55.43, 44.57, 10.86 +41.20, 40.00, 57.90, 42.10, 15.80 +41.20, 40.00, 57.89, 42.11, 15.79 +41.20, 40.00, 57.89, 42.11, 15.78 +41.20, 40.00, 57.88, 42.12, 15.77 +41.20, 40.00, 57.88, 42.12, 15.76 +41.20, 40.00, 57.88, 42.12, 15.75 +41.20, 40.00, 57.87, 42.13, 15.74 +41.20, 40.00, 57.87, 42.13, 15.73 +41.20, 40.00, 57.86, 42.14, 15.72 +41.20, 40.00, 57.86, 42.14, 15.72 +41.13, 40.00, 60.37, 39.63, 20.75 +41.20, 40.00, 55.38, 44.62, 10.75 +41.13, 40.00, 60.37, 39.63, 20.73 +41.20, 40.00, 55.37, 44.63, 10.74 +41.13, 40.00, 60.36, 39.64, 20.71 +41.20, 40.00, 55.36, 44.64, 10.72 +41.20, 40.00, 57.83, 42.17, 15.65 +41.20, 40.00, 57.82, 42.18, 15.64 +41.20, 40.00, 57.82, 42.18, 15.64 +41.20, 40.00, 57.81, 42.19, 15.63 +41.20, 40.00, 57.81, 42.19, 15.62 +41.20, 40.00, 57.80, 42.20, 15.61 +41.20, 40.00, 57.80, 42.20, 15.60 +41.20, 40.00, 57.80, 42.20, 15.59 +41.20, 40.00, 57.79, 42.21, 15.58 +41.20, 40.00, 57.79, 42.21, 15.57 +41.20, 40.00, 57.78, 42.22, 15.56 +41.20, 40.00, 57.78, 42.22, 15.55 +41.13, 40.00, 60.29, 39.71, 20.59 +41.13, 40.00, 57.82, 42.18, 15.64 +41.13, 40.00, 57.81, 42.19, 15.63 +41.13, 40.00, 57.81, 42.19, 15.62 +41.20, 40.00, 55.28, 44.72, 10.57 +41.20, 40.00, 57.75, 42.25, 15.50 +41.20, 40.00, 57.75, 42.25, 15.49 +41.20, 40.00, 57.74, 42.26, 15.48 +41.20, 40.00, 57.74, 42.26, 15.48 +41.20, 40.00, 57.73, 42.27, 15.47 +41.20, 40.00, 57.73, 42.27, 15.46 +41.20, 40.00, 57.72, 42.28, 15.45 +41.20, 40.00, 57.72, 42.28, 15.44 +41.20, 40.00, 57.72, 42.28, 15.43 +41.20, 40.00, 57.71, 42.29, 15.42 +41.20, 40.00, 57.71, 42.29, 15.41 +41.13, 40.00, 60.22, 39.78, 20.45 +41.20, 40.00, 55.23, 44.77, 10.45 +41.20, 40.00, 57.69, 42.31, 15.39 +41.20, 40.00, 57.69, 42.31, 15.38 +41.20, 40.00, 57.68, 42.32, 15.37 +41.20, 40.00, 57.68, 42.32, 15.36 +41.20, 40.00, 57.68, 42.32, 15.35 +41.20, 40.00, 57.67, 42.33, 15.34 +41.20, 40.00, 57.67, 42.33, 15.33 +41.20, 40.00, 57.66, 42.34, 15.32 +41.20, 40.00, 57.66, 42.34, 15.31 +41.20, 40.00, 57.65, 42.35, 15.31 +41.20, 40.00, 57.65, 42.35, 15.30 +41.20, 40.00, 57.64, 42.36, 15.29 +41.20, 40.00, 57.64, 42.36, 15.28 +41.20, 40.00, 57.63, 42.37, 15.27 +41.20, 40.00, 57.63, 42.37, 15.26 +41.20, 40.00, 57.63, 42.37, 15.25 +41.20, 40.00, 57.62, 42.38, 15.24 +41.20, 40.00, 57.62, 42.38, 15.23 +41.20, 40.00, 57.61, 42.39, 15.22 +41.20, 40.00, 57.61, 42.39, 15.22 +41.13, 40.00, 60.12, 39.88, 20.25 +41.20, 40.00, 55.13, 44.87, 10.25 +41.20, 40.00, 57.59, 42.41, 15.19 +41.20, 40.00, 57.59, 42.41, 15.18 +41.20, 40.00, 57.59, 42.41, 15.17 +41.20, 40.00, 57.58, 42.42, 15.16 +41.20, 40.00, 57.58, 42.42, 15.15 +41.20, 40.00, 57.57, 42.43, 15.14 +41.20, 40.00, 57.57, 42.43, 15.14 +41.20, 40.00, 57.56, 42.44, 15.13 +41.20, 40.00, 57.56, 42.44, 15.12 +41.20, 40.00, 57.55, 42.45, 15.11 +41.20, 40.00, 57.55, 42.45, 15.10 +41.20, 40.00, 57.55, 42.45, 15.09 +41.20, 40.00, 57.54, 42.46, 15.08 +41.20, 40.00, 57.54, 42.46, 15.07 +41.20, 40.00, 57.53, 42.47, 15.06 +41.20, 40.00, 57.53, 42.47, 15.05 +41.20, 40.00, 57.52, 42.48, 15.05 +41.13, 40.00, 60.04, 39.96, 20.08 +41.20, 40.00, 55.04, 44.96, 10.08 +41.20, 40.00, 57.51, 42.49, 15.02 +41.20, 40.00, 57.50, 42.50, 15.01 +41.20, 40.00, 57.50, 42.50, 15.00 +41.20, 40.00, 57.50, 42.50, 14.99 +41.20, 40.00, 57.49, 42.51, 14.98 +41.20, 40.00, 57.49, 42.51, 14.97 +41.20, 40.00, 57.48, 42.52, 14.96 +41.20, 40.00, 57.48, 42.52, 14.96 +41.20, 40.00, 57.47, 42.53, 14.95 +41.20, 40.00, 57.47, 42.53, 14.94 +41.20, 40.00, 57.46, 42.54, 14.93 +41.20, 40.00, 57.46, 42.54, 14.92 +41.20, 40.00, 57.46, 42.54, 14.91 +41.20, 40.00, 57.45, 42.55, 14.90 +41.20, 40.00, 57.45, 42.55, 14.89 +41.20, 40.00, 57.44, 42.56, 14.88 +41.20, 40.00, 57.44, 42.56, 14.87 +41.20, 40.00, 57.43, 42.57, 14.87 +41.20, 40.00, 57.43, 42.57, 14.86 +41.20, 40.00, 57.42, 42.58, 14.85 +41.20, 40.00, 57.42, 42.58, 14.84 +41.20, 40.00, 57.41, 42.59, 14.83 +41.20, 40.00, 57.41, 42.59, 14.82 +41.20, 40.00, 57.41, 42.59, 14.81 +41.20, 40.00, 57.40, 42.60, 14.80 +41.20, 40.00, 57.40, 42.60, 14.79 +41.20, 40.00, 57.39, 42.61, 14.78 +41.20, 40.00, 57.39, 42.61, 14.78 +41.20, 40.00, 57.38, 42.62, 14.77 +41.20, 40.00, 57.38, 42.62, 14.76 +41.20, 40.00, 57.37, 42.63, 14.75 +41.13, 40.00, 59.89, 40.11, 19.78 +41.20, 40.00, 54.89, 45.11, 9.79 +41.13, 40.00, 59.88, 40.12, 19.77 +41.13, 40.00, 57.41, 42.59, 14.81 +41.13, 40.00, 57.40, 42.60, 14.80 +41.13, 40.00, 57.40, 42.60, 14.80 +41.13, 40.00, 57.39, 42.61, 14.79 +41.13, 40.00, 57.39, 42.61, 14.78 +41.13, 40.00, 57.39, 42.61, 14.77 +41.13, 40.00, 57.38, 42.62, 14.76 +41.13, 40.00, 57.38, 42.62, 14.75 +41.20, 40.00, 54.85, 45.15, 9.70 +41.20, 40.00, 57.32, 42.68, 14.64 +41.20, 40.00, 57.31, 42.69, 14.63 +41.20, 40.00, 57.31, 42.69, 14.62 +41.20, 40.00, 57.31, 42.69, 14.61 +41.20, 40.00, 57.30, 42.70, 14.60 +41.20, 40.00, 57.30, 42.70, 14.59 +41.20, 40.00, 57.29, 42.71, 14.58 +41.13, 40.00, 59.81, 40.19, 19.62 +41.20, 40.00, 54.81, 45.19, 9.62 +41.20, 40.00, 57.28, 42.72, 14.56 +41.13, 40.00, 59.80, 40.20, 19.59 +41.13, 40.00, 57.32, 42.68, 14.64 +41.20, 40.00, 54.79, 45.21, 9.59 +41.13, 40.00, 59.78, 40.22, 19.56 +41.20, 40.00, 54.78, 45.22, 9.57 +41.13, 40.00, 59.77, 40.23, 19.55 +41.13, 40.00, 57.30, 42.70, 14.60 +41.20, 40.00, 54.77, 45.23, 9.54 +41.20, 40.00, 57.24, 42.76, 14.48 +41.20, 40.00, 57.23, 42.77, 14.47 +41.20, 40.00, 57.23, 42.77, 14.46 +41.20, 40.00, 57.23, 42.77, 14.45 +41.20, 40.00, 57.22, 42.78, 14.44 +41.13, 40.00, 59.74, 40.26, 19.48 +41.20, 40.00, 54.74, 45.26, 9.48 +41.20, 40.00, 57.21, 42.79, 14.42 +41.20, 40.00, 57.20, 42.80, 14.41 +41.20, 40.00, 57.20, 42.80, 14.40 +41.20, 40.00, 57.19, 42.81, 14.39 +41.20, 40.00, 57.19, 42.81, 14.38 +41.20, 40.00, 57.19, 42.81, 14.37 +41.20, 40.00, 57.18, 42.82, 14.36 +41.20, 40.00, 57.18, 42.82, 14.35 +41.20, 40.00, 57.17, 42.83, 14.34 +41.20, 40.00, 57.17, 42.83, 14.33 +41.20, 40.00, 57.16, 42.84, 14.33 +41.20, 40.00, 57.16, 42.84, 14.32 +41.20, 40.00, 57.15, 42.85, 14.31 +41.20, 40.00, 57.15, 42.85, 14.30 +41.20, 40.00, 57.14, 42.86, 14.29 +41.20, 40.00, 57.14, 42.86, 14.28 +41.20, 40.00, 57.14, 42.86, 14.27 +41.20, 40.00, 57.13, 42.87, 14.26 +41.20, 40.00, 57.13, 42.87, 14.25 +41.20, 40.00, 57.12, 42.88, 14.24 +41.20, 40.00, 57.12, 42.88, 14.24 +41.20, 40.00, 57.11, 42.89, 14.23 +41.20, 40.00, 57.11, 42.89, 14.22 +41.20, 40.00, 57.10, 42.90, 14.21 +41.20, 40.00, 57.10, 42.90, 14.20 +41.20, 40.00, 57.10, 42.90, 14.19 +41.20, 40.00, 57.09, 42.91, 14.18 +41.20, 40.00, 57.09, 42.91, 14.17 +41.20, 40.00, 57.08, 42.92, 14.16 +41.20, 40.00, 57.08, 42.92, 14.16 +41.20, 40.00, 57.07, 42.93, 14.15 +41.13, 40.00, 59.59, 40.41, 19.18 +41.20, 40.00, 54.59, 45.41, 9.18 +41.20, 40.00, 57.06, 42.94, 14.12 +41.20, 40.00, 57.06, 42.94, 14.11 +41.20, 40.00, 57.05, 42.95, 14.10 +41.20, 40.00, 57.05, 42.95, 14.09 +41.20, 40.00, 57.04, 42.96, 14.08 +41.20, 40.00, 57.04, 42.96, 14.07 +41.20, 40.00, 57.03, 42.97, 14.07 +41.20, 40.00, 57.03, 42.97, 14.06 +41.20, 40.00, 57.02, 42.98, 14.05 +41.20, 40.00, 57.02, 42.98, 14.04 +41.20, 40.00, 57.01, 42.99, 14.03 +41.20, 40.00, 57.01, 42.99, 14.02 +41.20, 40.00, 57.01, 42.99, 14.01 +41.20, 40.00, 57.00, 43.00, 14.00 +41.20, 40.00, 57.00, 43.00, 13.99 +41.20, 40.00, 56.99, 43.01, 13.98 +41.20, 40.00, 56.99, 43.01, 13.98 +41.20, 40.00, 56.98, 43.02, 13.97 +41.20, 40.00, 56.98, 43.02, 13.96 +41.20, 40.00, 56.97, 43.03, 13.95 +41.20, 40.00, 56.97, 43.03, 13.94 +41.20, 40.00, 56.97, 43.03, 13.93 +41.20, 40.00, 56.96, 43.04, 13.92 +41.20, 40.00, 56.96, 43.04, 13.91 +41.20, 40.00, 56.95, 43.05, 13.90 +41.20, 40.00, 56.95, 43.05, 13.89 +41.20, 40.00, 56.94, 43.06, 13.89 +41.20, 40.00, 56.94, 43.06, 13.88 +41.20, 40.00, 56.93, 43.07, 13.87 +41.20, 40.00, 56.93, 43.07, 13.86 +41.20, 40.00, 56.92, 43.08, 13.85 +41.20, 40.00, 56.92, 43.08, 13.84 +41.20, 40.00, 56.92, 43.08, 13.83 +41.20, 40.00, 56.91, 43.09, 13.82 +41.20, 40.00, 56.91, 43.09, 13.81 +41.20, 40.00, 56.90, 43.10, 13.80 +41.20, 40.00, 56.90, 43.10, 13.80 +41.20, 40.00, 56.89, 43.11, 13.79 +41.20, 40.00, 56.89, 43.11, 13.78 +41.20, 40.00, 56.88, 43.12, 13.77 +41.20, 40.00, 56.88, 43.12, 13.76 +41.20, 40.00, 56.88, 43.12, 13.75 +41.20, 40.00, 56.87, 43.13, 13.74 +41.20, 40.00, 56.87, 43.13, 13.73 +41.20, 40.00, 56.86, 43.14, 13.72 +41.20, 40.00, 56.86, 43.14, 13.72 +41.20, 40.00, 56.85, 43.15, 13.71 +41.20, 40.00, 56.85, 43.15, 13.70 +41.20, 40.00, 56.84, 43.16, 13.69 +41.20, 40.00, 56.84, 43.16, 13.68 +41.20, 40.00, 56.84, 43.16, 13.67 +41.20, 40.00, 56.83, 43.17, 13.66 +41.20, 40.00, 56.83, 43.17, 13.65 +41.20, 40.00, 56.82, 43.18, 13.64 +41.20, 40.00, 56.82, 43.18, 13.63 +41.20, 40.00, 56.81, 43.19, 13.63 +41.20, 40.00, 56.81, 43.19, 13.62 +41.20, 40.00, 56.80, 43.20, 13.61 +41.20, 40.00, 56.80, 43.20, 13.60 +41.20, 40.00, 56.79, 43.21, 13.59 +41.20, 40.00, 56.79, 43.21, 13.58 +41.20, 40.00, 56.79, 43.21, 13.57 +41.20, 40.00, 56.78, 43.22, 13.56 +41.20, 40.00, 56.78, 43.22, 13.55 +41.20, 40.00, 56.77, 43.23, 13.54 +41.20, 40.00, 56.77, 43.23, 13.54 +41.20, 40.00, 56.76, 43.24, 13.53 +41.20, 40.00, 56.76, 43.24, 13.52 +41.20, 40.00, 56.75, 43.25, 13.51 +41.20, 40.00, 56.75, 43.25, 13.50 +41.20, 40.00, 56.75, 43.25, 13.49 +41.20, 40.00, 56.74, 43.26, 13.48 +41.20, 40.00, 56.74, 43.26, 13.47 +41.20, 40.00, 56.73, 43.27, 13.46 +41.20, 40.00, 56.73, 43.27, 13.45 +41.20, 40.00, 56.72, 43.28, 13.45 +41.20, 40.00, 56.72, 43.28, 13.44 +41.20, 40.00, 56.71, 43.29, 13.43 +41.20, 40.00, 56.71, 43.29, 13.42 +41.20, 40.00, 56.70, 43.30, 13.41 +41.20, 40.00, 56.70, 43.30, 13.40 +41.20, 40.00, 56.70, 43.30, 13.39 +41.20, 40.00, 56.69, 43.31, 13.38 +41.20, 40.00, 56.69, 43.31, 13.37 +41.20, 40.00, 56.68, 43.32, 13.36 +41.20, 40.00, 56.68, 43.32, 13.36 +41.20, 40.00, 56.67, 43.33, 13.35 +41.20, 40.00, 56.67, 43.33, 13.34 +41.20, 40.00, 56.66, 43.34, 13.33 +41.20, 40.00, 56.66, 43.34, 13.32 +41.20, 40.00, 56.66, 43.34, 13.31 +41.20, 40.00, 56.65, 43.35, 13.30 +41.20, 40.00, 56.65, 43.35, 13.29 +41.20, 40.00, 56.64, 43.36, 13.28 +41.20, 40.00, 56.64, 43.36, 13.27 +41.20, 40.00, 56.63, 43.37, 13.27 +41.20, 40.00, 56.63, 43.37, 13.26 +41.20, 40.00, 56.62, 43.38, 13.25 +41.20, 40.00, 56.62, 43.38, 13.24 +41.20, 40.00, 56.61, 43.39, 13.23 +41.20, 40.00, 56.61, 43.39, 13.22 +41.20, 40.00, 56.61, 43.39, 13.21 +41.20, 40.00, 56.60, 43.40, 13.20 +41.20, 40.00, 56.60, 43.40, 13.19 +41.20, 40.00, 56.59, 43.41, 13.18 +41.20, 40.00, 56.59, 43.41, 13.18 +41.13, 40.00, 59.10, 40.90, 18.21 +41.20, 40.00, 54.11, 45.89, 8.21 +41.20, 40.00, 56.57, 43.43, 13.15 +41.20, 40.00, 56.57, 43.43, 13.14 +41.20, 40.00, 56.57, 43.43, 13.13 +41.20, 40.00, 56.56, 43.44, 13.12 +41.20, 40.00, 56.56, 43.44, 13.11 +41.20, 40.00, 56.55, 43.45, 13.10 +41.20, 40.00, 56.55, 43.45, 13.10 +41.20, 40.00, 56.54, 43.46, 13.09 +41.20, 40.00, 56.54, 43.46, 13.08 +41.20, 40.00, 56.53, 43.47, 13.07 +41.13, 40.00, 59.05, 40.95, 18.10 +41.13, 40.00, 56.58, 43.42, 13.15 +41.13, 40.00, 56.57, 43.43, 13.14 +41.13, 40.00, 56.57, 43.43, 13.13 +41.13, 40.00, 56.56, 43.44, 13.12 +41.13, 40.00, 56.56, 43.44, 13.12 +41.20, 40.00, 54.03, 45.97, 8.06 +41.20, 40.00, 56.50, 43.50, 13.00 +41.20, 40.00, 56.50, 43.50, 12.99 +41.20, 40.00, 56.49, 43.51, 12.98 +41.20, 40.00, 56.49, 43.51, 12.97 +41.20, 40.00, 56.48, 43.52, 12.96 +41.20, 40.00, 56.48, 43.52, 12.95 +41.20, 40.00, 56.47, 43.53, 12.95 +41.20, 40.00, 56.47, 43.53, 12.94 +41.20, 40.00, 56.46, 43.54, 12.93 +41.20, 40.00, 56.46, 43.54, 12.92 +41.20, 40.00, 56.45, 43.55, 12.91 +41.20, 40.00, 56.45, 43.55, 12.90 +41.20, 40.00, 56.45, 43.55, 12.89 +41.13, 40.00, 58.96, 41.04, 17.93 +41.20, 40.00, 53.97, 46.03, 7.93 +41.13, 40.00, 58.95, 41.05, 17.91 +41.20, 40.00, 53.96, 46.04, 7.91 +41.13, 40.00, 58.95, 41.05, 17.89 +41.13, 40.00, 56.47, 43.53, 12.94 +41.20, 40.00, 53.94, 46.06, 7.89 +41.20, 40.00, 56.41, 43.59, 12.82 +41.20, 40.00, 56.41, 43.59, 12.81 +41.20, 40.00, 56.40, 43.60, 12.80 +41.20, 40.00, 56.40, 43.60, 12.79 +41.20, 40.00, 56.39, 43.61, 12.79 +41.13, 40.00, 58.91, 41.09, 17.82 +41.20, 40.00, 53.91, 46.09, 7.82 +41.13, 40.00, 58.90, 41.10, 17.80 +41.13, 40.00, 56.42, 43.58, 12.85 +41.13, 40.00, 56.42, 43.58, 12.84 +41.13, 40.00, 56.42, 43.58, 12.83 +41.13, 40.00, 56.41, 43.59, 12.82 +41.13, 40.00, 56.41, 43.59, 12.82 +41.13, 40.00, 56.40, 43.60, 12.81 +41.20, 40.00, 53.88, 46.12, 7.76 +41.20, 40.00, 56.35, 43.65, 12.69 +41.20, 40.00, 56.34, 43.66, 12.68 +41.13, 40.00, 58.86, 41.14, 17.72 +41.20, 40.00, 53.86, 46.14, 7.72 +41.20, 40.00, 56.33, 43.67, 12.66 +41.20, 40.00, 56.32, 43.68, 12.65 +41.20, 40.00, 56.32, 43.68, 12.64 +41.13, 40.00, 58.84, 41.16, 17.67 +41.20, 40.00, 53.84, 46.16, 7.68 +41.13, 40.00, 58.83, 41.17, 17.65 +41.13, 40.00, 56.35, 43.65, 12.70 +41.13, 40.00, 56.35, 43.65, 12.69 +41.13, 40.00, 56.34, 43.66, 12.68 +41.13, 40.00, 56.34, 43.66, 12.68 +41.13, 40.00, 56.33, 43.67, 12.67 +41.13, 40.00, 56.33, 43.67, 12.66 +41.13, 40.00, 56.33, 43.67, 12.65 +41.13, 40.00, 56.32, 43.68, 12.64 +41.13, 40.00, 56.32, 43.68, 12.63 +41.13, 40.00, 56.31, 43.69, 12.62 +41.13, 40.00, 56.31, 43.69, 12.62 +41.20, 40.00, 53.78, 46.22, 7.56 +41.13, 40.00, 58.77, 41.23, 17.54 +41.13, 40.00, 56.30, 43.70, 12.59 +41.13, 40.00, 56.29, 43.71, 12.58 +41.13, 40.00, 56.29, 43.71, 12.57 +41.13, 40.00, 56.28, 43.72, 12.57 +41.13, 40.00, 56.28, 43.72, 12.56 +41.13, 40.00, 56.27, 43.73, 12.55 +41.13, 40.00, 56.27, 43.73, 12.54 +41.13, 40.00, 56.27, 43.73, 12.53 +41.13, 40.00, 56.26, 43.74, 12.52 +41.13, 40.00, 56.26, 43.74, 12.51 +41.13, 40.00, 56.25, 43.75, 12.51 +41.13, 40.00, 56.25, 43.75, 12.50 +41.13, 40.00, 56.24, 43.76, 12.49 +41.13, 40.00, 56.24, 43.76, 12.48 +41.13, 40.00, 56.24, 43.76, 12.47 +41.13, 40.00, 56.23, 43.77, 12.46 +41.13, 40.00, 56.23, 43.77, 12.45 +41.13, 40.00, 56.22, 43.78, 12.45 +41.13, 40.00, 56.22, 43.78, 12.44 +41.13, 40.00, 56.21, 43.79, 12.43 +41.13, 40.00, 56.21, 43.79, 12.42 +41.13, 40.00, 56.21, 43.79, 12.41 +41.13, 40.00, 56.20, 43.80, 12.40 +41.13, 40.00, 56.20, 43.80, 12.40 +41.13, 40.00, 56.19, 43.81, 12.39 +41.13, 40.00, 56.19, 43.81, 12.38 +41.13, 40.00, 56.18, 43.82, 12.37 +41.13, 40.00, 56.18, 43.82, 12.36 +41.13, 40.00, 56.18, 43.82, 12.35 +41.13, 40.00, 56.17, 43.83, 12.34 +41.20, 40.00, 53.65, 46.35, 7.29 +41.20, 40.00, 56.11, 43.89, 12.23 +41.20, 40.00, 56.11, 43.89, 12.22 +41.13, 40.00, 58.63, 41.37, 17.25 +41.13, 40.00, 56.15, 43.85, 12.30 +41.13, 40.00, 56.15, 43.85, 12.29 +41.13, 40.00, 56.14, 43.86, 12.28 +41.13, 40.00, 56.14, 43.86, 12.27 +41.13, 40.00, 56.13, 43.87, 12.27 +41.13, 40.00, 56.13, 43.87, 12.26 +41.13, 40.00, 56.12, 43.88, 12.25 +41.13, 40.00, 56.12, 43.88, 12.24 +41.13, 40.00, 56.12, 43.88, 12.23 +41.13, 40.00, 56.11, 43.89, 12.22 +41.13, 40.00, 56.11, 43.89, 12.22 +41.13, 40.00, 56.10, 43.90, 12.21 +41.13, 40.00, 56.10, 43.90, 12.20 +41.13, 40.00, 56.09, 43.91, 12.19 +41.13, 40.00, 56.09, 43.91, 12.18 +41.13, 40.00, 56.09, 43.91, 12.17 +41.13, 40.00, 56.08, 43.92, 12.16 +41.13, 40.00, 56.08, 43.92, 12.16 +41.13, 40.00, 56.07, 43.93, 12.15 +41.13, 40.00, 56.07, 43.93, 12.14 +41.13, 40.00, 56.07, 43.93, 12.13 +41.13, 40.00, 56.06, 43.94, 12.12 +41.13, 40.00, 56.06, 43.94, 12.11 +41.13, 40.00, 56.05, 43.95, 12.10 +41.13, 40.00, 56.05, 43.95, 12.10 +41.13, 40.00, 56.04, 43.96, 12.09 +41.13, 40.00, 56.04, 43.96, 12.08 +41.13, 40.00, 56.04, 43.96, 12.07 +41.13, 40.00, 56.03, 43.97, 12.06 +41.20, 40.00, 53.51, 46.49, 7.01 +41.13, 40.00, 58.49, 41.51, 16.99 +41.20, 40.00, 53.50, 46.50, 6.99 +41.13, 40.00, 58.49, 41.51, 16.97 +41.13, 40.00, 56.01, 43.99, 12.02 +41.13, 40.00, 56.01, 43.99, 12.01 +41.13, 40.00, 56.00, 44.00, 12.00 +41.13, 40.00, 56.00, 44.00, 11.99 +41.13, 40.00, 55.99, 44.01, 11.98 +41.13, 40.00, 55.99, 44.01, 11.98 +41.13, 40.00, 55.98, 44.02, 11.97 +41.13, 40.00, 55.98, 44.02, 11.96 +41.13, 40.00, 55.98, 44.02, 11.95 +41.13, 40.00, 55.97, 44.03, 11.94 +41.13, 40.00, 55.97, 44.03, 11.93 +41.13, 40.00, 55.96, 44.04, 11.93 +41.13, 40.00, 55.96, 44.04, 11.92 +41.13, 40.00, 55.95, 44.05, 11.91 +41.00, 40.00, 60.99, 39.01, 21.99 +41.13, 40.00, 51.00, 49.00, 2.00 +41.13, 40.00, 55.94, 44.06, 11.88 +41.13, 40.00, 55.94, 44.06, 11.88 +41.00, 40.00, 60.98, 39.02, 21.95 +41.13, 40.00, 50.99, 49.01, 1.97 +41.00, 40.00, 60.97, 39.03, 21.94 +41.00, 40.00, 56.02, 43.98, 12.04 +41.00, 40.00, 56.02, 43.98, 12.03 +41.00, 40.00, 56.01, 43.99, 12.03 +41.00, 40.00, 56.01, 43.99, 12.02 +41.00, 40.00, 56.01, 43.99, 12.01 +41.00, 40.00, 56.00, 44.00, 12.00 +41.13, 40.00, 50.96, 49.04, 1.91 +41.13, 40.00, 55.89, 44.11, 11.79 +41.13, 40.00, 55.89, 44.11, 11.78 +41.13, 40.00, 55.89, 44.11, 11.77 +41.13, 40.00, 55.88, 44.12, 11.76 +41.13, 40.00, 55.88, 44.12, 11.76 +41.00, 40.00, 60.92, 39.08, 21.83 +41.00, 40.00, 55.97, 44.03, 11.94 +41.13, 40.00, 50.92, 49.08, 1.84 +41.00, 40.00, 60.91, 39.09, 21.81 +41.00, 40.00, 55.96, 44.04, 11.92 +41.00, 40.00, 55.95, 44.05, 11.91 +41.00, 40.00, 55.95, 44.05, 11.90 +41.13, 40.00, 50.90, 49.10, 1.81 +41.13, 40.00, 55.84, 44.16, 11.69 +41.13, 40.00, 55.84, 44.16, 11.68 +41.13, 40.00, 55.83, 44.17, 11.67 +41.13, 40.00, 55.83, 44.17, 11.66 +41.13, 40.00, 55.83, 44.17, 11.65 +41.13, 40.00, 55.82, 44.18, 11.64 +41.20, 40.00, 53.30, 46.70, 6.59 +41.20, 40.00, 55.76, 44.24, 11.53 +41.20, 40.00, 55.76, 44.24, 11.52 +41.13, 40.00, 58.28, 41.72, 16.55 +41.13, 40.00, 55.80, 44.20, 11.60 +41.13, 40.00, 55.80, 44.20, 11.59 +41.13, 40.00, 55.79, 44.21, 11.58 +41.13, 40.00, 55.79, 44.21, 11.57 +41.13, 40.00, 55.78, 44.22, 11.56 +41.13, 40.00, 55.78, 44.22, 11.56 +41.13, 40.00, 55.77, 44.23, 11.55 +41.13, 40.00, 55.77, 44.23, 11.54 +41.13, 40.00, 55.77, 44.23, 11.53 +41.13, 40.00, 55.76, 44.24, 11.52 +41.13, 40.00, 55.76, 44.24, 11.51 +41.13, 40.00, 55.75, 44.25, 11.51 +41.20, 40.00, 53.23, 46.77, 6.45 +41.13, 40.00, 58.22, 41.78, 16.43 +41.13, 40.00, 55.74, 44.26, 11.48 +41.13, 40.00, 55.74, 44.26, 11.47 +41.13, 40.00, 55.73, 44.27, 11.46 +41.13, 40.00, 55.73, 44.27, 11.45 +41.13, 40.00, 55.72, 44.28, 11.45 +41.13, 40.00, 55.72, 44.28, 11.44 +41.00, 40.00, 60.76, 39.24, 21.51 +41.00, 40.00, 55.81, 44.19, 11.62 +41.00, 40.00, 55.81, 44.19, 11.61 +41.00, 40.00, 55.80, 44.20, 11.60 +41.00, 40.00, 55.80, 44.20, 11.60 +41.00, 40.00, 55.79, 44.21, 11.59 +41.00, 40.00, 55.79, 44.21, 11.58 +41.00, 40.00, 55.79, 44.21, 11.57 +41.00, 40.00, 55.78, 44.22, 11.57 +41.00, 40.00, 55.78, 44.22, 11.56 +41.13, 40.00, 50.73, 49.27, 1.47 +41.13, 40.00, 55.67, 44.33, 11.34 +41.13, 40.00, 55.67, 44.33, 11.34 +41.00, 40.00, 60.71, 39.29, 21.41 +41.13, 40.00, 50.72, 49.28, 1.43 +41.13, 40.00, 55.66, 44.34, 11.31 +41.00, 40.00, 60.69, 39.31, 21.39 +41.00, 40.00, 55.75, 44.25, 11.49 +41.00, 40.00, 55.74, 44.26, 11.49 +41.00, 40.00, 55.74, 44.26, 11.48 +41.00, 40.00, 55.74, 44.26, 11.47 +41.00, 40.00, 55.73, 44.27, 11.46 +41.00, 40.00, 55.73, 44.27, 11.46 +41.00, 40.00, 55.72, 44.28, 11.45 +41.13, 40.00, 50.68, 49.32, 1.36 +41.13, 40.00, 55.62, 44.38, 11.23 +41.13, 40.00, 55.61, 44.39, 11.23 +41.13, 40.00, 55.61, 44.39, 11.22 +41.13, 40.00, 55.60, 44.40, 11.21 +41.13, 40.00, 55.60, 44.40, 11.20 +41.20, 40.00, 53.07, 46.93, 6.15 +41.20, 40.00, 55.54, 44.46, 11.08 +41.20, 40.00, 55.54, 44.46, 11.07 +41.20, 40.00, 55.53, 44.47, 11.07 +41.20, 40.00, 55.53, 44.47, 11.06 +41.13, 40.00, 58.05, 41.95, 16.09 +41.13, 40.00, 55.57, 44.43, 11.14 +41.13, 40.00, 55.57, 44.43, 11.13 +41.20, 40.00, 53.04, 46.96, 6.08 +41.13, 40.00, 58.03, 41.97, 16.06 +41.13, 40.00, 55.55, 44.45, 11.10 +41.13, 40.00, 55.55, 44.45, 11.10 +41.13, 40.00, 55.54, 44.46, 11.09 +41.13, 40.00, 55.54, 44.46, 11.08 +41.13, 40.00, 55.54, 44.46, 11.07 +41.20, 40.00, 53.01, 46.99, 6.02 +41.20, 40.00, 55.48, 44.52, 10.95 +41.20, 40.00, 55.47, 44.53, 10.94 +41.20, 40.00, 55.47, 44.53, 10.94 +41.20, 40.00, 55.46, 44.54, 10.93 +41.20, 40.00, 55.46, 44.54, 10.92 +41.13, 40.00, 57.98, 42.02, 15.95 +41.13, 40.00, 55.50, 44.50, 11.00 +41.13, 40.00, 55.50, 44.50, 10.99 +41.13, 40.00, 55.49, 44.51, 10.98 +41.13, 40.00, 55.49, 44.51, 10.97 +41.13, 40.00, 55.48, 44.52, 10.97 +41.13, 40.00, 55.48, 44.52, 10.96 +41.13, 40.00, 55.47, 44.53, 10.95 +41.13, 40.00, 55.47, 44.53, 10.94 +41.13, 40.00, 55.47, 44.53, 10.93 +41.13, 40.00, 55.46, 44.54, 10.92 +41.13, 40.00, 55.46, 44.54, 10.91 +41.13, 40.00, 55.45, 44.55, 10.91 +41.13, 40.00, 55.45, 44.55, 10.90 +41.13, 40.00, 55.44, 44.56, 10.89 +41.13, 40.00, 55.44, 44.56, 10.88 +41.13, 40.00, 55.44, 44.56, 10.87 +41.13, 40.00, 55.43, 44.57, 10.86 +41.13, 40.00, 55.43, 44.57, 10.86 +41.13, 40.00, 55.42, 44.58, 10.85 +41.13, 40.00, 55.42, 44.58, 10.84 +41.00, 40.00, 60.46, 39.54, 20.92 +41.00, 40.00, 55.51, 44.49, 11.02 +41.00, 40.00, 55.51, 44.49, 11.01 +41.00, 40.00, 55.50, 44.50, 11.01 +41.00, 40.00, 55.50, 44.50, 11.00 +41.00, 40.00, 55.50, 44.50, 10.99 +41.00, 40.00, 55.49, 44.51, 10.98 +40.94, 40.00, 58.01, 41.99, 16.02 +40.94, 40.00, 55.53, 44.47, 11.07 +40.94, 40.00, 55.53, 44.47, 11.06 +40.94, 40.00, 55.53, 44.47, 11.05 +40.94, 40.00, 55.52, 44.48, 11.05 +40.94, 40.00, 55.52, 44.48, 11.04 +40.94, 40.00, 55.52, 44.48, 11.03 +40.94, 40.00, 55.51, 44.49, 11.03 +40.94, 40.00, 55.51, 44.49, 11.02 +40.94, 40.00, 55.51, 44.49, 11.01 +40.94, 40.00, 55.50, 44.50, 11.00 +40.94, 40.00, 55.50, 44.50, 11.00 +40.94, 40.00, 55.50, 44.50, 10.99 +40.94, 40.00, 55.49, 44.51, 10.98 +40.94, 40.00, 55.49, 44.51, 10.98 +40.94, 40.00, 55.48, 44.52, 10.97 +40.94, 40.00, 55.48, 44.52, 10.96 +40.94, 40.00, 55.48, 44.52, 10.96 +40.94, 40.00, 55.47, 44.53, 10.95 +40.94, 40.00, 55.47, 44.53, 10.94 +40.94, 40.00, 55.47, 44.53, 10.93 +40.94, 40.00, 55.46, 44.54, 10.93 +40.94, 40.00, 55.46, 44.54, 10.92 +40.94, 40.00, 55.46, 44.54, 10.91 +40.94, 40.00, 55.45, 44.55, 10.91 +40.94, 40.00, 55.45, 44.55, 10.90 +40.94, 40.00, 55.45, 44.55, 10.89 +40.94, 40.00, 55.44, 44.56, 10.89 +40.94, 40.00, 55.44, 44.56, 10.88 +40.94, 40.00, 55.44, 44.56, 10.87 +40.94, 40.00, 55.43, 44.57, 10.86 +40.94, 40.00, 55.43, 44.57, 10.86 +40.94, 40.00, 55.43, 44.57, 10.85 +41.00, 40.00, 52.90, 47.10, 5.80 +40.94, 40.00, 57.89, 42.11, 15.78 +41.00, 40.00, 52.89, 47.11, 5.79 +41.00, 40.00, 55.36, 44.64, 10.72 +41.00, 40.00, 55.36, 44.64, 10.71 +41.00, 40.00, 55.35, 44.65, 10.71 +40.94, 40.00, 57.87, 42.13, 15.74 +40.94, 40.00, 55.40, 44.60, 10.79 +40.94, 40.00, 55.39, 44.61, 10.79 +40.94, 40.00, 55.39, 44.61, 10.78 +40.94, 40.00, 55.39, 44.61, 10.77 +40.94, 40.00, 55.38, 44.62, 10.76 +40.94, 40.00, 55.38, 44.62, 10.76 +41.00, 40.00, 52.85, 47.15, 5.71 +41.00, 40.00, 55.32, 44.68, 10.64 +41.00, 40.00, 55.32, 44.68, 10.64 +41.00, 40.00, 55.31, 44.69, 10.63 +41.00, 40.00, 55.31, 44.69, 10.62 +41.00, 40.00, 55.31, 44.69, 10.61 +41.13, 40.00, 50.26, 49.74, 0.52 +41.13, 40.00, 55.20, 44.80, 10.40 +41.00, 40.00, 60.24, 39.76, 20.48 +41.00, 40.00, 55.29, 44.71, 10.58 +41.00, 40.00, 55.29, 44.71, 10.57 +41.00, 40.00, 55.28, 44.72, 10.57 +41.00, 40.00, 55.28, 44.72, 10.56 +41.00, 40.00, 55.28, 44.72, 10.55 +41.00, 40.00, 55.27, 44.73, 10.54 +40.94, 40.00, 57.79, 42.21, 15.58 +40.94, 40.00, 55.31, 44.69, 10.63 +40.94, 40.00, 55.31, 44.69, 10.62 +40.94, 40.00, 55.31, 44.69, 10.61 +40.94, 40.00, 55.30, 44.70, 10.61 +40.94, 40.00, 55.30, 44.70, 10.60 +40.94, 40.00, 55.30, 44.70, 10.59 +40.94, 40.00, 55.29, 44.71, 10.59 +40.94, 40.00, 55.29, 44.71, 10.58 +41.00, 40.00, 52.76, 47.24, 5.53 +40.94, 40.00, 57.75, 42.25, 15.51 +40.94, 40.00, 55.28, 44.72, 10.56 +40.94, 40.00, 55.28, 44.72, 10.55 +40.94, 40.00, 55.27, 44.73, 10.54 +40.94, 40.00, 55.27, 44.73, 10.54 +40.94, 40.00, 55.26, 44.74, 10.53 +40.87, 40.00, 57.78, 42.22, 15.57 +40.87, 40.00, 55.31, 44.69, 10.62 +40.87, 40.00, 55.30, 44.70, 10.61 +40.87, 40.00, 55.30, 44.70, 10.60 +40.87, 40.00, 55.30, 44.70, 10.60 +40.87, 40.00, 55.29, 44.71, 10.59 +40.87, 40.00, 55.29, 44.71, 10.58 +40.87, 40.00, 55.29, 44.71, 10.58 +40.87, 40.00, 55.28, 44.72, 10.57 +40.87, 40.00, 55.28, 44.72, 10.56 +40.87, 40.00, 55.28, 44.72, 10.56 +40.87, 40.00, 55.28, 44.72, 10.55 +40.87, 40.00, 55.27, 44.73, 10.54 +40.87, 40.00, 55.27, 44.73, 10.54 +40.87, 40.00, 55.27, 44.73, 10.53 +40.87, 40.00, 55.26, 44.74, 10.52 +40.74, 40.00, 60.30, 39.70, 20.60 +40.74, 40.00, 55.36, 44.64, 10.71 +40.87, 40.00, 50.31, 49.69, 0.62 +40.74, 40.00, 60.29, 39.71, 20.59 +40.74, 40.00, 55.35, 44.65, 10.69 +40.74, 40.00, 55.34, 44.66, 10.69 +40.87, 40.00, 50.30, 49.70, 0.60 +40.87, 40.00, 55.24, 44.76, 10.48 +40.87, 40.00, 55.24, 44.76, 10.47 +40.87, 40.00, 55.23, 44.77, 10.46 +40.87, 40.00, 55.23, 44.77, 10.46 +40.87, 40.00, 55.23, 44.77, 10.45 +40.87, 40.00, 55.22, 44.78, 10.44 +40.87, 40.00, 55.22, 44.78, 10.44 +40.87, 40.00, 55.22, 44.78, 10.43 +40.94, 40.00, 52.69, 47.31, 5.38 +40.94, 40.00, 55.16, 44.84, 10.32 +40.94, 40.00, 55.16, 44.84, 10.31 +40.94, 40.00, 55.15, 44.85, 10.30 +40.94, 40.00, 55.15, 44.85, 10.30 +40.94, 40.00, 55.15, 44.85, 10.29 +40.94, 40.00, 55.14, 44.86, 10.28 +40.94, 40.00, 55.14, 44.86, 10.28 +40.94, 40.00, 55.13, 44.87, 10.27 +40.94, 40.00, 55.13, 44.87, 10.26 +40.94, 40.00, 55.13, 44.87, 10.26 +40.94, 40.00, 55.12, 44.88, 10.25 +40.94, 40.00, 55.12, 44.88, 10.24 +40.94, 40.00, 55.12, 44.88, 10.23 +41.00, 40.00, 52.59, 47.41, 5.18 +40.94, 40.00, 57.58, 42.42, 15.16 +41.00, 40.00, 52.58, 47.42, 5.17 +41.00, 40.00, 55.05, 44.95, 10.11 +41.00, 40.00, 55.05, 44.95, 10.10 +41.00, 40.00, 55.05, 44.95, 10.09 +41.00, 40.00, 55.04, 44.96, 10.08 +41.00, 40.00, 55.04, 44.96, 10.08 +41.00, 40.00, 55.03, 44.97, 10.07 +41.00, 40.00, 55.03, 44.97, 10.06 +41.00, 40.00, 55.03, 44.97, 10.05 +41.00, 40.00, 55.02, 44.98, 10.05 +41.00, 40.00, 55.02, 44.98, 10.04 +41.00, 40.00, 55.02, 44.98, 10.03 +41.00, 40.00, 55.01, 44.99, 10.02 +41.13, 40.00, 49.96, 50.04, -0.07 +41.00, 40.00, 59.95, 40.05, 19.90 +41.00, 40.00, 55.00, 45.00, 10.00 +41.00, 40.00, 55.00, 45.00, 9.99 +41.00, 40.00, 54.99, 45.01, 9.98 +41.00, 40.00, 54.99, 45.01, 9.98 +41.00, 40.00, 54.98, 45.02, 9.97 +41.00, 40.00, 54.98, 45.02, 9.96 +41.00, 40.00, 54.98, 45.02, 9.95 +41.00, 40.00, 54.97, 45.03, 9.95 +41.00, 40.00, 54.97, 45.03, 9.94 +41.00, 40.00, 54.97, 45.03, 9.93 +41.00, 40.00, 54.96, 45.04, 9.92 +40.94, 40.00, 57.48, 42.52, 14.96 +41.00, 40.00, 52.48, 47.52, 4.97 +40.94, 40.00, 57.47, 42.53, 14.95 +40.94, 40.00, 55.00, 45.00, 10.00 +40.94, 40.00, 54.99, 45.01, 9.99 +40.94, 40.00, 54.99, 45.01, 9.98 +41.00, 40.00, 52.47, 47.53, 4.93 +41.00, 40.00, 54.93, 45.07, 9.87 +41.00, 40.00, 54.93, 45.07, 9.86 +41.00, 40.00, 54.93, 45.07, 9.85 +41.00, 40.00, 54.92, 45.08, 9.84 +41.00, 40.00, 54.92, 45.08, 9.84 +41.00, 40.00, 54.91, 45.09, 9.83 +41.00, 40.00, 54.91, 45.09, 9.82 +40.94, 40.00, 57.43, 42.57, 14.86 +41.00, 40.00, 52.43, 47.57, 4.86 +40.94, 40.00, 57.42, 42.58, 14.84 +40.94, 40.00, 54.95, 45.05, 9.89 +40.94, 40.00, 54.94, 45.06, 9.89 +40.94, 40.00, 54.94, 45.06, 9.88 +40.94, 40.00, 54.94, 45.06, 9.87 +40.94, 40.00, 54.93, 45.07, 9.86 +40.94, 40.00, 54.93, 45.07, 9.86 +40.94, 40.00, 54.93, 45.07, 9.85 +40.94, 40.00, 54.92, 45.08, 9.84 +40.94, 40.00, 54.92, 45.08, 9.84 +40.94, 40.00, 54.91, 45.09, 9.83 +40.94, 40.00, 54.91, 45.09, 9.82 +40.94, 40.00, 54.91, 45.09, 9.82 +41.00, 40.00, 52.38, 47.62, 4.77 +40.94, 40.00, 57.37, 42.63, 14.74 +41.00, 40.00, 52.38, 47.62, 4.75 +41.00, 40.00, 54.84, 45.16, 9.69 +41.00, 40.00, 54.84, 45.16, 9.68 +41.00, 40.00, 54.84, 45.16, 9.67 +41.00, 40.00, 54.83, 45.17, 9.66 +41.00, 40.00, 54.83, 45.17, 9.66 +41.00, 40.00, 54.82, 45.18, 9.65 +41.00, 40.00, 54.82, 45.18, 9.64 +41.00, 40.00, 54.82, 45.18, 9.63 +41.00, 40.00, 54.81, 45.19, 9.63 +41.00, 40.00, 54.81, 45.19, 9.62 +41.00, 40.00, 54.81, 45.19, 9.61 +41.00, 40.00, 54.80, 45.20, 9.60 +41.00, 40.00, 54.80, 45.20, 9.60 +41.00, 40.00, 54.79, 45.21, 9.59 +41.00, 40.00, 54.79, 45.21, 9.58 +41.00, 40.00, 54.79, 45.21, 9.57 +41.00, 40.00, 54.78, 45.22, 9.57 +41.00, 40.00, 54.78, 45.22, 9.56 +41.00, 40.00, 54.78, 45.22, 9.55 +41.00, 40.00, 54.77, 45.23, 9.54 +41.00, 40.00, 54.77, 45.23, 9.54 +41.00, 40.00, 54.76, 45.24, 9.53 +41.00, 40.00, 54.76, 45.24, 9.52 +41.00, 40.00, 54.76, 45.24, 9.51 +41.00, 40.00, 54.75, 45.25, 9.51 +41.00, 40.00, 54.75, 45.25, 9.50 +41.00, 40.00, 54.75, 45.25, 9.49 +41.00, 40.00, 54.74, 45.26, 9.48 +41.00, 40.00, 54.74, 45.26, 9.48 +41.00, 40.00, 54.73, 45.27, 9.47 +41.00, 40.00, 54.73, 45.27, 9.46 +41.00, 40.00, 54.73, 45.27, 9.45 +40.94, 40.00, 57.25, 42.75, 14.49 +40.94, 40.00, 54.77, 45.23, 9.54 +40.94, 40.00, 54.77, 45.23, 9.53 +40.94, 40.00, 54.76, 45.24, 9.53 +40.94, 40.00, 54.76, 45.24, 9.52 +40.94, 40.00, 54.76, 45.24, 9.51 +40.94, 40.00, 54.75, 45.25, 9.50 +40.94, 40.00, 54.75, 45.25, 9.50 +40.87, 40.00, 57.27, 42.73, 14.53 +40.87, 40.00, 54.79, 45.21, 9.58 +40.87, 40.00, 54.79, 45.21, 9.58 +40.87, 40.00, 54.78, 45.22, 9.57 +40.94, 40.00, 52.26, 47.74, 4.52 +40.94, 40.00, 54.73, 45.27, 9.46 +40.94, 40.00, 54.72, 45.28, 9.45 +40.94, 40.00, 54.72, 45.28, 9.44 +40.87, 40.00, 57.24, 42.76, 14.48 +40.87, 40.00, 54.76, 45.24, 9.53 +40.87, 40.00, 54.76, 45.24, 9.52 +40.87, 40.00, 54.76, 45.24, 9.52 +40.87, 40.00, 54.75, 45.25, 9.51 +40.87, 40.00, 54.75, 45.25, 9.50 +40.87, 40.00, 54.75, 45.25, 9.50 +40.87, 40.00, 54.74, 45.26, 9.49 +40.87, 40.00, 54.74, 45.26, 9.48 +40.74, 40.00, 59.78, 40.22, 19.56 +40.74, 40.00, 54.83, 45.17, 9.67 +40.74, 40.00, 54.83, 45.17, 9.66 +40.74, 40.00, 54.83, 45.17, 9.66 +40.74, 40.00, 54.83, 45.17, 9.65 +40.74, 40.00, 54.82, 45.18, 9.65 +40.74, 40.00, 54.82, 45.18, 9.64 +40.74, 40.00, 54.82, 45.18, 9.64 +40.74, 40.00, 54.82, 45.18, 9.63 +40.74, 40.00, 54.81, 45.19, 9.63 +40.74, 40.00, 54.81, 45.19, 9.62 +40.74, 40.00, 54.81, 45.19, 9.61 +40.74, 40.00, 54.80, 45.20, 9.61 +40.74, 40.00, 54.80, 45.20, 9.60 +40.74, 40.00, 54.80, 45.20, 9.60 +40.74, 40.00, 54.80, 45.20, 9.59 +40.74, 40.00, 54.79, 45.21, 9.59 +40.74, 40.00, 54.79, 45.21, 9.58 +40.74, 40.00, 54.79, 45.21, 9.58 +40.74, 40.00, 54.79, 45.21, 9.57 +40.74, 40.00, 54.78, 45.22, 9.56 +40.74, 40.00, 54.78, 45.22, 9.56 +40.74, 40.00, 54.78, 45.22, 9.55 +40.74, 40.00, 54.77, 45.23, 9.55 +40.74, 40.00, 54.77, 45.23, 9.54 +40.74, 40.00, 54.77, 45.23, 9.54 +40.74, 40.00, 54.77, 45.23, 9.53 +40.74, 40.00, 54.76, 45.24, 9.53 +40.74, 40.00, 54.76, 45.24, 9.52 +40.74, 40.00, 54.76, 45.24, 9.52 +40.87, 40.00, 49.71, 50.29, -0.58 +40.87, 40.00, 54.65, 45.35, 9.30 +40.87, 40.00, 54.65, 45.35, 9.30 +40.87, 40.00, 54.65, 45.35, 9.29 +40.87, 40.00, 54.64, 45.36, 9.28 +40.87, 40.00, 54.64, 45.36, 9.28 +40.94, 40.00, 52.11, 47.89, 4.23 +40.87, 40.00, 57.10, 42.90, 14.21 +40.94, 40.00, 52.11, 47.89, 4.21 +40.94, 40.00, 54.58, 45.42, 9.15 +40.94, 40.00, 54.57, 45.43, 9.14 +40.94, 40.00, 54.57, 45.43, 9.14 +40.94, 40.00, 54.57, 45.43, 9.13 +40.94, 40.00, 54.56, 45.44, 9.12 +40.94, 40.00, 54.56, 45.44, 9.12 +40.94, 40.00, 54.55, 45.45, 9.11 +40.94, 40.00, 54.55, 45.45, 9.10 +40.94, 40.00, 54.55, 45.45, 9.10 +41.00, 40.00, 52.02, 47.98, 4.05 +41.00, 40.00, 54.49, 45.51, 8.98 +41.00, 40.00, 54.49, 45.51, 8.97 +41.00, 40.00, 54.48, 45.52, 8.97 +41.00, 40.00, 54.48, 45.52, 8.96 +41.13, 40.00, 49.43, 50.57, -1.13 +41.13, 40.00, 54.37, 45.63, 8.74 +41.13, 40.00, 54.37, 45.63, 8.74 +41.13, 40.00, 54.36, 45.64, 8.73 +41.13, 40.00, 54.36, 45.64, 8.72 +41.13, 40.00, 54.36, 45.64, 8.71 +41.13, 40.00, 54.35, 45.65, 8.70 +41.13, 40.00, 54.35, 45.65, 8.69 +41.13, 40.00, 54.34, 45.66, 8.68 +41.13, 40.00, 54.34, 45.66, 8.68 +41.13, 40.00, 54.33, 45.67, 8.67 +41.13, 40.00, 54.33, 45.67, 8.66 +41.13, 40.00, 54.33, 45.67, 8.65 +41.13, 40.00, 54.32, 45.68, 8.64 +41.13, 40.00, 54.32, 45.68, 8.63 +41.13, 40.00, 54.31, 45.69, 8.63 +41.13, 40.00, 54.31, 45.69, 8.62 +41.13, 40.00, 54.30, 45.70, 8.61 +41.13, 40.00, 54.30, 45.70, 8.60 +41.00, 40.00, 59.34, 40.66, 18.68 +41.13, 40.00, 49.35, 50.65, -1.30 +41.00, 40.00, 59.33, 40.67, 18.66 +41.00, 40.00, 54.38, 45.62, 8.77 +41.00, 40.00, 54.38, 45.62, 8.76 +41.00, 40.00, 54.38, 45.62, 8.75 +40.94, 40.00, 56.89, 43.11, 13.79 +40.94, 40.00, 54.42, 45.58, 8.84 +40.94, 40.00, 54.41, 45.59, 8.83 +40.94, 40.00, 54.41, 45.59, 8.82 +40.94, 40.00, 54.41, 45.59, 8.82 +40.94, 40.00, 54.40, 45.60, 8.81 +40.94, 40.00, 54.40, 45.60, 8.80 +40.87, 40.00, 56.92, 43.08, 13.84 +40.87, 40.00, 54.44, 45.56, 8.89 +40.87, 40.00, 54.44, 45.56, 8.88 +40.87, 40.00, 54.44, 45.56, 8.87 +40.87, 40.00, 54.43, 45.57, 8.87 +40.87, 40.00, 54.43, 45.57, 8.86 +40.87, 40.00, 54.43, 45.57, 8.85 +40.74, 40.00, 59.47, 40.53, 18.93 +40.74, 40.00, 54.52, 45.48, 9.04 +40.74, 40.00, 54.52, 45.48, 9.04 +40.74, 40.00, 54.52, 45.48, 9.03 +40.67, 40.00, 57.03, 42.97, 14.07 +40.74, 40.00, 52.04, 47.96, 4.08 +40.67, 40.00, 57.03, 42.97, 14.06 +40.67, 40.00, 54.55, 45.45, 9.11 +40.67, 40.00, 54.55, 45.45, 9.10 +40.67, 40.00, 54.55, 45.45, 9.10 +40.67, 40.00, 54.55, 45.45, 9.09 +40.67, 40.00, 54.54, 45.46, 9.09 +40.67, 40.00, 54.54, 45.46, 9.08 +40.67, 40.00, 54.54, 45.46, 9.08 +40.67, 40.00, 54.54, 45.46, 9.07 +40.67, 40.00, 54.53, 45.47, 9.07 +40.67, 40.00, 54.53, 45.47, 9.06 +40.67, 40.00, 54.53, 45.47, 9.06 +40.61, 40.00, 57.05, 42.95, 14.10 +40.61, 40.00, 54.57, 45.43, 9.15 +40.61, 40.00, 54.57, 45.43, 9.14 +40.61, 40.00, 54.57, 45.43, 9.14 +40.61, 40.00, 54.57, 45.43, 9.13 +40.61, 40.00, 54.56, 45.44, 9.13 +40.61, 40.00, 54.56, 45.44, 9.13 +40.61, 40.00, 54.56, 45.44, 9.12 +40.67, 40.00, 52.04, 47.96, 4.07 +40.67, 40.00, 54.51, 45.49, 9.01 +40.67, 40.00, 54.50, 45.50, 9.01 +40.67, 40.00, 54.50, 45.50, 9.00 +40.67, 40.00, 54.50, 45.50, 9.00 +40.67, 40.00, 54.50, 45.50, 8.99 +40.67, 40.00, 54.49, 45.51, 8.99 +40.67, 40.00, 54.49, 45.51, 8.98 +40.74, 40.00, 51.97, 48.03, 3.93 +40.74, 40.00, 54.44, 45.56, 8.87 +40.74, 40.00, 54.43, 45.57, 8.87 +40.74, 40.00, 54.43, 45.57, 8.86 +40.74, 40.00, 54.43, 45.57, 8.86 +40.74, 40.00, 54.42, 45.58, 8.85 +40.74, 40.00, 54.42, 45.58, 8.84 +40.87, 40.00, 49.38, 50.62, -1.25 +40.87, 40.00, 54.32, 45.68, 8.63 +40.87, 40.00, 54.31, 45.69, 8.63 +40.87, 40.00, 54.31, 45.69, 8.62 +40.94, 40.00, 51.79, 48.21, 3.57 +40.94, 40.00, 54.25, 45.75, 8.51 +40.94, 40.00, 54.25, 45.75, 8.50 +40.94, 40.00, 54.25, 45.75, 8.49 +40.94, 40.00, 54.24, 45.76, 8.49 +40.94, 40.00, 54.24, 45.76, 8.48 +40.94, 40.00, 54.24, 45.76, 8.47 +40.94, 40.00, 54.23, 45.77, 8.47 +40.94, 40.00, 54.23, 45.77, 8.46 +40.94, 40.00, 54.23, 45.77, 8.45 +40.94, 40.00, 54.22, 45.78, 8.44 +40.94, 40.00, 54.22, 45.78, 8.44 +40.94, 40.00, 54.22, 45.78, 8.43 +40.94, 40.00, 54.21, 45.79, 8.42 +40.94, 40.00, 54.21, 45.79, 8.42 +40.94, 40.00, 54.20, 45.80, 8.41 +40.94, 40.00, 54.20, 45.80, 8.40 +40.94, 40.00, 54.20, 45.80, 8.40 +40.94, 40.00, 54.19, 45.81, 8.39 +40.94, 40.00, 54.19, 45.81, 8.38 +40.94, 40.00, 54.19, 45.81, 8.37 +40.94, 40.00, 54.18, 45.82, 8.37 +40.94, 40.00, 54.18, 45.82, 8.36 +40.94, 40.00, 54.18, 45.82, 8.35 +40.94, 40.00, 54.17, 45.83, 8.35 +40.94, 40.00, 54.17, 45.83, 8.34 +40.94, 40.00, 54.17, 45.83, 8.33 +40.94, 40.00, 54.16, 45.84, 8.33 +40.94, 40.00, 54.16, 45.84, 8.32 +40.94, 40.00, 54.16, 45.84, 8.31 +40.94, 40.00, 54.15, 45.85, 8.30 +40.94, 40.00, 54.15, 45.85, 8.30 +40.94, 40.00, 54.14, 45.86, 8.29 +40.87, 40.00, 56.66, 43.34, 13.33 +40.87, 40.00, 54.19, 45.81, 8.38 +40.87, 40.00, 54.18, 45.82, 8.37 +40.87, 40.00, 54.18, 45.82, 8.36 +40.87, 40.00, 54.18, 45.82, 8.36 +40.87, 40.00, 54.17, 45.83, 8.35 +40.74, 40.00, 59.21, 40.79, 18.43 +40.74, 40.00, 54.27, 45.73, 8.54 +40.74, 40.00, 54.27, 45.73, 8.53 +40.74, 40.00, 54.26, 45.74, 8.53 +40.74, 40.00, 54.26, 45.74, 8.52 +40.74, 40.00, 54.26, 45.74, 8.51 +40.74, 40.00, 54.25, 45.75, 8.51 +40.74, 40.00, 54.25, 45.75, 8.50 +40.74, 40.00, 54.25, 45.75, 8.50 +40.74, 40.00, 54.25, 45.75, 8.49 +40.74, 40.00, 54.24, 45.76, 8.49 +40.74, 40.00, 54.24, 45.76, 8.48 +40.74, 40.00, 54.24, 45.76, 8.48 +40.74, 40.00, 54.24, 45.76, 8.47 +40.74, 40.00, 54.23, 45.77, 8.46 +40.74, 40.00, 54.23, 45.77, 8.46 +40.74, 40.00, 54.23, 45.77, 8.45 +40.74, 40.00, 54.22, 45.78, 8.45 +40.74, 40.00, 54.22, 45.78, 8.44 +40.74, 40.00, 54.22, 45.78, 8.44 +40.74, 40.00, 54.22, 45.78, 8.43 +40.74, 40.00, 54.21, 45.79, 8.43 +40.74, 40.00, 54.21, 45.79, 8.42 +40.74, 40.00, 54.21, 45.79, 8.41 +40.74, 40.00, 54.20, 45.80, 8.41 +40.74, 40.00, 54.20, 45.80, 8.40 +40.74, 40.00, 54.20, 45.80, 8.40 +40.74, 40.00, 54.20, 45.80, 8.39 +40.74, 40.00, 54.19, 45.81, 8.39 +40.87, 40.00, 49.15, 50.85, -1.70 +40.87, 40.00, 54.09, 45.91, 8.18 +40.87, 40.00, 54.08, 45.92, 8.17 +40.87, 40.00, 54.08, 45.92, 8.16 +40.87, 40.00, 54.08, 45.92, 8.16 +40.94, 40.00, 51.55, 48.45, 3.11 +40.94, 40.00, 54.02, 45.98, 8.04 +40.94, 40.00, 54.02, 45.98, 8.04 +40.94, 40.00, 54.01, 45.99, 8.03 +40.94, 40.00, 54.01, 45.99, 8.02 +40.94, 40.00, 54.01, 45.99, 8.02 +40.94, 40.00, 54.00, 46.00, 8.01 +40.94, 40.00, 54.00, 46.00, 8.00 +40.94, 40.00, 54.00, 46.00, 7.99 +40.94, 40.00, 53.99, 46.01, 7.99 +40.94, 40.00, 53.99, 46.01, 7.98 +40.87, 40.00, 56.51, 43.49, 13.02 +40.94, 40.00, 51.51, 48.49, 3.02 +40.94, 40.00, 53.98, 46.02, 7.96 +40.94, 40.00, 53.98, 46.02, 7.95 +40.94, 40.00, 53.97, 46.03, 7.95 +40.94, 40.00, 53.97, 46.03, 7.94 +40.94, 40.00, 53.97, 46.03, 7.93 +40.94, 40.00, 53.96, 46.04, 7.93 +40.94, 40.00, 53.96, 46.04, 7.92 +40.94, 40.00, 53.96, 46.04, 7.91 +40.94, 40.00, 53.95, 46.05, 7.90 +41.00, 40.00, 51.43, 48.57, 2.85 +40.94, 40.00, 56.42, 43.58, 12.83 +40.94, 40.00, 53.94, 46.06, 7.88 +41.00, 40.00, 51.42, 48.58, 2.83 +41.00, 40.00, 53.88, 46.12, 7.77 +41.00, 40.00, 53.88, 46.12, 7.76 +41.00, 40.00, 53.88, 46.12, 7.75 +41.00, 40.00, 53.87, 46.13, 7.75 +41.00, 40.00, 53.87, 46.13, 7.74 +41.00, 40.00, 53.87, 46.13, 7.73 +41.00, 40.00, 53.86, 46.14, 7.72 +41.00, 40.00, 53.86, 46.14, 7.72 +41.00, 40.00, 53.85, 46.15, 7.71 +41.00, 40.00, 53.85, 46.15, 7.70 +41.00, 40.00, 53.85, 46.15, 7.69 +41.00, 40.00, 53.84, 46.16, 7.69 +41.00, 40.00, 53.84, 46.16, 7.68 +41.00, 40.00, 53.84, 46.16, 7.67 +41.00, 40.00, 53.83, 46.17, 7.66 +41.00, 40.00, 53.83, 46.17, 7.66 +41.00, 40.00, 53.82, 46.18, 7.65 +41.00, 40.00, 53.82, 46.18, 7.64 +41.00, 40.00, 53.82, 46.18, 7.63 +40.94, 40.00, 56.33, 43.67, 12.67 +41.00, 40.00, 51.34, 48.66, 2.68 +41.00, 40.00, 53.81, 46.19, 7.61 +41.00, 40.00, 53.80, 46.20, 7.60 +40.94, 40.00, 56.32, 43.68, 12.64 +40.94, 40.00, 53.84, 46.16, 7.69 +40.94, 40.00, 53.84, 46.16, 7.68 +40.94, 40.00, 53.84, 46.16, 7.67 +40.94, 40.00, 53.83, 46.17, 7.67 +40.94, 40.00, 53.83, 46.17, 7.66 +40.94, 40.00, 53.83, 46.17, 7.65 +40.94, 40.00, 53.82, 46.18, 7.65 +40.94, 40.00, 53.82, 46.18, 7.64 +40.94, 40.00, 53.82, 46.18, 7.63 +40.94, 40.00, 53.81, 46.19, 7.63 +40.94, 40.00, 53.81, 46.19, 7.62 +40.94, 40.00, 53.81, 46.19, 7.61 +40.94, 40.00, 53.80, 46.20, 7.60 +40.94, 40.00, 53.80, 46.20, 7.60 +40.94, 40.00, 53.80, 46.20, 7.59 +40.87, 40.00, 56.31, 43.69, 12.63 +40.94, 40.00, 51.32, 48.68, 2.63 +40.87, 40.00, 56.31, 43.69, 12.61 +40.87, 40.00, 53.83, 46.17, 7.66 +40.87, 40.00, 53.83, 46.17, 7.66 +40.87, 40.00, 53.82, 46.18, 7.65 +40.87, 40.00, 53.82, 46.18, 7.64 +40.87, 40.00, 53.82, 46.18, 7.64 +40.87, 40.00, 53.82, 46.18, 7.63 +40.87, 40.00, 53.81, 46.19, 7.62 +40.87, 40.00, 53.81, 46.19, 7.62 +40.87, 40.00, 53.81, 46.19, 7.61 +40.87, 40.00, 53.80, 46.20, 7.60 +40.87, 40.00, 53.80, 46.20, 7.60 +40.87, 40.00, 53.80, 46.20, 7.59 +40.87, 40.00, 53.79, 46.21, 7.58 +40.74, 40.00, 58.83, 41.17, 17.66 +40.74, 40.00, 53.89, 46.11, 7.77 +40.74, 40.00, 53.88, 46.12, 7.77 +40.74, 40.00, 53.88, 46.12, 7.76 +40.74, 40.00, 53.88, 46.12, 7.75 +40.74, 40.00, 53.87, 46.13, 7.75 +40.74, 40.00, 53.87, 46.13, 7.74 +40.74, 40.00, 53.87, 46.13, 7.74 +40.67, 40.00, 56.39, 43.61, 12.78 +40.67, 40.00, 53.91, 46.09, 7.83 +40.67, 40.00, 53.91, 46.09, 7.82 +40.67, 40.00, 53.91, 46.09, 7.82 +40.67, 40.00, 53.91, 46.09, 7.81 +40.67, 40.00, 53.90, 46.10, 7.81 +40.67, 40.00, 53.90, 46.10, 7.80 +40.67, 40.00, 53.90, 46.10, 7.80 +40.67, 40.00, 53.90, 46.10, 7.79 +40.67, 40.00, 53.89, 46.11, 7.79 +40.67, 40.00, 53.89, 46.11, 7.78 +40.67, 40.00, 53.89, 46.11, 7.78 +40.67, 40.00, 53.89, 46.11, 7.77 +40.67, 40.00, 53.88, 46.12, 7.77 +40.67, 40.00, 53.88, 46.12, 7.76 +40.67, 40.00, 53.88, 46.12, 7.76 +40.67, 40.00, 53.88, 46.12, 7.75 +40.67, 40.00, 53.87, 46.13, 7.75 +40.67, 40.00, 53.87, 46.13, 7.74 +40.67, 40.00, 53.87, 46.13, 7.74 +40.67, 40.00, 53.87, 46.13, 7.73 +40.61, 40.00, 56.38, 43.62, 12.77 +40.61, 40.00, 53.91, 46.09, 7.82 +40.61, 40.00, 53.91, 46.09, 7.82 +40.61, 40.00, 53.91, 46.09, 7.81 +40.61, 40.00, 53.90, 46.10, 7.81 +40.61, 40.00, 53.90, 46.10, 7.80 +40.61, 40.00, 53.90, 46.10, 7.80 +40.61, 40.00, 53.90, 46.10, 7.79 +40.61, 40.00, 53.89, 46.11, 7.79 +40.61, 40.00, 53.89, 46.11, 7.78 +40.67, 40.00, 51.37, 48.63, 2.74 +40.67, 40.00, 53.84, 46.16, 7.68 +40.67, 40.00, 53.84, 46.16, 7.67 +40.67, 40.00, 53.83, 46.17, 7.67 +40.67, 40.00, 53.83, 46.17, 7.66 +40.67, 40.00, 53.83, 46.17, 7.66 +40.67, 40.00, 53.83, 46.17, 7.65 +40.67, 40.00, 53.82, 46.18, 7.65 +40.61, 40.00, 56.34, 43.66, 12.68 +40.61, 40.00, 53.87, 46.13, 7.74 +40.61, 40.00, 53.87, 46.13, 7.73 +40.61, 40.00, 53.86, 46.14, 7.73 +40.61, 40.00, 53.86, 46.14, 7.72 +40.61, 40.00, 53.86, 46.14, 7.72 +40.61, 40.00, 53.86, 46.14, 7.71 +40.61, 40.00, 53.85, 46.15, 7.71 +40.61, 40.00, 53.85, 46.15, 7.70 +40.61, 40.00, 53.85, 46.15, 7.70 +40.67, 40.00, 51.33, 48.67, 2.65 +40.67, 40.00, 53.80, 46.20, 7.59 +40.67, 40.00, 53.79, 46.21, 7.59 +40.67, 40.00, 53.79, 46.21, 7.58 +40.61, 40.00, 56.31, 43.69, 12.62 +40.61, 40.00, 53.83, 46.17, 7.67 +40.67, 40.00, 51.31, 48.69, 2.62 +40.61, 40.00, 56.30, 43.70, 12.60 +40.61, 40.00, 53.83, 46.17, 7.66 +40.61, 40.00, 53.83, 46.17, 7.65 +40.61, 40.00, 53.82, 46.18, 7.65 +40.61, 40.00, 53.82, 46.18, 7.64 +40.61, 40.00, 53.82, 46.18, 7.64 +40.61, 40.00, 53.82, 46.18, 7.63 +40.61, 40.00, 53.81, 46.19, 7.63 +40.61, 40.00, 53.81, 46.19, 7.62 +40.61, 40.00, 53.81, 46.19, 7.62 +40.61, 40.00, 53.81, 46.19, 7.61 +40.67, 40.00, 51.28, 48.72, 2.57 +40.67, 40.00, 53.75, 46.25, 7.51 +40.67, 40.00, 53.75, 46.25, 7.50 +40.67, 40.00, 53.75, 46.25, 7.50 +40.67, 40.00, 53.75, 46.25, 7.49 +40.67, 40.00, 53.74, 46.26, 7.49 +40.67, 40.00, 53.74, 46.26, 7.48 +40.67, 40.00, 53.74, 46.26, 7.48 +40.67, 40.00, 53.74, 46.26, 7.47 +40.67, 40.00, 53.73, 46.27, 7.47 +40.67, 40.00, 53.73, 46.27, 7.46 +40.67, 40.00, 53.73, 46.27, 7.46 +40.67, 40.00, 53.73, 46.27, 7.45 +40.67, 40.00, 53.72, 46.28, 7.45 +40.67, 40.00, 53.72, 46.28, 7.44 +40.67, 40.00, 53.72, 46.28, 7.44 +40.67, 40.00, 53.72, 46.28, 7.43 +40.67, 40.00, 53.71, 46.29, 7.43 +40.67, 40.00, 53.71, 46.29, 7.42 +40.67, 40.00, 53.71, 46.29, 7.42 +40.67, 40.00, 53.71, 46.29, 7.41 +40.67, 40.00, 53.70, 46.30, 7.41 +40.67, 40.00, 53.70, 46.30, 7.40 +40.67, 40.00, 53.70, 46.30, 7.40 +40.67, 40.00, 53.70, 46.30, 7.39 +40.67, 40.00, 53.69, 46.31, 7.39 +40.67, 40.00, 53.69, 46.31, 7.38 +40.67, 40.00, 53.69, 46.31, 7.38 +40.67, 40.00, 53.69, 46.31, 7.37 +40.67, 40.00, 53.68, 46.32, 7.37 +40.67, 40.00, 53.68, 46.32, 7.36 +40.67, 40.00, 53.68, 46.32, 7.35 +40.67, 40.00, 53.67, 46.33, 7.35 +40.67, 40.00, 53.67, 46.33, 7.34 +40.67, 40.00, 53.67, 46.33, 7.34 +40.67, 40.00, 53.67, 46.33, 7.33 +40.67, 40.00, 53.66, 46.34, 7.33 +40.67, 40.00, 53.66, 46.34, 7.32 +40.67, 40.00, 53.66, 46.34, 7.32 +40.67, 40.00, 53.66, 46.34, 7.31 +40.67, 40.00, 53.65, 46.35, 7.31 +40.67, 40.00, 53.65, 46.35, 7.30 +40.67, 40.00, 53.65, 46.35, 7.30 +40.67, 40.00, 53.65, 46.35, 7.29 +40.61, 40.00, 56.17, 43.83, 12.33 +40.61, 40.00, 53.69, 46.31, 7.38 +40.61, 40.00, 53.69, 46.31, 7.38 +40.61, 40.00, 53.69, 46.31, 7.38 +40.61, 40.00, 53.69, 46.31, 7.37 +40.61, 40.00, 53.68, 46.32, 7.37 +40.61, 40.00, 53.68, 46.32, 7.36 +40.61, 40.00, 53.68, 46.32, 7.36 +40.61, 40.00, 53.68, 46.32, 7.35 +40.61, 40.00, 53.67, 46.33, 7.35 +40.47, 40.00, 58.71, 41.29, 17.43 +40.47, 40.00, 53.77, 46.23, 7.54 +40.47, 40.00, 53.77, 46.23, 7.54 +40.47, 40.00, 53.77, 46.23, 7.53 +40.47, 40.00, 53.76, 46.24, 7.53 +40.47, 40.00, 53.76, 46.24, 7.52 +40.47, 40.00, 53.76, 46.24, 7.52 +40.61, 40.00, 48.72, 51.28, -2.57 +40.47, 40.00, 58.70, 41.30, 17.40 +40.61, 40.00, 48.71, 51.29, -2.58 +40.61, 40.00, 53.65, 46.35, 7.31 +40.47, 40.00, 58.69, 41.31, 17.39 +40.61, 40.00, 48.71, 51.29, -2.59 +40.61, 40.00, 53.65, 46.35, 7.29 +40.61, 40.00, 53.64, 46.36, 7.29 +40.61, 40.00, 53.64, 46.36, 7.28 +40.47, 40.00, 58.68, 41.32, 17.37 +40.61, 40.00, 48.69, 51.31, -2.61 +40.47, 40.00, 58.68, 41.32, 17.36 +40.47, 40.00, 53.73, 46.27, 7.47 +40.47, 40.00, 53.73, 46.27, 7.46 +40.47, 40.00, 53.73, 46.27, 7.46 +40.47, 40.00, 53.73, 46.27, 7.46 +40.47, 40.00, 53.73, 46.27, 7.45 +40.47, 40.00, 53.72, 46.28, 7.45 +40.47, 40.00, 53.72, 46.28, 7.45 +40.47, 40.00, 53.72, 46.28, 7.44 +40.47, 40.00, 53.72, 46.28, 7.44 +40.47, 40.00, 53.72, 46.28, 7.43 +40.47, 40.00, 53.72, 46.28, 7.43 +40.47, 40.00, 53.71, 46.29, 7.43 +40.61, 40.00, 48.67, 51.33, -2.66 +40.61, 40.00, 53.61, 46.39, 7.22 +40.61, 40.00, 53.61, 46.39, 7.22 +40.61, 40.00, 53.61, 46.39, 7.21 +40.61, 40.00, 53.60, 46.40, 7.21 +40.67, 40.00, 51.08, 48.92, 2.16 +40.67, 40.00, 53.55, 46.45, 7.10 +40.61, 40.00, 56.07, 43.93, 12.14 +40.61, 40.00, 53.59, 46.41, 7.19 +40.67, 40.00, 51.07, 48.93, 2.14 +40.61, 40.00, 56.06, 43.94, 12.12 +40.61, 40.00, 53.59, 46.41, 7.17 +40.67, 40.00, 51.06, 48.94, 2.13 +40.67, 40.00, 53.53, 46.47, 7.07 +40.67, 40.00, 53.53, 46.47, 7.06 +40.67, 40.00, 53.53, 46.47, 7.05 +40.67, 40.00, 53.52, 46.48, 7.05 +40.67, 40.00, 53.52, 46.48, 7.04 +40.67, 40.00, 53.52, 46.48, 7.04 +40.67, 40.00, 53.52, 46.48, 7.03 +40.67, 40.00, 53.51, 46.49, 7.03 +40.74, 40.00, 50.99, 49.01, 1.98 +40.74, 40.00, 53.46, 46.54, 6.92 +40.74, 40.00, 53.46, 46.54, 6.91 +40.74, 40.00, 53.45, 46.55, 6.91 +40.74, 40.00, 53.45, 46.55, 6.90 +40.74, 40.00, 53.45, 46.55, 6.90 +40.74, 40.00, 53.45, 46.55, 6.89 +40.74, 40.00, 53.44, 46.56, 6.89 +40.87, 40.00, 48.40, 51.60, -3.21 +40.87, 40.00, 53.34, 46.66, 6.68 +40.87, 40.00, 53.33, 46.67, 6.67 +40.87, 40.00, 53.33, 46.67, 6.66 +40.87, 40.00, 53.33, 46.67, 6.66 +40.87, 40.00, 53.32, 46.68, 6.65 +40.87, 40.00, 53.32, 46.68, 6.64 +40.87, 40.00, 53.32, 46.68, 6.64 +40.94, 40.00, 50.79, 49.21, 1.59 +40.94, 40.00, 53.26, 46.74, 6.52 +40.94, 40.00, 53.26, 46.74, 6.52 +40.94, 40.00, 53.25, 46.75, 6.51 +40.94, 40.00, 53.25, 46.75, 6.50 +40.94, 40.00, 53.25, 46.75, 6.50 +40.94, 40.00, 53.24, 46.76, 6.49 +40.94, 40.00, 53.24, 46.76, 6.48 +40.94, 40.00, 53.24, 46.76, 6.47 +40.94, 40.00, 53.23, 46.77, 6.47 +40.94, 40.00, 53.23, 46.77, 6.46 +40.94, 40.00, 53.23, 46.77, 6.45 +40.94, 40.00, 53.22, 46.78, 6.45 +40.94, 40.00, 53.22, 46.78, 6.44 +40.94, 40.00, 53.22, 46.78, 6.43 +40.94, 40.00, 53.21, 46.79, 6.43 +40.94, 40.00, 53.21, 46.79, 6.42 +40.94, 40.00, 53.21, 46.79, 6.41 +40.94, 40.00, 53.20, 46.80, 6.40 +40.94, 40.00, 53.20, 46.80, 6.40 +40.94, 40.00, 53.20, 46.80, 6.39 +40.87, 40.00, 55.71, 44.29, 11.43 +40.87, -10.00, 25.00, 75.00, -50.00 +40.87, -10.00, 25.00, 75.00, -50.00 +40.74, -10.00, 25.00, 75.00, -50.00 +40.74, -10.00, 25.00, 75.00, -50.00 +40.74, -10.00, 25.00, 75.00, -50.00 +40.67, -10.00, 25.00, 75.00, -50.00 +40.67, -10.00, 25.00, 75.00, -50.00 +40.67, -10.00, 25.00, 75.00, -50.00 +40.67, -10.00, 25.00, 75.00, -50.00 +40.61, -10.00, 25.00, 75.00, -50.00 +40.61, -10.00, 25.00, 75.00, -50.00 +40.47, -10.00, 25.00, 75.00, -50.00 +40.41, -10.00, 25.00, 75.00, -50.00 +40.34, -10.00, 25.00, 75.00, -50.00 +40.14, -10.00, 25.00, 75.00, -50.00 +40.08, -10.00, 25.00, 75.00, -50.00 +39.88, -10.00, 25.00, 75.00, -50.00 +39.68, -10.00, 25.00, 75.00, -50.00 +39.55, -10.00, 25.00, 75.00, -50.00 +39.35, -10.00, 25.00, 75.00, -50.00 +39.09, -10.00, 25.00, 75.00, -50.00 +38.89, -10.00, 25.00, 75.00, -50.00 +38.63, -10.00, 25.00, 75.00, -50.00 +38.50, -10.00, 25.00, 75.00, -50.00 +38.10, -10.00, 27.96, 72.04, -44.08 +37.97, -10.00, 25.00, 75.00, -50.00 +37.57, -10.00, 28.00, 72.00, -44.01 +37.31, -10.00, 25.00, 75.00, -50.00 +36.98, -10.00, 25.62, 74.38, -48.77 +36.72, -10.00, 25.00, 75.00, -50.00 +36.39, -10.00, 25.71, 74.29, -48.58 +35.99, -10.00, 28.31, 71.69, -43.39 +35.60, -10.00, 28.43, 71.57, -43.13 +35.20, -10.00, 28.56, 71.44, -42.88 +34.67, -10.00, 33.73, 66.27, -32.54 +34.28, -10.00, 28.92, 71.08, -42.16 +33.82, -10.00, 31.57, 68.43, -36.86 +33.29, -10.00, 34.28, 65.72, -31.45 +32.76, -10.00, 34.51, 65.49, -30.98 +32.23, -10.00, 34.75, 65.25, -30.50 +31.71, -10.00, 34.99, 65.01, -30.02 +31.18, -10.00, 35.23, 64.77, -29.54 +30.59, -10.00, 37.99, 62.01, -24.01 +30.06, -10.00, 35.77, 64.23, -28.46 +29.53, -10.00, 36.01, 63.99, -27.97 +28.87, -10.00, 41.31, 58.69, -17.39 +28.28, -10.00, 39.14, 60.86, -21.73 +27.75, -10.00, 36.92, 63.08, -26.16 +27.16, -10.00, 39.70, 60.30, -20.61 +26.43, -10.00, 45.05, 54.95, -9.91 +25.84, -10.00, 40.41, 59.59, -19.17 +25.11, -10.00, 45.77, 54.23, -8.46 +24.39, -10.00, 46.18, 53.82, -7.63 +23.73, -10.00, 44.08, 55.92, -11.84 +22.94, -10.00, 49.49, 50.51, -1.01 +22.15, -10.00, 49.97, 50.03, -0.07 +21.42, -10.00, 47.92, 52.08, -4.16 +20.57, -10.00, 53.39, 46.61, 6.79 +19.78, -10.00, 51.40, 48.60, 2.81 +19.05, -10.00, 49.37, 50.63, -1.27 +18.26, -10.00, 52.33, 47.67, 4.65 +17.47, -10.00, 52.82, 47.18, 5.63 +16.68, -10.00, 53.31, 46.69, 6.62 +15.95, -10.00, 51.28, 48.72, 2.57 +15.29, -10.00, 49.21, 50.79, -1.58 +14.50, -10.00, 54.66, 45.34, 9.31 +13.71, -10.00, 55.16, 44.84, 10.32 +12.99, -10.00, 53.15, 46.85, 6.29 +12.13, -10.00, 58.65, 41.35, 17.30 +11.34, -10.00, 56.69, 43.31, 13.38 +10.55, -10.00, 57.21, 42.79, 14.41 +9.62, -10.00, 62.77, 37.23, 25.54 +8.83, -10.00, 58.35, 41.65, 16.70 +7.98, -10.00, 61.40, 38.60, 22.79 +7.12, -10.00, 61.97, 38.03, 23.95 +6.33, -10.00, 60.03, 39.97, 20.07 +5.41, -10.00, 65.61, 34.39, 31.22 +4.61, -10.00, 61.21, 38.79, 22.41 +3.76, -10.00, 64.27, 35.73, 28.54 +2.97, -10.00, 62.34, 37.66, 24.69 +2.11, -10.00, 65.41, 34.59, 30.82 +1.32, -10.00, 63.49, 36.51, 26.98 +0.53, -10.00, 64.04, 35.96, 28.09 +-0.20, -10.00, 62.08, 37.92, 24.16 +-0.99, -10.00, 65.11, 34.89, 30.22 +-1.78, -10.00, 65.67, 34.33, 31.35 +-2.50, -10.00, 63.72, 36.28, 27.43 +-3.30, -10.00, 66.76, 33.24, 33.51 +-3.96, -10.00, 62.29, 37.71, 24.57 +-4.68, -10.00, 65.28, 34.72, 30.56 +-5.47, -10.00, 68.33, 31.67, 36.66 +-6.20, -10.00, 66.39, 33.61, 32.77 +-6.99, -10.00, 69.44, 30.56, 38.88 +-7.65, -10.00, 64.98, 35.02, 29.96 +-8.37, -10.00, 67.99, 32.01, 35.98 +-9.10, -10.00, 68.53, 31.47, 37.07 +-9.76, -10.00, 66.55, 33.45, 33.11 +-10.48, -10.00, 69.57, 30.43, 39.14 +-11.21, -10.00, 70.12, 29.88, 40.24 +-11.87, -10.00, 68.15, 31.85, 36.30 +-12.59, -10.00, 71.17, 28.83, 42.35 +-13.18, -10.00, 66.69, 33.31, 33.38 +-13.84, -10.00, 69.67, 30.33, 39.34 +-14.44, -10.00, 67.66, 32.34, 35.32 +-15.03, -10.00, 68.12, 31.88, 36.24 +-15.56, -10.00, 66.07, 33.93, 32.13 +-16.22, -10.00, 71.53, 28.47, 43.06 +-16.81, -10.00, 69.53, 30.47, 39.05 +-17.40, -10.00, 70.00, 30.00, 40.00 +-17.93, -10.00, 67.95, 32.05, 35.91 +-18.46, -10.00, 68.38, 31.62, 36.76 +-18.98, -10.00, 68.81, 31.19, 37.62 +-19.51, -10.00, 69.24, 30.76, 38.48 +-19.97, -10.00, 67.15, 32.85, 34.30 +-20.50, -10.00, 70.06, 29.94, 40.12 +-20.96, -10.00, 67.97, 32.03, 35.95 +-21.36, -10.00, 65.84, 34.16, 31.68 +-21.82, -10.00, 68.70, 31.30, 37.41 +-22.28, -10.00, 69.10, 30.90, 38.19 +-22.68, -10.00, 66.97, 33.03, 33.94 +-22.94, -10.00, 62.27, 37.73, 24.54 +-23.40, -10.00, 70.08, 29.92, 40.16 +-23.73, -10.00, 65.44, 34.56, 30.87 +-23.99, -10.00, 63.22, 36.78, 26.43 +-24.39, -10.00, 68.51, 31.49, 37.02 +-24.72, -10.00, 66.34, 33.66, 32.68 +-24.98, -10.00, 64.12, 35.88, 28.24 +-25.31, -10.00, 66.90, 33.10, 33.80 +-25.58, -10.00, 64.68, 35.32, 29.37 +-25.84, -10.00, 64.94, 35.06, 29.88 +-26.10, -10.00, 65.20, 34.80, 30.40 +-26.37, -10.00, 65.46, 34.54, 30.92 +-26.56, -10.00, 63.20, 36.80, 26.39 +-26.83, -10.00, 65.93, 34.07, 31.86 +-27.03, -10.00, 63.67, 36.33, 27.34 +-27.16, -10.00, 61.36, 38.64, 22.72 +-27.36, -10.00, 64.05, 35.95, 28.09 +-27.55, -10.00, 64.26, 35.74, 28.52 +-27.69, -10.00, 61.95, 38.05, 23.91 +-27.82, -10.00, 62.12, 37.88, 24.24 +-27.88, -10.00, 59.76, 40.24, 19.53 +-27.95, -10.00, 59.88, 40.12, 19.76 +-28.15, -10.00, 65.04, 34.96, 30.08 +-28.21, -10.00, 60.21, 39.79, 20.43 +-28.34, -10.00, 62.85, 37.15, 25.71 +-28.41, -10.00, 60.50, 39.50, 21.00 +-28.41, -10.00, 58.10, 41.90, 16.20 +-28.48, -10.00, 60.69, 39.31, 21.38 +-28.48, -10.00, 58.29, 41.71, 16.57 +-28.48, -10.00, 58.35, 41.65, 16.71 +-28.61, -10.00, 63.47, 36.53, 26.93 +-28.61, -10.00, 58.59, 41.41, 17.19 +-28.48, -10.00, 53.62, 46.38, 7.24 +-28.61, -10.00, 63.68, 36.32, 27.35 +-28.48, -10.00, 53.76, 46.24, 7.52 +-28.48, -10.00, 58.77, 41.23, 17.54 +-28.41, -10.00, 56.32, 43.68, 12.64 +-28.41, -10.00, 58.86, 41.14, 17.72 +-28.34, -10.00, 56.41, 43.59, 12.82 +-28.21, -10.00, 53.91, 46.09, 7.81 +-28.15, -10.00, 56.40, 43.60, 12.79 +-28.08, -10.00, 56.41, 43.59, 12.83 +-27.95, -10.00, 53.91, 46.09, 7.82 +-27.95, -10.00, 58.92, 41.08, 17.84 +-27.82, -10.00, 53.95, 46.05, 7.89 +-27.82, -10.00, 58.96, 41.04, 17.91 +-27.62, -10.00, 51.46, 48.54, 2.92 +-27.55, -10.00, 56.42, 43.58, 12.84 +-27.42, -10.00, 53.91, 46.09, 7.83 +-27.29, -10.00, 53.88, 46.12, 7.76 +-27.16, -10.00, 53.85, 46.15, 7.69 +-27.03, -10.00, 53.81, 46.19, 7.62 +-26.83, -10.00, 51.25, 48.75, 2.51 +-26.76, -10.00, 56.21, 43.79, 12.42 +-26.56, -10.00, 51.18, 48.82, 2.36 +-26.50, -10.00, 56.14, 43.86, 12.27 +-26.30, -10.00, 51.11, 48.89, 2.21 +-26.04, -10.00, 48.50, 51.50, -3.01 +-25.97, -10.00, 55.92, 44.08, 11.84 +-25.77, -10.00, 50.89, 49.11, 1.78 +-25.58, -10.00, 50.80, 49.20, 1.60 +-25.44, -10.00, 53.23, 46.77, 6.46 +-25.25, -10.00, 50.67, 49.33, 1.33 +-25.05, -10.00, 50.58, 49.42, 1.15 +-24.92, -10.00, 53.00, 47.00, 6.01 +-24.79, -10.00, 52.96, 47.04, 5.92 +-24.65, -10.00, 52.92, 47.08, 5.83 +-24.46, -10.00, 50.35, 49.65, 0.70 +-24.26, -10.00, 50.26, 49.74, 0.51 +-23.99, -10.00, 47.64, 52.36, -4.72 +-23.93, -10.00, 55.06, 44.94, 10.11 +-23.66, -10.00, 47.50, 52.50, -5.01 +-23.47, -10.00, 49.87, 50.13, -0.26 +-23.40, -10.00, 54.81, 45.19, 9.63 +-23.14, -10.00, 47.25, 52.75, -5.50 +-22.94, -10.00, 49.62, 50.38, -0.76 +-22.87, -10.00, 54.56, 45.44, 9.13 +-22.61, -10.00, 47.00, 53.00, -6.00 +-22.41, -10.00, 49.37, 50.63, -1.26 +-22.28, -10.00, 51.79, 48.21, 3.57 +-22.15, -10.00, 51.73, 48.27, 3.47 +-21.88, -10.00, 46.64, 53.36, -6.73 +-21.82, -10.00, 54.05, 45.95, 8.10 +-21.62, -10.00, 49.00, 51.00, -2.00 +-21.49, -10.00, 51.42, 48.58, 2.83 +-21.29, -10.00, 48.84, 51.16, -2.33 +-21.09, -10.00, 48.73, 51.27, -2.54 +-20.96, -10.00, 51.14, 48.86, 2.29 +-20.76, -10.00, 48.56, 51.44, -2.87 +-20.57, -10.00, 48.46, 51.54, -3.09 +-20.43, -10.00, 50.87, 49.13, 1.74 +-20.24, -10.00, 48.29, 51.71, -3.43 +-20.04, -10.00, 48.18, 51.82, -3.65 +-19.97, -10.00, 53.11, 46.89, 6.22 +-19.78, -10.00, 48.05, 51.95, -3.90 +-19.64, -10.00, 50.46, 49.54, 0.92 +-19.51, -10.00, 50.40, 49.60, 0.80 +-19.38, -10.00, 50.33, 49.67, 0.67 +-19.25, -10.00, 50.27, 49.73, 0.54 +-19.12, -10.00, 50.21, 49.79, 0.41 +-18.92, -10.00, 47.62, 52.38, -4.76 +-18.85, -10.00, 52.55, 47.45, 5.09 +-18.65, -10.00, 47.49, 52.51, -5.03 +-18.59, -10.00, 52.41, 47.59, 4.83 +-18.39, -10.00, 47.35, 52.65, -5.29 +-18.33, -10.00, 52.28, 47.72, 4.56 +-18.13, -10.00, 47.22, 52.78, -5.57 +-18.06, -10.00, 52.14, 47.86, 4.28 +-17.86, -10.00, 47.08, 52.92, -5.84 +-17.80, -10.00, 52.00, 48.00, 4.00 +-17.67, -10.00, 49.46, 50.54, -1.08 +-17.53, -10.00, 49.39, 50.61, -1.22 +-17.40, -10.00, 49.32, 50.68, -1.36 +-17.34, -10.00, 51.77, 48.23, 3.54 +-17.27, -10.00, 51.75, 48.25, 3.49 +-17.07, -10.00, 46.68, 53.32, -6.64 +-17.01, -10.00, 51.60, 48.40, 3.20 +-16.87, -10.00, 49.06, 50.94, -1.89 +-16.81, -10.00, 51.50, 48.50, 3.01 +-16.61, -10.00, 46.44, 53.56, -7.13 +-16.61, -10.00, 53.88, 46.12, 7.75 +-16.48, -10.00, 48.86, 51.14, -2.28 +-16.48, -10.00, 53.83, 46.17, 7.65 +-16.28, -10.00, 46.29, 53.71, -7.43 +-16.28, -10.00, 53.73, 46.27, 7.45 +-16.08, -10.00, 46.18, 53.82, -7.63 +-16.08, -10.00, 53.62, 46.38, 7.25 +-16.02, -10.00, 51.12, 48.88, 2.25 +-15.95, -10.00, 51.10, 48.90, 2.19 +-15.82, -10.00, 48.55, 51.45, -2.90 +-15.75, -10.00, 50.99, 49.01, 1.98 +-15.75, -10.00, 53.49, 46.51, 6.97 +-15.69, -10.00, 50.99, 49.01, 1.97 +-15.56, -10.00, 48.44, 51.56, -3.13 +-15.56, -10.00, 53.40, 46.60, 6.80 +-15.49, -10.00, 50.90, 49.10, 1.80 +-15.42, -10.00, 50.87, 49.13, 1.74 +-15.42, -10.00, 53.36, 46.64, 6.73 +-15.29, -10.00, 48.34, 51.66, -3.32 +-15.29, -10.00, 53.30, 46.70, 6.61 +-15.23, -10.00, 50.80, 49.20, 1.60 +-15.16, -10.00, 50.77, 49.23, 1.54 +-15.16, -10.00, 53.26, 46.74, 6.53 +-15.03, -10.00, 48.24, 51.76, -3.52 +-15.03, -10.00, 53.20, 46.80, 6.40 +-15.03, -10.00, 53.22, 46.78, 6.44 +-14.96, -10.00, 50.72, 49.28, 1.44 +-14.90, -10.00, 50.69, 49.31, 1.37 +-14.90, -10.00, 53.18, 46.82, 6.35 +-14.90, -10.00, 53.20, 46.80, 6.39 +-14.77, -10.00, 48.17, 51.83, -3.66 +-14.77, -10.00, 53.13, 46.87, 6.27 +-14.70, -10.00, 50.63, 49.37, 1.26 +-14.70, -10.00, 53.12, 46.88, 6.24 +-14.70, -10.00, 53.14, 46.86, 6.27 +-14.63, -10.00, 50.63, 49.37, 1.26 +-14.63, -10.00, 53.12, 46.88, 6.24 +-14.63, -10.00, 53.14, 46.86, 6.28 +-14.50, -10.00, 48.11, 51.89, -3.77 +-14.50, -10.00, 53.07, 46.93, 6.15 +-14.44, -10.00, 50.57, 49.43, 1.14 +-14.44, -10.00, 53.06, 46.94, 6.12 +-14.44, -10.00, 53.07, 46.93, 6.15 +-14.37, -10.00, 50.57, 49.43, 1.14 +-14.37, -10.00, 53.06, 46.94, 6.12 +-14.37, -10.00, 53.07, 46.93, 6.15 +-14.37, -10.00, 53.09, 46.91, 6.18 +-14.24, -10.00, 48.06, 51.94, -3.87 +-14.24, -10.00, 53.02, 46.98, 6.05 +-14.24, -10.00, 53.04, 46.96, 6.08 +-14.24, -10.00, 53.06, 46.94, 6.11 +-14.17, -10.00, 50.55, 49.45, 1.10 +-14.17, -10.00, 53.04, 46.96, 6.07 +-14.17, -10.00, 53.05, 46.95, 6.11 +-14.11, -10.00, 50.55, 49.45, 1.09 +-14.11, -10.00, 53.03, 46.97, 6.07 +-14.11, -10.00, 53.05, 46.95, 6.10 +-13.97, -10.00, 48.02, 51.98, -3.96 +-13.97, -10.00, 52.98, 47.02, 5.96 +-13.97, -10.00, 53.00, 47.00, 5.99 +-13.97, -10.00, 53.01, 46.99, 6.02 +-13.97, -10.00, 53.02, 46.98, 6.05 +-13.91, -10.00, 50.52, 49.48, 1.04 +-13.91, -10.00, 53.00, 47.00, 6.01 +-13.91, -10.00, 53.02, 46.98, 6.04 +-13.91, -10.00, 53.03, 46.97, 6.07 +-13.91, -10.00, 53.05, 46.95, 6.10 +-13.84, -10.00, 50.54, 49.46, 1.08 +-13.84, -10.00, 53.03, 46.97, 6.06 +-13.84, -10.00, 53.04, 46.96, 6.09 +-13.84, -10.00, 53.06, 46.94, 6.11 +-13.84, -10.00, 53.07, 46.93, 6.14 +-13.84, -10.00, 53.09, 46.91, 6.17 +-13.71, -10.00, 48.06, 51.94, -3.89 +-13.71, -10.00, 53.01, 46.99, 6.03 +-13.71, -10.00, 53.03, 46.97, 6.06 +-13.71, -10.00, 53.04, 46.96, 6.09 +-13.71, -10.00, 53.06, 46.94, 6.11 +-13.71, -10.00, 53.07, 46.93, 6.14 +-13.71, -10.00, 53.08, 46.92, 6.17 +-13.65, -10.00, 50.58, 49.42, 1.15 +-13.65, -10.00, 53.06, 46.94, 6.12 +-13.65, -10.00, 53.08, 46.92, 6.15 +-13.65, -10.00, 53.09, 46.91, 6.18 +-13.65, -10.00, 53.10, 46.90, 6.21 +-13.58, -10.00, 50.60, 49.40, 1.19 +-13.58, -10.00, 53.08, 46.92, 6.16 +-13.58, -10.00, 53.09, 46.91, 6.19 +-13.58, -10.00, 53.11, 46.89, 6.21 +-13.58, -10.00, 53.12, 46.88, 6.24 +-13.58, -10.00, 53.13, 46.87, 6.27 +-13.45, -10.00, 48.10, 51.90, -3.79 +-13.45, -10.00, 53.06, 46.94, 6.12 +-13.45, -10.00, 53.07, 46.93, 6.15 +-13.45, -10.00, 53.09, 46.91, 6.17 +-13.45, -10.00, 53.10, 46.90, 6.20 +-13.38, -10.00, 50.59, 49.41, 1.18 +-13.38, -10.00, 53.08, 46.92, 6.15 +-13.38, -10.00, 53.09, 46.91, 6.18 +-13.32, -10.00, 50.58, 49.42, 1.16 +-13.32, -10.00, 53.06, 46.94, 6.13 +-13.32, -10.00, 53.08, 46.92, 6.15 +-13.32, -10.00, 53.09, 46.91, 6.18 +-13.18, -10.00, 48.06, 51.94, -3.88 +-13.18, -10.00, 53.01, 46.99, 6.03 +-13.18, -10.00, 53.03, 46.97, 6.05 +-13.12, -10.00, 50.52, 49.48, 1.03 +-13.12, -10.00, 53.00, 47.00, 6.00 +-13.12, -10.00, 53.01, 46.99, 6.02 +-13.05, -10.00, 50.50, 49.50, 1.00 +-13.05, -10.00, 52.98, 47.02, 5.97 +-13.05, -10.00, 53.00, 47.00, 5.99 +-13.05, -10.00, 53.01, 46.99, 6.02 +-13.05, -10.00, 53.02, 46.98, 6.04 +-12.92, -10.00, 47.99, 52.01, -4.02 +-12.92, -10.00, 52.94, 47.06, 5.88 +-12.85, -10.00, 50.43, 49.57, 0.86 +-12.85, -10.00, 52.91, 47.09, 5.83 +-12.85, -10.00, 52.93, 47.07, 5.85 +-12.79, -10.00, 50.41, 49.59, 0.83 +-12.79, -10.00, 52.90, 47.10, 5.79 +-12.66, -10.00, 47.86, 52.14, -4.27 +-12.66, -10.00, 52.82, 47.18, 5.64 +-12.66, -10.00, 52.83, 47.17, 5.65 +-12.59, -10.00, 50.32, 49.68, 0.63 +-12.59, -10.00, 52.80, 47.20, 5.59 +-12.59, -10.00, 52.81, 47.19, 5.61 +-12.52, -10.00, 50.30, 49.70, 0.59 +-12.39, -10.00, 47.73, 52.27, -4.53 +-12.39, -10.00, 52.69, 47.31, 5.37 +-12.39, -10.00, 52.70, 47.30, 5.39 +-12.39, -10.00, 52.70, 47.30, 5.41 +-12.33, -10.00, 50.19, 49.81, 0.38 +-12.33, -10.00, 52.67, 47.33, 5.34 +-12.26, -10.00, 50.16, 49.84, 0.32 +-12.26, -10.00, 52.64, 47.36, 5.28 +-12.13, -10.00, 47.61, 52.39, -4.79 +-12.13, -10.00, 52.56, 47.44, 5.11 +-12.06, -10.00, 50.04, 49.96, 0.09 +-12.06, -10.00, 52.52, 47.48, 5.05 +-12.06, -10.00, 52.53, 47.47, 5.06 +-12.00, -10.00, 50.02, 49.98, 0.03 +-12.00, -10.00, 52.50, 47.50, 4.99 +-12.00, -10.00, 52.50, 47.50, 5.01 +-11.87, -10.00, 47.47, 52.53, -5.06 +-11.87, -10.00, 52.42, 47.58, 4.84 +-11.87, -10.00, 52.43, 47.57, 4.85 +-11.87, -10.00, 52.43, 47.57, 4.87 +-11.80, -10.00, 49.92, 50.08, -0.16 +-11.80, -10.00, 52.40, 47.60, 4.79 +-11.80, -10.00, 52.40, 47.60, 4.81 +-11.73, -10.00, 49.89, 50.11, -0.22 +-11.73, -10.00, 52.37, 47.63, 4.73 +-11.73, -10.00, 52.37, 47.63, 4.75 +-11.73, -10.00, 52.38, 47.62, 4.76 +-11.73, -10.00, 52.39, 47.61, 4.77 +-11.73, -10.00, 52.39, 47.61, 4.79 +-11.60, -10.00, 47.36, 52.64, -5.29 +-11.60, -10.00, 52.31, 47.69, 4.61 +-11.60, -10.00, 52.31, 47.69, 4.62 +-11.60, -10.00, 52.32, 47.68, 4.64 +-11.60, -10.00, 52.32, 47.68, 4.65 +-11.60, -10.00, 52.33, 47.67, 4.66 +-11.54, -10.00, 49.81, 50.19, -0.37 +-11.54, -10.00, 52.29, 47.71, 4.58 +-11.54, -10.00, 52.30, 47.70, 4.60 +-11.54, -10.00, 52.30, 47.70, 4.61 +-11.54, -10.00, 52.31, 47.69, 4.62 +-11.54, -10.00, 52.32, 47.68, 4.63 +-11.54, -10.00, 52.32, 47.68, 4.64 +-11.54, -10.00, 52.33, 47.67, 4.65 +-11.54, -10.00, 52.33, 47.67, 4.67 +-11.54, -10.00, 52.34, 47.66, 4.68 +-11.54, -10.00, 52.34, 47.66, 4.69 +-11.54, -10.00, 52.35, 47.65, 4.70 +-11.54, -10.00, 52.36, 47.64, 4.71 +-11.54, -10.00, 52.36, 47.64, 4.72 +-11.60, -10.00, 54.89, 45.11, 9.78 +-11.60, -10.00, 52.42, 47.58, 4.85 +-11.60, -10.00, 52.43, 47.57, 4.86 +-11.60, -10.00, 52.43, 47.57, 4.87 +-11.60, -10.00, 52.44, 47.56, 4.88 +-11.60, -10.00, 52.45, 47.55, 4.89 +-11.60, -10.00, 52.45, 47.55, 4.91 +-11.60, -10.00, 52.46, 47.54, 4.92 +-11.60, -10.00, 52.46, 47.54, 4.93 +-11.60, -10.00, 52.47, 47.53, 4.94 +-11.73, -10.00, 57.52, 42.48, 15.04 +-11.73, -10.00, 52.58, 47.42, 5.17 +-11.73, -10.00, 52.59, 47.41, 5.18 +-11.73, -10.00, 52.60, 47.40, 5.19 +-11.73, -10.00, 52.60, 47.40, 5.20 +-11.73, -10.00, 52.61, 47.39, 5.22 +-11.73, -10.00, 52.62, 47.38, 5.23 +-11.73, -10.00, 52.62, 47.38, 5.24 +-11.73, -10.00, 52.63, 47.37, 5.26 +-11.73, -10.00, 52.63, 47.37, 5.27 +-11.73, -10.00, 52.64, 47.36, 5.28 +-11.73, -10.00, 52.65, 47.35, 5.30 +-11.73, -10.00, 52.65, 47.35, 5.31 +-11.73, -10.00, 52.66, 47.34, 5.32 +-11.73, -10.00, 52.67, 47.33, 5.33 +-11.73, -10.00, 52.67, 47.33, 5.35 +-11.73, -10.00, 52.68, 47.32, 5.36 +-11.73, -10.00, 52.69, 47.31, 5.37 +-11.73, -10.00, 52.69, 47.31, 5.39 +-11.73, -10.00, 52.70, 47.30, 5.40 +-11.80, -10.00, 55.23, 44.77, 10.46 +-11.73, -10.00, 50.24, 49.76, 0.48 +-11.80, -10.00, 55.24, 44.76, 10.48 +-11.80, -10.00, 52.78, 47.22, 5.55 +-11.80, -10.00, 52.78, 47.22, 5.57 +-11.80, -10.00, 52.79, 47.21, 5.58 +-11.80, -10.00, 52.80, 47.20, 5.59 +-11.80, -10.00, 52.80, 47.20, 5.61 +-11.80, -10.00, 52.81, 47.19, 5.62 +-11.80, -10.00, 52.82, 47.18, 5.63 +-11.80, -10.00, 52.82, 47.18, 5.65 +-11.80, -10.00, 52.83, 47.17, 5.66 +-11.80, -10.00, 52.84, 47.16, 5.67 +-11.80, -10.00, 52.84, 47.16, 5.69 +-11.87, -10.00, 55.37, 44.63, 10.74 +-11.87, -10.00, 52.91, 47.09, 5.81 +-11.87, -10.00, 52.91, 47.09, 5.83 +-11.87, -10.00, 52.92, 47.08, 5.84 +-11.87, -10.00, 52.93, 47.07, 5.86 +-11.87, -10.00, 52.93, 47.07, 5.87 +-11.87, -10.00, 52.94, 47.06, 5.88 +-11.87, -10.00, 52.95, 47.05, 5.90 +-11.87, -10.00, 52.96, 47.04, 5.91 +-11.87, -10.00, 52.96, 47.04, 5.93 +-11.87, -10.00, 52.97, 47.03, 5.94 +-11.87, -10.00, 52.98, 47.02, 5.95 +-11.87, -10.00, 52.98, 47.02, 5.97 +-11.87, -10.00, 52.99, 47.01, 5.98 +-11.87, -10.00, 53.00, 47.00, 6.00 +-11.87, -10.00, 53.00, 47.00, 6.01 +-11.87, -10.00, 53.01, 46.99, 6.02 +-11.87, -10.00, 53.02, 46.98, 6.04 +-11.87, -10.00, 53.03, 46.97, 6.05 +-11.87, -10.00, 53.03, 46.97, 6.07 +-11.87, -10.00, 53.04, 46.96, 6.08 +-11.87, -10.00, 53.05, 46.95, 6.09 +-11.87, -10.00, 53.05, 46.95, 6.11 +-11.87, -10.00, 53.06, 46.94, 6.12 +-11.87, -10.00, 53.07, 46.93, 6.14 +-11.87, -10.00, 53.07, 46.93, 6.15 +-11.87, -10.00, 53.08, 46.92, 6.16 +-11.87, -10.00, 53.09, 46.91, 6.18 +-11.87, -10.00, 53.10, 46.90, 6.19 +-11.87, -10.00, 53.10, 46.90, 6.21 +-11.87, -10.00, 53.11, 46.89, 6.22 +-11.87, -10.00, 53.12, 46.88, 6.23 +-11.87, -10.00, 53.12, 46.88, 6.25 +-11.87, -10.00, 53.13, 46.87, 6.26 +-11.87, -10.00, 53.14, 46.86, 6.28 +-11.87, -10.00, 53.14, 46.86, 6.29 +-11.87, -10.00, 53.15, 46.85, 6.30 +-11.87, -10.00, 53.16, 46.84, 6.32 +-11.87, -10.00, 53.17, 46.83, 6.33 +-11.87, -10.00, 53.17, 46.83, 6.35 +-11.80, -10.00, 50.66, 49.34, 1.32 +-11.87, -10.00, 55.66, 44.34, 11.32 +-11.80, -10.00, 50.67, 49.33, 1.34 +-11.80, -10.00, 53.15, 46.85, 6.30 +-11.80, -10.00, 53.16, 46.84, 6.31 +-11.80, -10.00, 53.16, 46.84, 6.33 +-11.80, -10.00, 53.17, 46.83, 6.34 +-11.73, -10.00, 50.66, 49.34, 1.31 +-11.73, -10.00, 53.13, 46.87, 6.27 +-11.73, -10.00, 53.14, 46.86, 6.28 +-11.73, -10.00, 53.15, 46.85, 6.29 +-11.73, -10.00, 53.15, 46.85, 6.31 +-11.73, -10.00, 53.16, 46.84, 6.32 +-11.73, -10.00, 53.17, 46.83, 6.33 +-11.73, -10.00, 53.17, 46.83, 6.35 +-11.73, -10.00, 53.18, 46.82, 6.36 +-11.60, -10.00, 48.14, 51.86, -3.71 +-11.60, -10.00, 53.09, 46.91, 6.19 +-11.60, -10.00, 53.10, 46.90, 6.20 +-11.54, -10.00, 50.58, 49.42, 1.17 +-11.54, -10.00, 53.06, 46.94, 6.12 +-11.54, -10.00, 53.07, 46.93, 6.13 +-11.54, -10.00, 53.07, 46.93, 6.15 +-11.47, -10.00, 50.56, 49.44, 1.11 +-11.47, -10.00, 53.03, 46.97, 6.07 +-11.47, -10.00, 53.04, 46.96, 6.08 +-11.34, -10.00, 48.00, 52.00, -4.00 +-11.34, -10.00, 52.95, 47.05, 5.90 +-11.27, -10.00, 50.43, 49.57, 0.87 +-11.27, -10.00, 52.91, 47.09, 5.82 +-11.27, -10.00, 52.92, 47.08, 5.83 +-11.21, -10.00, 50.40, 49.60, 0.80 +-11.21, -10.00, 52.88, 47.12, 5.75 +-11.21, -10.00, 52.88, 47.12, 5.76 +-11.07, -10.00, 47.84, 52.16, -4.32 +-11.07, -10.00, 52.79, 47.21, 5.58 +-11.07, -10.00, 52.79, 47.21, 5.59 +-11.01, -10.00, 50.28, 49.72, 0.55 +-11.01, -10.00, 52.75, 47.25, 5.50 +-10.94, -10.00, 50.23, 49.77, 0.47 +-10.81, -10.00, 47.67, 52.33, -4.67 +-10.81, -10.00, 52.61, 47.39, 5.22 +-10.81, -10.00, 52.62, 47.38, 5.23 +-10.74, -10.00, 50.10, 49.90, 0.19 +-10.68, -10.00, 50.05, 49.95, 0.10 +-10.68, -10.00, 52.52, 47.48, 5.05 +-10.55, -10.00, 47.48, 52.52, -5.03 +-10.55, -10.00, 52.43, 47.57, 4.86 +-10.55, -10.00, 52.43, 47.57, 4.86 +-10.48, -10.00, 49.91, 50.09, -0.18 +-10.48, -10.00, 52.39, 47.61, 4.77 +-10.42, -10.00, 49.87, 50.13, -0.27 +-10.42, -10.00, 52.34, 47.66, 4.68 +-10.28, -10.00, 47.30, 52.70, -5.40 +-10.28, -10.00, 52.24, 47.76, 4.49 +-10.22, -10.00, 49.72, 50.28, -0.56 +-10.22, -10.00, 52.20, 47.80, 4.39 +-10.15, -10.00, 49.67, 50.33, -0.65 +-10.15, -10.00, 52.15, 47.85, 4.29 +-10.02, -10.00, 47.10, 52.90, -5.79 +-10.02, -10.00, 52.05, 47.95, 4.10 +-10.02, -10.00, 52.05, 47.95, 4.10 +-9.95, -10.00, 49.53, 50.47, -0.95 +-9.89, -10.00, 49.48, 50.52, -1.05 +-9.89, -10.00, 51.95, 48.05, 3.90 +-9.89, -10.00, 51.95, 48.05, 3.90 +-9.76, -10.00, 46.90, 53.10, -6.19 +-9.76, -10.00, 51.85, 48.15, 3.69 +-9.76, -10.00, 51.85, 48.15, 3.69 +-9.76, -10.00, 51.85, 48.15, 3.69 +-9.69, -10.00, 49.32, 50.68, -1.35 +-9.69, -10.00, 51.79, 48.21, 3.59 +-9.69, -10.00, 51.79, 48.21, 3.58 +-9.62, -10.00, 49.27, 50.73, -1.46 +-9.62, -10.00, 51.74, 48.26, 3.48 +-9.62, -10.00, 51.74, 48.26, 3.48 +-9.62, -10.00, 51.74, 48.26, 3.47 +-9.49, -10.00, 46.69, 53.31, -6.61 +-9.49, -10.00, 51.63, 48.37, 3.27 +-9.49, -10.00, 51.63, 48.37, 3.27 +-9.49, -10.00, 51.63, 48.37, 3.26 +-9.49, -10.00, 51.63, 48.37, 3.26 +-9.49, -10.00, 51.63, 48.37, 3.25 +-9.43, -10.00, 49.10, 50.90, -1.79 +-9.43, -10.00, 51.57, 48.43, 3.15 +-9.43, -10.00, 51.57, 48.43, 3.14 +-9.43, -10.00, 51.57, 48.43, 3.14 +-9.43, -10.00, 51.57, 48.43, 3.13 +-9.43, -10.00, 51.56, 48.44, 3.13 +-9.43, -10.00, 51.56, 48.44, 3.12 +-9.43, -10.00, 51.56, 48.44, 3.12 +-9.43, -10.00, 51.56, 48.44, 3.12 +-9.43, -10.00, 51.56, 48.44, 3.11 +-9.43, -10.00, 51.55, 48.45, 3.11 +-9.43, -10.00, 51.55, 48.45, 3.10 +-9.43, -10.00, 51.55, 48.45, 3.10 +-9.43, -10.00, 51.55, 48.45, 3.09 +-9.49, -10.00, 54.07, 45.93, 8.13 +-9.49, -10.00, 51.59, 48.41, 3.19 +-9.49, -10.00, 51.59, 48.41, 3.18 +-9.49, -10.00, 51.59, 48.41, 3.18 +-9.49, -10.00, 51.59, 48.41, 3.17 +-9.62, -10.00, 56.63, 43.37, 13.26 +-9.62, -10.00, 51.68, 48.32, 3.37 +-9.62, -10.00, 51.68, 48.32, 3.36 +-9.62, -10.00, 51.68, 48.32, 3.36 +-9.69, -10.00, 54.20, 45.80, 8.40 +-9.69, -10.00, 51.73, 48.27, 3.46 +-9.69, -10.00, 51.73, 48.27, 3.45 +-9.69, -10.00, 51.73, 48.27, 3.45 +-9.76, -10.00, 54.25, 45.75, 8.49 +-9.76, -10.00, 51.77, 48.23, 3.55 +-9.76, -10.00, 51.77, 48.23, 3.54 +-9.76, -10.00, 51.77, 48.23, 3.54 +-9.89, -10.00, 56.81, 43.19, 13.63 +-9.89, -10.00, 51.87, 48.13, 3.74 +-9.89, -10.00, 51.87, 48.13, 3.74 +-9.89, -10.00, 51.87, 48.13, 3.74 +-9.95, -10.00, 54.39, 45.61, 8.78 +-10.02, -10.00, 54.44, 45.56, 8.88 +-10.02, -10.00, 51.97, 48.03, 3.93 +-10.02, -10.00, 51.97, 48.03, 3.93 +-10.02, -10.00, 51.97, 48.03, 3.93 +-10.02, -10.00, 51.97, 48.03, 3.93 +-10.15, -10.00, 57.01, 42.99, 14.02 +-10.15, -10.00, 52.07, 47.93, 4.13 +-10.15, -10.00, 52.07, 47.93, 4.14 +-10.22, -10.00, 54.59, 45.41, 9.18 +-10.22, -10.00, 52.12, 47.88, 4.24 +-10.22, -10.00, 52.12, 47.88, 4.24 +-10.22, -10.00, 52.12, 47.88, 4.24 +-10.28, -10.00, 54.64, 45.36, 9.29 +-10.28, -10.00, 52.17, 47.83, 4.34 +-10.28, -10.00, 52.17, 47.83, 4.35 +-10.28, -10.00, 52.17, 47.83, 4.35 +-10.42, -10.00, 57.22, 42.78, 14.44 +-10.42, -10.00, 52.28, 47.72, 4.55 +-10.42, -10.00, 52.28, 47.72, 4.56 +-10.42, -10.00, 52.28, 47.72, 4.56 +-10.48, -10.00, 54.80, 45.20, 9.61 +-10.48, -10.00, 52.33, 47.67, 4.66 +-10.48, -10.00, 52.33, 47.67, 4.67 +-10.48, -10.00, 52.34, 47.66, 4.67 +-10.48, -10.00, 52.34, 47.66, 4.68 +-10.48, -10.00, 52.34, 47.66, 4.68 +-10.48, -10.00, 52.34, 47.66, 4.68 +-10.55, -10.00, 54.86, 45.14, 9.73 +-10.55, -10.00, 52.40, 47.60, 4.79 +-10.55, -10.00, 52.40, 47.60, 4.79 +-10.55, -10.00, 52.40, 47.60, 4.80 +-10.55, -10.00, 52.40, 47.60, 4.80 +-10.55, -10.00, 52.40, 47.60, 4.81 +-10.55, -10.00, 52.41, 47.59, 4.81 +-10.68, -10.00, 57.45, 42.55, 14.90 +-10.68, -10.00, 52.51, 47.49, 5.02 +-10.68, -10.00, 52.51, 47.49, 5.02 +-10.68, -10.00, 52.51, 47.49, 5.03 +-10.68, -10.00, 52.52, 47.48, 5.03 +-10.68, -10.00, 52.52, 47.48, 5.04 +-10.68, -10.00, 52.52, 47.48, 5.04 +-10.68, -10.00, 52.52, 47.48, 5.05 +-10.68, -10.00, 52.53, 47.47, 5.05 +-10.68, -10.00, 52.53, 47.47, 5.06 +-10.68, -10.00, 52.53, 47.47, 5.06 +-10.68, -10.00, 52.53, 47.47, 5.07 +-10.74, -10.00, 55.06, 44.94, 10.12 +-10.74, -10.00, 52.59, 47.41, 5.18 +-10.74, -10.00, 52.59, 47.41, 5.19 +-10.74, -10.00, 52.60, 47.40, 5.19 +-10.74, -10.00, 52.60, 47.40, 5.20 +-10.74, -10.00, 52.60, 47.40, 5.20 +-10.74, -10.00, 52.60, 47.40, 5.21 +-10.74, -10.00, 52.61, 47.39, 5.21 +-10.74, -10.00, 52.61, 47.39, 5.22 +-10.74, -10.00, 52.61, 47.39, 5.22 +-10.74, -10.00, 52.61, 47.39, 5.23 +-10.74, -10.00, 52.62, 47.38, 5.24 +-10.74, -10.00, 52.62, 47.38, 5.24 +-10.74, -10.00, 52.62, 47.38, 5.25 +-10.74, -10.00, 52.63, 47.37, 5.25 +-10.74, -10.00, 52.63, 47.37, 5.26 +-10.74, -10.00, 52.63, 47.37, 5.26 +-10.74, -10.00, 52.63, 47.37, 5.27 +-10.74, -10.00, 52.64, 47.36, 5.27 +-10.81, -10.00, 55.16, 44.84, 10.32 +-10.74, -10.00, 50.17, 49.83, 0.34 +-10.81, -10.00, 55.17, 44.83, 10.33 +-10.81, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 50.18, 49.82, 0.36 +-10.74, -10.00, 52.65, 47.35, 5.31 +-10.81, -10.00, 55.18, 44.82, 10.36 +-10.81, -10.00, 52.71, 47.29, 5.42 +-10.81, -10.00, 52.71, 47.29, 5.43 +-10.81, -10.00, 52.72, 47.28, 5.43 +-10.81, -10.00, 52.72, 47.28, 5.44 +-10.81, -10.00, 52.72, 47.28, 5.44 +-10.81, -10.00, 52.73, 47.27, 5.45 +-10.81, -10.00, 52.73, 47.27, 5.46 +-10.74, -10.00, 50.21, 49.79, 0.42 +-10.74, -10.00, 52.68, 47.32, 5.37 +-10.74, -10.00, 52.69, 47.31, 5.37 +-10.74, -10.00, 52.69, 47.31, 5.38 +-10.74, -10.00, 52.69, 47.31, 5.39 +-10.74, -10.00, 52.70, 47.30, 5.39 +-10.74, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 52.70, 47.30, 5.41 +-10.74, -10.00, 52.71, 47.29, 5.41 +-10.74, -10.00, 52.71, 47.29, 5.42 +-10.74, -10.00, 52.71, 47.29, 5.43 +-10.74, -10.00, 52.72, 47.28, 5.43 +-10.74, -10.00, 52.72, 47.28, 5.44 +-10.74, -10.00, 52.72, 47.28, 5.44 +-10.68, -10.00, 50.20, 49.80, 0.40 +-10.74, -10.00, 55.20, 44.80, 10.40 +-10.68, -10.00, 50.21, 49.79, 0.41 +-10.68, -10.00, 52.68, 47.32, 5.36 +-10.68, -10.00, 52.68, 47.32, 5.37 +-10.68, -10.00, 52.69, 47.31, 5.37 +-10.68, -10.00, 52.69, 47.31, 5.38 +-10.68, -10.00, 52.69, 47.31, 5.38 +-10.68, -10.00, 52.69, 47.31, 5.39 +-10.68, -10.00, 52.70, 47.30, 5.39 +-10.68, -10.00, 52.70, 47.30, 5.40 +-10.68, -10.00, 52.70, 47.30, 5.40 +-10.68, -10.00, 52.70, 47.30, 5.41 +-10.55, -10.00, 47.66, 52.34, -4.67 +-10.55, -10.00, 52.61, 47.39, 5.22 +-10.55, -10.00, 52.61, 47.39, 5.22 +-10.55, -10.00, 52.61, 47.39, 5.23 +-10.55, -10.00, 52.62, 47.38, 5.23 +-10.55, -10.00, 52.62, 47.38, 5.24 +-10.55, -10.00, 52.62, 47.38, 5.24 +-10.55, -10.00, 52.62, 47.38, 5.24 +-10.55, -10.00, 52.62, 47.38, 5.25 +-10.55, -10.00, 52.63, 47.37, 5.25 +-10.55, -10.00, 52.63, 47.37, 5.26 +-10.55, -10.00, 52.63, 47.37, 5.26 +-10.48, -10.00, 50.11, 49.89, 0.22 +-10.48, -10.00, 52.58, 47.42, 5.17 +-10.48, -10.00, 52.59, 47.41, 5.17 +-10.48, -10.00, 52.59, 47.41, 5.18 +-10.48, -10.00, 52.59, 47.41, 5.18 +-10.42, -10.00, 50.07, 49.93, 0.14 +-10.42, -10.00, 52.54, 47.46, 5.09 +-10.42, -10.00, 52.55, 47.45, 5.09 +-10.42, -10.00, 52.55, 47.45, 5.09 +-10.42, -10.00, 52.55, 47.45, 5.10 +-10.42, -10.00, 52.55, 47.45, 5.10 +-10.28, -10.00, 47.51, 52.49, -4.98 +-10.28, -10.00, 52.45, 47.55, 4.91 +-10.28, -10.00, 52.45, 47.55, 4.91 +-10.28, -10.00, 52.46, 47.54, 4.91 +-10.28, -10.00, 52.46, 47.54, 4.91 +-10.22, -10.00, 49.94, 50.06, -0.13 +-10.22, -10.00, 52.41, 47.59, 4.82 +-10.22, -10.00, 52.41, 47.59, 4.82 +-10.22, -10.00, 52.41, 47.59, 4.82 +-10.15, -10.00, 49.89, 50.11, -0.22 +-10.15, -10.00, 52.36, 47.64, 4.72 +-10.15, -10.00, 52.36, 47.64, 4.73 +-10.15, -10.00, 52.36, 47.64, 4.73 +-10.15, -10.00, 52.36, 47.64, 4.73 +-10.02, -10.00, 47.32, 52.68, -5.36 +-10.02, -10.00, 52.26, 47.74, 4.53 +-10.02, -10.00, 52.26, 47.74, 4.53 +-10.02, -10.00, 52.27, 47.73, 4.53 +-10.02, -10.00, 52.27, 47.73, 4.53 +-9.95, -10.00, 49.74, 50.26, -0.51 +-9.95, -10.00, 52.22, 47.78, 4.43 +-9.95, -10.00, 52.22, 47.78, 4.43 +-9.89, -10.00, 49.69, 50.31, -0.61 +-9.89, -10.00, 52.16, 47.84, 4.33 +-9.89, -10.00, 52.16, 47.84, 4.33 +-9.76, -10.00, 47.12, 52.88, -5.76 +-9.76, -10.00, 52.06, 47.94, 4.13 +-9.76, -10.00, 52.06, 47.94, 4.13 +-9.76, -10.00, 52.06, 47.94, 4.12 +-9.69, -10.00, 49.54, 50.46, -0.92 +-9.69, -10.00, 52.01, 47.99, 4.02 +-9.69, -10.00, 52.01, 47.99, 4.02 +-9.69, -10.00, 52.01, 47.99, 4.02 +-9.62, -10.00, 49.49, 50.51, -1.03 +-9.62, -10.00, 51.96, 48.04, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.91 +-9.49, -10.00, 46.91, 53.09, -6.18 +-9.49, -10.00, 51.85, 48.15, 3.70 +-9.49, -10.00, 51.85, 48.15, 3.70 +-9.49, -10.00, 51.85, 48.15, 3.69 +-9.49, -10.00, 51.84, 48.16, 3.69 +-9.43, -10.00, 49.32, 50.68, -1.36 +-9.43, -10.00, 51.79, 48.21, 3.58 +-9.43, -10.00, 51.79, 48.21, 3.58 +-9.43, -10.00, 51.79, 48.21, 3.57 +-9.36, -10.00, 49.26, 50.74, -1.47 +-9.36, -10.00, 51.73, 48.27, 3.46 +-9.36, -10.00, 51.73, 48.27, 3.46 +-9.36, -10.00, 51.73, 48.27, 3.45 +-9.36, -10.00, 51.72, 48.28, 3.45 +-9.36, -10.00, 51.72, 48.28, 3.44 +-9.36, -10.00, 51.72, 48.28, 3.44 +-9.36, -10.00, 51.72, 48.28, 3.44 +-9.36, -10.00, 51.72, 48.28, 3.43 +-9.36, -10.00, 51.71, 48.29, 3.43 +-9.36, -10.00, 51.71, 48.29, 3.42 +-9.36, -10.00, 51.71, 48.29, 3.42 +-9.36, -10.00, 51.71, 48.29, 3.41 +-9.36, -10.00, 51.70, 48.30, 3.41 +-9.36, -10.00, 51.70, 48.30, 3.40 +-9.36, -10.00, 51.70, 48.30, 3.40 +-9.36, -10.00, 51.70, 48.30, 3.39 +-9.36, -10.00, 51.69, 48.31, 3.39 +-9.36, -10.00, 51.69, 48.31, 3.38 +-9.36, -10.00, 51.69, 48.31, 3.38 +-9.36, -10.00, 51.69, 48.31, 3.37 +-9.36, -10.00, 51.68, 48.32, 3.37 +-9.36, -10.00, 51.68, 48.32, 3.36 +-9.43, -10.00, 54.20, 45.80, 8.40 +-9.43, -10.00, 51.73, 48.27, 3.45 +-9.43, -10.00, 51.72, 48.28, 3.45 +-9.43, -10.00, 51.72, 48.28, 3.45 +-9.43, -10.00, 51.72, 48.28, 3.44 +-9.43, -10.00, 51.72, 48.28, 3.44 +-9.43, -10.00, 51.72, 48.28, 3.43 +-9.43, -10.00, 51.71, 48.29, 3.43 +-9.43, -10.00, 51.71, 48.29, 3.42 +-9.43, -10.00, 51.71, 48.29, 3.42 +-9.36, -10.00, 49.19, 50.81, -1.63 +-9.36, -10.00, 51.66, 48.34, 3.31 +-9.36, -10.00, 51.65, 48.35, 3.31 +-9.36, -10.00, 51.65, 48.35, 3.30 +-9.36, -10.00, 51.65, 48.35, 3.30 +-9.36, -10.00, 51.65, 48.35, 3.29 +-9.36, -10.00, 51.64, 48.36, 3.29 +-9.23, -10.00, 46.60, 53.40, -6.80 +-9.36, -10.00, 56.58, 43.42, 13.16 +-9.23, -10.00, 46.59, 53.41, -6.82 +-9.23, -10.00, 51.53, 48.47, 3.07 +-9.23, -10.00, 51.53, 48.47, 3.06 +-9.23, -10.00, 51.53, 48.47, 3.06 +-9.23, -10.00, 51.52, 48.48, 3.05 +-9.23, -10.00, 51.52, 48.48, 3.04 +-9.23, -10.00, 51.52, 48.48, 3.04 +-9.23, -10.00, 51.52, 48.48, 3.03 +-9.16, -10.00, 48.99, 51.01, -2.02 +-9.16, -10.00, 51.46, 48.54, 2.92 +-9.16, -10.00, 51.46, 48.54, 2.91 +-9.10, -10.00, 48.93, 51.07, -2.14 +-9.10, -10.00, 51.40, 48.60, 2.80 +-9.10, -10.00, 51.40, 48.60, 2.80 +-9.10, -10.00, 51.39, 48.61, 2.79 +-9.10, -10.00, 51.39, 48.61, 2.78 +-9.10, -10.00, 51.39, 48.61, 2.77 +-8.96, -10.00, 46.34, 53.66, -7.32 +-8.96, -10.00, 51.28, 48.72, 2.56 +-8.96, -10.00, 51.28, 48.72, 2.55 +-8.96, -10.00, 51.27, 48.73, 2.55 +-8.96, -10.00, 51.27, 48.73, 2.54 +-8.90, -10.00, 48.74, 51.26, -2.51 +-8.90, -10.00, 51.21, 48.79, 2.42 +-8.90, -10.00, 51.21, 48.79, 2.41 +-8.90, -10.00, 51.20, 48.80, 2.41 +-8.83, -10.00, 48.68, 51.32, -2.65 +-8.83, -10.00, 51.15, 48.85, 2.29 +-8.83, -10.00, 51.14, 48.86, 2.28 +-8.70, -10.00, 46.09, 53.91, -7.81 +-8.70, -10.00, 51.03, 48.97, 2.06 +-8.70, -10.00, 51.03, 48.97, 2.05 +-8.70, -10.00, 51.02, 48.98, 2.04 +-8.70, -10.00, 51.02, 48.98, 2.03 +-8.70, -10.00, 51.01, 48.99, 2.03 +-8.70, -10.00, 51.01, 48.99, 2.02 +-8.70, -10.00, 51.00, 49.00, 2.01 +-8.70, -10.00, 51.00, 49.00, 2.00 +-8.64, -10.00, 48.47, 51.53, -3.06 +-8.70, -10.00, 53.46, 46.54, 6.92 +-8.64, -10.00, 48.46, 51.54, -3.08 +-8.70, -10.00, 53.45, 46.55, 6.90 +-8.64, -10.00, 48.45, 51.55, -3.10 +-8.64, -10.00, 50.92, 49.08, 1.84 +-8.64, -10.00, 50.91, 49.09, 1.83 +-8.64, -10.00, 50.91, 49.09, 1.82 +-8.64, -10.00, 50.90, 49.10, 1.81 +-8.64, -10.00, 50.90, 49.10, 1.80 +-8.64, -10.00, 50.89, 49.11, 1.79 +-8.64, -10.00, 50.89, 49.11, 1.78 +-8.64, -10.00, 50.88, 49.12, 1.76 +-8.64, -10.00, 50.88, 49.12, 1.75 +-8.64, -10.00, 50.87, 49.13, 1.74 +-8.64, -10.00, 50.87, 49.13, 1.73 +-8.64, -10.00, 50.86, 49.14, 1.72 +-8.70, -10.00, 53.38, 46.62, 6.76 +-8.70, -10.00, 50.90, 49.10, 1.80 +-8.70, -10.00, 50.90, 49.10, 1.79 +-8.70, -10.00, 50.89, 49.11, 1.78 +-8.70, -10.00, 50.89, 49.11, 1.77 +-8.70, -10.00, 50.88, 49.12, 1.76 +-8.70, -10.00, 50.88, 49.12, 1.75 +-8.70, -10.00, 50.87, 49.13, 1.74 +-8.70, -10.00, 50.87, 49.13, 1.74 +-8.83, -10.00, 55.91, 44.09, 11.81 +-8.83, -10.00, 50.96, 49.04, 1.92 +-8.83, -10.00, 50.95, 49.05, 1.91 +-8.83, -10.00, 50.95, 49.05, 1.90 +-8.83, -10.00, 50.94, 49.06, 1.89 +-8.83, -10.00, 50.94, 49.06, 1.88 +-8.83, -10.00, 50.94, 49.06, 1.87 +-8.83, -10.00, 50.93, 49.07, 1.86 +-8.83, -10.00, 50.93, 49.07, 1.85 +-8.90, -10.00, 53.44, 46.56, 6.89 +-8.90, -10.00, 50.97, 49.03, 1.94 +-8.90, -10.00, 50.96, 49.04, 1.93 +-8.90, -10.00, 50.96, 49.04, 1.92 +-8.90, -10.00, 50.96, 49.04, 1.91 +-8.90, -10.00, 50.95, 49.05, 1.90 +-8.90, -10.00, 50.95, 49.05, 1.90 +-8.96, -10.00, 53.47, 46.53, 6.93 +-8.96, -10.00, 50.99, 49.01, 1.98 +-8.96, -10.00, 50.99, 49.01, 1.97 +-8.96, -10.00, 50.98, 49.02, 1.96 +-8.96, -10.00, 50.98, 49.02, 1.96 +-9.10, -10.00, 56.02, 43.98, 12.03 +-9.10, -10.00, 51.07, 48.93, 2.14 +-9.10, -10.00, 51.07, 48.93, 2.13 +-9.16, -10.00, 53.58, 46.42, 7.17 +-9.16, -10.00, 51.11, 48.89, 2.22 +-9.16, -10.00, 51.11, 48.89, 2.21 +-9.23, -10.00, 53.62, 46.38, 7.25 +-9.23, -10.00, 51.15, 48.85, 2.30 +-9.23, -10.00, 51.15, 48.85, 2.29 +-9.36, -10.00, 56.19, 43.81, 12.37 +-9.36, -10.00, 51.24, 48.76, 2.48 +-9.43, -10.00, 53.76, 46.24, 7.52 +-9.43, -10.00, 51.29, 48.71, 2.57 +-9.49, -10.00, 53.81, 46.19, 7.61 +-9.49, -10.00, 51.33, 48.67, 2.66 +-9.62, -10.00, 56.37, 43.63, 12.75 +-9.62, -10.00, 51.43, 48.57, 2.86 +-9.69, -10.00, 53.95, 46.05, 7.90 +-9.69, -10.00, 51.48, 48.52, 2.95 +-9.76, -10.00, 54.00, 46.00, 7.99 +-9.76, -10.00, 51.52, 48.48, 3.05 +-9.89, -10.00, 56.57, 43.43, 13.13 +-9.89, -10.00, 51.62, 48.38, 3.24 +-9.95, -10.00, 54.14, 45.86, 8.28 +-10.02, -10.00, 54.19, 45.81, 8.38 +-10.02, -10.00, 51.72, 48.28, 3.44 +-10.02, -10.00, 51.72, 48.28, 3.44 +-10.15, -10.00, 56.76, 43.24, 13.53 +-10.15, -10.00, 51.82, 48.18, 3.64 +-10.22, -10.00, 54.34, 45.66, 8.68 +-10.22, -10.00, 51.87, 48.13, 3.74 +-10.28, -10.00, 54.39, 45.61, 8.79 +-10.28, -10.00, 51.92, 48.08, 3.84 +-10.42, -10.00, 56.97, 43.03, 13.93 +-10.42, -10.00, 52.02, 47.98, 4.05 +-10.48, -10.00, 54.55, 45.45, 9.10 +-10.48, -10.00, 52.08, 47.92, 4.15 +-10.48, -10.00, 52.08, 47.92, 4.16 +-10.55, -10.00, 54.60, 45.40, 9.21 +-10.55, -10.00, 52.13, 47.87, 4.27 +-10.55, -10.00, 52.13, 47.87, 4.27 +-10.55, -10.00, 52.14, 47.86, 4.27 +-10.68, -10.00, 57.18, 42.82, 14.36 +-10.68, -10.00, 52.24, 47.76, 4.48 +-10.68, -10.00, 52.24, 47.76, 4.49 +-10.68, -10.00, 52.25, 47.75, 4.49 +-10.68, -10.00, 52.25, 47.75, 4.50 +-10.68, -10.00, 52.25, 47.75, 4.50 +-10.68, -10.00, 52.25, 47.75, 4.51 +-10.74, -10.00, 54.78, 45.22, 9.56 +-10.68, -10.00, 49.79, 50.21, -0.43 +-10.74, -10.00, 54.78, 45.22, 9.57 +-10.74, -10.00, 52.31, 47.69, 4.63 +-10.74, -10.00, 52.32, 47.68, 4.63 +-10.74, -10.00, 52.32, 47.68, 4.64 +-10.74, -10.00, 52.32, 47.68, 4.64 +-10.68, -10.00, 49.80, 50.20, -0.39 +-10.74, -10.00, 54.80, 45.20, 9.60 +-10.68, -10.00, 49.81, 50.19, -0.38 +-10.68, -10.00, 52.28, 47.72, 4.57 +-10.68, -10.00, 52.29, 47.71, 4.57 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.60 +-10.68, -10.00, 52.30, 47.70, 4.60 +-10.68, -10.00, 52.30, 47.70, 4.61 +-10.68, -10.00, 52.31, 47.69, 4.61 +-10.68, -10.00, 52.31, 47.69, 4.62 +-10.55, -10.00, 47.27, 52.73, -5.46 +-10.55, -10.00, 52.21, 47.79, 4.43 +-10.55, -10.00, 52.22, 47.78, 4.43 +-10.55, -10.00, 52.22, 47.78, 4.44 +-10.55, -10.00, 52.22, 47.78, 4.44 +-10.55, -10.00, 52.22, 47.78, 4.44 +-10.48, -10.00, 49.70, 50.30, -0.59 +-10.48, -10.00, 52.18, 47.82, 4.35 +-10.48, -10.00, 52.18, 47.82, 4.36 +-10.48, -10.00, 52.18, 47.82, 4.36 +-10.48, -10.00, 52.18, 47.82, 4.36 +-10.42, -10.00, 49.66, 50.34, -0.68 +-10.42, -10.00, 52.14, 47.86, 4.27 +-10.42, -10.00, 52.14, 47.86, 4.27 +-10.42, -10.00, 52.14, 47.86, 4.28 +-10.28, -10.00, 47.10, 52.90, -5.81 +-10.28, -10.00, 52.04, 47.96, 4.08 +-10.28, -10.00, 52.04, 47.96, 4.09 +-10.28, -10.00, 52.04, 47.96, 4.09 +-10.22, -10.00, 49.52, 50.48, -0.95 +-10.22, -10.00, 52.00, 48.00, 3.99 +-10.22, -10.00, 52.00, 48.00, 3.99 +-10.22, -10.00, 52.00, 48.00, 4.00 +-10.15, -10.00, 49.48, 50.52, -1.05 +-10.15, -10.00, 51.95, 48.05, 3.90 +-10.15, -10.00, 51.95, 48.05, 3.90 +-10.15, -10.00, 51.95, 48.05, 3.90 +-10.02, -10.00, 46.91, 53.09, -6.18 +-10.02, -10.00, 51.85, 48.15, 3.70 +-10.02, -10.00, 51.85, 48.15, 3.70 +-10.02, -10.00, 51.85, 48.15, 3.70 +-10.02, -10.00, 51.85, 48.15, 3.70 +-9.95, -10.00, 49.33, 50.67, -1.34 +-9.89, -10.00, 49.28, 50.72, -1.44 +-9.89, -10.00, 51.75, 48.25, 3.50 +-9.89, -10.00, 51.75, 48.25, 3.50 +-9.76, -10.00, 46.71, 53.29, -6.58 +-9.76, -10.00, 51.65, 48.35, 3.30 +-9.76, -10.00, 51.65, 48.35, 3.30 +-9.76, -10.00, 51.65, 48.35, 3.30 +-9.76, -10.00, 51.65, 48.35, 3.30 +-9.69, -10.00, 49.13, 50.87, -1.75 +-9.69, -10.00, 51.60, 48.40, 3.19 +-9.69, -10.00, 51.60, 48.40, 3.19 +-9.69, -10.00, 51.59, 48.41, 3.19 +-9.62, -10.00, 49.07, 50.93, -1.86 +-9.62, -10.00, 51.54, 48.46, 3.08 +-9.62, -10.00, 51.54, 48.46, 3.08 +-9.62, -10.00, 51.54, 48.46, 3.08 +-9.49, -10.00, 46.49, 53.51, -7.01 +-9.49, -10.00, 51.44, 48.56, 2.87 +-9.49, -10.00, 51.43, 48.57, 2.87 +-9.43, -10.00, 48.91, 51.09, -2.18 +-9.43, -10.00, 51.38, 48.62, 2.76 +-9.43, -10.00, 51.38, 48.62, 2.76 +-9.43, -10.00, 51.38, 48.62, 2.75 +-9.36, -10.00, 48.85, 51.15, -2.29 +-9.36, -10.00, 51.32, 48.68, 2.64 +-9.36, -10.00, 51.32, 48.68, 2.64 +-9.36, -10.00, 51.32, 48.68, 2.63 +-9.36, -10.00, 51.32, 48.68, 2.63 +-9.36, -10.00, 51.31, 48.69, 2.63 +-9.36, -10.00, 51.31, 48.69, 2.62 +-9.23, -10.00, 46.26, 53.74, -7.47 +-9.23, -10.00, 51.21, 48.79, 2.41 +-9.23, -10.00, 51.20, 48.80, 2.41 +-9.23, -10.00, 51.20, 48.80, 2.40 +-9.23, -10.00, 51.20, 48.80, 2.39 +-9.23, -10.00, 51.19, 48.81, 2.39 +-9.23, -10.00, 51.19, 48.81, 2.38 +-9.23, -10.00, 51.19, 48.81, 2.38 +-9.23, -10.00, 51.19, 48.81, 2.37 +-9.23, -10.00, 51.18, 48.82, 2.36 +-9.23, -10.00, 51.18, 48.82, 2.36 +-9.23, -10.00, 51.18, 48.82, 2.35 +-9.23, -10.00, 51.17, 48.83, 2.35 +-9.23, -10.00, 51.17, 48.83, 2.34 +-9.23, -10.00, 51.17, 48.83, 2.34 +-9.23, -10.00, 51.17, 48.83, 2.33 +-9.23, -10.00, 51.16, 48.84, 2.32 +-9.23, -10.00, 51.16, 48.84, 2.32 +-9.23, -10.00, 51.16, 48.84, 2.31 +-9.36, -10.00, 56.20, 43.80, 12.39 +-9.36, -10.00, 51.25, 48.75, 2.50 +-9.36, -10.00, 51.25, 48.75, 2.50 +-9.36, -10.00, 51.25, 48.75, 2.49 +-9.36, -10.00, 51.24, 48.76, 2.49 +-9.43, -10.00, 53.76, 46.24, 7.52 +-9.43, -10.00, 51.29, 48.71, 2.58 +-9.43, -10.00, 51.29, 48.71, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.57 +-9.49, -10.00, 53.80, 46.20, 7.61 +-9.49, -10.00, 51.33, 48.67, 2.66 +-9.49, -10.00, 51.33, 48.67, 2.66 +-9.49, -10.00, 51.33, 48.67, 2.65 +-9.62, -10.00, 56.37, 43.63, 12.73 +-9.62, -10.00, 51.42, 48.58, 2.84 +-9.62, -10.00, 51.42, 48.58, 2.84 +-9.62, -10.00, 51.42, 48.58, 2.84 +-9.69, -10.00, 53.94, 46.06, 7.88 +-9.69, -10.00, 51.47, 48.53, 2.93 +-9.69, -10.00, 51.47, 48.53, 2.93 +-9.76, -10.00, 53.99, 46.01, 7.97 +-9.76, -10.00, 51.51, 48.49, 3.03 +-9.76, -10.00, 51.51, 48.49, 3.02 +-9.76, -10.00, 51.51, 48.49, 3.02 +-9.76, -10.00, 51.51, 48.49, 3.02 +-9.89, -10.00, 56.55, 43.45, 13.10 +-9.89, -10.00, 51.61, 48.39, 3.22 +-9.89, -10.00, 51.61, 48.39, 3.22 +-9.95, -10.00, 54.13, 45.87, 8.26 +-9.95, -10.00, 51.66, 48.34, 3.31 +-10.02, -10.00, 54.18, 45.82, 8.36 +-10.02, -10.00, 51.71, 48.29, 3.41 +-10.02, -10.00, 51.71, 48.29, 3.41 +-10.02, -10.00, 51.71, 48.29, 3.41 +-10.02, -10.00, 51.71, 48.29, 3.41 +-10.15, -10.00, 56.75, 43.25, 13.50 +-10.15, -10.00, 51.81, 48.19, 3.61 +-10.15, -10.00, 51.81, 48.19, 3.61 +-10.15, -10.00, 51.81, 48.19, 3.62 +-10.22, -10.00, 54.33, 45.67, 8.66 +-10.22, -10.00, 51.86, 48.14, 3.72 +-10.22, -10.00, 51.86, 48.14, 3.72 +-10.28, -10.00, 54.38, 45.62, 8.76 +-10.28, -10.00, 51.91, 48.09, 3.82 +-10.28, -10.00, 51.91, 48.09, 3.82 +-10.28, -10.00, 51.91, 48.09, 3.83 +-10.28, -10.00, 51.91, 48.09, 3.83 +-10.28, -10.00, 51.92, 48.08, 3.83 +-10.28, -10.00, 51.92, 48.08, 3.83 +-10.42, -10.00, 56.96, 43.04, 13.92 +-10.42, -10.00, 52.02, 47.98, 4.04 +-10.42, -10.00, 52.02, 47.98, 4.04 +-10.42, -10.00, 52.02, 47.98, 4.04 +-10.42, -10.00, 52.02, 47.98, 4.05 +-10.42, -10.00, 52.02, 47.98, 4.05 +-10.42, -10.00, 52.03, 47.97, 4.05 +-10.42, -10.00, 52.03, 47.97, 4.06 +-10.42, -10.00, 52.03, 47.97, 4.06 +-10.42, -10.00, 52.03, 47.97, 4.06 +-10.42, -10.00, 52.03, 47.97, 4.06 +-10.42, -10.00, 52.03, 47.97, 4.07 +-10.42, -10.00, 52.04, 47.96, 4.07 +-10.42, -10.00, 52.04, 47.96, 4.07 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.09 +-10.42, -10.00, 52.04, 47.96, 4.09 +-10.42, -10.00, 52.05, 47.95, 4.09 +-10.42, -10.00, 52.05, 47.95, 4.10 +-10.28, -10.00, 47.01, 52.99, -5.99 +-10.28, -10.00, 51.95, 48.05, 3.90 +-10.28, -10.00, 51.95, 48.05, 3.90 +-10.28, -10.00, 51.95, 48.05, 3.91 +-10.28, -10.00, 51.95, 48.05, 3.91 +-10.28, -10.00, 51.96, 48.04, 3.91 +-10.28, -10.00, 51.96, 48.04, 3.91 +-10.28, -10.00, 51.96, 48.04, 3.92 +-10.28, -10.00, 51.96, 48.04, 3.92 +-10.28, -10.00, 51.96, 48.04, 3.92 +-10.28, -10.00, 51.96, 48.04, 3.92 +-10.22, -10.00, 49.44, 50.56, -1.12 +-10.22, -10.00, 51.91, 48.09, 3.83 +-10.22, -10.00, 51.91, 48.09, 3.83 +-10.22, -10.00, 51.91, 48.09, 3.83 +-10.22, -10.00, 51.92, 48.08, 3.83 +-10.22, -10.00, 51.92, 48.08, 3.83 +-10.22, -10.00, 51.92, 48.08, 3.83 +-10.15, -10.00, 49.40, 50.60, -1.21 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.75 +-10.02, -10.00, 46.83, 53.17, -6.34 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-9.95, -10.00, 49.25, 50.75, -1.49 +-9.95, -10.00, 51.72, 48.28, 3.45 +-9.95, -10.00, 51.72, 48.28, 3.45 +-9.95, -10.00, 51.72, 48.28, 3.45 +-9.89, -10.00, 49.20, 50.80, -1.60 +-9.89, -10.00, 51.67, 48.33, 3.35 +-9.89, -10.00, 51.67, 48.33, 3.35 +-9.89, -10.00, 51.67, 48.33, 3.35 +-9.89, -10.00, 51.67, 48.33, 3.35 +-9.89, -10.00, 51.67, 48.33, 3.34 +-9.89, -10.00, 51.67, 48.33, 3.34 +-9.76, -10.00, 46.63, 53.37, -6.74 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.69, -10.00, 49.04, 50.96, -1.91 +-9.69, -10.00, 51.52, 48.48, 3.03 +-9.69, -10.00, 51.51, 48.49, 3.03 +-9.62, -10.00, 48.99, 51.01, -2.02 +-9.62, -10.00, 51.46, 48.54, 2.92 +-9.62, -10.00, 51.46, 48.54, 2.92 +-9.62, -10.00, 51.46, 48.54, 2.92 +-9.62, -10.00, 51.46, 48.54, 2.92 +-9.62, -10.00, 51.46, 48.54, 2.91 +-9.62, -10.00, 51.46, 48.54, 2.91 +-9.49, -10.00, 46.41, 53.59, -7.18 +-9.49, -10.00, 51.35, 48.65, 2.71 +-9.49, -10.00, 51.35, 48.65, 2.70 +-9.49, -10.00, 51.35, 48.65, 2.70 +-9.49, -10.00, 51.35, 48.65, 2.69 +-9.43, -10.00, 48.82, 51.18, -2.35 +-9.43, -10.00, 51.29, 48.71, 2.59 +-9.43, -10.00, 51.29, 48.71, 2.58 +-9.43, -10.00, 51.29, 48.71, 2.58 +-9.43, -10.00, 51.29, 48.71, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.56 +-9.36, -10.00, 48.76, 51.24, -2.48 +-9.36, -10.00, 51.23, 48.77, 2.46 +-9.43, -10.00, 53.75, 46.25, 7.49 +-9.36, -10.00, 48.75, 51.25, -2.50 +-9.43, -10.00, 53.74, 46.26, 7.49 +-9.36, -10.00, 48.75, 51.25, -2.51 +-9.36, -10.00, 51.22, 48.78, 2.43 +-9.43, -10.00, 53.74, 46.26, 7.47 +-9.36, -10.00, 48.74, 51.26, -2.52 +-9.36, -10.00, 51.21, 48.79, 2.42 +-9.36, -10.00, 51.21, 48.79, 2.41 +-9.36, -10.00, 51.20, 48.80, 2.41 +-9.36, -10.00, 51.20, 48.80, 2.41 +-9.36, -10.00, 51.20, 48.80, 2.40 +-9.36, -10.00, 51.20, 48.80, 2.40 +-9.36, -10.00, 51.20, 48.80, 2.39 +-9.36, -10.00, 51.19, 48.81, 2.39 +-9.36, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 51.19, 48.81, 2.37 +-9.36, -10.00, 51.18, 48.82, 2.37 +-9.43, -10.00, 53.70, 46.30, 7.41 +-9.43, -10.00, 51.23, 48.77, 2.46 +-9.43, -10.00, 51.23, 48.77, 2.45 +-9.43, -10.00, 51.22, 48.78, 2.45 +-9.43, -10.00, 51.22, 48.78, 2.44 +-9.43, -10.00, 51.22, 48.78, 2.44 +-9.43, -10.00, 51.22, 48.78, 2.44 +-9.43, -10.00, 51.22, 48.78, 2.43 +-9.49, -10.00, 53.73, 46.27, 7.47 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.51 +-9.49, -10.00, 51.26, 48.74, 2.51 +-9.49, -10.00, 51.25, 48.75, 2.51 +-9.62, -10.00, 56.29, 43.71, 12.59 +-9.62, -10.00, 51.35, 48.65, 2.70 +-9.62, -10.00, 51.35, 48.65, 2.70 +-9.62, -10.00, 51.35, 48.65, 2.69 +-9.69, -10.00, 53.87, 46.13, 7.73 +-9.69, -10.00, 51.39, 48.61, 2.79 +-9.69, -10.00, 51.39, 48.61, 2.79 +-9.76, -10.00, 53.91, 46.09, 7.83 +-9.76, -10.00, 51.44, 48.56, 2.88 +-9.76, -10.00, 51.44, 48.56, 2.88 +-9.76, -10.00, 51.44, 48.56, 2.88 +-9.76, -10.00, 51.44, 48.56, 2.88 +-9.89, -10.00, 56.48, 43.52, 12.96 +-9.89, -10.00, 51.54, 48.46, 3.07 +-9.89, -10.00, 51.54, 48.46, 3.07 +-9.89, -10.00, 51.53, 48.47, 3.07 +-9.89, -10.00, 51.53, 48.47, 3.07 +-9.95, -10.00, 54.06, 45.94, 8.11 +-9.95, -10.00, 51.58, 48.42, 3.17 +-9.95, -10.00, 51.58, 48.42, 3.17 +-10.02, -10.00, 54.10, 45.90, 8.21 +-10.02, -10.00, 51.63, 48.37, 3.27 +-10.02, -10.00, 51.63, 48.37, 3.27 +-10.02, -10.00, 51.63, 48.37, 3.27 +-10.02, -10.00, 51.63, 48.37, 3.27 +-10.15, -10.00, 56.68, 43.32, 13.35 +-10.15, -10.00, 51.73, 48.27, 3.47 +-10.15, -10.00, 51.73, 48.27, 3.47 +-10.15, -10.00, 51.73, 48.27, 3.47 +-10.15, -10.00, 51.73, 48.27, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.75, 48.25, 3.49 +-10.15, -10.00, 51.75, 48.25, 3.49 +-10.15, -10.00, 51.75, 48.25, 3.49 +-10.15, -10.00, 51.75, 48.25, 3.49 +-10.02, -10.00, 46.70, 53.30, -6.59 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-9.95, -10.00, 49.13, 50.87, -1.75 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.89, -10.00, 49.08, 50.92, -1.85 +-9.95, -10.00, 54.07, 45.93, 8.14 +-9.89, -10.00, 49.08, 50.92, -1.85 +-9.89, -10.00, 51.55, 48.45, 3.10 +-9.89, -10.00, 51.55, 48.45, 3.09 +-9.89, -10.00, 51.55, 48.45, 3.09 +-9.89, -10.00, 51.55, 48.45, 3.09 +-9.95, -10.00, 54.07, 45.93, 8.14 +-9.95, -10.00, 51.60, 48.40, 3.19 +-9.95, -10.00, 51.60, 48.40, 3.19 +-9.95, -10.00, 51.60, 48.40, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-10.02, -10.00, 54.12, 45.88, 8.23 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.15, -10.00, 56.69, 43.31, 13.37 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.22, -10.00, 54.27, 45.73, 8.53 +-10.22, -10.00, 51.80, 48.20, 3.59 +-10.22, -10.00, 51.80, 48.20, 3.59 +-10.22, -10.00, 51.80, 48.20, 3.59 +-10.22, -10.00, 51.80, 48.20, 3.60 +-10.22, -10.00, 51.80, 48.20, 3.60 +-10.28, -10.00, 54.32, 45.68, 8.64 +-10.28, -10.00, 51.85, 48.15, 3.70 +-10.28, -10.00, 51.85, 48.15, 3.70 +-10.28, -10.00, 51.85, 48.15, 3.70 +-10.28, -10.00, 51.85, 48.15, 3.71 +-10.28, -10.00, 51.85, 48.15, 3.71 +-10.42, -10.00, 56.90, 43.10, 13.80 +-10.42, -10.00, 51.96, 48.04, 3.91 +-10.42, -10.00, 51.96, 48.04, 3.92 +-10.42, -10.00, 51.96, 48.04, 3.92 +-10.48, -10.00, 54.48, 45.52, 8.97 +-10.48, -10.00, 52.01, 47.99, 4.03 +-10.48, -10.00, 52.01, 47.99, 4.03 +-10.48, -10.00, 52.02, 47.98, 4.03 +-10.48, -10.00, 52.02, 47.98, 4.04 +-10.55, -10.00, 54.54, 45.46, 9.08 +-10.55, -10.00, 52.07, 47.93, 4.14 +-10.55, -10.00, 52.07, 47.93, 4.15 +-10.55, -10.00, 52.08, 47.92, 4.15 +-10.55, -10.00, 52.08, 47.92, 4.16 +-10.55, -10.00, 52.08, 47.92, 4.16 +-10.55, -10.00, 52.08, 47.92, 4.16 +-10.55, -10.00, 52.08, 47.92, 4.17 +-10.55, -10.00, 52.09, 47.91, 4.17 +-10.55, -10.00, 52.09, 47.91, 4.18 +-10.55, -10.00, 52.09, 47.91, 4.18 +-10.55, -10.00, 52.09, 47.91, 4.18 +-10.55, -10.00, 52.09, 47.91, 4.19 +-10.55, -10.00, 52.10, 47.90, 4.19 +-10.55, -10.00, 52.10, 47.90, 4.20 +-10.68, -10.00, 57.14, 42.86, 14.29 +-10.55, -10.00, 47.16, 52.84, -5.68 +-10.68, -10.00, 57.15, 42.85, 14.30 +-10.55, -10.00, 47.16, 52.84, -5.67 +-10.55, -10.00, 52.11, 47.89, 4.22 +-10.55, -10.00, 52.11, 47.89, 4.22 +-10.55, -10.00, 52.11, 47.89, 4.23 +-10.55, -10.00, 52.12, 47.88, 4.23 +-10.55, -10.00, 52.12, 47.88, 4.24 +-10.55, -10.00, 52.12, 47.88, 4.24 +-10.55, -10.00, 52.12, 47.88, 4.24 +-10.55, -10.00, 52.12, 47.88, 4.25 +-10.55, -10.00, 52.13, 47.87, 4.25 +-10.48, -10.00, 49.61, 50.39, -0.79 +-10.48, -10.00, 52.08, 47.92, 4.16 +-10.48, -10.00, 52.08, 47.92, 4.16 +-10.48, -10.00, 52.08, 47.92, 4.17 +-10.48, -10.00, 52.09, 47.91, 4.17 +-10.42, -10.00, 49.57, 50.43, -0.87 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.28, -10.00, 47.00, 53.00, -6.00 +-10.28, -10.00, 51.95, 48.05, 3.89 +-10.28, -10.00, 51.95, 48.05, 3.89 +-10.28, -10.00, 51.95, 48.05, 3.90 +-10.22, -10.00, 49.43, 50.57, -1.15 +-10.22, -10.00, 51.90, 48.10, 3.80 +-10.22, -10.00, 51.90, 48.10, 3.80 +-10.22, -10.00, 51.90, 48.10, 3.80 +-10.15, -10.00, 49.38, 50.62, -1.24 +-10.15, -10.00, 51.85, 48.15, 3.71 +-10.15, -10.00, 51.85, 48.15, 3.71 +-10.02, -10.00, 46.81, 53.19, -6.38 +-10.02, -10.00, 51.75, 48.25, 3.51 +-10.02, -10.00, 51.75, 48.25, 3.51 +-10.02, -10.00, 51.76, 48.24, 3.51 +-10.02, -10.00, 51.76, 48.24, 3.51 +-10.02, -10.00, 51.76, 48.24, 3.51 +-10.02, -10.00, 51.76, 48.24, 3.51 +-9.95, -10.00, 49.23, 50.77, -1.53 +-9.95, -10.00, 51.71, 48.29, 3.41 +-9.95, -10.00, 51.71, 48.29, 3.41 +-9.89, -10.00, 49.18, 50.82, -1.63 +-9.89, -10.00, 51.66, 48.34, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.30 +-9.89, -10.00, 51.65, 48.35, 3.30 +-9.89, -10.00, 51.65, 48.35, 3.30 +-9.95, -10.00, 54.17, 45.83, 8.34 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-10.02, -10.00, 54.22, 45.78, 8.44 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-9.95, -10.00, 49.23, 50.77, -1.54 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.89, -10.00, 49.18, 50.82, -1.65 +-9.95, -10.00, 54.17, 45.83, 8.34 +-9.89, -10.00, 49.18, 50.82, -1.65 +-9.89, -10.00, 51.65, 48.35, 3.29 +-9.89, -10.00, 51.65, 48.35, 3.29 +-9.89, -10.00, 51.65, 48.35, 3.29 +-9.89, -10.00, 51.65, 48.35, 3.29 +-9.76, -10.00, 46.60, 53.40, -6.80 +-9.76, -10.00, 51.55, 48.45, 3.09 +-9.76, -10.00, 51.54, 48.46, 3.09 +-9.76, -10.00, 51.54, 48.46, 3.09 +-9.76, -10.00, 51.54, 48.46, 3.09 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.69, -10.00, 49.02, 50.98, -1.97 +-9.69, -10.00, 51.49, 48.51, 2.97 +-9.69, -10.00, 51.49, 48.51, 2.97 +-9.69, -10.00, 51.48, 48.52, 2.97 +-9.69, -10.00, 51.48, 48.52, 2.97 +-9.62, -10.00, 48.96, 51.04, -2.08 +-9.62, -10.00, 51.43, 48.57, 2.86 +-9.62, -10.00, 51.43, 48.57, 2.86 +-9.62, -10.00, 51.43, 48.57, 2.86 +-9.62, -10.00, 51.43, 48.57, 2.85 +-9.62, -10.00, 51.42, 48.58, 2.85 +-9.49, -10.00, 46.38, 53.62, -7.24 +-9.49, -10.00, 51.32, 48.68, 2.64 +-9.49, -10.00, 51.32, 48.68, 2.64 +-9.49, -10.00, 51.32, 48.68, 2.64 +-9.49, -10.00, 51.32, 48.68, 2.63 +-9.49, -10.00, 51.31, 48.69, 2.63 +-9.49, -10.00, 51.31, 48.69, 2.63 +-9.49, -10.00, 51.31, 48.69, 2.62 +-9.49, -10.00, 51.31, 48.69, 2.62 +-9.43, -10.00, 48.79, 51.21, -2.43 +-9.43, -10.00, 51.26, 48.74, 2.51 +-9.43, -10.00, 51.25, 48.75, 2.51 +-9.43, -10.00, 51.25, 48.75, 2.50 +-9.43, -10.00, 51.25, 48.75, 2.50 +-9.43, -10.00, 51.25, 48.75, 2.49 +-9.43, -10.00, 51.24, 48.76, 2.49 +-9.36, -10.00, 48.72, 51.28, -2.56 +-9.36, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 51.19, 48.81, 2.37 +-9.36, -10.00, 51.18, 48.82, 2.37 +-9.36, -10.00, 51.18, 48.82, 2.36 +-9.36, -10.00, 51.18, 48.82, 2.36 +-9.36, -10.00, 51.18, 48.82, 2.35 +-9.36, -10.00, 51.17, 48.83, 2.35 +-9.36, -10.00, 51.17, 48.83, 2.34 +-9.36, -10.00, 51.17, 48.83, 2.34 +-9.36, -10.00, 51.17, 48.83, 2.33 +-9.36, -10.00, 51.16, 48.84, 2.33 +-9.36, -10.00, 51.16, 48.84, 2.32 +-9.36, -10.00, 51.16, 48.84, 2.32 +-9.36, -10.00, 51.16, 48.84, 2.31 +-9.36, -10.00, 51.15, 48.85, 2.31 +-9.36, -10.00, 51.15, 48.85, 2.30 +-9.36, -10.00, 51.15, 48.85, 2.30 +-9.36, -10.00, 51.15, 48.85, 2.29 +-9.36, -10.00, 51.14, 48.86, 2.29 +-9.36, -10.00, 51.14, 48.86, 2.28 +-9.36, -10.00, 51.14, 48.86, 2.28 +-9.36, -10.00, 51.14, 48.86, 2.27 +-9.36, -10.00, 51.13, 48.87, 2.27 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.25 +-9.36, -10.00, 51.12, 48.88, 2.25 +-9.36, -10.00, 51.12, 48.88, 2.24 +-9.36, -10.00, 51.12, 48.88, 2.24 +-9.36, -10.00, 51.12, 48.88, 2.23 +-9.36, -10.00, 51.11, 48.89, 2.23 +-9.36, -10.00, 51.11, 48.89, 2.22 +-9.36, -10.00, 51.11, 48.89, 2.22 +-9.36, -10.00, 51.11, 48.89, 2.21 +-9.36, -10.00, 51.10, 48.90, 2.21 +-9.36, -10.00, 51.10, 48.90, 2.20 +-9.36, -10.00, 51.10, 48.90, 2.20 +-9.36, -10.00, 51.10, 48.90, 2.19 +-9.36, -10.00, 51.09, 48.91, 2.19 +-9.36, -10.00, 51.09, 48.91, 2.18 +-9.36, -10.00, 51.09, 48.91, 2.18 +-9.36, -10.00, 51.09, 48.91, 2.17 +-9.23, -10.00, 46.04, 53.96, -7.92 +-9.23, -10.00, 50.98, 49.02, 1.96 +-9.23, -10.00, 50.98, 49.02, 1.96 +-9.23, -10.00, 50.98, 49.02, 1.95 +-9.23, -10.00, 50.97, 49.03, 1.95 +-9.23, -10.00, 50.97, 49.03, 1.94 +-9.23, -10.00, 50.97, 49.03, 1.94 +-9.23, -10.00, 50.96, 49.04, 1.93 +-9.23, -10.00, 50.96, 49.04, 1.92 +-9.23, -10.00, 50.96, 49.04, 1.92 +-9.23, -10.00, 50.96, 49.04, 1.91 +-9.23, -10.00, 50.95, 49.05, 1.91 +-9.23, -10.00, 50.95, 49.05, 1.90 +-9.23, -10.00, 50.95, 49.05, 1.90 +-9.23, -10.00, 50.94, 49.06, 1.89 +-9.23, -10.00, 50.94, 49.06, 1.88 +-9.23, -10.00, 50.94, 49.06, 1.88 +-9.36, -10.00, 55.98, 44.02, 11.96 +-9.36, -10.00, 51.03, 48.97, 2.07 +-9.36, -10.00, 51.03, 48.97, 2.06 +-9.36, -10.00, 51.03, 48.97, 2.06 +-9.36, -10.00, 51.03, 48.97, 2.05 +-9.36, -10.00, 51.02, 48.98, 2.05 +-9.36, -10.00, 51.02, 48.98, 2.04 +-9.36, -10.00, 51.02, 48.98, 2.04 +-9.36, -10.00, 51.02, 48.98, 2.03 +-9.36, -10.00, 51.01, 48.99, 2.03 +-9.43, -10.00, 53.53, 46.47, 7.07 +-9.43, -10.00, 51.06, 48.94, 2.12 +-9.43, -10.00, 51.06, 48.94, 2.11 +-9.43, -10.00, 51.05, 48.95, 2.11 +-9.43, -10.00, 51.05, 48.95, 2.10 +-9.43, -10.00, 51.05, 48.95, 2.10 +-9.43, -10.00, 51.05, 48.95, 2.10 +-9.43, -10.00, 51.05, 48.95, 2.09 +-9.43, -10.00, 51.04, 48.96, 2.09 +-9.43, -10.00, 51.04, 48.96, 2.08 +-9.49, -10.00, 53.56, 46.44, 7.12 +-9.49, -10.00, 51.09, 48.91, 2.17 +-9.49, -10.00, 51.09, 48.91, 2.17 +-9.49, -10.00, 51.08, 48.92, 2.17 +-9.49, -10.00, 51.08, 48.92, 2.16 +-9.49, -10.00, 51.08, 48.92, 2.16 +-9.49, -10.00, 51.08, 48.92, 2.16 +-9.49, -10.00, 51.08, 48.92, 2.15 +-9.49, -10.00, 51.07, 48.93, 2.15 +-9.62, -10.00, 56.12, 43.88, 12.23 +-9.62, -10.00, 51.17, 48.83, 2.34 +-9.62, -10.00, 51.17, 48.83, 2.34 +-9.62, -10.00, 51.17, 48.83, 2.33 +-9.62, -10.00, 51.17, 48.83, 2.33 +-9.62, -10.00, 51.16, 48.84, 2.33 +-9.62, -10.00, 51.16, 48.84, 2.33 +-9.62, -10.00, 51.16, 48.84, 2.32 +-9.62, -10.00, 51.16, 48.84, 2.32 +-9.62, -10.00, 51.16, 48.84, 2.32 +-9.62, -10.00, 51.16, 48.84, 2.31 +-9.62, -10.00, 51.16, 48.84, 2.31 +-9.62, -10.00, 51.15, 48.85, 2.31 +-9.62, -10.00, 51.15, 48.85, 2.31 +-9.62, -10.00, 51.15, 48.85, 2.30 +-9.62, -10.00, 51.15, 48.85, 2.30 +-9.69, -10.00, 53.67, 46.33, 7.34 +-9.62, -10.00, 48.68, 51.32, -2.65 +-9.69, -10.00, 53.67, 46.33, 7.34 +-9.62, -10.00, 48.67, 51.33, -2.65 +-9.69, -10.00, 53.67, 46.33, 7.33 +-9.69, -10.00, 51.19, 48.81, 2.38 +-9.69, -10.00, 51.19, 48.81, 2.38 +-9.62, -10.00, 48.67, 51.33, -2.66 +-9.62, -10.00, 51.14, 48.86, 2.28 +-9.69, -10.00, 53.66, 46.34, 7.32 +-9.69, -10.00, 51.19, 48.81, 2.37 +-9.69, -10.00, 51.18, 48.82, 2.37 +-9.69, -10.00, 51.18, 48.82, 2.37 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.35 +-9.69, -10.00, 51.18, 48.82, 2.35 +-9.69, -10.00, 51.17, 48.83, 2.35 +-9.69, -10.00, 51.17, 48.83, 2.35 +-9.69, -10.00, 51.17, 48.83, 2.34 +-9.62, -10.00, 48.65, 51.35, -2.70 +-9.62, -10.00, 51.12, 48.88, 2.24 +-9.62, -10.00, 51.12, 48.88, 2.24 +-9.62, -10.00, 51.12, 48.88, 2.23 +-9.62, -10.00, 51.12, 48.88, 2.23 +-9.62, -10.00, 51.11, 48.89, 2.23 +-9.62, -10.00, 51.11, 48.89, 2.23 +-9.62, -10.00, 51.11, 48.89, 2.22 +-9.62, -10.00, 51.11, 48.89, 2.22 +-9.49, -10.00, 46.07, 53.93, -7.87 +-9.49, -10.00, 51.01, 48.99, 2.01 +-9.49, -10.00, 51.01, 48.99, 2.01 +-9.49, -10.00, 51.00, 49.00, 2.01 +-9.49, -10.00, 51.00, 49.00, 2.00 +-9.49, -10.00, 51.00, 49.00, 2.00 +-9.49, -10.00, 51.00, 49.00, 2.00 +-9.49, -10.00, 51.00, 49.00, 1.99 +-9.49, -10.00, 50.99, 49.01, 1.99 +-9.49, -10.00, 50.99, 49.01, 1.98 +-9.49, -10.00, 50.99, 49.01, 1.98 +-9.43, -10.00, 48.47, 51.53, -3.07 +-9.43, -10.00, 50.94, 49.06, 1.87 +-9.43, -10.00, 50.93, 49.07, 1.87 +-9.43, -10.00, 50.93, 49.07, 1.86 +-9.43, -10.00, 50.93, 49.07, 1.86 +-9.43, -10.00, 50.93, 49.07, 1.86 +-9.43, -10.00, 50.93, 49.07, 1.85 +-9.43, -10.00, 50.92, 49.08, 1.85 +-9.43, -10.00, 50.92, 49.08, 1.84 +-9.43, -10.00, 50.92, 49.08, 1.84 +-9.43, -10.00, 50.92, 49.08, 1.83 +-9.43, -10.00, 50.91, 49.09, 1.83 +-9.43, -10.00, 50.91, 49.09, 1.83 +-9.43, -10.00, 50.91, 49.09, 1.82 +-9.43, -10.00, 50.91, 49.09, 1.82 +-9.43, -10.00, 50.91, 49.09, 1.81 +-9.36, -10.00, 48.38, 51.62, -3.24 +-9.36, -10.00, 50.85, 49.15, 1.70 +-9.36, -10.00, 50.85, 49.15, 1.70 +-9.36, -10.00, 50.85, 49.15, 1.69 +-9.36, -10.00, 50.84, 49.16, 1.69 +-9.36, -10.00, 50.84, 49.16, 1.68 +-9.36, -10.00, 50.84, 49.16, 1.68 +-9.36, -10.00, 50.84, 49.16, 1.68 +-9.43, -10.00, 53.36, 46.64, 6.71 +-9.43, -10.00, 50.88, 49.12, 1.77 +-9.43, -10.00, 50.88, 49.12, 1.76 +-9.43, -10.00, 50.88, 49.12, 1.76 +-9.43, -10.00, 50.88, 49.12, 1.75 +-9.43, -10.00, 50.87, 49.13, 1.75 +-9.36, -10.00, 48.35, 51.65, -3.30 +-9.43, -10.00, 53.34, 46.66, 6.68 +-9.43, -10.00, 50.87, 49.13, 1.73 +-9.43, -10.00, 50.87, 49.13, 1.73 +-9.43, -10.00, 50.86, 49.14, 1.73 +-9.43, -10.00, 50.86, 49.14, 1.72 +-9.43, -10.00, 50.86, 49.14, 1.72 +-9.43, -10.00, 50.86, 49.14, 1.71 +-9.43, -10.00, 50.85, 49.15, 1.71 +-9.43, -10.00, 50.85, 49.15, 1.70 +-9.43, -10.00, 50.85, 49.15, 1.70 +-9.43, -10.00, 50.85, 49.15, 1.70 +-9.49, -10.00, 53.37, 46.63, 6.73 +-9.49, -10.00, 50.89, 49.11, 1.79 +-9.49, -10.00, 50.89, 49.11, 1.78 +-9.49, -10.00, 50.89, 49.11, 1.78 +-9.49, -10.00, 50.89, 49.11, 1.78 +-9.49, -10.00, 50.89, 49.11, 1.77 +-9.49, -10.00, 50.88, 49.12, 1.77 +-9.49, -10.00, 50.88, 49.12, 1.76 +-9.62, -10.00, 55.92, 44.08, 11.85 +-9.62, -10.00, 50.98, 49.02, 1.96 +-9.62, -10.00, 50.98, 49.02, 1.95 +-9.62, -10.00, 50.98, 49.02, 1.95 +-9.62, -10.00, 50.97, 49.03, 1.95 +-9.62, -10.00, 50.97, 49.03, 1.95 +-9.62, -10.00, 50.97, 49.03, 1.94 +-9.62, -10.00, 50.97, 49.03, 1.94 +-9.62, -10.00, 50.97, 49.03, 1.94 +-9.69, -10.00, 53.49, 46.51, 6.98 +-9.62, -10.00, 48.49, 51.51, -3.01 +-9.69, -10.00, 53.49, 46.51, 6.97 +-9.69, -10.00, 51.01, 48.99, 2.03 +-9.69, -10.00, 51.01, 48.99, 2.02 +-9.69, -10.00, 51.01, 48.99, 2.02 +-9.69, -10.00, 51.01, 48.99, 2.02 +-9.69, -10.00, 51.01, 48.99, 2.02 +-9.69, -10.00, 51.01, 48.99, 2.01 +-9.69, -10.00, 51.01, 48.99, 2.01 +-9.69, -10.00, 51.00, 49.00, 2.01 +-9.69, -10.00, 51.00, 49.00, 2.01 +-9.69, -10.00, 51.00, 49.00, 2.00 +-9.69, -10.00, 51.00, 49.00, 2.00 +-9.69, -10.00, 51.00, 49.00, 2.00 +-9.76, -10.00, 53.52, 46.48, 7.04 +-9.69, -10.00, 48.53, 51.47, -2.95 +-9.76, -10.00, 53.52, 46.48, 7.04 +-9.76, -10.00, 51.05, 48.95, 2.09 +-9.76, -10.00, 51.04, 48.96, 2.09 +-9.76, -10.00, 51.04, 48.96, 2.09 +-9.76, -10.00, 51.04, 48.96, 2.09 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.07 +-9.76, -10.00, 51.04, 48.96, 2.07 +-9.76, -10.00, 51.04, 48.96, 2.07 +-9.76, -10.00, 51.03, 48.97, 2.07 +-9.76, -10.00, 51.03, 48.97, 2.07 +-9.76, -10.00, 51.03, 48.97, 2.07 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.05 +-9.76, -10.00, 51.03, 48.97, 2.05 +-9.76, -10.00, 51.03, 48.97, 2.05 +-9.76, -10.00, 51.02, 48.98, 2.05 +-9.76, -10.00, 51.02, 48.98, 2.05 +-9.76, -10.00, 51.02, 48.98, 2.05 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.03 +-9.76, -10.00, 51.02, 48.98, 2.03 +-9.76, -10.00, 51.02, 48.98, 2.03 +-9.76, -10.00, 51.01, 48.99, 2.03 +-9.76, -10.00, 51.01, 48.99, 2.03 +-9.76, -10.00, 51.01, 48.99, 2.03 +-9.69, -10.00, 48.49, 51.51, -3.02 +-9.69, -10.00, 50.96, 49.04, 1.92 +-9.69, -10.00, 50.96, 49.04, 1.92 +-9.69, -10.00, 50.96, 49.04, 1.92 +-9.69, -10.00, 50.96, 49.04, 1.91 +-9.69, -10.00, 50.96, 49.04, 1.91 +-9.69, -10.00, 50.96, 49.04, 1.91 +-9.69, -10.00, 50.95, 49.05, 1.91 +-9.69, -10.00, 50.95, 49.05, 1.91 +-9.69, -10.00, 50.95, 49.05, 1.90 +-9.62, -10.00, 48.43, 51.57, -3.14 +-9.62, -10.00, 50.90, 49.10, 1.80 +-9.62, -10.00, 50.90, 49.10, 1.80 +-9.62, -10.00, 50.90, 49.10, 1.79 +-9.62, -10.00, 50.90, 49.10, 1.79 +-9.62, -10.00, 50.89, 49.11, 1.79 +-9.62, -10.00, 50.89, 49.11, 1.78 +-9.62, -10.00, 50.89, 49.11, 1.78 +-9.62, -10.00, 50.89, 49.11, 1.78 +-9.62, -10.00, 50.89, 49.11, 1.78 +-9.62, -10.00, 50.89, 49.11, 1.77 +-9.62, -10.00, 50.89, 49.11, 1.77 +-9.62, -10.00, 50.88, 49.12, 1.77 +-9.62, -10.00, 50.88, 49.12, 1.76 +-9.62, -10.00, 50.88, 49.12, 1.76 +-9.69, -10.00, 53.40, 46.60, 6.80 +-9.69, -10.00, 50.93, 49.07, 1.86 +-9.62, -10.00, 48.41, 51.59, -3.19 +-9.69, -10.00, 53.40, 46.60, 6.80 +-9.69, -10.00, 50.92, 49.08, 1.85 +-9.69, -10.00, 50.92, 49.08, 1.85 +-9.69, -10.00, 50.92, 49.08, 1.84 +-9.76, -10.00, 53.44, 46.56, 6.89 +-9.76, -10.00, 50.97, 49.03, 1.94 +-9.76, -10.00, 50.97, 49.03, 1.94 +-9.76, -10.00, 50.97, 49.03, 1.94 +-9.76, -10.00, 50.97, 49.03, 1.93 +-9.76, -10.00, 50.97, 49.03, 1.93 +-9.76, -10.00, 50.97, 49.03, 1.93 +-9.76, -10.00, 50.96, 49.04, 1.93 +-9.89, -10.00, 56.01, 43.99, 12.01 +-9.89, -10.00, 51.06, 48.94, 2.12 +-9.89, -10.00, 51.06, 48.94, 2.12 +-9.89, -10.00, 51.06, 48.94, 2.12 +-9.89, -10.00, 51.06, 48.94, 2.12 +-9.95, -10.00, 53.58, 46.42, 7.16 +-9.95, -10.00, 51.11, 48.89, 2.22 +-10.02, -10.00, 53.63, 46.37, 7.26 +-10.02, -10.00, 51.16, 48.84, 2.32 +-10.02, -10.00, 51.16, 48.84, 2.32 +-10.02, -10.00, 51.16, 48.84, 2.32 +-10.02, -10.00, 51.16, 48.84, 2.32 +-10.15, -10.00, 56.20, 43.80, 12.41 +-10.15, -10.00, 51.26, 48.74, 2.52 +-10.15, -10.00, 51.26, 48.74, 2.52 +-10.22, -10.00, 53.78, 46.22, 7.57 +-10.22, -10.00, 51.31, 48.69, 2.62 +-10.22, -10.00, 51.31, 48.69, 2.62 +-10.22, -10.00, 51.31, 48.69, 2.63 +-10.28, -10.00, 53.84, 46.16, 7.67 +-10.28, -10.00, 51.36, 48.64, 2.73 +-10.28, -10.00, 51.37, 48.63, 2.73 +-10.28, -10.00, 51.37, 48.63, 2.73 +-10.28, -10.00, 51.37, 48.63, 2.74 +-10.42, -10.00, 56.41, 43.59, 12.82 +-10.42, -10.00, 51.47, 48.53, 2.94 +-10.42, -10.00, 51.47, 48.53, 2.94 +-10.42, -10.00, 51.47, 48.53, 2.95 +-10.48, -10.00, 54.00, 46.00, 7.99 +-10.48, -10.00, 51.53, 48.47, 3.05 +-10.48, -10.00, 51.53, 48.47, 3.06 +-10.48, -10.00, 51.53, 48.47, 3.06 +-10.55, -10.00, 54.05, 45.95, 8.11 +-10.55, -10.00, 51.58, 48.42, 3.17 +-10.55, -10.00, 51.59, 48.41, 3.17 +-10.55, -10.00, 51.59, 48.41, 3.17 +-10.55, -10.00, 51.59, 48.41, 3.18 +-10.55, -10.00, 51.59, 48.41, 3.18 +-10.55, -10.00, 51.59, 48.41, 3.19 +-10.68, -10.00, 56.64, 43.36, 13.28 +-10.68, -10.00, 51.70, 48.30, 3.39 +-10.68, -10.00, 51.70, 48.30, 3.40 +-10.68, -10.00, 51.70, 48.30, 3.41 +-10.68, -10.00, 51.71, 48.29, 3.41 +-10.68, -10.00, 51.71, 48.29, 3.42 +-10.68, -10.00, 51.71, 48.29, 3.42 +-10.68, -10.00, 51.71, 48.29, 3.43 +-10.68, -10.00, 51.72, 48.28, 3.43 +-10.68, -10.00, 51.72, 48.28, 3.44 +-10.68, -10.00, 51.72, 48.28, 3.44 +-10.74, -10.00, 54.24, 45.76, 8.49 +-10.68, -10.00, 49.25, 50.75, -1.49 +-10.74, -10.00, 54.25, 45.75, 8.50 +-10.74, -10.00, 51.78, 48.22, 3.56 +-10.74, -10.00, 51.78, 48.22, 3.57 +-10.74, -10.00, 51.79, 48.21, 3.57 +-10.74, -10.00, 51.79, 48.21, 3.58 +-10.74, -10.00, 51.79, 48.21, 3.58 +-10.74, -10.00, 51.79, 48.21, 3.59 +-10.68, -10.00, 49.28, 50.72, -1.45 +-10.68, -10.00, 51.75, 48.25, 3.50 +-10.68, -10.00, 51.75, 48.25, 3.51 +-10.68, -10.00, 51.76, 48.24, 3.51 +-10.68, -10.00, 51.76, 48.24, 3.52 +-10.68, -10.00, 51.76, 48.24, 3.52 +-10.68, -10.00, 51.76, 48.24, 3.53 +-10.68, -10.00, 51.77, 48.23, 3.53 +-10.68, -10.00, 51.77, 48.23, 3.54 +-10.68, -10.00, 51.77, 48.23, 3.54 +-10.68, -10.00, 51.77, 48.23, 3.55 +-10.68, -10.00, 51.78, 48.22, 3.55 +-10.68, -10.00, 51.78, 48.22, 3.56 +-10.68, -10.00, 51.78, 48.22, 3.56 +-10.68, -10.00, 51.78, 48.22, 3.57 +-10.68, -10.00, 51.79, 48.21, 3.57 +-10.68, -10.00, 51.79, 48.21, 3.58 +-10.68, -10.00, 51.79, 48.21, 3.58 +-10.68, -10.00, 51.79, 48.21, 3.59 +-10.68, -10.00, 51.80, 48.20, 3.59 +-10.68, -10.00, 51.80, 48.20, 3.60 +-10.68, -10.00, 51.80, 48.20, 3.60 +-10.68, -10.00, 51.80, 48.20, 3.61 +-10.68, -10.00, 51.81, 48.19, 3.61 +-10.68, -10.00, 51.81, 48.19, 3.62 +-10.68, -10.00, 51.81, 48.19, 3.62 +-10.68, -10.00, 51.81, 48.19, 3.63 +-10.55, -10.00, 46.77, 53.23, -6.45 +-10.55, -10.00, 51.72, 48.28, 3.44 +-10.55, -10.00, 51.72, 48.28, 3.44 +-10.55, -10.00, 51.72, 48.28, 3.45 +-10.55, -10.00, 51.73, 48.27, 3.45 +-10.55, -10.00, 51.73, 48.27, 3.45 +-10.55, -10.00, 51.73, 48.27, 3.46 +-10.55, -10.00, 51.73, 48.27, 3.46 +-10.55, -10.00, 51.73, 48.27, 3.47 +-10.55, -10.00, 51.74, 48.26, 3.47 +-10.55, -10.00, 51.74, 48.26, 3.48 +-10.55, -10.00, 51.74, 48.26, 3.48 +-10.55, -10.00, 51.74, 48.26, 3.48 +-10.55, -10.00, 51.74, 48.26, 3.49 +-10.55, -10.00, 51.75, 48.25, 3.49 +-10.55, -10.00, 51.75, 48.25, 3.50 +-10.55, -10.00, 51.75, 48.25, 3.50 +-10.55, -10.00, 51.75, 48.25, 3.50 +-10.55, -10.00, 51.75, 48.25, 3.51 +-10.55, -10.00, 51.76, 48.24, 3.51 +-10.55, -10.00, 51.76, 48.24, 3.52 +-10.55, -10.00, 51.76, 48.24, 3.52 +-10.55, -10.00, 51.76, 48.24, 3.52 +-10.55, -10.00, 51.76, 48.24, 3.53 +-10.55, -10.00, 51.77, 48.23, 3.53 +-10.55, -10.00, 51.77, 48.23, 3.54 +-10.55, -10.00, 51.77, 48.23, 3.54 +-10.55, -10.00, 51.77, 48.23, 3.54 +-10.55, -10.00, 51.77, 48.23, 3.55 +-10.55, -10.00, 51.78, 48.22, 3.55 +-10.55, -10.00, 51.78, 48.22, 3.56 +-10.55, -10.00, 51.78, 48.22, 3.56 +-10.55, -10.00, 51.78, 48.22, 3.57 +-10.55, -10.00, 51.78, 48.22, 3.57 +-10.55, -10.00, 51.79, 48.21, 3.57 +-10.55, -10.00, 51.79, 48.21, 3.58 +-10.55, -10.00, 51.79, 48.21, 3.58 +-10.55, -10.00, 51.79, 48.21, 3.59 +-10.55, -10.00, 51.80, 48.20, 3.59 +-10.55, -10.00, 51.80, 48.20, 3.59 +-10.55, -10.00, 51.80, 48.20, 3.60 +-10.55, -10.00, 51.80, 48.20, 3.60 +-10.55, -10.00, 51.80, 48.20, 3.61 +-10.55, -10.00, 51.81, 48.19, 3.61 +-10.55, -10.00, 51.81, 48.19, 3.61 +-10.55, -10.00, 51.81, 48.19, 3.62 +-10.55, -10.00, 51.81, 48.19, 3.62 +-10.55, -10.00, 51.81, 48.19, 3.63 +-10.55, -10.00, 51.82, 48.18, 3.63 +-10.55, -10.00, 51.82, 48.18, 3.64 +-10.55, -10.00, 51.82, 48.18, 3.64 +-10.55, -10.00, 51.82, 48.18, 3.64 +-10.55, -10.00, 51.82, 48.18, 3.65 +-10.55, -10.00, 51.83, 48.17, 3.65 +-10.55, -10.00, 51.83, 48.17, 3.66 +-10.55, -10.00, 51.83, 48.17, 3.66 +-10.55, -10.00, 51.83, 48.17, 3.66 +-10.55, -10.00, 51.83, 48.17, 3.67 +-10.55, -10.00, 51.84, 48.16, 3.67 +-10.55, -10.00, 51.84, 48.16, 3.68 +-10.55, -10.00, 51.84, 48.16, 3.68 +-10.55, -10.00, 51.84, 48.16, 3.68 +-10.55, -10.00, 51.84, 48.16, 3.69 +-10.55, -10.00, 51.85, 48.15, 3.69 +-10.55, -10.00, 51.85, 48.15, 3.70 +-10.48, -10.00, 49.33, 50.67, -1.34 +-10.48, -10.00, 51.80, 48.20, 3.61 +-10.48, -10.00, 51.80, 48.20, 3.61 +-10.48, -10.00, 51.81, 48.19, 3.61 +-10.48, -10.00, 51.81, 48.19, 3.62 +-10.42, -10.00, 49.29, 50.71, -1.42 +-10.42, -10.00, 51.76, 48.24, 3.52 +-10.42, -10.00, 51.76, 48.24, 3.53 +-10.42, -10.00, 51.76, 48.24, 3.53 +-10.42, -10.00, 51.77, 48.23, 3.53 +-10.42, -10.00, 51.77, 48.23, 3.54 +-10.42, -10.00, 51.77, 48.23, 3.54 +-10.42, -10.00, 51.77, 48.23, 3.54 +-10.28, -10.00, 46.73, 53.27, -6.54 +-10.28, -10.00, 51.67, 48.33, 3.35 +-10.28, -10.00, 51.68, 48.32, 3.35 +-10.28, -30.00, 25.00, 75.00, -50.00 +-10.28, -30.00, 36.53, 63.47, -26.95 +-10.28, -30.00, 36.45, 63.55, -27.09 +-10.28, -30.00, 36.38, 63.62, -27.24 +-10.28, -30.00, 36.31, 63.69, -27.39 +-10.22, -30.00, 33.71, 66.29, -32.58 +-10.22, -30.00, 36.11, 63.89, -27.78 +-10.22, -30.00, 36.03, 63.97, -27.93 +-10.22, -30.00, 35.96, 64.04, -28.08 +-10.28, -30.00, 38.41, 61.59, -23.19 +-10.28, -30.00, 35.86, 64.14, -28.28 +-10.28, -30.00, 35.79, 64.21, -28.43 +-10.42, -30.00, 40.76, 59.24, -18.49 +-10.42, -30.00, 35.74, 64.26, -28.52 +-10.48, -30.00, 38.19, 61.81, -23.63 +-10.55, -30.00, 38.16, 61.84, -23.67 +-10.68, -30.00, 40.66, 59.34, -18.68 +-10.68, -30.00, 35.65, 64.35, -28.71 +-10.81, -30.00, 40.62, 59.38, -18.77 +-10.94, -30.00, 40.64, 59.36, -18.71 +-11.01, -30.00, 38.15, 61.85, -23.70 +-11.07, -30.00, 38.13, 61.87, -23.74 +-11.27, -30.00, 43.15, 56.85, -13.70 +-11.34, -30.00, 38.19, 61.81, -23.63 +-11.54, -30.00, 43.21, 56.79, -13.58 +-11.73, -30.00, 43.29, 56.71, -13.42 +-11.87, -30.00, 40.85, 59.15, -18.30 +-12.06, -30.00, 43.40, 56.60, -13.20 +-12.26, -30.00, 43.48, 56.52, -13.03 +-12.39, -30.00, 41.04, 58.96, -17.91 +-12.59, -30.00, 43.60, 56.40, -12.80 +-12.85, -30.00, 46.20, 53.80, -7.59 +-13.05, -30.00, 43.82, 56.18, -12.37 +-13.32, -30.00, 46.42, 53.58, -7.15 +-13.58, -30.00, 46.56, 53.44, -6.88 +-13.71, -30.00, 41.65, 58.35, -16.69 +-13.97, -30.00, 46.74, 53.26, -6.53 +-14.24, -30.00, 46.87, 53.13, -6.25 +-14.50, -30.00, 47.01, 52.99, -5.97 +-14.90, -30.00, 52.20, 47.80, 4.40 +-15.03, -30.00, 42.35, 57.65, -15.29 +-15.42, -30.00, 52.48, 47.52, 4.96 +-15.69, -30.00, 47.68, 52.32, -4.63 +-16.02, -30.00, 50.35, 49.65, 0.70 +-16.28, -30.00, 48.02, 51.98, -3.95 +-16.61, -30.00, 50.69, 49.31, 1.39 +-17.01, -30.00, 53.41, 46.59, 6.82 +-17.27, -30.00, 48.62, 51.38, -2.76 +-17.60, -30.00, 51.29, 48.71, 2.58 +-17.93, -30.00, 51.49, 48.51, 2.99 +-18.19, -30.00, 49.17, 50.83, -1.65 +-18.59, -30.00, 54.37, 45.63, 8.74 +-18.92, -30.00, 52.11, 47.89, 4.21 +-19.25, -30.00, 52.31, 47.69, 4.63 +-19.64, -30.00, 55.04, 44.96, 10.09 +-19.97, -30.00, 52.78, 47.22, 5.56 +-20.30, -30.00, 52.99, 47.01, 5.98 +-20.70, -30.00, 55.72, 44.28, 11.45 +-21.03, -30.00, 53.47, 46.53, 6.93 +-21.36, -30.00, 53.68, 46.32, 7.36 +-21.75, -30.00, 56.42, 43.58, 12.84 +-22.15, -30.00, 56.69, 43.31, 13.37 +-22.54, -30.00, 56.95, 43.05, 13.91 +-22.87, -30.00, 54.70, 45.30, 9.41 +-23.20, -30.00, 54.92, 45.08, 9.85 +-23.60, -30.00, 57.67, 42.33, 15.34 +-23.93, -30.00, 55.42, 44.58, 10.84 +-24.39, -30.00, 60.69, 39.31, 21.38 +-24.72, -30.00, 55.97, 44.03, 11.95 +-25.05, -30.00, 56.20, 43.80, 12.41 +-25.44, -30.00, 58.95, 41.05, 17.91 +-25.77, -30.00, 56.71, 43.29, 13.43 +-26.10, -30.00, 56.95, 43.05, 13.89 +-26.50, -30.00, 59.70, 40.30, 19.40 +-26.83, -30.00, 57.47, 42.53, 14.93 +-27.16, -30.00, 57.70, 42.30, 15.40 +-27.55, -30.00, 60.46, 39.54, 20.92 +-27.88, -30.00, 58.23, 41.77, 16.46 +-28.21, -30.00, 58.47, 41.53, 16.94 +-28.48, -30.00, 56.19, 43.81, 12.38 +-28.87, -30.00, 61.43, 38.57, 22.85 +-29.20, -30.00, 59.20, 40.80, 18.40 +-29.47, -30.00, 56.92, 43.08, 13.84 +-29.79, -30.00, 59.64, 40.36, 19.28 +-30.06, -30.00, 57.37, 42.63, 14.73 +-30.32, -30.00, 57.56, 42.44, 15.13 +-30.59, -30.00, 57.76, 42.24, 15.53 +-30.85, -30.00, 57.97, 42.03, 15.93 +-31.25, -30.00, 63.21, 36.79, 26.42 +-31.51, -30.00, 58.47, 41.53, 16.94 +-31.77, -30.00, 58.67, 41.33, 17.35 +-31.90, -30.00, 53.84, 46.16, 7.67 +-32.17, -30.00, 58.99, 41.01, 17.97 +-32.43, -30.00, 59.19, 40.81, 18.39 +-32.70, -30.00, 59.40, 40.60, 18.80 +-32.89, -30.00, 57.09, 42.91, 14.18 +-33.09, -30.00, 57.25, 42.75, 14.50 +-33.35, -30.00, 59.93, 40.07, 19.86 +-33.49, -30.00, 55.10, 44.90, 10.20 +-33.68, -30.00, 57.73, 42.27, 15.47 +-33.95, -30.00, 60.42, 39.58, 20.84 +-34.01, -30.00, 53.07, 46.93, 6.13 +-34.21, -30.00, 58.17, 41.83, 16.35 +-34.41, -30.00, 58.34, 41.66, 16.68 +-34.54, -30.00, 55.98, 44.02, 11.97 +-34.74, -30.00, 58.62, 41.38, 17.24 +-34.80, -30.00, 53.74, 46.26, 7.49 +-34.94, -30.00, 56.33, 43.67, 12.67 +-35.07, -30.00, 56.45, 43.55, 12.90 +-35.27, -30.00, 59.09, 40.91, 18.18 +-35.33, -30.00, 54.22, 45.78, 8.43 +-35.46, -30.00, 56.81, 43.19, 13.62 +-35.53, -30.00, 54.41, 45.59, 8.81 +-35.60, -30.00, 54.48, 45.52, 8.95 +-35.79, -30.00, 59.59, 40.41, 19.18 +-35.86, -30.00, 54.72, 45.28, 9.44 +-35.86, -30.00, 52.27, 47.73, 4.54 +-35.99, -30.00, 57.33, 42.67, 14.67 +-36.06, -30.00, 54.93, 45.07, 9.87 +-36.12, -30.00, 55.01, 44.99, 10.01 +-36.25, -30.00, 57.60, 42.40, 15.20 +-36.32, -30.00, 55.20, 44.80, 10.40 +-36.32, -30.00, 52.75, 47.25, 5.51 +-36.32, -30.00, 52.78, 47.22, 5.56 +-36.39, -30.00, 55.32, 44.68, 10.65 +-36.52, -30.00, 57.92, 42.08, 15.84 +-36.52, -30.00, 53.00, 47.00, 6.00 +-36.52, -30.00, 53.02, 46.98, 6.05 +-36.52, -30.00, 53.05, 46.95, 6.10 +-36.52, -30.00, 53.07, 46.93, 6.14 +-36.52, -30.00, 53.10, 46.90, 6.19 +-36.58, -30.00, 55.64, 44.36, 11.29 +-36.58, -30.00, 53.20, 46.80, 6.39 +-36.58, -30.00, 53.22, 46.78, 6.44 +-36.58, -30.00, 53.24, 46.76, 6.49 +-36.58, -30.00, 53.27, 46.73, 6.54 +-36.58, -30.00, 53.29, 46.71, 6.59 +-36.58, -30.00, 53.32, 46.68, 6.64 +-36.52, -30.00, 50.82, 49.18, 1.64 +-36.52, -30.00, 53.32, 46.68, 6.64 +-36.52, -30.00, 53.34, 46.66, 6.69 +-36.52, -30.00, 53.37, 46.63, 6.73 +-36.39, -30.00, 48.35, 51.65, -3.30 +-36.32, -30.00, 50.79, 49.21, 1.59 +-36.25, -30.00, 50.77, 49.23, 1.54 +-36.12, -30.00, 48.22, 51.78, -3.56 +-36.12, -30.00, 53.19, 46.81, 6.38 +-36.06, -30.00, 50.69, 49.31, 1.38 +-36.06, -30.00, 53.18, 46.82, 6.37 +-35.99, -30.00, 50.68, 49.32, 1.37 +-35.86, -30.00, 48.14, 51.86, -3.73 +-35.86, -30.00, 53.10, 46.90, 6.20 +-35.79, -30.00, 50.60, 49.40, 1.20 +-35.73, -30.00, 50.57, 49.43, 1.15 +-35.60, -30.00, 48.02, 51.98, -3.95 +-35.53, -30.00, 50.47, 49.53, 0.94 +-35.46, -30.00, 50.44, 49.56, 0.88 +-35.33, -30.00, 47.89, 52.11, -4.22 +-35.27, -30.00, 50.33, 49.67, 0.66 +-35.20, -30.00, 50.30, 49.70, 0.60 +-35.07, -30.00, 47.75, 52.25, -4.50 +-35.07, -30.00, 52.71, 47.29, 5.42 +-34.94, -30.00, 47.69, 52.31, -4.63 +-34.94, -30.00, 52.65, 47.35, 5.30 +-34.80, -30.00, 47.62, 52.38, -4.75 +-34.74, -30.00, 50.06, 49.94, 0.13 +-34.67, -30.00, 50.03, 49.97, 0.07 +-34.67, -30.00, 52.52, 47.48, 5.04 +-34.54, -30.00, 47.50, 52.50, -5.01 +-34.48, -30.00, 49.94, 50.06, -0.13 +-34.48, -30.00, 52.42, 47.58, 4.85 +-34.41, -30.00, 49.92, 50.08, -0.16 +-34.28, -30.00, 47.37, 52.63, -5.27 +-34.21, -30.00, 49.80, 50.20, -0.39 +-34.15, -30.00, 49.77, 50.23, -0.46 +-34.01, -30.00, 47.21, 52.79, -5.57 +-34.01, -30.00, 52.17, 47.83, 4.35 +-33.95, -30.00, 49.67, 50.33, -0.67 +-33.88, -30.00, 49.63, 50.37, -0.74 +-33.75, -30.00, 47.07, 52.93, -5.85 +-33.75, -30.00, 52.03, 47.97, 4.06 +-33.68, -30.00, 49.52, 50.48, -0.95 +-33.68, -30.00, 52.01, 47.99, 4.02 +-33.62, -30.00, 49.50, 50.50, -0.99 +-33.49, -30.00, 46.94, 53.06, -6.11 +-33.49, -30.00, 51.90, 48.10, 3.80 +-33.42, -30.00, 49.39, 50.61, -1.21 +-33.42, -30.00, 51.88, 48.12, 3.76 +-33.35, -30.00, 49.37, 50.63, -1.26 +-33.35, -30.00, 51.85, 48.15, 3.71 +-33.22, -30.00, 46.82, 53.18, -6.35 +-33.22, -30.00, 51.78, 48.22, 3.56 +-33.16, -30.00, 49.27, 50.73, -1.46 +-33.16, -30.00, 51.75, 48.25, 3.51 +-33.09, -30.00, 49.24, 50.76, -1.51 +-33.09, -30.00, 51.73, 48.27, 3.45 +-33.09, -30.00, 51.74, 48.26, 3.48 +-32.96, -30.00, 46.71, 53.29, -6.59 +-32.96, -30.00, 51.66, 48.34, 3.32 +-32.96, -30.00, 51.67, 48.33, 3.35 +-32.89, -30.00, 49.16, 50.84, -1.67 +-32.89, -30.00, 51.65, 48.35, 3.29 +-32.89, -30.00, 51.66, 48.34, 3.31 +-32.89, -30.00, 51.67, 48.33, 3.33 +-32.89, -30.00, 51.68, 48.32, 3.36 +-32.89, -30.00, 51.69, 48.31, 3.38 +-32.83, -30.00, 49.18, 50.82, -1.64 +-32.83, -30.00, 51.66, 48.34, 3.32 +-32.83, -30.00, 51.67, 48.33, 3.34 +-32.83, -30.00, 51.68, 48.32, 3.36 +-32.70, -30.00, 46.65, 53.35, -6.70 +-32.70, -30.00, 51.60, 48.40, 3.21 +-32.70, -30.00, 51.61, 48.39, 3.23 +-32.70, -30.00, 51.62, 48.38, 3.25 +-32.70, -30.00, 51.63, 48.37, 3.27 +-32.70, -30.00, 51.64, 48.36, 3.29 +-32.70, -30.00, 51.65, 48.35, 3.31 +-32.70, -30.00, 51.66, 48.34, 3.33 +-32.70, -30.00, 51.67, 48.33, 3.35 +-32.70, -30.00, 51.68, 48.32, 3.37 +-32.70, -30.00, 51.69, 48.31, 3.39 +-32.70, -30.00, 51.70, 48.30, 3.41 +-32.70, -30.00, 51.71, 48.29, 3.43 +-32.70, -30.00, 51.72, 48.28, 3.45 +-32.70, -30.00, 51.73, 48.27, 3.47 +-32.70, -30.00, 51.74, 48.26, 3.49 +-32.70, -30.00, 51.75, 48.25, 3.51 +-32.70, -30.00, 51.76, 48.24, 3.53 +-32.70, -30.00, 51.77, 48.23, 3.55 +-32.83, -30.00, 56.83, 43.17, 13.66 +-32.83, -30.00, 51.89, 48.11, 3.79 +-32.83, -30.00, 51.91, 48.09, 3.81 +-32.83, -30.00, 51.92, 48.08, 3.83 +-32.83, -30.00, 51.93, 48.07, 3.85 +-32.89, -30.00, 54.46, 45.54, 8.92 +-32.89, -30.00, 52.00, 48.00, 4.00 +-32.89, -30.00, 52.01, 47.99, 4.02 +-32.89, -30.00, 52.02, 47.98, 4.04 +-32.89, -30.00, 52.03, 47.97, 4.06 +-32.89, -30.00, 52.04, 47.96, 4.08 +-32.89, -30.00, 52.05, 47.95, 4.10 +-32.89, -30.00, 52.06, 47.94, 4.13 +-32.89, -30.00, 52.07, 47.93, 4.15 +-32.89, -30.00, 52.08, 47.92, 4.17 +-32.89, -30.00, 52.10, 47.90, 4.19 +-32.96, -30.00, 54.63, 45.37, 9.26 +-32.89, -30.00, 49.65, 50.35, -0.71 +-32.96, -30.00, 54.65, 45.35, 9.30 +-32.96, -30.00, 52.19, 47.81, 4.38 +-32.96, -30.00, 52.20, 47.80, 4.40 +-32.96, -30.00, 52.21, 47.79, 4.42 +-32.96, -30.00, 52.22, 47.78, 4.44 +-32.96, -30.00, 52.23, 47.77, 4.47 +-32.96, -30.00, 52.24, 47.76, 4.49 +-33.09, -30.00, 57.30, 42.70, 14.60 +-33.09, -30.00, 52.37, 47.63, 4.73 +-33.09, -30.00, 52.38, 47.62, 4.76 +-33.09, -30.00, 52.39, 47.61, 4.78 +-33.09, -30.00, 52.40, 47.60, 4.80 +-33.09, -30.00, 52.41, 47.59, 4.83 +-33.09, -30.00, 52.42, 47.58, 4.85 +-32.96, -30.00, 47.39, 52.61, -5.21 +-32.96, -30.00, 52.35, 47.65, 4.70 +-32.96, -30.00, 52.36, 47.64, 4.72 +-32.96, -30.00, 52.37, 47.63, 4.74 +-33.09, -30.00, 57.42, 42.58, 14.85 +-33.09, -30.00, 52.49, 47.51, 4.98 +-33.09, -30.00, 52.50, 47.50, 5.01 +-33.09, -30.00, 52.52, 47.48, 5.03 +-33.09, -30.00, 52.53, 47.47, 5.05 +-33.09, -30.00, 52.54, 47.46, 5.08 +-33.09, -30.00, 52.55, 47.45, 5.10 +-33.09, -30.00, 52.56, 47.44, 5.12 +-33.09, -30.00, 52.57, 47.43, 5.15 +-32.96, -30.00, 47.54, 52.46, -4.92 +-33.09, -30.00, 57.54, 42.46, 15.08 +-32.96, -30.00, 47.56, 52.44, -4.87 +-32.96, -30.00, 52.52, 47.48, 5.04 +-32.96, -30.00, 52.53, 47.47, 5.06 +-32.96, -30.00, 52.54, 47.46, 5.08 +-32.96, -30.00, 52.55, 47.45, 5.11 +-32.96, -30.00, 52.56, 47.44, 5.13 +-32.96, -30.00, 52.57, 47.43, 5.15 +-32.89, -30.00, 50.06, 49.94, 0.13 +-32.89, -30.00, 52.55, 47.45, 5.09 +-32.89, -30.00, 52.56, 47.44, 5.12 +-32.89, -30.00, 52.57, 47.43, 5.14 +-32.89, -30.00, 52.58, 47.42, 5.16 +-32.89, -30.00, 52.59, 47.41, 5.18 +-32.89, -30.00, 52.60, 47.40, 5.20 +-32.83, -30.00, 50.09, 49.91, 0.18 +-32.83, -30.00, 52.57, 47.43, 5.15 +-32.83, -30.00, 52.58, 47.42, 5.17 +-32.83, -30.00, 52.59, 47.41, 5.19 +-32.83, -30.00, 52.60, 47.40, 5.21 +-32.70, -30.00, 47.57, 52.43, -4.86 +-32.70, -30.00, 52.53, 47.47, 5.05 +-32.70, -30.00, 52.54, 47.46, 5.07 +-32.70, -30.00, 52.55, 47.45, 5.09 +-32.70, -30.00, 52.56, 47.44, 5.11 +-32.63, -30.00, 50.05, 49.95, 0.09 +-32.63, -30.00, 52.53, 47.47, 5.05 +-32.63, -30.00, 52.54, 47.46, 5.07 +-32.56, -30.00, 50.02, 49.98, 0.05 +-32.56, -30.00, 52.51, 47.49, 5.01 +-32.56, -30.00, 52.52, 47.48, 5.03 +-32.43, -30.00, 47.48, 52.52, -5.04 +-32.43, -30.00, 52.44, 47.56, 4.87 +-32.43, -30.00, 52.44, 47.56, 4.89 +-32.43, -30.00, 52.45, 47.55, 4.91 +-32.43, -30.00, 52.46, 47.54, 4.93 +-32.43, -30.00, 52.47, 47.53, 4.94 +-32.43, -30.00, 52.48, 47.52, 4.96 +-32.37, -30.00, 49.97, 50.03, -0.06 +-32.37, -30.00, 52.45, 47.55, 4.90 +-32.37, -30.00, 52.46, 47.54, 4.92 +-32.37, -30.00, 52.47, 47.53, 4.93 +-32.30, -30.00, 49.95, 50.05, -0.09 +-32.30, -30.00, 52.43, 47.57, 4.87 +-32.30, -30.00, 52.44, 47.56, 4.89 +-32.30, -30.00, 52.45, 47.55, 4.90 +-32.17, -30.00, 47.42, 52.58, -5.16 +-32.17, -30.00, 52.37, 47.63, 4.74 +-32.17, -30.00, 52.38, 47.62, 4.76 +-32.17, -30.00, 52.39, 47.61, 4.77 +-32.17, -30.00, 52.39, 47.61, 4.79 +-32.17, -30.00, 52.40, 47.60, 4.80 +-32.17, -30.00, 52.41, 47.59, 4.82 +-32.17, -30.00, 52.42, 47.58, 4.84 +-32.17, -30.00, 52.43, 47.57, 4.85 +-32.17, -30.00, 52.43, 47.57, 4.87 +-32.10, -30.00, 49.92, 50.08, -0.16 +-32.10, -30.00, 52.40, 47.60, 4.80 +-32.10, -30.00, 52.41, 47.59, 4.82 +-32.04, -30.00, 49.90, 50.10, -0.21 +-32.04, -30.00, 52.37, 47.63, 4.75 +-32.04, -30.00, 52.38, 47.62, 4.76 +-31.90, -30.00, 47.35, 52.65, -5.31 +-31.90, -30.00, 52.30, 47.70, 4.60 +-31.90, -30.00, 52.30, 47.70, 4.61 +-31.90, -30.00, 52.31, 47.69, 4.62 +-31.90, -30.00, 52.32, 47.68, 4.64 +-31.90, -30.00, 52.33, 47.67, 4.65 +-31.90, -30.00, 52.33, 47.67, 4.67 +-31.90, -30.00, 52.34, 47.66, 4.68 +-31.90, -30.00, 52.35, 47.65, 4.70 +-31.90, -30.00, 52.35, 47.65, 4.71 +-31.84, -30.00, 49.84, 50.16, -0.32 +-31.84, -30.00, 52.32, 47.68, 4.64 +-31.84, -30.00, 52.33, 47.67, 4.65 +-31.84, -30.00, 52.33, 47.67, 4.67 +-31.77, -30.00, 49.82, 50.18, -0.36 +-31.77, -30.00, 52.30, 47.70, 4.59 +-31.77, -30.00, 52.30, 47.70, 4.61 +-31.77, -30.00, 52.31, 47.69, 4.62 +-31.77, -30.00, 52.32, 47.68, 4.63 +-31.77, -30.00, 52.32, 47.68, 4.65 +-31.64, -30.00, 47.29, 52.71, -5.43 +-31.64, -30.00, 52.24, 47.76, 4.47 +-31.64, -30.00, 52.24, 47.76, 4.49 +-31.64, -30.00, 52.25, 47.75, 4.50 +-31.64, -30.00, 52.26, 47.74, 4.51 +-31.64, -30.00, 52.26, 47.74, 4.52 +-31.64, -30.00, 52.27, 47.73, 4.54 +-31.57, -30.00, 49.75, 50.25, -0.50 +-31.57, -30.00, 52.23, 47.77, 4.46 +-31.57, -30.00, 52.24, 47.76, 4.47 +-31.57, -30.00, 52.24, 47.76, 4.48 +-31.51, -30.00, 49.73, 50.27, -0.55 +-31.51, -30.00, 52.20, 47.80, 4.41 +-31.51, -30.00, 52.21, 47.79, 4.42 +-31.51, -30.00, 52.21, 47.79, 4.43 +-31.51, -30.00, 52.22, 47.78, 4.44 +-31.51, -30.00, 52.23, 47.77, 4.45 +-31.51, -30.00, 52.23, 47.77, 4.46 +-31.51, -30.00, 52.24, 47.76, 4.48 +-31.51, -30.00, 52.24, 47.76, 4.49 +-31.51, -30.00, 52.25, 47.75, 4.50 +-31.51, -30.00, 52.25, 47.75, 4.51 +-31.51, -30.00, 52.26, 47.74, 4.52 +-31.38, -30.00, 47.22, 52.78, -5.55 +-31.38, -30.00, 52.17, 47.83, 4.34 +-31.38, -30.00, 52.18, 47.82, 4.35 +-31.38, -30.00, 52.18, 47.82, 4.36 +-31.38, -30.00, 52.19, 47.81, 4.37 +-31.31, -30.00, 49.67, 50.33, -0.66 +-31.31, -30.00, 52.15, 47.85, 4.30 +-31.31, -30.00, 52.15, 47.85, 4.30 +-31.31, -30.00, 52.16, 47.84, 4.31 +-31.31, -30.00, 52.16, 47.84, 4.32 +-31.38, -30.00, 54.69, 45.31, 9.38 +-31.31, -30.00, 49.70, 50.30, -0.60 +-31.31, -30.00, 52.18, 47.82, 4.35 +-31.31, -30.00, 52.18, 47.82, 4.36 +-31.31, -30.00, 52.19, 47.81, 4.37 +-31.31, -30.00, 52.19, 47.81, 4.38 +-31.31, -30.00, 52.20, 47.80, 4.39 +-31.31, -30.00, 52.20, 47.80, 4.40 +-31.25, -30.00, 49.69, 50.31, -0.63 +-31.25, -30.00, 52.16, 47.84, 4.32 +-31.25, -30.00, 52.17, 47.83, 4.33 +-31.11, -30.00, 47.13, 52.87, -5.74 +-31.11, -30.00, 52.08, 47.92, 4.15 +-31.11, -30.00, 52.08, 47.92, 4.16 +-31.11, -30.00, 52.08, 47.92, 4.17 +-31.11, -30.00, 52.09, 47.91, 4.18 +-31.11, -30.00, 52.09, 47.91, 4.19 +-31.11, -30.00, 52.10, 47.90, 4.19 +-31.11, -30.00, 52.10, 47.90, 4.20 +-31.11, -30.00, 52.11, 47.89, 4.21 +-31.11, -30.00, 52.11, 47.89, 4.22 +-31.11, -30.00, 52.11, 47.89, 4.23 +-31.05, -30.00, 49.60, 50.40, -0.81 +-31.05, -30.00, 52.07, 47.93, 4.14 +-31.05, -30.00, 52.08, 47.92, 4.15 +-30.98, -30.00, 49.56, 50.44, -0.88 +-30.98, -30.00, 52.03, 47.97, 4.07 +-30.98, -30.00, 52.04, 47.96, 4.07 +-30.98, -30.00, 52.04, 47.96, 4.08 +-30.98, -30.00, 52.04, 47.96, 4.09 +-30.98, -30.00, 52.05, 47.95, 4.10 +-30.85, -30.00, 47.01, 52.99, -5.98 +-30.98, -30.00, 57.00, 43.00, 14.00 +-30.98, -30.00, 52.06, 47.94, 4.12 +-30.98, -30.00, 52.06, 47.94, 4.13 +-30.98, -30.00, 52.07, 47.93, 4.13 +-30.98, -30.00, 52.07, 47.93, 4.14 +-30.98, -30.00, 52.07, 47.93, 4.15 +-30.85, -30.00, 47.03, 52.97, -5.93 +-30.85, -30.00, 51.98, 48.02, 3.96 +-30.85, -30.00, 51.98, 48.02, 3.97 +-30.85, -30.00, 51.99, 48.01, 3.98 +-30.78, -30.00, 49.47, 50.53, -1.06 +-30.78, -30.00, 51.94, 48.06, 3.89 +-30.78, -30.00, 51.95, 48.05, 3.89 +-30.78, -30.00, 51.95, 48.05, 3.90 +-30.78, -30.00, 51.95, 48.05, 3.91 +-30.78, -30.00, 51.96, 48.04, 3.91 +-30.85, -30.00, 54.48, 45.52, 8.96 +-30.85, -30.00, 52.01, 47.99, 4.02 +-30.85, -30.00, 52.01, 47.99, 4.03 +-30.85, -30.00, 52.02, 47.98, 4.04 +-30.85, -30.00, 52.02, 47.98, 4.04 +-30.85, -30.00, 52.02, 47.98, 4.05 +-30.85, -30.00, 52.03, 47.97, 4.06 +-30.85, -30.00, 52.03, 47.97, 4.06 +-30.85, -30.00, 52.03, 47.97, 4.07 +-30.85, -30.00, 52.04, 47.96, 4.07 +-30.85, -30.00, 52.04, 47.96, 4.08 +-30.85, -30.00, 52.04, 47.96, 4.09 +-30.85, -30.00, 52.05, 47.95, 4.09 +-30.85, -30.00, 52.05, 47.95, 4.10 +-30.85, -30.00, 52.05, 47.95, 4.11 +-30.85, -30.00, 52.06, 47.94, 4.11 +-30.98, -30.00, 57.10, 42.90, 14.21 +-30.98, -30.00, 52.16, 47.84, 4.32 +-30.98, -30.00, 52.17, 47.83, 4.33 +-30.98, -30.00, 52.17, 47.83, 4.34 +-30.98, -30.00, 52.17, 47.83, 4.35 +-30.98, -30.00, 52.18, 47.82, 4.35 +-30.98, -30.00, 52.18, 47.82, 4.36 +-31.05, -30.00, 54.71, 45.29, 9.41 +-30.98, -30.00, 49.72, 50.28, -0.57 +-31.05, -30.00, 54.71, 45.29, 9.43 +-30.98, -30.00, 49.72, 50.28, -0.55 +-30.98, -30.00, 52.20, 47.80, 4.40 +-30.98, -30.00, 52.20, 47.80, 4.41 +-30.98, -30.00, 52.21, 47.79, 4.41 +-30.98, -30.00, 52.21, 47.79, 4.42 +-31.05, -30.00, 54.74, 45.26, 9.47 +-31.05, -30.00, 52.27, 47.73, 4.54 +-31.05, -30.00, 52.27, 47.73, 4.54 +-31.05, -30.00, 52.28, 47.72, 4.55 +-31.11, -30.00, 54.80, 45.20, 9.60 +-31.11, -30.00, 52.33, 47.67, 4.67 +-31.11, -30.00, 52.34, 47.66, 4.68 +-31.11, -30.00, 52.34, 47.66, 4.68 +-31.11, -30.00, 52.35, 47.65, 4.69 +-31.11, -30.00, 52.35, 47.65, 4.70 +-31.11, -30.00, 52.35, 47.65, 4.71 +-31.11, -30.00, 52.36, 47.64, 4.72 +-31.11, -30.00, 52.36, 47.64, 4.73 +-31.11, -30.00, 52.37, 47.63, 4.73 +-31.11, -30.00, 52.37, 47.63, 4.74 +-31.11, -30.00, 52.38, 47.62, 4.75 +-31.11, -30.00, 52.38, 47.62, 4.76 +-31.11, -30.00, 52.38, 47.62, 4.77 +-31.11, -30.00, 52.39, 47.61, 4.78 +-31.25, -30.00, 57.44, 42.56, 14.87 +-31.25, -30.00, 52.50, 47.50, 4.99 +-31.25, -30.00, 52.50, 47.50, 5.00 +-31.25, -30.00, 52.51, 47.49, 5.01 +-31.25, -30.00, 52.51, 47.49, 5.02 +-31.25, -30.00, 52.51, 47.49, 5.03 +-31.25, -30.00, 52.52, 47.48, 5.04 +-31.25, -30.00, 52.52, 47.48, 5.05 +-31.11, -30.00, 47.49, 52.51, -5.03 +-31.11, -30.00, 52.43, 47.57, 4.87 +-31.11, -30.00, 52.44, 47.56, 4.88 +-31.11, -30.00, 52.44, 47.56, 4.88 +-31.11, -30.00, 52.45, 47.55, 4.89 +-31.11, -30.00, 52.45, 47.55, 4.90 +-31.11, -30.00, 52.45, 47.55, 4.91 +-31.11, -30.00, 52.46, 47.54, 4.92 +-31.11, -30.00, 52.46, 47.54, 4.93 +-31.11, -30.00, 52.47, 47.53, 4.93 +-31.11, -30.00, 52.47, 47.53, 4.94 +-31.11, -30.00, 52.48, 47.52, 4.95 +-31.11, -30.00, 52.48, 47.52, 4.96 +-31.11, -30.00, 52.48, 47.52, 4.97 +-31.11, -30.00, 52.49, 47.51, 4.98 +-31.11, -30.00, 52.49, 47.51, 4.98 +-31.11, -30.00, 52.50, 47.50, 4.99 +-31.11, -30.00, 52.50, 47.50, 5.00 +-31.11, -30.00, 52.50, 47.50, 5.01 +-31.11, -30.00, 52.51, 47.49, 5.02 +-31.05, -30.00, 49.99, 50.01, -0.02 +-31.05, -30.00, 52.47, 47.53, 4.93 +-31.05, -30.00, 52.47, 47.53, 4.94 +-31.05, -30.00, 52.48, 47.52, 4.95 +-31.05, -30.00, 52.48, 47.52, 4.96 +-31.05, -30.00, 52.48, 47.52, 4.97 +-31.05, -30.00, 52.49, 47.51, 4.97 +-31.05, -30.00, 52.49, 47.51, 4.98 +-31.05, -30.00, 52.49, 47.51, 4.99 +-31.11, -30.00, 55.02, 44.98, 10.04 +-31.11, -30.00, 52.55, 47.45, 5.11 +-31.05, -30.00, 50.04, 49.96, 0.07 +-31.05, -30.00, 52.51, 47.49, 5.02 +-31.11, -30.00, 55.04, 44.96, 10.07 +-31.05, -30.00, 50.05, 49.95, 0.09 +-31.05, -30.00, 52.52, 47.48, 5.05 +-31.05, -30.00, 52.53, 47.47, 5.05 +-31.05, -30.00, 52.53, 47.47, 5.06 +-31.05, -30.00, 52.53, 47.47, 5.07 +-31.05, -30.00, 52.54, 47.46, 5.08 +-31.05, -30.00, 52.54, 47.46, 5.09 +-31.05, -30.00, 52.55, 47.45, 5.09 +-31.05, -30.00, 52.55, 47.45, 5.10 +-31.05, -30.00, 52.55, 47.45, 5.11 +-31.05, -30.00, 52.56, 47.44, 5.12 +-31.05, -30.00, 52.56, 47.44, 5.12 +-31.05, -30.00, 52.57, 47.43, 5.13 +-31.05, -30.00, 52.57, 47.43, 5.14 +-31.05, -30.00, 52.57, 47.43, 5.15 +-31.05, -30.00, 52.58, 47.42, 5.16 +-31.05, -30.00, 52.58, 47.42, 5.16 +-31.05, -30.00, 52.59, 47.41, 5.17 +-31.05, -30.00, 52.59, 47.41, 5.18 +-31.05, -30.00, 52.59, 47.41, 5.19 +-31.05, -30.00, 52.60, 47.40, 5.20 +-31.05, -30.00, 52.60, 47.40, 5.20 +-31.05, -30.00, 52.61, 47.39, 5.21 +-31.05, -30.00, 52.61, 47.39, 5.22 +-31.05, -30.00, 52.61, 47.39, 5.23 +-31.05, -30.00, 52.62, 47.38, 5.23 +-31.05, -30.00, 52.62, 47.38, 5.24 +-31.05, -30.00, 52.63, 47.37, 5.25 +-31.05, -30.00, 52.63, 47.37, 5.26 +-31.05, -30.00, 52.63, 47.37, 5.27 +-31.05, -30.00, 52.64, 47.36, 5.27 +-31.05, -30.00, 52.64, 47.36, 5.28 +-31.05, -30.00, 52.64, 47.36, 5.29 +-31.05, -30.00, 52.65, 47.35, 5.30 +-31.05, -30.00, 52.65, 47.35, 5.31 +-30.98, -30.00, 50.13, 49.87, 0.27 +-30.98, -30.00, 52.61, 47.39, 5.22 +-31.05, -30.00, 55.14, 44.86, 10.27 +-31.05, -30.00, 52.67, 47.33, 5.34 +-31.05, -30.00, 52.67, 47.33, 5.34 +-31.05, -30.00, 52.68, 47.32, 5.35 +-31.05, -30.00, 52.68, 47.32, 5.36 +-31.05, -30.00, 52.68, 47.32, 5.37 +-31.05, -30.00, 52.69, 47.31, 5.37 +-31.05, -30.00, 52.69, 47.31, 5.38 +-31.05, -30.00, 52.70, 47.30, 5.39 +-31.05, -30.00, 52.70, 47.30, 5.40 +-31.05, -30.00, 52.70, 47.30, 5.41 +-31.05, -30.00, 52.71, 47.29, 5.41 +-30.98, -30.00, 50.19, 49.81, 0.38 +-30.98, -30.00, 52.67, 47.33, 5.33 +-30.98, -30.00, 52.67, 47.33, 5.34 +-30.98, -30.00, 52.67, 47.33, 5.34 +-30.98, -30.00, 52.68, 47.32, 5.35 +-30.98, -30.00, 52.68, 47.32, 5.36 +-30.98, -30.00, 52.68, 47.32, 5.37 +-30.98, -30.00, 52.69, 47.31, 5.37 +-30.98, -30.00, 52.69, 47.31, 5.38 +-30.98, -30.00, 52.69, 47.31, 5.39 +-30.98, -30.00, 52.70, 47.30, 5.40 +-30.98, -30.00, 52.70, 47.30, 5.40 +-30.98, -30.00, 52.71, 47.29, 5.41 +-30.98, -30.00, 52.71, 47.29, 5.42 +-30.98, -30.00, 52.71, 47.29, 5.43 +-30.98, -30.00, 52.72, 47.28, 5.43 +-30.98, -30.00, 52.72, 47.28, 5.44 +-30.98, -30.00, 52.72, 47.28, 5.45 +-30.98, -30.00, 52.73, 47.27, 5.46 +-30.98, -30.00, 52.73, 47.27, 5.46 +-30.98, -30.00, 52.73, 47.27, 5.47 +-30.98, -30.00, 52.74, 47.26, 5.48 +-30.85, -30.00, 47.70, 52.30, -4.60 +-30.98, -30.00, 57.69, 42.31, 15.38 +-30.85, -30.00, 47.71, 52.29, -4.59 +-30.98, -30.00, 57.70, 42.30, 15.39 +-30.98, -30.00, 52.76, 47.24, 5.51 +-30.98, -30.00, 52.76, 47.24, 5.52 +-30.85, -30.00, 47.72, 52.28, -4.56 +-30.85, -30.00, 52.67, 47.33, 5.33 +-30.85, -30.00, 52.67, 47.33, 5.34 +-30.85, -30.00, 52.67, 47.33, 5.35 +-30.85, -30.00, 52.68, 47.32, 5.35 +-30.78, -30.00, 50.16, 49.84, 0.32 +-30.78, -30.00, 52.63, 47.37, 5.27 +-30.78, -30.00, 52.64, 47.36, 5.27 +-30.78, -30.00, 52.64, 47.36, 5.28 +-30.78, -30.00, 52.64, 47.36, 5.28 +-30.78, -30.00, 52.64, 47.36, 5.29 +-30.78, -30.00, 52.65, 47.35, 5.30 +-30.78, -30.00, 52.65, 47.35, 5.30 +-30.78, -30.00, 52.65, 47.35, 5.31 +-30.78, -30.00, 52.66, 47.34, 5.31 +-30.72, -30.00, 50.14, 49.86, 0.28 +-30.72, -30.00, 52.61, 47.39, 5.23 +-30.72, -30.00, 52.62, 47.38, 5.23 +-30.72, -30.00, 52.62, 47.38, 5.24 +-30.72, -30.00, 52.62, 47.38, 5.24 +-30.72, -30.00, 52.62, 47.38, 5.25 +-30.72, -30.00, 52.63, 47.37, 5.25 +-30.59, -30.00, 47.59, 52.41, -4.83 +-30.59, -30.00, 52.53, 47.47, 5.06 +-30.59, -30.00, 52.53, 47.47, 5.07 +-30.59, -30.00, 52.54, 47.46, 5.07 +-30.59, -30.00, 52.54, 47.46, 5.08 +-30.59, -30.00, 52.54, 47.46, 5.08 +-30.59, -30.00, 52.54, 47.46, 5.09 +-30.59, -30.00, 52.54, 47.46, 5.09 +-30.59, -30.00, 52.55, 47.45, 5.09 +-30.59, -30.00, 52.55, 47.45, 5.10 +-30.59, -30.00, 52.55, 47.45, 5.10 +-30.59, -30.00, 52.55, 47.45, 5.11 +-30.59, -30.00, 52.56, 47.44, 5.11 +-30.59, -30.00, 52.56, 47.44, 5.12 +-30.59, -30.00, 52.56, 47.44, 5.12 +-30.59, -30.00, 52.56, 47.44, 5.12 +-30.59, -30.00, 52.56, 47.44, 5.13 +-30.52, -30.00, 50.05, 49.95, 0.09 +-30.52, -30.00, 52.52, 47.48, 5.04 +-30.59, -30.00, 55.04, 44.96, 10.09 +-30.52, -30.00, 50.05, 49.95, 0.10 +-30.52, -30.00, 52.53, 47.47, 5.05 +-30.59, -30.00, 55.05, 44.95, 10.10 +-30.59, -30.00, 52.58, 47.42, 5.16 +-30.52, -30.00, 50.06, 49.94, 0.12 +-30.52, -30.00, 52.53, 47.47, 5.07 +-30.52, -30.00, 52.54, 47.46, 5.07 +-30.52, -30.00, 52.54, 47.46, 5.07 +-30.52, -30.00, 52.54, 47.46, 5.08 +-30.52, -30.00, 52.54, 47.46, 5.08 +-30.52, -30.00, 52.54, 47.46, 5.09 +-30.45, -30.00, 50.02, 49.98, 0.05 +-30.45, -30.00, 52.50, 47.50, 4.99 +-30.45, -30.00, 52.50, 47.50, 5.00 +-30.45, -30.00, 52.50, 47.50, 5.00 +-30.45, -30.00, 52.50, 47.50, 5.00 +-30.45, -30.00, 52.50, 47.50, 5.01 +-30.45, -30.00, 52.51, 47.49, 5.01 +-30.45, -30.00, 52.51, 47.49, 5.01 +-30.45, -30.00, 52.51, 47.49, 5.02 +-30.45, -30.00, 52.51, 47.49, 5.02 +-30.45, -30.00, 52.51, 47.49, 5.03 +-30.45, -30.00, 52.51, 47.49, 5.03 +-30.32, -30.00, 47.47, 52.53, -5.05 +-30.32, -30.00, 52.42, 47.58, 4.84 +-30.32, -30.00, 52.42, 47.58, 4.84 +-30.32, -30.00, 52.42, 47.58, 4.84 +-30.32, -30.00, 52.42, 47.58, 4.84 +-30.32, -30.00, 52.42, 47.58, 4.85 +-30.32, -30.00, 52.42, 47.58, 4.85 +-30.26, -30.00, 49.90, 50.10, -0.19 +-30.26, -30.00, 52.38, 47.62, 4.75 +-30.26, -30.00, 52.38, 47.62, 4.75 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.77 +-30.26, -30.00, 52.38, 47.62, 4.77 +-30.19, -30.00, 49.86, 50.14, -0.27 +-30.19, -30.00, 52.34, 47.66, 4.67 +-30.19, -30.00, 52.34, 47.66, 4.67 +-30.19, -30.00, 52.34, 47.66, 4.67 +-30.19, -30.00, 52.34, 47.66, 4.68 +-30.06, -30.00, 47.30, 52.70, -5.41 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-29.99, -30.00, 49.72, 50.28, -0.56 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.93, -30.00, 49.67, 50.33, -0.66 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.79, -30.00, 47.10, 52.90, -5.81 +-29.79, -30.00, 52.04, 47.96, 4.08 +-29.79, -30.00, 52.04, 47.96, 4.07 +-29.79, -30.00, 52.04, 47.96, 4.07 +-29.79, -30.00, 52.04, 47.96, 4.07 +-29.79, -30.00, 52.04, 47.96, 4.07 +-29.79, -30.00, 52.03, 47.97, 4.07 +-29.79, -30.00, 52.03, 47.97, 4.07 +-29.79, -30.00, 52.03, 47.97, 4.07 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.05 +-29.79, -30.00, 52.03, 47.97, 4.05 +-29.73, -30.00, 49.50, 50.50, -0.99 +-29.73, -30.00, 51.98, 48.02, 3.95 +-29.73, -30.00, 51.97, 48.03, 3.95 +-29.73, -30.00, 51.97, 48.03, 3.95 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.93 +-29.73, -30.00, 51.97, 48.03, 3.93 +-29.73, -30.00, 51.97, 48.03, 3.93 +-29.73, -30.00, 51.96, 48.04, 3.93 +-29.73, -30.00, 51.96, 48.04, 3.93 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.91 +-29.73, -30.00, 51.96, 48.04, 3.91 +-29.66, -30.00, 49.43, 50.57, -1.13 +-29.73, -30.00, 54.43, 45.57, 8.85 +-29.66, -30.00, 49.43, 50.57, -1.14 +-29.66, -30.00, 51.90, 48.10, 3.80 +-29.66, -30.00, 51.90, 48.10, 3.80 +-29.73, -30.00, 54.42, 45.58, 8.84 +-29.73, -30.00, 51.95, 48.05, 3.90 +-29.73, -30.00, 51.95, 48.05, 3.89 +-29.73, -30.00, 51.95, 48.05, 3.89 +-29.73, -30.00, 51.94, 48.06, 3.89 +-29.73, -30.00, 51.94, 48.06, 3.89 +-29.73, -30.00, 51.94, 48.06, 3.89 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.87 +-29.73, -30.00, 51.94, 48.06, 3.87 +-29.73, -30.00, 51.93, 48.07, 3.87 +-29.73, -30.00, 51.93, 48.07, 3.87 +-29.73, -30.00, 51.93, 48.07, 3.87 +-29.73, -30.00, 51.93, 48.07, 3.86 +-29.73, -30.00, 51.93, 48.07, 3.86 +-29.73, -30.00, 51.93, 48.07, 3.86 +-29.73, -30.00, 51.93, 48.07, 3.86 +-29.79, -30.00, 54.45, 45.55, 8.90 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 57.01, 42.99, 14.02 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.06, 47.94, 4.13 +-29.93, -30.00, 52.06, 47.94, 4.13 +-29.99, -30.00, 54.59, 45.41, 9.17 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-30.06, -30.00, 54.64, 45.36, 9.27 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.19, -30.00, 57.21, 42.79, 14.42 +-30.19, -30.00, 52.27, 47.73, 4.53 +-30.06, -30.00, 47.22, 52.78, -5.55 +-30.19, -30.00, 57.21, 42.79, 14.42 +-30.19, -30.00, 52.27, 47.73, 4.53 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.55 +-30.19, -30.00, 52.27, 47.73, 4.55 +-30.19, -30.00, 52.27, 47.73, 4.55 +-30.19, -30.00, 52.27, 47.73, 4.55 +-30.19, -30.00, 52.28, 47.72, 4.55 +-30.19, -30.00, 52.28, 47.72, 4.55 +-30.19, -30.00, 52.28, 47.72, 4.55 +-30.06, -30.00, 47.23, 52.77, -5.53 +-30.19, -30.00, 57.22, 42.78, 14.44 +-30.06, -30.00, 47.24, 52.76, -5.53 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.37 +-30.06, -30.00, 52.18, 47.82, 4.37 +-30.06, -30.00, 52.18, 47.82, 4.37 +-29.99, -30.00, 49.66, 50.34, -0.68 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-30.06, -30.00, 54.66, 45.34, 9.31 +-29.99, -30.00, 49.66, 50.34, -0.68 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-30.06, -30.00, 54.66, 45.34, 9.31 +-29.99, -30.00, 49.66, 50.34, -0.68 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.93, -30.00, 49.61, 50.39, -0.78 +-29.93, -30.00, 52.08, 47.92, 4.17 +-29.99, -30.00, 54.60, 45.40, 9.21 +-29.93, -30.00, 49.61, 50.39, -0.78 +-29.93, -30.00, 52.08, 47.92, 4.17 +-29.93, -30.00, 52.08, 47.92, 4.17 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.79, -30.00, 47.04, 52.96, -5.93 +-29.79, -30.00, 51.98, 48.02, 3.96 +-29.79, -30.00, 51.98, 48.02, 3.96 +-29.79, -30.00, 51.98, 48.02, 3.96 +-29.79, -30.00, 51.98, 48.02, 3.96 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 49.45, 50.55, -1.10 +-29.73, -30.00, 51.92, 48.08, 3.84 +-29.73, -30.00, 51.92, 48.08, 3.84 +-29.73, -30.00, 51.92, 48.08, 3.83 +-29.73, -30.00, 51.92, 48.08, 3.83 +-29.73, -30.00, 51.91, 48.09, 3.83 +-29.73, -30.00, 51.91, 48.09, 3.83 +-29.73, -30.00, 51.91, 48.09, 3.83 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.81 +-29.73, -30.00, 51.91, 48.09, 3.81 +-29.73, -30.00, 51.90, 48.10, 3.81 +-29.73, -30.00, 51.90, 48.10, 3.81 +-29.73, -30.00, 51.90, 48.10, 3.81 +-29.66, -30.00, 49.38, 50.62, -1.24 +-29.66, -30.00, 51.85, 48.15, 3.70 +-29.66, -30.00, 51.85, 48.15, 3.70 +-29.66, -30.00, 51.85, 48.15, 3.70 +-29.66, -30.00, 51.85, 48.15, 3.69 +-29.66, -30.00, 51.85, 48.15, 3.69 +-29.66, -30.00, 51.84, 48.16, 3.69 +-29.66, -30.00, 51.84, 48.16, 3.69 +-29.73, -30.00, 54.36, 45.64, 8.73 +-29.73, -30.00, 51.89, 48.11, 3.78 +-29.73, -30.00, 51.89, 48.11, 3.78 +-29.73, -30.00, 51.89, 48.11, 3.78 +-29.73, -30.00, 51.89, 48.11, 3.77 +-29.73, -30.00, 51.89, 48.11, 3.77 +-29.73, -30.00, 51.89, 48.11, 3.77 +-29.73, -30.00, 51.88, 48.12, 3.77 +-29.73, -30.00, 51.88, 48.12, 3.77 +-29.73, -30.00, 51.88, 48.12, 3.76 +-29.73, -30.00, 51.88, 48.12, 3.76 +-29.66, -30.00, 49.36, 50.64, -1.28 +-29.66, -30.00, 51.83, 48.17, 3.66 +-29.66, -30.00, 51.83, 48.17, 3.66 +-29.73, -30.00, 54.35, 45.65, 8.70 +-29.73, -30.00, 51.88, 48.12, 3.75 +-29.73, -30.00, 51.87, 48.13, 3.75 +-29.73, -30.00, 51.87, 48.13, 3.75 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.79, -30.00, 54.39, 45.61, 8.78 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.73, -30.00, 49.39, 50.61, -1.21 +-29.79, -30.00, 54.39, 45.61, 8.77 +-29.73, -30.00, 49.39, 50.61, -1.22 +-29.73, -30.00, 51.86, 48.14, 3.73 +-29.73, -30.00, 51.86, 48.14, 3.72 +-29.73, -30.00, 51.86, 48.14, 3.72 +-29.79, -30.00, 54.38, 45.62, 8.76 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 56.95, 43.05, 13.89 +-29.93, -30.00, 52.00, 48.00, 4.01 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.99, -30.00, 54.52, 45.48, 9.04 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-30.06, -30.00, 54.57, 45.43, 9.14 +-29.99, -30.00, 49.58, 50.42, -0.85 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-30.06, -30.00, 54.57, 45.43, 9.14 +-29.99, -30.00, 49.58, 50.42, -0.85 +-30.06, -30.00, 54.57, 45.43, 9.14 +-30.06, -30.00, 52.10, 47.90, 4.20 +-30.06, -30.00, 52.10, 47.90, 4.20 +-30.06, -30.00, 52.10, 47.90, 4.20 +-30.06, -30.00, 52.10, 47.90, 4.20 +-30.19, -30.00, 57.14, 42.86, 14.29 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.26, -30.00, 54.73, 45.27, 9.47 +-30.26, -30.00, 52.26, 47.74, 4.53 +-30.19, -30.00, 49.74, 50.26, -0.52 +-30.19, -30.00, 52.21, 47.79, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.45 +-30.06, -30.00, 47.18, 52.82, -5.64 +-30.06, -30.00, 52.12, 47.88, 4.25 +-30.06, -30.00, 52.12, 47.88, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-29.99, -30.00, 49.60, 50.40, -0.79 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.93, -30.00, 49.55, 50.45, -0.89 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.02, 47.98, 4.05 +-29.93, -30.00, 52.02, 47.98, 4.05 +-29.79, -30.00, 46.98, 53.02, -6.04 +-29.79, -30.00, 51.92, 48.08, 3.85 +-29.79, -30.00, 51.92, 48.08, 3.85 +-29.79, -30.00, 51.92, 48.08, 3.85 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.79, -30.00, 51.91, 48.09, 3.83 +-29.79, -30.00, 51.91, 48.09, 3.83 +-29.79, -30.00, 51.91, 48.09, 3.83 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.73, -30.00, 49.38, 50.62, -1.23 +-29.79, -30.00, 54.38, 45.62, 8.75 +-29.79, -30.00, 51.90, 48.10, 3.81 +-29.79, -30.00, 51.90, 48.10, 3.81 +-29.79, -30.00, 51.90, 48.10, 3.81 +-29.79, -30.00, 51.90, 48.10, 3.80 +-29.79, -30.00, 51.90, 48.10, 3.80 +-29.79, -30.00, 51.90, 48.10, 3.80 +-29.73, -30.00, 49.38, 50.62, -1.24 +-29.79, -30.00, 54.37, 45.63, 8.74 +-29.79, -30.00, 51.90, 48.10, 3.80 +-29.73, -30.00, 49.38, 50.62, -1.25 +-29.79, -30.00, 54.37, 45.63, 8.74 +-29.79, -30.00, 51.90, 48.10, 3.79 +-29.79, -30.00, 51.89, 48.11, 3.79 +-29.79, -30.00, 51.89, 48.11, 3.79 +-29.79, -30.00, 51.89, 48.11, 3.79 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.77 +-29.79, -30.00, 51.89, 48.11, 3.77 +-29.79, -30.00, 51.89, 48.11, 3.77 +-29.79, -30.00, 51.89, 48.11, 3.77 +-29.79, -30.00, 51.88, 48.12, 3.77 +-29.79, -30.00, 51.88, 48.12, 3.77 +-29.79, -30.00, 51.88, 48.12, 3.77 +-29.79, -30.00, 51.88, 48.12, 3.76 +-29.79, -30.00, 51.88, 48.12, 3.76 +-29.79, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 56.92, 43.08, 13.85 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.99, -30.00, 52.02, 47.98, 4.04 +-29.99, -30.00, 52.02, 47.98, 4.04 +-29.93, -30.00, 49.50, 50.50, -1.01 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.93, -30.00, 49.50, 50.50, -1.01 +-29.93, -30.00, 51.97, 48.03, 3.93 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.93, -30.00, 49.49, 50.51, -1.01 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.93, -30.00, 49.49, 50.51, -1.01 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.01, 47.99, 4.03 +-29.99, -30.00, 52.01, 47.99, 4.03 +-29.99, -30.00, 52.01, 47.99, 4.03 +-29.99, -30.00, 52.01, 47.99, 4.03 +-30.06, -30.00, 54.54, 45.46, 9.07 +-30.06, -30.00, 52.06, 47.94, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.19, -30.00, 57.11, 42.89, 14.22 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.06, -30.00, 47.13, 52.87, -5.74 +-30.06, -30.00, 52.07, 47.93, 4.15 +-30.19, -30.00, 57.12, 42.88, 14.23 +-30.06, -30.00, 47.13, 52.87, -5.74 +-30.19, -30.00, 57.12, 42.88, 14.24 +-30.19, -30.00, 52.17, 47.83, 4.35 +-30.19, -30.00, 52.18, 47.82, 4.35 +-30.19, -30.00, 52.18, 47.82, 4.35 +-30.19, -30.00, 52.18, 47.82, 4.35 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.37 +-30.19, -30.00, 52.18, 47.82, 4.37 +-30.19, -30.00, 52.18, 47.82, 4.37 +-30.19, -30.00, 52.18, 47.82, 4.37 +-30.19, -30.00, 52.19, 47.81, 4.37 +-30.19, -30.00, 52.19, 47.81, 4.37 +-30.19, -30.00, 52.19, 47.81, 4.37 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.39 +-30.19, -30.00, 52.19, 47.81, 4.39 +-30.19, -30.00, 52.19, 47.81, 4.39 +-30.19, -30.00, 52.19, 47.81, 4.39 +-30.19, -30.00, 52.20, 47.80, 4.39 +-30.19, -30.00, 52.20, 47.80, 4.39 +-30.19, -30.00, 52.20, 47.80, 4.39 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.06, -30.00, 47.17, 52.83, -5.67 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-29.99, -30.00, 49.59, 50.41, -0.82 +-29.99, -30.00, 52.06, 47.94, 4.12 +-29.99, -30.00, 52.06, 47.94, 4.12 +-29.99, -30.00, 52.06, 47.94, 4.12 +-29.93, -30.00, 49.54, 50.46, -0.92 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.79, -30.00, 46.97, 53.03, -6.07 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.73, -30.00, 49.38, 50.62, -1.23 +-29.73, -30.00, 51.86, 48.14, 3.71 +-29.73, -30.00, 51.85, 48.15, 3.71 +-29.73, -30.00, 51.85, 48.15, 3.71 +-29.73, -30.00, 51.85, 48.15, 3.71 +-29.73, -30.00, 51.85, 48.15, 3.70 +-29.73, -30.00, 51.85, 48.15, 3.70 +-29.73, -30.00, 51.85, 48.15, 3.70 +-29.73, -30.00, 51.85, 48.15, 3.70 +-29.66, -30.00, 49.33, 50.67, -1.35 +-29.73, -30.00, 54.32, 45.68, 8.64 +-29.73, -30.00, 51.85, 48.15, 3.69 +-29.73, -30.00, 51.84, 48.16, 3.69 +-29.73, -30.00, 51.84, 48.16, 3.69 +-29.73, -30.00, 51.84, 48.16, 3.68 +-29.66, -30.00, 49.32, 50.68, -1.36 +-29.66, -30.00, 51.79, 48.21, 3.58 +-29.66, -30.00, 51.79, 48.21, 3.58 +-29.66, -30.00, 51.79, 48.21, 3.58 +-29.66, -30.00, 51.79, 48.21, 3.57 +-29.53, -30.00, 46.74, 53.26, -6.52 +-29.53, -30.00, 51.68, 48.32, 3.37 +-29.53, -30.00, 51.68, 48.32, 3.37 +-29.53, -30.00, 51.68, 48.32, 3.36 +-29.53, -30.00, 51.68, 48.32, 3.36 +-29.53, -30.00, 51.68, 48.32, 3.35 +-29.53, -30.00, 51.68, 48.32, 3.35 +-29.53, -30.00, 51.67, 48.33, 3.35 +-29.53, -30.00, 51.67, 48.33, 3.34 +-29.53, -30.00, 51.67, 48.33, 3.34 +-29.66, -30.00, 56.71, 43.29, 13.42 +-29.66, -30.00, 51.77, 48.23, 3.53 +-29.66, -30.00, 51.77, 48.23, 3.53 +-29.66, -30.00, 51.76, 48.24, 3.53 +-29.66, -30.00, 51.76, 48.24, 3.53 +-29.66, -30.00, 51.76, 48.24, 3.52 +-29.66, -30.00, 51.76, 48.24, 3.52 +-29.53, -30.00, 46.72, 53.28, -6.57 +-29.53, -30.00, 51.66, 48.34, 3.32 +-29.53, -30.00, 51.66, 48.34, 3.31 +-29.53, -30.00, 51.65, 48.35, 3.31 +-29.53, -30.00, 51.65, 48.35, 3.31 +-29.53, -30.00, 51.65, 48.35, 3.30 +-29.53, -30.00, 51.65, 48.35, 3.30 +-29.53, -30.00, 51.65, 48.35, 3.29 +-29.53, -30.00, 51.65, 48.35, 3.29 +-29.66, -30.00, 56.69, 43.31, 13.37 +-29.66, -30.00, 51.74, 48.26, 3.48 +-29.66, -30.00, 51.74, 48.26, 3.48 +-29.66, -30.00, 51.74, 48.26, 3.48 +-29.66, -30.00, 51.74, 48.26, 3.48 +-29.66, -30.00, 51.74, 48.26, 3.47 +-29.66, -30.00, 51.74, 48.26, 3.47 +-29.73, -30.00, 54.26, 45.74, 8.51 +-29.66, -30.00, 49.26, 50.74, -1.48 +-29.66, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 51.73, 48.27, 3.45 +-29.66, -30.00, 51.73, 48.27, 3.45 +-29.73, -30.00, 54.25, 45.75, 8.49 +-29.73, -30.00, 51.77, 48.23, 3.55 +-29.73, -30.00, 51.77, 48.23, 3.54 +-29.73, -30.00, 51.77, 48.23, 3.54 +-29.79, -30.00, 54.29, 45.71, 8.58 +-29.79, -30.00, 51.82, 48.18, 3.64 +-29.79, -30.00, 51.82, 48.18, 3.64 +-29.79, -30.00, 51.82, 48.18, 3.63 +-29.79, -30.00, 51.82, 48.18, 3.63 +-29.79, -30.00, 51.82, 48.18, 3.63 +-29.79, -30.00, 51.82, 48.18, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.61 +-29.93, -30.00, 56.85, 43.15, 13.70 +-29.93, -30.00, 51.91, 48.09, 3.81 +-29.93, -30.00, 51.91, 48.09, 3.81 +-29.93, -30.00, 51.91, 48.09, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.99, -30.00, 54.43, 45.57, 8.85 +-29.99, -30.00, 51.95, 48.05, 3.91 +-29.93, -30.00, 49.43, 50.57, -1.14 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.99, -30.00, 54.42, 45.58, 8.85 +-29.99, -30.00, 51.95, 48.05, 3.90 +-29.99, -30.00, 51.95, 48.05, 3.90 +-29.99, -30.00, 51.95, 48.05, 3.90 +-29.99, -30.00, 51.95, 48.05, 3.90 +-30.06, -30.00, 54.47, 45.53, 8.95 +-30.06, -30.00, 52.00, 48.00, 4.00 +-30.06, -30.00, 52.00, 48.00, 4.00 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.01, 47.99, 4.01 +-30.06, -30.00, 52.01, 47.99, 4.01 +-30.06, -30.00, 52.01, 47.99, 4.01 +-30.06, -30.00, 52.01, 47.99, 4.01 +-30.19, -30.00, 57.05, 42.95, 14.10 +-30.19, -30.00, 52.11, 47.89, 4.21 +-30.19, -30.00, 52.11, 47.89, 4.21 +-30.19, -30.00, 52.11, 47.89, 4.21 +-30.19, -30.00, 52.11, 47.89, 4.22 +-30.19, -30.00, 52.11, 47.89, 4.22 +-30.19, -30.00, 52.11, 47.89, 4.22 +-30.19, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 47.07, 52.93, -5.86 +-30.06, -30.00, 52.01, 47.99, 4.02 +-30.06, -30.00, 52.01, 47.99, 4.02 +-30.06, -30.00, 52.01, 47.99, 4.02 +-30.06, -30.00, 52.01, 47.99, 4.02 +-30.06, -30.00, 52.01, 47.99, 4.03 +-30.06, -30.00, 52.01, 47.99, 4.03 +-30.19, -30.00, 57.06, 42.94, 14.11 +-30.06, -30.00, 47.07, 52.93, -5.86 +-30.19, -30.00, 57.06, 42.94, 14.11 +-30.19, -30.00, 52.11, 47.89, 4.23 +-30.06, -30.00, 47.07, 52.93, -5.86 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 49.50, 50.50, -1.01 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-30.06, -30.00, 54.49, 45.51, 8.98 +-29.99, -30.00, 49.50, 50.50, -1.01 +-29.99, -30.00, 51.97, 48.03, 3.94 +-30.06, -30.00, 54.49, 45.51, 8.98 +-29.99, -30.00, 49.50, 50.50, -1.01 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 49.45, 50.55, -1.11 +-29.93, -30.00, 51.92, 48.08, 3.84 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.79, -30.00, 46.87, 53.13, -6.26 +-29.79, -30.00, 51.81, 48.19, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.61 +-29.79, -30.00, 51.81, 48.19, 3.61 +-29.79, -30.00, 51.81, 48.19, 3.61 +-29.79, -30.00, 51.80, 48.20, 3.61 +-29.79, -30.00, 51.80, 48.20, 3.61 +-29.79, -30.00, 51.80, 48.20, 3.61 +-29.79, -30.00, 51.80, 48.20, 3.60 +-29.79, -30.00, 51.80, 48.20, 3.60 +-29.79, -30.00, 51.80, 48.20, 3.60 +-29.79, -30.00, 51.80, 48.20, 3.60 +-29.73, -30.00, 49.28, 50.72, -1.44 +-29.73, -30.00, 51.75, 48.25, 3.50 +-29.73, -30.00, 51.75, 48.25, 3.50 +-29.73, -30.00, 51.75, 48.25, 3.49 +-29.73, -30.00, 51.75, 48.25, 3.49 +-29.73, -30.00, 51.74, 48.26, 3.49 +-29.79, -30.00, 54.27, 45.73, 8.53 +-29.79, -30.00, 51.79, 48.21, 3.59 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.57 +-29.73, -30.00, 49.26, 50.74, -1.47 +-29.73, -30.00, 51.74, 48.26, 3.47 +-29.73, -30.00, 51.73, 48.27, 3.47 +-29.73, -30.00, 51.73, 48.27, 3.47 +-29.73, -30.00, 51.73, 48.27, 3.47 +-29.73, -30.00, 51.73, 48.27, 3.46 +-29.73, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 49.21, 50.79, -1.58 +-29.66, -30.00, 51.68, 48.32, 3.36 +-29.66, -30.00, 51.68, 48.32, 3.35 +-29.66, -30.00, 51.68, 48.32, 3.35 +-29.73, -30.00, 54.20, 45.80, 8.39 +-29.73, -30.00, 51.72, 48.28, 3.45 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.43 +-29.66, -30.00, 49.19, 50.81, -1.61 +-29.66, -30.00, 51.67, 48.33, 3.33 +-29.66, -30.00, 51.66, 48.34, 3.33 +-29.53, -30.00, 46.62, 53.38, -6.76 +-29.53, -30.00, 51.56, 48.44, 3.12 +-29.53, -30.00, 51.56, 48.44, 3.12 +-29.53, -30.00, 51.56, 48.44, 3.12 +-29.53, -30.00, 51.56, 48.44, 3.11 +-29.53, -30.00, 51.55, 48.45, 3.11 +-29.53, -30.00, 51.55, 48.45, 3.11 +-29.53, -30.00, 51.55, 48.45, 3.10 +-29.53, -30.00, 51.55, 48.45, 3.10 +-29.53, -30.00, 51.55, 48.45, 3.10 +-29.53, -30.00, 51.55, 48.45, 3.09 +-29.53, -30.00, 51.54, 48.46, 3.09 +-29.53, -30.00, 51.54, 48.46, 3.08 +-29.53, -30.00, 51.54, 48.46, 3.08 +-29.53, -30.00, 51.54, 48.46, 3.08 +-29.47, -30.00, 49.02, 50.98, -1.97 +-29.53, -30.00, 54.01, 45.99, 8.01 +-29.47, -30.00, 49.01, 50.99, -1.98 +-29.53, -30.00, 54.00, 46.00, 8.01 +-29.53, -30.00, 51.53, 48.47, 3.06 +-29.53, -30.00, 51.53, 48.47, 3.06 +-29.53, -30.00, 51.53, 48.47, 3.05 +-29.53, -30.00, 51.52, 48.48, 3.05 +-29.53, -30.00, 51.52, 48.48, 3.05 +-29.53, -30.00, 51.52, 48.48, 3.04 +-29.53, -30.00, 51.52, 48.48, 3.04 +-29.53, -30.00, 51.52, 48.48, 3.03 +-29.53, -30.00, 51.52, 48.48, 3.03 +-29.53, -30.00, 51.51, 48.49, 3.03 +-29.53, -30.00, 51.51, 48.49, 3.02 +-29.53, -30.00, 51.51, 48.49, 3.02 +-29.53, -30.00, 51.51, 48.49, 3.02 +-29.53, -30.00, 51.51, 48.49, 3.01 +-29.53, -30.00, 51.51, 48.49, 3.01 +-29.53, -30.00, 51.50, 48.50, 3.01 +-29.53, -30.00, 51.50, 48.50, 3.00 +-29.53, -30.00, 51.50, 48.50, 3.00 +-29.53, -30.00, 51.50, 48.50, 3.00 +-29.66, -30.00, 56.54, 43.46, 13.08 +-29.66, -30.00, 51.59, 48.41, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.73, -30.00, 54.11, 45.89, 8.22 +-29.73, -30.00, 51.64, 48.36, 3.28 +-29.73, -30.00, 51.64, 48.36, 3.28 +-29.73, -30.00, 51.64, 48.36, 3.27 +-29.79, -30.00, 54.16, 45.84, 8.32 +-29.73, -30.00, 49.16, 50.84, -1.67 +-29.73, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 54.15, 45.85, 8.31 +-29.73, -30.00, 49.16, 50.84, -1.68 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 54.15, 45.85, 8.30 +-29.79, -30.00, 51.68, 48.32, 3.35 +-29.79, -30.00, 51.68, 48.32, 3.35 +-29.79, -30.00, 51.67, 48.33, 3.35 +-29.79, -30.00, 51.67, 48.33, 3.35 +-29.93, -30.00, 56.72, 43.28, 13.43 +-29.93, -30.00, 51.77, 48.23, 3.54 +-29.93, -30.00, 51.77, 48.23, 3.54 +-29.99, -30.00, 54.29, 45.71, 8.59 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-30.06, -30.00, 54.34, 45.66, 8.69 +-30.06, -30.00, 51.87, 48.13, 3.74 +-30.06, -30.00, 51.87, 48.13, 3.74 +-30.06, -30.00, 51.87, 48.13, 3.74 +-30.19, -30.00, 56.92, 43.08, 13.83 +-30.19, -30.00, 51.97, 48.03, 3.94 +-30.19, -30.00, 51.97, 48.03, 3.95 +-30.26, -30.00, 54.50, 45.50, 8.99 +-30.26, -30.00, 52.02, 47.98, 4.05 +-30.26, -30.00, 52.03, 47.97, 4.05 +-30.26, -30.00, 52.03, 47.97, 4.05 +-30.32, -30.00, 54.55, 45.45, 9.10 +-30.32, -30.00, 52.08, 47.92, 4.16 +-30.32, -30.00, 52.08, 47.92, 4.16 +-30.32, -30.00, 52.08, 47.92, 4.16 +-30.32, -30.00, 52.08, 47.92, 4.16 +-30.32, -30.00, 52.08, 47.92, 4.17 +-30.32, -30.00, 52.08, 47.92, 4.17 +-30.32, -30.00, 52.09, 47.91, 4.17 +-30.32, -30.00, 52.09, 47.91, 4.17 +-30.32, -30.00, 52.09, 47.91, 4.17 +-30.32, -30.00, 52.09, 47.91, 4.18 +-30.45, -30.00, 57.13, 42.87, 14.27 +-30.45, -30.00, 52.19, 47.81, 4.38 +-30.45, -30.00, 52.19, 47.81, 4.39 +-30.45, -30.00, 52.19, 47.81, 4.39 +-30.45, -30.00, 52.20, 47.80, 4.39 +-30.45, -30.00, 52.20, 47.80, 4.40 +-30.45, -30.00, 52.20, 47.80, 4.40 +-30.45, -30.00, 52.20, 47.80, 4.40 +-30.45, -30.00, 52.20, 47.80, 4.41 +-30.45, -30.00, 52.20, 47.80, 4.41 +-30.45, -30.00, 52.21, 47.79, 4.41 +-30.45, -30.00, 52.21, 47.79, 4.42 +-30.45, -30.00, 52.21, 47.79, 4.42 +-30.45, -30.00, 52.21, 47.79, 4.42 +-30.45, -30.00, 52.21, 47.79, 4.43 +-30.45, -30.00, 52.21, 47.79, 4.43 +-30.45, -30.00, 52.22, 47.78, 4.43 +-30.45, -30.00, 52.22, 47.78, 4.44 +-30.45, -30.00, 52.22, 47.78, 4.44 +-30.45, -30.00, 52.22, 47.78, 4.44 +-30.45, -30.00, 52.22, 47.78, 4.45 +-30.45, -30.00, 52.23, 47.77, 4.45 +-30.45, -30.00, 52.23, 47.77, 4.45 +-30.45, -30.00, 52.23, 47.77, 4.46 +-30.45, -30.00, 52.23, 47.77, 4.46 +-30.45, -30.00, 52.23, 47.77, 4.46 +-30.45, -30.00, 52.23, 47.77, 4.47 +-30.45, -30.00, 52.24, 47.76, 4.47 +-30.45, -30.00, 52.24, 47.76, 4.47 +-30.45, -30.00, 52.24, 47.76, 4.48 +-30.45, -30.00, 52.24, 47.76, 4.48 +-30.45, -30.00, 52.24, 47.76, 4.48 +-30.32, -30.00, 47.20, 52.80, -5.60 +-30.32, -30.00, 52.15, 47.85, 4.29 +-30.32, -30.00, 52.15, 47.85, 4.29 +-30.45, -30.00, 57.19, 42.81, 14.38 +-30.45, -30.00, 52.25, 47.75, 4.50 +-30.45, -30.00, 52.25, 47.75, 4.50 +-30.45, -30.00, 52.25, 47.75, 4.51 +-30.32, -30.00, 47.21, 52.79, -5.58 +-30.32, -30.00, 52.16, 47.84, 4.31 +-30.32, -30.00, 52.16, 47.84, 4.31 +-30.32, -30.00, 52.16, 47.84, 4.32 +-30.32, -30.00, 52.16, 47.84, 4.32 +-30.32, -30.00, 52.16, 47.84, 4.32 +-30.32, -30.00, 52.16, 47.84, 4.32 +-30.26, -30.00, 49.64, 50.36, -0.72 +-30.26, -30.00, 52.11, 47.89, 4.23 +-30.26, -30.00, 52.12, 47.88, 4.23 +-30.26, -30.00, 52.12, 47.88, 4.23 +-30.26, -30.00, 52.12, 47.88, 4.23 +-30.26, -30.00, 52.12, 47.88, 4.24 +-30.26, -30.00, 52.12, 47.88, 4.24 +-30.26, -30.00, 52.12, 47.88, 4.24 +-30.26, -30.00, 52.12, 47.88, 4.24 +-30.19, -30.00, 49.60, 50.40, -0.80 +-30.19, -30.00, 52.07, 47.93, 4.15 +-30.19, -30.00, 52.07, 47.93, 4.15 +-30.19, -30.00, 52.07, 47.93, 4.15 +-30.19, -30.00, 52.08, 47.92, 4.15 +-30.19, -30.00, 52.08, 47.92, 4.15 +-30.19, -30.00, 52.08, 47.92, 4.15 +-30.06, -30.00, 47.03, 52.97, -5.93 +-30.06, -30.00, 51.98, 48.02, 3.96 +-30.06, -30.00, 51.98, 48.02, 3.96 +-30.06, -30.00, 51.98, 48.02, 3.96 +-30.06, -30.00, 51.98, 48.02, 3.96 +-29.99, -30.00, 49.46, 50.54, -1.08 +-30.06, -30.00, 54.45, 45.55, 8.90 +-29.99, -30.00, 49.46, 50.54, -1.08 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-30.06, -30.00, 54.45, 45.55, 8.90 +-29.99, -30.00, 49.46, 50.54, -1.08 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.93, -30.00, 49.41, 50.59, -1.18 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.75 +-29.93, -30.00, 51.88, 48.12, 3.75 +-29.93, -30.00, 51.88, 48.12, 3.75 +-29.79, -30.00, 46.83, 53.17, -6.33 +-29.79, -30.00, 51.78, 48.22, 3.55 +-29.79, -30.00, 51.78, 48.22, 3.55 +-29.79, -30.00, 51.77, 48.23, 3.55 +-29.79, -30.00, 51.77, 48.23, 3.55 +-29.73, -30.00, 49.25, 50.75, -1.50 +-29.73, -30.00, 51.72, 48.28, 3.45 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.43 +-29.73, -30.00, 51.72, 48.28, 3.43 +-29.73, -30.00, 51.71, 48.29, 3.43 +-29.73, -30.00, 51.71, 48.29, 3.43 +-29.73, -30.00, 51.71, 48.29, 3.42 +-29.73, -30.00, 51.71, 48.29, 3.42 +-29.73, -30.00, 51.71, 48.29, 3.42 +-29.66, -30.00, 49.19, 50.81, -1.62 +-29.66, -30.00, 51.66, 48.34, 3.32 +-29.66, -30.00, 51.66, 48.34, 3.31 +-29.66, -30.00, 51.66, 48.34, 3.31 +-29.66, -30.00, 51.65, 48.35, 3.31 +-29.66, -30.00, 51.65, 48.35, 3.31 +-29.66, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 51.65, 48.35, 3.29 +-29.66, -30.00, 51.65, 48.35, 3.29 +-29.73, -30.00, 54.17, 45.83, 8.33 +-29.73, -30.00, 51.69, 48.31, 3.39 +-29.66, -30.00, 49.17, 50.83, -1.66 +-29.66, -30.00, 51.64, 48.36, 3.28 +-29.66, -30.00, 51.64, 48.36, 3.28 +-29.66, -30.00, 51.64, 48.36, 3.28 +-29.66, -30.00, 51.64, 48.36, 3.27 +-29.66, -30.00, 51.64, 48.36, 3.27 +-29.66, -30.00, 51.63, 48.37, 3.27 +-29.66, -30.00, 51.63, 48.37, 3.27 +-29.66, -30.00, 51.63, 48.37, 3.26 +-29.66, -30.00, 51.63, 48.37, 3.26 +-29.66, -30.00, 51.63, 48.37, 3.26 +-29.66, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 54.15, 45.85, 8.30 +-29.73, -30.00, 51.68, 48.32, 3.35 +-29.73, -30.00, 51.67, 48.33, 3.35 +-29.73, -30.00, 51.67, 48.33, 3.35 +-29.73, -30.00, 51.67, 48.33, 3.35 +-29.73, -30.00, 51.67, 48.33, 3.34 +-29.73, -30.00, 51.67, 48.33, 3.34 +-29.73, -30.00, 51.67, 48.33, 3.34 +-29.73, -30.00, 51.67, 48.33, 3.34 +-29.66, -30.00, 49.15, 50.85, -1.71 +-29.66, -30.00, 51.62, 48.38, 3.23 +-29.66, -30.00, 51.62, 48.38, 3.23 +-29.66, -30.00, 51.61, 48.39, 3.23 +-29.66, -30.00, 51.61, 48.39, 3.23 +-29.66, -30.00, 51.61, 48.39, 3.22 +-29.66, -30.00, 51.61, 48.39, 3.22 +-29.66, -30.00, 51.61, 48.39, 3.22 +-29.73, -30.00, 54.13, 45.87, 8.26 +-29.73, -30.00, 51.66, 48.34, 3.31 +-29.73, -30.00, 51.66, 48.34, 3.31 +-29.73, -30.00, 51.65, 48.35, 3.31 +-29.73, -30.00, 51.65, 48.35, 3.31 +-29.73, -30.00, 51.65, 48.35, 3.31 +-29.73, -30.00, 51.65, 48.35, 3.30 +-29.73, -30.00, 51.65, 48.35, 3.30 +-29.73, -30.00, 51.65, 48.35, 3.30 +-29.73, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 49.13, 50.87, -1.75 +-29.66, -30.00, 51.60, 48.40, 3.19 +-29.66, -30.00, 51.60, 48.40, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.73, -30.00, 54.11, 45.89, 8.22 +-29.73, -30.00, 51.64, 48.36, 3.27 +-29.73, -30.00, 51.63, 48.37, 3.27 +-29.73, -30.00, 51.63, 48.37, 3.27 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.66, -30.00, 49.11, 50.89, -1.78 +-29.66, -30.00, 51.58, 48.42, 3.16 +-29.66, -30.00, 51.58, 48.42, 3.15 +-29.66, -30.00, 51.58, 48.42, 3.15 +-29.66, -30.00, 51.57, 48.43, 3.15 +-29.66, -30.00, 51.57, 48.43, 3.15 +-29.66, -30.00, 51.57, 48.43, 3.14 +-29.66, -30.00, 51.57, 48.43, 3.14 +-29.66, -30.00, 51.57, 48.43, 3.14 +-29.66, -30.00, 51.57, 48.43, 3.14 +-29.66, -30.00, 51.57, 48.43, 3.13 +-29.66, -30.00, 51.57, 48.43, 3.13 +-29.73, -30.00, 54.09, 45.91, 8.17 +-29.73, -30.00, 51.61, 48.39, 3.23 +-29.73, -30.00, 51.61, 48.39, 3.22 +-29.73, -30.00, 51.61, 48.39, 3.22 +-29.66, -30.00, 49.09, 50.91, -1.82 +-29.66, -30.00, 51.56, 48.44, 3.12 +-29.66, -30.00, 51.56, 48.44, 3.12 +-29.66, -30.00, 51.56, 48.44, 3.11 +-29.66, -30.00, 51.56, 48.44, 3.11 +-29.66, -30.00, 51.55, 48.45, 3.11 +-29.66, -30.00, 51.55, 48.45, 3.11 +-29.66, -30.00, 51.55, 48.45, 3.10 +-29.66, -30.00, 51.55, 48.45, 3.10 +-29.73, -30.00, 54.07, 45.93, 8.14 +-29.73, -30.00, 51.60, 48.40, 3.20 +-29.73, -30.00, 51.60, 48.40, 3.19 +-29.73, -30.00, 51.60, 48.40, 3.19 +-29.73, -30.00, 51.59, 48.41, 3.19 +-29.73, -30.00, 51.59, 48.41, 3.19 +-29.73, -30.00, 51.59, 48.41, 3.18 +-29.73, -30.00, 51.59, 48.41, 3.18 +-29.73, -30.00, 51.59, 48.41, 3.18 +-29.79, -30.00, 54.11, 45.89, 8.22 +-29.73, -30.00, 49.12, 50.88, -1.77 +-29.79, -30.00, 54.11, 45.89, 8.22 +-29.79, -30.00, 51.64, 48.36, 3.27 +-29.79, -30.00, 51.64, 48.36, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.93, -30.00, 56.67, 43.33, 13.34 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.99, -30.00, 54.25, 45.75, 8.49 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-30.06, -30.00, 54.30, 45.70, 8.59 +-30.06, -30.00, 51.82, 48.18, 3.65 +-30.06, -30.00, 51.82, 48.18, 3.65 +-30.06, -30.00, 51.82, 48.18, 3.65 +-30.06, -30.00, 51.82, 48.18, 3.65 +-30.06, -30.00, 51.82, 48.18, 3.65 +-29.99, -30.00, 49.30, 50.70, -1.39 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.93, -30.00, 49.25, 50.75, -1.49 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.93, -30.00, 49.25, 50.75, -1.51 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.93, -30.00, 49.25, 50.75, -1.51 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.99, -30.00, 51.77, 48.23, 3.54 +-29.93, -30.00, 49.25, 50.75, -1.51 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.93, -30.00, 49.25, 50.75, -1.51 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-30.06, -30.00, 54.29, 45.71, 8.58 +-29.99, -30.00, 49.30, 50.70, -1.41 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-30.06, -30.00, 54.29, 45.71, 8.58 +-29.99, -30.00, 49.30, 50.70, -1.41 +-30.06, -30.00, 54.29, 45.71, 8.58 +-30.06, -30.00, 51.82, 48.18, 3.63 +-30.06, -30.00, 51.82, 48.18, 3.63 +-30.06, -30.00, 51.82, 48.18, 3.63 +-30.06, -30.00, 51.82, 48.18, 3.64 +-30.06, -30.00, 51.82, 48.18, 3.64 +-30.19, -30.00, 56.86, 43.14, 13.72 +-30.19, -30.00, 51.92, 48.08, 3.84 +-30.19, -30.00, 51.92, 48.08, 3.84 +-30.19, -30.00, 51.92, 48.08, 3.84 +-30.19, 0.00, 75.00, 25.00, 50.00 +-30.19, 0.00, 74.65, 25.35, 49.29 +-30.19, 0.00, 74.76, 25.24, 49.52 +-30.19, 0.00, 74.87, 25.13, 49.74 +-30.19, 0.00, 74.99, 25.01, 49.97 +-30.06, 0.00, 70.06, 29.94, 40.11 +-30.06, 0.00, 75.00, 25.00, 50.00 +-30.06, 0.00, 75.00, 25.00, 50.00 +-30.06, 0.00, 75.00, 25.00, 50.00 +-30.06, 0.00, 75.00, 25.00, 50.00 +-29.99, 0.00, 73.04, 26.96, 46.08 +-29.99, 0.00, 75.00, 25.00, 50.00 +-29.93, 0.00, 73.22, 26.78, 46.43 +-29.93, 0.00, 75.00, 25.00, 50.00 +-29.79, 0.00, 70.87, 29.13, 41.74 +-29.73, 0.00, 73.40, 26.60, 46.81 +-29.66, 0.00, 73.47, 26.53, 46.93 +-29.53, 0.00, 71.01, 28.99, 42.01 +-29.47, 0.00, 73.54, 26.46, 47.08 +-29.27, 0.00, 68.56, 31.44, 37.11 +-29.14, 0.00, 71.04, 28.96, 42.08 +-29.00, 0.00, 71.05, 28.95, 42.10 +-28.74, 0.00, 66.01, 33.99, 32.03 +-28.61, 0.00, 70.97, 29.03, 41.93 +-28.41, 0.00, 68.45, 31.55, 36.91 +-28.21, 0.00, 68.41, 31.59, 36.82 +-27.95, 0.00, 65.85, 34.15, 31.69 +-27.82, 0.00, 70.79, 29.21, 41.59 +-27.55, 0.00, 65.76, 34.24, 31.51 +-27.36, 0.00, 68.18, 31.82, 36.37 +-27.03, 0.00, 63.09, 36.91, 26.19 +-26.83, 0.00, 67.99, 32.01, 35.98 +-26.50, 0.00, 62.90, 37.10, 25.80 +-26.24, 0.00, 65.27, 34.73, 30.54 +-25.84, 0.00, 60.13, 39.87, 20.25 +-25.58, 0.00, 64.97, 35.03, 29.94 +-25.25, 0.00, 62.34, 37.66, 24.69 +-24.92, 0.00, 62.19, 37.81, 24.38 +-24.52, 0.00, 59.51, 40.49, 19.03 +-24.19, 0.00, 61.83, 38.17, 23.66 +-23.86, 0.00, 61.67, 38.33, 23.34 +-23.47, 0.00, 58.99, 41.01, 17.98 +-23.07, 0.00, 58.78, 41.22, 17.56 +-22.68, 0.00, 58.57, 41.43, 17.14 +-22.28, 0.00, 58.36, 41.64, 16.71 +-21.82, 0.00, 55.62, 44.38, 11.24 +-21.49, 0.00, 60.40, 39.60, 20.79 +-21.03, 0.00, 55.19, 44.81, 10.37 +-20.50, 0.00, 52.40, 47.60, 4.79 +-20.17, 0.00, 59.64, 40.36, 19.28 +-19.71, 0.00, 54.42, 45.58, 8.85 +-19.18, 0.00, 51.63, 48.37, 3.26 +-18.72, 0.00, 53.82, 46.18, 7.65 +-18.19, 0.00, 51.03, 48.97, 2.05 +-17.80, 0.00, 55.74, 44.26, 11.48 +-17.27, 0.00, 50.46, 49.54, 0.93 +-16.74, 0.00, 50.13, 49.87, 0.26 +-16.28, 0.00, 52.32, 47.68, 4.64 +-15.82, 0.00, 52.03, 47.97, 4.06 +-15.29, 0.00, 49.22, 50.78, -1.56 +-14.77, 0.00, 48.88, 51.12, -2.24 +-14.24, 0.00, 48.54, 51.46, -2.92 +-13.84, 0.00, 53.24, 46.76, 6.48 +-13.32, 0.00, 47.95, 52.05, -4.10 +-12.85, 0.00, 50.12, 49.88, 0.25 +-12.33, 0.00, 47.30, 52.70, -5.40 +-11.80, 0.00, 46.95, 53.05, -6.10 +-11.27, 0.00, 46.60, 53.40, -6.80 +-10.74, 0.00, 46.24, 53.76, -7.51 +-10.22, 0.00, 45.89, 54.11, -8.23 +-9.69, 0.00, 45.53, 54.47, -8.95 +-9.23, 0.00, 47.69, 52.31, -4.63 +-8.70, 0.00, 44.85, 55.15, -10.30 +-8.31, 0.00, 49.53, 50.47, -0.94 +-7.78, 0.00, 44.22, 55.78, -11.56 +-7.32, 0.00, 46.37, 53.63, -7.25 +-6.79, 0.00, 43.53, 56.47, -12.94 +-6.26, 0.00, 43.16, 56.84, -13.68 +-5.80, 0.00, 45.31, 54.69, -9.39 +-5.41, 0.00, 47.50, 52.50, -4.99 +-4.88, 0.00, 42.18, 57.82, -15.64 +-4.42, 0.00, 44.32, 55.68, -11.35 +-3.89, 0.00, 41.47, 58.53, -17.06 +-3.43, 0.00, 43.61, 56.39, -12.78 +-3.03, 0.00, 45.80, 54.20, -8.41 +-2.57, 0.00, 42.99, 57.01, -14.02 +-2.04, 0.00, 40.13, 59.87, -19.74 +-1.58, 0.00, 42.26, 57.74, -15.48 +-1.19, 0.00, 44.44, 55.56, -11.12 +-0.73, 0.00, 41.62, 58.38, -16.75 +-0.40, 0.00, 46.32, 53.68, -7.35 +0.07, 0.00, 41.03, 58.97, -17.93 +0.53, 0.00, 40.68, 59.32, -18.63 +0.86, 0.00, 45.38, 54.62, -9.24 +1.32, 0.00, 40.08, 59.92, -19.83 +1.71, 0.00, 42.25, 57.75, -15.50 +2.11, 0.00, 41.95, 58.05, -16.11 +2.44, 0.00, 44.16, 55.84, -11.67 +2.90, 0.00, 38.86, 61.14, -22.28 +3.23, 0.00, 43.55, 56.45, -12.91 +3.56, 0.00, 43.29, 56.71, -13.43 +3.96, 0.00, 40.50, 59.50, -18.99 +4.28, 0.00, 42.71, 57.29, -14.58 +4.61, 0.00, 42.45, 57.55, -15.11 +5.01, 0.00, 39.66, 60.34, -20.68 +5.27, 0.00, 44.39, 55.61, -11.23 +5.60, 0.00, 41.65, 58.35, -16.71 +5.93, 0.00, 41.38, 58.62, -17.25 +6.20, 0.00, 43.63, 56.37, -12.75 +6.59, 0.00, 38.36, 61.64, -23.28 +6.86, 0.00, 43.08, 56.92, -13.84 +7.19, 0.00, 40.34, 59.66, -19.33 +7.45, 0.00, 42.58, 57.42, -14.83 +7.71, 0.00, 42.36, 57.64, -15.29 +7.98, 0.00, 42.13, 57.87, -15.74 +8.24, 0.00, 41.90, 58.10, -16.20 +8.44, 0.00, 44.19, 55.81, -11.62 +8.70, 0.00, 41.49, 58.51, -17.02 +8.96, 0.00, 41.26, 58.74, -17.48 +9.10, 0.00, 46.07, 53.93, -7.86 +9.29, 0.00, 43.41, 56.59, -13.17 +9.56, 0.00, 40.71, 59.29, -18.58 +9.76, 0.00, 43.00, 57.00, -14.01 +9.89, 0.00, 45.33, 54.67, -9.34 +10.09, 0.00, 42.67, 57.33, -14.65 +10.28, 0.00, 42.49, 57.51, -15.03 +10.42, 0.00, 44.82, 55.18, -10.36 +10.61, 0.00, 42.16, 57.84, -15.68 +10.68, 0.00, 47.01, 52.99, -5.97 +10.88, 0.00, 41.88, 58.12, -16.24 +11.07, 0.00, 41.69, 58.31, -16.62 +11.14, 0.00, 46.54, 53.46, -6.91 +11.21, 0.00, 46.45, 53.55, -7.09 +11.40, 0.00, 41.32, 58.68, -17.36 +11.47, 0.00, 46.17, 53.83, -7.66 +11.60, 0.00, 43.56, 56.44, -12.89 +11.67, 0.00, 45.93, 54.07, -8.13 +11.87, 0.00, 40.80, 59.20, -18.41 +11.87, 0.00, 48.17, 51.83, -3.66 +11.93, 0.00, 45.60, 54.40, -8.80 +12.00, 0.00, 45.51, 54.49, -8.98 +12.13, 0.00, 42.89, 57.11, -14.22 +12.19, 0.00, 45.27, 54.73, -9.46 +12.26, 0.00, 45.17, 54.83, -9.65 +12.26, 0.00, 47.60, 52.40, -4.80 +12.39, 0.00, 42.51, 57.49, -14.98 +12.39, 0.00, 47.41, 52.59, -5.19 +12.39, 0.00, 47.36, 52.64, -5.28 +12.39, 0.00, 47.31, 52.69, -5.37 +12.46, 0.00, 44.75, 55.25, -10.51 +12.46, 0.00, 47.17, 52.83, -5.66 +12.46, 0.00, 47.12, 52.88, -5.75 +12.46, 0.00, 47.08, 52.92, -5.84 +12.46, 0.00, 47.03, 52.97, -5.94 +12.46, 0.00, 46.98, 53.02, -6.03 +12.46, 0.00, 46.94, 53.06, -6.12 +12.46, 0.00, 46.89, 53.11, -6.22 +12.46, 0.00, 46.84, 53.16, -6.31 +12.39, 0.00, 49.32, 50.68, -1.36 +12.39, 0.00, 46.80, 53.20, -6.40 +12.39, 0.00, 46.75, 53.25, -6.49 +12.26, 0.00, 51.75, 48.25, 3.50 +12.26, 0.00, 46.76, 53.24, -6.48 +12.19, 0.00, 49.24, 50.76, -1.53 +12.19, 0.00, 46.72, 53.28, -6.56 +12.13, 0.00, 49.20, 50.80, -1.61 +12.00, 0.00, 51.72, 48.28, 3.44 +11.93, 0.00, 49.25, 50.75, -1.49 +11.93, 0.00, 46.74, 53.26, -6.53 +11.87, 0.00, 49.21, 50.79, -1.57 +11.87, 0.00, 46.70, 53.30, -6.61 +11.67, 0.00, 54.22, 45.78, 8.44 +11.67, 0.00, 46.76, 53.24, -6.48 +11.60, 0.00, 49.24, 50.76, -1.53 +11.47, 0.00, 51.76, 48.24, 3.53 +11.34, 0.00, 51.82, 48.18, 3.64 +11.21, 0.00, 51.88, 48.12, 3.75 +11.14, 0.00, 49.41, 50.59, -1.17 +11.14, 0.00, 46.90, 53.10, -6.20 +11.07, 0.00, 49.38, 50.62, -1.24 +10.94, 0.00, 51.91, 48.09, 3.82 +10.88, 0.00, 49.45, 50.55, -1.11 +10.81, 0.00, 49.45, 50.55, -1.09 +10.61, 0.00, 54.51, 45.49, 9.01 +10.55, 0.00, 49.57, 50.43, -0.85 +10.42, 0.00, 52.10, 47.90, 4.21 +10.35, 0.00, 49.64, 50.36, -0.71 +10.28, 0.00, 49.65, 50.35, -0.69 +10.15, 0.00, 52.19, 47.81, 4.37 +10.02, 0.00, 52.25, 47.75, 4.50 +9.89, 0.00, 52.31, 47.69, 4.62 +9.82, 0.00, 49.85, 50.15, -0.30 +9.62, 0.00, 54.91, 45.09, 9.81 +9.56, 0.00, 49.98, 50.02, -0.05 +9.49, 0.00, 49.99, 50.01, -0.02 +9.29, 0.00, 55.05, 44.95, 10.10 +9.23, 0.00, 50.12, 49.88, 0.24 +9.10, 0.00, 52.66, 47.34, 5.31 +9.03, 0.00, 50.20, 49.80, 0.40 +8.83, 0.00, 55.26, 44.74, 10.52 +8.77, 0.00, 50.33, 49.67, 0.66 +8.70, 0.00, 50.35, 49.65, 0.69 +8.57, 0.00, 52.89, 47.11, 5.77 +8.50, 0.00, 50.43, 49.57, 0.86 +8.31, 0.00, 55.49, 44.51, 10.99 +8.24, 0.00, 50.57, 49.43, 1.13 +8.17, 0.00, 50.59, 49.41, 1.17 +8.04, 0.00, 53.13, 46.87, 6.25 +7.91, 0.00, 53.20, 46.80, 6.39 +7.78, 0.00, 53.27, 46.73, 6.53 +7.65, 0.00, 53.34, 46.66, 6.67 +7.51, 0.00, 53.41, 46.59, 6.81 +7.45, 0.00, 50.96, 49.04, 1.91 +7.25, 0.00, 56.02, 43.98, 12.04 +7.19, 0.00, 51.10, 48.90, 2.20 +7.12, 0.00, 51.12, 48.88, 2.25 +6.99, 0.00, 53.67, 46.33, 7.33 +6.86, 0.00, 53.74, 46.26, 7.48 +6.72, 0.00, 53.81, 46.19, 7.63 +6.66, 0.00, 51.37, 48.63, 2.73 +6.59, 0.00, 51.39, 48.61, 2.78 +6.46, 0.00, 53.94, 46.06, 7.88 +6.39, 0.00, 51.49, 48.51, 2.98 +6.33, 0.00, 51.52, 48.48, 3.03 +6.20, 0.00, 54.06, 45.94, 8.13 +6.13, 0.00, 51.62, 48.38, 3.24 +5.93, 0.00, 56.69, 43.31, 13.38 +5.87, 0.00, 51.77, 48.23, 3.55 +5.80, 0.00, 51.80, 48.20, 3.60 +5.67, 0.00, 54.35, 45.65, 8.70 +5.60, 0.00, 51.91, 48.09, 3.81 +5.54, 0.00, 51.94, 48.06, 3.87 +5.41, 0.00, 54.49, 45.51, 8.97 +5.34, 0.00, 52.04, 47.96, 4.09 +5.27, 0.00, 52.07, 47.93, 4.15 +5.14, 0.00, 54.62, 45.38, 9.25 +5.14, 0.00, 49.66, 50.34, -0.68 +5.08, 0.00, 52.16, 47.84, 4.33 +5.01, 0.00, 52.19, 47.81, 4.39 +4.88, 0.00, 54.75, 45.25, 9.49 +4.88, 0.00, 49.78, 50.22, -0.43 +4.81, 0.00, 52.29, 47.71, 4.58 +4.75, 0.00, 52.32, 47.68, 4.64 +4.61, 0.00, 54.87, 45.13, 9.75 +4.61, 0.00, 49.91, 50.09, -0.18 +4.48, 0.00, 54.94, 45.06, 9.88 +4.48, 0.00, 49.98, 50.02, -0.05 +4.35, 0.00, 55.00, 45.00, 10.01 +4.28, 0.00, 52.57, 47.43, 5.13 +4.28, 0.00, 50.08, 49.92, 0.15 +4.22, 0.00, 52.58, 47.42, 5.17 +4.22, 0.00, 50.09, 49.91, 0.19 +4.09, 0.00, 55.12, 44.88, 10.24 +4.02, 0.00, 52.68, 47.32, 5.37 +4.02, 0.00, 50.20, 49.80, 0.40 +4.02, 0.00, 50.18, 49.82, 0.37 +3.96, 0.00, 52.69, 47.31, 5.38 +3.96, 0.00, 50.20, 49.80, 0.40 +3.82, 0.00, 55.23, 44.77, 10.46 +3.82, 0.00, 50.27, 49.73, 0.55 +3.76, 0.00, 52.78, 47.22, 5.56 +3.76, 0.00, 50.29, 49.71, 0.59 +3.76, 0.00, 50.28, 49.72, 0.56 +3.69, 0.00, 52.79, 47.21, 5.57 +3.69, 0.00, 50.30, 49.70, 0.60 +3.69, 0.00, 50.29, 49.71, 0.58 +3.69, 0.00, 50.27, 49.73, 0.55 +3.56, 0.00, 55.30, 44.70, 10.61 +3.56, 0.00, 50.35, 49.65, 0.69 +3.49, 0.00, 52.85, 47.15, 5.71 +3.49, 0.00, 50.37, 49.63, 0.74 +3.49, 0.00, 50.36, 49.64, 0.71 +3.43, 0.00, 52.86, 47.14, 5.73 +3.43, 0.00, 50.38, 49.62, 0.76 +3.43, 0.00, 50.37, 49.63, 0.73 +3.43, 0.00, 50.35, 49.65, 0.71 +3.30, 0.00, 55.38, 44.62, 10.77 +3.30, 0.00, 50.43, 49.57, 0.86 +3.30, 0.00, 50.42, 49.58, 0.83 +3.30, 0.00, 50.40, 49.60, 0.81 +3.30, 0.00, 50.39, 49.61, 0.78 +3.30, 0.00, 50.38, 49.62, 0.76 +3.30, 0.00, 50.37, 49.63, 0.73 +3.30, 0.00, 50.35, 49.65, 0.71 +3.30, 0.00, 50.34, 49.66, 0.68 +3.30, 0.00, 50.33, 49.67, 0.66 +3.30, 0.00, 50.32, 49.68, 0.63 +3.30, 0.00, 50.30, 49.70, 0.61 +3.23, 0.00, 52.81, 47.19, 5.63 +3.23, 0.00, 50.33, 49.67, 0.66 +3.23, 0.00, 50.32, 49.68, 0.64 +3.23, 0.00, 50.31, 49.69, 0.61 +3.23, 0.00, 50.29, 49.71, 0.59 +3.16, 0.00, 52.80, 47.20, 5.61 +3.16, 0.00, 50.32, 49.68, 0.64 +3.16, 0.00, 50.31, 49.69, 0.61 +3.16, 0.00, 50.30, 49.70, 0.59 +3.16, 0.00, 50.28, 49.72, 0.57 +3.16, 0.00, 50.27, 49.73, 0.54 +3.16, 0.00, 50.26, 49.74, 0.52 +3.16, 0.00, 50.25, 49.75, 0.50 +3.16, 0.00, 50.24, 49.76, 0.47 +3.16, 0.00, 50.22, 49.78, 0.45 +3.16, 0.00, 50.21, 49.79, 0.43 +3.16, 0.00, 50.20, 49.80, 0.40 +3.16, 0.00, 50.19, 49.81, 0.38 +3.16, 0.00, 50.18, 49.82, 0.35 +3.16, 0.00, 50.17, 49.83, 0.33 +3.03, 0.00, 55.20, 44.80, 10.39 +3.03, 0.00, 50.24, 49.76, 0.48 +3.03, 0.00, 50.23, 49.77, 0.46 +3.03, 0.00, 50.22, 49.78, 0.44 +3.03, 0.00, 50.21, 49.79, 0.41 +3.03, 0.00, 50.20, 49.80, 0.39 +3.03, 0.00, 50.18, 49.82, 0.37 +3.03, 0.00, 50.17, 49.83, 0.35 +3.03, 0.00, 50.16, 49.84, 0.32 +3.03, 0.00, 50.15, 49.85, 0.30 +3.03, 0.00, 50.14, 49.86, 0.28 +3.03, 0.00, 50.13, 49.87, 0.25 +2.97, 0.00, 52.64, 47.36, 5.28 +2.97, 0.00, 50.15, 49.85, 0.31 +2.97, 0.00, 50.14, 49.86, 0.29 +2.97, 0.00, 50.13, 49.87, 0.26 +2.97, 0.00, 50.12, 49.88, 0.24 +2.90, 0.00, 52.63, 47.37, 5.26 +2.90, 0.00, 50.15, 49.85, 0.30 +2.90, 0.00, 50.14, 49.86, 0.28 +2.90, 0.00, 50.13, 49.87, 0.25 +2.77, 0.00, 55.16, 44.84, 10.32 +2.77, 0.00, 50.21, 49.79, 0.41 +2.77, 0.00, 50.19, 49.81, 0.39 +2.77, 0.00, 50.18, 49.82, 0.37 +2.77, 0.00, 50.17, 49.83, 0.35 +2.77, 0.00, 50.16, 49.84, 0.33 +2.70, 0.00, 52.68, 47.32, 5.35 +2.70, 0.00, 50.19, 49.81, 0.39 +2.70, 0.00, 50.18, 49.82, 0.37 +2.70, 0.00, 50.17, 49.83, 0.35 +2.70, 0.00, 50.16, 49.84, 0.33 +2.70, 0.00, 50.15, 49.85, 0.30 +2.64, 0.00, 52.66, 47.34, 5.33 +2.70, 0.00, 47.66, 52.34, -4.68 +2.64, 0.00, 52.64, 47.36, 5.29 +2.64, 0.00, 50.16, 49.84, 0.32 +2.64, 0.00, 50.15, 49.85, 0.30 +2.50, 0.00, 55.19, 44.81, 10.37 +2.50, 0.00, 50.23, 49.77, 0.46 +2.50, 0.00, 50.22, 49.78, 0.45 +2.50, 0.00, 50.21, 49.79, 0.43 +2.44, 0.00, 52.73, 47.27, 5.45 +2.44, 0.00, 50.24, 49.76, 0.49 +2.44, 0.00, 50.24, 49.76, 0.47 +2.44, 0.00, 50.23, 49.77, 0.45 +2.44, 0.00, 50.22, 49.78, 0.43 +2.44, 0.00, 50.21, 49.79, 0.42 +2.44, 0.00, 50.20, 49.80, 0.40 +2.44, 0.00, 50.19, 49.81, 0.38 +2.44, 0.00, 50.18, 49.82, 0.36 +2.44, 0.00, 50.17, 49.83, 0.34 +2.37, 0.00, 52.68, 47.32, 5.37 +2.37, 0.00, 50.20, 49.80, 0.41 +2.37, 0.00, 50.19, 49.81, 0.39 +2.24, 0.00, 55.23, 44.77, 10.46 +2.24, 0.00, 50.28, 49.72, 0.55 +2.24, 0.00, 50.27, 49.73, 0.54 +2.18, 0.00, 52.78, 47.22, 5.56 +2.18, 0.00, 50.30, 49.70, 0.60 +2.18, 0.00, 50.29, 49.71, 0.59 +2.18, 0.00, 50.28, 49.72, 0.57 +2.11, 0.00, 52.80, 47.20, 5.60 +2.11, 0.00, 50.32, 49.68, 0.64 +2.11, 0.00, 50.31, 49.69, 0.62 +2.11, 0.00, 50.30, 49.70, 0.60 +2.11, 0.00, 50.29, 49.71, 0.59 +1.98, 0.00, 55.33, 44.67, 10.66 +1.98, 0.00, 50.38, 49.62, 0.76 +1.98, 0.00, 50.37, 49.63, 0.74 +1.98, 0.00, 50.36, 49.64, 0.73 +1.91, 0.00, 52.88, 47.12, 5.76 +1.91, 0.00, 50.40, 49.60, 0.80 +1.91, 0.00, 50.39, 49.61, 0.78 +1.85, 0.00, 52.91, 47.09, 5.81 +1.85, 0.00, 50.43, 49.57, 0.85 +1.85, 0.00, 50.42, 49.58, 0.84 +1.85, 0.00, 50.41, 49.59, 0.83 +1.85, 0.00, 50.41, 49.59, 0.81 +1.71, 0.00, 55.44, 44.56, 10.89 +1.71, 0.00, 50.49, 49.51, 0.99 +1.71, 0.00, 50.49, 49.51, 0.97 +1.71, 0.00, 50.48, 49.52, 0.96 +1.71, 0.00, 50.47, 49.53, 0.95 +1.71, 0.00, 50.47, 49.53, 0.93 +1.65, 0.00, 52.98, 47.02, 5.96 +1.65, 0.00, 50.50, 49.50, 1.01 +1.65, 0.00, 50.50, 49.50, 1.00 +1.65, 0.00, 50.49, 49.51, 0.98 +1.65, 0.00, 50.49, 49.51, 0.97 +1.58, 0.00, 53.00, 47.00, 6.00 +1.58, 0.00, 50.52, 49.48, 1.05 +1.58, 0.00, 50.52, 49.48, 1.03 +1.45, 0.00, 55.55, 44.45, 11.11 +1.45, 0.00, 50.61, 49.39, 1.21 +1.45, 0.00, 50.60, 49.40, 1.20 +1.38, 0.00, 53.12, 46.88, 6.23 +1.38, 0.00, 50.64, 49.36, 1.28 +1.38, 0.00, 50.63, 49.37, 1.27 +1.38, 0.00, 50.63, 49.37, 1.26 +1.38, 0.00, 50.62, 49.38, 1.25 +1.32, 0.00, 53.14, 46.86, 6.28 +1.32, 0.00, 50.66, 49.34, 1.33 +1.32, 0.00, 50.66, 49.34, 1.32 +1.32, 0.00, 50.65, 49.35, 1.31 +1.32, 0.00, 50.65, 49.35, 1.30 +1.32, 0.00, 50.64, 49.36, 1.29 +1.32, 0.00, 50.64, 49.36, 1.28 +1.32, 0.00, 50.63, 49.37, 1.27 +1.32, 0.00, 50.63, 49.37, 1.26 +1.19, 0.00, 55.67, 44.33, 11.33 +1.19, 0.00, 50.72, 49.28, 1.44 +1.19, 0.00, 50.71, 49.29, 1.43 +1.19, 0.00, 50.71, 49.29, 1.42 +1.12, 0.00, 53.23, 46.77, 6.45 +1.12, 0.00, 50.75, 49.25, 1.50 +1.12, 0.00, 50.75, 49.25, 1.49 +1.12, 0.00, 50.74, 49.26, 1.48 +1.12, 0.00, 50.74, 49.26, 1.48 +1.05, 0.00, 53.25, 46.75, 6.51 +1.05, 0.00, 50.78, 49.22, 1.56 +1.05, 0.00, 50.78, 49.22, 1.55 +1.05, 0.00, 50.77, 49.23, 1.54 +1.05, 0.00, 50.77, 49.23, 1.53 +1.05, 0.00, 50.76, 49.24, 1.53 +1.05, 0.00, 50.76, 49.24, 1.52 +0.92, 0.00, 55.80, 44.20, 11.60 +1.05, 0.00, 45.81, 54.19, -8.38 +0.92, 0.00, 55.79, 44.21, 11.58 +0.92, 0.00, 50.84, 49.16, 1.69 +0.92, 0.00, 50.84, 49.16, 1.68 +0.92, 0.00, 50.84, 49.16, 1.67 +0.86, 0.00, 53.36, 46.64, 6.71 +0.86, 0.00, 50.88, 49.12, 1.76 +0.86, 0.00, 50.88, 49.12, 1.75 +0.86, 0.00, 50.87, 49.13, 1.75 +0.86, 0.00, 50.87, 49.13, 1.74 +0.86, 0.00, 50.87, 49.13, 1.73 +0.86, 0.00, 50.86, 49.14, 1.73 +0.79, 0.00, 53.38, 46.62, 6.76 +0.79, 0.00, 50.91, 49.09, 1.81 +0.79, 0.00, 50.90, 49.10, 1.81 +0.79, 0.00, 50.90, 49.10, 1.80 +0.79, 0.00, 50.90, 49.10, 1.80 +0.79, 0.00, 50.90, 49.10, 1.79 +0.66, 0.00, 55.94, 44.06, 11.87 +0.79, 0.00, 45.95, 54.05, -8.11 +0.66, 0.00, 55.93, 44.07, 11.86 +0.66, 0.00, 50.98, 49.02, 1.97 +0.66, 0.00, 50.98, 49.02, 1.96 +0.66, 0.00, 50.98, 49.02, 1.96 +0.66, 0.00, 50.98, 49.02, 1.95 +0.66, 0.00, 50.97, 49.03, 1.95 +0.66, 0.00, 50.97, 49.03, 1.94 +0.66, 0.00, 50.97, 49.03, 1.94 +0.66, 0.00, 50.97, 49.03, 1.93 +0.66, 0.00, 50.96, 49.04, 1.93 +0.59, 0.00, 53.48, 46.52, 6.97 +0.66, 0.00, 48.49, 51.51, -3.02 +0.59, 0.00, 53.48, 46.52, 6.96 +0.66, 0.00, 48.48, 51.52, -3.03 +0.59, 0.00, 53.47, 46.53, 6.95 +0.59, 0.00, 51.00, 49.00, 2.00 +0.59, 0.00, 51.00, 49.00, 2.00 +0.59, 0.00, 51.00, 49.00, 1.99 +0.59, 0.00, 50.99, 49.01, 1.99 +0.59, 0.00, 50.99, 49.01, 1.98 +0.59, 0.00, 50.99, 49.01, 1.98 +0.59, 0.00, 50.99, 49.01, 1.97 +0.59, 0.00, 50.98, 49.02, 1.97 +0.59, 0.00, 50.98, 49.02, 1.96 +0.59, 0.00, 50.98, 49.02, 1.96 +0.59, 0.00, 50.98, 49.02, 1.96 +0.59, 0.00, 50.98, 49.02, 1.95 +0.59, 0.00, 50.97, 49.03, 1.95 +0.59, 0.00, 50.97, 49.03, 1.94 +0.59, 0.00, 50.97, 49.03, 1.94 +0.59, 0.00, 50.97, 49.03, 1.93 +0.59, 0.00, 50.96, 49.04, 1.93 +0.59, 0.00, 50.96, 49.04, 1.92 +0.59, 0.00, 50.96, 49.04, 1.92 +0.66, 0.00, 48.44, 51.56, -3.13 +0.66, 0.00, 50.91, 49.09, 1.81 +0.66, 0.00, 50.90, 49.10, 1.81 +0.66, 0.00, 50.90, 49.10, 1.80 +0.66, 0.00, 50.90, 49.10, 1.80 +0.66, 0.00, 50.90, 49.10, 1.79 +0.66, 0.00, 50.89, 49.11, 1.79 +0.66, 0.00, 50.89, 49.11, 1.78 +0.66, 0.00, 50.89, 49.11, 1.78 +0.66, 0.00, 50.89, 49.11, 1.77 +0.66, 0.00, 50.88, 49.12, 1.77 +0.66, 0.00, 50.88, 49.12, 1.76 +0.79, 0.00, 45.83, 54.17, -8.33 +0.79, 0.00, 50.78, 49.22, 1.55 +0.79, 0.00, 50.77, 49.23, 1.55 +0.79, 0.00, 50.77, 49.23, 1.54 +0.79, 0.00, 50.77, 49.23, 1.53 +0.79, 0.00, 50.76, 49.24, 1.53 +0.79, 0.00, 50.76, 49.24, 1.52 +0.86, 0.00, 48.24, 51.76, -3.53 +0.86, 0.00, 50.71, 49.29, 1.41 +0.86, 0.00, 50.70, 49.30, 1.40 +0.86, 0.00, 50.70, 49.30, 1.40 +0.86, 0.00, 50.70, 49.30, 1.39 +0.86, 0.00, 50.69, 49.31, 1.38 +0.86, 0.00, 50.69, 49.31, 1.38 +0.86, 0.00, 50.69, 49.31, 1.37 +0.86, 0.00, 50.68, 49.32, 1.37 +0.86, 0.00, 50.68, 49.32, 1.36 +0.86, 0.00, 50.68, 49.32, 1.35 +0.92, 0.00, 48.15, 51.85, -3.70 +0.92, 0.00, 50.62, 49.38, 1.24 +0.92, 0.00, 50.62, 49.38, 1.23 +0.92, 0.00, 50.61, 49.39, 1.23 +0.92, 0.00, 50.61, 49.39, 1.22 +1.05, 0.00, 45.56, 54.44, -8.87 +1.05, 0.00, 50.50, 49.50, 1.01 +1.05, 0.00, 50.50, 49.50, 1.00 +1.05, 0.00, 50.49, 49.51, 0.99 +1.12, 0.00, 47.97, 52.03, -4.06 +1.12, 0.00, 50.44, 49.56, 0.87 +1.12, 0.00, 50.43, 49.57, 0.87 +1.12, 0.00, 50.43, 49.57, 0.86 +1.12, 0.00, 50.42, 49.58, 0.85 +1.12, 0.00, 50.42, 49.58, 0.84 +1.12, 0.00, 50.42, 49.58, 0.83 +1.19, 0.00, 47.89, 52.11, -4.22 +1.19, 0.00, 50.36, 49.64, 0.72 +1.19, 0.00, 50.35, 49.65, 0.71 +1.19, 0.00, 50.35, 49.65, 0.70 +1.19, 0.00, 50.34, 49.66, 0.69 +1.19, 0.00, 50.34, 49.66, 0.68 +1.32, 0.00, 45.29, 54.71, -9.42 +1.32, 0.00, 50.23, 49.77, 0.46 +1.32, 0.00, 50.23, 49.77, 0.45 +1.32, 0.00, 50.22, 49.78, 0.44 +1.32, 0.00, 50.22, 49.78, 0.43 +1.32, 0.00, 50.21, 49.79, 0.42 +1.32, 0.00, 50.21, 49.79, 0.41 +1.38, 0.00, 47.68, 52.32, -4.64 +1.38, 0.00, 50.15, 49.85, 0.29 +1.38, 0.00, 50.14, 49.86, 0.28 +1.38, 0.00, 50.14, 49.86, 0.27 +1.38, 0.00, 50.13, 49.87, 0.26 +1.38, 0.00, 50.13, 49.87, 0.25 +1.32, 0.00, 52.64, 47.36, 5.28 +1.32, 0.00, 50.17, 49.83, 0.33 +1.32, 0.00, 50.16, 49.84, 0.32 +1.32, 0.00, 50.16, 49.84, 0.31 +1.38, 0.00, 47.63, 52.37, -4.74 +1.32, 0.00, 52.62, 47.38, 5.23 +1.38, 0.00, 47.62, 52.38, -4.76 +1.38, 0.00, 50.09, 49.91, 0.17 +1.38, 0.00, 50.08, 49.92, 0.16 +1.38, 0.00, 50.08, 49.92, 0.15 +1.38, 0.00, 50.07, 49.93, 0.14 +1.38, 0.00, 50.06, 49.94, 0.13 +1.38, 0.00, 50.06, 49.94, 0.12 +1.32, 0.00, 52.58, 47.42, 5.15 +1.32, 0.00, 50.10, 49.90, 0.20 +1.32, 0.00, 50.09, 49.91, 0.19 +1.32, 0.00, 50.09, 49.91, 0.18 +1.32, 0.00, 50.08, 49.92, 0.17 +1.32, 0.00, 50.08, 49.92, 0.16 +1.32, 0.00, 50.07, 49.93, 0.15 +1.19, 0.00, 55.11, 44.89, 10.23 +1.19, 0.00, 50.16, 49.84, 0.33 +1.19, 0.00, 50.16, 49.84, 0.32 +1.19, 0.00, 50.16, 49.84, 0.31 +1.19, 0.00, 50.15, 49.85, 0.30 +1.12, 0.00, 52.67, 47.33, 5.34 +1.12, 0.00, 50.19, 49.81, 0.38 +1.12, 0.00, 50.19, 49.81, 0.38 +1.12, 0.00, 50.18, 49.82, 0.37 +1.05, 0.00, 52.70, 47.30, 5.40 +1.05, 0.00, 50.23, 49.77, 0.45 +1.05, 0.00, 50.22, 49.78, 0.44 +1.05, 0.00, 50.22, 49.78, 0.43 +1.05, 0.00, 50.21, 49.79, 0.43 +0.92, 0.00, 55.25, 44.75, 10.51 +0.92, 0.00, 50.31, 49.69, 0.61 +0.92, 0.00, 50.30, 49.70, 0.60 +0.86, 0.00, 52.82, 47.18, 5.64 +0.86, 0.00, 50.34, 49.66, 0.69 +0.86, 0.00, 50.34, 49.66, 0.68 +0.86, 0.00, 50.34, 49.66, 0.68 +0.79, 0.00, 52.86, 47.14, 5.71 +0.79, 0.00, 50.38, 49.62, 0.76 +0.79, 0.00, 50.38, 49.62, 0.76 +0.79, 0.00, 50.38, 49.62, 0.75 +0.66, 0.00, 55.42, 44.58, 10.83 +0.66, 0.00, 50.47, 49.53, 0.94 +0.66, 0.00, 50.47, 49.53, 0.93 +0.66, 0.00, 50.46, 49.54, 0.93 +0.66, 0.00, 50.46, 49.54, 0.92 +0.59, 0.00, 52.98, 47.02, 5.96 +0.66, 0.00, 47.99, 52.01, -4.03 +0.59, 0.00, 52.98, 47.02, 5.95 +0.59, 0.00, 50.50, 49.50, 1.01 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 0.99 +0.53, 0.00, 53.02, 46.98, 6.03 +0.53, 0.00, 50.54, 49.46, 1.08 +0.53, 0.00, 50.54, 49.46, 1.08 +0.53, 0.00, 50.54, 49.46, 1.08 +0.53, 0.00, 50.54, 49.46, 1.07 +0.53, 0.00, 50.53, 49.47, 1.07 +0.53, 0.00, 50.53, 49.47, 1.06 +0.53, 0.00, 50.53, 49.47, 1.06 +0.40, 0.00, 55.57, 44.43, 11.14 +0.40, 0.00, 50.63, 49.37, 1.25 +0.40, 0.00, 50.62, 49.38, 1.25 +0.40, 0.00, 50.62, 49.38, 1.25 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.23 +0.33, 0.00, 53.14, 46.86, 6.27 +0.33, 0.00, 50.66, 49.34, 1.33 +0.33, 0.00, 50.66, 49.34, 1.32 +0.33, 0.00, 50.66, 49.34, 1.32 +0.33, 0.00, 50.66, 49.34, 1.32 +0.33, 0.00, 50.66, 49.34, 1.32 +0.40, 0.00, 48.14, 51.86, -3.73 +0.33, 0.00, 53.13, 46.87, 6.26 +0.40, 0.00, 48.13, 51.87, -3.73 +0.40, 0.00, 50.60, 49.40, 1.21 +0.40, 0.00, 50.60, 49.40, 1.20 +0.33, 0.00, 53.12, 46.88, 6.24 +0.40, 0.00, 48.13, 51.87, -3.75 +0.40, 0.00, 50.60, 49.40, 1.20 +0.40, 0.00, 50.60, 49.40, 1.19 +0.40, 0.00, 50.59, 49.41, 1.19 +0.40, 0.00, 50.59, 49.41, 1.19 +0.40, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 50.59, 49.41, 1.17 +0.40, 0.00, 50.58, 49.42, 1.17 +0.40, 0.00, 50.58, 49.42, 1.17 +0.40, 0.00, 50.58, 49.42, 1.16 +0.40, 0.00, 50.58, 49.42, 1.16 +0.40, 0.00, 50.58, 49.42, 1.16 +0.53, 0.00, 45.53, 54.47, -8.93 +0.53, 0.00, 50.48, 49.52, 0.95 +0.53, 0.00, 50.47, 49.53, 0.95 +0.53, 0.00, 50.47, 49.53, 0.94 +0.53, 0.00, 50.47, 49.53, 0.94 +0.53, 0.00, 50.47, 49.53, 0.94 +0.53, 0.00, 50.47, 49.53, 0.93 +0.53, 0.00, 50.46, 49.54, 0.93 +0.59, 0.00, 47.94, 52.06, -4.12 +0.59, 0.00, 50.41, 49.59, 0.82 +0.59, 0.00, 50.41, 49.59, 0.82 +0.59, 0.00, 50.41, 49.59, 0.81 +0.59, 0.00, 50.40, 49.60, 0.81 +0.59, 0.00, 50.40, 49.60, 0.80 +0.59, 0.00, 50.40, 49.60, 0.80 +0.66, 0.00, 47.88, 52.12, -4.25 +0.66, 0.00, 50.34, 49.66, 0.69 +0.66, 0.00, 50.34, 49.66, 0.68 +0.66, 0.00, 50.34, 49.66, 0.68 +0.66, 0.00, 50.34, 49.66, 0.67 +0.66, 0.00, 50.33, 49.67, 0.67 +0.79, 0.00, 45.29, 54.71, -9.42 +0.79, 0.00, 50.23, 49.77, 0.46 +0.79, 0.00, 50.23, 49.77, 0.45 +0.79, 0.00, 50.22, 49.78, 0.45 +0.79, 0.00, 50.22, 49.78, 0.44 +0.79, 0.00, 50.22, 49.78, 0.44 +0.86, 0.00, 47.69, 52.31, -4.61 +0.86, 0.00, 50.16, 49.84, 0.32 +0.86, 0.00, 50.16, 49.84, 0.32 +0.86, 0.00, 50.16, 49.84, 0.31 +0.86, 0.00, 50.15, 49.85, 0.30 +0.86, 0.00, 50.15, 49.85, 0.30 +0.92, 0.00, 47.62, 52.38, -4.75 +0.92, 0.00, 50.09, 49.91, 0.19 +0.92, 0.00, 50.09, 49.91, 0.18 +0.92, 0.00, 50.09, 49.91, 0.17 +0.92, 0.00, 50.08, 49.92, 0.16 +1.05, 0.00, 45.04, 54.96, -9.93 +1.05, 0.00, 49.98, 50.02, -0.05 +1.05, 0.00, 49.97, 50.03, -0.06 +1.05, 0.00, 49.97, 50.03, -0.06 +1.05, 0.00, 49.96, 50.04, -0.07 +1.05, 0.00, 49.96, 50.04, -0.08 +1.05, 0.00, 49.96, 50.04, -0.09 +1.05, 0.00, 49.95, 50.05, -0.10 +1.05, 0.00, 49.95, 50.05, -0.10 +1.05, 0.00, 49.94, 50.06, -0.11 +1.05, 0.00, 49.94, 50.06, -0.12 +1.05, 0.00, 49.94, 50.06, -0.13 +1.05, 0.00, 49.93, 50.07, -0.14 +1.12, 0.00, 47.41, 52.59, -5.19 +1.12, 0.00, 49.87, 50.13, -0.25 +1.12, 0.00, 49.87, 50.13, -0.26 +1.12, 0.00, 49.87, 50.13, -0.27 +1.12, 0.00, 49.86, 50.14, -0.28 +1.12, 0.00, 49.86, 50.14, -0.28 +1.12, 0.00, 49.85, 50.15, -0.29 +1.12, 0.00, 49.85, 50.15, -0.30 +1.05, 0.00, 52.37, 47.63, 4.73 +1.05, 0.00, 49.89, 50.11, -0.22 +1.05, 0.00, 49.89, 50.11, -0.23 +1.05, 0.00, 49.88, 50.12, -0.23 +1.05, 0.00, 49.88, 50.12, -0.24 +1.05, 0.00, 49.87, 50.13, -0.25 +1.05, 0.00, 49.87, 50.13, -0.26 +1.05, 0.00, 49.87, 50.13, -0.27 +1.05, 0.00, 49.86, 50.14, -0.27 +1.05, 0.00, 49.86, 50.14, -0.28 +0.92, 0.00, 54.90, 45.10, 9.80 +1.05, 0.00, 44.91, 55.09, -10.18 +1.05, 0.00, 49.85, 50.15, -0.30 +1.05, 0.00, 49.84, 50.16, -0.31 +0.92, 0.00, 54.88, 45.12, 9.77 +0.92, 0.00, 49.94, 50.06, -0.13 +0.92, 0.00, 49.93, 50.07, -0.14 +0.92, 0.00, 49.93, 50.07, -0.14 +0.92, 0.00, 49.93, 50.07, -0.15 +0.92, 0.00, 49.92, 50.08, -0.16 +0.92, 0.00, 49.92, 50.08, -0.16 +0.92, 0.00, 49.91, 50.09, -0.17 +0.86, 0.00, 52.43, 47.57, 4.87 +0.86, 0.00, 49.96, 50.04, -0.08 +0.86, 0.00, 49.95, 50.05, -0.09 +0.86, 0.00, 49.95, 50.05, -0.10 +0.86, 0.00, 49.95, 50.05, -0.10 +0.86, 0.00, 49.95, 50.05, -0.11 +0.86, 0.00, 49.94, 50.06, -0.12 +0.86, 0.00, 49.94, 50.06, -0.12 +0.86, 0.00, 49.94, 50.06, -0.13 +0.86, 0.00, 49.93, 50.07, -0.14 +0.86, 0.00, 49.93, 50.07, -0.14 +0.86, 0.00, 49.93, 50.07, -0.15 +0.86, 0.00, 49.92, 50.08, -0.15 +0.86, 0.00, 49.92, 50.08, -0.16 +0.86, 0.00, 49.92, 50.08, -0.17 +0.86, 0.00, 49.91, 50.09, -0.17 +0.79, 0.00, 52.43, 47.57, 4.86 +0.79, 0.00, 49.96, 50.04, -0.09 +0.86, 0.00, 47.43, 52.57, -5.14 +0.79, 0.00, 52.42, 47.58, 4.84 +0.86, 0.00, 47.43, 52.57, -5.15 +0.86, 0.00, 49.89, 50.11, -0.21 +0.86, 0.00, 49.89, 50.11, -0.22 +0.86, 0.00, 49.89, 50.11, -0.22 +0.86, 0.00, 49.88, 50.12, -0.23 +0.86, 0.00, 49.88, 50.12, -0.24 +0.86, 0.00, 49.88, 50.12, -0.24 +0.79, 0.00, 52.40, 47.60, 4.79 +0.79, 0.00, 49.92, 50.08, -0.16 +0.79, 0.00, 49.92, 50.08, -0.16 +0.79, 0.00, 49.92, 50.08, -0.17 +0.79, 0.00, 49.91, 50.09, -0.17 +0.79, 0.00, 49.91, 50.09, -0.18 +0.79, 0.00, 49.91, 50.09, -0.19 +0.79, 0.00, 49.90, 50.10, -0.19 +0.79, 0.00, 49.90, 50.10, -0.20 +0.79, 0.00, 49.90, 50.10, -0.20 +0.79, 0.00, 49.90, 50.10, -0.21 +0.79, 0.00, 49.89, 50.11, -0.22 +0.79, 0.00, 49.89, 50.11, -0.22 +0.79, 0.00, 49.89, 50.11, -0.23 +0.79, 0.00, 49.88, 50.12, -0.23 +0.79, 0.00, 49.88, 50.12, -0.24 +0.79, 0.00, 49.88, 50.12, -0.25 +0.79, 0.00, 49.87, 50.13, -0.25 +0.79, 0.00, 49.87, 50.13, -0.26 +0.79, 0.00, 49.87, 50.13, -0.26 +0.79, 0.00, 49.87, 50.13, -0.27 +0.79, 0.00, 49.86, 50.14, -0.28 +0.79, 0.00, 49.86, 50.14, -0.28 +0.66, 0.00, 54.90, 45.10, 9.80 +0.66, 0.00, 49.95, 50.05, -0.09 +0.66, 0.00, 49.95, 50.05, -0.10 +0.66, 0.00, 49.95, 50.05, -0.10 +0.66, 0.00, 49.95, 50.05, -0.11 +0.66, 0.00, 49.94, 50.06, -0.11 +0.66, 0.00, 49.94, 50.06, -0.12 +0.66, 0.00, 49.94, 50.06, -0.12 +0.66, 0.00, 49.94, 50.06, -0.13 +0.66, 0.00, 49.93, 50.07, -0.13 +0.79, 0.00, 44.89, 55.11, -10.22 +0.79, 0.00, 49.83, 50.17, -0.34 +0.66, 0.00, 54.87, 45.13, 9.74 +0.66, 0.00, 49.92, 50.08, -0.15 +0.66, 0.00, 49.92, 50.08, -0.16 +0.66, 0.00, 49.92, 50.08, -0.16 +0.66, 0.00, 49.92, 50.08, -0.17 +0.66, 0.00, 49.91, 50.09, -0.17 +0.66, 0.00, 49.91, 50.09, -0.18 +0.66, 0.00, 49.91, 50.09, -0.18 +0.66, 0.00, 49.91, 50.09, -0.19 +0.66, 0.00, 49.90, 50.10, -0.19 +0.66, 0.00, 49.90, 50.10, -0.20 +0.66, 0.00, 49.90, 50.10, -0.20 +0.66, 0.00, 49.90, 50.10, -0.21 +0.66, 0.00, 49.89, 50.11, -0.21 +0.66, 0.00, 49.89, 50.11, -0.22 +0.66, 0.00, 49.89, 50.11, -0.22 +0.66, 0.00, 49.89, 50.11, -0.23 +0.66, 0.00, 49.88, 50.12, -0.23 +0.66, 0.00, 49.88, 50.12, -0.24 +0.66, 0.00, 49.88, 50.12, -0.24 +0.66, 0.00, 49.88, 50.12, -0.25 +0.66, 0.00, 49.87, 50.13, -0.25 +0.66, 0.00, 49.87, 50.13, -0.26 +0.59, 0.00, 52.39, 47.61, 4.78 +0.59, 0.00, 49.92, 50.08, -0.17 +0.59, 0.00, 49.91, 50.09, -0.17 +0.59, 0.00, 49.91, 50.09, -0.18 +0.59, 0.00, 49.91, 50.09, -0.18 +0.59, 0.00, 49.91, 50.09, -0.19 +0.59, 0.00, 49.90, 50.10, -0.19 +0.59, 0.00, 49.90, 50.10, -0.19 +0.59, 0.00, 49.90, 50.10, -0.20 +0.59, 0.00, 49.90, 50.10, -0.20 +0.59, 0.00, 49.90, 50.10, -0.21 +0.59, 0.00, 49.89, 50.11, -0.21 +0.59, 0.00, 49.89, 50.11, -0.22 +0.59, 0.00, 49.89, 50.11, -0.22 +0.59, 0.00, 49.89, 50.11, -0.23 +0.59, 0.00, 49.88, 50.12, -0.23 +0.59, 0.00, 49.88, 50.12, -0.23 +0.59, 0.00, 49.88, 50.12, -0.24 +0.53, 0.00, 52.40, 47.60, 4.80 +0.53, 0.00, 49.93, 50.07, -0.15 +0.53, 0.00, 49.92, 50.08, -0.15 +0.53, 0.00, 49.92, 50.08, -0.16 +0.53, 0.00, 49.92, 50.08, -0.16 +0.53, 0.00, 49.92, 50.08, -0.16 +0.53, 0.00, 49.92, 50.08, -0.17 +0.53, 0.00, 49.91, 50.09, -0.17 +0.53, 0.00, 49.91, 50.09, -0.18 +0.53, 0.00, 49.91, 50.09, -0.18 +0.53, 0.00, 49.91, 50.09, -0.18 +0.53, 0.00, 49.91, 50.09, -0.19 +0.53, 0.00, 49.90, 50.10, -0.19 +0.53, 0.00, 49.90, 50.10, -0.20 +0.53, 0.00, 49.90, 50.10, -0.20 +0.40, 0.00, 54.94, 45.06, 9.88 +0.40, 0.00, 50.00, 50.00, -0.01 +0.40, 0.00, 49.99, 50.01, -0.01 +0.40, 0.00, 49.99, 50.01, -0.01 +0.40, 0.00, 49.99, 50.01, -0.02 +0.40, 0.00, 49.99, 50.01, -0.02 +0.40, 0.00, 49.99, 50.01, -0.02 +0.40, 0.00, 49.99, 50.01, -0.03 +0.40, 0.00, 49.99, 50.01, -0.03 +0.40, 0.00, 49.98, 50.02, -0.03 +0.40, 0.00, 49.98, 50.02, -0.03 +0.40, 0.00, 49.98, 50.02, -0.04 +0.40, 0.00, 49.98, 50.02, -0.04 +0.40, 0.00, 49.98, 50.02, -0.04 +0.40, 0.00, 49.98, 50.02, -0.05 +0.40, 0.00, 49.98, 50.02, -0.05 +0.33, 0.00, 52.50, 47.50, 4.99 +0.33, 0.00, 50.02, 49.98, 0.04 +0.33, 0.00, 50.02, 49.98, 0.04 +0.33, 0.00, 50.02, 49.98, 0.04 +0.33, 0.00, 50.02, 49.98, 0.04 +0.33, 0.00, 50.02, 49.98, 0.03 +0.26, 0.00, 52.54, 47.46, 5.08 +0.26, 0.00, 50.06, 49.94, 0.13 +0.26, 0.00, 50.06, 49.94, 0.13 +0.26, 0.00, 50.06, 49.94, 0.13 +0.26, 0.00, 50.06, 49.94, 0.12 +0.26, 0.00, 50.06, 49.94, 0.12 +0.26, 0.00, 50.06, 49.94, 0.12 +0.26, 0.00, 50.06, 49.94, 0.12 +0.33, 0.00, 47.54, 52.46, -4.93 +0.26, 0.00, 52.53, 47.47, 5.06 +0.26, 0.00, 50.06, 49.94, 0.11 +0.26, 0.00, 50.05, 49.95, 0.11 +0.26, 0.00, 50.05, 49.95, 0.11 +0.26, 0.00, 50.05, 49.95, 0.11 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.09 +0.26, 0.00, 50.05, 49.95, 0.09 +0.26, 0.00, 50.04, 49.96, 0.09 +0.26, 0.00, 50.04, 49.96, 0.09 +0.26, 0.00, 50.04, 49.96, 0.09 +0.26, 0.00, 50.04, 49.96, 0.08 +0.26, 0.00, 50.04, 49.96, 0.08 +0.26, 0.00, 50.04, 49.96, 0.08 +0.26, 0.00, 50.04, 49.96, 0.08 +0.13, 0.00, 55.08, 44.92, 10.16 +0.13, 0.00, 50.14, 49.86, 0.27 +0.13, 0.00, 50.14, 49.86, 0.27 +0.13, 0.00, 50.14, 49.86, 0.27 +0.13, 0.00, 50.14, 49.86, 0.27 +0.13, 0.00, 50.13, 49.87, 0.27 +0.07, 0.00, 52.66, 47.34, 5.31 +0.13, 0.00, 47.66, 52.34, -4.68 +0.07, 0.00, 52.66, 47.34, 5.31 +0.07, 0.00, 50.18, 49.82, 0.37 +0.13, 0.00, 47.66, 52.34, -4.68 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.07, 0.00, 52.65, 47.35, 5.30 +0.07, 0.00, 50.18, 49.82, 0.36 +0.07, 0.00, 50.18, 49.82, 0.36 +0.00, 0.00, 52.70, 47.30, 5.40 +0.00, 0.00, 50.23, 49.77, 0.46 +0.00, 0.00, 50.23, 49.77, 0.46 +0.00, 0.00, 50.23, 49.77, 0.46 +0.00, 0.00, 50.23, 49.77, 0.46 +-0.13, 0.00, 55.27, 44.73, 10.54 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.20, 0.00, 52.85, 47.15, 5.71 +-0.20, 0.00, 50.38, 49.62, 0.77 +-0.26, 0.00, 52.91, 47.09, 5.81 +-0.26, 0.00, 50.43, 49.57, 0.87 +-0.26, 0.00, 50.44, 49.56, 0.87 +-0.26, 0.00, 50.44, 49.56, 0.87 +-0.40, 0.00, 55.48, 44.52, 10.96 +-0.40, 0.00, 50.54, 49.46, 1.08 +-0.40, 0.00, 50.54, 49.46, 1.08 +-0.40, 0.00, 50.54, 49.46, 1.08 +-0.40, 0.00, 50.54, 49.46, 1.09 +-0.40, 0.00, 50.54, 49.46, 1.09 +-0.40, 0.00, 50.55, 49.45, 1.09 +-0.40, 0.00, 50.55, 49.45, 1.09 +-0.40, 0.00, 50.55, 49.45, 1.10 +-0.40, 0.00, 50.55, 49.45, 1.10 +-0.40, 0.00, 50.55, 49.45, 1.10 +-0.46, 0.00, 53.08, 46.93, 6.15 +-0.46, 0.00, 50.60, 49.40, 1.21 +-0.46, 0.00, 50.61, 49.39, 1.21 +-0.46, 0.00, 50.61, 49.39, 1.22 +-0.53, 0.00, 53.13, 46.87, 6.26 +-0.53, 0.00, 50.66, 49.34, 1.32 +-0.53, 0.00, 50.66, 49.34, 1.33 +-0.53, 0.00, 50.67, 49.33, 1.33 +-0.53, 0.00, 50.67, 49.33, 1.34 +-0.53, 0.00, 50.67, 49.33, 1.34 +-0.53, 0.00, 50.67, 49.33, 1.34 +-0.53, 0.00, 50.67, 49.33, 1.35 +-0.53, 0.00, 50.68, 49.32, 1.35 +-0.66, 0.00, 55.72, 44.28, 11.44 +-0.53, 0.00, 45.74, 54.26, -8.53 +-0.66, 0.00, 55.73, 44.27, 11.45 +-0.53, 0.00, 45.74, 54.26, -8.52 +-0.66, 0.00, 55.73, 44.27, 11.46 +-0.66, 0.00, 50.79, 49.21, 1.58 +-0.66, 0.00, 50.79, 49.21, 1.58 +-0.66, 0.00, 50.79, 49.21, 1.59 +-0.66, 0.00, 50.80, 49.20, 1.59 +-0.66, 0.00, 50.80, 49.20, 1.60 +-0.66, 0.00, 50.80, 49.20, 1.60 +-0.66, 0.00, 50.80, 49.20, 1.61 +-0.66, 0.00, 50.81, 49.19, 1.61 +-0.66, 0.00, 50.81, 49.19, 1.62 +-0.66, 0.00, 50.81, 49.19, 1.62 +-0.66, 0.00, 50.81, 49.19, 1.63 +-0.66, 0.00, 50.82, 49.18, 1.63 +-0.66, 0.00, 50.82, 49.18, 1.64 +-0.66, 0.00, 50.82, 49.18, 1.64 +-0.66, 0.00, 50.82, 49.18, 1.65 +-0.53, 0.00, 45.78, 54.22, -8.44 +-0.53, 0.00, 50.73, 49.27, 1.46 +-0.66, 0.00, 55.77, 44.23, 11.55 +-0.53, 0.00, 45.79, 54.21, -8.42 +-0.53, 0.00, 50.73, 49.27, 1.47 +-0.53, 0.00, 50.74, 49.26, 1.47 +-0.53, 0.00, 50.74, 49.26, 1.48 +-0.53, 0.00, 50.74, 49.26, 1.48 +-0.53, 0.00, 50.74, 49.26, 1.48 +-0.53, 0.00, 50.74, 49.26, 1.49 +-0.53, 0.00, 50.75, 49.25, 1.49 +-0.53, 0.00, 50.75, 49.25, 1.50 +-0.53, 0.00, 50.75, 49.25, 1.50 +-0.53, 0.00, 50.75, 49.25, 1.50 +-0.53, 0.00, 50.75, 49.25, 1.51 +-0.53, 0.00, 50.76, 49.24, 1.51 +-0.46, 0.00, 48.24, 51.76, -3.53 +-0.46, 0.00, 50.71, 49.29, 1.42 +-0.46, 0.00, 50.71, 49.29, 1.42 +-0.46, 0.00, 50.71, 49.29, 1.43 +-0.46, 0.00, 50.72, 49.28, 1.43 +-0.46, 0.00, 50.72, 49.28, 1.43 +-0.46, 0.00, 50.72, 49.28, 1.44 +-0.46, 0.00, 50.72, 49.28, 1.44 +-0.46, 0.00, 50.72, 49.28, 1.44 +-0.46, 0.00, 50.72, 49.28, 1.45 +-0.46, 0.00, 50.73, 49.27, 1.45 +-0.40, 0.00, 48.21, 51.79, -3.59 +-0.40, 0.00, 50.68, 49.32, 1.36 +-0.40, 0.00, 50.68, 49.32, 1.36 +-0.40, 0.00, 50.68, 49.32, 1.36 +-0.40, 0.00, 50.68, 49.32, 1.37 +-0.40, 0.00, 50.69, 49.31, 1.37 +-0.40, 0.00, 50.69, 49.31, 1.37 +-0.26, 0.00, 45.64, 54.36, -8.71 +-0.40, 0.00, 55.63, 44.37, 11.27 +-0.40, 0.00, 50.69, 49.31, 1.38 +-0.40, 0.00, 50.69, 49.31, 1.38 +-0.40, 0.00, 50.69, 49.31, 1.39 +-0.40, 0.00, 50.70, 49.30, 1.39 +-0.40, 0.00, 50.70, 49.30, 1.39 +-0.26, 0.00, 45.65, 54.35, -8.69 +-0.40, 0.00, 55.64, 44.36, 11.29 +-0.26, 0.00, 45.66, 54.34, -8.69 +-0.26, 0.00, 50.60, 49.40, 1.20 +-0.26, 0.00, 50.60, 49.40, 1.21 +-0.26, 0.00, 50.60, 49.40, 1.21 +-0.26, 0.00, 50.61, 49.39, 1.21 +-0.26, 0.00, 50.61, 49.39, 1.21 +-0.26, 0.00, 50.61, 49.39, 1.21 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.23 +-0.26, 0.00, 50.61, 49.39, 1.23 +-0.26, 0.00, 50.61, 49.39, 1.23 +-0.26, 0.00, 50.62, 49.38, 1.23 +-0.26, 0.00, 50.62, 49.38, 1.23 +-0.26, 0.00, 50.62, 49.38, 1.24 +-0.40, 0.00, 55.66, 44.34, 11.32 +-0.26, 0.00, 45.68, 54.32, -8.65 +-0.40, 0.00, 55.66, 44.34, 11.33 +-0.40, 0.00, 50.72, 49.28, 1.44 +-0.40, 0.00, 50.72, 49.28, 1.45 +-0.40, 0.00, 50.73, 49.27, 1.45 +-0.40, 0.00, 50.73, 49.27, 1.45 +-0.40, 0.00, 50.73, 49.27, 1.46 +-0.40, 0.00, 50.73, 49.27, 1.46 +-0.40, 0.00, 50.73, 49.27, 1.46 +-0.40, 0.00, 50.73, 49.27, 1.47 +-0.40, 0.00, 50.73, 49.27, 1.47 +-0.46, 0.00, 53.26, 46.74, 6.51 +-0.46, 0.00, 50.79, 49.21, 1.57 +-0.46, 0.00, 50.79, 49.21, 1.58 +-0.46, 0.00, 50.79, 49.21, 1.58 +-0.46, 0.00, 50.79, 49.21, 1.58 +-0.46, 0.00, 50.79, 49.21, 1.59 +-0.46, 0.00, 50.80, 49.20, 1.59 +-0.46, 0.00, 50.80, 49.20, 1.59 +-0.46, 0.00, 50.80, 49.20, 1.60 +-0.46, 0.00, 50.80, 49.20, 1.60 +-0.53, 0.00, 53.32, 46.68, 6.65 +-0.53, 0.00, 50.85, 49.15, 1.71 +-0.53, 0.00, 50.86, 49.14, 1.71 +-0.53, 0.00, 50.86, 49.14, 1.72 +-0.53, 0.00, 50.86, 49.14, 1.72 +-0.53, 0.00, 50.86, 49.14, 1.72 +-0.53, 0.00, 50.86, 49.14, 1.73 +-0.53, 0.00, 50.87, 49.13, 1.73 +-0.53, 0.00, 50.87, 49.13, 1.74 +-0.53, 0.00, 50.87, 49.13, 1.74 +-0.53, 0.00, 50.87, 49.13, 1.74 +-0.66, 0.00, 55.92, 44.08, 11.83 +-0.66, 0.00, 50.98, 49.02, 1.95 +-0.66, 0.00, 50.98, 49.02, 1.96 +-0.66, 0.00, 50.98, 49.02, 1.96 +-0.66, 0.00, 50.98, 49.02, 1.97 +-0.66, 0.00, 50.99, 49.01, 1.97 +-0.66, 0.00, 50.99, 49.01, 1.98 +-0.66, 0.00, 50.99, 49.01, 1.98 +-0.66, 0.00, 50.99, 49.01, 1.99 +-0.66, 0.00, 51.00, 49.00, 1.99 +-0.66, 0.00, 51.00, 49.00, 2.00 +-0.66, 0.00, 51.00, 49.00, 2.00 +-0.66, 0.00, 51.00, 49.00, 2.01 +-0.66, 0.00, 51.01, 48.99, 2.01 +-0.66, 0.00, 51.01, 48.99, 2.02 +-0.66, 0.00, 51.01, 48.99, 2.02 +-0.66, 0.00, 51.01, 48.99, 2.03 +-0.66, 0.00, 51.02, 48.98, 2.03 +-0.66, 0.00, 51.02, 48.98, 2.04 +-0.66, 0.00, 51.02, 48.98, 2.04 +-0.66, 0.00, 51.02, 48.98, 2.05 +-0.66, 0.00, 51.03, 48.97, 2.05 +-0.66, 0.00, 51.03, 48.97, 2.06 +-0.66, 0.00, 51.03, 48.97, 2.06 +-0.66, 0.00, 51.03, 48.97, 2.07 +-0.66, 0.00, 51.04, 48.96, 2.07 +-0.66, 0.00, 51.04, 48.96, 2.08 +-0.66, 0.00, 51.04, 48.96, 2.08 +-0.66, 0.00, 51.04, 48.96, 2.09 +-0.66, 0.00, 51.05, 48.95, 2.09 +-0.66, 0.00, 51.05, 48.95, 2.10 +-0.66, 0.00, 51.05, 48.95, 2.10 +-0.66, 0.00, 51.05, 48.95, 2.10 +-0.66, 0.00, 51.05, 48.95, 2.11 +-0.66, 0.00, 51.06, 48.94, 2.11 +-0.66, 0.00, 51.06, 48.94, 2.12 +-0.66, 0.00, 51.06, 48.94, 2.12 +-0.66, 0.00, 51.06, 48.94, 2.13 +-0.66, 0.00, 51.07, 48.93, 2.13 +-0.66, 0.00, 51.07, 48.93, 2.14 +-0.66, 0.00, 51.07, 48.93, 2.14 +-0.66, 0.00, 51.07, 48.93, 2.15 +-0.66, 0.00, 51.08, 48.92, 2.15 +-0.66, 0.00, 51.08, 48.92, 2.16 +-0.66, 0.00, 51.08, 48.92, 2.16 +-0.66, 0.00, 51.08, 48.92, 2.17 +-0.66, 0.00, 51.09, 48.91, 2.17 +-0.66, 0.00, 51.09, 48.91, 2.18 +-0.66, 0.00, 51.09, 48.91, 2.18 +-0.66, 0.00, 51.09, 48.91, 2.19 +-0.66, 0.00, 51.10, 48.90, 2.19 +-0.66, 0.00, 51.10, 48.90, 2.20 +-0.53, 0.00, 46.06, 53.94, -7.88 +-0.66, 0.00, 56.05, 43.95, 12.10 +-0.66, 0.00, 51.11, 48.89, 2.21 +-0.66, 0.00, 51.11, 48.89, 2.22 +-0.66, 0.00, 51.11, 48.89, 2.22 +-0.66, 0.00, 51.11, 48.89, 2.23 +-0.66, 0.00, 51.12, 48.88, 2.23 +-0.66, 0.00, 51.12, 48.88, 2.24 +-0.66, 0.00, 51.12, 48.88, 2.24 +-0.66, 0.00, 51.12, 48.88, 2.25 +-0.66, 0.00, 51.13, 48.87, 2.25 +-0.66, 0.00, 51.13, 48.87, 2.26 +-0.53, 0.00, 46.09, 53.91, -7.82 +-0.66, 0.00, 56.08, 43.92, 12.15 +-0.66, 0.00, 51.14, 48.86, 2.27 +-0.66, 0.00, 51.14, 48.86, 2.28 +-0.53, 0.00, 46.10, 53.90, -7.81 +-0.66, 0.00, 56.09, 43.91, 12.17 +-0.66, 0.00, 51.14, 48.86, 2.29 +-0.66, 0.00, 51.15, 48.85, 2.29 +-0.66, 0.00, 51.15, 48.85, 2.30 +-0.66, 0.00, 51.15, 48.85, 2.30 +-0.66, 0.00, 51.15, 48.85, 2.31 +-0.66, 0.00, 51.16, 48.84, 2.31 +-0.66, 0.00, 51.16, 48.84, 2.32 +-0.66, 0.00, 51.16, 48.84, 2.32 +-0.66, 0.00, 51.16, 48.84, 2.33 +-0.66, 0.00, 51.17, 48.83, 2.33 +-0.66, 0.00, 51.17, 48.83, 2.34 +-0.66, 0.00, 51.17, 48.83, 2.34 +-0.66, 0.00, 51.17, 48.83, 2.35 +-0.66, 0.00, 51.18, 48.82, 2.35 +-0.66, 0.00, 51.18, 48.82, 2.36 +-0.66, 0.00, 51.18, 48.82, 2.36 +-0.66, 0.00, 51.18, 48.82, 2.37 +-0.66, 0.00, 51.19, 48.81, 2.37 +-0.66, 0.00, 51.19, 48.81, 2.38 +-0.66, 0.00, 51.19, 48.81, 2.38 +-0.66, 0.00, 51.19, 48.81, 2.39 +-0.66, 0.00, 51.20, 48.80, 2.39 +-0.66, 0.00, 51.20, 48.80, 2.40 +-0.66, 0.00, 51.20, 48.80, 2.40 +-0.66, 0.00, 51.20, 48.80, 2.41 +-0.66, 0.00, 51.21, 48.79, 2.41 +-0.66, 0.00, 51.21, 48.79, 2.42 +-0.73, 0.00, 53.73, 46.27, 7.47 +-0.73, 0.00, 51.26, 48.74, 2.53 +-0.73, 0.00, 51.27, 48.73, 2.53 +-0.66, 0.00, 48.75, 51.25, -2.50 +-0.73, 0.00, 53.74, 46.26, 7.49 +-0.73, 0.00, 51.27, 48.73, 2.55 +-0.73, 0.00, 51.28, 48.72, 2.55 +-0.73, 0.00, 51.28, 48.72, 2.56 +-0.73, 0.00, 51.28, 48.72, 2.57 +-0.73, 0.00, 51.29, 48.71, 2.57 +-0.73, 0.00, 51.29, 48.71, 2.58 +-0.73, 0.00, 51.29, 48.71, 2.58 +-0.73, 0.00, 51.29, 48.71, 2.59 +-0.73, 0.00, 51.30, 48.70, 2.59 +-0.73, 0.00, 51.30, 48.70, 2.60 +-0.73, 0.00, 51.30, 48.70, 2.60 +-0.73, 0.00, 51.30, 48.70, 2.61 +-0.79, 0.00, 53.83, 46.17, 7.66 +-0.73, 0.00, 48.84, 51.16, -2.32 +-0.73, 0.00, 51.31, 48.69, 2.63 +-0.73, 0.00, 51.32, 48.68, 2.63 +-0.73, 0.00, 51.32, 48.68, 2.64 +-0.79, 0.00, 53.84, 46.16, 7.69 +-0.79, 0.00, 51.37, 48.63, 2.75 +-0.79, 0.00, 51.38, 48.62, 2.75 +-0.79, 0.00, 51.38, 48.62, 2.76 +-0.79, 0.00, 51.38, 48.62, 2.77 +-0.79, 0.00, 51.39, 48.61, 2.77 +-0.79, 0.00, 51.39, 48.61, 2.78 +-0.79, 0.00, 51.39, 48.61, 2.78 +-0.79, 0.00, 51.39, 48.61, 2.79 +-0.92, 0.00, 56.44, 43.56, 12.88 +-0.92, 0.00, 51.50, 48.50, 3.00 +-0.92, 0.00, 51.50, 48.50, 3.01 +-0.92, 0.00, 51.51, 48.49, 3.01 +-0.92, 0.00, 51.51, 48.49, 3.02 +-0.92, 0.00, 51.51, 48.49, 3.03 +-0.92, 0.00, 51.52, 48.48, 3.04 +-0.79, 0.00, 46.48, 53.52, -7.04 +-0.79, 0.00, 51.42, 48.58, 2.85 +-0.79, 0.00, 51.43, 48.57, 2.86 +-0.79, 0.00, 51.43, 48.57, 2.86 +-0.79, 0.00, 51.43, 48.57, 2.87 +-0.79, 0.00, 51.44, 48.56, 2.87 +-0.92, 0.00, 56.48, 43.52, 12.97 +-0.92, 0.00, 51.54, 48.46, 3.08 +-0.92, 0.00, 51.55, 48.45, 3.09 +-0.92, 0.00, 51.55, 48.45, 3.10 +-0.92, 0.00, 51.55, 48.45, 3.11 +-0.92, 0.00, 51.56, 48.44, 3.11 +-0.92, 0.00, 51.56, 48.44, 3.12 +-0.92, 0.00, 51.56, 48.44, 3.13 +-0.92, 0.00, 51.57, 48.43, 3.13 +-0.92, 0.00, 51.57, 48.43, 3.14 +-0.92, 0.00, 51.57, 48.43, 3.15 +-0.92, 0.00, 51.58, 48.42, 3.15 +-0.92, 0.00, 51.58, 48.42, 3.16 +-0.92, 0.00, 51.58, 48.42, 3.17 +-0.92, 0.00, 51.59, 48.41, 3.17 +-0.92, 0.00, 51.59, 48.41, 3.18 +-0.92, 0.00, 51.59, 48.41, 3.19 +-0.92, 0.00, 51.60, 48.40, 3.20 +-0.92, 0.00, 51.60, 48.40, 3.20 +-0.92, 0.00, 51.60, 48.40, 3.21 +-0.92, 0.00, 51.61, 48.39, 3.22 +-0.99, 0.00, 54.13, 45.87, 8.27 +-0.99, 0.00, 51.67, 48.33, 3.33 +-0.99, 0.00, 51.67, 48.33, 3.34 +-0.99, 0.00, 51.67, 48.33, 3.34 +-0.99, 0.00, 51.68, 48.32, 3.35 +-0.99, 0.00, 51.68, 48.32, 3.36 +-0.99, 0.00, 51.68, 48.32, 3.37 +-0.99, 0.00, 51.69, 48.31, 3.37 +-0.99, 0.00, 51.69, 48.31, 3.38 +-0.99, 0.00, 51.69, 48.31, 3.39 +-0.92, 0.00, 49.18, 50.82, -1.65 +-0.92, 0.00, 51.65, 48.35, 3.30 +-0.92, 0.00, 51.66, 48.34, 3.31 +-0.92, 0.00, 51.66, 48.34, 3.32 +-0.92, 0.00, 51.66, 48.34, 3.33 +-0.92, 0.00, 51.67, 48.33, 3.33 +-0.92, 0.00, 51.67, 48.33, 3.34 +-0.99, 0.00, 54.19, 45.81, 8.39 +-0.99, 0.00, 51.73, 48.27, 3.45 +-0.99, 0.00, 51.73, 48.27, 3.46 +-0.99, 0.00, 51.73, 48.27, 3.47 +-0.99, 0.00, 51.74, 48.26, 3.47 +-0.99, 0.00, 51.74, 48.26, 3.48 +-0.99, 0.00, 51.74, 48.26, 3.49 +-0.99, 0.00, 51.75, 48.25, 3.50 +-0.99, 0.00, 51.75, 48.25, 3.50 +-0.92, 0.00, 49.23, 50.77, -1.53 +-0.99, 0.00, 54.23, 45.77, 8.46 +-0.92, 0.00, 49.24, 50.76, -1.52 +-0.92, 0.00, 51.72, 48.28, 3.43 +-0.92, 0.00, 51.72, 48.28, 3.44 +-0.92, 0.00, 51.72, 48.28, 3.45 +-0.92, 0.00, 51.73, 48.27, 3.45 +-0.92, 0.00, 51.73, 48.27, 3.46 +-0.92, 0.00, 51.73, 48.27, 3.47 +-0.79, 0.00, 46.69, 53.31, -6.61 +-0.79, 0.00, 51.64, 48.36, 3.28 +-0.79, 0.00, 51.64, 48.36, 3.29 +-0.79, 0.00, 51.65, 48.35, 3.29 +-0.79, 0.00, 51.65, 48.35, 3.30 +-0.79, 0.00, 51.65, 48.35, 3.31 +-0.79, 0.00, 51.66, 48.34, 3.31 +-0.79, 0.00, 51.66, 48.34, 3.32 +-0.73, 0.00, 49.14, 50.86, -1.72 +-0.73, 0.00, 51.62, 48.38, 3.23 +-0.73, 0.00, 51.62, 48.38, 3.24 +-0.66, 0.00, 49.10, 50.90, -1.80 +-0.66, 0.00, 51.57, 48.43, 3.15 +-0.66, 0.00, 51.58, 48.42, 3.15 +-0.66, 0.00, 51.58, 48.42, 3.16 +-0.53, 0.00, 46.54, 53.46, -6.92 +-0.66, 0.00, 56.53, 43.47, 13.05 +-0.53, 0.00, 46.54, 53.46, -6.92 +-0.53, 0.00, 51.49, 48.51, 2.98 +-0.53, 0.00, 51.49, 48.51, 2.98 +-0.53, 0.00, 51.49, 48.51, 2.98 +-0.53, 0.00, 51.49, 48.51, 2.99 +-0.53, 0.00, 51.50, 48.50, 2.99 +-0.46, 0.00, 48.98, 51.02, -2.05 +-0.46, 0.00, 51.45, 48.55, 2.90 +-0.46, 0.00, 51.45, 48.55, 2.90 +-0.40, 0.00, 48.93, 51.07, -2.14 +-0.40, 0.00, 51.40, 48.60, 2.81 +-0.40, 0.00, 51.41, 48.59, 2.81 +-0.26, 0.00, 46.36, 53.64, -7.27 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.20, 0.00, 48.79, 51.21, -2.42 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.20, 0.00, 51.27, 48.73, 2.53 +-0.20, 0.00, 51.27, 48.73, 2.53 +-0.20, 0.00, 51.27, 48.73, 2.53 +-0.20, 0.00, 51.27, 48.73, 2.53 +-0.13, 0.00, 48.75, 51.25, -2.51 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +0.00, 0.00, 46.18, 53.82, -7.65 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.07, 0.00, 48.60, 51.40, -2.80 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.13, 0.00, 48.55, 51.45, -2.91 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.03 +0.26, 0.00, 45.97, 54.03, -8.05 +0.26, 0.00, 50.92, 49.08, 1.83 +0.26, 0.00, 50.92, 49.08, 1.83 +0.26, 0.00, 50.91, 49.09, 1.83 +0.26, 0.00, 50.91, 49.09, 1.83 +0.33, 0.00, 48.39, 51.61, -3.22 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.71 +0.33, 0.00, 50.86, 49.14, 1.71 +0.33, 0.00, 50.85, 49.15, 1.71 +0.33, 0.00, 50.85, 49.15, 1.71 +0.33, 0.00, 50.85, 49.15, 1.70 +0.33, 0.00, 50.85, 49.15, 1.70 +0.40, 0.00, 48.33, 51.67, -3.34 +0.40, 0.00, 50.80, 49.20, 1.60 +0.40, 0.00, 50.80, 49.20, 1.59 +0.40, 0.00, 50.80, 49.20, 1.59 +0.53, 0.00, 45.75, 54.25, -8.50 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.37 +0.53, 0.00, 50.68, 49.32, 1.37 +0.53, 0.00, 50.68, 49.32, 1.36 +0.53, 0.00, 50.68, 49.32, 1.36 +0.53, 0.00, 50.68, 49.32, 1.36 +0.53, 0.00, 50.68, 49.32, 1.35 +0.40, 0.00, 55.72, 44.28, 11.44 +0.40, 0.00, 50.77, 49.23, 1.54 +0.53, 0.00, 45.73, 54.27, -8.54 +0.40, 0.00, 55.71, 44.29, 11.43 +0.53, 0.00, 45.72, 54.28, -8.55 +0.53, 0.00, 50.67, 49.33, 1.33 +0.53, 0.00, 50.66, 49.34, 1.33 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.31 +0.53, 0.00, 50.65, 49.35, 1.31 +0.53, 0.00, 50.65, 49.35, 1.30 +0.53, 0.00, 50.65, 49.35, 1.30 +0.53, 0.00, 50.65, 49.35, 1.30 +0.53, 0.00, 50.65, 49.35, 1.29 +0.53, 0.00, 50.64, 49.36, 1.29 +0.40, 0.00, 55.69, 44.31, 11.37 +0.40, 0.00, 50.74, 49.26, 1.48 +0.40, 0.00, 50.74, 49.26, 1.48 +0.40, 0.00, 50.74, 49.26, 1.47 +0.40, 0.00, 50.74, 49.26, 1.47 +0.40, 0.00, 50.73, 49.27, 1.47 +0.40, 0.00, 50.73, 49.27, 1.47 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.45 +0.40, 0.00, 50.73, 49.27, 1.45 +0.40, 0.00, 50.72, 49.28, 1.45 +0.40, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 50.72, 49.28, 1.43 +0.40, 0.00, 50.72, 49.28, 1.43 +0.40, 0.00, 50.71, 49.29, 1.43 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.41 +0.40, 0.00, 50.70, 49.30, 1.41 +0.40, 0.00, 50.70, 49.30, 1.41 +0.40, 0.00, 50.70, 49.30, 1.40 +0.40, 0.00, 50.70, 49.30, 1.40 +0.40, 0.00, 50.70, 49.30, 1.40 +0.40, 0.00, 50.70, 49.30, 1.39 +0.40, 0.00, 50.70, 49.30, 1.39 +0.40, 0.00, 50.69, 49.31, 1.39 +0.40, 0.00, 50.69, 49.31, 1.39 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.37 +0.40, 0.00, 50.69, 49.31, 1.37 +0.40, 0.00, 50.68, 49.32, 1.37 +0.40, 0.00, 50.68, 49.32, 1.36 +0.40, 0.00, 50.68, 49.32, 1.36 +0.53, 0.00, 45.64, 54.36, -8.73 +0.53, 0.00, 50.58, 49.42, 1.16 +0.53, 0.00, 50.58, 49.42, 1.15 +0.53, 0.00, 50.57, 49.43, 1.15 +0.53, 0.00, 50.57, 49.43, 1.14 +0.53, 0.00, 50.57, 49.43, 1.14 +0.53, 0.00, 50.57, 49.43, 1.14 +0.53, 0.00, 50.57, 49.43, 1.13 +0.59, 0.00, 48.04, 51.96, -3.91 +0.53, 0.00, 53.03, 46.97, 6.07 +0.53, 0.00, 50.56, 49.44, 1.12 +0.53, 0.00, 50.56, 49.44, 1.12 +0.53, 0.00, 50.56, 49.44, 1.11 +0.53, 0.00, 50.55, 49.45, 1.11 +0.53, 0.00, 50.55, 49.45, 1.10 +0.59, 0.00, 48.03, 51.97, -3.94 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 0.99 +0.59, 0.00, 50.49, 49.51, 0.99 +0.59, 0.00, 50.49, 49.51, 0.98 +0.59, 0.00, 50.49, 49.51, 0.98 +0.59, 0.00, 50.49, 49.51, 0.97 +0.59, 0.00, 50.48, 49.52, 0.97 +0.59, 0.00, 50.48, 49.52, 0.97 +0.59, 0.00, 50.48, 49.52, 0.96 +0.59, 0.00, 50.48, 49.52, 0.96 +0.66, 0.00, 47.95, 52.05, -4.09 +0.66, 0.00, 50.42, 49.58, 0.85 +0.66, 0.00, 50.42, 49.58, 0.84 +0.66, 0.00, 50.42, 49.58, 0.84 +0.66, 0.00, 50.42, 49.58, 0.83 +0.66, 0.00, 50.41, 49.59, 0.83 +0.66, 0.00, 50.41, 49.59, 0.82 +0.66, 0.00, 50.41, 49.59, 0.82 +0.66, 0.00, 50.41, 49.59, 0.81 +0.66, 0.00, 50.40, 49.60, 0.81 +0.66, 0.00, 50.40, 49.60, 0.80 +0.66, 0.00, 50.40, 49.60, 0.80 +0.66, 0.00, 50.40, 49.60, 0.79 +0.66, 0.00, 50.39, 49.61, 0.79 +0.66, 0.00, 50.39, 49.61, 0.78 +0.66, 0.00, 50.39, 49.61, 0.78 +0.66, 0.00, 50.39, 49.61, 0.77 +0.79, 0.00, 45.34, 54.66, -9.32 +0.79, 0.00, 50.28, 49.72, 0.56 +0.79, 0.00, 50.28, 49.72, 0.56 +0.79, 0.00, 50.28, 49.72, 0.55 +0.79, 0.00, 50.27, 49.73, 0.55 +0.79, 0.00, 50.27, 49.73, 0.54 +0.66, 0.00, 55.31, 44.69, 10.62 +0.79, 0.00, 45.32, 54.68, -9.36 +0.66, 0.00, 55.30, 44.70, 10.61 +0.66, 0.00, 50.36, 49.64, 0.72 +0.66, 0.00, 50.36, 49.64, 0.71 +0.66, 0.00, 50.35, 49.65, 0.71 +0.66, 0.00, 50.35, 49.65, 0.70 +0.66, 0.00, 50.35, 49.65, 0.70 +0.66, 0.00, 50.35, 49.65, 0.69 +0.66, 0.00, 50.34, 49.66, 0.69 +0.66, 0.00, 50.34, 49.66, 0.68 +0.66, 0.00, 50.34, 49.66, 0.68 +0.66, 0.00, 50.34, 49.66, 0.67 +0.66, 0.00, 50.33, 49.67, 0.67 +0.66, 0.00, 50.33, 49.67, 0.66 +0.66, 0.00, 50.33, 49.67, 0.66 +0.59, 0.00, 52.85, 47.15, 5.70 +0.59, 0.00, 50.37, 49.63, 0.75 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.73 +0.59, 0.00, 50.37, 49.63, 0.73 +0.59, 0.00, 50.36, 49.64, 0.73 +0.53, 0.00, 52.88, 47.12, 5.76 +0.53, 0.00, 50.41, 49.59, 0.82 +0.59, 0.00, 47.88, 52.12, -4.23 +0.53, 0.00, 52.88, 47.12, 5.75 +0.53, 0.00, 50.40, 49.60, 0.80 +0.53, 0.00, 50.40, 49.60, 0.80 +0.53, 0.00, 50.40, 49.60, 0.80 +0.53, 0.00, 50.40, 49.60, 0.79 +0.53, 0.00, 50.39, 49.61, 0.79 +0.53, 0.00, 50.39, 49.61, 0.78 +0.53, 0.00, 50.39, 49.61, 0.78 +0.40, 0.00, 55.43, 44.57, 10.86 +0.40, 0.00, 50.49, 49.51, 0.97 +0.40, 0.00, 50.48, 49.52, 0.97 +0.40, 0.00, 50.48, 49.52, 0.97 +0.40, 0.00, 50.48, 49.52, 0.96 +0.40, 0.00, 50.48, 49.52, 0.96 +0.40, 0.00, 50.48, 49.52, 0.96 +0.40, 0.00, 50.48, 49.52, 0.95 +0.40, 0.00, 50.48, 49.52, 0.95 +0.33, 0.00, 53.00, 47.00, 5.99 +0.33, 0.00, 50.52, 49.48, 1.05 +0.33, 0.00, 50.52, 49.48, 1.04 +0.33, 0.00, 50.52, 49.48, 1.04 +0.33, 0.00, 50.52, 49.48, 1.04 +0.33, 0.00, 50.52, 49.48, 1.04 +0.33, 0.00, 50.52, 49.48, 1.03 +0.33, 0.00, 50.52, 49.48, 1.03 +0.33, 0.00, 50.51, 49.49, 1.03 +0.26, 0.00, 53.03, 46.97, 6.07 +0.26, 0.00, 50.56, 49.44, 1.12 +0.26, 0.00, 50.56, 49.44, 1.12 +0.26, 0.00, 50.56, 49.44, 1.12 +0.13, 0.00, 55.60, 44.40, 11.20 +0.13, 0.00, 50.66, 49.34, 1.31 +0.13, 0.00, 50.66, 49.34, 1.31 +0.13, 0.00, 50.66, 49.34, 1.31 +0.13, 0.00, 50.66, 49.34, 1.31 +0.07, 0.00, 53.18, 46.82, 6.35 +0.13, 0.00, 48.18, 51.82, -3.63 +0.07, 0.00, 53.18, 46.82, 6.35 +0.07, 0.00, 50.70, 49.30, 1.41 +0.07, 0.00, 50.70, 49.30, 1.41 +0.07, 0.00, 50.70, 49.30, 1.41 +0.07, 0.00, 50.70, 49.30, 1.41 +0.00, 0.00, 53.22, 46.78, 6.45 +0.00, 0.00, 50.75, 49.25, 1.51 +0.00, 0.00, 50.75, 49.25, 1.51 +0.00, 0.00, 50.75, 49.25, 1.51 +0.00, 0.00, 50.75, 49.25, 1.51 +0.00, 0.00, 50.75, 49.25, 1.51 +-0.13, 0.00, 55.80, 44.20, 11.59 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.86, 49.14, 1.71 +-0.20, 0.00, 53.38, 46.62, 6.75 +-0.20, 0.00, 50.91, 49.09, 1.81 +-0.20, 0.00, 50.91, 49.09, 1.81 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.26, 0.00, 53.43, 46.57, 6.87 +-0.26, 0.00, 50.96, 49.04, 1.93 +-0.26, 0.00, 50.96, 49.04, 1.93 +-0.26, 0.00, 50.96, 49.04, 1.93 +-0.40, 0.00, 56.01, 43.99, 12.02 +-0.40, 0.00, 51.07, 48.93, 2.13 +-0.40, 0.00, 51.07, 48.93, 2.14 +-0.40, 0.00, 51.07, 48.93, 2.14 +-0.40, 0.00, 51.07, 48.93, 2.14 +-0.40, 0.00, 51.07, 48.93, 2.14 +-0.40, 0.00, 51.07, 48.93, 2.15 +-0.40, 0.00, 51.08, 48.92, 2.15 +-0.40, 0.00, 51.08, 48.92, 2.15 +-0.40, 0.00, 51.08, 48.92, 2.16 +-0.40, 0.00, 51.08, 48.92, 2.16 +-0.40, 0.00, 51.08, 48.92, 2.16 +-0.40, 0.00, 51.08, 48.92, 2.17 +-0.40, 0.00, 51.08, 48.92, 2.17 +-0.46, 0.00, 53.61, 46.39, 7.21 +-0.46, 0.00, 51.14, 48.86, 2.27 +-0.46, 0.00, 51.14, 48.86, 2.28 +-0.46, 0.00, 51.14, 48.86, 2.28 +-0.46, 0.00, 51.14, 48.86, 2.28 +-0.46, 0.00, 51.14, 48.86, 2.29 +-0.46, 0.00, 51.15, 48.85, 2.29 +-0.46, 0.00, 51.15, 48.85, 2.30 +-0.46, 0.00, 51.15, 48.85, 2.30 +-0.46, 0.00, 51.15, 48.85, 2.30 +-0.46, 0.00, 51.15, 48.85, 2.31 +-0.46, 0.00, 51.15, 48.85, 2.31 +-0.46, 0.00, 51.16, 48.84, 2.31 +-0.46, 0.00, 51.16, 48.84, 2.32 +-0.46, 0.00, 51.16, 48.84, 2.32 +-0.46, 0.00, 51.16, 48.84, 2.32 +-0.46, 0.00, 51.16, 48.84, 2.33 +-0.40, 0.00, 48.64, 51.36, -2.71 +-0.40, 0.00, 51.12, 48.88, 2.23 +-0.46, 0.00, 53.64, 46.36, 7.28 +-0.46, 0.00, 51.17, 48.83, 2.34 +-0.46, 0.00, 51.17, 48.83, 2.34 +-0.46, 0.00, 51.17, 48.83, 2.35 +-0.46, 0.00, 51.17, 48.83, 2.35 +-0.46, 0.00, 51.18, 48.82, 2.35 +-0.40, 0.00, 48.66, 51.34, -2.69 +-0.40, 0.00, 51.13, 48.87, 2.26 +-0.40, 0.00, 51.13, 48.87, 2.26 +-0.40, 0.00, 51.13, 48.87, 2.27 +-0.40, 0.00, 51.13, 48.87, 2.27 +-0.40, 0.00, 51.14, 48.86, 2.27 +-0.40, 0.00, 51.14, 48.86, 2.28 +-0.40, 0.00, 51.14, 48.86, 2.28 +-0.26, 0.00, 46.10, 53.90, -7.81 +-0.26, 0.00, 51.04, 48.96, 2.08 +-0.26, 0.00, 51.04, 48.96, 2.09 +-0.26, 0.00, 51.04, 48.96, 2.09 +-0.26, 0.00, 51.05, 48.95, 2.09 +-0.26, 0.00, 51.05, 48.95, 2.09 +-0.20, 0.00, 48.53, 51.47, -2.95 +-0.26, 0.00, 53.52, 46.48, 7.04 +-0.20, 0.00, 48.53, 51.47, -2.95 +-0.20, 0.00, 51.00, 49.00, 2.00 +-0.20, 0.00, 51.00, 49.00, 2.00 +-0.20, 0.00, 51.00, 49.00, 2.00 +-0.20, 0.00, 51.00, 49.00, 2.00 +-0.20, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 48.48, 51.52, -3.04 +-0.13, 0.00, 50.95, 49.05, 1.91 +-0.13, 0.00, 50.95, 49.05, 1.91 +-0.13, 0.00, 50.96, 49.04, 1.91 +-0.13, 0.00, 50.96, 49.04, 1.91 +0.00, 0.00, 45.91, 54.09, -8.17 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 48.34, 51.66, -3.33 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.13, 0.00, 48.28, 51.72, -3.44 +0.13, 0.00, 50.75, 49.25, 1.51 +0.13, 0.00, 50.75, 49.25, 1.51 +0.13, 0.00, 50.75, 49.25, 1.50 +0.13, 0.00, 50.75, 49.25, 1.50 +0.13, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 45.71, 54.29, -8.58 +0.26, 0.00, 50.65, 49.35, 1.30 +0.26, 0.00, 50.65, 49.35, 1.30 +0.26, 0.00, 50.65, 49.35, 1.30 +0.33, 0.00, 48.13, 51.87, -3.75 +0.33, 0.00, 50.60, 49.40, 1.19 +0.33, 0.00, 50.60, 49.40, 1.19 +0.33, 0.00, 50.59, 49.41, 1.19 +0.33, 0.00, 50.59, 49.41, 1.19 +0.33, 0.00, 50.59, 49.41, 1.18 +0.33, 0.00, 50.59, 49.41, 1.18 +0.33, 0.00, 50.59, 49.41, 1.18 +0.33, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 48.07, 51.93, -3.87 +0.40, 0.00, 50.54, 49.46, 1.07 +0.40, 0.00, 50.53, 49.47, 1.07 +0.40, 0.00, 50.53, 49.47, 1.07 +0.40, 0.00, 50.53, 49.47, 1.06 +0.53, 0.00, 45.49, 54.51, -9.03 +0.53, 0.00, 50.43, 49.57, 0.86 +0.53, 0.00, 50.43, 49.57, 0.85 +0.59, 0.00, 47.90, 52.10, -4.19 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.73 +0.59, 0.00, 50.36, 49.64, 0.73 +0.59, 0.00, 50.36, 49.64, 0.72 +0.59, 0.00, 50.36, 49.64, 0.72 +0.59, 0.00, 50.36, 49.64, 0.71 +0.59, 0.00, 50.35, 49.65, 0.71 +0.59, 0.00, 50.35, 49.65, 0.70 +0.59, 0.00, 50.35, 49.65, 0.70 +0.59, 0.00, 50.35, 49.65, 0.70 +0.59, 0.00, 50.35, 49.65, 0.69 +0.66, 0.00, 47.82, 52.18, -4.36 +0.59, 0.00, 52.81, 47.19, 5.63 +0.66, 0.00, 47.82, 52.18, -4.37 +0.66, 0.00, 50.29, 49.71, 0.57 +0.66, 0.00, 50.28, 49.72, 0.57 +0.66, 0.00, 50.28, 49.72, 0.56 +0.66, 0.00, 50.28, 49.72, 0.56 +0.66, 0.00, 50.28, 49.72, 0.55 +0.66, 0.00, 50.27, 49.73, 0.55 +0.66, 0.00, 50.27, 49.73, 0.54 +0.66, 0.00, 50.27, 49.73, 0.54 +0.66, 0.00, 50.27, 49.73, 0.53 +0.66, 0.00, 50.26, 49.74, 0.53 +0.66, 0.00, 50.26, 49.74, 0.52 +0.66, 0.00, 50.26, 49.74, 0.52 +0.59, 0.00, 52.78, 47.22, 5.56 +0.59, 0.00, 50.30, 49.70, 0.61 +0.59, 0.00, 50.30, 49.70, 0.60 +0.59, 0.00, 50.30, 49.70, 0.60 +0.59, 0.00, 50.30, 49.70, 0.60 +0.59, 0.00, 50.30, 49.70, 0.59 +0.59, 0.00, 50.29, 49.71, 0.59 +0.59, 0.00, 50.29, 49.71, 0.58 +0.59, 0.00, 50.29, 49.71, 0.58 +0.59, 0.00, 50.29, 49.71, 0.57 +0.59, 0.00, 50.28, 49.72, 0.57 +0.59, 0.00, 50.28, 49.72, 0.56 +0.59, 0.00, 50.28, 49.72, 0.56 +0.59, 0.00, 50.28, 49.72, 0.56 +0.59, 0.00, 50.28, 49.72, 0.55 +0.59, 0.00, 50.27, 49.73, 0.55 +0.53, 0.00, 52.79, 47.21, 5.59 +0.53, 0.00, 50.32, 49.68, 0.64 +0.53, 0.00, 50.32, 49.68, 0.63 +0.53, 0.00, 50.31, 49.69, 0.63 +0.53, 0.00, 50.31, 49.69, 0.63 +0.53, 0.00, 50.31, 49.69, 0.62 +0.53, 0.00, 50.31, 49.69, 0.62 +0.53, 0.00, 50.31, 49.69, 0.61 +0.40, 0.00, 55.35, 44.65, 10.70 +0.40, 0.00, 50.40, 49.60, 0.81 +0.40, 0.00, 50.40, 49.60, 0.80 +0.40, 0.00, 50.40, 49.60, 0.80 +0.40, 0.00, 50.40, 49.60, 0.80 +0.40, 0.00, 50.40, 49.60, 0.79 +0.40, 0.00, 50.40, 49.60, 0.79 +0.40, 0.00, 50.39, 49.61, 0.79 +0.40, 0.00, 50.39, 49.61, 0.78 +0.33, 0.00, 52.91, 47.09, 5.83 +0.33, 0.00, 50.44, 49.56, 0.88 +0.33, 0.00, 50.44, 49.56, 0.88 +0.33, 0.00, 50.44, 49.56, 0.87 +0.33, 0.00, 50.44, 49.56, 0.87 +0.33, 0.00, 50.43, 49.57, 0.87 +0.33, 0.00, 50.43, 49.57, 0.87 +0.33, 0.00, 50.43, 49.57, 0.86 +0.26, 0.00, 52.95, 47.05, 5.90 +0.26, 0.00, 50.48, 49.52, 0.96 +0.26, 0.00, 50.48, 49.52, 0.96 +0.26, 0.00, 50.48, 49.52, 0.96 +0.26, 0.00, 50.48, 49.52, 0.95 +0.26, 0.00, 50.48, 49.52, 0.95 +0.26, 0.00, 50.47, 49.53, 0.95 +0.26, 0.00, 50.47, 49.53, 0.95 +0.13, 0.00, 55.52, 44.48, 11.03 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.07, 0.00, 53.09, 46.91, 6.18 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.00, 0.00, 53.14, 46.86, 6.28 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +-0.13, 0.00, 55.71, 44.29, 11.42 +-0.13, 0.00, 50.77, 49.23, 1.53 +0.00, 0.00, 45.72, 54.28, -8.55 +-0.13, 0.00, 55.71, 44.29, 11.42 +0.00, 0.00, 45.72, 54.28, -8.55 +0.00, 0.00, 50.67, 49.33, 1.33 +-0.13, 0.00, 55.71, 44.29, 11.42 +0.00, 0.00, 45.72, 54.28, -8.55 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.07, 0.00, 48.15, 51.85, -3.71 +0.07, 0.00, 50.62, 49.38, 1.24 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.61, 49.39, 1.23 +0.07, 0.00, 50.61, 49.39, 1.23 +0.07, 0.00, 50.61, 49.39, 1.23 +0.00, 0.00, 53.14, 46.86, 6.27 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +-0.13, 0.00, 55.71, 44.29, 11.41 +-0.13, 0.00, 50.76, 49.24, 1.53 +-0.13, 0.00, 50.76, 49.24, 1.53 +-0.13, 0.00, 50.76, 49.24, 1.53 +-0.13, 0.00, 50.77, 49.23, 1.53 +-0.20, 0.00, 53.29, 46.71, 6.57 +-0.20, 0.00, 50.82, 49.18, 1.63 +-0.20, 0.00, 50.82, 49.18, 1.63 +-0.20, 0.00, 50.82, 49.18, 1.64 +-0.20, 0.00, 50.82, 49.18, 1.64 +-0.20, 0.00, 50.82, 49.18, 1.64 +-0.20, 0.00, 50.82, 49.18, 1.64 +-0.26, 0.00, 53.34, 46.66, 6.68 +-0.26, 0.00, 50.87, 49.13, 1.74 +-0.26, 0.00, 50.87, 49.13, 1.74 +-0.26, 0.00, 50.87, 49.13, 1.75 +-0.26, 0.00, 50.87, 49.13, 1.75 +-0.40, 0.00, 55.92, 44.08, 11.84 +-0.40, 0.00, 50.98, 49.02, 1.95 +-0.40, 0.00, 50.98, 49.02, 1.96 +-0.40, 0.00, 50.98, 49.02, 1.96 +-0.40, 0.00, 50.98, 49.02, 1.96 +-0.40, 0.00, 50.98, 49.02, 1.96 +-0.46, 0.00, 53.51, 46.49, 7.01 +-0.46, 0.00, 51.03, 48.97, 2.07 +-0.46, 0.00, 51.04, 48.96, 2.07 +-0.46, 0.00, 51.04, 48.96, 2.08 +-0.46, 0.00, 51.04, 48.96, 2.08 +-0.46, 0.00, 51.04, 48.96, 2.08 +-0.53, 0.00, 53.57, 46.43, 7.13 +-0.53, 0.00, 51.10, 48.90, 2.19 +-0.53, 0.00, 51.10, 48.90, 2.19 +-0.53, 0.00, 51.10, 48.90, 2.20 +-0.66, 0.00, 56.14, 43.86, 12.29 +-0.66, 0.00, 51.20, 48.80, 2.41 +-0.66, 0.00, 51.21, 48.79, 2.41 +-0.66, 0.00, 51.21, 48.79, 2.42 +-0.66, 0.00, 51.21, 48.79, 2.42 +-0.66, 0.00, 51.21, 48.79, 2.43 +-0.73, 0.00, 53.74, 46.26, 7.47 +-0.73, 0.00, 51.27, 48.73, 2.54 +-0.73, 0.00, 51.27, 48.73, 2.54 +-0.73, 0.00, 51.27, 48.73, 2.55 +-0.73, 0.00, 51.28, 48.72, 2.55 +-0.73, 0.00, 51.28, 48.72, 2.56 +-0.79, 0.00, 53.80, 46.20, 7.61 +-0.79, 0.00, 51.33, 48.67, 2.67 +-0.79, 0.00, 51.34, 48.66, 2.67 +-0.79, 0.00, 51.34, 48.66, 2.68 +-0.79, 0.00, 51.34, 48.66, 2.69 +-0.79, 0.00, 51.35, 48.65, 2.69 +-0.79, 0.00, 51.35, 48.65, 2.70 +-0.79, 0.00, 51.35, 48.65, 2.70 +-0.79, 0.00, 51.35, 48.65, 2.71 +-0.92, 0.00, 56.40, 43.60, 12.80 +-0.92, 0.00, 51.46, 48.54, 2.92 +-0.92, 0.00, 51.46, 48.54, 2.93 +-0.92, 0.00, 51.47, 48.53, 2.94 +-0.92, 0.00, 51.47, 48.53, 2.94 +-0.92, 0.00, 51.47, 48.53, 2.95 +-0.92, 0.00, 51.48, 48.52, 2.96 +-0.99, 0.00, 54.00, 46.00, 8.01 +-0.99, 0.00, 51.53, 48.47, 3.07 +-0.92, 0.00, 49.02, 50.98, -1.97 +-0.92, 0.00, 51.49, 48.51, 2.98 +-0.99, 0.00, 54.02, 45.98, 8.03 +-0.92, 0.00, 49.03, 50.97, -1.95 +-0.92, 0.00, 51.50, 48.50, 3.01 +-0.99, 0.00, 54.03, 45.97, 8.06 +-0.99, 0.00, 51.56, 48.44, 3.12 +-0.99, 0.00, 51.56, 48.44, 3.13 +-0.99, 0.00, 51.57, 48.43, 3.13 +-0.99, 0.00, 51.57, 48.43, 3.14 +-1.05, 0.00, 54.10, 45.90, 8.19 +-1.05, 0.00, 51.63, 48.37, 3.26 +-1.05, 0.00, 51.63, 48.37, 3.26 +-1.05, 0.00, 51.64, 48.36, 3.27 +-1.05, 0.00, 51.64, 48.36, 3.28 +-1.05, 0.00, 51.64, 48.36, 3.29 +-1.05, 0.00, 51.65, 48.35, 3.30 +-1.05, 0.00, 51.65, 48.35, 3.30 +-1.05, 0.00, 51.66, 48.34, 3.31 +-1.05, 0.00, 51.66, 48.34, 3.32 +-1.05, 0.00, 51.66, 48.34, 3.33 +-1.05, 0.00, 51.67, 48.33, 3.34 +-1.05, 0.00, 51.67, 48.33, 3.34 +-1.05, 0.00, 51.68, 48.32, 3.35 +-1.05, 0.00, 51.68, 48.32, 3.36 +-1.05, 0.00, 51.68, 48.32, 3.37 +-1.05, 0.00, 51.69, 48.31, 3.38 +-1.19, 0.00, 56.73, 43.27, 13.47 +-1.19, 0.00, 51.80, 48.20, 3.59 +-1.19, 0.00, 51.80, 48.20, 3.60 +-1.19, 0.00, 51.80, 48.20, 3.61 +-1.19, 0.00, 51.81, 48.19, 3.62 +-1.19, 0.00, 51.81, 48.19, 3.63 +-1.19, 0.00, 51.82, 48.18, 3.64 +-1.19, 0.00, 51.82, 48.18, 3.64 +-1.19, 0.00, 51.83, 48.17, 3.65 +-1.19, 0.00, 51.83, 48.17, 3.66 +-1.19, 0.00, 51.84, 48.16, 3.67 +-1.19, 0.00, 51.84, 48.16, 3.68 +-1.19, 0.00, 51.84, 48.16, 3.69 +-1.19, 0.00, 51.85, 48.15, 3.70 +-1.19, 0.00, 51.85, 48.15, 3.71 +-1.19, 0.00, 51.86, 48.14, 3.72 +-1.19, 0.00, 51.86, 48.14, 3.72 +-1.19, 0.00, 51.87, 48.13, 3.73 +-1.19, 0.00, 51.87, 48.13, 3.74 +-1.25, 0.00, 54.40, 45.60, 8.79 +-1.25, 0.00, 51.93, 48.07, 3.86 +-1.19, 0.00, 49.41, 50.59, -1.17 +-1.25, 0.00, 54.41, 45.59, 8.82 +-1.19, 0.00, 49.42, 50.58, -1.16 +-1.25, 0.00, 54.42, 45.58, 8.84 +-1.19, 0.00, 49.43, 50.57, -1.14 +-1.19, 0.00, 51.91, 48.09, 3.82 +-1.19, 0.00, 51.91, 48.09, 3.82 +-1.19, 0.00, 51.92, 48.08, 3.83 +-1.19, 0.00, 51.92, 48.08, 3.84 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.05, 35.00, 73.53, 26.47, 47.07 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.05, 35.00, 73.94, 26.06, 47.88 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.05, 35.00, 74.21, 25.79, 48.42 +-1.05, 35.00, 75.00, 25.00, 50.00 +-1.05, 35.00, 75.00, 25.00, 50.00 +-0.99, 35.00, 75.00, 25.00, 50.00 +-0.92, 35.00, 75.00, 25.00, 50.00 +-0.92, 35.00, 75.00, 25.00, 50.00 +-0.73, 35.00, 72.30, 27.70, 44.60 +-0.66, 35.00, 75.00, 25.00, 50.00 +-0.53, 35.00, 74.89, 25.11, 49.78 +-0.46, 35.00, 75.00, 25.00, 50.00 +-0.26, 35.00, 72.49, 27.51, 44.98 +-0.13, 35.00, 74.99, 25.01, 49.99 +0.00, 35.00, 75.00, 25.00, 50.00 +0.13, 35.00, 75.00, 25.00, 50.00 +0.33, 35.00, 72.57, 27.43, 45.13 +0.53, 35.00, 72.55, 27.45, 45.10 +0.66, 35.00, 75.00, 25.00, 50.00 +0.86, 35.00, 72.56, 27.44, 45.11 +1.12, 35.00, 70.01, 29.99, 40.03 +1.32, 35.00, 72.46, 27.54, 44.93 +1.58, 35.00, 69.92, 30.08, 39.84 +1.85, 35.00, 69.85, 30.15, 39.69 +2.18, 35.00, 67.25, 32.75, 34.50 +2.44, 35.00, 69.65, 30.35, 39.29 +2.70, 35.00, 69.57, 30.43, 39.14 +3.03, 35.00, 66.97, 33.03, 33.94 +3.43, 35.00, 64.32, 35.68, 28.64 +3.76, 35.00, 66.66, 33.34, 33.33 +4.09, 35.00, 66.53, 33.47, 33.06 +4.55, 35.00, 61.36, 38.64, 22.71 +4.88, 35.00, 66.17, 33.83, 32.33 +5.34, 35.00, 60.99, 39.01, 21.97 +5.67, 35.00, 65.79, 34.21, 31.59 +6.13, 35.00, 60.61, 39.39, 21.22 +6.59, 35.00, 60.37, 39.63, 20.74 +6.99, 35.00, 62.65, 37.35, 25.31 +7.45, 35.00, 59.94, 40.06, 19.88 +7.98, 35.00, 57.17, 42.83, 14.34 +8.50, 35.00, 56.88, 43.12, 13.75 +9.03, 35.00, 56.58, 43.42, 13.16 +9.49, 35.00, 58.80, 41.20, 17.60 +10.09, 35.00, 53.50, 46.50, 7.01 +10.61, 35.00, 55.67, 44.33, 11.34 +11.14, 35.00, 55.37, 44.63, 10.73 +11.73, 35.00, 52.54, 47.46, 5.07 +12.26, 35.00, 54.70, 45.30, 9.40 +12.79, 35.00, 54.39, 45.61, 8.77 +13.32, 35.00, 54.07, 45.93, 8.14 +13.84, 35.00, 53.76, 46.24, 7.51 +14.37, 35.00, 53.44, 46.56, 6.87 +14.90, 35.00, 53.12, 46.88, 6.23 +15.42, 35.00, 52.79, 47.21, 5.59 +15.95, 35.00, 52.47, 47.53, 4.94 +16.61, 35.00, 47.10, 52.90, -5.80 +17.14, 35.00, 51.72, 48.28, 3.43 +17.73, 35.00, 48.86, 51.14, -2.27 +18.33, 35.00, 48.48, 51.52, -3.04 +18.98, 35.00, 45.58, 54.42, -8.85 +19.58, 35.00, 47.66, 52.34, -4.68 +20.17, 35.00, 47.27, 52.73, -5.46 +20.83, 35.00, 44.36, 55.64, -11.28 +21.36, 35.00, 48.96, 51.04, -2.08 +21.95, 35.00, 46.09, 53.91, -7.82 +22.48, 35.00, 48.21, 51.79, -3.57 +23.01, 35.00, 47.86, 52.14, -4.27 +23.53, 35.00, 47.51, 52.49, -4.98 +24.13, 35.00, 44.63, 55.37, -10.73 +24.65, 35.00, 46.75, 53.25, -6.50 +25.18, 35.00, 46.39, 53.61, -7.22 +25.71, 35.00, 46.03, 53.97, -7.94 +26.24, 35.00, 45.67, 54.33, -8.67 +26.76, 35.00, 45.30, 54.70, -9.39 +27.29, 35.00, 44.94, 55.06, -10.13 +27.82, 35.00, 44.57, 55.43, -10.86 +28.34, 35.00, 44.20, 55.80, -11.61 +28.81, 35.00, 46.35, 53.65, -7.31 +29.33, 35.00, 43.50, 56.50, -13.00 +29.86, 35.00, 43.12, 56.88, -13.75 +30.32, 35.00, 45.27, 54.73, -9.47 +30.72, 35.00, 47.46, 52.54, -5.08 +31.25, 35.00, 42.13, 57.87, -15.73 +31.71, 35.00, 44.27, 55.73, -11.46 +32.17, 35.00, 43.94, 56.06, -12.13 +32.56, 35.00, 46.12, 53.88, -7.76 +33.02, 35.00, 43.31, 56.69, -13.38 +33.49, 35.00, 42.97, 57.03, -14.06 +33.82, 35.00, 47.67, 52.33, -4.66 +34.28, 35.00, 42.38, 57.62, -15.23 +34.61, 35.00, 47.08, 52.92, -5.84 +34.94, 35.00, 46.83, 53.17, -6.33 +35.33, 35.00, 44.06, 55.94, -11.87 +35.66, 35.00, 46.29, 53.71, -7.43 +35.99, 35.00, 46.04, 53.96, -7.93 +36.39, 35.00, 43.26, 56.74, -13.48 +36.72, 35.00, 45.48, 54.52, -9.04 +36.98, 35.00, 47.75, 52.25, -4.51 +37.31, 35.00, 45.02, 54.98, -9.96 +37.57, 35.00, 47.28, 52.72, -5.43 +37.84, 35.00, 47.08, 52.92, -5.85 +38.10, 35.00, 46.87, 53.13, -6.27 +38.36, 35.00, 46.66, 53.34, -6.69 +38.63, 35.00, 46.44, 53.56, -7.11 +38.89, 35.00, 46.23, 53.77, -7.54 +39.09, 35.00, 48.54, 51.46, -2.92 +39.35, 35.00, 45.85, 54.15, -8.29 +39.55, 35.00, 48.16, 51.84, -3.68 +39.68, 35.00, 50.52, 49.48, 1.03 +39.88, 35.00, 47.88, 52.12, -4.24 +40.14, 35.00, 45.19, 54.81, -9.62 +40.34, 35.00, 47.49, 52.51, -5.02 +40.41, 35.00, 52.37, 47.63, 4.73 +40.61, 35.00, 47.25, 52.75, -5.49 +40.74, 35.00, 49.60, 50.40, -0.79 +40.94, 35.00, 46.96, 53.04, -6.08 +41.00, 35.00, 51.83, 48.17, 3.67 +41.13, 35.00, 49.24, 50.76, -1.52 +41.20, 35.00, 51.64, 48.36, 3.28 +41.20, 35.00, 54.09, 45.91, 8.18 +41.20, 35.00, 54.07, 45.93, 8.13 +41.20, 35.00, 54.04, 45.96, 8.08 +41.20, 35.00, 54.02, 45.98, 8.04 +41.13, 35.00, 56.52, 43.48, 13.03 +41.00, 35.00, 59.07, 40.93, 18.13 +41.00, 35.00, 54.10, 45.90, 8.20 +41.00, 35.00, 54.08, 45.92, 8.15 +41.00, 35.00, 54.05, 45.95, 8.11 +40.94, 35.00, 56.55, 43.45, 13.11 +40.94, 35.00, 54.06, 45.94, 8.12 +40.94, 35.00, 54.04, 45.96, 8.07 +40.87, 35.00, 56.54, 43.46, 13.07 +40.74, 35.00, 59.09, 40.91, 18.17 +40.74, 35.00, 54.12, 45.88, 8.24 +40.67, 35.00, 56.62, 43.38, 13.24 +40.61, 35.00, 56.65, 43.35, 13.30 +40.41, 35.00, 61.72, 38.28, 23.44 +40.21, 35.00, 61.85, 38.15, 23.70 +40.14, 35.00, 56.94, 43.06, 13.87 +39.95, 35.00, 62.01, 37.99, 24.02 +39.81, 35.00, 59.62, 40.38, 19.24 +39.62, 35.00, 62.22, 37.78, 24.44 +39.62, 35.00, 54.79, 45.21, 9.58 +39.42, 35.00, 62.34, 37.66, 24.67 +39.35, 35.00, 57.42, 42.58, 14.85 +39.29, 35.00, 57.46, 42.54, 14.92 +39.29, 35.00, 54.97, 45.03, 9.94 +39.16, 35.00, 60.00, 40.00, 19.99 +39.09, 35.00, 57.56, 42.44, 15.12 +39.09, 35.00, 55.07, 44.93, 10.14 +39.09, 35.00, 55.06, 44.94, 10.11 +39.02, 35.00, 57.56, 42.44, 15.13 +38.89, 35.00, 60.12, 39.88, 20.24 +38.83, 35.00, 57.68, 42.32, 15.36 +38.76, 35.00, 57.72, 42.28, 15.44 +38.63, 35.00, 60.27, 39.73, 20.55 +38.56, 35.00, 57.84, 42.16, 15.68 +38.50, 35.00, 57.88, 42.12, 15.75 +38.36, 35.00, 60.43, 39.57, 20.87 +38.30, 35.00, 58.00, 42.00, 16.00 +38.30, 35.00, 55.51, 44.49, 11.03 +38.23, 35.00, 58.02, 41.98, 16.05 +38.23, 35.00, 55.54, 44.46, 11.08 +38.23, 35.00, 55.53, 44.47, 11.05 +38.10, 35.00, 60.56, 39.44, 21.12 +38.10, 35.00, 55.60, 44.40, 11.21 +38.10, 35.00, 55.59, 44.41, 11.18 +38.10, 35.00, 55.58, 44.42, 11.16 +38.10, 35.00, 55.57, 44.43, 11.14 +38.10, 35.00, 55.56, 44.44, 11.11 +38.10, 35.00, 55.54, 44.46, 11.09 +38.10, 35.00, 55.53, 44.47, 11.07 +38.10, 35.00, 55.52, 44.48, 11.04 +38.10, 35.00, 55.51, 44.49, 11.02 +38.10, 35.00, 55.50, 44.50, 11.00 +38.03, 35.00, 58.01, 41.99, 16.02 +38.03, 35.00, 55.53, 44.47, 11.05 +38.03, 35.00, 55.51, 44.49, 11.03 +38.03, 35.00, 55.50, 44.50, 11.00 +38.10, 35.00, 52.97, 47.03, 5.94 +38.10, 35.00, 55.43, 44.57, 10.86 +38.10, 35.00, 55.42, 44.58, 10.84 +38.10, 35.00, 55.41, 44.59, 10.81 +38.10, 35.00, 55.39, 44.61, 10.79 +38.23, 35.00, 50.34, 49.66, 0.68 +38.30, 35.00, 52.75, 47.25, 5.50 +38.30, 35.00, 55.21, 44.79, 10.42 +38.30, 35.00, 55.20, 44.80, 10.39 +38.36, 35.00, 52.66, 47.34, 5.33 +38.36, 35.00, 55.12, 44.88, 10.25 +38.50, 35.00, 50.07, 49.93, 0.13 +38.50, 35.00, 55.00, 45.00, 9.99 +38.56, 35.00, 52.46, 47.54, 4.93 +38.56, 35.00, 54.92, 45.08, 9.84 +38.56, 35.00, 54.91, 45.09, 9.82 +38.63, 35.00, 52.37, 47.63, 4.75 +38.63, 35.00, 54.83, 45.17, 9.66 +38.76, 35.00, 49.77, 50.23, -0.45 +38.76, 35.00, 54.70, 45.30, 9.41 +38.83, 35.00, 52.17, 47.83, 4.34 +38.89, 35.00, 52.10, 47.90, 4.21 +39.02, 35.00, 49.52, 50.48, -0.96 +39.02, 35.00, 54.45, 45.55, 8.89 +39.09, 35.00, 51.91, 48.09, 3.82 +39.16, 35.00, 51.85, 48.15, 3.69 +39.16, 35.00, 54.30, 45.70, 8.60 +39.29, 35.00, 49.24, 50.76, -1.51 +39.35, 35.00, 51.65, 48.35, 3.30 +39.42, 35.00, 51.58, 48.42, 3.17 +39.55, 35.00, 49.00, 51.00, -2.01 +39.55, 35.00, 53.92, 46.08, 7.84 +39.62, 35.00, 51.38, 48.62, 2.77 +39.68, 35.00, 51.32, 48.68, 2.63 +39.81, 35.00, 48.73, 51.27, -2.54 +39.81, 35.00, 53.65, 46.35, 7.31 +39.88, 35.00, 51.11, 48.89, 2.23 +39.95, 35.00, 51.05, 48.95, 2.09 +40.08, 35.00, 48.46, 51.54, -3.09 +40.08, 35.00, 53.38, 46.62, 6.76 +40.14, 35.00, 50.84, 49.16, 1.68 +40.21, 35.00, 50.77, 49.23, 1.54 +40.21, 35.00, 53.22, 46.78, 6.45 +40.34, 35.00, 48.16, 51.84, -3.68 +40.41, 35.00, 50.56, 49.44, 1.13 +40.41, 35.00, 53.01, 46.99, 6.03 +40.47, 35.00, 50.47, 49.53, 0.95 +40.47, 35.00, 52.92, 47.08, 5.85 +40.47, 35.00, 52.90, 47.10, 5.81 +40.47, 35.00, 52.88, 47.12, 5.77 +40.47, 35.00, 52.86, 47.14, 5.73 +40.61, 35.00, 47.80, 52.20, -4.40 +40.61, 35.00, 52.72, 47.28, 5.44 +40.61, 35.00, 52.70, 47.30, 5.40 +40.61, 35.00, 52.68, 47.32, 5.36 +40.61, 35.00, 52.66, 47.34, 5.32 +40.67, 35.00, 50.12, 49.88, 0.23 +40.67, 35.00, 52.57, 47.43, 5.13 +40.67, 35.00, 52.55, 47.45, 5.09 +40.67, 35.00, 52.52, 47.48, 5.05 +40.67, 35.00, 52.50, 47.50, 5.01 +40.67, 35.00, 52.48, 47.52, 4.96 +40.67, 35.00, 52.46, 47.54, 4.92 +40.67, 35.00, 52.44, 47.56, 4.88 +40.67, 35.00, 52.42, 47.58, 4.84 +40.67, 35.00, 52.40, 47.60, 4.79 +40.67, 35.00, 52.38, 47.62, 4.75 +40.67, 35.00, 52.35, 47.65, 4.71 +40.67, 35.00, 52.33, 47.67, 4.67 +40.61, 35.00, 54.83, 45.17, 9.67 +40.61, 35.00, 52.34, 47.66, 4.68 +40.47, 35.00, 57.36, 42.64, 14.72 +40.47, 35.00, 52.40, 47.60, 4.80 +40.41, 35.00, 54.90, 45.10, 9.80 +40.41, 35.00, 52.41, 47.59, 4.81 +40.41, 35.00, 52.39, 47.61, 4.77 +40.34, 35.00, 54.89, 45.11, 9.78 +40.34, 35.00, 52.40, 47.60, 4.79 +40.21, 35.00, 57.42, 42.58, 14.84 +40.21, 35.00, 52.46, 47.54, 4.91 +40.14, 35.00, 54.96, 45.04, 9.92 +40.14, 35.00, 52.47, 47.53, 4.93 +40.08, 35.00, 54.97, 45.03, 9.94 +40.08, 35.00, 52.48, 47.52, 4.96 +39.95, 35.00, 57.50, 42.50, 15.00 +39.95, 35.00, 52.54, 47.46, 5.08 +39.88, 35.00, 55.04, 44.96, 10.09 +39.88, 35.00, 52.55, 47.45, 5.11 +39.81, 35.00, 55.06, 44.94, 10.11 +39.81, 35.00, 52.57, 47.43, 5.13 +39.68, 35.00, 57.59, 42.41, 15.18 +39.68, 35.00, 52.63, 47.37, 5.26 +39.62, 35.00, 55.13, 44.87, 10.27 +39.62, 35.00, 52.64, 47.36, 5.29 +39.55, 35.00, 55.15, 44.85, 10.30 +39.55, 35.00, 52.66, 47.34, 5.32 +39.42, 35.00, 57.69, 42.31, 15.37 +39.42, 35.00, 52.73, 47.27, 5.45 +39.42, 35.00, 52.71, 47.29, 5.42 +39.35, 35.00, 55.21, 44.79, 10.43 +39.35, 35.00, 52.73, 47.27, 5.45 +39.35, 35.00, 52.71, 47.29, 5.42 +39.35, 35.00, 52.69, 47.31, 5.39 +39.35, 35.00, 52.68, 47.32, 5.35 +39.29, 35.00, 55.18, 44.82, 10.36 +39.29, 35.00, 52.69, 47.31, 5.39 +39.29, 35.00, 52.68, 47.32, 5.36 +39.29, 35.00, 52.66, 47.34, 5.32 +39.16, 35.00, 57.69, 42.31, 15.38 +39.16, 35.00, 52.73, 47.27, 5.46 +39.16, 35.00, 52.71, 47.29, 5.43 +39.16, 35.00, 52.70, 47.30, 5.40 +39.16, 35.00, 52.68, 47.32, 5.37 +39.09, 35.00, 55.19, 44.81, 10.38 +39.09, 35.00, 52.70, 47.30, 5.40 +39.09, 35.00, 52.69, 47.31, 5.37 +39.09, 35.00, 52.67, 47.33, 5.34 +39.09, 35.00, 52.66, 47.34, 5.31 +39.09, 35.00, 52.64, 47.36, 5.28 +39.09, 35.00, 52.62, 47.38, 5.25 +39.09, 35.00, 52.61, 47.39, 5.22 +39.09, 35.00, 52.59, 47.41, 5.19 +39.09, 35.00, 52.58, 47.42, 5.16 +39.09, 35.00, 52.56, 47.44, 5.13 +39.09, 35.00, 52.55, 47.45, 5.10 +39.09, 35.00, 52.53, 47.47, 5.07 +39.09, 35.00, 52.52, 47.48, 5.04 +39.09, 35.00, 52.50, 47.50, 5.00 +39.09, 35.00, 52.49, 47.51, 4.97 +39.09, 35.00, 52.47, 47.53, 4.94 +39.09, 35.00, 52.46, 47.54, 4.91 +39.09, 35.00, 52.44, 47.56, 4.88 +39.16, 35.00, 49.90, 50.10, -0.19 +39.16, 35.00, 52.36, 47.64, 4.72 +39.16, 35.00, 52.34, 47.66, 4.69 +39.16, 35.00, 52.33, 47.67, 4.66 +39.16, 35.00, 52.31, 47.69, 4.63 +39.16, 35.00, 52.30, 47.70, 4.60 +39.16, 35.00, 52.28, 47.72, 4.56 +39.16, 35.00, 52.27, 47.73, 4.53 +39.29, 35.00, 47.21, 52.79, -5.58 +39.16, 35.00, 57.18, 42.82, 14.36 +39.16, 35.00, 52.22, 47.78, 4.44 +39.29, 35.00, 47.16, 52.84, -5.68 +39.29, 35.00, 52.09, 47.91, 4.18 +39.29, 35.00, 52.07, 47.93, 4.14 +39.29, 35.00, 52.06, 47.94, 4.11 +39.29, 35.00, 52.04, 47.96, 4.08 +39.35, 35.00, 49.50, 50.50, -0.99 +39.35, 35.00, 51.96, 48.04, 3.92 +39.35, 35.00, 51.94, 48.06, 3.88 +39.42, 35.00, 49.40, 50.60, -1.19 +39.42, 35.00, 51.86, 48.14, 3.72 +39.42, 35.00, 51.84, 48.16, 3.69 +39.42, 35.00, 51.83, 48.17, 3.65 +39.42, 35.00, 51.81, 48.19, 3.62 +39.42, 35.00, 51.79, 48.21, 3.59 +39.55, 35.00, 46.73, 53.27, -6.53 +39.55, 35.00, 51.66, 48.34, 3.32 +39.55, 35.00, 51.64, 48.36, 3.29 +39.55, 35.00, 51.63, 48.37, 3.25 +39.55, 35.00, 51.61, 48.39, 3.22 +39.55, 35.00, 51.59, 48.41, 3.18 +39.55, 35.00, 51.57, 48.43, 3.15 +39.55, 35.00, 51.56, 48.44, 3.12 +39.55, 35.00, 51.54, 48.46, 3.08 +39.62, 35.00, 49.00, 51.00, -2.00 +39.62, 35.00, 51.46, 48.54, 2.91 +39.62, 35.00, 51.44, 48.56, 2.88 +39.62, 35.00, 51.42, 48.58, 2.84 +39.62, 35.00, 51.40, 48.60, 2.81 +39.62, 35.00, 51.39, 48.61, 2.77 +39.62, 35.00, 51.37, 48.63, 2.74 +39.62, 35.00, 51.35, 48.65, 2.71 +39.62, 35.00, 51.34, 48.66, 2.67 +39.62, 35.00, 51.32, 48.68, 2.64 +39.62, 35.00, 51.30, 48.70, 2.60 +39.62, 35.00, 51.28, 48.72, 2.57 +39.62, 35.00, 51.27, 48.73, 2.53 +39.62, 35.00, 51.25, 48.75, 2.50 +39.55, 35.00, 53.75, 46.25, 7.51 +39.55, 35.00, 51.26, 48.74, 2.53 +39.55, 35.00, 51.25, 48.75, 2.49 +39.55, 35.00, 51.23, 48.77, 2.46 +39.42, 35.00, 56.26, 43.74, 12.51 +39.42, 35.00, 51.30, 48.70, 2.59 +39.42, 35.00, 51.28, 48.72, 2.56 +39.42, 35.00, 51.26, 48.74, 2.53 +39.35, 35.00, 53.77, 46.23, 7.54 +39.35, 35.00, 51.28, 48.72, 2.56 +39.35, 35.00, 51.26, 48.74, 2.53 +39.35, 35.00, 51.25, 48.75, 2.49 +39.35, 35.00, 51.23, 48.77, 2.46 +39.29, 35.00, 53.74, 46.26, 7.47 +39.29, 35.00, 51.25, 48.75, 2.50 +39.29, 35.00, 51.23, 48.77, 2.46 +39.29, 35.00, 51.22, 48.78, 2.43 +39.16, 35.00, 56.24, 43.76, 12.49 +39.16, 35.00, 51.28, 48.72, 2.57 +39.09, 35.00, 53.79, 46.21, 7.58 +39.09, 35.00, 51.30, 48.70, 2.60 +39.09, 35.00, 51.29, 48.71, 2.57 +39.02, 35.00, 53.79, 46.21, 7.59 +39.02, 35.00, 51.31, 48.69, 2.61 +38.89, 35.00, 56.33, 43.67, 12.67 +38.89, 35.00, 51.38, 48.62, 2.75 +38.89, 35.00, 51.36, 48.64, 2.72 +38.83, 35.00, 53.87, 46.13, 7.74 +38.83, 35.00, 51.38, 48.62, 2.76 +38.83, 35.00, 51.37, 48.63, 2.73 +38.76, 35.00, 53.87, 46.13, 7.75 +38.76, 35.00, 51.39, 48.61, 2.78 +38.76, 35.00, 51.37, 48.63, 2.75 +38.63, 35.00, 56.40, 43.60, 12.81 +38.63, 35.00, 51.45, 48.55, 2.89 +38.63, 35.00, 51.43, 48.57, 2.87 +38.56, 35.00, 53.94, 46.06, 7.88 +38.56, 35.00, 51.46, 48.54, 2.91 +38.56, 35.00, 51.44, 48.56, 2.88 +38.50, 35.00, 53.95, 46.05, 7.90 +38.50, 35.00, 51.47, 48.53, 2.93 +38.50, 35.00, 51.45, 48.55, 2.90 +38.36, 35.00, 56.48, 43.52, 12.96 +38.36, 35.00, 51.53, 48.47, 3.05 +38.36, 35.00, 51.51, 48.49, 3.03 +38.36, 35.00, 51.50, 48.50, 3.00 +38.36, 35.00, 51.49, 48.51, 2.98 +38.30, 35.00, 54.00, 46.00, 7.99 +38.30, 35.00, 51.51, 48.49, 3.03 +38.30, 35.00, 51.50, 48.50, 3.00 +38.30, 35.00, 51.49, 48.51, 2.98 +38.30, 35.00, 51.48, 48.52, 2.95 +38.30, 35.00, 51.46, 48.54, 2.93 +38.30, 35.00, 51.45, 48.55, 2.90 +38.30, 35.00, 51.44, 48.56, 2.88 +38.30, 35.00, 51.43, 48.57, 2.85 +38.23, 35.00, 53.94, 46.06, 7.87 +38.23, 35.00, 51.45, 48.55, 2.90 +38.23, 35.00, 51.44, 48.56, 2.88 +38.23, 35.00, 51.43, 48.57, 2.85 +38.23, 35.00, 51.41, 48.59, 2.83 +38.23, 35.00, 51.40, 48.60, 2.81 +38.23, 35.00, 51.39, 48.61, 2.78 +38.23, 35.00, 51.38, 48.62, 2.76 +38.23, 35.00, 51.37, 48.63, 2.73 +38.23, 35.00, 51.35, 48.65, 2.71 +38.23, 35.00, 51.34, 48.66, 2.68 +38.23, 35.00, 51.33, 48.67, 2.66 +38.23, 35.00, 51.32, 48.68, 2.64 +38.23, 35.00, 51.31, 48.69, 2.61 +38.23, 35.00, 51.29, 48.71, 2.59 +38.30, 35.00, 48.76, 51.24, -2.48 +38.23, 35.00, 53.74, 46.26, 7.48 +38.30, 35.00, 48.74, 51.26, -2.53 +38.30, 35.00, 51.19, 48.81, 2.39 +38.30, 35.00, 51.18, 48.82, 2.37 +38.30, 35.00, 51.17, 48.83, 2.34 +38.30, 35.00, 51.16, 48.84, 2.32 +38.30, 35.00, 51.15, 48.85, 2.29 +38.30, 35.00, 51.13, 48.87, 2.27 +38.30, 35.00, 51.12, 48.88, 2.24 +38.30, 35.00, 51.11, 48.89, 2.22 +38.30, 35.00, 51.10, 48.90, 2.19 +38.36, 35.00, 48.56, 51.44, -2.88 +38.36, 35.00, 51.02, 48.98, 2.04 +38.36, 35.00, 51.01, 48.99, 2.02 +38.36, 35.00, 51.00, 49.00, 1.99 +38.36, 35.00, 50.98, 49.02, 1.97 +38.36, 35.00, 50.97, 49.03, 1.94 +38.36, 35.00, 50.96, 49.04, 1.92 +38.36, 35.00, 50.95, 49.05, 1.89 +38.36, 35.00, 50.93, 49.07, 1.87 +38.36, 35.00, 50.92, 49.08, 1.84 +38.36, 35.00, 50.91, 49.09, 1.82 +38.36, 35.00, 50.90, 49.10, 1.79 +38.36, 35.00, 50.88, 49.12, 1.77 +38.36, 35.00, 50.87, 49.13, 1.74 +38.36, 35.00, 50.86, 49.14, 1.71 +38.36, 35.00, 50.84, 49.16, 1.69 +38.36, 35.00, 50.83, 49.17, 1.66 +38.30, 35.00, 53.34, 46.66, 6.68 +38.30, 35.00, 50.86, 49.14, 1.71 +38.30, 35.00, 50.84, 49.16, 1.69 +38.30, 35.00, 50.83, 49.17, 1.66 +38.23, 35.00, 53.34, 46.66, 6.68 +38.23, 35.00, 50.86, 49.14, 1.71 +38.23, 35.00, 50.85, 49.15, 1.69 +38.23, 35.00, 50.83, 49.17, 1.67 +38.23, 35.00, 50.82, 49.18, 1.64 +38.23, 35.00, 50.81, 49.19, 1.62 +38.23, 35.00, 50.80, 49.20, 1.59 +38.23, 35.00, 50.78, 49.22, 1.57 +38.23, 35.00, 50.77, 49.23, 1.54 +38.23, 35.00, 50.76, 49.24, 1.52 +38.23, 35.00, 50.75, 49.25, 1.50 +38.23, 35.00, 50.74, 49.26, 1.47 +38.10, 35.00, 55.77, 44.23, 11.53 +38.10, 35.00, 50.81, 49.19, 1.62 +38.10, 35.00, 50.80, 49.20, 1.60 +38.10, 35.00, 50.79, 49.21, 1.58 +38.03, 35.00, 53.30, 46.70, 6.60 +38.03, 35.00, 50.82, 49.18, 1.63 +38.03, 35.00, 50.80, 49.20, 1.61 +37.97, 35.00, 53.31, 46.69, 6.63 +37.97, 35.00, 50.83, 49.17, 1.66 +37.97, 35.00, 50.82, 49.18, 1.64 +37.97, 35.00, 50.81, 49.19, 1.62 +37.97, 35.00, 50.80, 49.20, 1.59 +37.97, 35.00, 50.79, 49.21, 1.57 +37.97, 35.00, 50.78, 49.22, 1.55 +37.97, 35.00, 50.76, 49.24, 1.53 +37.97, 35.00, 50.75, 49.25, 1.51 +37.97, 35.00, 50.74, 49.26, 1.48 +37.97, 35.00, 50.73, 49.27, 1.46 +37.97, 35.00, 50.72, 49.28, 1.44 +37.97, 35.00, 50.71, 49.29, 1.42 +37.97, 35.00, 50.70, 49.30, 1.39 +37.97, 35.00, 50.69, 49.31, 1.37 +37.84, 35.00, 55.72, 44.28, 11.44 +37.84, 35.00, 50.76, 49.24, 1.53 +37.84, 35.00, 50.75, 49.25, 1.51 +37.84, 35.00, 50.74, 49.26, 1.48 +37.77, 35.00, 53.25, 46.75, 6.51 +37.77, 35.00, 50.77, 49.23, 1.54 +37.77, 35.00, 50.76, 49.24, 1.52 +37.77, 35.00, 50.75, 49.25, 1.50 +37.77, 35.00, 50.74, 49.26, 1.48 +37.77, 35.00, 50.73, 49.27, 1.46 +37.77, 35.00, 50.72, 49.28, 1.44 +37.77, 35.00, 50.71, 49.29, 1.42 +37.77, 35.00, 50.70, 49.30, 1.40 +37.77, 35.00, 50.69, 49.31, 1.38 +37.77, 35.00, 50.68, 49.32, 1.36 +37.77, 35.00, 50.67, 49.33, 1.33 +37.77, 35.00, 50.66, 49.34, 1.31 +37.77, 35.00, 50.65, 49.35, 1.29 +37.71, 35.00, 53.16, 46.84, 6.32 +37.71, 35.00, 50.68, 49.32, 1.35 +37.71, 35.00, 50.67, 49.33, 1.33 +37.57, 35.00, 55.70, 44.30, 11.40 +37.57, 35.00, 50.75, 49.25, 1.49 +37.57, 35.00, 50.74, 49.26, 1.47 +37.51, 35.00, 53.25, 46.75, 6.49 +37.51, 35.00, 50.77, 49.23, 1.53 +37.51, 35.00, 50.76, 49.24, 1.51 +37.51, 35.00, 50.75, 49.25, 1.49 +37.51, 35.00, 50.74, 49.26, 1.48 +37.51, 35.00, 50.73, 49.27, 1.46 +37.57, 35.00, 48.20, 51.80, -3.61 +37.57, 35.00, 50.66, 49.34, 1.32 +37.57, 35.00, 50.65, 49.35, 1.30 +37.57, 35.00, 50.64, 49.36, 1.28 +37.57, 35.00, 50.63, 49.37, 1.26 +37.57, 35.00, 50.62, 49.38, 1.24 +37.57, 35.00, 50.61, 49.39, 1.22 +37.51, 35.00, 53.12, 46.88, 6.25 +37.51, 35.00, 50.64, 49.36, 1.28 +37.51, 35.00, 50.63, 49.37, 1.27 +37.51, 35.00, 50.62, 49.38, 1.25 +37.51, 35.00, 50.61, 49.39, 1.23 +37.51, 35.00, 50.60, 49.40, 1.21 +37.44, 35.00, 53.12, 46.88, 6.23 +37.44, 35.00, 50.64, 49.36, 1.27 +37.51, 35.00, 48.10, 51.90, -3.79 +37.51, 35.00, 50.57, 49.43, 1.13 +37.51, 35.00, 50.56, 49.44, 1.12 +37.51, 35.00, 50.55, 49.45, 1.10 +37.51, 35.00, 50.54, 49.46, 1.08 +37.57, 35.00, 48.01, 51.99, -3.98 +37.57, 35.00, 50.47, 49.53, 0.94 +37.57, 35.00, 50.46, 49.54, 0.92 +37.57, 35.00, 50.45, 49.55, 0.90 +37.57, 35.00, 50.44, 49.56, 0.88 +37.57, 35.00, 50.43, 49.57, 0.86 +37.57, 35.00, 50.42, 49.58, 0.84 +37.51, 35.00, 52.93, 47.07, 5.87 +37.57, 35.00, 47.93, 52.07, -4.14 +37.57, 35.00, 50.39, 49.61, 0.79 +37.57, 35.00, 50.38, 49.62, 0.77 +37.57, 35.00, 50.37, 49.63, 0.75 +37.57, 35.00, 50.36, 49.64, 0.73 +37.57, 35.00, 50.35, 49.65, 0.71 +37.71, 35.00, 45.30, 54.70, -9.40 +37.71, 35.00, 50.24, 49.76, 0.47 +37.71, 35.00, 50.23, 49.77, 0.45 +37.71, 35.00, 50.22, 49.78, 0.43 +37.71, 35.00, 50.21, 49.79, 0.41 +37.77, 35.00, 47.67, 52.33, -4.65 +37.77, 35.00, 50.13, 49.87, 0.27 +37.77, 35.00, 50.12, 49.88, 0.25 +37.77, 35.00, 50.11, 49.89, 0.23 +37.77, 35.00, 50.10, 49.90, 0.21 +37.77, 35.00, 50.09, 49.91, 0.19 +37.77, 35.00, 50.08, 49.92, 0.17 +37.77, 35.00, 50.07, 49.93, 0.15 +37.77, 35.00, 50.06, 49.94, 0.12 +37.77, 35.00, 50.05, 49.95, 0.10 +37.77, 35.00, 50.04, 49.96, 0.08 +37.77, 35.00, 50.03, 49.97, 0.06 +37.77, 35.00, 50.02, 49.98, 0.04 +37.77, 35.00, 50.01, 49.99, 0.02 +37.77, 35.00, 50.00, 50.00, -0.00 +37.77, 35.00, 49.99, 50.01, -0.02 +37.84, 35.00, 47.46, 52.54, -5.08 +37.84, 35.00, 49.92, 50.08, -0.16 +37.77, 35.00, 52.43, 47.57, 4.86 +37.84, 35.00, 47.43, 52.57, -5.15 +37.84, 35.00, 49.89, 50.11, -0.23 +37.77, 35.00, 52.40, 47.60, 4.80 +37.77, 35.00, 49.92, 50.08, -0.17 +37.77, 35.00, 49.91, 50.09, -0.19 +37.77, 35.00, 49.89, 50.11, -0.21 +37.77, 35.00, 49.88, 50.12, -0.23 +37.71, 35.00, 52.40, 47.60, 4.79 +37.71, 35.00, 49.91, 50.09, -0.17 +37.71, 35.00, 49.90, 50.10, -0.19 +37.71, 35.00, 49.89, 50.11, -0.21 +37.71, 35.00, 49.88, 50.12, -0.23 +37.71, 35.00, 49.87, 50.13, -0.25 +37.71, 35.00, 49.86, 50.14, -0.27 +37.71, 35.00, 49.85, 50.15, -0.29 +37.71, 35.00, 49.84, 50.16, -0.31 +37.71, 35.00, 49.83, 50.17, -0.33 +37.71, 35.00, 49.82, 50.18, -0.36 +37.71, 35.00, 49.81, 50.19, -0.38 +37.71, 35.00, 49.80, 50.20, -0.40 +37.71, 35.00, 49.79, 50.21, -0.42 +37.71, 35.00, 49.78, 50.22, -0.44 +37.57, 35.00, 54.81, 45.19, 9.63 +37.57, 35.00, 49.86, 50.14, -0.28 +37.57, 35.00, 49.85, 50.15, -0.30 +37.51, 35.00, 52.36, 47.64, 4.73 +37.51, 35.00, 49.88, 50.12, -0.24 +37.51, 35.00, 49.87, 50.13, -0.25 +37.51, 35.00, 49.86, 50.14, -0.27 +37.51, 35.00, 49.85, 50.15, -0.29 +37.51, 35.00, 49.84, 50.16, -0.31 +37.51, 35.00, 49.84, 50.16, -0.33 +37.51, 35.00, 49.83, 50.17, -0.35 +37.44, 35.00, 52.34, 47.66, 4.68 +37.44, 35.00, 49.86, 50.14, -0.29 +37.44, 35.00, 49.85, 50.15, -0.30 +37.44, 35.00, 49.84, 50.16, -0.32 +37.44, 35.00, 49.83, 50.17, -0.34 +37.44, 35.00, 49.82, 50.18, -0.36 +37.31, 35.00, 54.85, 45.15, 9.71 +37.31, 35.00, 49.90, 50.10, -0.20 +37.31, 35.00, 49.89, 50.11, -0.21 +37.31, 35.00, 49.88, 50.12, -0.23 +37.24, 35.00, 52.40, 47.60, 4.80 +37.24, 35.00, 49.92, 50.08, -0.17 +37.24, 35.00, 49.91, 50.09, -0.18 +37.24, 35.00, 49.90, 50.10, -0.20 +37.24, 35.00, 49.89, 50.11, -0.22 +37.18, 35.00, 52.41, 47.59, 4.81 +37.18, 35.00, 49.93, 50.07, -0.15 +37.18, 35.00, 49.92, 50.08, -0.17 +37.18, 35.00, 49.91, 50.09, -0.18 +37.05, 35.00, 54.94, 45.06, 9.89 +37.05, 35.00, 49.99, 50.01, -0.02 +37.05, 35.00, 49.98, 50.02, -0.03 +36.98, 35.00, 52.50, 47.50, 5.00 +36.98, 35.00, 50.02, 49.98, 0.04 +36.98, 35.00, 50.01, 49.99, 0.02 +36.98, 35.00, 50.00, 50.00, 0.01 +36.91, 35.00, 52.52, 47.48, 5.04 +36.91, 35.00, 50.04, 49.96, 0.08 +36.91, 35.00, 50.03, 49.97, 0.06 +36.78, 35.00, 55.07, 44.93, 10.14 +36.78, 35.00, 50.12, 49.88, 0.24 +36.78, 35.00, 50.11, 49.89, 0.22 +36.72, 35.00, 52.63, 47.37, 5.25 +36.72, 35.00, 50.15, 49.85, 0.30 +36.72, 35.00, 50.14, 49.86, 0.28 +36.72, 35.00, 50.13, 49.87, 0.27 +36.65, 35.00, 52.65, 47.35, 5.30 +36.65, 35.00, 50.17, 49.83, 0.34 +36.65, 35.00, 50.17, 49.83, 0.33 +36.65, 35.00, 50.16, 49.84, 0.32 +36.52, 35.00, 55.20, 44.80, 10.39 +36.52, 35.00, 50.25, 49.75, 0.49 +36.52, 35.00, 50.24, 49.76, 0.48 +36.52, 35.00, 50.24, 49.76, 0.47 +36.45, 35.00, 52.75, 47.25, 5.50 +36.45, 35.00, 50.27, 49.73, 0.55 +36.45, 35.00, 50.27, 49.73, 0.54 +36.45, 35.00, 50.26, 49.74, 0.53 +36.45, 35.00, 50.26, 49.74, 0.52 +36.45, 35.00, 50.25, 49.75, 0.50 +36.45, 35.00, 50.25, 49.75, 0.49 +36.45, 35.00, 50.24, 49.76, 0.48 +36.45, 35.00, 50.24, 49.76, 0.47 +36.45, 35.00, 50.23, 49.77, 0.46 +36.45, 35.00, 50.23, 49.77, 0.45 +36.39, 35.00, 52.74, 47.26, 5.48 +36.39, 35.00, 50.26, 49.74, 0.53 +36.39, 35.00, 50.26, 49.74, 0.52 +36.39, 35.00, 50.25, 49.75, 0.51 +36.39, 35.00, 50.25, 49.75, 0.50 +36.39, 35.00, 50.24, 49.76, 0.49 +36.25, 35.00, 55.28, 44.72, 10.56 +36.25, 35.00, 50.33, 49.67, 0.67 +36.25, 35.00, 50.33, 49.67, 0.66 +36.25, 35.00, 50.32, 49.68, 0.65 +36.25, 35.00, 50.32, 49.68, 0.64 +36.25, 35.00, 50.31, 49.69, 0.63 +36.25, 35.00, 50.31, 49.69, 0.62 +36.25, 35.00, 50.30, 49.70, 0.61 +36.25, 35.00, 50.30, 49.70, 0.60 +36.25, 35.00, 50.30, 49.70, 0.59 +36.25, 35.00, 50.29, 49.71, 0.58 +36.25, 35.00, 50.29, 49.71, 0.57 +36.25, 35.00, 50.28, 49.72, 0.56 +36.25, 35.00, 50.28, 49.72, 0.55 +36.19, 35.00, 52.79, 47.21, 5.59 +36.19, 35.00, 50.32, 49.68, 0.63 +36.19, 35.00, 50.31, 49.69, 0.63 +36.19, 35.00, 50.31, 49.69, 0.62 +36.19, 35.00, 50.30, 49.70, 0.61 +36.19, 35.00, 50.30, 49.70, 0.60 +36.19, 35.00, 50.29, 49.71, 0.59 +36.19, 35.00, 50.29, 49.71, 0.58 +36.19, 35.00, 50.29, 49.71, 0.57 +36.19, 35.00, 50.28, 49.72, 0.56 +36.19, 35.00, 50.28, 49.72, 0.55 +36.19, 35.00, 50.27, 49.73, 0.54 +36.19, 35.00, 50.27, 49.73, 0.54 +36.19, 35.00, 50.26, 49.74, 0.53 +36.19, 35.00, 50.26, 49.74, 0.52 +36.19, 35.00, 50.25, 49.75, 0.51 +36.12, 35.00, 52.77, 47.23, 5.54 +36.12, 35.00, 50.30, 49.70, 0.59 +36.19, 35.00, 47.77, 52.23, -4.46 +36.19, 35.00, 50.24, 49.76, 0.47 +36.19, 35.00, 50.23, 49.77, 0.47 +36.19, 35.00, 50.23, 49.77, 0.46 +36.19, 35.00, 50.22, 49.78, 0.45 +36.19, 35.00, 50.22, 49.78, 0.44 +36.19, 35.00, 50.21, 49.79, 0.43 +36.19, 35.00, 50.21, 49.79, 0.42 +36.19, 35.00, 50.21, 49.79, 0.41 +36.25, 35.00, 47.68, 52.32, -4.64 +36.25, 35.00, 50.15, 49.85, 0.29 +36.25, 35.00, 50.14, 49.86, 0.28 +36.25, 35.00, 50.14, 49.86, 0.28 +36.25, 35.00, 50.13, 49.87, 0.27 +36.25, 35.00, 50.13, 49.87, 0.26 +36.25, 35.00, 50.12, 49.88, 0.25 +36.25, 35.00, 50.12, 49.88, 0.24 +36.25, 35.00, 50.11, 49.89, 0.23 +36.25, 35.00, 50.11, 49.89, 0.22 +36.25, 35.00, 50.10, 49.90, 0.21 +36.25, 35.00, 50.10, 49.90, 0.20 +36.25, 35.00, 50.10, 49.90, 0.19 +36.25, 35.00, 50.09, 49.91, 0.18 +36.25, 35.00, 50.09, 49.91, 0.17 +36.39, 35.00, 45.04, 54.96, -9.92 +36.39, 35.00, 49.98, 50.02, -0.05 +36.39, 35.00, 49.97, 50.03, -0.06 +36.39, 35.00, 49.97, 50.03, -0.07 +36.39, 35.00, 49.96, 50.04, -0.08 +36.39, 35.00, 49.96, 50.04, -0.09 +36.45, 35.00, 47.43, 52.57, -5.14 +36.45, 35.00, 49.90, 50.10, -0.21 +36.45, 35.00, 49.89, 50.11, -0.22 +36.45, 35.00, 49.88, 50.12, -0.23 +36.45, 35.00, 49.88, 50.12, -0.24 +36.39, 35.00, 52.40, 47.60, 4.79 +36.45, 35.00, 47.40, 52.60, -5.21 +36.39, 35.00, 52.38, 47.62, 4.77 +36.39, 35.00, 49.91, 50.09, -0.18 +36.45, 35.00, 47.38, 52.62, -5.24 +36.39, 35.00, 52.37, 47.63, 4.74 +36.45, 35.00, 47.37, 52.63, -5.26 +36.45, 35.00, 49.84, 50.16, -0.33 +36.45, 35.00, 49.83, 50.17, -0.34 +36.45, 35.00, 49.83, 50.17, -0.35 +36.45, 35.00, 49.82, 50.18, -0.36 +36.45, 35.00, 49.81, 50.19, -0.37 +36.45, 35.00, 49.81, 50.19, -0.38 +36.45, 35.00, 49.80, 50.20, -0.39 +36.45, 35.00, 49.80, 50.20, -0.40 +36.52, 35.00, 47.27, 52.73, -5.46 +36.52, 35.00, 49.74, 50.26, -0.52 +36.52, 35.00, 49.73, 50.27, -0.54 +36.52, 35.00, 49.73, 50.27, -0.55 +36.52, 35.00, 49.72, 50.28, -0.56 +36.52, 35.00, 49.71, 50.29, -0.57 +36.52, 35.00, 49.71, 50.29, -0.58 +36.52, 35.00, 49.70, 50.30, -0.59 +36.52, 35.00, 49.70, 50.30, -0.60 +36.52, 35.00, 49.69, 50.31, -0.62 +36.52, 35.00, 49.69, 50.31, -0.63 +36.52, 35.00, 49.68, 50.32, -0.64 +36.52, 35.00, 49.68, 50.32, -0.65 +36.52, 35.00, 49.67, 50.33, -0.66 +36.52, 35.00, 49.66, 50.34, -0.67 +36.52, 35.00, 49.66, 50.34, -0.68 +36.52, 35.00, 49.65, 50.35, -0.70 +36.52, 35.00, 49.65, 50.35, -0.71 +36.52, 35.00, 49.64, 50.36, -0.72 +36.52, 35.00, 49.64, 50.36, -0.73 +36.52, 35.00, 49.63, 50.37, -0.74 +36.52, 35.00, 49.62, 50.38, -0.75 +36.52, 35.00, 49.62, 50.38, -0.76 +36.52, 35.00, 49.61, 50.39, -0.78 +36.52, 35.00, 49.61, 50.39, -0.79 +36.52, 35.00, 49.60, 50.40, -0.80 +36.52, 35.00, 49.60, 50.40, -0.81 +36.52, 35.00, 49.59, 50.41, -0.82 +36.45, 35.00, 52.11, 47.89, 4.21 +36.45, 35.00, 49.63, 50.37, -0.74 +36.45, 35.00, 49.62, 50.38, -0.75 +36.45, 35.00, 49.62, 50.38, -0.77 +36.45, 35.00, 49.61, 50.39, -0.78 +36.39, 35.00, 52.13, 47.87, 4.26 +36.45, 35.00, 47.13, 52.87, -5.74 +36.39, 35.00, 52.12, 47.88, 4.23 +36.39, 35.00, 49.64, 50.36, -0.72 +36.39, 35.00, 49.64, 50.36, -0.73 +36.39, 35.00, 49.63, 50.37, -0.74 +36.39, 35.00, 49.62, 50.38, -0.75 +36.39, 35.00, 49.62, 50.38, -0.76 +36.39, 35.00, 49.61, 50.39, -0.77 +36.39, 35.00, 49.61, 50.39, -0.78 +36.39, 35.00, 49.60, 50.40, -0.79 +36.39, 35.00, 49.60, 50.40, -0.80 +36.39, 35.00, 49.59, 50.41, -0.81 +36.39, 35.00, 49.59, 50.41, -0.82 +36.39, 35.00, 49.58, 50.42, -0.83 +36.25, 35.00, 54.62, 45.38, 9.24 +36.25, 35.00, 49.67, 50.33, -0.66 +36.25, 35.00, 49.67, 50.33, -0.66 +36.25, 35.00, 49.66, 50.34, -0.67 +36.25, 35.00, 49.66, 50.34, -0.68 +36.25, 35.00, 49.65, 50.35, -0.69 +36.25, 35.00, 49.65, 50.35, -0.70 +36.25, 35.00, 49.64, 50.36, -0.71 +36.25, 35.00, 49.64, 50.36, -0.72 +36.25, 35.00, 49.63, 50.37, -0.73 +36.25, 35.00, 49.63, 50.37, -0.74 +36.25, 35.00, 49.63, 50.37, -0.75 +36.25, 35.00, 49.62, 50.38, -0.76 +36.25, 35.00, 49.62, 50.38, -0.77 +36.25, 35.00, 49.61, 50.39, -0.78 +36.19, 35.00, 52.13, 47.87, 4.26 +36.19, 35.00, 49.65, 50.35, -0.70 +36.19, 35.00, 49.65, 50.35, -0.71 +36.19, 35.00, 49.64, 50.36, -0.71 +36.19, 35.00, 49.64, 50.36, -0.72 +36.19, 35.00, 49.63, 50.37, -0.73 +36.19, 35.00, 49.63, 50.37, -0.74 +36.19, 35.00, 49.63, 50.37, -0.75 +36.19, 35.00, 49.62, 50.38, -0.76 +36.19, 35.00, 49.62, 50.38, -0.77 +36.19, 35.00, 49.61, 50.39, -0.78 +36.19, 35.00, 49.61, 50.39, -0.79 +36.19, 35.00, 49.60, 50.40, -0.79 +36.12, 35.00, 52.12, 47.88, 4.24 +36.12, 35.00, 49.64, 50.36, -0.71 +36.12, 35.00, 49.64, 50.36, -0.72 +36.12, 35.00, 49.64, 50.36, -0.73 +36.12, 35.00, 49.63, 50.37, -0.74 +36.12, 35.00, 49.63, 50.37, -0.75 +35.99, 35.00, 54.67, 45.33, 9.33 +35.99, 35.00, 49.72, 50.28, -0.56 +35.99, 35.00, 49.71, 50.29, -0.57 +35.99, 35.00, 49.71, 50.29, -0.58 +35.93, 35.00, 52.23, 47.77, 4.46 +35.93, 35.00, 49.75, 50.25, -0.49 +35.93, 35.00, 49.75, 50.25, -0.50 +35.93, 35.00, 49.75, 50.25, -0.51 +35.93, 35.00, 49.74, 50.26, -0.51 +35.93, 35.00, 49.74, 50.26, -0.52 +35.93, 35.00, 49.74, 50.26, -0.53 +35.93, 35.00, 49.73, 50.27, -0.53 +35.93, 35.00, 49.73, 50.27, -0.54 +35.93, 35.00, 49.73, 50.27, -0.55 +35.93, 35.00, 49.72, 50.28, -0.56 +35.93, 35.00, 49.72, 50.28, -0.56 +35.93, 35.00, 49.72, 50.28, -0.57 +35.86, 35.00, 52.23, 47.77, 4.47 +35.86, 35.00, 49.76, 50.24, -0.48 +35.86, 35.00, 49.76, 50.24, -0.49 +35.86, 35.00, 49.75, 50.25, -0.50 +35.73, 35.00, 54.79, 45.21, 9.58 +35.73, 35.00, 49.85, 50.15, -0.31 +35.73, 35.00, 49.84, 50.16, -0.31 +35.73, 35.00, 49.84, 50.16, -0.32 +35.73, 35.00, 49.84, 50.16, -0.33 +35.73, 35.00, 49.83, 50.17, -0.33 +35.73, 35.00, 49.83, 50.17, -0.34 +35.73, 35.00, 49.83, 50.17, -0.34 +35.73, 35.00, 49.83, 50.17, -0.35 +35.73, 35.00, 49.82, 50.18, -0.35 +35.73, 35.00, 49.82, 50.18, -0.36 +35.73, 35.00, 49.82, 50.18, -0.36 +35.73, 35.00, 49.82, 50.18, -0.37 +35.73, 35.00, 49.81, 50.19, -0.37 +35.73, 35.00, 49.81, 50.19, -0.38 +35.73, 35.00, 49.81, 50.19, -0.39 +35.73, 35.00, 49.80, 50.20, -0.39 +35.73, 35.00, 49.80, 50.20, -0.40 +35.73, 35.00, 49.80, 50.20, -0.40 +35.66, 35.00, 52.32, 47.68, 4.64 +35.73, 35.00, 47.32, 52.68, -5.36 +35.73, 35.00, 49.79, 50.21, -0.42 +35.73, 35.00, 49.79, 50.21, -0.42 +35.73, 35.00, 49.79, 50.21, -0.43 +35.73, 35.00, 49.78, 50.22, -0.43 +35.73, 35.00, 49.78, 50.22, -0.44 +35.73, 35.00, 49.78, 50.22, -0.45 +35.73, 35.00, 49.77, 50.23, -0.45 +35.86, 35.00, 44.73, 55.27, -10.54 +35.86, 35.00, 49.67, 50.33, -0.66 +35.86, 35.00, 49.67, 50.33, -0.67 +35.86, 35.00, 49.66, 50.34, -0.67 +35.86, 35.00, 49.66, 50.34, -0.68 +35.86, 35.00, 49.66, 50.34, -0.69 +35.86, 35.00, 49.65, 50.35, -0.69 +35.86, 35.00, 49.65, 50.35, -0.70 +35.86, 35.00, 49.65, 50.35, -0.71 +35.86, 35.00, 49.64, 50.36, -0.71 +35.86, 35.00, 49.64, 50.36, -0.72 +35.93, 35.00, 47.12, 52.88, -5.77 +35.93, 35.00, 49.58, 50.42, -0.83 +35.93, 35.00, 49.58, 50.42, -0.84 +35.93, 35.00, 49.58, 50.42, -0.85 +35.93, 35.00, 49.57, 50.43, -0.85 +35.99, 35.00, 47.05, 52.95, -5.90 +35.93, 35.00, 52.04, 47.96, 4.08 +35.99, 35.00, 47.04, 52.96, -5.92 +35.99, 35.00, 49.51, 50.49, -0.98 +35.99, 35.00, 49.51, 50.49, -0.99 +35.99, 35.00, 49.50, 50.50, -1.00 +35.99, 35.00, 49.50, 50.50, -1.00 +35.99, 35.00, 49.49, 50.51, -1.01 +35.99, 35.00, 49.49, 50.51, -1.02 +36.12, 35.00, 44.44, 55.56, -11.11 +36.12, 35.00, 49.38, 50.62, -1.23 +36.12, 35.00, 49.38, 50.62, -1.24 +36.12, 35.00, 49.38, 50.62, -1.25 +36.12, 35.00, 49.37, 50.63, -1.26 +36.12, 35.00, 49.37, 50.63, -1.27 +36.12, 35.00, 49.36, 50.64, -1.28 +36.12, 35.00, 49.36, 50.64, -1.28 +35.99, 35.00, 54.40, 45.60, 8.79 +35.99, 35.00, 49.45, 50.55, -1.10 +35.99, 35.00, 49.45, 50.55, -1.11 +35.99, 35.00, 49.44, 50.56, -1.12 +35.99, 35.00, 49.44, 50.56, -1.12 +35.99, 35.00, 49.43, 50.57, -1.13 +35.99, 35.00, 49.43, 50.57, -1.14 +35.99, 35.00, 49.43, 50.57, -1.15 +35.99, 35.00, 49.42, 50.58, -1.15 +35.99, 35.00, 49.42, 50.58, -1.16 +35.99, 35.00, 49.42, 50.58, -1.17 +35.99, 35.00, 49.41, 50.59, -1.17 +35.93, 35.00, 51.93, 48.07, 3.86 +35.93, 35.00, 49.46, 50.54, -1.09 +35.93, 35.00, 49.45, 50.55, -1.10 +35.93, 35.00, 49.45, 50.55, -1.10 +35.93, 35.00, 49.44, 50.56, -1.11 +35.93, 35.00, 49.44, 50.56, -1.12 +35.93, 35.00, 49.44, 50.56, -1.12 +35.93, 35.00, 49.43, 50.57, -1.13 +35.86, 35.00, 51.95, 48.05, 3.90 +35.86, 35.00, 49.48, 50.52, -1.05 +35.86, 35.00, 49.47, 50.53, -1.05 +35.86, 35.00, 49.47, 50.53, -1.06 +35.73, 35.00, 54.51, 45.49, 9.02 +35.73, 35.00, 49.56, 50.44, -0.87 +35.73, 35.00, 49.56, 50.44, -0.88 +35.73, 35.00, 49.56, 50.44, -0.88 +35.66, 35.00, 52.08, 47.92, 4.16 +35.66, 35.00, 49.60, 50.40, -0.79 +35.66, 35.00, 49.60, 50.40, -0.80 +35.66, 35.00, 49.60, 50.40, -0.80 +35.66, 35.00, 49.60, 50.40, -0.81 +35.66, 35.00, 49.59, 50.41, -0.81 +35.66, 35.00, 49.59, 50.41, -0.82 +35.66, 35.00, 49.59, 50.41, -0.82 +35.66, 35.00, 49.59, 50.41, -0.83 +35.66, 35.00, 49.58, 50.42, -0.83 +35.66, 35.00, 49.58, 50.42, -0.84 +35.66, 35.00, 49.58, 50.42, -0.84 +35.66, 35.00, 49.58, 50.42, -0.85 +35.66, 35.00, 49.57, 50.43, -0.85 +35.66, 35.00, 49.57, 50.43, -0.86 +35.66, 35.00, 49.57, 50.43, -0.86 +35.66, 35.00, 49.57, 50.43, -0.87 +35.60, 35.00, 52.09, 47.91, 4.17 +35.60, 35.00, 49.61, 50.39, -0.78 +35.60, 35.00, 49.61, 50.39, -0.78 +35.60, 35.00, 49.61, 50.39, -0.79 +35.60, 35.00, 49.60, 50.40, -0.79 +35.60, 35.00, 49.60, 50.40, -0.80 +35.60, 35.00, 49.60, 50.40, -0.80 +35.60, 35.00, 49.60, 50.40, -0.80 +35.60, 35.00, 49.60, 50.40, -0.81 +35.60, 35.00, 49.59, 50.41, -0.81 +35.60, 35.00, 49.59, 50.41, -0.82 +35.60, 35.00, 49.59, 50.41, -0.82 +35.60, 35.00, 49.59, 50.41, -0.83 +35.60, 35.00, 49.58, 50.42, -0.83 +35.60, 35.00, 49.58, 50.42, -0.84 +35.60, 35.00, 49.58, 50.42, -0.84 +35.46, 35.00, 54.62, 45.38, 9.24 +35.46, 35.00, 49.68, 50.32, -0.65 +35.46, 35.00, 49.67, 50.33, -0.65 +35.46, 35.00, 49.67, 50.33, -0.66 +35.40, 35.00, 52.19, 47.81, 4.38 +35.46, 35.00, 47.20, 52.80, -5.61 +35.40, 35.00, 52.19, 47.81, 4.38 +35.40, 35.00, 49.71, 50.29, -0.57 +35.40, 35.00, 49.71, 50.29, -0.57 +35.40, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 49.71, 50.29, -0.59 +35.40, 35.00, 49.71, 50.29, -0.59 +35.40, 35.00, 49.70, 50.30, -0.59 +35.40, 35.00, 49.70, 50.30, -0.59 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.61 +35.40, 35.00, 49.70, 50.30, -0.61 +35.40, 35.00, 49.69, 50.31, -0.61 +35.33, 35.00, 52.21, 47.79, 4.43 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.53 +35.33, 35.00, 49.74, 50.26, -0.53 +35.33, 35.00, 49.73, 50.27, -0.53 +35.33, 35.00, 49.73, 50.27, -0.53 +35.33, 35.00, 49.73, 50.27, -0.54 +35.33, 35.00, 49.73, 50.27, -0.54 +35.33, 35.00, 49.73, 50.27, -0.54 +35.20, 35.00, 54.77, 45.23, 9.54 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.13, 35.00, 52.34, 47.66, 4.69 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.07, 35.00, 52.39, 47.61, 4.78 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.17 +34.94, 35.00, 54.96, 45.04, 9.92 +34.94, 35.00, 50.02, 49.98, 0.03 +34.94, 35.00, 50.02, 49.98, 0.03 +34.94, 35.00, 50.02, 49.98, 0.03 +34.94, 35.00, 50.02, 49.98, 0.03 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.87, 35.00, 52.54, 47.46, 5.08 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.15 +34.80, 35.00, 52.59, 47.41, 5.19 +34.87, 35.00, 47.60, 52.40, -4.80 +34.87, 35.00, 50.07, 49.93, 0.15 +34.87, 35.00, 50.08, 49.92, 0.15 +34.87, 35.00, 50.08, 49.92, 0.15 +34.87, 35.00, 50.08, 49.92, 0.15 +34.87, 35.00, 50.08, 49.92, 0.15 +34.94, 35.00, 47.56, 52.44, -4.89 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 44.99, 55.01, -10.02 +35.07, 35.00, 49.93, 50.07, -0.14 +35.07, 35.00, 49.93, 50.07, -0.14 +35.13, 35.00, 47.41, 52.59, -5.18 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.25 +35.20, 35.00, 47.35, 52.65, -5.29 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.20, 35.00, 49.82, 50.18, -0.36 +35.20, 35.00, 49.82, 50.18, -0.36 +35.20, 35.00, 49.82, 50.18, -0.36 +35.33, 35.00, 44.78, 55.22, -10.45 +35.20, 35.00, 54.76, 45.24, 9.53 +35.33, 35.00, 44.77, 55.23, -10.45 +35.33, 35.00, 49.72, 50.28, -0.57 +35.33, 35.00, 49.72, 50.28, -0.57 +35.33, 35.00, 49.71, 50.29, -0.57 +35.33, 35.00, 49.71, 50.29, -0.57 +35.33, 35.00, 49.71, 50.29, -0.58 +35.33, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 47.19, 52.81, -5.62 +35.40, 35.00, 49.66, 50.34, -0.68 +35.40, 35.00, 49.66, 50.34, -0.69 +35.40, 35.00, 49.66, 50.34, -0.69 +35.40, 35.00, 49.65, 50.35, -0.69 +35.40, 35.00, 49.65, 50.35, -0.69 +35.40, 35.00, 49.65, 50.35, -0.70 +35.40, 35.00, 49.65, 50.35, -0.70 +35.40, 35.00, 49.65, 50.35, -0.70 +35.46, 35.00, 47.13, 52.87, -5.75 +35.46, 35.00, 49.60, 50.40, -0.81 +35.46, 35.00, 49.59, 50.41, -0.81 +35.46, 35.00, 49.59, 50.41, -0.82 +35.46, 35.00, 49.59, 50.41, -0.82 +35.46, 35.00, 49.59, 50.41, -0.82 +35.46, 35.00, 49.59, 50.41, -0.83 +35.46, 35.00, 49.59, 50.41, -0.83 +35.46, 35.00, 49.58, 50.42, -0.83 +35.46, 35.00, 49.58, 50.42, -0.84 +35.46, 35.00, 49.58, 50.42, -0.84 +35.46, 35.00, 49.58, 50.42, -0.84 +35.46, 35.00, 49.58, 50.42, -0.85 +35.46, 35.00, 49.57, 50.43, -0.85 +35.46, 35.00, 49.57, 50.43, -0.85 +35.46, 35.00, 49.57, 50.43, -0.86 +35.46, 35.00, 49.57, 50.43, -0.86 +35.46, 35.00, 49.57, 50.43, -0.86 +35.46, 35.00, 49.57, 50.43, -0.87 +35.46, 35.00, 49.56, 50.44, -0.87 +35.46, 35.00, 49.56, 50.44, -0.88 +35.40, 35.00, 52.08, 47.92, 4.16 +35.40, 35.00, 49.61, 50.39, -0.78 +35.40, 35.00, 49.61, 50.39, -0.79 +35.40, 35.00, 49.61, 50.39, -0.79 +35.40, 35.00, 49.60, 50.40, -0.79 +35.40, 35.00, 49.60, 50.40, -0.79 +35.40, 35.00, 49.60, 50.40, -0.80 +35.40, 35.00, 49.60, 50.40, -0.80 +35.40, 35.00, 49.60, 50.40, -0.80 +35.40, 35.00, 49.60, 50.40, -0.81 +35.40, 35.00, 49.60, 50.40, -0.81 +35.40, 35.00, 49.59, 50.41, -0.81 +35.33, 35.00, 52.11, 47.89, 4.23 +35.33, 35.00, 49.64, 50.36, -0.72 +35.33, 35.00, 49.64, 50.36, -0.72 +35.33, 35.00, 49.64, 50.36, -0.72 +35.33, 35.00, 49.64, 50.36, -0.73 +35.20, 35.00, 54.68, 45.32, 9.36 +35.20, 35.00, 49.73, 50.27, -0.53 +35.20, 35.00, 49.73, 50.27, -0.53 +35.20, 35.00, 49.73, 50.27, -0.53 +35.20, 35.00, 49.73, 50.27, -0.54 +35.20, 35.00, 49.73, 50.27, -0.54 +35.20, 35.00, 49.73, 50.27, -0.54 +35.13, 35.00, 52.25, 47.75, 4.50 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.45 +35.13, 35.00, 49.78, 50.22, -0.45 +35.07, 35.00, 52.30, 47.70, 4.60 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +34.94, 35.00, 54.87, 45.13, 9.73 +35.07, 35.00, 44.88, 55.12, -10.24 +34.94, 35.00, 54.87, 45.13, 9.73 +34.94, 35.00, 49.92, 50.08, -0.16 +34.94, 35.00, 49.92, 50.08, -0.16 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.87, 35.00, 52.45, 47.55, 4.89 +34.94, 35.00, 47.45, 52.55, -5.09 +34.94, 35.00, 49.93, 50.07, -0.15 +34.87, 35.00, 52.45, 47.55, 4.90 +34.87, 35.00, 49.98, 50.02, -0.05 +34.87, 35.00, 49.98, 50.02, -0.05 +34.87, 35.00, 49.98, 50.02, -0.04 +34.94, 35.00, 47.46, 52.54, -5.09 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +35.07, 35.00, 44.89, 55.11, -10.22 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.13, 35.00, 47.31, 52.69, -5.38 +35.07, 35.00, 52.30, 47.70, 4.61 +35.13, 35.00, 47.31, 52.69, -5.38 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.07, 35.00, 52.30, 47.70, 4.60 +35.13, 35.00, 47.31, 52.69, -5.39 +35.13, 35.00, 49.78, 50.22, -0.45 +35.07, 35.00, 52.30, 47.70, 4.60 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +34.94, 35.00, 54.87, 45.13, 9.74 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.87, 35.00, 52.45, 47.55, 4.90 +34.94, 35.00, 47.46, 52.54, -5.09 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.87, 35.00, 52.45, 47.55, 4.90 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.99, 50.01, -0.03 +34.87, 35.00, 49.99, 50.01, -0.03 +34.80, 35.00, 52.51, 47.49, 5.02 +34.80, 35.00, 50.04, 49.96, 0.07 +34.80, 35.00, 50.04, 49.96, 0.08 +34.80, 35.00, 50.04, 49.96, 0.08 +34.67, 35.00, 55.08, 44.92, 10.16 +34.67, 35.00, 50.14, 49.86, 0.28 +34.67, 35.00, 50.14, 49.86, 0.28 +34.67, 35.00, 50.14, 49.86, 0.28 +34.67, 35.00, 50.14, 49.86, 0.29 +34.67, 35.00, 50.14, 49.86, 0.29 +34.67, 35.00, 50.15, 49.85, 0.29 +34.67, 35.00, 50.15, 49.85, 0.29 +34.67, 35.00, 50.15, 49.85, 0.30 +34.67, 35.00, 50.15, 49.85, 0.30 +34.67, 35.00, 50.15, 49.85, 0.30 +34.67, 35.00, 50.15, 49.85, 0.30 +34.67, 35.00, 50.15, 49.85, 0.31 +34.67, 35.00, 50.15, 49.85, 0.31 +34.61, 35.00, 52.68, 47.32, 5.35 +34.61, 35.00, 50.21, 49.79, 0.41 +34.61, 35.00, 50.21, 49.79, 0.42 +34.61, 35.00, 50.21, 49.79, 0.42 +34.61, 35.00, 50.21, 49.79, 0.42 +34.54, 35.00, 52.73, 47.27, 5.47 +34.54, 35.00, 50.26, 49.74, 0.53 +34.54, 35.00, 50.27, 49.73, 0.53 +34.54, 35.00, 50.27, 49.73, 0.53 +34.54, 35.00, 50.27, 49.73, 0.54 +34.54, 35.00, 50.27, 49.73, 0.54 +34.54, 35.00, 50.27, 49.73, 0.55 +34.54, 35.00, 50.27, 49.73, 0.55 +34.54, 35.00, 50.28, 49.72, 0.55 +34.54, 35.00, 50.28, 49.72, 0.56 +34.41, 35.00, 55.32, 44.68, 10.65 +34.41, 35.00, 50.38, 49.62, 0.76 +34.41, 35.00, 50.38, 49.62, 0.77 +34.41, 35.00, 50.39, 49.61, 0.77 +34.41, 35.00, 50.39, 49.61, 0.78 +34.34, 35.00, 52.91, 47.09, 5.82 +34.34, 35.00, 50.44, 49.56, 0.88 +34.34, 35.00, 50.44, 49.56, 0.89 +34.34, 35.00, 50.45, 49.55, 0.89 +34.34, 35.00, 50.45, 49.55, 0.90 +34.34, 35.00, 50.45, 49.55, 0.90 +34.34, 35.00, 50.45, 49.55, 0.91 +34.34, 35.00, 50.46, 49.54, 0.91 +34.34, 35.00, 50.46, 49.54, 0.92 +34.34, 35.00, 50.46, 49.54, 0.92 +34.34, 35.00, 50.46, 49.54, 0.93 +34.34, 35.00, 50.47, 49.53, 0.93 +34.34, 35.00, 50.47, 49.53, 0.94 +34.34, 35.00, 50.47, 49.53, 0.94 +34.34, 35.00, 50.47, 49.53, 0.95 +34.34, 35.00, 50.48, 49.52, 0.95 +34.34, 35.00, 50.48, 49.52, 0.96 +34.34, 35.00, 50.48, 49.52, 0.96 +34.34, 35.00, 50.48, 49.52, 0.97 +34.28, 35.00, 53.01, 46.99, 6.02 +34.34, 35.00, 48.02, 51.98, -3.97 +34.34, 35.00, 50.49, 49.51, 0.98 +34.34, 35.00, 50.49, 49.51, 0.99 +34.34, 35.00, 50.50, 49.50, 0.99 +34.34, 35.00, 50.50, 49.50, 1.00 +34.34, 35.00, 50.50, 49.50, 1.00 +34.34, 35.00, 50.50, 49.50, 1.01 +34.34, 35.00, 50.51, 49.49, 1.01 +34.34, 35.00, 50.51, 49.49, 1.02 +34.34, 35.00, 50.51, 49.49, 1.02 +34.34, 35.00, 50.51, 49.49, 1.03 +34.34, 35.00, 50.52, 49.48, 1.03 +34.34, 35.00, 50.52, 49.48, 1.04 +34.34, 35.00, 50.52, 49.48, 1.04 +34.41, 35.00, 48.00, 52.00, -4.00 +34.34, 35.00, 53.00, 47.00, 6.00 +34.41, 35.00, 48.01, 51.99, -3.99 +34.41, 35.00, 50.48, 49.52, 0.96 +34.41, 35.00, 50.48, 49.52, 0.97 +34.41, 35.00, 50.49, 49.51, 0.97 +34.41, 35.00, 50.49, 49.51, 0.97 +34.41, 35.00, 50.49, 49.51, 0.98 +34.54, 35.00, 45.45, 54.55, -9.10 +34.54, 35.00, 50.39, 49.61, 0.79 +34.54, 35.00, 50.40, 49.60, 0.79 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.81 +34.54, 35.00, 50.40, 49.60, 0.81 +34.61, 35.00, 47.88, 52.12, -4.23 +34.61, 35.00, 50.36, 49.64, 0.72 +34.54, 35.00, 52.88, 47.12, 5.76 +34.61, 35.00, 47.89, 52.11, -4.22 +34.61, 35.00, 50.36, 49.64, 0.73 +34.61, 35.00, 50.36, 49.64, 0.73 +34.61, 35.00, 50.37, 49.63, 0.73 +34.61, 35.00, 50.37, 49.63, 0.73 +34.61, 35.00, 50.37, 49.63, 0.74 +34.67, 35.00, 47.85, 52.15, -4.30 +34.67, 35.00, 50.32, 49.68, 0.64 +34.67, 35.00, 50.32, 49.68, 0.65 +34.67, 35.00, 50.32, 49.68, 0.65 +34.80, 35.00, 45.28, 54.72, -9.44 +34.80, 35.00, 50.23, 49.77, 0.45 +34.80, 35.00, 50.23, 49.77, 0.45 +34.87, 35.00, 47.71, 52.29, -4.59 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.94, 35.00, 47.66, 52.34, -4.68 +34.94, 35.00, 50.13, 49.87, 0.27 +35.07, 35.00, 45.09, 54.91, -9.82 +35.07, 35.00, 50.03, 49.97, 0.07 +35.13, 35.00, 47.51, 52.49, -4.98 +35.13, 35.00, 49.98, 50.02, -0.03 +35.13, 35.00, 49.98, 50.02, -0.03 +35.13, 35.00, 49.98, 50.02, -0.03 +35.20, 35.00, 47.46, 52.54, -5.08 +35.20, 35.00, 49.93, 50.07, -0.14 +35.20, 35.00, 49.93, 50.07, -0.14 +35.20, 35.00, 49.93, 50.07, -0.14 +35.20, 35.00, 49.93, 50.07, -0.14 +35.33, 35.00, 44.89, 55.11, -10.23 +35.33, 35.00, 49.83, 50.17, -0.34 +35.33, 35.00, 49.83, 50.17, -0.35 +35.33, 35.00, 49.83, 50.17, -0.35 +35.33, 35.00, 49.82, 50.18, -0.35 +35.40, 35.00, 47.30, 52.70, -5.40 +35.40, 35.00, 49.77, 50.23, -0.46 +35.40, 35.00, 49.77, 50.23, -0.46 +35.40, 35.00, 49.77, 50.23, -0.46 +35.40, 35.00, 49.77, 50.23, -0.47 +35.46, 35.00, 47.24, 52.76, -5.51 +35.46, 35.00, 49.71, 50.29, -0.57 +35.46, 35.00, 49.71, 50.29, -0.57 +35.46, 35.00, 49.71, 50.29, -0.58 +35.46, 35.00, 49.71, 50.29, -0.58 +35.46, 35.00, 49.71, 50.29, -0.59 +35.46, 35.00, 49.71, 50.29, -0.59 +35.46, 35.00, 49.70, 50.30, -0.59 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.61 +35.46, 35.00, 49.70, 50.30, -0.61 +35.46, 35.00, 49.69, 50.31, -0.61 +35.46, 35.00, 49.69, 50.31, -0.62 +35.46, 35.00, 49.69, 50.31, -0.62 +35.46, 35.00, 49.69, 50.31, -0.62 +35.46, 35.00, 49.69, 50.31, -0.63 +35.46, 35.00, 49.68, 50.32, -0.63 +35.40, 35.00, 52.20, 47.80, 4.41 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.55 +35.40, 35.00, 49.73, 50.27, -0.55 +35.40, 35.00, 49.72, 50.28, -0.55 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.57 +35.40, 35.00, 49.71, 50.29, -0.57 +35.40, 35.00, 49.71, 50.29, -0.57 +35.33, 35.00, 52.23, 47.77, 4.47 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.49 +35.33, 35.00, 49.76, 50.24, -0.49 +35.33, 35.00, 49.75, 50.25, -0.49 +35.33, 35.00, 49.75, 50.25, -0.49 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.51 +35.33, 35.00, 49.75, 50.25, -0.51 +35.20, 35.00, 54.79, 45.21, 9.57 +35.20, 35.00, 49.84, 50.16, -0.31 +35.20, 35.00, 49.84, 50.16, -0.32 +35.13, 35.00, 52.36, 47.64, 4.73 +35.13, 35.00, 49.89, 50.11, -0.22 +35.13, 35.00, 49.89, 50.11, -0.22 +35.13, 35.00, 49.89, 50.11, -0.22 +35.13, 35.00, 49.89, 50.11, -0.22 +35.07, 35.00, 52.41, 47.59, 4.82 +35.07, 35.00, 49.94, 50.06, -0.12 +35.07, 35.00, 49.94, 50.06, -0.12 +35.07, 35.00, 49.94, 50.06, -0.13 +35.07, 35.00, 49.94, 50.06, -0.13 +34.94, 35.00, 54.98, 45.02, 9.96 +34.94, 35.00, 50.04, 49.96, 0.07 +34.94, 35.00, 50.04, 49.96, 0.07 +34.94, 35.00, 50.04, 49.96, 0.07 +34.87, 35.00, 52.56, 47.44, 5.12 +34.87, 35.00, 50.09, 49.91, 0.17 +34.87, 35.00, 50.09, 49.91, 0.18 +34.87, 35.00, 50.09, 49.91, 0.18 +34.80, 35.00, 52.61, 47.39, 5.22 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.29 +34.80, 35.00, 50.14, 49.86, 0.29 +34.80, 35.00, 50.14, 49.86, 0.29 +34.80, 35.00, 50.15, 49.85, 0.29 +34.80, 35.00, 50.15, 49.85, 0.29 +34.80, 35.00, 50.15, 49.85, 0.29 +34.67, 35.00, 55.19, 44.81, 10.38 +34.67, 35.00, 50.25, 49.75, 0.50 +34.67, 35.00, 50.25, 49.75, 0.50 +34.67, 35.00, 50.25, 49.75, 0.50 +34.67, 35.00, 50.25, 49.75, 0.50 +34.67, 35.00, 50.25, 49.75, 0.51 +34.67, 35.00, 50.25, 49.75, 0.51 +34.67, 35.00, 50.26, 49.74, 0.51 +34.67, 35.00, 50.26, 49.74, 0.51 +34.67, 35.00, 50.26, 49.74, 0.52 +34.67, 35.00, 50.26, 49.74, 0.52 +34.67, 35.00, 50.26, 49.74, 0.52 +34.67, 35.00, 50.26, 49.74, 0.52 +34.67, 35.00, 50.26, 49.74, 0.53 +34.67, 35.00, 50.26, 49.74, 0.53 +34.67, 35.00, 50.27, 49.73, 0.53 +34.67, 35.00, 50.27, 49.73, 0.53 +34.67, 35.00, 50.27, 49.73, 0.53 +34.67, 35.00, 50.27, 49.73, 0.54 +34.67, 35.00, 50.27, 49.73, 0.54 +34.67, 35.00, 50.27, 49.73, 0.54 +34.67, 35.00, 50.27, 49.73, 0.54 +34.67, 35.00, 50.27, 49.73, 0.55 +34.67, 35.00, 50.27, 49.73, 0.55 +34.67, 35.00, 50.28, 49.72, 0.55 +34.67, 35.00, 50.28, 49.72, 0.55 +34.67, 35.00, 50.28, 49.72, 0.56 +34.67, 35.00, 50.28, 49.72, 0.56 +34.80, 35.00, 45.24, 54.76, -9.52 +34.80, 35.00, 50.18, 49.82, 0.36 +34.80, 35.00, 50.18, 49.82, 0.37 +34.80, 35.00, 50.18, 49.82, 0.37 +34.87, 35.00, 47.66, 52.34, -4.67 +34.87, 35.00, 50.14, 49.86, 0.27 +34.87, 35.00, 50.14, 49.86, 0.27 +34.87, 35.00, 50.14, 49.86, 0.27 +34.94, 35.00, 47.62, 52.38, -4.77 +34.94, 35.00, 50.09, 49.91, 0.17 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +35.07, 35.00, 45.05, 54.95, -9.91 +34.94, 35.00, 55.03, 44.97, 10.07 +35.07, 35.00, 45.05, 54.95, -9.91 +35.07, 35.00, 49.99, 50.01, -0.02 +35.07, 35.00, 49.99, 50.01, -0.02 +35.13, 35.00, 47.47, 52.53, -5.06 +35.13, 35.00, 49.94, 50.06, -0.12 +35.13, 35.00, 49.94, 50.06, -0.12 +35.20, 35.00, 47.42, 52.58, -5.17 +35.20, 35.00, 49.89, 50.11, -0.22 +35.20, 35.00, 49.89, 50.11, -0.23 +35.20, 35.00, 49.89, 50.11, -0.23 +35.20, 35.00, 49.89, 50.11, -0.23 +35.20, 35.00, 49.88, 50.12, -0.23 +35.20, 35.00, 49.88, 50.12, -0.23 +35.20, 35.00, 49.88, 50.12, -0.23 +35.20, 35.00, 49.88, 50.12, -0.24 +35.33, 35.00, 44.84, 55.16, -10.32 +35.33, 35.00, 49.78, 50.22, -0.44 +35.33, 35.00, 49.78, 50.22, -0.44 +35.33, 35.00, 49.78, 50.22, -0.44 +35.40, 35.00, 47.26, 52.74, -5.49 +35.40, 35.00, 49.73, 50.27, -0.55 +35.40, 35.00, 49.72, 50.28, -0.55 +35.40, 35.00, 49.72, 50.28, -0.55 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.57 +35.40, 35.00, 49.72, 50.28, -0.57 +35.33, 35.00, 52.24, 47.76, 4.47 +35.33, 35.00, 49.76, 50.24, -0.47 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.49 +35.33, 35.00, 49.76, 50.24, -0.49 +35.33, 35.00, 49.75, 50.25, -0.49 +35.33, 35.00, 49.75, 50.25, -0.49 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.51 +35.33, 35.00, 49.75, 50.25, -0.51 +35.33, 35.00, 49.74, 50.26, -0.51 +35.33, 35.00, 49.74, 50.26, -0.51 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.20, 35.00, 54.78, 45.22, 9.56 +35.20, 35.00, 49.84, 50.16, -0.33 +35.20, 35.00, 49.83, 50.17, -0.33 +35.20, 35.00, 49.83, 50.17, -0.33 +35.20, 35.00, 49.83, 50.17, -0.33 +35.13, 35.00, 52.35, 47.65, 4.71 +35.13, 35.00, 49.88, 50.12, -0.24 +35.20, 35.00, 47.36, 52.64, -5.28 +35.13, 35.00, 52.35, 47.65, 4.70 +35.20, 35.00, 47.36, 52.64, -5.28 +35.20, 35.00, 49.83, 50.17, -0.34 +35.20, 35.00, 49.83, 50.17, -0.34 +35.20, 35.00, 49.83, 50.17, -0.34 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.83, 50.17, -0.35 +35.13, 35.00, 52.35, 47.65, 4.69 +35.13, 35.00, 49.87, 50.13, -0.25 +35.13, 35.00, 49.87, 50.13, -0.25 +35.13, 35.00, 49.87, 50.13, -0.25 +35.07, 35.00, 52.39, 47.61, 4.79 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +34.94, 35.00, 54.96, 45.04, 9.93 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.87, 35.00, 52.54, 47.46, 5.08 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.15 +34.87, 35.00, 50.07, 49.93, 0.15 +34.87, 35.00, 50.07, 49.93, 0.15 +34.80, 35.00, 52.60, 47.40, 5.19 +34.80, 35.00, 50.12, 49.88, 0.25 +34.80, 35.00, 50.13, 49.87, 0.25 +34.80, 35.00, 50.13, 49.87, 0.25 +34.67, 35.00, 55.17, 44.83, 10.34 +34.67, 35.00, 50.23, 49.77, 0.45 +34.67, 35.00, 50.23, 49.77, 0.46 +34.67, 35.00, 50.23, 49.77, 0.46 +34.67, 35.00, 50.23, 49.77, 0.46 +34.67, 35.00, 50.23, 49.77, 0.46 +34.67, 35.00, 50.23, 49.77, 0.47 +34.67, 35.00, 50.23, 49.77, 0.47 +34.61, 35.00, 52.76, 47.24, 5.52 +34.67, 35.00, 47.77, 52.23, -4.47 +34.61, 35.00, 52.76, 47.24, 5.52 +34.61, 35.00, 50.29, 49.71, 0.58 +34.61, 35.00, 50.29, 49.71, 0.58 +34.61, 35.00, 50.29, 49.71, 0.59 +34.61, 35.00, 50.29, 49.71, 0.59 +34.61, 35.00, 50.30, 49.70, 0.59 +34.61, 35.00, 50.30, 49.70, 0.59 +34.61, 35.00, 50.30, 49.70, 0.60 +34.61, 35.00, 50.30, 49.70, 0.60 +34.61, 35.00, 50.30, 49.70, 0.60 +34.61, 35.00, 50.30, 49.70, 0.61 +34.61, 35.00, 50.30, 49.70, 0.61 +34.61, 35.00, 50.31, 49.69, 0.61 +34.61, 35.00, 50.31, 49.69, 0.62 +34.61, 35.00, 50.31, 49.69, 0.62 +34.61, 35.00, 50.31, 49.69, 0.62 +34.61, 35.00, 50.31, 49.69, 0.62 +34.61, 35.00, 50.31, 49.69, 0.63 +34.61, 35.00, 50.31, 49.69, 0.63 +34.61, 35.00, 50.32, 49.68, 0.63 +34.61, 35.00, 50.32, 49.68, 0.64 +34.61, 35.00, 50.32, 49.68, 0.64 +34.61, 35.00, 50.32, 49.68, 0.64 +34.61, 35.00, 50.32, 49.68, 0.64 +34.61, 35.00, 50.32, 49.68, 0.65 +34.61, 35.00, 50.33, 49.67, 0.65 +34.61, 35.00, 50.33, 49.67, 0.65 +34.61, 35.00, 50.33, 49.67, 0.66 +34.67, 35.00, 47.81, 52.19, -4.38 +34.67, 35.00, 50.28, 49.72, 0.56 +34.67, 35.00, 50.28, 49.72, 0.56 +34.67, 35.00, 50.28, 49.72, 0.57 +34.67, 35.00, 50.28, 49.72, 0.57 +34.67, 35.00, 50.29, 49.71, 0.57 +34.67, 35.00, 50.29, 49.71, 0.57 +34.67, 35.00, 50.29, 49.71, 0.58 +34.67, 35.00, 50.29, 49.71, 0.58 +34.67, 35.00, 50.29, 49.71, 0.58 +34.80, 35.00, 45.25, 54.75, -9.50 +34.80, 35.00, 50.19, 49.81, 0.39 +34.80, 35.00, 50.19, 49.81, 0.39 +34.80, 35.00, 50.20, 49.80, 0.39 +34.87, 35.00, 47.67, 52.33, -4.65 +34.87, 35.00, 50.15, 49.85, 0.29 +34.87, 35.00, 50.15, 49.85, 0.29 +34.94, 35.00, 47.63, 52.37, -4.75 +34.94, 35.00, 50.10, 49.90, 0.20 +34.94, 35.00, 50.10, 49.90, 0.20 +35.07, 35.00, 45.06, 54.94, -9.89 +35.07, 35.00, 50.00, 50.00, -0.00 +35.07, 35.00, 50.00, 50.00, -0.00 +35.13, 35.00, 47.48, 52.52, -5.05 +35.13, 35.00, 49.95, 50.05, -0.10 +35.13, 35.00, 49.95, 50.05, -0.10 +35.13, 35.00, 49.95, 50.05, -0.11 +35.13, 35.00, 49.95, 50.05, -0.11 +35.20, 35.00, 47.42, 52.58, -5.15 +35.20, 35.00, 49.90, 50.10, -0.21 +35.20, 35.00, 49.90, 50.10, -0.21 +35.20, 35.00, 49.89, 50.11, -0.21 +35.33, 35.00, 44.85, 55.15, -10.30 +35.33, 35.00, 49.79, 50.21, -0.41 +35.33, 35.00, 49.79, 50.21, -0.42 +35.40, 35.00, 47.27, 52.73, -5.46 +35.40, 35.00, 49.74, 50.26, -0.52 +35.40, 35.00, 49.74, 50.26, -0.52 +35.40, 35.00, 49.74, 50.26, -0.53 +35.40, 35.00, 49.73, 50.27, -0.53 +35.40, 35.00, 49.73, 50.27, -0.53 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.55 +35.46, 35.00, 47.20, 52.80, -5.59 +35.40, 35.00, 52.20, 47.80, 4.39 +35.40, 35.00, 49.72, 50.28, -0.55 +35.40, 35.00, 49.72, 50.28, -0.56 +35.46, 35.00, 47.20, 52.80, -5.60 +35.46, 35.00, 49.67, 50.33, -0.66 +35.46, 35.00, 49.67, 50.33, -0.67 +35.40, 35.00, 52.19, 47.81, 4.37 +35.40, 35.00, 49.71, 50.29, -0.57 +35.46, 35.00, 47.19, 52.81, -5.62 +35.40, 35.00, 52.18, 47.82, 4.36 +35.40, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 49.71, 50.29, -0.59 +35.40, 35.00, 49.71, 50.29, -0.59 +35.40, 35.00, 49.70, 50.30, -0.59 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.33, 35.00, 52.22, 47.78, 4.44 +35.33, 35.00, 49.74, 50.26, -0.51 +35.33, 35.00, 49.74, 50.26, -0.51 +35.33, 35.00, 49.74, 50.26, -0.52 +35.20, 35.00, 54.78, 45.22, 9.57 +35.20, 35.00, 49.84, 50.16, -0.32 +35.20, 35.00, 49.84, 50.16, -0.32 +35.20, 35.00, 49.84, 50.16, -0.32 +35.13, 35.00, 52.36, 47.64, 4.72 +35.13, 35.00, 49.89, 50.11, -0.23 +35.13, 35.00, 49.89, 50.11, -0.23 +35.13, 35.00, 49.89, 50.11, -0.23 +35.07, 35.00, 52.41, 47.59, 4.81 +35.07, 35.00, 49.93, 50.07, -0.13 +35.07, 35.00, 49.93, 50.07, -0.13 +35.07, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 54.98, 45.02, 9.95 +34.94, 35.00, 50.03, 49.97, 0.07 +34.94, 35.00, 50.03, 49.97, 0.07 +34.94, 35.00, 50.03, 49.97, 0.07 +34.94, 35.00, 50.03, 49.97, 0.07 +34.87, 35.00, 52.56, 47.44, 5.11 +34.87, 35.00, 50.08, 49.92, 0.17 +34.87, 35.00, 50.08, 49.92, 0.17 +34.87, 35.00, 50.09, 49.91, 0.17 +34.80, 35.00, 52.61, 47.39, 5.22 +34.80, 35.00, 50.14, 49.86, 0.27 +34.80, 35.00, 50.14, 49.86, 0.27 +34.67, 35.00, 55.18, 44.82, 10.36 +34.67, 35.00, 50.24, 49.76, 0.48 +34.67, 35.00, 50.24, 49.76, 0.48 +34.67, 35.00, 50.24, 49.76, 0.48 +34.67, 35.00, 50.24, 49.76, 0.48 +34.61, 35.00, 52.76, 47.24, 5.53 +34.61, 35.00, 50.29, 49.71, 0.59 +34.61, 35.00, 50.30, 49.70, 0.59 +34.61, 35.00, 50.30, 49.70, 0.59 +34.54, 35.00, 52.82, 47.18, 5.64 +34.54, 35.00, 50.35, 49.65, 0.70 +34.54, 35.00, 50.35, 49.65, 0.70 +34.54, 35.00, 50.35, 49.65, 0.71 +34.41, 35.00, 55.40, 44.60, 10.80 +34.54, 35.00, 45.41, 54.59, -9.17 +34.41, 35.00, 55.40, 44.60, 10.81 +34.41, 35.00, 50.46, 49.54, 0.92 +34.41, 35.00, 50.46, 49.54, 0.93 +34.41, 35.00, 50.47, 49.53, 0.93 +34.41, 35.00, 50.47, 49.53, 0.94 +34.41, 35.00, 50.47, 49.53, 0.94 +34.41, 35.00, 50.47, 49.53, 0.94 +34.34, 35.00, 53.00, 47.00, 5.99 +34.34, 35.00, 50.53, 49.47, 1.05 +34.34, 35.00, 50.53, 49.47, 1.06 +34.34, 35.00, 50.53, 49.47, 1.06 +34.34, 35.00, 50.53, 49.47, 1.07 +34.34, 35.00, 50.54, 49.46, 1.07 +34.41, 35.00, 48.02, 51.98, -3.97 +34.41, 35.00, 50.49, 49.51, 0.98 +34.41, 35.00, 50.49, 49.51, 0.99 +34.41, 35.00, 50.50, 49.50, 0.99 +34.54, 35.00, 45.45, 54.55, -9.09 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.81 +34.54, 35.00, 50.41, 49.59, 0.81 +34.61, 35.00, 47.89, 52.11, -4.23 +34.61, 35.00, 50.36, 49.64, 0.72 +34.61, 35.00, 50.36, 49.64, 0.72 +34.61, 35.00, 50.36, 49.64, 0.72 +34.61, 35.00, 50.36, 49.64, 0.73 +34.61, 35.00, 50.36, 49.64, 0.73 +34.61, 35.00, 50.37, 49.63, 0.73 +34.61, 35.00, 50.37, 49.63, 0.74 +34.67, 35.00, 47.85, 52.15, -4.30 +34.67, 35.00, 50.32, 49.68, 0.64 +34.67, 35.00, 50.32, 49.68, 0.64 +34.67, 35.00, 50.32, 49.68, 0.65 +34.80, 35.00, 45.28, 54.72, -9.44 +34.87, 35.00, 47.70, 52.30, -4.59 +34.87, 35.00, 50.18, 49.82, 0.35 +34.87, 35.00, 50.18, 49.82, 0.35 +34.87, 35.00, 50.18, 49.82, 0.36 +34.94, 35.00, 47.66, 52.34, -4.69 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +35.07, 35.00, 45.09, 54.91, -9.82 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.13, 35.00, 47.51, 52.49, -4.98 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.07, 35.00, 52.50, 47.50, 5.00 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +34.94, 35.00, 55.07, 44.93, 10.13 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +35.07, 35.00, 45.08, 54.92, -9.84 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +34.94, 35.00, 55.07, 44.93, 10.13 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.87, 35.00, 52.65, 47.35, 5.29 +34.87, 35.00, 50.17, 49.83, 0.35 +34.94, 35.00, 47.65, 52.35, -4.69 +34.87, 35.00, 52.65, 47.35, 5.29 +34.94, 35.00, 47.65, 52.35, -4.69 +34.94, 35.00, 50.13, 49.87, 0.25 +34.94, 35.00, 50.13, 49.87, 0.25 +34.94, 35.00, 50.13, 49.87, 0.25 +34.94, 35.00, 50.13, 49.87, 0.25 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +35.07, 35.00, 45.09, 54.91, -9.83 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.13, 35.00, 47.51, 52.49, -4.98 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.05 +35.13, 35.00, 49.98, 50.02, -0.05 +35.13, 35.00, 49.98, 50.02, -0.05 +35.20, 35.00, 47.45, 52.55, -5.09 +35.20, 35.00, 49.93, 50.07, -0.15 +35.20, 35.00, 49.92, 50.08, -0.15 +35.33, 35.00, 44.88, 55.12, -10.24 +35.33, 35.00, 49.82, 50.18, -0.35 +35.33, 35.00, 49.82, 50.18, -0.36 +35.33, 35.00, 49.82, 50.18, -0.36 +35.40, 35.00, 47.30, 52.70, -5.40 +35.40, 35.00, 49.77, 50.23, -0.46 +35.40, 35.00, 49.77, 50.23, -0.47 +35.40, 35.00, 49.77, 50.23, -0.47 +35.40, 35.00, 49.76, 50.24, -0.47 +35.40, 35.00, 49.76, 50.24, -0.48 +35.40, 35.00, 49.76, 50.24, -0.48 +35.40, 35.00, 49.76, 50.24, -0.48 +35.40, 35.00, 49.76, 50.24, -0.48 +35.46, 35.00, 47.23, 52.77, -5.53 +35.46, 35.00, 49.70, 50.30, -0.59 +35.46, 35.00, 49.70, 50.30, -0.59 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.61 +35.60, 35.00, 44.65, 55.35, -10.70 +35.60, 35.00, 49.59, 50.41, -0.81 +35.60, 35.00, 49.59, 50.41, -0.82 +35.60, 35.00, 49.59, 50.41, -0.82 +35.60, 35.00, 49.59, 50.41, -0.83 +35.60, 35.00, 49.58, 50.42, -0.83 +35.60, 35.00, 49.58, 50.42, -0.84 +35.60, 35.00, 49.58, 50.42, -0.84 +35.60, 35.00, 49.58, 50.42, -0.85 +35.60, 35.00, 49.58, 50.42, -0.85 +35.60, 35.00, 49.57, 50.43, -0.85 +35.60, 35.00, 49.57, 50.43, -0.86 +35.60, 35.00, 49.57, 50.43, -0.86 +35.60, 35.00, 49.57, 50.43, -0.87 +35.60, 35.00, 49.56, 50.44, -0.87 +35.60, 35.00, 49.56, 50.44, -0.88 +35.60, 35.00, 49.56, 50.44, -0.88 +35.46, 35.00, 54.60, 45.40, 9.20 +35.46, 35.00, 49.65, 50.35, -0.69 +35.46, 35.00, 49.65, 50.35, -0.69 +35.46, 35.00, 49.65, 50.35, -0.70 +35.46, 35.00, 49.65, 50.35, -0.70 +35.40, 35.00, 52.17, 47.83, 4.34 +35.40, 35.00, 49.70, 50.30, -0.61 +35.40, 35.00, 49.69, 50.31, -0.61 +35.40, 35.00, 49.69, 50.31, -0.61 +35.40, 35.00, 49.69, 50.31, -0.62 +35.40, 0.00, 25.00, 75.00, -50.00 +35.40, 0.00, 25.00, 75.00, -50.00 +35.40, 0.00, 25.00, 75.00, -50.00 +35.33, 0.00, 25.43, 74.57, -49.14 +35.33, 0.00, 25.00, 75.00, -50.00 +35.33, 0.00, 25.00, 75.00, -50.00 +35.20, 0.00, 27.61, 72.39, -44.79 +35.20, 0.00, 25.00, 75.00, -50.00 +35.13, 0.00, 25.00, 75.00, -50.00 +35.13, 0.00, 25.00, 75.00, -50.00 +35.07, 0.00, 25.00, 75.00, -50.00 +34.94, 0.00, 27.15, 72.85, -45.71 +34.87, 0.00, 25.00, 75.00, -50.00 +34.67, 0.00, 29.55, 70.45, -40.89 +34.61, 0.00, 25.00, 75.00, -50.00 +34.54, 0.00, 25.00, 75.00, -50.00 +34.34, 0.00, 29.41, 70.59, -41.17 +34.28, 0.00, 25.00, 75.00, -50.00 +34.08, 0.00, 29.36, 70.64, -41.29 +33.88, 0.00, 29.38, 70.62, -41.25 +33.75, 0.00, 26.88, 73.12, -46.25 +33.55, 0.00, 29.37, 70.63, -41.26 +33.35, 0.00, 29.39, 70.61, -41.21 +33.09, 0.00, 31.94, 68.06, -36.12 +32.83, 0.00, 32.01, 67.99, -35.97 +32.70, 0.00, 27.05, 72.95, -45.91 +32.43, 0.00, 32.07, 67.93, -35.87 +32.17, 0.00, 32.14, 67.86, -35.71 +31.77, 0.00, 37.27, 62.73, -25.47 +31.64, 0.00, 27.36, 72.64, -45.28 +31.25, 0.00, 37.43, 62.57, -25.15 +30.98, 0.00, 32.56, 67.44, -34.87 +30.65, 0.00, 35.17, 64.83, -29.67 +30.32, 0.00, 35.30, 64.70, -29.40 +29.93, 0.00, 37.96, 62.04, -24.09 +29.60, 0.00, 35.62, 64.38, -28.76 +29.27, 0.00, 35.76, 64.24, -28.48 +28.81, 0.00, 40.94, 59.06, -18.12 +28.48, 0.00, 36.14, 63.86, -27.73 +28.02, 0.00, 41.32, 58.68, -17.36 +27.69, 0.00, 36.52, 63.48, -26.96 +27.22, 0.00, 41.71, 58.29, -16.58 +26.76, 0.00, 41.96, 58.04, -16.09 +26.37, 0.00, 39.68, 60.32, -20.64 +25.91, 0.00, 42.40, 57.60, -15.20 +25.38, 0.00, 45.17, 54.83, -9.65 +24.92, 0.00, 42.95, 57.05, -14.09 +24.52, 0.00, 40.69, 59.31, -18.63 +23.99, 0.00, 45.94, 54.06, -8.13 +23.53, 0.00, 43.72, 56.28, -12.55 +23.01, 0.00, 46.50, 53.50, -6.99 +22.48, 0.00, 46.82, 53.18, -6.37 +21.95, 0.00, 47.13, 52.87, -5.74 +21.42, 0.00, 47.44, 52.56, -5.11 +20.90, 0.00, 47.76, 52.24, -4.48 +20.30, 0.00, 50.60, 49.40, 1.20 +19.78, 0.00, 48.45, 51.55, -3.10 +19.12, 0.00, 53.82, 46.18, 7.63 +18.59, 0.00, 49.20, 50.80, -1.60 +18.06, 0.00, 49.53, 50.47, -0.95 +17.47, 0.00, 52.38, 47.62, 4.76 +16.87, 0.00, 52.76, 47.24, 5.52 +16.35, 0.00, 50.62, 49.38, 1.24 +15.69, 0.00, 56.00, 44.00, 12.00 +15.10, 0.00, 53.92, 46.08, 7.84 +14.57, 0.00, 51.79, 48.21, 3.57 +13.97, 0.00, 54.65, 45.35, 9.30 +13.45, 0.00, 52.52, 47.48, 5.05 +12.79, 0.00, 57.92, 42.08, 15.83 +12.19, 0.00, 55.84, 44.16, 11.68 +11.60, 0.00, 56.24, 43.76, 12.49 +10.94, 0.00, 59.17, 40.83, 18.34 +10.35, 0.00, 57.10, 42.90, 14.21 +9.76, 0.00, 57.51, 42.49, 15.02 +9.10, 0.00, 60.44, 39.56, 20.89 +8.50, 0.00, 58.38, 41.62, 16.77 +7.91, 0.00, 58.80, 41.20, 17.60 +7.25, 0.00, 61.74, 38.26, 23.48 +6.66, 0.00, 59.69, 40.31, 19.37 +6.06, 0.00, 60.11, 39.89, 20.22 +5.41, 0.00, 63.06, 36.94, 26.11 +4.88, 0.00, 58.49, 41.51, 16.98 +4.28, 0.00, 61.39, 38.61, 22.78 +3.69, 0.00, 61.82, 38.18, 23.64 +3.16, 0.00, 59.73, 40.27, 19.47 +2.64, 0.00, 60.12, 39.88, 20.24 +1.98, 0.00, 65.55, 34.45, 31.10 +1.58, 0.00, 55.95, 44.05, 11.90 +1.05, 0.00, 61.29, 38.71, 22.57 +0.53, 0.00, 61.68, 38.32, 23.36 +0.00, 0.00, 62.08, 37.92, 24.15 +-0.46, 0.00, 59.95, 40.05, 19.90 +-0.99, 0.00, 62.82, 37.18, 25.65 +-1.52, 0.00, 63.22, 36.78, 26.45 +-1.98, 0.00, 61.11, 38.89, 22.21 +-2.50, 0.00, 63.98, 36.02, 27.97 +-3.03, 0.00, 64.39, 35.61, 28.78 +-3.43, 0.00, 59.76, 40.24, 19.51 +-3.96, 0.00, 65.11, 34.89, 30.22 +-4.42, 0.00, 63.00, 37.00, 26.00 +-4.88, 0.00, 63.36, 36.64, 26.73 +-5.27, 0.00, 61.21, 38.79, 22.42 +-5.73, 0.00, 64.05, 35.95, 28.10 +-6.20, 0.00, 64.42, 35.58, 28.84 +-6.59, 0.00, 62.27, 37.73, 24.54 +-7.05, 0.00, 65.11, 34.89, 30.22 +-7.38, 0.00, 60.44, 39.56, 20.89 +-7.78, 0.00, 63.24, 36.76, 26.48 +-8.11, 0.00, 61.05, 38.95, 22.09 +-8.44, 0.00, 61.33, 38.67, 22.65 +-8.83, 0.00, 64.13, 35.87, 28.25 +-9.16, 0.00, 61.94, 38.06, 23.87 +-9.49, 0.00, 62.22, 37.78, 24.44 +-9.76, 0.00, 59.98, 40.02, 19.96 +-10.15, 0.00, 65.26, 34.74, 30.52 +-10.48, 0.00, 63.07, 36.93, 26.15 +-10.74, 0.00, 60.84, 39.16, 21.68 +-11.01, 0.00, 61.08, 38.92, 22.16 +-11.27, 0.00, 61.32, 38.68, 22.64 +-11.54, 0.00, 61.56, 38.44, 23.12 +-11.80, 0.00, 61.80, 38.20, 23.61 +-12.00, 0.00, 59.52, 40.48, 19.05 +-12.26, 0.00, 62.24, 37.76, 24.48 +-12.39, 0.00, 57.44, 42.56, 14.88 +-12.59, 0.00, 60.11, 39.89, 20.22 +-12.85, 0.00, 62.83, 37.17, 25.65 +-13.05, 0.00, 60.55, 39.45, 21.10 +-13.18, 0.00, 58.23, 41.77, 16.46 +-13.38, 0.00, 60.90, 39.10, 21.80 +-13.58, 0.00, 61.10, 38.90, 22.20 +-13.65, 0.00, 56.26, 43.74, 12.51 +-13.84, 0.00, 61.40, 38.60, 22.80 +-13.91, 0.00, 56.56, 43.44, 13.11 +-14.11, 0.00, 61.70, 38.30, 23.40 +-14.17, 0.00, 56.86, 43.14, 13.72 +-14.24, 0.00, 56.96, 43.04, 13.93 +-14.44, 0.00, 62.11, 37.89, 24.22 +-14.50, 0.00, 57.27, 42.73, 14.54 +-14.63, 0.00, 59.90, 40.10, 19.79 +-14.70, 0.00, 57.53, 42.47, 15.06 +-14.77, 0.00, 57.63, 42.37, 15.27 +-14.90, 0.00, 60.26, 39.74, 20.52 +-14.90, 0.00, 55.37, 44.63, 10.74 +-14.90, 0.00, 55.43, 44.57, 10.86 +-14.96, 0.00, 58.00, 42.00, 16.01 +-15.03, 0.00, 58.11, 41.89, 16.22 +-15.03, 0.00, 55.70, 44.30, 11.39 +-15.03, 0.00, 55.75, 44.25, 11.50 +-15.03, 0.00, 55.81, 44.19, 11.62 +-15.16, 0.00, 60.91, 39.09, 21.82 +-15.16, 0.00, 56.02, 43.98, 12.04 +-15.03, 0.00, 51.03, 48.97, 2.07 +-15.16, 0.00, 61.08, 38.92, 22.16 +-15.16, 0.00, 56.19, 43.81, 12.38 +-15.03, 0.00, 51.20, 48.80, 2.41 +-15.03, 0.00, 56.20, 43.80, 12.41 +-15.03, 0.00, 56.26, 43.74, 12.52 +-14.96, 0.00, 53.80, 46.20, 7.59 +-14.96, 0.00, 56.32, 43.68, 12.65 +-14.96, 0.00, 56.38, 43.62, 12.76 +-14.90, 0.00, 53.91, 46.09, 7.83 +-14.90, 0.00, 56.44, 43.56, 12.88 +-14.77, 0.00, 51.45, 48.55, 2.91 +-14.77, 0.00, 56.45, 43.55, 12.91 +-14.70, 0.00, 53.99, 46.01, 7.98 +-14.63, 0.00, 53.99, 46.01, 7.99 +-14.50, 0.00, 51.48, 48.52, 2.95 +-14.44, 0.00, 53.95, 46.05, 7.91 +-14.37, 0.00, 53.96, 46.04, 7.92 +-14.24, 0.00, 51.44, 48.56, 2.88 +-14.24, 0.00, 56.44, 43.56, 12.88 +-14.17, 0.00, 53.97, 46.03, 7.94 +-13.97, 0.00, 48.93, 51.07, -2.14 +-13.91, 0.00, 53.88, 46.12, 7.75 +-13.84, 0.00, 53.88, 46.12, 7.76 +-13.71, 0.00, 51.36, 48.64, 2.72 +-13.65, 0.00, 53.83, 46.17, 7.67 +-13.58, 0.00, 53.83, 46.17, 7.67 +-13.45, 0.00, 51.31, 48.69, 2.63 +-13.32, 0.00, 51.27, 48.73, 2.53 +-13.18, 0.00, 51.22, 48.78, 2.43 +-13.05, 0.00, 51.17, 48.83, 2.33 +-12.92, 0.00, 51.12, 48.88, 2.23 +-12.79, 0.00, 51.06, 48.94, 2.13 +-12.66, 0.00, 51.01, 48.99, 2.03 +-12.52, 0.00, 50.96, 49.04, 1.92 +-12.39, 0.00, 50.91, 49.09, 1.82 +-12.26, 0.00, 50.86, 49.14, 1.71 +-12.13, 0.00, 50.80, 49.20, 1.60 +-12.06, 0.00, 53.27, 46.73, 6.54 +-11.87, 0.00, 48.22, 51.78, -3.56 +-11.73, 0.00, 50.64, 49.36, 1.28 +-11.60, 0.00, 50.58, 49.42, 1.17 +-11.54, 0.00, 53.05, 46.95, 6.10 +-11.34, 0.00, 48.00, 52.00, -4.00 +-11.27, 0.00, 52.94, 47.06, 5.87 +-11.07, 0.00, 47.89, 52.11, -4.23 +-11.01, 0.00, 52.82, 47.18, 5.64 +-10.81, 0.00, 47.77, 52.23, -4.46 +-10.68, 0.00, 50.18, 49.82, 0.37 +-10.55, 0.00, 50.12, 49.88, 0.25 +-10.42, 0.00, 50.06, 49.94, 0.13 +-10.28, 0.00, 50.00, 50.00, 0.01 +-10.15, 0.00, 49.94, 50.06, -0.11 +-10.02, 0.00, 49.88, 50.12, -0.24 +-9.89, 0.00, 49.82, 50.18, -0.36 +-9.69, 0.00, 47.24, 52.76, -5.53 +-9.62, 0.00, 52.17, 47.83, 4.33 +-9.43, 0.00, 47.11, 52.89, -5.78 +-9.23, 0.00, 47.00, 53.00, -6.01 +-9.16, 0.00, 51.92, 48.08, 3.85 +-8.96, 0.00, 46.87, 53.13, -6.27 +-8.90, 0.00, 51.79, 48.21, 3.59 +-8.70, 0.00, 46.73, 53.27, -6.53 +-8.64, 0.00, 51.66, 48.34, 3.32 +-8.44, 0.00, 46.60, 53.40, -6.80 +-8.31, 0.00, 49.00, 51.00, -1.99 +-8.17, 0.00, 48.94, 51.06, -2.13 +-8.04, 0.00, 48.87, 51.13, -2.26 +-7.91, 0.00, 48.80, 51.20, -2.40 +-7.78, 0.00, 48.73, 51.27, -2.54 +-7.58, 0.00, 46.14, 53.86, -7.73 +-7.51, 0.00, 51.06, 48.94, 2.12 +-7.32, 0.00, 46.00, 54.00, -8.01 +-7.25, 0.00, 50.92, 49.08, 1.83 +-7.05, 0.00, 45.85, 54.15, -8.30 +-6.99, 0.00, 50.77, 49.23, 1.54 +-6.79, 0.00, 45.70, 54.30, -8.59 +-6.72, 0.00, 50.62, 49.38, 1.25 +-6.59, 0.00, 48.08, 51.92, -3.84 +-6.46, 0.00, 48.00, 52.00, -3.99 +-6.33, 0.00, 47.93, 52.07, -4.14 +-6.20, 0.00, 47.85, 52.15, -4.29 +-6.06, 0.00, 47.78, 52.22, -4.45 +-6.00, 0.00, 50.22, 49.78, 0.44 +-5.80, 0.00, 45.15, 54.85, -9.70 +-5.73, 0.00, 50.07, 49.93, 0.13 +-5.54, 0.00, 45.00, 55.00, -10.01 +-5.47, 0.00, 49.91, 50.09, -0.18 +-5.41, 0.00, 49.88, 50.12, -0.24 +-5.27, 0.00, 47.33, 52.67, -5.34 +-5.21, 0.00, 49.77, 50.23, -0.45 +-5.14, 0.00, 49.74, 50.26, -0.51 +-4.94, 0.00, 44.67, 55.33, -10.66 +-4.94, 0.00, 52.10, 47.90, 4.21 +-4.75, 0.00, 44.56, 55.44, -10.89 +-4.68, 0.00, 49.47, 50.53, -1.06 +-4.61, 0.00, 49.44, 50.56, -1.13 +-4.48, 0.00, 46.88, 53.12, -6.23 +-4.42, 0.00, 49.32, 50.68, -1.36 +-4.35, 0.00, 49.29, 50.71, -1.42 +-4.22, 0.00, 46.73, 53.27, -6.53 +-4.15, 0.00, 49.17, 50.83, -1.66 +-4.09, 0.00, 49.14, 50.86, -1.72 +-3.96, 0.00, 46.58, 53.42, -6.84 +-3.89, 0.00, 49.02, 50.98, -1.96 +-3.82, 0.00, 48.98, 51.02, -2.03 +-3.82, 0.00, 51.47, 48.53, 2.94 +-3.69, 0.00, 46.44, 53.56, -7.12 +-3.63, 0.00, 48.88, 51.12, -2.25 +-3.56, 0.00, 48.84, 51.16, -2.32 +-3.43, 0.00, 46.28, 53.72, -7.43 +-3.43, 0.00, 51.24, 48.76, 2.48 +-3.36, 0.00, 48.73, 51.27, -2.54 +-3.30, 0.00, 48.69, 51.31, -2.61 +-3.30, 0.00, 51.18, 48.82, 2.36 +-3.16, 0.00, 46.15, 53.85, -7.71 +-3.16, 0.00, 51.10, 48.90, 2.21 +-3.10, 0.00, 48.59, 51.41, -2.81 +-3.10, 0.00, 51.08, 48.92, 2.15 +-3.03, 0.00, 48.57, 51.43, -2.87 +-3.03, 0.00, 51.05, 48.95, 2.10 +-2.90, 0.00, 46.02, 53.98, -7.96 +-2.90, 0.00, 50.97, 49.03, 1.95 +-2.90, 0.00, 50.98, 49.02, 1.97 +-2.83, 0.00, 48.47, 51.53, -3.05 +-2.83, 0.00, 50.96, 49.04, 1.91 +-2.83, 0.00, 50.97, 49.03, 1.93 +-2.77, 0.00, 48.46, 51.54, -3.09 +-2.77, 0.00, 50.94, 49.06, 1.88 +-2.77, 0.00, 50.95, 49.05, 1.90 +-2.64, 0.00, 45.92, 54.08, -8.17 +-2.64, 0.00, 50.87, 49.13, 1.74 +-2.64, 0.00, 50.88, 49.12, 1.76 +-2.64, 0.00, 50.89, 49.11, 1.78 +-2.57, 0.00, 48.38, 51.62, -3.25 +-2.57, 0.00, 50.86, 49.14, 1.72 +-2.57, 0.00, 50.87, 49.13, 1.74 +-2.57, 0.00, 50.88, 49.12, 1.76 +-2.57, 0.00, 50.89, 49.11, 1.78 +-2.57, 0.00, 50.90, 49.10, 1.79 +-2.57, 0.00, 50.91, 49.09, 1.81 +-2.50, 0.00, 48.39, 51.61, -3.21 +-2.50, 0.00, 50.88, 49.12, 1.75 +-2.57, 0.00, 53.41, 46.59, 6.81 +-2.57, 0.00, 50.94, 49.06, 1.89 +-2.57, 0.00, 50.95, 49.05, 1.91 +-2.57, 0.00, 50.96, 49.04, 1.93 +-2.57, 0.00, 50.97, 49.03, 1.95 +-2.57, 0.00, 50.98, 49.02, 1.97 +-2.57, 0.00, 50.99, 49.01, 1.99 +-2.57, 0.00, 51.00, 49.00, 2.01 +-2.57, 0.00, 51.01, 48.99, 2.02 +-2.57, 0.00, 51.02, 48.98, 2.04 +-2.57, 0.00, 51.03, 48.97, 2.06 +-2.57, 0.00, 51.04, 48.96, 2.08 +-2.64, 0.00, 53.57, 46.43, 7.15 +-2.64, 0.00, 51.11, 48.89, 2.22 +-2.64, 0.00, 51.12, 48.88, 2.24 +-2.64, 0.00, 51.13, 48.87, 2.26 +-2.64, 0.00, 51.14, 48.86, 2.28 +-2.77, 0.00, 56.19, 43.81, 12.39 +-2.77, 0.00, 51.26, 48.74, 2.52 +-2.77, 0.00, 51.27, 48.73, 2.54 +-2.77, 0.00, 51.28, 48.72, 2.56 +-2.83, 0.00, 53.81, 46.19, 7.63 +-2.83, 0.00, 51.35, 48.65, 2.70 +-2.83, 0.00, 51.36, 48.64, 2.72 +-2.83, 0.00, 51.37, 48.63, 2.75 +-2.83, 0.00, 51.38, 48.62, 2.77 +-2.90, 0.00, 53.92, 46.08, 7.83 +-2.90, 0.00, 51.45, 48.55, 2.91 +-2.90, 0.00, 51.47, 48.53, 2.93 +-3.03, 0.00, 56.52, 43.48, 13.04 +-3.03, 0.00, 51.59, 48.41, 3.17 +-3.03, 0.00, 51.60, 48.40, 3.20 +-3.03, 0.00, 51.61, 48.39, 3.22 +-3.10, 0.00, 54.14, 45.86, 8.29 +-3.10, 0.00, 51.68, 48.32, 3.36 +-3.16, 0.00, 54.22, 45.78, 8.43 +-3.16, 0.00, 51.76, 48.24, 3.51 +-3.16, 0.00, 51.77, 48.23, 3.53 +-3.16, 0.00, 51.78, 48.22, 3.56 +-3.16, 0.00, 51.79, 48.21, 3.58 +-3.30, 0.00, 56.85, 43.15, 13.69 +-3.30, 0.00, 51.91, 48.09, 3.83 +-3.30, 0.00, 51.93, 48.07, 3.85 +-3.30, 0.00, 51.94, 48.06, 3.88 +-3.30, 0.00, 51.95, 48.05, 3.90 +-3.36, 0.00, 54.49, 45.51, 8.97 +-3.36, 0.00, 52.03, 47.97, 4.05 +-3.43, 0.00, 54.56, 45.44, 9.12 +-3.43, 0.00, 52.10, 47.90, 4.20 +-3.43, 0.00, 52.11, 47.89, 4.23 +-3.56, 0.00, 57.17, 42.83, 14.34 +-3.56, 0.00, 52.24, 47.76, 4.48 +-3.56, 0.00, 52.25, 47.75, 4.51 +-3.56, 0.00, 52.27, 47.73, 4.53 +-3.63, 0.00, 54.80, 45.20, 9.60 +-3.63, 0.00, 52.34, 47.66, 4.69 +-3.63, 0.00, 52.36, 47.64, 4.71 +-3.63, 0.00, 52.37, 47.63, 4.74 +-3.63, 0.00, 52.38, 47.62, 4.77 +-3.69, 0.00, 54.92, 45.08, 9.84 +-3.69, 0.00, 52.46, 47.54, 4.92 +-3.69, 0.00, 52.48, 47.52, 4.95 +-3.69, 0.00, 52.49, 47.51, 4.98 +-3.69, 0.00, 52.50, 47.50, 5.01 +-3.82, 0.00, 57.56, 42.44, 15.12 +-3.82, 0.00, 52.63, 47.37, 5.26 +-3.82, 0.00, 52.64, 47.36, 5.29 +-3.82, 0.00, 52.66, 47.34, 5.32 +-3.82, 0.00, 52.67, 47.33, 5.35 +-3.82, 0.00, 52.69, 47.31, 5.38 +-3.89, 0.00, 55.22, 44.78, 10.45 +-3.89, 0.00, 52.77, 47.23, 5.53 +-3.89, 0.00, 52.78, 47.22, 5.56 +-3.89, 0.00, 52.80, 47.20, 5.59 +-3.89, 0.00, 52.81, 47.19, 5.62 +-3.89, 0.00, 52.82, 47.18, 5.65 +-3.89, 0.00, 52.84, 47.16, 5.68 +-3.89, 0.00, 52.85, 47.15, 5.71 +-3.89, 0.00, 52.87, 47.13, 5.74 +-3.89, 0.00, 52.88, 47.12, 5.77 +-3.89, 0.00, 52.90, 47.10, 5.79 +-3.89, 0.00, 52.91, 47.09, 5.82 +-3.96, 0.00, 55.45, 44.55, 10.90 +-3.96, 0.00, 52.99, 47.01, 5.98 +-3.96, 0.00, 53.01, 46.99, 6.01 +-3.96, 0.00, 53.02, 46.98, 6.04 +-3.96, 0.00, 53.04, 46.96, 6.07 +-3.96, 0.00, 53.05, 46.95, 6.10 +-3.96, 0.00, 53.07, 46.93, 6.13 +-3.96, 0.00, 53.08, 46.92, 6.16 +-3.96, 0.00, 53.10, 46.90, 6.19 +-3.96, 0.00, 53.11, 46.89, 6.22 +-3.89, 0.00, 50.60, 49.40, 1.21 +-3.89, 0.00, 53.09, 46.91, 6.18 +-3.89, 0.00, 53.10, 46.90, 6.21 +-3.89, 0.00, 53.12, 46.88, 6.24 +-3.89, 0.00, 53.13, 46.87, 6.27 +-3.89, 0.00, 53.15, 46.85, 6.30 +-3.82, 0.00, 50.64, 49.36, 1.28 +-3.82, 0.00, 53.13, 46.87, 6.25 +-3.82, 0.00, 53.14, 46.86, 6.28 +-3.82, 0.00, 53.16, 46.84, 6.31 +-3.82, 0.00, 53.17, 46.83, 6.34 +-3.82, 0.00, 53.18, 46.82, 6.37 +-3.82, 0.00, 53.20, 46.80, 6.40 +-3.82, 0.00, 53.21, 46.79, 6.43 +-3.69, 0.00, 48.18, 51.82, -3.63 +-3.69, 0.00, 53.14, 46.86, 6.28 +-3.69, 0.00, 53.16, 46.84, 6.31 +-3.63, 0.00, 50.65, 49.35, 1.30 +-3.63, 0.00, 53.13, 46.87, 6.27 +-3.63, 0.00, 53.15, 46.85, 6.29 +-3.63, 0.00, 53.16, 46.84, 6.32 +-3.56, 0.00, 50.65, 49.35, 1.31 +-3.56, 0.00, 53.14, 46.86, 6.28 +-3.56, 0.00, 53.15, 46.85, 6.30 +-3.56, 0.00, 53.16, 46.84, 6.33 +-3.43, 0.00, 48.13, 51.87, -3.73 +-3.43, 0.00, 53.09, 46.91, 6.18 +-3.36, 0.00, 50.58, 49.42, 1.17 +-3.36, 0.00, 53.07, 46.93, 6.13 +-3.36, 0.00, 53.08, 46.92, 6.16 +-3.36, 0.00, 53.09, 46.91, 6.19 +-3.36, 0.00, 53.11, 46.89, 6.21 +-3.30, 0.00, 50.60, 49.40, 1.19 +-3.30, 0.00, 53.08, 46.92, 6.16 +-3.30, 0.00, 53.09, 46.91, 6.19 +-3.30, 0.00, 53.11, 46.89, 6.21 +-3.16, 0.00, 48.07, 51.93, -3.85 +-3.16, 0.00, 53.03, 46.97, 6.06 +-3.16, 0.00, 53.04, 46.96, 6.08 +-3.16, 0.00, 53.05, 46.95, 6.11 +-3.16, 0.00, 53.07, 46.93, 6.13 +-3.16, 0.00, 53.08, 46.92, 6.15 +-3.10, 0.00, 50.57, 49.43, 1.14 +-3.10, 0.00, 53.05, 46.95, 6.10 +-3.10, 0.00, 53.06, 46.94, 6.13 +-3.10, 0.00, 53.07, 46.93, 6.15 +-3.03, 0.00, 50.56, 49.44, 1.13 +-3.03, 0.00, 53.05, 46.95, 6.10 +-3.03, 0.00, 53.06, 46.94, 6.12 +-3.03, 0.00, 53.07, 46.93, 6.14 +-3.03, 0.00, 53.08, 46.92, 6.16 +-2.90, 0.00, 48.05, 51.95, -3.90 +-3.03, 0.00, 58.05, 41.95, 16.10 +-2.90, 0.00, 48.07, 51.93, -3.86 +-2.90, 0.00, 53.03, 46.97, 6.05 +-2.90, 0.00, 53.04, 46.96, 6.08 +-2.90, 0.00, 53.05, 46.95, 6.10 +-2.90, 0.00, 53.06, 46.94, 6.12 +-2.90, 0.00, 53.07, 46.93, 6.14 +-2.90, 0.00, 53.08, 46.92, 6.16 +-2.90, 0.00, 53.09, 46.91, 6.18 +-2.83, 0.00, 50.58, 49.42, 1.16 +-2.83, 0.00, 53.06, 46.94, 6.13 +-2.83, 0.00, 53.07, 46.93, 6.15 +-2.90, 0.00, 55.61, 44.39, 11.21 +-2.83, 0.00, 50.62, 49.38, 1.25 +-2.83, 0.00, 53.11, 46.89, 6.21 +-2.83, 0.00, 53.12, 46.88, 6.23 +-2.83, 0.00, 53.13, 46.87, 6.26 +-2.83, 0.00, 53.14, 46.86, 6.28 +-2.83, 0.00, 53.15, 46.85, 6.30 +-2.90, 0.00, 55.68, 44.32, 11.36 +-2.90, 0.00, 53.22, 46.78, 6.44 +-2.90, 0.00, 53.23, 46.77, 6.46 +-2.90, 0.00, 53.24, 46.76, 6.48 +-2.90, 0.00, 53.25, 46.75, 6.51 +-2.90, 0.00, 53.26, 46.74, 6.53 +-2.90, 0.00, 53.27, 46.73, 6.55 +-2.83, 0.00, 50.76, 49.24, 1.53 +-2.90, 0.00, 55.77, 44.23, 11.54 +-2.90, 0.00, 53.31, 46.69, 6.61 +-2.83, 0.00, 50.80, 49.20, 1.59 +-2.83, 0.00, 53.28, 46.72, 6.56 +-2.83, 0.00, 53.29, 46.71, 6.58 +-2.83, 0.00, 53.30, 46.70, 6.60 +-2.83, 0.00, 53.31, 46.69, 6.62 +-2.83, 0.00, 53.32, 46.68, 6.64 +-2.83, 0.00, 53.33, 46.67, 6.66 +-2.83, 0.00, 53.34, 46.66, 6.69 +-2.83, 0.00, 53.35, 46.65, 6.71 +-2.83, 0.00, 53.36, 46.64, 6.73 +-2.83, 0.00, 53.37, 46.63, 6.75 +-2.83, 0.00, 53.39, 46.61, 6.77 +-2.83, 0.00, 53.40, 46.60, 6.79 +-2.83, 0.00, 53.41, 46.59, 6.81 +-2.77, 0.00, 50.90, 49.10, 1.79 +-2.77, 0.00, 53.38, 46.62, 6.76 +-2.77, 0.00, 53.39, 46.61, 6.78 +-2.77, 0.00, 53.40, 46.60, 6.80 +-2.77, 0.00, 53.41, 46.59, 6.82 +-2.77, 0.00, 53.42, 46.58, 6.84 +-2.77, 0.00, 53.43, 46.57, 6.86 +-2.64, 0.00, 48.40, 51.60, -3.21 +-2.64, 0.00, 53.35, 46.65, 6.70 +-2.64, 0.00, 53.36, 46.64, 6.72 +-2.64, 0.00, 53.37, 46.63, 6.74 +-2.64, 0.00, 53.38, 46.62, 6.76 +-2.64, 0.00, 53.39, 46.61, 6.78 +-2.64, 0.00, 53.40, 46.60, 6.80 +-2.64, 0.00, 53.41, 46.59, 6.82 +-2.57, 0.00, 50.90, 49.10, 1.80 +-2.57, 0.00, 53.38, 46.62, 6.76 +-2.57, 0.00, 53.39, 46.61, 6.78 +-2.50, 0.00, 50.88, 49.12, 1.76 +-2.50, 0.00, 53.36, 46.64, 6.72 +-2.50, 0.00, 53.37, 46.63, 6.74 +-2.37, 0.00, 48.33, 51.67, -3.33 +-2.37, 0.00, 53.29, 46.71, 6.57 +-2.37, 0.00, 53.30, 46.70, 6.59 +-2.31, 0.00, 50.78, 49.22, 1.57 +-2.31, 0.00, 53.26, 46.74, 6.53 +-2.31, 0.00, 53.27, 46.73, 6.55 +-2.24, 0.00, 50.76, 49.24, 1.52 +-2.24, 0.00, 53.24, 46.76, 6.48 +-2.24, 0.00, 53.25, 46.75, 6.50 +-2.11, 0.00, 48.21, 51.79, -3.57 +-2.11, 0.00, 53.17, 46.83, 6.33 +-2.11, 0.00, 53.17, 46.83, 6.35 +-2.04, 0.00, 50.66, 49.34, 1.32 +-2.04, 0.00, 53.14, 46.86, 6.28 +-1.98, 0.00, 50.63, 49.37, 1.25 +-1.98, 0.00, 53.10, 46.90, 6.21 +-1.85, 0.00, 48.07, 51.93, -3.86 +-1.85, 0.00, 53.02, 46.98, 6.04 +-1.78, 0.00, 50.50, 49.50, 1.01 +-1.78, 0.00, 52.98, 47.02, 5.97 +-1.71, 0.00, 50.47, 49.53, 0.94 +-1.71, 0.00, 52.95, 47.05, 5.89 +-1.58, 0.00, 47.91, 52.09, -4.18 +-1.58, 0.00, 52.86, 47.14, 5.72 +-1.58, 0.00, 52.87, 47.13, 5.73 +-1.58, 0.00, 52.87, 47.13, 5.74 +-1.52, 0.00, 50.36, 49.64, 0.71 +-1.52, 0.00, 52.83, 47.17, 5.67 +-1.45, 0.00, 50.32, 49.68, 0.64 +-1.45, 0.00, 52.80, 47.20, 5.59 +-1.32, 0.00, 47.76, 52.24, -4.49 +-1.32, 0.00, 52.71, 47.29, 5.41 +-1.25, 0.00, 50.19, 49.81, 0.38 +-1.25, 0.00, 52.67, 47.33, 5.33 +-1.25, 0.00, 52.67, 47.33, 5.34 +-1.19, 0.00, 50.15, 49.85, 0.31 +-1.19, 0.00, 52.63, 47.37, 5.26 +-1.05, 0.00, 47.59, 52.41, -4.82 +-1.05, 0.00, 52.54, 47.46, 5.08 +-1.05, 0.00, 52.54, 47.46, 5.09 +-0.99, 0.00, 50.03, 49.97, 0.05 +-0.99, 0.00, 52.50, 47.50, 5.00 +-0.99, 0.00, 52.50, 47.50, 5.01 +-0.92, 0.00, 49.99, 50.01, -0.03 +-0.92, 0.00, 52.46, 47.54, 4.92 +-0.92, 0.00, 52.47, 47.53, 4.93 +-0.79, 0.00, 47.43, 52.57, -5.15 +-0.79, 0.00, 52.37, 47.63, 4.75 +-0.79, 0.00, 52.38, 47.62, 4.75 +-0.73, 0.00, 49.86, 50.14, -0.29 +-0.73, 0.00, 52.33, 47.67, 4.66 +-0.66, 0.00, 49.81, 50.19, -0.37 +-0.66, 0.00, 52.29, 47.71, 4.57 +-0.66, 0.00, 52.29, 47.71, 4.58 +-0.53, 0.00, 47.25, 52.75, -5.50 +-0.53, 0.00, 52.19, 47.81, 4.39 +-0.46, 0.00, 49.68, 50.32, -0.65 +-0.46, 0.00, 52.15, 47.85, 4.30 +-0.46, 0.00, 52.15, 47.85, 4.30 +-0.46, 0.00, 52.15, 47.85, 4.30 +-0.40, 0.00, 49.63, 50.37, -0.73 +-0.40, 0.00, 52.11, 47.89, 4.21 +-0.40, 0.00, 52.11, 47.89, 4.21 +-0.40, 0.00, 52.11, 47.89, 4.22 +-0.26, 0.00, 47.07, 52.93, -5.87 +-0.26, 0.00, 52.01, 47.99, 4.02 +-0.26, 0.00, 52.01, 47.99, 4.03 +-0.26, 0.00, 52.01, 47.99, 4.03 +-0.20, 0.00, 49.49, 50.51, -1.01 +-0.20, 0.00, 51.97, 48.03, 3.93 +-0.20, 0.00, 51.97, 48.03, 3.93 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.13, 0.00, 49.45, 50.55, -1.11 +-0.13, 0.00, 51.92, 48.08, 3.84 +-0.13, 0.00, 51.92, 48.08, 3.84 +0.00, 0.00, 46.88, 53.12, -6.25 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.07, 0.00, 49.30, 50.70, -1.40 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.00, 0.00, 54.29, 45.71, 8.58 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.07, 0.00, 49.30, 50.70, -1.41 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.76, 48.24, 3.53 +0.07, 0.00, 51.76, 48.24, 3.53 +0.13, 0.00, 49.24, 50.76, -1.51 +0.13, 0.00, 51.71, 48.29, 3.43 +0.13, 0.00, 51.71, 48.29, 3.43 +0.13, 0.00, 51.71, 48.29, 3.43 +0.13, 0.00, 51.71, 48.29, 3.43 +0.13, 0.00, 51.71, 48.29, 3.42 +0.13, 0.00, 51.71, 48.29, 3.42 +0.26, 0.00, 46.67, 53.33, -6.66 +0.26, 0.00, 51.61, 48.39, 3.22 +0.26, 0.00, 51.61, 48.39, 3.22 +0.26, 0.00, 51.61, 48.39, 3.22 +0.26, 0.00, 51.61, 48.39, 3.22 +0.26, 0.00, 51.61, 48.39, 3.21 +0.26, 0.00, 51.61, 48.39, 3.21 +0.26, 0.00, 51.60, 48.40, 3.21 +0.26, 0.00, 51.60, 48.40, 3.21 +0.26, 0.00, 51.60, 48.40, 3.21 +0.26, 0.00, 51.60, 48.40, 3.20 +0.33, 0.00, 49.08, 50.92, -1.84 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.09 +0.33, 0.00, 51.55, 48.45, 3.09 +0.40, 0.00, 49.02, 50.98, -1.96 +0.33, 0.00, 54.01, 45.99, 8.03 +0.40, 0.00, 49.02, 50.98, -1.96 +0.33, 0.00, 54.01, 45.99, 8.02 +0.40, 0.00, 49.02, 50.98, -1.97 +0.33, 0.00, 54.01, 45.99, 8.02 +0.40, 0.00, 49.01, 50.99, -1.97 +0.33, 0.00, 54.01, 45.99, 8.01 +0.40, 0.00, 49.01, 50.99, -1.98 +0.40, 0.00, 51.48, 48.52, 2.96 +0.40, 0.00, 51.48, 48.52, 2.96 +0.40, 0.00, 51.48, 48.52, 2.96 +0.40, 0.00, 51.48, 48.52, 2.95 +0.40, 0.00, 51.48, 48.52, 2.95 +0.40, 0.00, 51.47, 48.53, 2.95 +0.40, 0.00, 51.47, 48.53, 2.95 +0.53, 0.00, 46.43, 53.57, -7.14 +0.53, 0.00, 51.37, 48.63, 2.74 +0.53, 0.00, 51.37, 48.63, 2.74 +0.53, 0.00, 51.37, 48.63, 2.73 +0.53, 0.00, 51.36, 48.64, 2.73 +0.53, 0.00, 51.36, 48.64, 2.72 +0.53, 0.00, 51.36, 48.64, 2.72 +0.53, 0.00, 51.36, 48.64, 2.72 +0.53, 0.00, 51.36, 48.64, 2.71 +0.53, 0.00, 51.35, 48.65, 2.71 +0.53, 0.00, 51.35, 48.65, 2.70 +0.40, 0.00, 56.39, 43.61, 12.79 +0.40, 0.00, 51.45, 48.55, 2.90 +0.53, 0.00, 46.40, 53.60, -7.19 +0.53, 0.00, 51.35, 48.65, 2.69 +0.53, 0.00, 51.34, 48.66, 2.69 +0.53, 0.00, 51.34, 48.66, 2.68 +0.53, 0.00, 51.34, 48.66, 2.68 +0.53, 0.00, 51.34, 48.66, 2.67 +0.53, 0.00, 51.34, 48.66, 2.67 +0.53, 0.00, 51.33, 48.67, 2.67 +0.53, 0.00, 51.33, 48.67, 2.66 +0.53, 0.00, 51.33, 48.67, 2.66 +0.53, 0.00, 51.33, 48.67, 2.66 +0.53, 0.00, 51.33, 48.67, 2.65 +0.40, 0.00, 56.37, 43.63, 12.73 +0.40, 0.00, 51.42, 48.58, 2.84 +0.40, 0.00, 51.42, 48.58, 2.84 +0.40, 0.00, 51.42, 48.58, 2.84 +0.40, 0.00, 51.42, 48.58, 2.83 +0.33, 0.00, 53.94, 46.06, 7.87 +0.33, 0.00, 51.46, 48.54, 2.93 +0.33, 0.00, 51.46, 48.54, 2.93 +0.33, 0.00, 51.46, 48.54, 2.92 +0.33, 0.00, 51.46, 48.54, 2.92 +0.33, 0.00, 51.46, 48.54, 2.92 +0.33, 0.00, 51.46, 48.54, 2.92 +0.33, 0.00, 51.46, 48.54, 2.91 +0.33, 0.00, 51.46, 48.54, 2.91 +0.33, 0.00, 51.45, 48.55, 2.91 +0.33, 0.00, 51.45, 48.55, 2.91 +0.33, 0.00, 51.45, 48.55, 2.90 +0.33, 0.00, 51.45, 48.55, 2.90 +0.26, 0.00, 53.97, 46.03, 7.94 +0.26, 0.00, 51.50, 48.50, 3.00 +0.26, 0.00, 51.50, 48.50, 2.99 +0.26, 0.00, 51.50, 48.50, 2.99 +0.13, 0.00, 56.54, 43.46, 13.08 +0.13, 0.00, 51.59, 48.41, 3.19 +0.13, 0.00, 51.59, 48.41, 3.19 +0.13, 0.00, 51.59, 48.41, 3.19 +0.13, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 54.11, 45.89, 8.23 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 54.16, 45.84, 8.32 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +-0.13, 0.00, 56.73, 43.27, 13.46 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.20, 0.00, 54.31, 45.69, 8.63 +-0.20, 0.00, 51.84, 48.16, 3.69 +-0.20, 0.00, 51.84, 48.16, 3.69 +-0.20, 0.00, 51.84, 48.16, 3.69 +-0.20, 0.00, 51.85, 48.15, 3.69 +-0.20, 0.00, 51.85, 48.15, 3.69 +-0.26, 0.00, 54.37, 45.63, 8.74 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.81 +-0.26, 0.00, 51.90, 48.10, 3.81 +-0.26, 0.00, 51.90, 48.10, 3.81 +-0.26, 0.00, 51.91, 48.09, 3.81 +-0.26, 0.00, 51.91, 48.09, 3.81 +-0.26, 0.00, 51.91, 48.09, 3.81 +-0.26, 0.00, 51.91, 48.09, 3.82 +-0.40, 0.00, 56.95, 43.05, 13.91 +-0.26, 0.00, 46.97, 53.03, -6.07 +-0.40, 0.00, 56.96, 43.04, 13.91 +-0.40, 0.00, 52.01, 47.99, 4.03 +-0.40, 0.00, 52.01, 47.99, 4.03 +-0.40, 0.00, 52.02, 47.98, 4.03 +-0.40, 0.00, 52.02, 47.98, 4.03 +-0.40, 0.00, 52.02, 47.98, 4.04 +-0.40, 0.00, 52.02, 47.98, 4.04 +-0.40, 0.00, 52.02, 47.98, 4.04 +-0.40, 0.00, 52.02, 47.98, 4.05 +-0.40, 0.00, 52.02, 47.98, 4.05 +-0.46, 0.00, 54.55, 45.45, 9.10 +-0.46, 0.00, 52.08, 47.92, 4.16 +-0.46, 0.00, 52.08, 47.92, 4.16 +-0.46, 0.00, 52.08, 47.92, 4.16 +-0.46, 0.00, 52.08, 47.92, 4.17 +-0.46, 0.00, 52.08, 47.92, 4.17 +-0.46, 0.00, 52.09, 47.91, 4.17 +-0.46, 0.00, 52.09, 47.91, 4.18 +-0.46, 0.00, 52.09, 47.91, 4.18 +-0.46, 0.00, 52.09, 47.91, 4.18 +-0.46, 0.00, 52.09, 47.91, 4.19 +-0.46, 0.00, 52.09, 47.91, 4.19 +-0.46, 0.00, 52.10, 47.90, 4.19 +-0.46, 0.00, 52.10, 47.90, 4.20 +-0.46, 0.00, 52.10, 47.90, 4.20 +-0.53, 0.00, 54.62, 45.38, 9.25 +-0.53, 0.00, 52.15, 47.85, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.33 +-0.53, 0.00, 52.17, 47.83, 4.33 +-0.53, 0.00, 52.17, 47.83, 4.33 +-0.53, 0.00, 52.17, 47.83, 4.34 +-0.66, 0.00, 57.21, 42.79, 14.43 +-0.66, 0.00, 52.27, 47.73, 4.55 +-0.66, 0.00, 52.28, 47.72, 4.55 +-0.66, 0.00, 52.28, 47.72, 4.56 +-0.66, 0.00, 52.28, 47.72, 4.56 +-0.66, 0.00, 52.28, 47.72, 4.57 +-0.66, 0.00, 52.29, 47.71, 4.57 +-0.66, 0.00, 52.29, 47.71, 4.58 +-0.66, 0.00, 52.29, 47.71, 4.58 +-0.66, 0.00, 52.29, 47.71, 4.59 +-0.66, 0.00, 52.30, 47.70, 4.59 +-0.66, 0.00, 52.30, 47.70, 4.60 +-0.66, 0.00, 52.30, 47.70, 4.60 +-0.66, 0.00, 52.30, 47.70, 4.61 +-0.66, 0.00, 52.31, 47.69, 4.61 +-0.66, 0.00, 52.31, 47.69, 4.62 +-0.66, 0.00, 52.31, 47.69, 4.62 +-0.73, 0.00, 54.83, 45.17, 9.67 +-0.73, 0.00, 52.37, 47.63, 4.73 +-0.73, 0.00, 52.37, 47.63, 4.74 +-0.73, 0.00, 52.37, 47.63, 4.74 +-0.73, 0.00, 52.37, 47.63, 4.75 +-0.73, 0.00, 52.38, 47.62, 4.75 +-0.73, 0.00, 52.38, 47.62, 4.76 +-0.73, 0.00, 52.38, 47.62, 4.76 +-0.73, 0.00, 52.38, 47.62, 4.77 +-0.73, 0.00, 52.39, 47.61, 4.77 +-0.73, 0.00, 52.39, 47.61, 4.78 +-0.73, 0.00, 52.39, 47.61, 4.78 +-0.73, 0.00, 52.39, 47.61, 4.79 +-0.73, 0.00, 52.40, 47.60, 4.80 +-0.73, 0.00, 52.40, 47.60, 4.80 +-0.73, 0.00, 52.40, 47.60, 4.81 +-0.73, 0.00, 52.41, 47.59, 4.81 +-0.73, 0.00, 52.41, 47.59, 4.82 +-0.73, 0.00, 52.41, 47.59, 4.82 +-0.73, 0.00, 52.41, 47.59, 4.83 +-0.73, 0.00, 52.42, 47.58, 4.83 +-0.73, 0.00, 52.42, 47.58, 4.84 +-0.73, 0.00, 52.42, 47.58, 4.84 +-0.66, 0.00, 49.90, 50.10, -0.19 +-0.73, 0.00, 54.90, 45.10, 9.80 +-0.66, 0.00, 49.91, 50.09, -0.18 +-0.66, 0.00, 52.38, 47.62, 4.77 +-0.66, 0.00, 52.39, 47.61, 4.77 +-0.66, 0.00, 52.39, 47.61, 4.78 +-0.66, 0.00, 52.39, 47.61, 4.78 +-0.66, 0.00, 52.39, 47.61, 4.79 +-0.66, 0.00, 52.40, 47.60, 4.79 +-0.66, 0.00, 52.40, 47.60, 4.80 +-0.66, 0.00, 52.40, 47.60, 4.80 +-0.66, 0.00, 52.40, 47.60, 4.81 +-0.53, 0.00, 47.36, 52.64, -5.28 +-0.66, 0.00, 57.35, 42.65, 14.70 +-0.53, 0.00, 47.37, 52.63, -5.27 +-0.53, 0.00, 52.31, 47.69, 4.62 +-0.53, 0.00, 52.31, 47.69, 4.63 +-0.53, 0.00, 52.32, 47.68, 4.63 +-0.53, 0.00, 52.32, 47.68, 4.64 +-0.53, 0.00, 52.32, 47.68, 4.64 +-0.53, 0.00, 52.32, 47.68, 4.64 +-0.46, 0.00, 49.80, 50.20, -0.40 +-0.46, 0.00, 52.28, 47.72, 4.55 +-0.46, 0.00, 52.28, 47.72, 4.56 +-0.46, 0.00, 52.28, 47.72, 4.56 +-0.46, 0.00, 52.28, 47.72, 4.56 +-0.46, 0.00, 52.28, 47.72, 4.57 +-0.40, 0.00, 49.76, 50.24, -0.47 +-0.40, 0.00, 52.24, 47.76, 4.47 +-0.40, 0.00, 52.24, 47.76, 4.48 +-0.40, 0.00, 52.24, 47.76, 4.48 +-0.40, 0.00, 52.24, 47.76, 4.48 +-0.26, 0.00, 47.20, 52.80, -5.60 +-0.26, 0.00, 52.14, 47.86, 4.29 +-0.26, 0.00, 52.15, 47.85, 4.29 +-0.26, 0.00, 52.15, 47.85, 4.29 +-0.26, 0.00, 52.15, 47.85, 4.29 +-0.20, 0.00, 49.63, 50.37, -0.75 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.13, 0.00, 49.58, 50.42, -0.84 +-0.13, 0.00, 52.05, 47.95, 4.11 +-0.13, 0.00, 52.05, 47.95, 4.11 +-0.13, 0.00, 52.05, 47.95, 4.11 +0.00, 0.00, 47.01, 52.99, -5.98 +0.00, 0.00, 51.96, 48.04, 3.91 +0.00, 0.00, 51.96, 48.04, 3.91 +0.00, 0.00, 51.96, 48.04, 3.91 +0.00, 0.00, 51.96, 48.04, 3.91 +0.07, 0.00, 49.43, 50.57, -1.13 +0.07, 0.00, 51.91, 48.09, 3.81 +0.07, 0.00, 51.91, 48.09, 3.81 +0.07, 0.00, 51.91, 48.09, 3.81 +0.07, 0.00, 51.91, 48.09, 3.81 +0.07, 0.00, 51.90, 48.10, 3.81 +0.13, 0.00, 49.38, 50.62, -1.23 +0.13, 0.00, 51.85, 48.15, 3.71 +0.13, 0.00, 51.85, 48.15, 3.71 +0.13, 0.00, 51.85, 48.15, 3.71 +0.13, 0.00, 51.85, 48.15, 3.71 +0.13, 0.00, 51.85, 48.15, 3.70 +0.13, 0.00, 51.85, 48.15, 3.70 +0.26, 0.00, 46.81, 53.19, -6.38 +0.26, 0.00, 51.75, 48.25, 3.50 +0.26, 0.00, 51.75, 48.25, 3.50 +0.26, 0.00, 51.75, 48.25, 3.50 +0.33, 0.00, 49.23, 50.77, -1.55 +0.33, 0.00, 51.70, 48.30, 3.39 +0.33, 0.00, 51.70, 48.30, 3.39 +0.33, 0.00, 51.69, 48.31, 3.39 +0.33, 0.00, 51.69, 48.31, 3.39 +0.33, 0.00, 51.69, 48.31, 3.38 +0.33, 0.00, 51.69, 48.31, 3.38 +0.33, 0.00, 51.69, 48.31, 3.38 +0.33, 0.00, 51.69, 48.31, 3.38 +0.33, 0.00, 51.69, 48.31, 3.37 +0.33, 0.00, 51.69, 48.31, 3.37 +0.33, 0.00, 51.68, 48.32, 3.37 +0.40, 0.00, 49.16, 50.84, -1.68 +0.40, 0.00, 51.63, 48.37, 3.26 +0.40, 0.00, 51.63, 48.37, 3.26 +0.40, 0.00, 51.63, 48.37, 3.26 +0.40, 0.00, 51.63, 48.37, 3.26 +0.40, 0.00, 51.63, 48.37, 3.25 +0.53, 0.00, 46.58, 53.42, -6.84 +0.53, 0.00, 51.52, 48.48, 3.05 +0.53, 0.00, 51.52, 48.48, 3.04 +0.53, 0.00, 51.52, 48.48, 3.04 +0.53, 0.00, 51.52, 48.48, 3.04 +0.53, 0.00, 51.52, 48.48, 3.03 +0.53, 0.00, 51.51, 48.49, 3.03 +0.53, 0.00, 51.51, 48.49, 3.02 +0.40, 0.00, 56.55, 43.45, 13.11 +0.40, 0.00, 51.61, 48.39, 3.22 +0.40, 0.00, 51.61, 48.39, 3.21 +0.40, 0.00, 51.60, 48.40, 3.21 +0.40, 0.00, 51.60, 48.40, 3.21 +0.40, 0.00, 51.60, 48.40, 3.20 +0.40, 0.00, 51.60, 48.40, 3.20 +0.40, 0.00, 51.60, 48.40, 3.20 +0.40, 0.00, 51.60, 48.40, 3.19 +0.40, 0.00, 51.60, 48.40, 3.19 +0.53, 0.00, 46.55, 53.45, -6.90 +0.53, 0.00, 51.49, 48.51, 2.99 +0.53, 0.00, 51.49, 48.51, 2.98 +0.53, 0.00, 51.49, 48.51, 2.98 +0.53, 0.00, 51.49, 48.51, 2.97 +0.53, 0.00, 51.49, 48.51, 2.97 +0.53, 0.00, 51.48, 48.52, 2.97 +0.53, 0.00, 51.48, 48.52, 2.96 +0.40, 0.00, 56.52, 43.48, 13.04 +0.40, 0.00, 51.58, 48.42, 3.15 +0.40, 0.00, 51.58, 48.42, 3.15 +0.40, 0.00, 51.57, 48.43, 3.15 +0.40, 0.00, 51.57, 48.43, 3.15 +0.33, 0.00, 54.09, 45.91, 8.19 +0.33, 0.00, 51.62, 48.38, 3.24 +0.33, 0.00, 51.62, 48.38, 3.24 +0.40, 0.00, 49.10, 50.90, -1.81 +0.40, 0.00, 51.57, 48.43, 3.13 +0.40, 0.00, 51.56, 48.44, 3.13 +0.40, 0.00, 51.56, 48.44, 3.13 +0.40, 0.00, 51.56, 48.44, 3.12 +0.40, 0.00, 51.56, 48.44, 3.12 +0.53, 0.00, 46.52, 53.48, -6.97 +0.53, 0.00, 51.46, 48.54, 2.91 +0.53, 0.00, 51.46, 48.54, 2.91 +0.53, 0.00, 51.45, 48.55, 2.91 +0.53, 0.00, 51.45, 48.55, 2.90 +0.53, 0.00, 51.45, 48.55, 2.90 +0.53, 0.00, 51.45, 48.55, 2.89 +0.40, 0.00, 56.49, 43.51, 12.98 +0.40, 0.00, 51.54, 48.46, 3.09 +0.40, 0.00, 51.54, 48.46, 3.08 +0.40, 0.00, 51.54, 48.46, 3.08 +0.33, 0.00, 54.06, 45.94, 8.12 +0.33, 0.00, 51.59, 48.41, 3.17 +0.33, 0.00, 51.59, 48.41, 3.17 +0.33, 0.00, 51.58, 48.42, 3.17 +0.40, 0.00, 49.06, 50.94, -1.88 +0.40, 0.00, 51.53, 48.47, 3.06 +0.40, 0.00, 51.53, 48.47, 3.06 +0.40, 0.00, 51.53, 48.47, 3.06 +0.53, 0.00, 46.48, 53.52, -7.03 +0.53, 0.00, 51.43, 48.57, 2.85 +0.53, 0.00, 51.42, 48.58, 2.85 +0.53, 0.00, 51.42, 48.58, 2.85 +0.53, 0.00, 51.42, 48.58, 2.84 +0.53, 0.00, 51.42, 48.58, 2.84 +0.53, 0.00, 51.42, 48.58, 2.83 +0.40, 0.00, 56.46, 43.54, 12.92 +0.40, 0.00, 51.51, 48.49, 3.02 +0.40, 0.00, 51.51, 48.49, 3.02 +0.33, 0.00, 54.03, 45.97, 8.06 +0.33, 0.00, 51.56, 48.44, 3.12 +0.33, 0.00, 51.56, 48.44, 3.11 +0.33, 0.00, 51.56, 48.44, 3.11 +0.26, 0.00, 54.08, 45.92, 8.15 +0.26, 0.00, 51.60, 48.40, 3.21 +0.26, 0.00, 51.60, 48.40, 3.20 +0.33, 0.00, 49.08, 50.92, -1.84 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.09 +0.33, 0.00, 51.55, 48.45, 3.09 +0.33, 0.00, 51.54, 48.46, 3.09 +0.33, 0.00, 51.54, 48.46, 3.09 +0.33, 0.00, 51.54, 48.46, 3.08 +0.33, 0.00, 51.54, 48.46, 3.08 +0.33, 0.00, 51.54, 48.46, 3.08 +0.33, 0.00, 51.54, 48.46, 3.08 +0.26, 0.00, 54.06, 45.94, 8.12 +0.26, 0.00, 51.59, 48.41, 3.17 +0.13, 0.00, 56.63, 43.37, 13.25 +0.13, 0.00, 51.68, 48.32, 3.37 +0.13, 0.00, 51.68, 48.32, 3.37 +0.07, 0.00, 54.20, 45.80, 8.41 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.13, 0.00, 49.21, 50.79, -1.58 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.35 +0.13, 0.00, 51.68, 48.32, 3.35 +0.13, 0.00, 51.68, 48.32, 3.35 +0.07, 0.00, 54.20, 45.80, 8.39 +0.07, 0.00, 51.73, 48.27, 3.45 +0.00, 0.00, 54.25, 45.75, 8.49 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +-0.13, 0.00, 56.82, 43.18, 13.64 +-0.13, 0.00, 51.87, 48.13, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.76 +-0.13, 0.00, 51.88, 48.12, 3.76 +-0.13, 0.00, 51.88, 48.12, 3.76 +0.00, 0.00, 46.84, 53.16, -6.33 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.07, 0.00, 49.26, 50.74, -1.48 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.45 +0.07, 0.00, 51.73, 48.27, 3.45 +0.07, 0.00, 51.73, 48.27, 3.45 +0.07, 0.00, 51.73, 48.27, 3.45 +0.07, 0.00, 51.73, 48.27, 3.45 +0.13, 0.00, 49.20, 50.80, -1.59 +0.13, 0.00, 51.68, 48.32, 3.35 +0.13, 0.00, 51.68, 48.32, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.66, 48.34, 3.33 +0.13, 0.00, 51.66, 48.34, 3.33 +0.07, 0.00, 54.19, 45.81, 8.37 +0.13, 0.00, 49.19, 50.81, -1.62 +0.07, 0.00, 54.18, 45.82, 8.37 +0.07, 0.00, 51.71, 48.29, 3.43 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.00, 0.00, 54.23, 45.77, 8.46 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.07, 0.00, 49.24, 50.76, -1.52 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.13, 0.00, 49.19, 50.81, -1.63 +0.13, 0.00, 51.66, 48.34, 3.32 +0.13, 0.00, 51.66, 48.34, 3.32 +0.13, 0.00, 51.66, 48.34, 3.32 +0.13, 0.00, 51.66, 48.34, 3.31 +0.13, 0.00, 51.66, 48.34, 3.31 +0.07, 0.00, 54.18, 45.82, 8.36 +0.07, 0.00, 51.71, 48.29, 3.41 +0.07, 0.00, 51.71, 48.29, 3.41 +0.07, 0.00, 51.71, 48.29, 3.41 +0.07, 0.00, 51.70, 48.30, 3.41 +0.07, 0.00, 51.70, 48.30, 3.41 +0.07, 0.00, 51.70, 48.30, 3.41 +0.07, 0.00, 51.70, 48.30, 3.41 +0.13, 0.00, 49.18, 50.82, -1.64 +0.13, 0.00, 51.65, 48.35, 3.31 +0.13, 0.00, 51.65, 48.35, 3.31 +0.26, 0.00, 46.61, 53.39, -6.78 +0.26, 0.00, 51.55, 48.45, 3.10 +0.26, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 49.03, 50.97, -1.94 +0.33, 0.00, 51.50, 48.50, 3.00 +0.33, 0.00, 51.50, 48.50, 3.00 +0.33, 0.00, 51.50, 48.50, 2.99 +0.33, 0.00, 51.50, 48.50, 2.99 +0.33, 0.00, 51.49, 48.51, 2.99 +0.33, 0.00, 51.49, 48.51, 2.99 +0.33, 0.00, 51.49, 48.51, 2.98 +0.33, 0.00, 51.49, 48.51, 2.98 +0.33, 0.00, 51.49, 48.51, 2.98 +0.33, 0.00, 51.49, 48.51, 2.98 +0.33, 0.00, 51.49, 48.51, 2.97 +0.33, 0.00, 51.49, 48.51, 2.97 +0.40, 0.00, 48.96, 51.04, -2.07 +0.40, 0.00, 51.43, 48.57, 2.87 +0.40, 0.00, 51.43, 48.57, 2.86 +0.53, 0.00, 46.39, 53.61, -7.23 +0.53, 0.00, 51.33, 48.67, 2.66 +0.59, 0.00, 48.81, 51.19, -2.39 +0.59, 0.00, 51.28, 48.72, 2.55 +0.59, 0.00, 51.27, 48.73, 2.55 +0.59, 0.00, 51.27, 48.73, 2.54 +0.59, 0.00, 51.27, 48.73, 2.54 +0.59, 0.00, 51.27, 48.73, 2.53 +0.59, 0.00, 51.26, 48.74, 2.53 +0.66, 0.00, 48.74, 51.26, -2.52 +0.59, 0.00, 53.73, 46.27, 7.46 +0.59, 0.00, 51.26, 48.74, 2.51 +0.66, 0.00, 48.73, 51.27, -2.53 +0.66, 0.00, 51.20, 48.80, 2.41 +0.66, 0.00, 51.20, 48.80, 2.40 +0.66, 0.00, 51.20, 48.80, 2.40 +0.66, 0.00, 51.20, 48.80, 2.39 +0.79, 0.00, 46.15, 53.85, -7.70 +0.79, 0.00, 51.09, 48.91, 2.18 +0.79, 0.00, 51.09, 48.91, 2.18 +0.86, 0.00, 48.56, 51.44, -2.87 +0.86, 0.00, 51.03, 48.97, 2.06 +0.92, 0.00, 48.51, 51.49, -2.99 +0.92, 0.00, 50.98, 49.02, 1.95 +0.92, 0.00, 50.97, 49.03, 1.94 +0.92, 0.00, 50.97, 49.03, 1.94 +0.92, 0.00, 50.96, 49.04, 1.93 +0.92, 0.00, 50.96, 49.04, 1.92 +0.92, 0.00, 50.96, 49.04, 1.92 +0.86, 0.00, 53.48, 46.52, 6.95 +0.86, 0.00, 51.00, 49.00, 2.00 +0.86, 0.00, 51.00, 49.00, 2.00 +0.86, 0.00, 50.99, 49.01, 1.99 +0.86, 0.00, 50.99, 49.01, 1.98 +0.92, 0.00, 48.47, 51.53, -3.07 +0.92, 0.00, 50.94, 49.06, 1.87 +0.92, 0.00, 50.93, 49.07, 1.86 +0.92, 0.00, 50.93, 49.07, 1.86 +1.05, 0.00, 45.88, 54.12, -8.24 +1.05, 0.00, 50.82, 49.18, 1.64 +1.05, 0.00, 50.82, 49.18, 1.63 +1.05, 0.00, 50.81, 49.19, 1.63 +1.05, 0.00, 50.81, 49.19, 1.62 +1.05, 0.00, 50.81, 49.19, 1.61 +1.05, 0.00, 50.80, 49.20, 1.60 +1.05, 0.00, 50.80, 49.20, 1.60 +1.05, 0.00, 50.79, 49.21, 1.59 +1.05, 0.00, 50.79, 49.21, 1.58 +1.05, 0.00, 50.79, 49.21, 1.57 +1.05, 0.00, 50.78, 49.22, 1.56 +1.05, 0.00, 50.78, 49.22, 1.56 +1.05, 0.00, 50.77, 49.23, 1.55 +1.05, 0.00, 50.77, 49.23, 1.54 +1.05, 0.00, 50.77, 49.23, 1.53 +1.05, 0.00, 50.76, 49.24, 1.52 +1.05, 0.00, 50.76, 49.24, 1.52 +1.05, 0.00, 50.75, 49.25, 1.51 +1.05, 0.00, 50.75, 49.25, 1.50 +1.12, 0.00, 48.22, 51.78, -3.55 +1.05, 0.00, 53.21, 46.79, 6.43 +1.05, 0.00, 50.74, 49.26, 1.48 +1.05, 0.00, 50.73, 49.27, 1.47 +1.05, 0.00, 50.73, 49.27, 1.46 +1.05, 0.00, 50.73, 49.27, 1.45 +1.05, 0.00, 50.72, 49.28, 1.44 +1.05, 0.00, 50.72, 49.28, 1.44 +1.05, 0.00, 50.71, 49.29, 1.43 +0.92, 0.00, 55.75, 44.25, 11.51 +0.92, 0.00, 50.81, 49.19, 1.61 +0.92, 0.00, 50.80, 49.20, 1.61 +0.92, 0.00, 50.80, 49.20, 1.60 +0.92, 0.00, 50.80, 49.20, 1.59 +0.92, 0.00, 50.79, 49.21, 1.58 +0.92, 0.00, 50.79, 49.21, 1.58 +0.92, 0.00, 50.79, 49.21, 1.57 +0.92, 0.00, 50.78, 49.22, 1.56 +0.92, 0.00, 50.78, 49.22, 1.56 +1.05, 0.00, 45.73, 54.27, -8.54 +1.05, 0.00, 50.67, 49.33, 1.34 +1.05, 0.00, 50.67, 49.33, 1.34 +1.05, 0.00, 50.66, 49.34, 1.33 +0.92, 0.00, 55.70, 44.30, 11.41 +0.92, 0.00, 50.76, 49.24, 1.51 +0.92, 0.00, 50.75, 49.25, 1.50 +0.92, 0.00, 50.75, 49.25, 1.50 +0.86, 0.00, 53.27, 46.73, 6.53 +0.86, 0.00, 50.79, 49.21, 1.58 +0.86, 0.00, 50.79, 49.21, 1.58 +0.86, 0.00, 50.79, 49.21, 1.57 +0.86, 0.00, 50.78, 49.22, 1.56 +0.86, 0.00, 50.78, 49.22, 1.56 +0.86, 0.00, 50.78, 49.22, 1.55 +0.86, 0.00, 50.77, 49.23, 1.55 +0.86, 0.00, 50.77, 49.23, 1.54 +0.86, 0.00, 50.77, 49.23, 1.53 +0.86, 0.00, 50.76, 49.24, 1.53 +0.86, 0.00, 50.76, 49.24, 1.52 +0.86, 0.00, 50.76, 49.24, 1.51 +0.86, 0.00, 50.75, 49.25, 1.51 +0.86, 0.00, 50.75, 49.25, 1.50 +0.86, 0.00, 50.75, 49.25, 1.49 +0.86, 0.00, 50.74, 49.26, 1.49 +0.86, 0.00, 50.74, 49.26, 1.48 +0.79, 0.00, 53.26, 46.74, 6.52 +0.79, 0.00, 50.78, 49.22, 1.57 +0.79, 0.00, 50.78, 49.22, 1.56 +0.79, 0.00, 50.78, 49.22, 1.56 +0.79, 0.00, 50.78, 49.22, 1.55 +0.79, 0.00, 50.77, 49.23, 1.54 +0.79, 0.00, 50.77, 49.23, 1.54 +0.79, 0.00, 50.77, 49.23, 1.53 +0.79, 0.00, 50.76, 49.24, 1.53 +0.79, 0.00, 50.76, 49.24, 1.52 +0.79, 0.00, 50.76, 49.24, 1.51 +0.86, 0.00, 48.23, 51.77, -3.53 +0.86, 0.00, 50.70, 49.30, 1.40 +0.86, 0.00, 50.70, 49.30, 1.40 +0.86, 0.00, 50.70, 49.30, 1.39 +0.92, 0.00, 48.17, 51.83, -3.66 +0.92, 0.00, 50.64, 49.36, 1.28 +0.86, 0.00, 53.16, 46.84, 6.31 +0.86, 0.00, 50.68, 49.32, 1.36 +0.86, 0.00, 50.68, 49.32, 1.36 +0.86, 0.00, 50.68, 49.32, 1.35 +0.86, 0.00, 50.67, 49.33, 1.34 +0.86, 0.00, 50.67, 49.33, 1.34 +0.86, 0.00, 50.67, 49.33, 1.33 +0.79, 0.00, 53.18, 46.82, 6.37 +0.79, 0.00, 50.71, 49.29, 1.42 +0.79, 0.00, 50.71, 49.29, 1.41 +0.79, 0.00, 50.70, 49.30, 1.41 +0.86, 0.00, 48.18, 51.82, -3.64 +0.86, 0.00, 50.65, 49.35, 1.29 +0.86, 0.00, 50.64, 49.36, 1.29 +0.86, 0.00, 50.64, 49.36, 1.28 +0.86, 0.00, 50.64, 49.36, 1.28 +0.92, 0.00, 48.11, 51.89, -3.77 +0.92, 0.00, 50.58, 49.42, 1.16 +0.92, 0.00, 50.58, 49.42, 1.16 +0.92, 0.00, 50.57, 49.43, 1.15 +0.92, 0.00, 50.57, 49.43, 1.14 +0.92, 0.00, 50.57, 49.43, 1.13 +0.92, 0.00, 50.56, 49.44, 1.13 +0.86, 0.00, 53.08, 46.92, 6.16 +0.86, 0.00, 50.61, 49.39, 1.21 +0.86, 0.00, 50.60, 49.40, 1.21 +0.86, 0.00, 50.60, 49.40, 1.20 +0.86, 0.00, 50.60, 49.40, 1.19 +0.86, 0.00, 50.59, 49.41, 1.19 +0.86, 0.00, 50.59, 49.41, 1.18 +0.86, 0.00, 50.59, 49.41, 1.18 +0.86, 0.00, 50.58, 49.42, 1.17 +0.86, 0.00, 50.58, 49.42, 1.16 +0.86, 0.00, 50.58, 49.42, 1.16 +0.86, 0.00, 50.57, 49.43, 1.15 +0.86, 0.00, 50.57, 49.43, 1.14 +0.92, 0.00, 48.05, 51.95, -3.91 +0.92, 0.00, 50.52, 49.48, 1.03 +0.92, 0.00, 50.51, 49.49, 1.02 +0.92, 0.00, 50.51, 49.49, 1.02 +0.86, 0.00, 53.03, 46.97, 6.05 +0.86, 0.00, 50.55, 49.45, 1.10 +0.86, 0.00, 50.55, 49.45, 1.10 +0.86, 0.00, 50.54, 49.46, 1.09 +0.86, 0.00, 50.54, 49.46, 1.08 +0.79, 0.00, 53.06, 46.94, 6.12 +0.86, 0.00, 48.06, 51.94, -3.87 +0.86, 0.00, 50.53, 49.47, 1.06 +0.79, 0.00, 53.05, 46.95, 6.10 +0.79, 0.00, 50.58, 49.42, 1.15 +0.86, 0.00, 48.05, 51.95, -3.90 +0.86, 0.00, 50.52, 49.48, 1.04 +0.86, 0.00, 50.52, 49.48, 1.03 +0.86, 0.00, 50.51, 49.49, 1.03 +0.86, 0.00, 50.51, 49.49, 1.02 +0.86, 0.00, 50.51, 49.49, 1.01 +0.86, 0.00, 50.50, 49.50, 1.01 +0.86, 0.00, 50.50, 49.50, 1.00 +0.86, 0.00, 50.50, 49.50, 1.00 +0.86, 0.00, 50.49, 49.51, 0.99 +0.86, 0.00, 50.49, 49.51, 0.98 +0.86, 0.00, 50.49, 49.51, 0.98 +0.86, 0.00, 50.48, 49.52, 0.97 +0.79, 0.00, 53.00, 47.00, 6.01 +0.79, 0.00, 50.53, 49.47, 1.06 +0.79, 0.00, 50.53, 49.47, 1.05 +0.79, 0.00, 50.52, 49.48, 1.04 +0.66, 0.00, 55.56, 44.44, 11.12 +0.79, 0.00, 45.57, 54.43, -8.85 +0.79, 0.00, 50.51, 49.49, 1.03 +0.79, 0.00, 50.51, 49.49, 1.02 +0.79, 0.00, 50.51, 49.49, 1.02 +0.79, 0.00, 50.50, 49.50, 1.01 +0.79, 0.00, 50.50, 49.50, 1.00 +0.79, 0.00, 50.50, 49.50, 1.00 +0.79, 0.00, 50.50, 49.50, 0.99 +0.79, 0.00, 50.49, 49.51, 0.99 +0.79, 0.00, 50.49, 49.51, 0.98 +0.79, 0.00, 50.49, 49.51, 0.97 +0.66, 0.00, 55.53, 44.47, 11.05 +0.66, 0.00, 50.58, 49.42, 1.16 +0.66, 0.00, 50.58, 49.42, 1.16 +0.66, 0.00, 50.58, 49.42, 1.15 +0.66, 0.00, 50.57, 49.43, 1.15 +0.66, 0.00, 50.57, 49.43, 1.14 +0.59, 0.00, 53.09, 46.91, 6.18 +0.59, 0.00, 50.62, 49.38, 1.23 +0.59, 0.00, 50.61, 49.39, 1.23 +0.66, 0.00, 48.09, 51.91, -3.82 +0.59, 0.00, 53.08, 46.92, 6.16 +0.66, 0.00, 48.09, 51.91, -3.83 +0.66, 0.00, 50.55, 49.45, 1.11 +0.66, 0.00, 50.55, 49.45, 1.10 +0.66, 0.00, 50.55, 49.45, 1.10 +0.66, 0.00, 50.55, 49.45, 1.09 +0.66, 0.00, 50.54, 49.46, 1.09 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.07 +0.66, 0.00, 50.53, 49.47, 1.07 +0.66, 0.00, 50.53, 49.47, 1.06 +0.66, 0.00, 50.53, 49.47, 1.06 +0.59, 0.00, 53.05, 46.95, 6.09 +0.59, 0.00, 50.57, 49.43, 1.15 +0.59, 0.00, 50.57, 49.43, 1.14 +0.59, 0.00, 50.57, 49.43, 1.14 +0.59, 0.00, 50.57, 49.43, 1.13 +0.59, 0.00, 50.56, 49.44, 1.13 +0.59, 0.00, 50.56, 49.44, 1.12 +0.59, 0.00, 50.56, 49.44, 1.12 +0.59, 0.00, 50.56, 49.44, 1.11 +0.66, 0.00, 48.03, 51.97, -3.93 +0.59, 0.00, 53.02, 46.98, 6.05 +0.66, 0.00, 48.03, 51.97, -3.94 +0.59, 0.00, 53.02, 46.98, 6.04 +0.59, 0.00, 50.55, 49.45, 1.09 +0.59, 0.00, 50.54, 49.46, 1.09 +0.59, 0.00, 50.54, 49.46, 1.08 +0.59, 0.00, 50.54, 49.46, 1.08 +0.59, 0.00, 50.54, 49.46, 1.07 +0.59, 0.00, 50.53, 49.47, 1.07 +0.59, 0.00, 50.53, 49.47, 1.06 +0.59, 0.00, 50.53, 49.47, 1.06 +0.59, 0.00, 50.53, 49.47, 1.06 +0.59, 0.00, 50.53, 49.47, 1.05 +0.59, 0.00, 50.52, 49.48, 1.05 +0.59, 0.00, 50.52, 49.48, 1.04 +0.53, 0.00, 53.04, 46.96, 6.08 +0.53, 0.00, 50.57, 49.43, 1.13 +0.53, 0.00, 50.56, 49.44, 1.13 +0.53, 0.00, 50.56, 49.44, 1.13 +0.53, 0.00, 50.56, 49.44, 1.12 +0.53, 0.00, 50.56, 49.44, 1.12 +0.40, 0.00, 55.60, 44.40, 11.20 +0.40, 0.00, 50.65, 49.35, 1.31 +0.40, 0.00, 50.65, 49.35, 1.31 +0.40, 0.00, 50.65, 49.35, 1.30 +0.40, 0.00, 50.65, 49.35, 1.30 +0.33, 0.00, 53.17, 46.83, 6.34 +0.33, 0.00, 50.70, 49.30, 1.39 +0.33, 0.00, 50.70, 49.30, 1.39 +0.33, 0.00, 50.69, 49.31, 1.39 +0.26, 0.00, 53.21, 46.79, 6.43 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.47 +0.13, 0.00, 55.78, 44.22, 11.56 +0.13, 0.00, 50.83, 49.17, 1.67 +0.13, 0.00, 50.83, 49.17, 1.67 +0.13, 0.00, 50.83, 49.17, 1.67 +0.13, 0.00, 50.83, 49.17, 1.67 +0.07, 0.00, 53.35, 46.65, 6.71 +0.07, 0.00, 50.88, 49.12, 1.76 +0.07, 0.00, 50.88, 49.12, 1.76 +0.07, 0.00, 50.88, 49.12, 1.76 +0.00, 0.00, 53.40, 46.60, 6.81 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +-0.13, 0.00, 55.97, 44.03, 11.95 +-0.13, 0.00, 51.03, 48.97, 2.06 +-0.13, 0.00, 51.03, 48.97, 2.06 +-0.13, 0.00, 51.03, 48.97, 2.06 +-0.13, 0.00, 51.03, 48.97, 2.07 +-0.20, 0.00, 53.55, 46.45, 7.11 +-0.20, 0.00, 51.08, 48.92, 2.17 +-0.20, 0.00, 51.08, 48.92, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.18 +-0.20, 0.00, 51.09, 48.91, 2.18 +-0.26, 0.00, 53.61, 46.39, 7.22 +-0.26, 0.00, 51.14, 48.86, 2.28 +-0.26, 0.00, 51.14, 48.86, 2.28 +-0.26, 0.00, 51.14, 48.86, 2.28 +-0.26, 0.00, 51.14, 48.86, 2.29 +-0.26, 0.00, 51.14, 48.86, 2.29 +-0.26, 0.00, 51.15, 48.85, 2.29 +-0.40, 0.00, 56.19, 43.81, 12.38 +-0.40, 0.00, 51.25, 48.75, 2.49 +-0.40, 0.00, 51.25, 48.75, 2.50 +-0.40, 0.00, 51.25, 48.75, 2.50 +-0.40, 0.00, 51.25, 48.75, 2.50 +-0.40, 0.00, 51.25, 48.75, 2.51 +-0.40, 0.00, 51.25, 48.75, 2.51 +-0.46, 0.00, 53.78, 46.22, 7.56 +-0.40, 0.00, 48.79, 51.21, -2.43 +-0.40, 0.00, 51.26, 48.74, 2.52 +-0.40, 0.00, 51.26, 48.74, 2.52 +-0.46, 0.00, 53.78, 46.22, 7.57 +-0.46, 0.00, 51.31, 48.69, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.65 +-0.46, 0.00, 51.33, 48.67, 2.65 +-0.53, 0.00, 53.85, 46.15, 7.70 +-0.53, 0.00, 51.38, 48.62, 2.76 +-0.53, 0.00, 51.38, 48.62, 2.76 +-0.53, 0.00, 51.38, 48.62, 2.77 +-0.53, 0.00, 51.38, 48.62, 2.77 +-0.53, 0.00, 51.39, 48.61, 2.77 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.79 +-0.53, 0.00, 51.39, 48.61, 2.79 +-0.53, 0.00, 51.40, 48.60, 2.79 +-0.53, 0.00, 51.40, 48.60, 2.80 +-0.53, 0.00, 51.40, 48.60, 2.80 +-0.53, 0.00, 51.40, 48.60, 2.81 +-0.53, 0.00, 51.40, 48.60, 2.81 +-0.53, 0.00, 51.41, 48.59, 2.81 +-0.53, 0.00, 51.41, 48.59, 2.82 +-0.53, 0.00, 51.41, 48.59, 2.82 +-0.53, 0.00, 51.41, 48.59, 2.83 +-0.53, 0.00, 51.41, 48.59, 2.83 +-0.53, 0.00, 51.42, 48.58, 2.83 +-0.53, 0.00, 51.42, 48.58, 2.84 +-0.53, 0.00, 51.42, 48.58, 2.84 +-0.53, 0.00, 51.42, 48.58, 2.85 +-0.53, 0.00, 51.42, 48.58, 2.85 +-0.53, 0.00, 51.43, 48.57, 2.85 +-0.46, 0.00, 48.91, 51.09, -2.19 +-0.46, 0.00, 51.38, 48.62, 2.76 +-0.46, 0.00, 51.38, 48.62, 2.76 +-0.46, 0.00, 51.38, 48.62, 2.77 +-0.46, 0.00, 51.39, 48.61, 2.77 +-0.40, 0.00, 48.87, 51.13, -2.27 +-0.40, 0.00, 51.34, 48.66, 2.68 +-0.40, 0.00, 51.34, 48.66, 2.68 +-0.40, 0.00, 51.34, 48.66, 2.68 +-0.40, 0.00, 51.34, 48.66, 2.69 +-0.40, 0.00, 51.35, 48.65, 2.69 +-0.40, 0.00, 51.35, 48.65, 2.69 +-0.40, 0.00, 51.35, 48.65, 2.70 +-0.40, 0.00, 51.35, 48.65, 2.70 +-0.40, 0.00, 51.35, 48.65, 2.70 +-0.26, 0.00, 46.31, 53.69, -7.38 +-0.26, 0.00, 51.25, 48.75, 2.51 +-0.26, 0.00, 51.26, 48.74, 2.51 +-0.26, 0.00, 51.26, 48.74, 2.51 +-0.26, 0.00, 51.26, 48.74, 2.51 +-0.20, 0.00, 48.74, 51.26, -2.53 +-0.20, 0.00, 51.21, 48.79, 2.42 +-0.20, 0.00, 51.21, 48.79, 2.42 +-0.20, 0.00, 51.21, 48.79, 2.42 +-0.13, 0.00, 48.69, 51.31, -2.62 +-0.13, 0.00, 51.16, 48.84, 2.32 +-0.13, 0.00, 51.16, 48.84, 2.33 +-0.13, 0.00, 51.16, 48.84, 2.33 +-0.13, 0.00, 51.16, 48.84, 2.33 +-0.13, 0.00, 51.16, 48.84, 2.33 +-0.13, 0.00, 51.16, 48.84, 2.33 +0.00, 0.00, 46.12, 53.88, -7.76 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.07, 0.00, 48.54, 51.46, -2.91 +0.07, 0.00, 51.02, 48.98, 2.03 +0.07, 0.00, 51.02, 48.98, 2.03 +0.07, 0.00, 51.02, 48.98, 2.03 +0.13, 0.00, 48.49, 51.51, -3.01 +0.13, 0.00, 50.96, 49.04, 1.93 +0.13, 0.00, 50.96, 49.04, 1.93 +0.13, 0.00, 50.96, 49.04, 1.93 +0.26, 0.00, 45.92, 54.08, -8.16 +0.26, 0.00, 50.86, 49.14, 1.73 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.71 +0.33, 0.00, 48.33, 51.67, -3.33 +0.33, 0.00, 50.81, 49.19, 1.61 +0.33, 0.00, 50.80, 49.20, 1.61 +0.33, 0.00, 50.80, 49.20, 1.61 +0.33, 0.00, 50.80, 49.20, 1.60 +0.33, 0.00, 50.80, 49.20, 1.60 +0.33, 0.00, 50.80, 49.20, 1.60 +0.33, 0.00, 50.80, 49.20, 1.60 +0.33, 0.00, 50.80, 49.20, 1.59 +0.40, 0.00, 48.27, 51.73, -3.45 +0.40, 0.00, 50.74, 49.26, 1.49 +0.40, 0.00, 50.74, 49.26, 1.49 +0.40, 0.00, 50.74, 49.26, 1.48 +0.40, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 53.26, 46.74, 6.52 +0.40, 0.00, 48.27, 51.73, -3.47 +0.40, 0.00, 50.74, 49.26, 1.47 +0.33, 0.00, 53.26, 46.74, 6.51 +0.33, 0.00, 50.78, 49.22, 1.57 +0.33, 0.00, 50.78, 49.22, 1.56 +0.33, 0.00, 50.78, 49.22, 1.56 +0.33, 0.00, 50.78, 49.22, 1.56 +0.33, 0.00, 50.78, 49.22, 1.56 +0.40, 0.00, 48.25, 51.75, -3.49 +0.33, 0.00, 53.25, 46.75, 6.49 +0.40, 0.00, 48.25, 51.75, -3.50 +0.40, 0.00, 50.72, 49.28, 1.44 +0.33, 0.00, 53.24, 46.76, 6.49 +0.40, 0.00, 48.25, 51.75, -3.50 +0.33, 0.00, 53.24, 46.76, 6.48 +0.33, 0.00, 50.77, 49.23, 1.53 +0.33, 0.00, 50.77, 49.23, 1.53 +0.33, 0.00, 50.76, 49.24, 1.53 +0.33, 0.00, 50.76, 49.24, 1.53 +0.33, 0.00, 50.76, 49.24, 1.52 +0.33, 0.00, 50.76, 49.24, 1.52 +0.33, 0.00, 50.76, 49.24, 1.52 +0.33, 0.00, 50.76, 49.24, 1.52 +0.33, 0.00, 50.76, 49.24, 1.51 +0.33, 0.00, 50.76, 49.24, 1.51 +0.33, 0.00, 50.75, 49.25, 1.51 +0.33, 0.00, 50.75, 49.25, 1.51 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.49 +0.33, 0.00, 50.75, 49.25, 1.49 +0.33, 0.00, 50.74, 49.26, 1.49 +0.33, 0.00, 50.74, 49.26, 1.49 +0.33, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 50.74, 49.26, 1.47 +0.33, 0.00, 50.74, 49.26, 1.47 +0.33, 0.00, 50.73, 49.27, 1.47 +0.33, 0.00, 50.73, 49.27, 1.47 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.45 +0.40, 0.00, 48.20, 51.80, -3.59 +0.40, 0.00, 50.67, 49.33, 1.35 +0.40, 0.00, 50.67, 49.33, 1.35 +0.40, 0.00, 50.67, 49.33, 1.34 +0.40, 0.00, 50.67, 49.33, 1.34 +0.33, 0.00, 53.19, 46.81, 6.38 +0.33, 0.00, 50.72, 49.28, 1.43 +0.33, 0.00, 50.72, 49.28, 1.43 +0.33, 0.00, 50.71, 49.29, 1.43 +0.33, 0.00, 50.71, 49.29, 1.43 +0.33, 0.00, 50.71, 49.29, 1.42 +0.26, 0.00, 53.23, 46.77, 6.47 +0.26, 0.00, 50.76, 49.24, 1.52 +0.26, 0.00, 50.76, 49.24, 1.52 +0.26, 0.00, 50.76, 49.24, 1.52 +0.26, 0.00, 50.76, 49.24, 1.51 +0.26, 0.00, 50.76, 49.24, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.50 +0.13, 0.00, 55.79, 44.21, 11.59 +0.13, 0.00, 50.85, 49.15, 1.70 +0.13, 0.00, 50.85, 49.15, 1.70 +0.13, 0.00, 50.85, 49.15, 1.70 +0.07, 0.00, 53.37, 46.63, 6.74 +0.07, 0.00, 50.90, 49.10, 1.80 +0.07, 0.00, 50.90, 49.10, 1.79 +0.00, 0.00, 53.42, 46.58, 6.84 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +-0.13, 0.00, 55.99, 44.01, 11.98 +-0.13, 0.00, 51.05, 48.95, 2.09 +-0.13, 0.00, 51.05, 48.95, 2.09 +-0.20, 0.00, 53.57, 46.43, 7.14 +-0.20, 0.00, 51.10, 48.90, 2.20 +-0.20, 0.00, 51.10, 48.90, 2.20 +-0.20, 0.00, 51.10, 48.90, 2.20 +-0.26, 0.00, 53.62, 46.38, 7.24 +-0.26, 0.00, 51.15, 48.85, 2.30 +-0.26, 0.00, 51.15, 48.85, 2.30 +-0.26, 0.00, 51.15, 48.85, 2.31 +-0.26, 0.00, 51.15, 48.85, 2.31 +-0.26, 0.00, 51.16, 48.84, 2.31 +-0.26, 0.00, 51.16, 48.84, 2.31 +-0.26, 0.00, 51.16, 48.84, 2.31 +-0.26, 0.00, 51.16, 48.84, 2.32 +-0.26, 0.00, 51.16, 48.84, 2.32 +-0.26, 0.00, 51.16, 48.84, 2.32 +-0.40, 0.00, 56.20, 43.80, 12.41 +-0.40, 0.00, 51.26, 48.74, 2.52 +-0.40, 0.00, 51.26, 48.74, 2.53 +-0.40, 0.00, 51.26, 48.74, 2.53 +-0.46, 0.00, 53.79, 46.21, 7.58 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.53, 0.00, 53.84, 46.16, 7.69 +-0.53, 0.00, 51.37, 48.63, 2.75 +-0.53, 0.00, 51.37, 48.63, 2.75 +-0.53, 0.00, 51.38, 48.62, 2.75 +-0.53, 0.00, 51.38, 48.62, 2.76 +-0.53, 0.00, 51.38, 48.62, 2.76 +-0.53, 0.00, 51.38, 48.62, 2.77 +-0.53, 0.00, 51.38, 48.62, 2.77 +-0.53, 0.00, 51.39, 48.61, 2.77 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.79 +-0.53, 0.00, 51.39, 48.61, 2.79 +-0.66, 0.00, 56.44, 43.56, 12.88 +-0.66, 0.00, 51.50, 48.50, 3.00 +-0.66, 0.00, 51.50, 48.50, 3.00 +-0.66, 0.00, 51.50, 48.50, 3.01 +-0.66, 0.00, 51.51, 48.49, 3.01 +-0.73, 0.00, 54.03, 45.97, 8.06 +-0.73, 0.00, 51.56, 48.44, 3.12 +-0.73, 0.00, 51.56, 48.44, 3.13 +-0.73, 0.00, 51.57, 48.43, 3.13 +-0.73, 0.00, 51.57, 48.43, 3.14 +-0.73, 0.00, 51.57, 48.43, 3.14 +-0.73, 0.00, 51.57, 48.43, 3.15 +-0.73, 0.00, 51.58, 48.42, 3.15 +-0.73, 0.00, 51.58, 48.42, 3.16 +-0.73, 0.00, 51.58, 48.42, 3.16 +-0.73, 0.00, 51.59, 48.41, 3.17 +-0.73, 0.00, 51.59, 48.41, 3.18 +-0.73, 0.00, 51.59, 48.41, 3.18 +-0.73, 0.00, 51.59, 48.41, 3.19 +-0.79, 0.00, 54.12, 45.88, 8.24 +-0.79, 0.00, 51.65, 48.35, 3.30 +-0.79, 0.00, 51.65, 48.35, 3.30 +-0.79, 0.00, 51.65, 48.35, 3.31 +-0.79, 0.00, 51.66, 48.34, 3.32 +-0.79, 0.00, 51.66, 48.34, 3.32 +-0.79, 0.00, 51.66, 48.34, 3.33 +-0.92, 0.00, 56.71, 43.29, 13.42 +-0.92, 0.00, 51.77, 48.23, 3.54 +-0.92, 0.00, 51.77, 48.23, 3.55 +-0.92, 0.00, 51.78, 48.22, 3.55 +-0.92, 0.00, 51.78, 48.22, 3.56 +-0.79, 0.00, 46.74, 53.26, -6.52 +-0.79, 0.00, 51.69, 48.31, 3.37 +-0.79, 0.00, 51.69, 48.31, 3.38 +-0.79, 0.00, 51.69, 48.31, 3.39 +-0.79, 0.00, 51.70, 48.30, 3.39 +-0.92, 0.00, 56.74, 43.26, 13.48 +-0.92, 0.00, 51.80, 48.20, 3.60 +-0.92, 0.00, 51.80, 48.20, 3.61 +-0.92, 0.00, 51.81, 48.19, 3.62 +-0.92, 0.00, 51.81, 48.19, 3.62 +-0.92, 0.00, 51.82, 48.18, 3.63 +-0.92, 0.00, 51.82, 48.18, 3.64 +-0.92, 0.00, 51.82, 48.18, 3.64 +-0.92, 0.00, 51.83, 48.17, 3.65 +-0.92, 0.00, 51.83, 48.17, 3.66 +-0.92, 0.00, 51.83, 48.17, 3.67 +-0.92, 0.00, 51.84, 48.16, 3.67 +-0.92, 0.00, 51.84, 48.16, 3.68 +-0.92, 0.00, 51.84, 48.16, 3.69 +-0.92, 0.00, 51.85, 48.15, 3.69 +-0.92, 0.00, 51.85, 48.15, 3.70 +-0.79, 0.00, 46.81, 53.19, -6.38 +-0.79, 0.00, 51.76, 48.24, 3.51 +-0.79, 0.00, 51.76, 48.24, 3.52 +-0.79, 0.00, 51.76, 48.24, 3.53 +-0.79, 0.00, 51.77, 48.23, 3.53 +-0.79, 0.00, 51.77, 48.23, 3.54 +-0.79, 0.00, 51.77, 48.23, 3.54 +-0.79, 0.00, 51.77, 48.23, 3.55 +-0.79, 0.00, 51.78, 48.22, 3.56 +-0.79, 0.00, 51.78, 48.22, 3.56 +-0.79, 0.00, 51.78, 48.22, 3.57 +-0.79, 0.00, 51.79, 48.21, 3.57 +-0.79, 0.00, 51.79, 48.21, 3.58 +-0.79, 0.00, 51.79, 48.21, 3.59 +-0.79, 0.00, 51.80, 48.20, 3.59 +-0.73, 0.00, 49.28, 50.72, -1.45 +-0.73, 0.00, 51.75, 48.25, 3.50 +-0.73, 0.00, 51.75, 48.25, 3.51 +-0.73, 0.00, 51.76, 48.24, 3.51 +-0.73, 0.00, 51.76, 48.24, 3.52 +-0.73, 0.00, 51.76, 48.24, 3.52 +-0.73, 0.00, 51.77, 48.23, 3.53 +-0.73, 0.00, 51.77, 48.23, 3.54 +-0.73, 0.00, 51.77, 48.23, 3.54 +-0.73, 0.00, 51.77, 48.23, 3.55 +-0.73, 0.00, 51.78, 48.22, 3.55 +-0.66, 0.00, 49.26, 50.74, -1.49 +-0.66, 0.00, 51.73, 48.27, 3.46 +-0.66, 0.00, 51.73, 48.27, 3.47 +-0.66, 0.00, 51.74, 48.26, 3.47 +-0.66, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 51.74, 48.26, 3.49 +-0.66, 0.00, 51.75, 48.25, 3.49 +-0.66, 0.00, 51.75, 48.25, 3.50 +-0.66, 0.00, 51.75, 48.25, 3.50 +-0.66, 0.00, 51.75, 48.25, 3.51 +-0.66, 0.00, 51.76, 48.24, 3.51 +-0.66, 0.00, 51.76, 48.24, 3.52 +-0.53, 0.00, 46.72, 53.28, -6.56 +-0.53, 0.00, 51.66, 48.34, 3.33 +-0.53, 0.00, 51.67, 48.33, 3.33 +-0.53, 0.00, 51.67, 48.33, 3.34 +-0.53, 0.00, 51.67, 48.33, 3.34 +-0.53, 0.00, 51.67, 48.33, 3.34 +-0.53, 0.00, 51.67, 48.33, 3.35 +-0.53, 0.00, 51.68, 48.32, 3.35 +-0.53, 0.00, 51.68, 48.32, 3.36 +-0.53, 0.00, 51.68, 48.32, 3.36 +-0.53, 0.00, 51.68, 48.32, 3.36 +-0.53, 0.00, 51.68, 48.32, 3.37 +-0.53, 0.00, 51.69, 48.31, 3.37 +-0.53, 0.00, 51.69, 48.31, 3.37 +-0.53, 0.00, 51.69, 48.31, 3.38 +-0.53, 0.00, 51.69, 48.31, 3.38 +-0.53, 0.00, 51.69, 48.31, 3.39 +-0.53, 0.00, 51.70, 48.30, 3.39 +-0.53, 0.00, 51.70, 48.30, 3.39 +-0.53, 0.00, 51.70, 48.30, 3.40 +-0.53, 0.00, 51.70, 48.30, 3.40 +-0.46, 0.00, 49.18, 50.82, -1.64 +-0.46, 0.00, 51.66, 48.34, 3.31 +-0.53, 0.00, 54.18, 45.82, 8.36 +-0.53, 0.00, 51.71, 48.29, 3.42 +-0.53, 0.00, 51.71, 48.29, 3.42 +-0.53, 0.00, 51.71, 48.29, 3.43 +-0.53, 0.00, 51.71, 48.29, 3.43 +-0.53, 0.00, 51.72, 48.28, 3.43 +-0.53, 0.00, 51.72, 48.28, 3.44 +-0.53, 0.00, 51.72, 48.28, 3.44 +-0.53, 0.00, 51.72, 48.28, 3.45 +-0.53, 0.00, 51.72, 48.28, 3.45 +-0.53, 0.00, 51.73, 48.27, 3.45 +-0.53, 0.00, 51.73, 48.27, 3.46 +-0.53, 0.00, 51.73, 48.27, 3.46 +-0.53, 0.00, 51.73, 48.27, 3.46 +-0.53, 0.00, 51.73, 48.27, 3.47 +-0.53, 0.00, 51.74, 48.26, 3.47 +-0.53, 0.00, 51.74, 48.26, 3.48 +-0.53, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 56.79, 43.21, 13.57 +-0.66, 0.00, 51.84, 48.16, 3.69 +-0.66, 0.00, 51.85, 48.15, 3.69 +-0.66, 0.00, 51.85, 48.15, 3.70 +-0.66, 0.00, 51.85, 48.15, 3.70 +-0.73, 0.00, 54.38, 45.62, 8.75 +-0.73, 0.00, 51.91, 48.09, 3.81 +-0.73, 0.00, 51.91, 48.09, 3.82 +-0.73, 0.00, 51.91, 48.09, 3.82 +-0.73, 0.00, 51.91, 48.09, 3.83 +-0.73, 0.00, 51.92, 48.08, 3.83 +-0.73, 0.00, 51.92, 48.08, 3.84 +-0.73, 0.00, 51.92, 48.08, 3.85 +-0.79, 0.00, 54.45, 45.55, 8.89 +-0.79, 0.00, 51.98, 48.02, 3.96 +-0.79, 0.00, 51.98, 48.02, 3.96 +-0.79, 0.00, 51.98, 48.02, 3.97 +-0.79, 0.00, 51.99, 48.01, 3.97 +-0.92, 0.00, 57.03, 42.97, 14.07 +-0.92, 0.00, 52.09, 47.91, 4.19 +-0.92, 0.00, 52.10, 47.90, 4.19 +-0.92, 0.00, 52.10, 47.90, 4.20 +-0.99, 0.00, 54.62, 45.38, 9.25 +-0.99, 0.00, 52.16, 47.84, 4.31 +-0.99, 0.00, 52.16, 47.84, 4.32 +-0.99, 0.00, 52.16, 47.84, 4.33 +-0.99, 0.00, 52.17, 47.83, 4.34 +-0.99, 0.00, 52.17, 47.83, 4.34 +-0.99, 0.00, 52.18, 47.82, 4.35 +-0.99, 0.00, 52.18, 47.82, 4.36 +-0.99, 0.00, 52.18, 47.82, 4.37 +-0.99, 0.00, 52.19, 47.81, 4.37 +-0.99, 0.00, 52.19, 47.81, 4.38 +-0.99, 0.00, 52.19, 47.81, 4.39 +-1.05, 0.00, 54.72, 45.28, 9.44 +-1.05, 0.00, 52.25, 47.75, 4.50 +-1.05, 0.00, 52.26, 47.74, 4.51 +-1.05, 0.00, 52.26, 47.74, 4.52 +-1.05, 0.00, 52.26, 47.74, 4.53 +-1.19, 0.00, 57.31, 42.69, 14.62 +-1.19, 0.00, 52.37, 47.63, 4.74 +-1.19, 0.00, 52.38, 47.62, 4.75 +-1.19, 0.00, 52.38, 47.62, 4.76 +-1.19, 0.00, 52.38, 47.62, 4.77 +-1.19, 0.00, 52.39, 47.61, 4.78 +-1.19, 0.00, 52.39, 47.61, 4.79 +-1.19, 0.00, 52.40, 47.60, 4.79 +-1.19, 0.00, 52.40, 47.60, 4.80 +-1.19, 0.00, 52.41, 47.59, 4.81 +-1.19, 0.00, 52.41, 47.59, 4.82 +-1.19, 0.00, 52.42, 47.58, 4.83 +-1.19, 0.00, 52.42, 47.58, 4.84 +-1.19, 0.00, 52.42, 47.58, 4.85 +-1.19, 0.00, 52.43, 47.57, 4.86 +-1.19, 0.00, 52.43, 47.57, 4.87 +-1.19, 0.00, 52.44, 47.56, 4.87 +-1.19, 0.00, 52.44, 47.56, 4.88 +-1.19, 0.00, 52.45, 47.55, 4.89 +-1.19, 0.00, 52.45, 47.55, 4.90 +-1.19, 0.00, 52.46, 47.54, 4.91 +-1.25, 0.00, 54.98, 45.02, 9.96 +-1.25, 0.00, 52.51, 47.49, 5.03 +-1.25, 0.00, 52.52, 47.48, 5.04 +-1.25, 0.00, 52.52, 47.48, 5.05 +-1.19, 0.00, 50.01, 49.99, 0.01 +-1.19, 0.00, 52.48, 47.52, 4.97 +-1.19, 0.00, 52.49, 47.51, 4.97 +-1.19, 0.00, 52.49, 47.51, 4.98 +-1.19, 0.00, 52.50, 47.50, 4.99 +-1.05, 0.00, 47.46, 52.54, -5.08 +-1.05, 0.00, 52.41, 47.59, 4.81 +-1.05, 0.00, 52.41, 47.59, 4.82 +-1.05, 0.00, 52.41, 47.59, 4.83 +-1.05, 0.00, 52.42, 47.58, 4.83 +-1.05, 0.00, 52.42, 47.58, 4.84 +-1.05, 0.00, 52.43, 47.57, 4.85 +-1.05, 0.00, 52.43, 47.57, 4.86 +-1.05, 0.00, 52.43, 47.57, 4.87 +-1.05, 0.00, 52.44, 47.56, 4.87 +-1.05, 0.00, 52.44, 47.56, 4.88 +-1.05, 0.00, 52.44, 47.56, 4.89 +-1.05, 0.00, 52.45, 47.55, 4.90 +-1.05, 0.00, 52.45, 47.55, 4.91 +-0.99, 0.00, 49.94, 50.06, -0.13 +-0.99, 0.00, 52.41, 47.59, 4.82 +-0.99, 0.00, 52.41, 47.59, 4.83 +-0.99, 0.00, 52.42, 47.58, 4.84 +-0.99, 0.00, 52.42, 47.58, 4.84 +-0.92, 0.00, 49.90, 50.10, -0.19 +-0.92, 0.00, 52.38, 47.62, 4.76 +-0.92, 0.00, 52.38, 47.62, 4.77 +-0.92, 0.00, 52.39, 47.61, 4.77 +-0.92, 0.00, 52.39, 47.61, 4.78 +-0.79, 0.00, 47.35, 52.65, -5.30 +-0.79, 0.00, 52.30, 47.70, 4.59 diff --git a/matlab/examples/BicopShield/BicopShield_LQI/BicopShield_GreyboxModel_LinearSS.mat b/matlab/examples/BicopShield/BicopShield_LQI/BicopShield_GreyboxModel_LinearSS.mat new file mode 100644 index 00000000..6e330b26 Binary files /dev/null and b/matlab/examples/BicopShield/BicopShield_LQI/BicopShield_GreyboxModel_LinearSS.mat differ diff --git a/matlab/examples/BicopShield/BicopShield_LQI/BicopShield_LQI.m b/matlab/examples/BicopShield/BicopShield_LQI/BicopShield_LQI.m new file mode 100644 index 00000000..96fb69bd --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_LQI/BicopShield_LQI.m @@ -0,0 +1,84 @@ +clear all; close all; clc; +%% +readtable pid1.csv; +load BicopShield_GreyboxModel_LinearSS.mat; +down_const = 5; +y=downsample(ans.Var1,down_const); +ref=zeros(3,length(y)); +ref(1,:)=downsample(ans.Var2,down_const); +ref=deg2rad(ref); +u1=downsample(ans.Var3,down_const); % motor1 input +u2=downsample(ans.Var4,down_const); % motor2 input +u=ans.Var5; + +%% Model augmentation +Ts=0.01 +intA = [model.A, zeros(2, 1); -model.C(1,:), ones(1,1)]; +intB = [model.B; 0 0]; +intC = [model.C(1,:), 0]; +continuos_model=ss(intA,intB,intC,[0 0]); +zmodel = c2d(continuos_model,Ts,'foh') +%% LQ Gain and stability +Q_lqr=diag([10 1 1]); +R_lqr=diag([1e-2 1e-2]); +K=dlqr(zmodel.A,zmodel.B,Q_lqr,R_lqr); +body=eig(zmodel.A-zmodel.B*K) + +% stability +num_points = 100; +theta = linspace(0, 2*pi, num_points); +x = cos(theta); +y = sin(theta); + +plot(x, y); +hold on +plot(body,'x'); +axis equal; +xlabel('x'); +ylabel('y'); + + +%% Simulation +t=0:0.01:48-0.01; %time vector +x_sim=zeros(3,length(t)); +u_sim=zeros(2,length(t)); +y_sim=zeros(1,length(t)); +x1prev=0; + +for i=1:length(t)-1 +u_lq=-K*(x_sim(:,i)-ref(:,i)); % computation +if u_lq(1,1)>30 %saturation + u_lq(1,1)=30; +elseif u_lq(1,1)<-30 + u_lq(1,1)=-30; +end +if u_lq(2,1)>30 + u_lq(2,1)=30; +elseif u_lq(2,1)<-30 + u_lq(2,1)=-30; +end +x_sim(:,i+1)=zmodel.A*x_sim(:,i)+zmodel.B*u_lq; % model simulation +x_sim(3,i+1)=x_sim(3,i)+Ts*(ref(1,i)-x_sim(1,i+1)); %integrator +u_sim(:,i)=u_lq; +end +%% +figure +subplot(3,1,1) +plot(t, x_sim(1,:),'LineWidth', 1.5); +hold on +plot(t,ref(1,:)); +ylabel('Uhol [rad]'); +legend('Measured data LQR','Reference') + +subplot(3,1,2) +plot(t, x_sim(2,:),'LineWidth', 1.5); +ylabel('Angular speed [rad/s]'); + + +subplot(3,1,3) +plot(t, u_sim(1,:),'LineWidth', 1.5); +hold on +plot(t, u_sim(2,:),'LineWidth', 1.5); +ylabel('Percent [%]'); +xlabel('Time [s]'); +legend('Input motor 1','Input motor 2'); diff --git a/matlab/examples/BicopShield/BicopShield_PID/BicopShield_PID.m b/matlab/examples/BicopShield/BicopShield_PID/BicopShield_PID.m new file mode 100644 index 00000000..3121ea27 --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_PID/BicopShield_PID.m @@ -0,0 +1,78 @@ +clear all;close all; clc +%% +%open +readtable pid1.csv; +y=ans.Var1; % angle +ref=ans.Var2; % reference +u1=ans.Var3; % motor1 +u2=ans.Var4; % motor2 +u=ans.Var5; % PID output + +Ts=0.01; % Sampling period +t=0:Ts:239.98; % Time vector +t=t'; + +% Measured data plot +figure(1) +plot(t,y, 'LineWidth', 1.5); +hold on +grid on +plot(t,ref); +legend('Namerané dáta','Žiadaná hodnota'); +title('Namerané dáta'); +xlabel('Čas (s)'); +ylabel('Uhol ( °)'); + + +% Identification ARX +% parameters for arx +na=4; +nb=4; +nk=1; +data=iddata(y,u,'Ts',Ts); % Data object +sys=arx(data,[na nb nk]); % Identification + +sim_data=sim(sys,u); % Simulation + +figure(3) +plot(sim_data,'LineWidth', 1.5) +grid on +legend('Identificated ARX model'); +title('ARX Model'); +xlabel('Time (s)'); +ylabel('Angle ( °)'); + +%compare model a validačné data +figure(4) +compare(sys,data,100) +grid on +legend('Validation data','Identificated ARX model'); +xlabel('Time (s)'); +ylabel('Angle ( °)'); + +% PID controller +Kp=1.5; +Ki=2.0; +Kd=0.5; +pid_controller=pid(Kp,1/Ki,Kd,0,Ts); +sys_PID=feedback(pid_controller*sys,1); + +% Simulation with PID +[y_sim, t_sim] = lsim(sys_PID, ref, t); + +% Plot Results +figure(5) +plot(t,ref,'b'); +grid on +xlabel('Time (s)'); +ylabel('Angle ( °)'); +title('ARX Model with PID'); +hold on +plot(t,y,'LineWidth', 1.5) +plot(t_sim, y_sim,'LineWidth', 1.5); +legend('Reference','Measured data','ARX model with PID'); + + + + + diff --git a/matlab/examples/BicopShield/BicopShield_PID/pid1.csv b/matlab/examples/BicopShield/BicopShield_PID/pid1.csv new file mode 100644 index 00000000..48c77ebf --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_PID/pid1.csv @@ -0,0 +1,23999 @@ +0.00, 10.00, 57.58, 42.43, 15.15 +0.00, 10.00, 57.61, 42.39, 15.23 +0.00, 10.00, 57.65, 42.35, 15.30 +0.00, 10.00, 57.69, 42.31, 15.38 +0.00, 10.00, 57.72, 42.28, 15.45 +0.00, 10.00, 57.76, 42.24, 15.52 +0.00, 10.00, 57.80, 42.20, 15.60 +0.00, 10.00, 57.84, 42.16, 15.68 +0.00, 10.00, 57.88, 42.13, 15.75 +0.00, 10.00, 57.91, 42.09, 15.82 +0.00, 10.00, 57.95, 42.05, 15.90 +0.00, 10.00, 57.99, 42.01, 15.98 +0.07, 10.00, 55.50, 44.50, 11.01 +0.07, 10.00, 58.01, 41.99, 16.03 +0.00, 10.00, 60.57, 39.43, 21.14 +0.00, 10.00, 58.14, 41.86, 16.27 +0.00, 10.00, 58.17, 41.83, 16.35 +0.00, 10.00, 58.21, 41.79, 16.42 +0.00, 10.00, 58.25, 41.75, 16.50 +0.00, 10.00, 58.29, 41.71, 16.57 +0.00, 10.00, 58.32, 41.68, 16.65 +0.00, 10.00, 58.36, 41.64, 16.72 +0.00, 10.00, 58.40, 41.60, 16.80 +0.07, 10.00, 55.92, 44.08, 11.83 +0.07, 10.00, 58.42, 41.58, 16.85 +0.07, 10.00, 58.46, 41.54, 16.92 +0.07, 10.00, 58.50, 41.50, 17.00 +0.07, 10.00, 58.54, 41.46, 17.07 +0.07, 10.00, 58.57, 41.43, 17.15 +0.07, 10.00, 58.61, 41.39, 17.22 +0.07, 10.00, 58.65, 41.35, 17.30 +0.07, 10.00, 58.69, 41.31, 17.37 +0.07, 10.00, 58.72, 41.28, 17.45 +0.07, 10.00, 58.76, 41.24, 17.52 +0.07, 10.00, 58.80, 41.20, 17.59 +0.07, 10.00, 58.83, 41.17, 17.67 +0.07, 10.00, 58.87, 41.13, 17.74 +0.07, 10.00, 58.91, 41.09, 17.82 +0.07, 10.00, 58.95, 41.05, 17.89 +0.13, 10.00, 56.46, 43.54, 12.92 +0.13, 10.00, 58.97, 41.03, 17.94 +0.13, 10.00, 59.01, 40.99, 18.02 +0.13, 10.00, 59.04, 40.96, 18.09 +0.13, 10.00, 59.08, 40.92, 18.16 +0.13, 10.00, 59.12, 40.88, 18.24 +0.26, 10.00, 54.11, 45.89, 8.22 +0.26, 10.00, 59.09, 40.91, 18.19 +0.33, 10.00, 56.61, 43.39, 13.22 +0.33, 10.00, 59.12, 40.88, 18.23 +0.40, 10.00, 56.63, 43.37, 13.26 +0.40, 10.00, 59.14, 40.86, 18.28 +0.53, 10.00, 54.13, 45.87, 8.26 +0.53, 10.00, 59.11, 40.89, 18.22 +0.59, 10.00, 56.62, 43.38, 13.25 +0.66, 10.00, 56.61, 43.39, 13.22 +0.79, 10.00, 54.07, 45.93, 8.15 +0.86, 10.00, 56.53, 43.47, 13.06 +0.92, 10.00, 56.52, 43.48, 13.03 +1.05, 10.00, 53.98, 46.02, 7.96 +1.12, 10.00, 56.43, 43.57, 12.87 +1.32, 10.00, 51.37, 48.63, 2.75 +1.38, 10.00, 56.30, 43.70, 12.60 +1.45, 10.00, 56.28, 43.72, 12.57 +1.65, 10.00, 51.22, 48.78, 2.45 +1.71, 10.00, 56.15, 43.85, 12.30 +1.91, 10.00, 51.09, 48.91, 2.17 +1.98, 10.00, 56.01, 43.99, 12.02 +2.18, 10.00, 50.95, 49.05, 1.90 +2.37, 10.00, 50.83, 49.17, 1.66 +2.44, 10.00, 55.75, 44.25, 11.50 +2.64, 10.00, 50.69, 49.31, 1.37 +2.77, 10.00, 53.09, 46.91, 6.17 +2.97, 10.00, 50.49, 49.51, 0.99 +3.03, 10.00, 55.41, 44.59, 10.83 +3.23, 10.00, 50.35, 49.65, 0.69 +3.43, 10.00, 50.22, 49.78, 0.45 +3.69, 10.00, 47.58, 52.42, -4.85 +3.76, 10.00, 54.97, 45.03, 9.93 +4.02, 10.00, 47.38, 52.62, -5.25 +4.09, 10.00, 54.76, 45.24, 9.53 +4.28, 10.00, 49.69, 50.31, -0.61 +4.55, 10.00, 47.04, 52.96, -5.91 +4.75, 10.00, 49.39, 50.61, -1.23 +4.88, 10.00, 51.78, 48.22, 3.56 +5.08, 10.00, 49.18, 50.82, -1.64 +5.27, 10.00, 49.05, 50.95, -1.91 +5.41, 10.00, 51.44, 48.56, 2.88 +5.60, 10.00, 48.83, 51.17, -2.33 +5.80, 10.00, 48.70, 51.30, -2.60 +5.93, 10.00, 51.09, 48.91, 2.18 +6.13, 10.00, 48.48, 51.52, -3.03 +6.33, 10.00, 48.35, 51.65, -3.30 +6.46, 10.00, 50.74, 49.26, 1.47 +6.66, 10.00, 48.13, 51.87, -3.74 +6.86, 10.00, 47.99, 52.01, -4.02 +6.99, 10.00, 50.38, 49.62, 0.75 +7.19, 10.00, 47.77, 52.23, -4.47 +7.38, 10.00, 47.63, 52.37, -4.74 +7.51, 10.00, 50.01, 49.99, 0.02 +7.71, 10.00, 47.40, 52.60, -5.20 +7.91, 10.00, 47.26, 52.74, -5.48 +8.04, 10.00, 49.64, 50.36, -0.72 +8.24, 10.00, 47.02, 52.98, -5.95 +8.31, 10.00, 51.93, 48.07, 3.85 +8.50, 10.00, 46.84, 53.16, -6.32 +8.70, 10.00, 46.70, 53.30, -6.61 +8.77, 10.00, 51.59, 48.41, 3.19 +8.96, 10.00, 46.51, 53.49, -6.99 +9.03, 10.00, 51.40, 48.60, 2.81 +9.23, 10.00, 46.31, 53.69, -7.37 +9.36, 10.00, 48.69, 51.31, -2.62 +9.49, 10.00, 48.59, 51.41, -2.81 +9.62, 10.00, 48.50, 51.50, -3.01 +9.76, 10.00, 48.40, 51.60, -3.20 +9.89, 10.00, 48.30, 51.70, -3.40 +10.02, 10.00, 48.20, 51.80, -3.60 +10.09, 10.00, 50.62, 49.38, 1.25 +10.28, 10.00, 45.53, 54.47, -8.94 +10.35, 10.00, 50.42, 49.58, 0.84 +10.42, 10.00, 50.37, 49.63, 0.74 +10.55, 10.00, 47.80, 52.20, -4.40 +10.61, 10.00, 50.22, 49.78, 0.44 +10.68, 10.00, 50.17, 49.83, 0.33 +10.81, 10.00, 47.59, 52.41, -4.81 +10.88, 10.00, 50.01, 49.99, 0.02 +10.94, 10.00, 49.96, 50.04, -0.08 +11.07, 10.00, 47.38, 52.62, -5.23 +11.14, 10.00, 49.80, 50.20, -0.39 +11.21, 10.00, 49.75, 50.25, -0.50 +11.34, 10.00, 47.17, 52.83, -5.65 +11.40, 10.00, 49.59, 50.41, -0.82 +11.47, 10.00, 49.54, 50.46, -0.93 +11.47, 10.00, 52.00, 48.00, 4.00 +11.60, 10.00, 46.95, 53.05, -6.09 +11.67, 10.00, 49.37, 50.63, -1.26 +11.73, 10.00, 49.31, 50.69, -1.37 +11.73, 10.00, 51.78, 48.22, 3.56 +11.87, 10.00, 46.73, 53.27, -6.54 +11.87, 10.00, 51.67, 48.33, 3.33 +11.87, 10.00, 51.66, 48.34, 3.32 +11.93, 10.00, 49.13, 50.87, -1.74 +11.93, 10.00, 51.59, 48.41, 3.19 +12.00, 10.00, 49.07, 50.93, -1.87 +12.00, 10.00, 51.53, 48.47, 3.06 +12.00, 10.00, 51.52, 48.48, 3.05 +12.13, 10.00, 46.47, 53.53, -7.06 +12.13, 10.00, 51.41, 48.59, 2.82 +12.13, 10.00, 51.40, 48.60, 2.80 +12.13, 10.00, 51.39, 48.61, 2.78 +12.19, 10.00, 48.86, 51.14, -2.28 +12.19, 10.00, 51.33, 48.67, 2.65 +12.19, 10.00, 51.32, 48.68, 2.64 +12.19, 10.00, 51.31, 48.69, 2.62 +12.19, 10.00, 51.30, 48.70, 2.60 +12.19, 10.00, 51.29, 48.71, 2.59 +12.19, 10.00, 51.28, 48.72, 2.57 +12.19, 10.00, 51.28, 48.72, 2.55 +12.13, 10.00, 53.79, 46.21, 7.58 +12.13, 10.00, 51.31, 48.69, 2.62 +12.13, 10.00, 51.30, 48.70, 2.60 +12.13, 10.00, 51.29, 48.71, 2.59 +12.13, 10.00, 51.29, 48.71, 2.57 +12.13, 10.00, 51.28, 48.72, 2.56 +12.13, 10.00, 51.27, 48.73, 2.54 +12.00, 10.00, 56.31, 43.69, 12.61 +12.00, 10.00, 51.35, 48.65, 2.71 +12.00, 10.00, 51.35, 48.65, 2.69 +12.00, 10.00, 51.34, 48.66, 2.68 +11.93, 10.00, 53.85, 46.15, 7.71 +11.93, 10.00, 51.37, 48.63, 2.75 +11.93, 10.00, 51.37, 48.63, 2.73 +11.93, 10.00, 51.36, 48.64, 2.72 +11.87, 10.00, 53.87, 46.13, 7.75 +11.87, 10.00, 51.40, 48.60, 2.79 +11.87, 10.00, 51.39, 48.61, 2.78 +11.73, 10.00, 56.42, 43.58, 12.85 +11.73, 10.00, 51.47, 48.53, 2.95 +11.67, 10.00, 53.99, 46.01, 7.98 +11.67, 10.00, 51.51, 48.49, 3.02 +11.60, 10.00, 54.03, 45.97, 8.05 +11.60, 10.00, 51.55, 48.45, 3.10 +11.47, 10.00, 56.59, 43.41, 13.17 +11.47, 10.00, 51.64, 48.36, 3.27 +11.47, 10.00, 51.63, 48.37, 3.26 +11.40, 10.00, 54.15, 45.85, 8.29 +11.40, 10.00, 51.67, 48.33, 3.34 +11.40, 10.00, 51.66, 48.34, 3.33 +11.34, 10.00, 54.18, 45.82, 8.36 +11.34, 10.00, 51.70, 48.30, 3.41 +11.21, 10.00, 56.74, 43.26, 13.48 +11.21, 10.00, 51.79, 48.21, 3.59 +11.14, 10.00, 54.31, 45.69, 8.62 +11.14, 10.00, 51.83, 48.17, 3.67 +11.07, 10.00, 54.35, 45.65, 8.70 +11.07, 10.00, 51.88, 48.12, 3.75 +10.94, 10.00, 56.92, 43.08, 13.83 +10.94, 10.00, 51.97, 48.03, 3.94 +10.88, 10.00, 54.49, 45.51, 8.97 +10.88, 10.00, 52.01, 47.99, 4.02 +10.81, 10.00, 54.53, 45.47, 9.06 +10.81, 10.00, 52.05, 47.95, 4.11 +10.81, 10.00, 52.05, 47.95, 4.10 +10.68, 10.00, 57.09, 42.91, 14.18 +10.68, 10.00, 52.14, 47.86, 4.29 +10.68, 10.00, 52.14, 47.86, 4.28 +10.68, 10.00, 52.14, 47.86, 4.28 +10.61, 10.00, 54.66, 45.34, 9.32 +10.61, 10.00, 52.18, 47.82, 4.37 +10.61, 10.00, 52.18, 47.82, 4.36 +10.55, 10.00, 54.70, 45.30, 9.40 +10.55, 10.00, 52.23, 47.77, 4.45 +10.55, 10.00, 52.23, 47.77, 4.45 +10.42, 10.00, 57.27, 42.73, 14.53 +10.42, 10.00, 52.32, 47.68, 4.64 +10.35, 10.00, 54.84, 45.16, 9.68 +10.35, 10.00, 52.37, 47.63, 4.74 +10.28, 10.00, 54.89, 45.11, 9.78 +10.28, 10.00, 52.42, 47.58, 4.83 +10.28, 10.00, 52.41, 47.59, 4.83 +10.15, 10.00, 57.46, 42.54, 14.91 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.15, 10.00, 52.51, 47.49, 5.02 +10.09, 10.00, 55.03, 44.97, 10.06 +10.09, 10.00, 52.56, 47.44, 5.12 +10.09, 10.00, 52.56, 47.44, 5.12 +10.02, 10.00, 55.08, 44.92, 10.16 +10.02, 10.00, 52.61, 47.39, 5.21 +10.02, 10.00, 52.61, 47.39, 5.21 +10.02, 10.00, 52.61, 47.39, 5.21 +9.89, 10.00, 57.65, 42.35, 15.30 +9.89, 10.00, 52.71, 47.29, 5.41 +9.89, 10.00, 52.71, 47.29, 5.41 +9.89, 10.00, 52.71, 47.29, 5.41 +9.82, 10.00, 55.23, 44.77, 10.46 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.52 +9.82, 10.00, 52.76, 47.24, 5.53 +9.82, 10.00, 52.76, 47.24, 5.53 +9.82, 10.00, 52.76, 47.24, 5.53 +9.82, 10.00, 52.76, 47.24, 5.53 +9.82, 10.00, 52.77, 47.23, 5.53 +9.82, 10.00, 52.77, 47.23, 5.53 +9.82, 10.00, 52.77, 47.23, 5.53 +9.82, 10.00, 52.77, 47.23, 5.53 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.54 +9.82, 10.00, 52.77, 47.23, 5.55 +9.82, 10.00, 52.77, 47.23, 5.55 +9.82, 10.00, 52.77, 47.23, 5.55 +9.82, 10.00, 52.77, 47.23, 5.55 +9.82, 10.00, 52.78, 47.22, 5.55 +9.89, 10.00, 50.25, 49.75, 0.51 +9.89, 10.00, 52.73, 47.27, 5.45 +9.89, 10.00, 52.73, 47.27, 5.45 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +9.89, 10.00, 52.73, 47.27, 5.46 +10.02, 10.00, 47.69, 52.31, -4.63 +9.89, 10.00, 57.67, 42.33, 15.35 +10.02, 10.00, 47.69, 52.31, -4.62 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.02, 10.00, 52.63, 47.37, 5.26 +10.09, 10.00, 50.11, 49.89, 0.22 +10.09, 10.00, 52.58, 47.42, 5.16 +10.09, 10.00, 52.58, 47.42, 5.16 +10.09, 10.00, 52.58, 47.42, 5.16 +10.09, 10.00, 52.58, 47.42, 5.16 +10.15, 10.00, 50.06, 49.94, 0.12 +10.15, 10.00, 52.53, 47.47, 5.06 +10.15, 10.00, 52.53, 47.47, 5.06 +10.15, 10.00, 52.53, 47.47, 5.06 +10.15, 10.00, 52.53, 47.47, 5.06 +10.28, 10.00, 47.48, 52.52, -5.03 +10.28, 10.00, 52.43, 47.57, 4.85 +10.28, 10.00, 52.43, 47.57, 4.85 +10.28, 10.00, 52.42, 47.58, 4.85 +10.28, 10.00, 52.42, 47.58, 4.85 +10.35, 10.00, 49.90, 50.10, -0.20 +10.35, 10.00, 52.37, 47.63, 4.74 +10.35, 10.00, 52.37, 47.63, 4.74 +10.35, 10.00, 52.37, 47.63, 4.74 +10.35, 10.00, 52.37, 47.63, 4.74 +10.35, 10.00, 52.37, 47.63, 4.73 +10.35, 10.00, 52.37, 47.63, 4.73 +10.35, 10.00, 52.36, 47.64, 4.73 +10.42, 10.00, 49.84, 50.16, -0.32 +10.42, 10.00, 52.31, 47.69, 4.62 +10.42, 10.00, 52.31, 47.69, 4.62 +10.42, 10.00, 52.31, 47.69, 4.62 +10.42, 10.00, 52.31, 47.69, 4.61 +10.55, 10.00, 47.26, 52.74, -5.48 +10.55, 10.00, 52.20, 47.80, 4.41 +10.55, 10.00, 52.20, 47.80, 4.40 +10.55, 10.00, 52.20, 47.80, 4.40 +10.55, 10.00, 52.20, 47.80, 4.39 +10.55, 10.00, 52.20, 47.80, 4.39 +10.55, 10.00, 52.19, 47.81, 4.39 +10.55, 10.00, 52.19, 47.81, 4.38 +10.55, 10.00, 52.19, 47.81, 4.38 +10.61, 10.00, 49.67, 50.33, -0.67 +10.55, 10.00, 54.66, 45.34, 9.31 +10.55, 10.00, 52.18, 47.82, 4.37 +10.61, 10.00, 49.66, 50.34, -0.68 +10.61, 10.00, 52.13, 47.87, 4.26 +10.61, 10.00, 52.13, 47.87, 4.25 +10.61, 10.00, 52.12, 47.88, 4.25 +10.61, 10.00, 52.12, 47.88, 4.24 +10.68, 10.00, 49.60, 50.40, -0.80 +10.68, 10.00, 52.07, 47.93, 4.13 +10.68, 10.00, 52.06, 47.94, 4.13 +10.81, 10.00, 47.02, 52.98, -5.96 +10.81, 10.00, 51.96, 48.04, 3.92 +10.81, 10.00, 51.96, 48.04, 3.91 +10.81, 10.00, 51.95, 48.05, 3.91 +10.81, 10.00, 51.95, 48.05, 3.90 +10.81, 10.00, 51.95, 48.05, 3.90 +10.81, 10.00, 51.94, 48.06, 3.89 +10.81, 10.00, 51.94, 48.06, 3.88 +10.81, 10.00, 51.94, 48.06, 3.88 +10.81, 10.00, 51.94, 48.06, 3.87 +10.68, 10.00, 56.98, 43.02, 13.95 +10.68, 10.00, 52.03, 47.97, 4.06 +10.81, 10.00, 46.98, 53.02, -6.03 +10.68, 10.00, 56.97, 43.03, 13.94 +10.81, 10.00, 46.98, 53.02, -6.04 +10.81, 10.00, 51.92, 48.08, 3.84 +10.81, 10.00, 51.92, 48.08, 3.83 +10.88, 10.00, 49.39, 50.61, -1.22 +10.88, 10.00, 51.86, 48.14, 3.72 +10.88, 10.00, 51.86, 48.14, 3.71 +10.88, 10.00, 51.85, 48.15, 3.71 +10.94, 10.00, 49.33, 50.67, -1.34 +10.94, 10.00, 51.80, 48.20, 3.59 +10.94, 10.00, 51.79, 48.21, 3.59 +10.94, 10.00, 51.79, 48.21, 3.58 +10.94, 10.00, 51.79, 48.21, 3.57 +10.88, 10.00, 54.30, 45.70, 8.61 +10.88, 10.00, 51.83, 48.17, 3.66 +10.88, 10.00, 51.83, 48.17, 3.65 +10.88, 10.00, 51.82, 48.18, 3.64 +10.88, 10.00, 51.82, 48.18, 3.64 +10.88, 10.00, 51.82, 48.18, 3.63 +10.88, 10.00, 51.81, 48.19, 3.62 +10.88, 10.00, 51.81, 48.19, 3.62 +10.94, 10.00, 49.28, 50.72, -1.43 +10.94, 10.00, 51.75, 48.25, 3.51 +10.94, 10.00, 51.75, 48.25, 3.50 +10.94, 10.00, 51.75, 48.25, 3.49 +10.94, 10.00, 51.74, 48.26, 3.48 +10.94, 10.00, 51.74, 48.26, 3.48 +10.94, 10.00, 51.74, 48.26, 3.47 +11.07, 10.00, 46.69, 53.31, -6.62 +11.07, 10.00, 51.63, 48.37, 3.26 +11.07, 10.00, 51.62, 48.38, 3.25 +11.07, 10.00, 51.62, 48.38, 3.24 +11.07, 10.00, 51.62, 48.38, 3.23 +11.07, 10.00, 51.61, 48.39, 3.22 +11.07, 10.00, 51.61, 48.39, 3.22 +10.94, 10.00, 56.65, 43.35, 13.29 +11.07, 10.00, 46.66, 53.34, -6.69 +10.94, 10.00, 56.64, 43.36, 13.28 +10.94, 10.00, 51.69, 48.31, 3.38 +11.07, 10.00, 46.65, 53.35, -6.71 +10.94, 10.00, 56.63, 43.37, 13.26 +11.07, 10.00, 46.64, 53.36, -6.72 +11.07, 10.00, 51.58, 48.42, 3.16 +11.07, 10.00, 51.57, 48.43, 3.15 +11.07, 10.00, 51.57, 48.43, 3.14 +11.07, 10.00, 51.57, 48.43, 3.13 +11.07, 10.00, 51.56, 48.44, 3.12 +11.14, 10.00, 49.04, 50.96, -1.93 +11.14, 10.00, 51.50, 48.50, 3.01 +11.14, 10.00, 51.50, 48.50, 3.00 +11.14, 10.00, 51.50, 48.50, 2.99 +11.14, 10.00, 51.49, 48.51, 2.98 +11.14, 10.00, 51.49, 48.51, 2.97 +11.14, 10.00, 51.48, 48.52, 2.96 +11.14, 10.00, 51.48, 48.52, 2.96 +11.14, 10.00, 51.47, 48.53, 2.95 +11.14, 10.00, 51.47, 48.53, 2.94 +11.14, 10.00, 51.47, 48.53, 2.93 +11.14, 10.00, 51.46, 48.54, 2.92 +11.14, 10.00, 51.46, 48.54, 2.91 +11.14, 10.00, 51.45, 48.55, 2.90 +11.14, 10.00, 51.45, 48.55, 2.90 +11.14, 10.00, 51.44, 48.56, 2.89 +11.14, 10.00, 51.44, 48.56, 2.88 +11.14, 10.00, 51.44, 48.56, 2.87 +11.14, 10.00, 51.43, 48.57, 2.86 +11.14, 10.00, 51.43, 48.57, 2.85 +11.14, 10.00, 51.42, 48.58, 2.84 +11.21, 10.00, 48.90, 51.10, -2.21 +11.14, 10.00, 53.89, 46.11, 7.77 +11.21, 10.00, 48.89, 51.11, -2.22 +11.21, 10.00, 51.36, 48.64, 2.71 +11.21, 10.00, 51.35, 48.65, 2.70 +11.21, 10.00, 51.35, 48.65, 2.69 +11.21, 10.00, 51.34, 48.66, 2.68 +11.21, 10.00, 51.34, 48.66, 2.67 +11.21, 10.00, 51.33, 48.67, 2.66 +11.21, 10.00, 51.33, 48.67, 2.66 +11.21, 10.00, 51.32, 48.68, 2.65 +11.21, 10.00, 51.32, 48.68, 2.64 +11.21, 10.00, 51.31, 48.69, 2.63 +11.34, 10.00, 46.27, 53.73, -7.47 +11.34, 10.00, 51.21, 48.79, 2.41 +11.34, 10.00, 51.20, 48.80, 2.40 +11.34, 10.00, 51.20, 48.80, 2.39 +11.34, 10.00, 51.19, 48.81, 2.38 +11.34, 10.00, 51.19, 48.81, 2.37 +11.34, 10.00, 51.18, 48.82, 2.36 +11.34, 10.00, 51.18, 48.82, 2.35 +11.34, 10.00, 51.17, 48.83, 2.34 +11.34, 10.00, 51.17, 48.83, 2.33 +11.34, 10.00, 51.16, 48.84, 2.32 +11.34, 10.00, 51.16, 48.84, 2.31 +11.34, 10.00, 51.15, 48.85, 2.30 +11.34, 10.00, 51.15, 48.85, 2.29 +11.34, 10.00, 51.14, 48.86, 2.28 +11.34, 10.00, 51.14, 48.86, 2.27 +11.34, 10.00, 51.13, 48.87, 2.26 +11.34, 10.00, 51.13, 48.87, 2.25 +11.34, 10.00, 51.12, 48.88, 2.24 +11.34, 10.00, 51.12, 48.88, 2.23 +11.34, 10.00, 51.11, 48.89, 2.22 +11.21, 10.00, 56.15, 43.85, 12.30 +11.21, 10.00, 51.20, 48.80, 2.40 +11.21, 10.00, 51.20, 48.80, 2.39 +11.21, 10.00, 51.19, 48.81, 2.38 +11.21, 10.00, 51.19, 48.81, 2.37 +11.14, 10.00, 53.70, 46.30, 7.41 +11.14, 10.00, 51.23, 48.77, 2.45 +11.14, 10.00, 51.22, 48.78, 2.45 +11.14, 10.00, 51.22, 48.78, 2.44 +11.14, 10.00, 51.21, 48.79, 2.43 +11.14, 10.00, 51.21, 48.79, 2.42 +11.14, 10.00, 51.21, 48.79, 2.41 +11.14, 10.00, 51.20, 48.80, 2.40 +11.14, 10.00, 51.20, 48.80, 2.39 +11.14, 10.00, 51.19, 48.81, 2.39 +11.14, 10.00, 51.19, 48.81, 2.38 +11.07, 10.00, 53.71, 46.29, 7.41 +11.07, 10.00, 51.23, 48.77, 2.46 +11.07, 10.00, 51.23, 48.77, 2.45 +11.07, 10.00, 51.22, 48.78, 2.44 +11.07, 10.00, 51.22, 48.78, 2.44 +10.94, 10.00, 56.26, 43.74, 12.51 +10.94, 10.00, 51.31, 48.69, 2.62 +10.94, 10.00, 51.31, 48.69, 2.61 +10.88, 10.00, 53.82, 46.18, 7.65 +10.88, 10.00, 51.35, 48.65, 2.70 +10.88, 10.00, 51.35, 48.65, 2.69 +10.88, 10.00, 51.34, 48.66, 2.69 +10.88, 10.00, 51.34, 48.66, 2.68 +10.81, 10.00, 53.86, 46.14, 7.72 +10.81, 10.00, 51.38, 48.62, 2.77 +10.81, 10.00, 51.38, 48.62, 2.76 +10.81, 10.00, 51.38, 48.62, 2.75 +10.81, 10.00, 51.37, 48.63, 2.75 +10.81, 10.00, 51.37, 48.63, 2.74 +10.68, 10.00, 56.41, 43.59, 12.82 +10.68, 10.00, 51.46, 48.54, 2.93 +10.68, 10.00, 51.46, 48.54, 2.92 +10.61, 10.00, 53.98, 46.02, 7.96 +10.61, 10.00, 51.51, 48.49, 3.01 +10.61, 10.00, 51.50, 48.50, 3.01 +10.55, 10.00, 54.02, 45.98, 8.05 +10.55, 10.00, 51.55, 48.45, 3.10 +10.55, 10.00, 51.55, 48.45, 3.10 +10.55, 10.00, 51.55, 48.45, 3.09 +10.55, 10.00, 51.54, 48.46, 3.09 +10.42, 10.00, 56.58, 43.42, 13.17 +10.42, 10.00, 51.64, 48.36, 3.28 +10.42, 10.00, 51.64, 48.36, 3.28 +10.42, 10.00, 51.64, 48.36, 3.27 +10.35, 10.00, 54.16, 45.84, 8.31 +10.35, 10.00, 51.68, 48.32, 3.37 +10.35, 10.00, 51.68, 48.32, 3.36 +10.35, 10.00, 51.68, 48.32, 3.36 +10.35, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 54.20, 45.80, 8.40 +10.28, 10.00, 51.73, 48.27, 3.45 +10.28, 10.00, 51.73, 48.27, 3.45 +10.28, 10.00, 51.72, 48.28, 3.45 +10.28, 10.00, 51.72, 48.28, 3.45 +10.15, 10.00, 56.77, 43.23, 13.53 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.09, 10.00, 54.34, 45.66, 8.68 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.02, 10.00, 54.39, 45.61, 8.78 +10.09, 10.00, 49.39, 50.61, -1.21 +10.02, 10.00, 54.39, 45.61, 8.77 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +10.02, 10.00, 51.91, 48.09, 3.83 +9.89, 10.00, 56.96, 43.04, 13.91 +9.89, 10.00, 52.01, 47.99, 4.03 +9.89, 10.00, 52.01, 47.99, 4.03 +9.89, 10.00, 52.01, 47.99, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.03 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +10.02, 10.00, 46.98, 53.02, -6.05 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +9.89, 10.00, 56.96, 43.04, 13.92 +9.89, 10.00, 52.02, 47.98, 4.03 +10.02, 10.00, 46.97, 53.03, -6.05 +9.89, 10.00, 56.96, 43.04, 13.92 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.04 +9.89, 10.00, 52.02, 47.98, 4.05 +9.89, 10.00, 52.02, 47.98, 4.05 +9.89, 10.00, 52.02, 47.98, 4.05 +9.89, 10.00, 52.02, 47.98, 4.05 +9.89, 10.00, 52.02, 47.98, 4.05 +9.82, 10.00, 54.55, 45.45, 9.09 +9.82, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 52.08, 47.92, 4.16 +9.82, 10.00, 52.08, 47.92, 4.16 +9.82, 10.00, 52.08, 47.92, 4.16 +9.82, 10.00, 52.08, 47.92, 4.16 +9.82, 10.00, 52.08, 47.92, 4.16 +9.89, 10.00, 49.56, 50.44, -0.88 +9.89, 10.00, 52.03, 47.97, 4.06 +9.89, 10.00, 52.03, 47.97, 4.06 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.03, 47.97, 4.07 +9.89, 10.00, 52.04, 47.96, 4.07 +9.89, 10.00, 52.04, 47.96, 4.07 +9.89, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 54.56, 45.44, 9.12 +9.82, 10.00, 52.09, 47.91, 4.17 +9.82, 10.00, 52.09, 47.91, 4.18 +9.82, 10.00, 52.09, 47.91, 4.18 +9.82, 10.00, 52.09, 47.91, 4.18 +9.82, 10.00, 52.09, 47.91, 4.18 +9.82, 10.00, 52.09, 47.91, 4.18 +9.89, 10.00, 49.57, 50.43, -0.86 +9.89, 10.00, 52.04, 47.96, 4.08 +9.89, 10.00, 52.04, 47.96, 4.08 +9.89, 10.00, 52.04, 47.96, 4.09 +9.89, 10.00, 52.04, 47.96, 4.09 +10.02, 10.00, 47.00, 53.00, -6.00 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.02, 10.00, 51.94, 48.06, 3.89 +10.09, 10.00, 49.42, 50.58, -1.16 +10.09, 10.00, 51.89, 48.11, 3.79 +10.09, 10.00, 51.89, 48.11, 3.78 +10.09, 10.00, 51.89, 48.11, 3.78 +10.09, 10.00, 51.89, 48.11, 3.78 +10.15, 10.00, 49.37, 50.63, -1.26 +10.15, 10.00, 51.84, 48.16, 3.68 +10.15, 10.00, 51.84, 48.16, 3.68 +10.15, 10.00, 51.84, 48.16, 3.68 +10.09, 10.00, 54.36, 45.64, 8.72 +10.15, 10.00, 49.37, 50.63, -1.27 +10.15, 10.00, 51.84, 48.16, 3.68 +10.09, 10.00, 54.36, 45.64, 8.72 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.09, 10.00, 51.89, 48.11, 3.77 +10.15, 10.00, 49.36, 50.64, -1.27 +10.15, 10.00, 51.84, 48.16, 3.67 +10.15, 10.00, 51.83, 48.17, 3.67 +10.15, 10.00, 51.83, 48.17, 3.67 +10.15, 10.00, 51.83, 48.17, 3.67 +10.15, 10.00, 51.83, 48.17, 3.67 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.66 +10.15, 10.00, 51.83, 48.17, 3.65 +10.09, 10.00, 54.35, 45.65, 8.70 +10.09, 10.00, 51.88, 48.12, 3.75 +10.09, 10.00, 51.88, 48.12, 3.75 +10.09, 10.00, 51.88, 48.12, 3.75 +10.09, 10.00, 51.88, 48.12, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.09, 10.00, 51.87, 48.13, 3.75 +10.02, 10.00, 54.39, 45.61, 8.79 +10.02, 10.00, 51.92, 48.08, 3.85 +10.02, 10.00, 51.92, 48.08, 3.85 +10.02, 10.00, 51.92, 48.08, 3.85 +10.02, 10.00, 51.92, 48.08, 3.85 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 51.92, 48.08, 3.84 +10.09, 10.00, 49.40, 50.60, -1.20 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.74 +10.15, 10.00, 49.35, 50.65, -1.30 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.15, 10.00, 51.82, 48.18, 3.64 +10.09, 10.00, 54.34, 45.66, 8.68 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.74 +10.09, 10.00, 51.87, 48.13, 3.73 +10.02, 10.00, 54.39, 45.61, 8.78 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 51.92, 48.08, 3.83 +10.09, 10.00, 49.39, 50.61, -1.21 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.09, 10.00, 51.87, 48.13, 3.73 +10.15, 10.00, 49.34, 50.66, -1.31 +10.15, 10.00, 51.81, 48.19, 3.63 +10.15, 10.00, 51.81, 48.19, 3.63 +10.15, 10.00, 51.81, 48.19, 3.63 +10.15, 10.00, 51.81, 48.19, 3.63 +10.09, 10.00, 54.33, 45.67, 8.67 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 51.86, 48.14, 3.72 +10.15, 10.00, 49.34, 50.66, -1.33 +10.15, 10.00, 51.81, 48.19, 3.62 +10.15, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.60 +10.15, 10.00, 51.80, 48.20, 3.59 +10.15, 10.00, 51.80, 48.20, 3.59 +10.15, 10.00, 51.80, 48.20, 3.59 +10.15, 10.00, 51.80, 48.20, 3.59 +10.28, 10.00, 46.75, 53.25, -6.50 +10.28, 10.00, 51.69, 48.31, 3.39 +10.28, 10.00, 51.69, 48.31, 3.39 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.68, 48.32, 3.37 +10.28, 10.00, 51.68, 48.32, 3.37 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.35 +10.15, 10.00, 56.72, 43.28, 13.44 +10.15, 10.00, 51.77, 48.23, 3.55 +10.15, 10.00, 51.77, 48.23, 3.55 +10.15, 10.00, 51.77, 48.23, 3.55 +10.15, 10.00, 51.77, 48.23, 3.55 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.77, 48.23, 3.53 +10.15, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 54.29, 45.71, 8.57 +10.09, 10.00, 51.81, 48.19, 3.63 +10.09, 10.00, 51.81, 48.19, 3.63 +10.09, 10.00, 51.81, 48.19, 3.63 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 54.33, 45.67, 8.67 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 49.34, 50.66, -1.32 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 54.33, 45.67, 8.66 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +9.89, 10.00, 56.90, 43.10, 13.80 +9.89, 10.00, 51.96, 48.04, 3.91 +9.89, 10.00, 51.96, 48.04, 3.91 +9.89, 10.00, 51.96, 48.04, 3.91 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +10.02, 10.00, 46.92, 53.08, -6.17 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +9.89, 10.00, 56.90, 43.10, 13.81 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.93 +10.02, 10.00, 46.92, 53.08, -6.16 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.09, 10.00, 49.34, 50.66, -1.32 +10.02, 10.00, 54.33, 45.67, 8.67 +10.02, 10.00, 51.86, 48.14, 3.73 +10.02, 10.00, 51.86, 48.14, 3.73 +10.09, 10.00, 49.34, 50.66, -1.32 +10.02, 10.00, 54.33, 45.67, 8.67 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 49.34, 50.66, -1.32 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 54.33, 45.67, 8.66 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 49.34, 50.66, -1.32 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.61 +10.09, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 54.33, 45.67, 8.66 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +9.89, 10.00, 56.90, 43.10, 13.80 +10.02, 10.00, 46.91, 53.09, -6.18 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.86, 48.14, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.02, 10.00, 51.85, 48.15, 3.71 +10.09, 10.00, 49.33, 50.67, -1.33 +10.09, 10.00, 51.80, 48.20, 3.61 +10.09, 10.00, 51.80, 48.20, 3.61 +10.15, 10.00, 49.28, 50.72, -1.44 +10.15, 10.00, 51.75, 48.25, 3.51 +10.15, 10.00, 51.75, 48.25, 3.51 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.15, 10.00, 51.75, 48.25, 3.50 +10.28, 10.00, 46.70, 53.30, -6.59 +10.28, 10.00, 51.65, 48.35, 3.29 +10.28, 10.00, 51.65, 48.35, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.35, 10.00, 49.12, 50.88, -1.76 +10.35, 10.00, 51.59, 48.41, 3.19 +10.35, 10.00, 51.59, 48.41, 3.18 +10.35, 10.00, 51.59, 48.41, 3.18 +10.42, 10.00, 49.07, 50.93, -1.87 +10.35, 10.00, 54.06, 45.94, 8.12 +10.42, 10.00, 49.06, 50.94, -1.87 +10.42, 10.00, 51.53, 48.47, 3.07 +10.42, 10.00, 51.53, 48.47, 3.07 +10.42, 10.00, 51.53, 48.47, 3.06 +10.42, 10.00, 51.53, 48.47, 3.06 +10.42, 10.00, 51.53, 48.47, 3.06 +10.42, 10.00, 51.53, 48.47, 3.05 +10.42, 10.00, 51.53, 48.47, 3.05 +10.55, 10.00, 46.48, 53.52, -7.04 +10.55, 10.00, 51.42, 48.58, 2.84 +10.55, 10.00, 51.42, 48.58, 2.84 +10.55, 10.00, 51.42, 48.58, 2.84 +10.55, 10.00, 51.42, 48.58, 2.83 +10.55, 10.00, 51.41, 48.59, 2.83 +10.55, 10.00, 51.41, 48.59, 2.82 +10.55, 10.00, 51.41, 48.59, 2.82 +10.55, 10.00, 51.41, 48.59, 2.82 +10.55, 10.00, 51.41, 48.59, 2.81 +10.55, 10.00, 51.40, 48.60, 2.81 +10.55, 10.00, 51.40, 48.60, 2.80 +10.55, 10.00, 51.40, 48.60, 2.80 +10.55, 10.00, 51.40, 48.60, 2.80 +10.55, 10.00, 51.40, 48.60, 2.79 +10.55, 10.00, 51.39, 48.61, 2.79 +10.55, 10.00, 51.39, 48.61, 2.78 +10.55, 10.00, 51.39, 48.61, 2.78 +10.55, 10.00, 51.39, 48.61, 2.77 +10.55, 10.00, 51.39, 48.61, 2.77 +10.55, 10.00, 51.38, 48.62, 2.77 +10.55, 10.00, 51.38, 48.62, 2.76 +10.55, 10.00, 51.38, 48.62, 2.76 +10.61, 10.00, 48.86, 51.14, -2.29 +10.61, 10.00, 51.33, 48.67, 2.65 +10.61, 10.00, 51.32, 48.68, 2.65 +10.61, 10.00, 51.32, 48.68, 2.64 +10.61, 10.00, 51.32, 48.68, 2.64 +10.61, 10.00, 51.32, 48.68, 2.63 +10.61, 10.00, 51.31, 48.69, 2.63 +10.55, 10.00, 53.83, 46.17, 7.67 +10.55, 10.00, 51.36, 48.64, 2.72 +10.55, 10.00, 51.36, 48.64, 2.71 +10.55, 10.00, 51.36, 48.64, 2.71 +10.55, 10.00, 51.35, 48.65, 2.71 +10.55, 10.00, 51.35, 48.65, 2.70 +10.55, 10.00, 51.35, 48.65, 2.70 +10.55, 10.00, 51.35, 48.65, 2.69 +10.55, 10.00, 51.34, 48.66, 2.69 +10.55, 10.00, 51.34, 48.66, 2.69 +10.55, 10.00, 51.34, 48.66, 2.68 +10.55, 10.00, 51.34, 48.66, 2.68 +10.55, 10.00, 51.34, 48.66, 2.67 +10.55, 10.00, 51.33, 48.67, 2.67 +10.55, 10.00, 51.33, 48.67, 2.66 +10.55, 10.00, 51.33, 48.67, 2.66 +10.55, 10.00, 51.33, 48.67, 2.66 +10.55, 10.00, 51.33, 48.67, 2.65 +10.55, 10.00, 51.32, 48.68, 2.65 +10.55, 10.00, 51.32, 48.68, 2.64 +10.42, 10.00, 56.36, 43.64, 12.73 +10.42, 10.00, 51.42, 48.58, 2.84 +10.42, 10.00, 51.42, 48.58, 2.83 +10.42, 10.00, 51.41, 48.59, 2.83 +10.35, 10.00, 53.93, 46.07, 7.87 +10.35, 10.00, 51.46, 48.54, 2.92 +10.35, 10.00, 51.46, 48.54, 2.92 +10.35, 10.00, 51.46, 48.54, 2.92 +10.35, 10.00, 51.46, 48.54, 2.92 +10.35, 10.00, 51.46, 48.54, 2.91 +10.35, 10.00, 51.46, 48.54, 2.91 +10.35, 10.00, 51.45, 48.55, 2.91 +10.35, 10.00, 51.45, 48.55, 2.91 +10.35, 10.00, 51.45, 48.55, 2.90 +10.35, 10.00, 51.45, 48.55, 2.90 +10.35, 10.00, 51.45, 48.55, 2.90 +10.35, 10.00, 51.45, 48.55, 2.89 +10.28, 10.00, 53.97, 46.03, 7.94 +10.28, 10.00, 51.49, 48.51, 2.99 +10.28, 10.00, 51.49, 48.51, 2.99 +10.15, 10.00, 56.54, 43.46, 13.07 +10.15, 10.00, 51.59, 48.41, 3.18 +10.15, 10.00, 51.59, 48.41, 3.18 +10.09, 10.00, 54.11, 45.89, 8.22 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 51.64, 48.36, 3.28 +10.02, 10.00, 54.16, 45.84, 8.32 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +10.02, 10.00, 51.69, 48.31, 3.37 +9.89, 10.00, 56.73, 43.27, 13.46 +9.89, 10.00, 51.79, 48.21, 3.57 +9.89, 10.00, 51.79, 48.21, 3.57 +9.82, 10.00, 54.31, 45.69, 8.62 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 51.84, 48.16, 3.69 +9.82, 10.00, 51.84, 48.16, 3.69 +9.82, 10.00, 51.84, 48.16, 3.69 +9.82, 10.00, 51.84, 48.16, 3.69 +9.76, 10.00, 54.37, 45.63, 8.73 +9.76, 10.00, 51.90, 48.10, 3.79 +9.76, 10.00, 51.90, 48.10, 3.79 +9.62, 10.00, 56.94, 43.06, 13.88 +9.62, 10.00, 52.00, 48.00, 4.00 +9.62, 10.00, 52.00, 48.00, 4.00 +9.62, 10.00, 52.00, 48.00, 4.00 +9.56, 10.00, 54.52, 45.48, 9.05 +9.56, 10.00, 52.05, 47.95, 4.11 +9.56, 10.00, 52.06, 47.94, 4.11 +9.56, 10.00, 52.06, 47.94, 4.12 +9.56, 10.00, 52.06, 47.94, 4.12 +9.56, 10.00, 52.06, 47.94, 4.12 +9.56, 10.00, 52.06, 47.94, 4.13 +9.62, 10.00, 49.54, 50.46, -0.91 +9.62, 10.00, 52.02, 47.98, 4.03 +9.62, 10.00, 52.02, 47.98, 4.03 +9.62, 10.00, 52.02, 47.98, 4.04 +9.62, 10.00, 52.02, 47.98, 4.04 +9.62, 10.00, 52.02, 47.98, 4.04 +9.62, 10.00, 52.02, 47.98, 4.05 +9.62, 10.00, 52.02, 47.98, 4.05 +9.62, 10.00, 52.03, 47.97, 4.05 +9.62, 10.00, 52.03, 47.97, 4.05 +9.62, 10.00, 52.03, 47.97, 4.06 +9.56, 10.00, 54.55, 45.45, 9.10 +9.62, 10.00, 49.56, 50.44, -0.88 +9.62, 10.00, 52.03, 47.97, 4.07 +9.62, 10.00, 52.03, 47.97, 4.07 +9.62, 10.00, 52.04, 47.96, 4.07 +9.62, 10.00, 52.04, 47.96, 4.07 +9.62, 10.00, 52.04, 47.96, 4.08 +9.62, 10.00, 52.04, 47.96, 4.08 +9.62, 10.00, 52.04, 47.96, 4.08 +9.62, 10.00, 52.04, 47.96, 4.09 +9.62, 10.00, 52.04, 47.96, 4.09 +9.62, 10.00, 52.05, 47.95, 4.09 +9.62, 10.00, 52.05, 47.95, 4.09 +9.62, 10.00, 52.05, 47.95, 4.10 +9.62, 10.00, 52.05, 47.95, 4.10 +9.62, 10.00, 52.05, 47.95, 4.10 +9.62, 10.00, 52.05, 47.95, 4.11 +9.62, 10.00, 52.05, 47.95, 4.11 +9.62, 10.00, 52.06, 47.94, 4.11 +9.62, 10.00, 52.06, 47.94, 4.11 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.13 +9.76, 10.00, 47.02, 52.98, -5.96 +9.76, 10.00, 51.97, 48.03, 3.93 +9.76, 10.00, 51.97, 48.03, 3.93 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.94 +9.76, 10.00, 51.97, 48.03, 3.95 +9.76, 10.00, 51.97, 48.03, 3.95 +9.76, 10.00, 51.97, 48.03, 3.95 +9.76, 10.00, 51.98, 48.02, 3.95 +9.62, 10.00, 57.02, 42.98, 14.04 +9.76, 10.00, 47.03, 52.97, -5.93 +9.76, 10.00, 51.98, 48.02, 3.96 +9.76, 10.00, 51.98, 48.02, 3.96 +9.76, 10.00, 51.98, 48.02, 3.96 +9.76, 10.00, 51.98, 48.02, 3.96 +9.82, 10.00, 49.46, 50.54, -1.08 +9.82, 10.00, 51.93, 48.07, 3.87 +9.82, 10.00, 51.93, 48.07, 3.87 +9.82, 10.00, 51.94, 48.06, 3.87 +9.82, 10.00, 51.94, 48.06, 3.87 +9.82, 10.00, 51.94, 48.06, 3.87 +9.82, 10.00, 51.94, 48.06, 3.87 +9.82, 10.00, 51.94, 48.06, 3.88 +9.82, 10.00, 51.94, 48.06, 3.88 +9.82, 10.00, 51.94, 48.06, 3.88 +9.82, 10.00, 51.94, 48.06, 3.88 +9.82, 10.00, 51.94, 48.06, 3.88 +9.76, 10.00, 54.46, 45.54, 8.93 +9.76, 10.00, 51.99, 48.01, 3.98 +9.76, 10.00, 51.99, 48.01, 3.99 +9.76, 10.00, 51.99, 48.01, 3.99 +9.76, 10.00, 51.99, 48.01, 3.99 +9.76, 10.00, 52.00, 48.00, 3.99 +9.82, 10.00, 49.47, 50.53, -1.05 +9.82, 10.00, 51.95, 48.05, 3.89 +9.82, 10.00, 51.95, 48.05, 3.90 +9.82, 10.00, 51.95, 48.05, 3.90 +9.89, 10.00, 49.43, 50.57, -1.14 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +10.02, 10.00, 46.86, 53.14, -6.27 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.09, 10.00, 49.29, 50.71, -1.43 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.76, 48.24, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.51 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.50 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.09, 10.00, 51.75, 48.25, 3.49 +10.02, 10.00, 54.27, 45.73, 8.53 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +10.02, 10.00, 51.79, 48.21, 3.59 +9.89, 10.00, 56.84, 43.16, 13.67 +10.02, 10.00, 46.85, 53.15, -6.30 +9.89, 10.00, 56.84, 43.16, 13.67 +9.89, 10.00, 51.89, 48.11, 3.79 +9.89, 10.00, 51.89, 48.11, 3.79 +9.89, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 54.42, 45.58, 8.83 +9.89, 10.00, 49.42, 50.58, -1.15 +9.89, 10.00, 51.90, 48.10, 3.79 +9.89, 10.00, 51.90, 48.10, 3.79 +9.89, 10.00, 51.90, 48.10, 3.79 +9.89, 10.00, 51.90, 48.10, 3.79 +10.02, 10.00, 46.85, 53.15, -6.29 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +10.02, 10.00, 51.80, 48.20, 3.60 +9.89, 10.00, 56.84, 43.16, 13.68 +9.89, 10.00, 51.90, 48.10, 3.79 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.80 +9.82, 10.00, 54.42, 45.58, 8.84 +9.82, 10.00, 51.95, 48.05, 3.90 +9.82, 10.00, 51.95, 48.05, 3.90 +9.82, 10.00, 51.95, 48.05, 3.90 +9.89, 10.00, 49.43, 50.57, -1.14 +9.89, 10.00, 51.90, 48.10, 3.80 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +10.02, 10.00, 46.86, 53.14, -6.28 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +10.02, 10.00, 51.80, 48.20, 3.61 +9.89, 10.00, 56.85, 43.15, 13.69 +9.89, 10.00, 51.90, 48.10, 3.81 +9.89, 10.00, 51.90, 48.10, 3.81 +9.82, 10.00, 54.43, 45.57, 8.85 +9.82, 10.00, 51.95, 48.05, 3.91 +9.82, 10.00, 51.96, 48.04, 3.91 +9.82, 10.00, 51.96, 48.04, 3.91 +9.82, 10.00, 51.96, 48.04, 3.91 +9.89, 10.00, 49.44, 50.56, -1.13 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +10.02, 10.00, 46.87, 53.13, -6.27 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +9.89, 10.00, 56.85, 43.15, 13.70 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.82, 10.00, 54.43, 45.57, 8.86 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.93 +9.82, 10.00, 51.96, 48.04, 3.93 +9.89, 10.00, 49.44, 50.56, -1.11 +9.89, 10.00, 51.91, 48.09, 3.83 +9.89, 10.00, 51.92, 48.08, 3.83 +10.02, 10.00, 46.87, 53.13, -6.25 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +9.89, 10.00, 56.86, 43.14, 13.72 +9.89, 10.00, 51.92, 48.08, 3.83 +9.89, 10.00, 51.92, 48.08, 3.83 +9.89, 10.00, 51.92, 48.08, 3.83 +9.82, 10.00, 54.44, 45.56, 8.88 +9.82, 10.00, 51.97, 48.03, 3.93 +9.82, 10.00, 51.97, 48.03, 3.94 +9.82, 10.00, 51.97, 48.03, 3.94 +9.82, 10.00, 51.97, 48.03, 3.94 +9.89, 10.00, 49.45, 50.55, -1.10 +9.89, 10.00, 51.92, 48.08, 3.84 +9.89, 10.00, 51.92, 48.08, 3.84 +9.89, 10.00, 51.92, 48.08, 3.84 +10.02, 10.00, 46.88, 53.12, -6.24 +10.02, 10.00, 51.82, 48.18, 3.65 +10.02, 10.00, 51.82, 48.18, 3.65 +10.02, 10.00, 51.82, 48.18, 3.65 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +9.89, 10.00, 56.87, 43.13, 13.73 +10.02, 10.00, 46.88, 53.12, -6.24 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.02, 10.00, 51.82, 48.18, 3.64 +10.09, 10.00, 49.30, 50.70, -1.40 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 49.25, 50.75, -1.51 +10.15, 10.00, 51.72, 48.28, 3.43 +10.15, 10.00, 51.72, 48.28, 3.43 +10.15, 10.00, 51.72, 48.28, 3.43 +10.28, 10.00, 46.67, 53.33, -6.66 +10.28, 10.00, 51.61, 48.39, 3.23 +10.28, 10.00, 51.61, 48.39, 3.23 +10.28, 10.00, 51.61, 48.39, 3.23 +10.28, 10.00, 51.61, 48.39, 3.22 +10.28, 10.00, 51.61, 48.39, 3.22 +10.28, 10.00, 51.61, 48.39, 3.22 +10.28, 10.00, 51.61, 48.39, 3.22 +10.28, 10.00, 51.61, 48.39, 3.21 +10.28, 10.00, 51.61, 48.39, 3.21 +10.28, 10.00, 51.61, 48.39, 3.21 +10.28, 10.00, 51.60, 48.40, 3.21 +10.28, 10.00, 51.60, 48.40, 3.21 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.20 +10.28, 10.00, 51.60, 48.40, 3.19 +10.35, 10.00, 49.07, 50.93, -1.85 +10.35, 10.00, 51.54, 48.46, 3.09 +10.35, 10.00, 51.54, 48.46, 3.09 +10.35, 10.00, 51.54, 48.46, 3.08 +10.35, 10.00, 51.54, 48.46, 3.08 +10.35, 10.00, 51.54, 48.46, 3.08 +10.35, 10.00, 51.54, 48.46, 3.08 +10.35, 10.00, 51.54, 48.46, 3.07 +10.28, 10.00, 54.06, 45.94, 8.11 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.15 +10.15, 10.00, 56.62, 43.38, 13.24 +10.15, 10.00, 51.67, 48.33, 3.35 +10.15, 10.00, 51.67, 48.33, 3.35 +10.15, 10.00, 51.67, 48.33, 3.35 +10.15, 10.00, 51.67, 48.33, 3.35 +10.15, 10.00, 51.67, 48.33, 3.34 +10.15, 10.00, 51.67, 48.33, 3.34 +10.15, 10.00, 51.67, 48.33, 3.34 +10.09, 10.00, 54.19, 45.81, 8.38 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 51.72, 48.28, 3.44 +10.02, 10.00, 54.24, 45.76, 8.48 +10.02, 10.00, 51.77, 48.23, 3.53 +10.02, 10.00, 51.77, 48.23, 3.53 +10.02, 10.00, 51.77, 48.23, 3.53 +10.02, 10.00, 51.77, 48.23, 3.53 +9.89, 10.00, 56.81, 43.19, 13.62 +9.89, 10.00, 51.87, 48.13, 3.73 +9.89, 10.00, 51.87, 48.13, 3.73 +9.89, 10.00, 51.87, 48.13, 3.73 +9.82, 10.00, 54.39, 45.61, 8.78 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.84 +9.82, 10.00, 51.92, 48.08, 3.85 +9.82, 10.00, 51.92, 48.08, 3.85 +9.82, 10.00, 51.92, 48.08, 3.85 +9.82, 10.00, 51.92, 48.08, 3.85 +9.76, 10.00, 54.45, 45.55, 8.89 +9.76, 10.00, 51.98, 48.02, 3.95 +9.76, 10.00, 51.98, 48.02, 3.95 +9.62, 10.00, 57.02, 42.98, 14.04 +9.62, 10.00, 52.08, 47.92, 4.16 +9.62, 10.00, 52.08, 47.92, 4.16 +9.62, 10.00, 52.08, 47.92, 4.16 +9.62, 10.00, 52.08, 47.92, 4.17 +9.62, 10.00, 52.08, 47.92, 4.17 +9.62, 10.00, 52.09, 47.91, 4.17 +9.62, 10.00, 52.09, 47.91, 4.17 +9.62, 10.00, 52.09, 47.91, 4.18 +9.62, 10.00, 52.09, 47.91, 4.18 +9.62, 10.00, 52.09, 47.91, 4.18 +9.62, 10.00, 52.09, 47.91, 4.19 +9.62, 10.00, 52.09, 47.91, 4.19 +9.62, 10.00, 52.10, 47.90, 4.19 +9.62, 10.00, 52.10, 47.90, 4.19 +9.56, 10.00, 54.62, 45.38, 9.24 +9.56, 10.00, 52.15, 47.85, 4.30 +9.56, 10.00, 52.15, 47.85, 4.30 +9.49, 10.00, 54.67, 45.33, 9.35 +9.56, 10.00, 49.68, 50.32, -0.63 +9.56, 10.00, 52.16, 47.84, 4.31 +9.49, 10.00, 54.68, 45.32, 9.36 +9.56, 10.00, 49.69, 50.31, -0.62 +9.49, 10.00, 54.68, 45.32, 9.37 +9.56, 10.00, 49.69, 50.31, -0.62 +9.56, 10.00, 52.17, 47.83, 4.33 +9.56, 10.00, 52.17, 47.83, 4.33 +9.56, 10.00, 52.17, 47.83, 4.34 +9.62, 10.00, 49.65, 50.35, -0.70 +9.62, 10.00, 52.12, 47.88, 4.24 +9.62, 10.00, 52.12, 47.88, 4.25 +9.62, 10.00, 52.12, 47.88, 4.25 +9.56, 10.00, 54.65, 45.35, 9.30 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.37 +9.56, 10.00, 52.18, 47.82, 4.37 +9.56, 10.00, 52.19, 47.81, 4.37 +9.56, 10.00, 52.19, 47.81, 4.38 +9.56, 10.00, 52.19, 47.81, 4.38 +9.56, 10.00, 52.19, 47.81, 4.38 +9.62, 10.00, 49.67, 50.33, -0.66 +9.62, 10.00, 52.14, 47.86, 4.29 +9.62, 10.00, 52.15, 47.85, 4.29 +9.76, 10.00, 47.10, 52.90, -5.79 +9.76, 10.00, 52.05, 47.95, 4.10 +9.82, 10.00, 49.53, 50.47, -0.94 +9.82, 10.00, 52.00, 48.00, 4.00 +9.82, 10.00, 52.00, 48.00, 4.00 +9.82, 10.00, 52.00, 48.00, 4.00 +9.82, 10.00, 52.00, 48.00, 4.01 +9.82, 10.00, 52.00, 48.00, 4.01 +9.82, 10.00, 52.00, 48.00, 4.01 +9.82, 10.00, 52.00, 48.00, 4.01 +9.82, 10.00, 52.01, 47.99, 4.01 +9.82, 10.00, 52.01, 47.99, 4.01 +9.82, 10.00, 52.01, 47.99, 4.01 +9.82, 10.00, 52.01, 47.99, 4.01 +9.82, 10.00, 52.01, 47.99, 4.02 +9.82, 10.00, 52.01, 47.99, 4.02 +9.89, 10.00, 49.49, 50.51, -1.02 +9.89, 10.00, 51.96, 48.04, 3.92 +9.89, 10.00, 51.96, 48.04, 3.92 +10.02, 10.00, 46.92, 53.08, -6.16 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.02, 10.00, 51.86, 48.14, 3.72 +10.09, 10.00, 49.34, 50.66, -1.32 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 51.81, 48.19, 3.61 +10.09, 10.00, 51.81, 48.19, 3.61 +10.15, 10.00, 49.29, 50.71, -1.43 +10.15, 10.00, 51.76, 48.24, 3.51 +10.15, 10.00, 51.76, 48.24, 3.51 +10.15, 10.00, 51.76, 48.24, 3.51 +10.28, 10.00, 46.71, 53.29, -6.58 +10.28, 10.00, 51.65, 48.35, 3.31 +10.28, 10.00, 51.65, 48.35, 3.31 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.30 +10.28, 10.00, 51.65, 48.35, 3.29 +10.28, 10.00, 51.65, 48.35, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.27 +10.28, 10.00, 51.64, 48.36, 3.27 +10.28, 10.00, 51.64, 48.36, 3.27 +10.35, 10.00, 49.11, 50.89, -1.78 +10.35, 10.00, 51.58, 48.42, 3.17 +10.35, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 51.58, 48.42, 3.15 +10.35, 10.00, 51.58, 48.42, 3.15 +10.35, 10.00, 51.57, 48.43, 3.15 +10.35, 10.00, 51.57, 48.43, 3.15 +10.35, 10.00, 51.57, 48.43, 3.14 +10.28, 10.00, 54.09, 45.91, 8.18 +10.28, 10.00, 51.62, 48.38, 3.24 +10.28, 10.00, 51.62, 48.38, 3.24 +10.28, 10.00, 51.62, 48.38, 3.23 +10.28, 10.00, 51.62, 48.38, 3.23 +10.35, 10.00, 49.09, 50.91, -1.81 +10.35, 10.00, 51.56, 48.44, 3.13 +10.35, 10.00, 51.56, 48.44, 3.12 +10.35, 10.00, 51.56, 48.44, 3.12 +10.35, 10.00, 51.56, 48.44, 3.12 +10.35, 10.00, 51.56, 48.44, 3.12 +10.35, 10.00, 51.56, 48.44, 3.11 +10.35, 10.00, 51.56, 48.44, 3.11 +10.35, 10.00, 51.55, 48.45, 3.11 +10.35, 10.00, 51.55, 48.45, 3.11 +10.35, 10.00, 51.55, 48.45, 3.10 +10.35, 10.00, 51.55, 48.45, 3.10 +10.35, 10.00, 51.55, 48.45, 3.10 +10.35, 10.00, 51.55, 48.45, 3.10 +10.35, 10.00, 51.55, 48.45, 3.09 +10.35, 10.00, 51.55, 48.45, 3.09 +10.28, 10.00, 54.07, 45.93, 8.13 +10.28, 10.00, 51.59, 48.41, 3.18 +10.35, 10.00, 49.07, 50.93, -1.86 +10.28, 10.00, 54.06, 45.94, 8.12 +10.28, 10.00, 51.59, 48.41, 3.18 +10.28, 10.00, 51.59, 48.41, 3.18 +10.28, 10.00, 51.59, 48.41, 3.17 +10.28, 10.00, 51.59, 48.41, 3.17 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.17 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.28, 10.00, 51.58, 48.42, 3.16 +10.35, 10.00, 49.06, 50.94, -1.89 +10.35, 10.00, 51.53, 48.47, 3.05 +10.35, 10.00, 51.53, 48.47, 3.05 +10.35, 10.00, 51.52, 48.48, 3.05 +10.35, 10.00, 51.52, 48.48, 3.05 +10.35, 10.00, 51.52, 48.48, 3.04 +10.35, 10.00, 51.52, 48.48, 3.04 +10.35, 10.00, 51.52, 48.48, 3.04 +10.35, 10.00, 51.52, 48.48, 3.04 +10.28, 10.00, 54.04, 45.96, 8.08 +10.28, 10.00, 51.57, 48.43, 3.13 +10.28, 10.00, 51.56, 48.44, 3.13 +10.28, 10.00, 51.56, 48.44, 3.13 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.12 +10.28, 10.00, 51.56, 48.44, 3.11 +10.28, 10.00, 51.56, 48.44, 3.11 +10.28, 10.00, 51.55, 48.45, 3.11 +10.28, 10.00, 51.55, 48.45, 3.11 +10.28, 10.00, 51.55, 48.45, 3.11 +10.28, 10.00, 51.55, 48.45, 3.10 +10.28, 10.00, 51.55, 48.45, 3.10 +10.15, 10.00, 56.59, 43.41, 13.19 +10.28, 10.00, 46.61, 53.39, -6.79 +10.15, 10.00, 56.59, 43.41, 13.18 +10.15, 10.00, 51.65, 48.35, 3.29 +10.15, 10.00, 51.65, 48.35, 3.29 +10.15, 10.00, 51.65, 48.35, 3.29 +10.15, 10.00, 51.65, 48.35, 3.29 +10.15, 10.00, 51.64, 48.36, 3.29 +10.15, 10.00, 51.64, 48.36, 3.29 +10.15, 10.00, 51.64, 48.36, 3.29 +10.15, 10.00, 51.64, 48.36, 3.29 +10.15, 10.00, 51.64, 48.36, 3.28 +10.15, 10.00, 51.64, 48.36, 3.28 +10.09, 10.00, 54.16, 45.84, 8.33 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.09, 10.00, 51.69, 48.31, 3.38 +10.02, 10.00, 54.21, 45.79, 8.42 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.48 +10.02, 10.00, 51.74, 48.26, 3.47 +10.02, 10.00, 51.74, 48.26, 3.47 +10.02, 10.00, 51.74, 48.26, 3.47 +10.02, 10.00, 51.74, 48.26, 3.47 +9.89, 10.00, 56.78, 43.22, 13.56 +9.89, 10.00, 51.84, 48.16, 3.67 +9.89, 10.00, 51.84, 48.16, 3.67 +9.89, 10.00, 51.84, 48.16, 3.68 +9.82, 10.00, 54.36, 45.64, 8.72 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.78 +9.82, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 51.89, 48.11, 3.79 +9.82, 10.00, 51.90, 48.10, 3.79 +9.82, 10.00, 51.90, 48.10, 3.79 +9.82, 10.00, 51.90, 48.10, 3.79 +9.82, 10.00, 51.90, 48.10, 3.79 +9.76, 10.00, 54.42, 45.58, 8.84 +9.76, 10.00, 51.95, 48.05, 3.90 +9.76, 10.00, 51.95, 48.05, 3.90 +9.76, 10.00, 51.95, 48.05, 3.90 +9.76, 10.00, 51.95, 48.05, 3.90 +9.62, 10.00, 57.00, 43.00, 13.99 +9.62, 10.00, 52.05, 47.95, 4.11 +9.62, 10.00, 52.05, 47.95, 4.11 +9.62, 10.00, 52.06, 47.94, 4.11 +9.62, 10.00, 52.06, 47.94, 4.11 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.12 +9.62, 10.00, 52.06, 47.94, 4.13 +9.62, 10.00, 52.06, 47.94, 4.13 +9.62, 10.00, 52.07, 47.93, 4.13 +9.62, 10.00, 52.07, 47.93, 4.13 +9.62, 10.00, 52.07, 47.93, 4.14 +9.62, 10.00, 52.07, 47.93, 4.14 +9.62, 10.00, 52.07, 47.93, 4.14 +9.62, 10.00, 52.07, 47.93, 4.15 +9.62, 10.00, 52.07, 47.93, 4.15 +9.62, 10.00, 52.08, 47.92, 4.15 +9.62, 10.00, 52.08, 47.92, 4.15 +9.62, 10.00, 52.08, 47.92, 4.16 +9.56, 10.00, 54.60, 45.40, 9.20 +9.56, 10.00, 52.13, 47.87, 4.26 +9.56, 10.00, 52.13, 47.87, 4.27 +9.56, 10.00, 52.13, 47.87, 4.27 +9.56, 10.00, 52.14, 47.86, 4.27 +9.56, 10.00, 52.14, 47.86, 4.28 +9.56, 10.00, 52.14, 47.86, 4.28 +9.56, 10.00, 52.14, 47.86, 4.28 +9.56, 10.00, 52.14, 47.86, 4.29 +9.56, 10.00, 52.14, 47.86, 4.29 +9.56, 10.00, 52.15, 47.85, 4.29 +9.56, 10.00, 52.15, 47.85, 4.30 +9.56, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 49.63, 50.37, -0.74 +9.62, 10.00, 52.10, 47.90, 4.21 +9.56, 10.00, 54.63, 45.37, 9.25 +9.62, 10.00, 49.63, 50.37, -0.73 +9.62, 10.00, 52.11, 47.89, 4.21 +9.62, 10.00, 52.11, 47.89, 4.22 +9.62, 10.00, 52.11, 47.89, 4.22 +9.56, 10.00, 54.63, 45.37, 9.27 +9.56, 10.00, 52.16, 47.84, 4.33 +9.56, 10.00, 52.16, 47.84, 4.33 +9.56, 10.00, 52.17, 47.83, 4.33 +9.56, 10.00, 52.17, 47.83, 4.34 +9.56, 10.00, 52.17, 47.83, 4.34 +9.56, 10.00, 52.17, 47.83, 4.34 +9.56, 10.00, 52.17, 47.83, 4.35 +9.56, 10.00, 52.17, 47.83, 4.35 +9.56, 10.00, 52.18, 47.82, 4.35 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.36 +9.56, 10.00, 52.18, 47.82, 4.36 +9.62, 10.00, 49.66, 50.34, -0.68 +9.62, 10.00, 52.13, 47.87, 4.27 +9.62, 10.00, 52.14, 47.86, 4.27 +9.62, 10.00, 52.14, 47.86, 4.27 +9.62, 10.00, 52.14, 47.86, 4.28 +9.76, 10.00, 47.10, 52.90, -5.81 +9.76, 10.00, 52.04, 47.96, 4.08 +9.76, 10.00, 52.04, 47.96, 4.08 +9.76, 10.00, 52.04, 47.96, 4.09 +9.62, 10.00, 57.09, 42.91, 14.18 +9.62, 10.00, 52.15, 47.85, 4.29 +9.62, 10.00, 52.15, 47.85, 4.29 +9.62, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 52.15, 47.85, 4.30 +9.62, 10.00, 52.15, 47.85, 4.31 +9.62, 10.00, 52.15, 47.85, 4.31 +9.62, 10.00, 52.16, 47.84, 4.31 +9.62, 10.00, 52.16, 47.84, 4.32 +9.76, 10.00, 47.12, 52.88, -5.77 +9.76, 10.00, 52.06, 47.94, 4.12 +9.76, 10.00, 52.06, 47.94, 4.12 +9.76, 10.00, 52.06, 47.94, 4.13 +9.82, 10.00, 49.54, 50.46, -0.92 +9.82, 10.00, 52.01, 47.99, 4.03 +9.82, 10.00, 52.02, 47.98, 4.03 +9.82, 10.00, 52.02, 47.98, 4.03 +9.82, 10.00, 52.02, 47.98, 4.03 +9.82, 10.00, 52.02, 47.98, 4.03 +9.82, 10.00, 52.02, 47.98, 4.04 +9.82, 10.00, 52.02, 47.98, 4.04 +9.82, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 54.54, 45.46, 9.08 +9.76, 10.00, 52.07, 47.93, 4.14 +9.76, 10.00, 52.07, 47.93, 4.14 +9.76, 10.00, 52.07, 47.93, 4.14 +9.76, 10.00, 52.07, 47.93, 4.15 +9.76, 10.00, 52.07, 47.93, 4.15 +9.76, 10.00, 52.07, 47.93, 4.15 +9.76, 10.00, 52.08, 47.92, 4.15 +9.82, 10.00, 49.56, 50.44, -0.89 +9.82, 10.00, 52.03, 47.97, 4.06 +9.82, 10.00, 52.03, 47.97, 4.06 +9.82, 10.00, 52.03, 47.97, 4.06 +9.82, 10.00, 52.03, 47.97, 4.06 +9.89, 10.00, 49.51, 50.49, -0.98 +9.82, 10.00, 54.50, 45.50, 9.01 +9.89, 10.00, 49.51, 50.49, -0.98 +9.89, 10.00, 51.98, 48.02, 3.96 +9.89, 10.00, 51.98, 48.02, 3.97 +9.82, 10.00, 54.50, 45.50, 9.01 +9.89, 10.00, 49.51, 50.49, -0.98 +9.82, 10.00, 54.51, 45.49, 9.01 +9.82, 10.00, 52.03, 47.97, 4.07 +9.82, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 52.04, 47.96, 4.07 +9.82, 10.00, 52.04, 47.96, 4.08 +9.82, 10.00, 52.04, 47.96, 4.08 +9.82, 10.00, 52.04, 47.96, 4.08 +9.89, 10.00, 49.52, 50.48, -0.96 +9.89, 10.00, 51.99, 48.01, 3.98 +9.89, 10.00, 51.99, 48.01, 3.98 +9.89, 10.00, 51.99, 48.01, 3.98 +10.02, 10.00, 46.95, 53.05, -6.10 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.02, 10.00, 51.89, 48.11, 3.78 +10.09, 10.00, 49.37, 50.63, -1.26 +10.09, 10.00, 51.84, 48.16, 3.68 +10.09, 10.00, 51.84, 48.16, 3.68 +10.15, 10.00, 49.32, 50.68, -1.36 +10.15, 10.00, 51.79, 48.21, 3.58 +10.15, 10.00, 51.79, 48.21, 3.58 +10.15, 10.00, 51.79, 48.21, 3.58 +10.28, 10.00, 46.75, 53.25, -6.51 +10.28, 10.00, 51.69, 48.31, 3.38 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.69, 48.31, 3.37 +10.28, 10.00, 51.68, 48.32, 3.37 +10.28, 10.00, 51.68, 48.32, 3.37 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.36 +10.28, 10.00, 51.68, 48.32, 3.35 +10.28, 10.00, 51.68, 48.32, 3.35 +10.28, 10.00, 51.67, 48.33, 3.35 +10.28, 10.00, 51.67, 48.33, 3.35 +10.35, 10.00, 49.15, 50.85, -1.70 +10.35, 10.00, 51.62, 48.38, 3.24 +10.35, 10.00, 51.62, 48.38, 3.24 +10.42, 10.00, 49.10, 50.90, -1.81 +10.42, 10.00, 51.57, 48.43, 3.13 +10.42, 10.00, 51.57, 48.43, 3.13 +10.42, 10.00, 51.56, 48.44, 3.13 +10.42, 10.00, 51.56, 48.44, 3.13 +10.42, 10.00, 51.56, 48.44, 3.12 +10.42, 10.00, 51.56, 48.44, 3.12 +10.42, 10.00, 51.56, 48.44, 3.12 +10.42, 10.00, 51.56, 48.44, 3.11 +10.42, 10.00, 51.56, 48.44, 3.11 +10.35, 10.00, 54.08, 45.92, 8.15 +10.35, 10.00, 51.60, 48.40, 3.20 +10.35, 10.00, 51.60, 48.40, 3.20 +10.35, 10.00, 51.60, 48.40, 3.20 +10.35, 10.00, 51.60, 48.40, 3.20 +10.35, 10.00, 51.60, 48.40, 3.19 +10.28, 10.00, 54.12, 45.88, 8.23 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.29 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.28, 10.00, 51.64, 48.36, 3.28 +10.35, 10.00, 49.11, 50.89, -1.77 +10.35, 10.00, 51.59, 48.41, 3.17 +10.28, 10.00, 54.11, 45.89, 8.21 +10.35, 10.00, 49.11, 50.89, -1.78 +10.28, 10.00, 54.10, 45.90, 8.21 +10.28, 10.00, 51.63, 48.37, 3.26 +10.28, 10.00, 51.63, 48.37, 3.26 +10.28, 10.00, 51.63, 48.37, 3.26 +10.28, 10.00, 51.63, 48.37, 3.25 +10.15, 10.00, 56.67, 43.33, 13.34 +10.15, 10.00, 51.72, 48.28, 3.45 +10.15, 10.00, 51.72, 48.28, 3.45 +10.09, 10.00, 54.25, 45.75, 8.49 +10.09, 10.00, 51.77, 48.23, 3.55 +10.09, 10.00, 51.77, 48.23, 3.55 +10.09, 10.00, 51.77, 48.23, 3.55 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.09, 10.00, 51.77, 48.23, 3.54 +10.15, 10.00, 49.25, 50.75, -1.50 +10.15, 10.00, 51.72, 48.28, 3.44 +10.15, 10.00, 51.72, 48.28, 3.44 +10.15, 10.00, 51.72, 48.28, 3.44 +10.15, 10.00, 51.72, 48.28, 3.44 +10.15, 10.00, 51.72, 48.28, 3.44 +10.09, 10.00, 54.24, 45.76, 8.48 +10.09, 10.00, 51.77, 48.23, 3.53 +10.09, 10.00, 51.77, 48.23, 3.53 +10.09, 10.00, 51.77, 48.23, 3.53 +10.02, 10.00, 54.29, 45.71, 8.58 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.02, 10.00, 51.82, 48.18, 3.63 +10.09, 10.00, 49.29, 50.71, -1.41 +10.09, 10.00, 51.77, 48.23, 3.53 +10.09, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 51.76, 48.24, 3.53 +10.15, 10.00, 49.24, 50.76, -1.52 +10.09, 10.00, 54.24, 45.76, 8.47 +10.09, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 51.76, 48.24, 3.53 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.02, 10.00, 54.28, 45.72, 8.57 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.02, 10.00, 51.81, 48.19, 3.62 +10.09, 10.00, 49.29, 50.71, -1.42 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.09, 10.00, 51.76, 48.24, 3.52 +10.02, 10.00, 54.28, 45.72, 8.56 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +10.02, 10.00, 51.81, 48.19, 3.61 +9.89, 10.00, 56.85, 43.15, 13.70 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.81 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.89, 10.00, 51.91, 48.09, 3.82 +9.82, 10.00, 54.43, 45.57, 8.86 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.92 +9.82, 10.00, 51.96, 48.04, 3.93 +9.82, 10.00, 51.96, 48.04, 3.93 +9.82, 10.00, 51.96, 48.04, 3.93 +9.82, 10.00, 51.96, 48.04, 3.93 +9.76, 10.00, 54.49, 45.51, 8.97 +9.76, 10.00, 52.02, 47.98, 4.03 +9.76, 10.00, 52.02, 47.98, 4.03 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.04 +9.76, 10.00, 52.02, 47.98, 4.05 +9.76, 10.00, 52.02, 47.98, 4.05 +9.76, 10.00, 52.03, 47.97, 4.05 +9.76, 10.00, 52.03, 47.97, 4.05 +9.76, 10.00, 52.03, 47.97, 4.05 +9.76, 10.00, 52.03, 47.97, 4.06 +9.76, 10.00, 52.03, 47.97, 4.06 +9.76, -10.00, 25.00, 75.00, -50.00 +9.76, -10.00, 36.88, 63.12, -26.24 +9.76, -10.00, 36.81, 63.19, -26.39 +9.76, -10.00, 36.73, 63.27, -26.54 +9.76, -10.00, 36.66, 63.34, -26.68 +9.62, -10.00, 41.63, 58.37, -16.75 +9.62, -10.00, 36.61, 63.39, -26.78 +9.62, -10.00, 36.54, 63.46, -26.93 +9.62, -10.00, 36.46, 63.54, -27.07 +9.62, -10.00, 36.39, 63.61, -27.22 +9.62, -10.00, 36.32, 63.68, -27.37 +9.62, -10.00, 36.24, 63.76, -27.52 +9.56, -10.00, 38.69, 61.31, -22.62 +9.49, -10.00, 38.67, 61.33, -22.67 +9.49, -10.00, 36.12, 63.88, -27.76 +9.36, -10.00, 41.09, 58.91, -17.82 +9.29, -10.00, 38.60, 61.40, -22.81 +9.23, -10.00, 38.57, 61.43, -22.85 +9.10, -10.00, 41.07, 58.93, -17.85 +9.03, -10.00, 38.58, 61.42, -22.84 +8.96, -10.00, 38.56, 61.44, -22.88 +8.83, -10.00, 41.06, 58.94, -17.88 +8.70, -10.00, 41.09, 58.91, -17.83 +8.57, -10.00, 41.12, 58.88, -17.77 +8.44, -10.00, 41.15, 58.85, -17.71 +8.31, -10.00, 41.18, 58.82, -17.65 +8.17, -10.00, 41.21, 58.79, -17.59 +8.04, -10.00, 41.24, 58.76, -17.52 +7.91, -10.00, 41.27, 58.73, -17.46 +7.71, -10.00, 43.82, 56.18, -12.35 +7.45, -10.00, 46.43, 53.57, -7.14 +7.25, -10.00, 44.04, 55.96, -11.92 +7.12, -10.00, 41.60, 58.40, -16.80 +6.92, -10.00, 44.16, 55.84, -11.68 +6.66, -10.00, 46.77, 53.23, -6.47 +6.46, -10.00, 44.38, 55.62, -11.24 +6.20, -10.00, 46.99, 53.01, -6.02 +5.93, -10.00, 47.13, 52.87, -5.74 +5.67, -10.00, 47.27, 52.73, -5.47 +5.54, -10.00, 42.36, 57.64, -15.27 +5.27, -10.00, 47.45, 52.55, -5.10 +5.01, -10.00, 47.59, 52.41, -4.82 +4.75, -10.00, 47.73, 52.27, -4.54 +4.48, -10.00, 47.88, 52.12, -4.25 +4.22, -10.00, 48.02, 51.98, -3.96 +3.96, -10.00, 48.16, 51.84, -3.67 +3.69, -10.00, 48.31, 51.69, -3.38 +3.43, -10.00, 48.46, 51.54, -3.08 +3.03, -10.00, 53.65, 46.35, 7.30 +2.77, -10.00, 48.86, 51.14, -2.29 +2.44, -10.00, 51.53, 48.47, 3.06 +2.18, -10.00, 49.21, 50.79, -1.58 +1.85, -10.00, 51.88, 48.12, 3.77 +1.58, -10.00, 49.57, 50.43, -0.87 +1.19, -10.00, 54.76, 45.24, 9.53 +0.92, -10.00, 49.98, 50.02, -0.04 +0.59, -10.00, 52.66, 47.34, 5.31 +0.26, -10.00, 52.87, 47.13, 5.73 +0.00, -10.00, 50.55, 49.45, 1.11 +-0.40, -10.00, 55.76, 44.24, 11.52 +-0.73, -10.00, 53.50, 46.50, 7.00 +-0.99, -10.00, 51.19, 48.81, 2.38 +-1.32, -10.00, 53.88, 46.12, 7.76 +-1.71, -10.00, 56.62, 43.38, 13.23 +-1.98, -10.00, 51.84, 48.16, 3.68 +-2.31, -10.00, 54.53, 45.47, 9.06 +-2.64, -10.00, 54.75, 45.25, 9.50 +-3.03, -10.00, 57.49, 42.51, 14.98 +-3.30, -10.00, 52.72, 47.28, 5.44 +-3.63, -10.00, 55.42, 44.58, 10.83 +-3.96, -10.00, 55.64, 44.36, 11.28 +-4.35, -10.00, 58.39, 41.61, 16.77 +-4.61, -10.00, 53.62, 46.38, 7.24 +-4.94, -10.00, 56.32, 43.68, 12.64 +-5.21, -10.00, 54.03, 45.97, 8.06 +-5.54, -10.00, 56.73, 43.27, 13.46 +-5.80, -10.00, 54.44, 45.56, 8.88 +-6.06, -10.00, 54.62, 45.38, 9.25 +-6.46, -10.00, 59.85, 40.15, 19.70 +-6.79, -10.00, 57.61, 42.39, 15.23 +-7.05, -10.00, 55.33, 44.67, 10.66 +-7.32, -10.00, 55.52, 44.48, 11.03 +-7.58, -10.00, 55.71, 44.29, 11.41 +-7.91, -10.00, 58.42, 41.58, 16.83 +-8.17, -10.00, 56.14, 43.86, 12.27 +-8.44, -10.00, 56.33, 43.67, 12.66 +-8.70, -10.00, 56.52, 43.48, 13.04 +-9.10, -10.00, 61.76, 38.24, 23.52 +-9.36, -10.00, 57.01, 42.99, 14.02 +-9.62, -10.00, 57.21, 42.79, 14.41 +-9.89, -10.00, 57.40, 42.60, 14.81 +-10.15, -10.00, 57.60, 42.40, 15.20 +-10.42, -10.00, 57.80, 42.20, 15.60 +-10.55, -10.00, 52.96, 47.04, 5.92 +-10.81, -10.00, 58.10, 41.90, 16.20 +-11.07, -10.00, 58.30, 41.70, 16.61 +-11.27, -10.00, 55.99, 44.01, 11.97 +-11.60, -10.00, 61.18, 38.82, 22.36 +-11.80, -10.00, 56.39, 43.61, 12.79 +-12.00, -10.00, 56.55, 43.45, 13.10 +-12.26, -10.00, 59.23, 40.77, 18.46 +-12.52, -10.00, 59.43, 40.57, 18.87 +-12.66, -10.00, 54.60, 45.40, 9.20 +-12.85, -10.00, 57.23, 42.77, 14.46 +-13.05, -10.00, 57.39, 42.61, 14.78 +-13.32, -10.00, 60.07, 39.93, 20.15 +-13.45, -10.00, 55.24, 44.76, 10.48 +-13.65, -10.00, 57.87, 42.13, 15.75 +-13.84, -10.00, 58.04, 41.96, 16.07 +-13.97, -10.00, 55.68, 44.32, 11.36 +-14.17, -10.00, 58.31, 41.69, 16.63 +-14.24, -10.00, 53.44, 46.56, 6.87 +-14.44, -10.00, 58.55, 41.45, 17.09 +-14.63, -10.00, 58.71, 41.29, 17.42 +-14.77, -10.00, 56.36, 43.64, 12.71 +-14.90, -10.00, 56.47, 43.53, 12.95 +-14.96, -10.00, 54.07, 45.93, 8.14 +-15.16, -10.00, 59.18, 40.82, 18.36 +-15.29, -10.00, 56.83, 43.17, 13.65 +-15.42, -10.00, 56.95, 43.05, 13.89 +-15.49, -10.00, 54.54, 45.46, 9.09 +-15.56, -10.00, 54.62, 45.38, 9.23 +-15.69, -10.00, 57.21, 42.79, 14.41 +-15.82, -10.00, 57.33, 42.67, 14.66 +-15.95, -10.00, 57.45, 42.55, 14.90 +-16.02, -10.00, 55.05, 44.95, 10.10 +-16.08, -10.00, 55.12, 44.88, 10.24 +-16.08, -10.00, 52.67, 47.33, 5.34 +-16.22, -10.00, 57.74, 42.26, 15.48 +-16.28, -10.00, 55.34, 44.66, 10.68 +-16.35, -10.00, 55.41, 44.59, 10.83 +-16.48, -10.00, 58.01, 41.99, 16.02 +-16.48, -10.00, 53.09, 46.91, 6.18 +-16.48, -10.00, 53.11, 46.89, 6.22 +-16.55, -10.00, 55.66, 44.34, 11.32 +-16.55, -10.00, 53.21, 46.79, 6.42 +-16.61, -10.00, 55.76, 44.24, 11.51 +-16.61, -10.00, 53.31, 46.69, 6.62 +-16.61, -10.00, 53.33, 46.67, 6.67 +-16.61, -10.00, 53.36, 46.64, 6.72 +-16.74, -10.00, 58.43, 41.57, 16.86 +-16.74, -10.00, 53.51, 46.49, 7.02 +-16.74, -10.00, 53.53, 46.47, 7.07 +-16.74, -10.00, 53.56, 46.44, 7.12 +-16.74, -10.00, 53.58, 46.42, 7.17 +-16.74, -10.00, 53.61, 46.39, 7.22 +-16.74, -10.00, 53.64, 46.36, 7.27 +-16.74, -10.00, 53.66, 46.34, 7.32 +-16.74, -10.00, 53.69, 46.31, 7.37 +-16.74, -10.00, 53.71, 46.29, 7.42 +-16.74, -10.00, 53.74, 46.26, 7.47 +-16.74, -10.00, 53.76, 46.24, 7.52 +-16.74, -10.00, 53.79, 46.21, 7.57 +-16.61, -10.00, 48.77, 51.23, -2.46 +-16.61, -10.00, 53.74, 46.26, 7.48 +-16.61, -10.00, 53.76, 46.24, 7.53 +-16.61, -10.00, 53.79, 46.21, 7.58 +-16.61, -10.00, 53.81, 46.19, 7.62 +-16.61, -10.00, 53.84, 46.16, 7.67 +-16.61, -10.00, 53.86, 46.14, 7.72 +-16.55, -10.00, 51.37, 48.63, 2.73 +-16.55, -10.00, 53.86, 46.14, 7.72 +-16.55, -10.00, 53.89, 46.11, 7.77 +-16.48, -10.00, 51.39, 48.61, 2.78 +-16.48, -10.00, 53.89, 46.11, 7.77 +-16.48, -10.00, 53.91, 46.09, 7.82 +-16.35, -10.00, 48.89, 51.11, -2.22 +-16.35, -10.00, 53.86, 46.14, 7.72 +-16.35, -10.00, 53.88, 46.12, 7.76 +-16.28, -10.00, 51.38, 48.62, 2.77 +-16.28, -10.00, 53.88, 46.12, 7.76 +-16.22, -10.00, 51.38, 48.62, 2.76 +-16.22, -10.00, 53.88, 46.12, 7.75 +-16.22, -10.00, 53.90, 46.10, 7.80 +-16.08, -10.00, 48.88, 51.12, -2.24 +-16.08, -10.00, 53.85, 46.15, 7.69 +-16.08, -10.00, 53.87, 46.13, 7.74 +-16.02, -10.00, 51.37, 48.63, 2.74 +-16.02, -10.00, 53.87, 46.13, 7.73 +-15.95, -10.00, 51.37, 48.63, 2.73 +-15.95, -10.00, 53.86, 46.14, 7.72 +-15.82, -10.00, 48.84, 51.16, -2.32 +-15.82, -10.00, 53.81, 46.19, 7.61 +-15.75, -10.00, 51.31, 48.69, 2.61 +-15.75, -10.00, 53.80, 46.20, 7.60 +-15.69, -10.00, 51.30, 48.70, 2.60 +-15.69, -10.00, 53.79, 46.21, 7.58 +-15.56, -10.00, 48.77, 51.23, -2.46 +-15.56, -10.00, 53.74, 46.26, 7.47 +-15.49, -10.00, 51.23, 48.77, 2.47 +-15.49, -10.00, 53.73, 46.27, 7.45 +-15.42, -10.00, 51.23, 48.77, 2.45 +-15.42, -10.00, 53.72, 46.28, 7.44 +-15.42, -10.00, 53.74, 46.26, 7.48 +-15.29, -10.00, 48.72, 51.28, -2.57 +-15.29, -10.00, 53.68, 46.32, 7.36 +-15.23, -10.00, 51.18, 48.82, 2.36 +-15.16, -10.00, 51.15, 48.85, 2.30 +-15.16, -10.00, 53.64, 46.36, 7.28 +-15.03, -10.00, 48.61, 51.39, -2.77 +-15.03, -10.00, 53.58, 46.42, 7.16 +-14.96, -10.00, 51.07, 48.93, 2.15 +-14.96, -10.00, 53.57, 46.43, 7.13 +-14.90, -10.00, 51.06, 48.94, 2.12 +-14.90, -10.00, 53.55, 46.45, 7.11 +-14.90, -10.00, 53.57, 46.43, 7.14 +-14.77, -10.00, 48.55, 51.45, -2.91 +-14.77, -10.00, 53.51, 46.49, 7.02 +-14.70, -10.00, 51.00, 49.00, 2.01 +-14.63, -10.00, 50.97, 49.03, 1.94 +-14.63, -10.00, 53.46, 46.54, 6.92 +-14.63, -10.00, 53.48, 46.52, 6.96 +-14.50, -10.00, 48.45, 51.55, -3.09 +-14.50, -10.00, 53.41, 46.59, 6.83 +-14.44, -10.00, 50.91, 49.09, 1.82 +-14.37, -10.00, 50.88, 49.12, 1.75 +-14.37, -10.00, 53.36, 46.64, 6.73 +-14.24, -10.00, 48.34, 51.66, -3.33 +-14.24, -10.00, 53.30, 46.70, 6.59 +-14.24, -10.00, 53.31, 46.69, 6.63 +-14.17, -10.00, 50.81, 49.19, 1.61 +-14.17, -10.00, 53.29, 46.71, 6.59 +-14.11, -10.00, 50.79, 49.21, 1.58 +-14.11, -10.00, 53.28, 46.72, 6.55 +-13.97, -10.00, 48.25, 51.75, -3.50 +-13.97, -10.00, 53.21, 46.79, 6.41 +-13.97, -10.00, 53.22, 46.78, 6.44 +-13.91, -10.00, 50.72, 49.28, 1.43 +-13.91, -10.00, 53.20, 46.80, 6.40 +-13.84, -10.00, 50.70, 49.30, 1.39 +-13.84, -10.00, 53.18, 46.82, 6.36 +-13.71, -10.00, 48.15, 51.85, -3.69 +-13.71, -10.00, 53.11, 46.89, 6.22 +-13.71, -10.00, 53.12, 46.88, 6.25 +-13.65, -10.00, 50.62, 49.38, 1.23 +-13.65, -10.00, 53.10, 46.90, 6.20 +-13.58, -10.00, 50.59, 49.41, 1.19 +-13.58, -10.00, 53.08, 46.92, 6.16 +-13.58, -10.00, 53.09, 46.91, 6.19 +-13.45, -10.00, 48.06, 51.94, -3.87 +-13.45, -10.00, 53.02, 46.98, 6.04 +-13.45, -10.00, 53.03, 46.97, 6.07 +-13.38, -10.00, 50.52, 49.48, 1.05 +-13.38, -10.00, 53.01, 46.99, 6.02 +-13.32, -10.00, 50.50, 49.50, 1.00 +-13.32, -10.00, 52.98, 47.02, 5.97 +-13.18, -10.00, 47.95, 52.05, -4.09 +-13.18, -10.00, 52.91, 47.09, 5.82 +-13.18, -10.00, 52.92, 47.08, 5.84 +-13.12, -10.00, 50.41, 49.59, 0.82 +-13.12, -10.00, 52.90, 47.10, 5.79 +-13.05, -10.00, 50.39, 49.61, 0.77 +-13.05, -10.00, 52.87, 47.13, 5.74 +-13.05, -10.00, 52.88, 47.12, 5.76 +-13.05, -10.00, 52.89, 47.11, 5.78 +-12.92, -10.00, 47.86, 52.14, -4.28 +-12.92, -10.00, 52.81, 47.19, 5.63 +-12.92, -10.00, 52.83, 47.17, 5.65 +-12.85, -10.00, 50.31, 49.69, 0.63 +-12.85, -10.00, 52.80, 47.20, 5.59 +-12.85, -10.00, 52.81, 47.19, 5.62 +-12.85, -10.00, 52.82, 47.18, 5.64 +-12.79, -10.00, 50.31, 49.69, 0.62 +-12.79, -10.00, 52.79, 47.21, 5.58 +-12.79, -10.00, 52.80, 47.20, 5.60 +-12.66, -10.00, 47.77, 52.23, -4.46 +-12.66, -10.00, 52.72, 47.28, 5.44 +-12.66, -10.00, 52.73, 47.27, 5.46 +-12.66, -10.00, 52.74, 47.26, 5.48 +-12.59, -10.00, 50.23, 49.77, 0.46 +-12.59, -10.00, 52.71, 47.29, 5.42 +-12.59, -10.00, 52.72, 47.28, 5.44 +-12.59, -10.00, 52.73, 47.27, 5.46 +-12.59, -10.00, 52.74, 47.26, 5.48 +-12.52, -10.00, 50.23, 49.77, 0.46 +-12.52, -10.00, 52.71, 47.29, 5.42 +-12.52, -10.00, 52.72, 47.28, 5.44 +-12.52, -10.00, 52.73, 47.27, 5.46 +-12.52, -10.00, 52.74, 47.26, 5.48 +-12.52, -10.00, 52.75, 47.25, 5.50 +-12.52, -10.00, 52.76, 47.24, 5.52 +-12.52, -10.00, 52.77, 47.23, 5.53 +-12.39, -10.00, 47.73, 52.27, -4.53 +-12.39, -10.00, 52.69, 47.31, 5.37 +-12.39, -10.00, 52.70, 47.30, 5.39 +-12.39, -10.00, 52.70, 47.30, 5.41 +-12.39, -10.00, 52.71, 47.29, 5.43 +-12.39, -10.00, 52.72, 47.28, 5.44 +-12.39, -10.00, 52.73, 47.27, 5.46 +-12.39, -10.00, 52.74, 47.26, 5.48 +-12.39, -10.00, 52.75, 47.25, 5.50 +-12.39, -10.00, 52.76, 47.24, 5.52 +-12.39, -10.00, 52.77, 47.23, 5.53 +-12.39, -10.00, 52.78, 47.22, 5.55 +-12.39, -10.00, 52.78, 47.22, 5.57 +-12.33, -10.00, 50.27, 49.73, 0.54 +-12.33, -10.00, 52.75, 47.25, 5.51 +-12.33, -10.00, 52.76, 47.24, 5.52 +-12.33, -10.00, 52.77, 47.23, 5.54 +-12.33, -10.00, 52.78, 47.22, 5.56 +-12.33, -10.00, 52.79, 47.21, 5.58 +-12.33, -10.00, 52.80, 47.20, 5.59 +-12.33, -10.00, 52.81, 47.19, 5.61 +-12.33, -10.00, 52.81, 47.19, 5.63 +-12.33, -10.00, 52.82, 47.18, 5.65 +-12.33, -10.00, 52.83, 47.17, 5.66 +-12.26, -10.00, 50.32, 49.68, 0.64 +-12.33, -10.00, 55.32, 44.68, 10.64 +-12.26, -10.00, 50.34, 49.66, 0.67 +-12.26, -10.00, 52.82, 47.18, 5.63 +-12.26, -10.00, 52.82, 47.18, 5.65 +-12.26, -10.00, 52.83, 47.17, 5.67 +-12.26, -10.00, 52.84, 47.16, 5.68 +-12.26, -10.00, 52.85, 47.15, 5.70 +-12.26, -10.00, 52.86, 47.14, 5.72 +-12.26, -10.00, 52.87, 47.13, 5.73 +-12.13, -10.00, 47.83, 52.17, -4.34 +-12.13, -10.00, 52.78, 47.22, 5.57 +-12.13, -10.00, 52.79, 47.21, 5.58 +-12.13, -10.00, 52.80, 47.20, 5.60 +-12.13, -10.00, 52.81, 47.19, 5.62 +-12.13, -10.00, 52.82, 47.18, 5.63 +-12.06, -10.00, 50.30, 49.70, 0.60 +-12.06, -10.00, 52.78, 47.22, 5.56 +-12.06, -10.00, 52.79, 47.21, 5.58 +-12.06, -10.00, 52.80, 47.20, 5.60 +-12.06, -10.00, 52.81, 47.19, 5.61 +-12.06, -10.00, 52.81, 47.19, 5.63 +-12.06, -10.00, 52.82, 47.18, 5.64 +-12.00, -10.00, 50.31, 49.69, 0.61 +-12.00, -10.00, 52.79, 47.21, 5.57 +-12.00, -10.00, 52.79, 47.21, 5.59 +-12.00, -10.00, 52.80, 47.20, 5.60 +-12.00, -10.00, 52.81, 47.19, 5.62 +-11.87, -10.00, 47.77, 52.23, -4.45 +-11.87, -10.00, 52.72, 47.28, 5.45 +-11.87, -10.00, 52.73, 47.27, 5.46 +-11.87, -10.00, 52.74, 47.26, 5.48 +-11.87, -10.00, 52.74, 47.26, 5.49 +-11.87, -10.00, 52.75, 47.25, 5.50 +-11.80, -10.00, 50.24, 49.76, 0.47 +-11.80, -10.00, 52.72, 47.28, 5.43 +-11.80, -10.00, 52.72, 47.28, 5.45 +-11.80, -10.00, 52.73, 47.27, 5.46 +-11.73, -10.00, 50.21, 49.79, 0.43 +-11.73, -10.00, 52.69, 47.31, 5.39 +-11.73, -10.00, 52.70, 47.30, 5.40 +-11.73, -10.00, 52.71, 47.29, 5.41 +-11.73, -10.00, 52.71, 47.29, 5.42 +-11.73, -10.00, 52.72, 47.28, 5.44 +-11.60, -10.00, 47.68, 52.32, -4.64 +-11.60, -10.00, 52.63, 47.37, 5.26 +-11.60, -10.00, 52.64, 47.36, 5.28 +-11.60, -10.00, 52.64, 47.36, 5.29 +-11.54, -10.00, 50.13, 49.87, 0.26 +-11.54, -10.00, 52.61, 47.39, 5.21 +-11.54, -10.00, 52.61, 47.39, 5.22 +-11.54, -10.00, 52.62, 47.38, 5.24 +-11.47, -10.00, 50.10, 49.90, 0.20 +-11.47, -10.00, 52.58, 47.42, 5.16 +-11.47, -10.00, 52.58, 47.42, 5.17 +-11.47, -10.00, 52.59, 47.41, 5.18 +-11.47, -10.00, 52.60, 47.40, 5.19 +-11.34, -10.00, 47.56, 52.44, -4.88 +-11.34, -10.00, 52.51, 47.49, 5.01 +-11.34, -10.00, 52.51, 47.49, 5.02 +-11.34, -10.00, 52.52, 47.48, 5.03 +-11.34, -10.00, 52.52, 47.48, 5.04 +-11.27, -10.00, 50.01, 49.99, 0.01 +-11.27, -10.00, 52.48, 47.52, 4.96 +-11.27, -10.00, 52.49, 47.51, 4.97 +-11.27, -10.00, 52.49, 47.51, 4.98 +-11.27, -10.00, 52.50, 47.50, 4.99 +-11.21, -10.00, 49.98, 50.02, -0.04 +-11.21, -10.00, 52.46, 47.54, 4.91 +-11.21, -10.00, 52.46, 47.54, 4.92 +-11.21, -10.00, 52.47, 47.53, 4.93 +-11.21, -10.00, 52.47, 47.53, 4.94 +-11.21, -10.00, 52.47, 47.53, 4.95 +-11.07, -10.00, 47.44, 52.56, -5.13 +-11.07, -10.00, 52.38, 47.62, 4.77 +-11.07, -10.00, 52.39, 47.61, 4.77 +-11.07, -10.00, 52.39, 47.61, 4.78 +-11.07, -10.00, 52.40, 47.60, 4.79 +-11.07, -10.00, 52.40, 47.60, 4.80 +-11.01, -10.00, 49.88, 50.12, -0.24 +-11.01, -10.00, 52.36, 47.64, 4.72 +-11.01, -10.00, 52.36, 47.64, 4.72 +-11.01, -10.00, 52.37, 47.63, 4.73 +-10.94, -10.00, 49.85, 50.15, -0.31 +-10.94, -10.00, 52.32, 47.68, 4.65 +-10.94, -10.00, 52.33, 47.67, 4.65 +-10.94, -10.00, 52.33, 47.67, 4.66 +-10.94, -10.00, 52.33, 47.67, 4.67 +-10.81, -10.00, 47.29, 52.71, -5.41 +-10.94, -10.00, 57.28, 42.72, 14.57 +-10.81, -10.00, 47.30, 52.70, -5.40 +-10.81, -10.00, 52.25, 47.75, 4.49 +-10.81, -10.00, 52.25, 47.75, 4.50 +-10.81, -10.00, 52.25, 47.75, 4.51 +-10.81, -10.00, 52.26, 47.74, 4.51 +-10.81, -10.00, 52.26, 47.74, 4.52 +-10.81, -10.00, 52.26, 47.74, 4.52 +-10.81, -10.00, 52.27, 47.73, 4.53 +-10.74, -10.00, 49.75, 50.25, -0.51 +-10.74, -10.00, 52.22, 47.78, 4.44 +-10.74, -10.00, 52.22, 47.78, 4.45 +-10.74, -10.00, 52.23, 47.77, 4.45 +-10.74, -10.00, 52.23, 47.77, 4.46 +-10.74, -10.00, 52.23, 47.77, 4.47 +-10.74, -10.00, 52.24, 47.76, 4.47 +-10.74, -10.00, 52.24, 47.76, 4.48 +-10.74, -10.00, 52.24, 47.76, 4.48 +-10.74, -10.00, 52.24, 47.76, 4.49 +-10.74, -10.00, 52.25, 47.75, 4.49 +-10.74, -10.00, 52.25, 47.75, 4.50 +-10.74, -10.00, 52.25, 47.75, 4.50 +-10.74, -10.00, 52.26, 47.74, 4.51 +-10.74, -10.00, 52.26, 47.74, 4.52 +-10.74, -10.00, 52.26, 47.74, 4.52 +-10.74, -10.00, 52.26, 47.74, 4.53 +-10.74, -10.00, 52.27, 47.73, 4.53 +-10.74, -10.00, 52.27, 47.73, 4.54 +-10.74, -10.00, 52.27, 47.73, 4.54 +-10.74, -10.00, 52.27, 47.73, 4.55 +-10.74, -10.00, 52.28, 47.72, 4.55 +-10.74, -10.00, 52.28, 47.72, 4.56 +-10.74, -10.00, 52.28, 47.72, 4.57 +-10.74, -10.00, 52.29, 47.71, 4.57 +-10.74, -10.00, 52.29, 47.71, 4.58 +-10.74, -10.00, 52.29, 47.71, 4.58 +-10.74, -10.00, 52.29, 47.71, 4.59 +-10.74, -10.00, 52.30, 47.70, 4.59 +-10.74, -10.00, 52.30, 47.70, 4.60 +-10.74, -10.00, 52.30, 47.70, 4.60 +-10.74, -10.00, 52.31, 47.69, 4.61 +-10.68, -10.00, 49.79, 50.21, -0.43 +-10.74, -10.00, 54.78, 45.22, 9.57 +-10.74, -10.00, 52.31, 47.69, 4.63 +-10.74, -10.00, 52.32, 47.68, 4.63 +-10.74, -10.00, 52.32, 47.68, 4.64 +-10.68, -10.00, 49.80, 50.20, -0.40 +-10.74, -10.00, 54.80, 45.20, 9.59 +-10.68, -10.00, 49.81, 50.19, -0.39 +-10.74, -10.00, 54.80, 45.20, 9.60 +-10.74, -10.00, 52.33, 47.67, 4.66 +-10.68, -10.00, 49.81, 50.19, -0.37 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.59 +-10.74, -10.00, 54.82, 45.18, 9.64 +-10.74, -10.00, 52.35, 47.65, 4.70 +-10.74, -10.00, 52.35, 47.65, 4.71 +-10.74, -10.00, 52.36, 47.64, 4.71 +-10.74, -10.00, 52.36, 47.64, 4.72 +-10.74, -10.00, 52.36, 47.64, 4.72 +-10.74, -10.00, 52.36, 47.64, 4.73 +-10.74, -10.00, 52.37, 47.63, 4.74 +-10.74, -10.00, 52.37, 47.63, 4.74 +-10.74, -10.00, 52.37, 47.63, 4.75 +-10.74, -10.00, 52.38, 47.62, 4.75 +-10.74, -10.00, 52.38, 47.62, 4.76 +-10.81, -10.00, 54.90, 45.10, 9.81 +-10.81, -10.00, 52.43, 47.57, 4.87 +-10.81, -10.00, 52.44, 47.56, 4.87 +-10.81, -10.00, 52.44, 47.56, 4.88 +-10.81, -10.00, 52.44, 47.56, 4.89 +-10.81, -10.00, 52.45, 47.55, 4.89 +-10.81, -10.00, 52.45, 47.55, 4.90 +-10.81, -10.00, 52.45, 47.55, 4.90 +-10.81, -10.00, 52.46, 47.54, 4.91 +-10.81, -10.00, 52.46, 47.54, 4.92 +-10.94, -10.00, 57.50, 42.50, 15.01 +-10.94, -10.00, 52.56, 47.44, 5.13 +-10.94, -10.00, 52.57, 47.43, 5.14 +-10.94, -10.00, 52.57, 47.43, 5.14 +-10.94, -10.00, 52.58, 47.42, 5.15 +-10.94, -10.00, 52.58, 47.42, 5.16 +-10.94, -10.00, 52.58, 47.42, 5.16 +-10.94, -10.00, 52.59, 47.41, 5.17 +-10.94, -10.00, 52.59, 47.41, 5.18 +-10.94, -10.00, 52.59, 47.41, 5.19 +-11.01, -10.00, 55.12, 44.88, 10.24 +-11.01, -10.00, 52.65, 47.35, 5.30 +-11.01, -10.00, 52.65, 47.35, 5.31 +-11.01, -10.00, 52.66, 47.34, 5.31 +-11.01, -10.00, 52.66, 47.34, 5.32 +-11.01, -10.00, 52.66, 47.34, 5.33 +-11.01, -10.00, 52.67, 47.33, 5.34 +-11.01, -10.00, 52.67, 47.33, 5.34 +-11.01, -10.00, 52.68, 47.32, 5.35 +-11.01, -10.00, 52.68, 47.32, 5.36 +-11.01, -10.00, 52.68, 47.32, 5.37 +-11.07, -10.00, 55.21, 44.79, 10.42 +-11.07, -10.00, 52.74, 47.26, 5.48 +-11.07, -10.00, 52.75, 47.25, 5.49 +-11.07, -10.00, 52.75, 47.25, 5.50 +-11.07, -10.00, 52.75, 47.25, 5.51 +-11.07, -10.00, 52.76, 47.24, 5.51 +-11.07, -10.00, 52.76, 47.24, 5.52 +-11.07, -10.00, 52.77, 47.23, 5.53 +-11.07, -10.00, 52.77, 47.23, 5.54 +-11.07, -10.00, 52.77, 47.23, 5.55 +-11.21, -10.00, 57.82, 42.18, 15.64 +-11.21, -10.00, 52.88, 47.12, 5.76 +-11.21, -10.00, 52.89, 47.11, 5.77 +-11.21, -10.00, 52.89, 47.11, 5.78 +-11.21, -10.00, 52.89, 47.11, 5.79 +-11.21, -10.00, 52.90, 47.10, 5.80 +-11.21, -10.00, 52.90, 47.10, 5.81 +-11.21, -10.00, 52.91, 47.09, 5.82 +-11.21, -10.00, 52.91, 47.09, 5.83 +-11.21, -10.00, 52.92, 47.08, 5.84 +-11.21, -10.00, 52.92, 47.08, 5.84 +-11.21, -10.00, 52.93, 47.07, 5.85 +-11.21, -10.00, 52.93, 47.07, 5.86 +-11.21, -10.00, 52.94, 47.06, 5.87 +-11.21, -10.00, 52.94, 47.06, 5.88 +-11.21, -10.00, 52.94, 47.06, 5.89 +-11.21, -10.00, 52.95, 47.05, 5.90 +-11.21, -10.00, 52.95, 47.05, 5.91 +-11.21, -10.00, 52.96, 47.04, 5.92 +-11.21, -10.00, 52.96, 47.04, 5.93 +-11.21, -10.00, 52.97, 47.03, 5.93 +-11.21, -10.00, 52.97, 47.03, 5.94 +-11.21, -10.00, 52.98, 47.02, 5.95 +-11.21, -10.00, 52.98, 47.02, 5.96 +-11.21, -10.00, 52.99, 47.01, 5.97 +-11.21, -10.00, 52.99, 47.01, 5.98 +-11.21, -10.00, 52.99, 47.01, 5.99 +-11.21, -10.00, 53.00, 47.00, 6.00 +-11.21, -10.00, 53.00, 47.00, 6.01 +-11.21, -10.00, 53.01, 46.99, 6.02 +-11.21, -10.00, 53.01, 46.99, 6.03 +-11.21, -10.00, 53.02, 46.98, 6.03 +-11.21, -10.00, 53.02, 46.98, 6.04 +-11.21, -10.00, 53.03, 46.97, 6.05 +-11.21, -10.00, 53.03, 46.97, 6.06 +-11.21, -10.00, 53.04, 46.96, 6.07 +-11.21, -10.00, 53.04, 46.96, 6.08 +-11.21, -10.00, 53.04, 46.96, 6.09 +-11.21, -10.00, 53.05, 46.95, 6.10 +-11.21, -10.00, 53.05, 46.95, 6.11 +-11.21, -10.00, 53.06, 46.94, 6.12 +-11.21, -10.00, 53.06, 46.94, 6.12 +-11.21, -10.00, 53.07, 46.93, 6.13 +-11.21, -10.00, 53.07, 46.93, 6.14 +-11.21, -10.00, 53.08, 46.92, 6.15 +-11.21, -10.00, 53.08, 46.92, 6.16 +-11.21, -10.00, 53.08, 46.92, 6.17 +-11.21, -10.00, 53.09, 46.91, 6.18 +-11.21, -10.00, 53.09, 46.91, 6.19 +-11.21, -10.00, 53.10, 46.90, 6.20 +-11.21, -10.00, 53.10, 46.90, 6.21 +-11.21, -10.00, 53.11, 46.89, 6.22 +-11.21, -10.00, 53.11, 46.89, 6.22 +-11.21, -10.00, 53.12, 46.88, 6.23 +-11.21, -10.00, 53.12, 46.88, 6.24 +-11.21, -10.00, 53.13, 46.87, 6.25 +-11.21, -10.00, 53.13, 46.87, 6.26 +-11.21, -10.00, 53.13, 46.87, 6.27 +-11.21, -10.00, 53.14, 46.86, 6.28 +-11.21, -10.00, 53.14, 46.86, 6.29 +-11.07, -10.00, 48.11, 51.89, -3.79 +-11.21, -10.00, 58.10, 41.90, 16.19 +-11.07, -10.00, 48.11, 51.89, -3.77 +-11.07, -10.00, 53.06, 46.94, 6.12 +-11.07, -10.00, 53.07, 46.93, 6.13 +-11.07, -10.00, 53.07, 46.93, 6.14 +-11.07, -10.00, 53.07, 46.93, 6.15 +-11.01, -10.00, 50.56, 49.44, 1.11 +-11.01, -10.00, 53.03, 46.97, 6.06 +-11.01, -10.00, 53.04, 46.96, 6.07 +-11.01, -10.00, 53.04, 46.96, 6.08 +-11.01, -10.00, 53.04, 46.96, 6.09 +-11.01, -10.00, 53.05, 46.95, 6.09 +-10.94, -10.00, 50.53, 49.47, 1.06 +-10.94, -10.00, 53.00, 47.00, 6.01 +-10.94, -10.00, 53.01, 46.99, 6.02 +-10.94, -10.00, 53.01, 46.99, 6.02 +-10.81, -10.00, 47.97, 52.03, -4.06 +-10.81, -10.00, 52.92, 47.08, 5.84 +-10.81, -10.00, 52.92, 47.08, 5.84 +-10.81, -10.00, 52.92, 47.08, 5.85 +-10.81, -10.00, 52.93, 47.07, 5.86 +-10.81, -10.00, 52.93, 47.07, 5.86 +-10.81, -10.00, 52.93, 47.07, 5.87 +-10.74, -10.00, 50.42, 49.58, 0.83 +-10.74, -10.00, 52.89, 47.11, 5.78 +-10.74, -10.00, 52.89, 47.11, 5.79 +-10.74, -10.00, 52.90, 47.10, 5.79 +-10.74, -10.00, 52.90, 47.10, 5.80 +-10.68, -10.00, 50.38, 49.62, 0.76 +-10.68, -10.00, 52.85, 47.15, 5.71 +-10.68, -10.00, 52.86, 47.14, 5.71 +-10.68, -10.00, 52.86, 47.14, 5.72 +-10.68, -10.00, 52.86, 47.14, 5.72 +-10.68, -10.00, 52.86, 47.14, 5.73 +-10.68, -10.00, 52.87, 47.13, 5.73 +-10.68, -10.00, 52.87, 47.13, 5.74 +-10.55, -10.00, 47.83, 52.17, -4.34 +-10.55, -10.00, 52.77, 47.23, 5.55 +-10.55, -10.00, 52.78, 47.22, 5.55 +-10.55, -10.00, 52.78, 47.22, 5.56 +-10.55, -10.00, 52.78, 47.22, 5.56 +-10.55, -10.00, 52.78, 47.22, 5.57 +-10.55, -10.00, 52.78, 47.22, 5.57 +-10.55, -10.00, 52.79, 47.21, 5.57 +-10.55, -10.00, 52.79, 47.21, 5.58 +-10.55, -10.00, 52.79, 47.21, 5.58 +-10.55, -10.00, 52.79, 47.21, 5.59 +-10.48, -10.00, 50.27, 49.73, 0.55 +-10.55, -10.00, 55.27, 44.73, 10.54 +-10.48, -10.00, 50.28, 49.72, 0.55 +-10.48, -10.00, 52.75, 47.25, 5.50 +-10.48, -10.00, 52.75, 47.25, 5.51 +-10.48, -10.00, 52.75, 47.25, 5.51 +-10.48, -10.00, 52.76, 47.24, 5.51 +-10.48, -10.00, 52.76, 47.24, 5.52 +-10.48, -10.00, 52.76, 47.24, 5.52 +-10.48, -10.00, 52.76, 47.24, 5.52 +-10.48, -10.00, 52.76, 47.24, 5.53 +-10.48, -10.00, 52.77, 47.23, 5.53 +-10.48, -10.00, 52.77, 47.23, 5.53 +-10.48, -10.00, 52.77, 47.23, 5.54 +-10.48, -10.00, 52.77, 47.23, 5.54 +-10.48, -10.00, 52.77, 47.23, 5.55 +-10.42, -10.00, 50.25, 49.75, 0.51 +-10.48, -10.00, 55.25, 44.75, 10.50 +-10.42, -10.00, 50.26, 49.74, 0.51 +-10.42, -10.00, 52.73, 47.27, 5.46 +-10.42, -10.00, 52.73, 47.27, 5.46 +-10.42, -10.00, 52.73, 47.27, 5.47 +-10.42, -10.00, 52.73, 47.27, 5.47 +-10.42, -10.00, 52.74, 47.26, 5.47 +-10.42, -10.00, 52.74, 47.26, 5.48 +-10.42, -10.00, 52.74, 47.26, 5.48 +-10.28, -10.00, 47.70, 52.30, -4.61 +-10.28, -10.00, 52.64, 47.36, 5.28 +-10.28, -10.00, 52.64, 47.36, 5.29 +-10.28, -10.00, 52.64, 47.36, 5.29 +-10.28, -10.00, 52.65, 47.35, 5.29 +-10.28, -10.00, 52.65, 47.35, 5.29 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.30 +-10.28, -10.00, 52.65, 47.35, 5.31 +-10.28, -10.00, 52.65, 47.35, 5.31 +-10.28, -10.00, 52.66, 47.34, 5.31 +-10.28, -10.00, 52.66, 47.34, 5.31 +-10.28, -10.00, 52.66, 47.34, 5.31 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.28, -10.00, 52.66, 47.34, 5.32 +-10.42, -10.00, 57.71, 42.29, 15.41 +-10.42, -10.00, 52.76, 47.24, 5.53 +-10.42, -10.00, 52.77, 47.23, 5.53 +-10.42, -10.00, 52.77, 47.23, 5.54 +-10.42, -10.00, 52.77, 47.23, 5.54 +-10.42, -10.00, 52.77, 47.23, 5.54 +-10.42, -10.00, 52.77, 47.23, 5.54 +-10.42, -10.00, 52.77, 47.23, 5.55 +-10.42, -10.00, 52.78, 47.22, 5.55 +-10.48, -10.00, 55.30, 44.70, 10.60 +-10.48, -10.00, 52.83, 47.17, 5.66 +-10.48, -10.00, 52.83, 47.17, 5.66 +-10.48, -10.00, 52.83, 47.17, 5.66 +-10.48, -10.00, 52.83, 47.17, 5.67 +-10.48, -10.00, 52.84, 47.16, 5.67 +-10.48, -10.00, 52.84, 47.16, 5.67 +-10.48, -10.00, 52.84, 47.16, 5.68 +-10.48, -10.00, 52.84, 47.16, 5.68 +-10.55, -10.00, 55.36, 44.64, 10.73 +-10.55, -10.00, 52.89, 47.11, 5.79 +-10.55, -10.00, 52.90, 47.10, 5.79 +-10.55, -10.00, 52.90, 47.10, 5.80 +-10.55, -10.00, 52.90, 47.10, 5.80 +-10.55, -10.00, 52.90, 47.10, 5.81 +-10.55, -10.00, 52.90, 47.10, 5.81 +-10.55, -10.00, 52.91, 47.09, 5.81 +-10.55, -10.00, 52.91, 47.09, 5.82 +-10.68, -10.00, 57.95, 42.05, 15.91 +-10.68, -10.00, 53.01, 46.99, 6.03 +-10.68, -10.00, 53.02, 46.98, 6.03 +-10.68, -10.00, 53.02, 46.98, 6.04 +-10.68, -10.00, 53.02, 46.98, 6.04 +-10.68, -10.00, 53.02, 46.98, 6.05 +-10.68, -10.00, 53.03, 46.97, 6.05 +-10.68, -10.00, 53.03, 46.97, 6.06 +-10.68, -10.00, 53.03, 46.97, 6.06 +-10.68, -10.00, 53.03, 46.97, 6.07 +-10.68, -10.00, 53.04, 46.96, 6.07 +-10.68, -10.00, 53.04, 46.96, 6.08 +-10.68, -10.00, 53.04, 46.96, 6.08 +-10.74, -10.00, 55.57, 44.43, 11.13 +-10.68, -10.00, 50.57, 49.43, 1.15 +-10.68, -10.00, 53.05, 46.95, 6.10 +-10.74, -10.00, 55.57, 44.43, 11.15 +-10.74, -10.00, 53.10, 46.90, 6.21 +-10.68, -10.00, 50.58, 49.42, 1.17 +-10.68, -10.00, 53.06, 46.94, 6.12 +-10.68, -10.00, 53.06, 46.94, 6.12 +-10.68, -10.00, 53.06, 46.94, 6.13 +-10.68, -10.00, 53.07, 46.93, 6.13 +-10.68, -10.00, 53.07, 46.93, 6.14 +-10.68, -10.00, 53.07, 46.93, 6.14 +-10.55, -10.00, 48.03, 51.97, -3.94 +-10.55, -10.00, 52.98, 47.02, 5.95 +-10.55, -10.00, 52.98, 47.02, 5.96 +-10.55, -10.00, 52.98, 47.02, 5.96 +-10.55, -10.00, 52.98, 47.02, 5.97 +-10.55, -10.00, 52.99, 47.01, 5.97 +-10.48, -10.00, 50.47, 49.53, 0.93 +-10.48, -10.00, 52.94, 47.06, 5.88 +-10.48, -10.00, 52.94, 47.06, 5.88 +-10.48, -10.00, 52.94, 47.06, 5.89 +-10.48, -10.00, 52.95, 47.05, 5.89 +-10.42, -10.00, 50.43, 49.57, 0.85 +-10.42, -10.00, 52.90, 47.10, 5.80 +-10.42, -10.00, 52.90, 47.10, 5.80 +-10.28, -10.00, 47.86, 52.14, -4.28 +-10.28, -10.00, 52.80, 47.20, 5.61 +-10.28, -10.00, 52.80, 47.20, 5.61 +-10.22, -10.00, 50.28, 49.72, 0.57 +-10.22, -10.00, 52.76, 47.24, 5.51 +-10.22, -10.00, 52.76, 47.24, 5.52 +-10.22, -10.00, 52.76, 47.24, 5.52 +-10.22, -10.00, 52.76, 47.24, 5.52 +-10.15, -10.00, 50.24, 49.76, 0.48 +-10.15, -10.00, 52.71, 47.29, 5.42 +-10.15, -10.00, 52.71, 47.29, 5.42 +-10.15, -10.00, 52.71, 47.29, 5.42 +-10.02, -10.00, 47.67, 52.33, -4.66 +-10.02, -10.00, 52.61, 47.39, 5.23 +-10.02, -10.00, 52.61, 47.39, 5.23 +-10.02, -10.00, 52.61, 47.39, 5.23 +-10.02, -10.00, 52.61, 47.39, 5.23 +-9.95, -10.00, 50.09, 49.91, 0.18 +-9.95, -10.00, 52.56, 47.44, 5.13 +-9.89, -10.00, 50.04, 49.96, 0.08 +-9.89, -10.00, 52.51, 47.49, 5.03 +-9.89, -10.00, 52.51, 47.49, 5.03 +-9.89, -10.00, 52.51, 47.49, 5.03 +-9.76, -10.00, 47.47, 52.53, -5.06 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.82 +-9.76, -10.00, 52.41, 47.59, 4.81 +-9.76, -10.00, 52.41, 47.59, 4.81 +-9.69, -10.00, 49.88, 50.12, -0.23 +-9.76, -10.00, 54.88, 45.12, 9.75 +-9.76, -10.00, 52.40, 47.60, 4.81 +-9.69, -10.00, 49.88, 50.12, -0.24 +-9.69, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 52.35, 47.65, 4.69 +-9.69, -10.00, 52.35, 47.65, 4.69 +-9.62, -10.00, 49.82, 50.18, -0.35 +-9.62, -10.00, 52.29, 47.71, 4.59 +-9.62, -10.00, 52.29, 47.71, 4.58 +-9.62, -10.00, 52.29, 47.71, 4.58 +-9.62, -10.00, 52.29, 47.71, 4.58 +-9.62, -10.00, 52.29, 47.71, 4.58 +-9.62, -10.00, 52.29, 47.71, 4.57 +-9.62, -10.00, 52.29, 47.71, 4.57 +-9.62, -10.00, 52.28, 47.72, 4.57 +-9.62, -10.00, 52.28, 47.72, 4.56 +-9.62, -10.00, 52.28, 47.72, 4.56 +-9.62, -10.00, 52.28, 47.72, 4.56 +-9.62, -10.00, 52.28, 47.72, 4.56 +-9.62, -10.00, 52.28, 47.72, 4.55 +-9.62, -10.00, 52.28, 47.72, 4.55 +-9.62, -10.00, 52.27, 47.73, 4.55 +-9.62, -10.00, 52.27, 47.73, 4.55 +-9.49, -10.00, 47.23, 52.77, -5.54 +-9.62, -10.00, 57.21, 42.79, 14.43 +-9.49, -10.00, 47.22, 52.78, -5.55 +-9.49, -10.00, 52.17, 47.83, 4.33 +-9.62, -10.00, 57.21, 42.79, 14.42 +-9.62, -10.00, 52.26, 47.74, 4.53 +-9.62, -10.00, 52.26, 47.74, 4.52 +-9.62, -10.00, 52.26, 47.74, 4.52 +-9.62, -10.00, 52.26, 47.74, 4.52 +-9.62, -10.00, 52.26, 47.74, 4.51 +-9.62, -10.00, 52.26, 47.74, 4.51 +-9.62, -10.00, 52.25, 47.75, 4.51 +-9.62, -10.00, 52.25, 47.75, 4.51 +-9.62, -10.00, 52.25, 47.75, 4.50 +-9.69, -10.00, 54.77, 45.23, 9.54 +-9.69, -10.00, 52.30, 47.70, 4.60 +-9.69, -10.00, 52.30, 47.70, 4.59 +-9.69, -10.00, 52.30, 47.70, 4.59 +-9.69, -10.00, 52.30, 47.70, 4.59 +-9.69, -10.00, 52.29, 47.71, 4.59 +-9.69, -10.00, 52.29, 47.71, 4.59 +-9.76, -10.00, 54.81, 45.19, 9.63 +-9.76, -10.00, 52.34, 47.66, 4.68 +-9.76, -10.00, 52.34, 47.66, 4.68 +-9.76, -10.00, 52.34, 47.66, 4.68 +-9.76, -10.00, 52.34, 47.66, 4.68 +-9.76, -10.00, 52.34, 47.66, 4.67 +-9.76, -10.00, 52.34, 47.66, 4.67 +-9.76, -10.00, 52.33, 47.67, 4.67 +-9.76, -10.00, 52.33, 47.67, 4.67 +-9.89, -10.00, 57.38, 42.62, 14.75 +-9.89, -10.00, 52.43, 47.57, 4.86 +-9.89, -10.00, 52.43, 47.57, 4.86 +-9.89, -10.00, 52.43, 47.57, 4.86 +-9.95, -10.00, 54.95, 45.05, 9.90 +-9.95, -10.00, 52.48, 47.52, 4.96 +-9.95, -10.00, 52.48, 47.52, 4.96 +-9.95, -10.00, 52.48, 47.52, 4.96 +-10.02, -10.00, 55.00, 45.00, 10.00 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.02, -10.00, 52.53, 47.47, 5.06 +-10.15, -10.00, 57.57, 42.43, 15.15 +-10.15, -10.00, 52.63, 47.37, 5.26 +-10.15, -10.00, 52.63, 47.37, 5.26 +-10.15, -10.00, 52.63, 47.37, 5.26 +-10.22, -10.00, 55.15, 44.85, 10.31 +-10.22, -10.00, 52.68, 47.32, 5.36 +-10.22, -10.00, 52.68, 47.32, 5.37 +-10.22, -10.00, 52.68, 47.32, 5.37 +-10.28, -10.00, 55.21, 44.79, 10.41 +-10.28, -10.00, 52.74, 47.26, 5.47 +-10.28, -10.00, 52.74, 47.26, 5.47 +-10.28, -10.00, 52.74, 47.26, 5.47 +-10.42, -10.00, 57.78, 42.22, 15.56 +-10.42, -10.00, 52.84, 47.16, 5.68 +-10.42, -10.00, 52.84, 47.16, 5.68 +-10.42, -10.00, 52.84, 47.16, 5.68 +-10.42, -10.00, 52.84, 47.16, 5.69 +-10.48, -10.00, 55.37, 44.63, 10.73 +-10.48, -10.00, 52.90, 47.10, 5.79 +-10.48, -10.00, 52.90, 47.10, 5.80 +-10.55, -10.00, 55.42, 44.58, 10.84 +-10.55, -10.00, 52.95, 47.05, 5.90 +-10.55, -10.00, 52.95, 47.05, 5.91 +-10.55, -10.00, 52.96, 47.04, 5.91 +-10.68, -10.00, 58.00, 42.00, 16.00 +-10.68, -10.00, 53.06, 46.94, 6.12 +-10.68, -10.00, 53.06, 46.94, 6.13 +-10.74, -10.00, 55.59, 44.41, 11.17 +-10.74, -10.00, 53.12, 46.88, 6.24 +-10.81, -10.00, 55.64, 44.36, 11.28 +-10.81, -10.00, 53.17, 46.83, 6.35 +-10.81, -10.00, 53.18, 46.82, 6.35 +-10.94, -10.00, 58.22, 41.78, 16.45 +-10.94, -10.00, 53.28, 46.72, 6.56 +-10.94, -10.00, 53.29, 46.71, 6.57 +-11.01, -10.00, 55.81, 44.19, 11.62 +-11.01, -10.00, 53.34, 46.66, 6.69 +-11.07, -10.00, 55.87, 44.13, 11.74 +-11.07, -10.00, 53.40, 46.60, 6.80 +-11.07, -10.00, 53.40, 46.60, 6.81 +-11.21, -10.00, 58.45, 41.55, 16.90 +-11.21, -10.00, 53.51, 46.49, 7.02 +-11.21, -10.00, 53.52, 46.48, 7.03 +-11.21, -10.00, 53.52, 46.48, 7.04 +-11.27, -10.00, 56.05, 43.95, 12.10 +-11.27, -10.00, 53.58, 46.42, 7.16 +-11.34, -10.00, 56.11, 43.89, 12.21 +-11.34, -10.00, 53.64, 46.36, 7.28 +-11.34, -10.00, 53.64, 46.36, 7.29 +-11.47, -10.00, 58.69, 41.31, 17.39 +-11.47, -10.00, 53.75, 46.25, 7.51 +-11.47, -10.00, 53.76, 46.24, 7.52 +-11.47, -10.00, 53.77, 46.23, 7.53 +-11.54, -10.00, 56.29, 43.71, 12.59 +-11.54, -10.00, 53.83, 46.17, 7.65 +-11.60, -10.00, 56.35, 43.65, 12.71 +-11.60, -10.00, 53.89, 46.11, 7.78 +-11.60, -10.00, 53.89, 46.11, 7.79 +-11.60, -10.00, 53.90, 46.10, 7.80 +-11.73, -10.00, 58.95, 41.05, 17.90 +-11.73, -10.00, 54.01, 45.99, 8.02 +-11.73, -10.00, 54.02, 45.98, 8.04 +-11.73, -10.00, 54.03, 45.97, 8.05 +-11.73, -10.00, 54.03, 45.97, 8.06 +-11.73, -10.00, 54.04, 45.96, 8.08 +-11.80, -10.00, 56.57, 43.43, 13.13 +-11.80, -10.00, 54.10, 45.90, 8.20 +-11.80, -10.00, 54.11, 45.89, 8.22 +-11.87, -10.00, 56.64, 43.36, 13.27 +-11.87, -10.00, 54.17, 45.83, 8.34 +-11.87, -10.00, 54.18, 45.82, 8.36 +-11.87, -10.00, 54.19, 45.81, 8.37 +-11.87, -10.00, 54.19, 45.81, 8.38 +-11.87, -10.00, 54.20, 45.80, 8.40 +-11.87, -10.00, 54.21, 45.79, 8.41 +-11.87, -10.00, 54.21, 45.79, 8.43 +-11.87, -10.00, 54.22, 45.78, 8.44 +-11.87, -10.00, 54.23, 45.77, 8.45 +-11.87, -10.00, 54.23, 45.77, 8.47 +-11.87, -10.00, 54.24, 45.76, 8.48 +-11.87, -10.00, 54.25, 45.75, 8.50 +-11.87, -10.00, 54.26, 45.74, 8.51 +-12.00, -10.00, 59.31, 40.69, 18.61 +-11.87, -10.00, 49.33, 50.67, -1.35 +-11.87, -10.00, 54.28, 45.72, 8.55 +-11.87, -10.00, 54.28, 45.72, 8.57 +-11.87, -10.00, 54.29, 45.71, 8.58 +-11.87, -10.00, 54.30, 45.70, 8.60 +-11.87, -10.00, 54.30, 45.70, 8.61 +-11.87, -10.00, 54.31, 45.69, 8.62 +-11.87, -10.00, 54.32, 45.68, 8.64 +-11.87, -10.00, 54.33, 45.67, 8.65 +-11.87, -10.00, 54.33, 45.67, 8.67 +-11.87, -10.00, 54.34, 45.66, 8.68 +-11.87, -10.00, 54.35, 45.65, 8.69 +-11.87, -10.00, 54.35, 45.65, 8.71 +-11.87, -10.00, 54.36, 45.64, 8.72 +-11.87, -10.00, 54.37, 45.63, 8.74 +-11.87, -10.00, 54.37, 45.63, 8.75 +-11.87, -10.00, 54.38, 45.62, 8.76 +-11.87, -10.00, 54.39, 45.61, 8.78 +-11.87, -10.00, 54.40, 45.60, 8.79 +-11.87, -10.00, 54.40, 45.60, 8.81 +-11.87, -10.00, 54.41, 45.59, 8.82 +-11.87, -10.00, 54.42, 45.58, 8.83 +-11.87, -10.00, 54.42, 45.58, 8.85 +-11.87, -10.00, 54.43, 45.57, 8.86 +-11.80, -10.00, 51.92, 48.08, 3.83 +-11.80, -10.00, 54.39, 45.61, 8.79 +-11.80, -10.00, 54.40, 45.60, 8.80 +-11.80, -10.00, 54.41, 45.59, 8.82 +-11.80, -10.00, 54.41, 45.59, 8.83 +-11.73, -10.00, 51.90, 48.10, 3.80 +-11.73, -10.00, 54.38, 45.62, 8.76 +-11.73, -10.00, 54.38, 45.62, 8.77 +-11.73, -10.00, 54.39, 45.61, 8.78 +-11.73, -10.00, 54.40, 45.60, 8.80 +-11.73, -10.00, 54.40, 45.60, 8.81 +-11.73, -10.00, 54.41, 45.59, 8.82 +-11.73, -10.00, 54.42, 45.58, 8.83 +-11.60, -10.00, 49.38, 50.62, -1.24 +-11.60, -10.00, 54.33, 45.67, 8.66 +-11.60, -10.00, 54.34, 45.66, 8.67 +-11.60, -10.00, 54.34, 45.66, 8.69 +-11.54, -10.00, 51.83, 48.17, 3.65 +-11.54, -10.00, 54.30, 45.70, 8.61 +-11.47, -10.00, 51.79, 48.21, 3.58 +-11.47, -10.00, 54.27, 45.73, 8.53 +-11.47, -10.00, 54.27, 45.73, 8.54 +-11.47, -10.00, 54.28, 45.72, 8.55 +-11.34, -10.00, 49.24, 50.76, -1.52 +-11.34, -10.00, 54.19, 45.81, 8.38 +-11.27, -10.00, 51.67, 48.33, 3.34 +-11.27, -10.00, 54.15, 45.85, 8.30 +-11.27, -10.00, 54.15, 45.85, 8.31 +-11.21, -10.00, 51.64, 48.36, 3.27 +-11.21, -10.00, 54.11, 45.89, 8.23 +-11.21, -10.00, 54.12, 45.88, 8.23 +-11.21, -10.00, 54.12, 45.88, 8.24 +-11.07, -10.00, 49.08, 50.92, -1.83 +-11.07, -10.00, 54.03, 45.97, 8.06 +-11.01, -10.00, 51.51, 48.49, 3.03 +-11.01, -10.00, 53.99, 46.01, 7.98 +-11.01, -10.00, 53.99, 46.01, 7.99 +-10.94, -10.00, 51.48, 48.52, 2.95 +-10.94, -10.00, 53.95, 46.05, 7.90 +-10.81, -10.00, 48.91, 51.09, -2.18 +-10.81, -10.00, 53.86, 46.14, 7.72 +-10.74, -10.00, 51.34, 48.66, 2.68 +-10.74, -10.00, 53.81, 46.19, 7.63 +-10.74, -10.00, 53.82, 46.18, 7.63 +-10.68, -10.00, 51.30, 48.70, 2.60 +-10.68, -10.00, 53.77, 46.23, 7.54 +-10.68, -10.00, 53.77, 46.23, 7.55 +-10.55, -10.00, 48.73, 51.27, -2.53 +-10.55, -10.00, 53.68, 46.32, 7.36 +-10.55, -10.00, 53.68, 46.32, 7.36 +-10.55, -10.00, 53.68, 46.32, 7.37 +-10.55, -10.00, 53.69, 46.31, 7.37 +-10.48, -10.00, 51.17, 48.83, 2.33 +-10.48, -10.00, 53.64, 46.36, 7.28 +-10.48, -10.00, 53.64, 46.36, 7.28 +-10.48, -10.00, 53.64, 46.36, 7.29 +-10.48, -10.00, 53.65, 46.35, 7.29 +-10.42, -10.00, 51.13, 48.87, 2.25 +-10.42, -10.00, 53.60, 46.40, 7.20 +-10.42, -10.00, 53.60, 46.40, 7.20 +-10.42, -10.00, 53.60, 46.40, 7.21 +-10.42, -10.00, 53.60, 46.40, 7.21 +-10.42, -10.00, 53.61, 46.39, 7.21 +-10.42, -10.00, 53.61, 46.39, 7.21 +-10.28, -10.00, 48.57, 51.43, -2.87 +-10.28, -10.00, 53.51, 46.49, 7.02 +-10.28, -10.00, 53.51, 46.49, 7.02 +-10.28, -10.00, 53.51, 46.49, 7.03 +-10.28, -10.00, 53.51, 46.49, 7.03 +-10.28, -10.00, 53.51, 46.49, 7.03 +-10.28, -10.00, 53.52, 46.48, 7.03 +-10.28, -10.00, 53.52, 46.48, 7.03 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.04 +-10.28, -10.00, 53.52, 46.48, 7.05 +-10.28, -10.00, 53.52, 46.48, 7.05 +-10.28, -10.00, 53.53, 46.47, 7.05 +-10.28, -10.00, 53.53, 46.47, 7.05 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.06 +-10.28, -10.00, 53.53, 46.47, 7.07 +-10.28, -10.00, 53.53, 46.47, 7.07 +-10.28, -10.00, 53.54, 46.46, 7.07 +-10.28, -10.00, 53.54, 46.46, 7.07 +-10.28, -10.00, 53.54, 46.46, 7.07 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.08 +-10.28, -10.00, 53.54, 46.46, 7.09 +-10.28, -10.00, 53.54, 46.46, 7.09 +-10.28, -10.00, 53.55, 46.45, 7.09 +-10.28, -10.00, 53.55, 46.45, 7.09 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.10 +-10.28, -10.00, 53.55, 46.45, 7.11 +-10.28, -10.00, 53.55, 46.45, 7.11 +-10.22, -10.00, 51.03, 48.97, 2.07 +-10.22, -10.00, 53.51, 46.49, 7.01 +-10.22, -10.00, 53.51, 46.49, 7.01 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.22, -10.00, 53.51, 46.49, 7.02 +-10.15, -10.00, 50.99, 49.01, 1.98 +-10.15, -10.00, 53.46, 46.54, 6.93 +-10.15, -10.00, 53.46, 46.54, 6.93 +-10.15, -10.00, 53.46, 46.54, 6.93 +-10.02, -10.00, 48.42, 51.58, -3.16 +-10.02, -10.00, 53.37, 46.63, 6.73 +-10.02, -10.00, 53.37, 46.63, 6.73 +-10.02, -10.00, 53.37, 46.63, 6.73 +-10.02, -10.00, 53.37, 46.63, 6.73 +-10.02, -10.00, 53.37, 46.63, 6.73 +-9.95, -10.00, 50.84, 49.16, 1.69 +-9.95, -10.00, 53.32, 46.68, 6.63 +-9.89, -10.00, 50.79, 49.21, 1.59 +-9.89, -10.00, 53.27, 46.73, 6.53 +-9.89, -10.00, 53.27, 46.73, 6.53 +-9.76, -10.00, 48.22, 51.78, -3.56 +-9.76, -10.00, 53.16, 46.84, 6.33 +-9.76, -10.00, 53.16, 46.84, 6.33 +-9.76, -10.00, 53.16, 46.84, 6.33 +-9.69, -10.00, 50.64, 49.36, 1.28 +-9.69, -10.00, 53.11, 46.89, 6.22 +-9.62, -10.00, 50.59, 49.41, 1.18 +-9.62, -10.00, 53.06, 46.94, 6.12 +-9.62, -10.00, 53.06, 46.94, 6.11 +-9.49, -10.00, 48.01, 51.99, -3.97 +-9.49, -10.00, 52.95, 47.05, 5.91 +-9.43, -10.00, 50.43, 49.57, 0.86 +-9.43, -10.00, 52.90, 47.10, 5.80 +-9.43, -10.00, 52.90, 47.10, 5.80 +-9.36, -10.00, 50.37, 49.63, 0.75 +-9.36, -10.00, 52.84, 47.16, 5.69 +-9.23, -10.00, 47.80, 52.20, -4.40 +-9.23, -10.00, 52.74, 47.26, 5.48 +-9.23, -10.00, 52.74, 47.26, 5.47 +-9.23, -10.00, 52.73, 47.27, 5.47 +-9.16, -10.00, 50.21, 49.79, 0.42 +-9.16, -10.00, 52.68, 47.32, 5.36 +-9.10, -10.00, 50.15, 49.85, 0.31 +-9.10, -10.00, 52.62, 47.38, 5.24 +-9.10, -10.00, 52.62, 47.38, 5.24 +-8.96, -10.00, 47.57, 52.43, -4.86 +-8.96, -10.00, 52.51, 47.49, 5.02 +-8.96, -10.00, 52.51, 47.49, 5.02 +-8.90, -10.00, 49.98, 50.02, -0.03 +-8.90, -10.00, 52.45, 47.55, 4.90 +-8.90, -10.00, 52.45, 47.55, 4.89 +-8.83, -10.00, 49.92, 50.08, -0.16 +-8.83, -10.00, 52.39, 47.61, 4.78 +-8.83, -10.00, 52.38, 47.62, 4.77 +-8.70, -10.00, 47.34, 52.66, -5.33 +-8.70, -10.00, 52.28, 47.72, 4.55 +-8.70, -10.00, 52.27, 47.73, 4.54 +-8.64, -10.00, 49.74, 50.26, -0.51 +-8.64, -10.00, 52.21, 47.79, 4.42 +-8.64, -10.00, 52.21, 47.79, 4.41 +-8.64, -10.00, 52.20, 47.80, 4.40 +-8.57, -10.00, 49.67, 50.33, -0.65 +-8.57, -10.00, 52.14, 47.86, 4.28 +-8.57, -10.00, 52.13, 47.87, 4.27 +-8.44, -10.00, 47.09, 52.91, -5.83 +-8.44, -10.00, 52.02, 47.98, 4.05 +-8.37, -10.00, 49.50, 50.50, -1.01 +-8.37, -10.00, 51.96, 48.04, 3.92 +-8.37, -10.00, 51.96, 48.04, 3.91 +-8.31, -10.00, 49.43, 50.57, -1.14 +-8.31, -10.00, 51.89, 48.11, 3.79 +-8.31, -10.00, 51.89, 48.11, 3.78 +-8.31, -10.00, 51.88, 48.12, 3.76 +-8.17, -10.00, 46.83, 53.17, -6.34 +-8.17, -10.00, 51.77, 48.23, 3.54 +-8.17, -10.00, 51.76, 48.24, 3.52 +-8.17, -10.00, 51.76, 48.24, 3.51 +-8.11, -10.00, 49.23, 50.77, -1.55 +-8.11, -10.00, 51.69, 48.31, 3.38 +-8.04, -10.00, 49.16, 50.84, -1.67 +-8.04, -10.00, 51.63, 48.37, 3.26 +-8.04, -10.00, 51.62, 48.38, 3.24 +-8.04, -10.00, 51.61, 48.39, 3.23 +-8.04, -10.00, 51.61, 48.39, 3.21 +-7.91, -10.00, 46.55, 53.45, -6.89 +-7.91, -10.00, 51.49, 48.51, 2.98 +-7.91, -10.00, 51.48, 48.52, 2.97 +-7.84, -10.00, 48.95, 51.05, -2.09 +-7.84, -10.00, 51.42, 48.58, 2.83 +-7.84, -10.00, 51.41, 48.59, 2.82 +-7.84, -10.00, 51.40, 48.60, 2.80 +-7.84, -10.00, 51.39, 48.61, 2.79 +-7.84, -10.00, 51.39, 48.61, 2.77 +-7.84, -10.00, 51.38, 48.62, 2.75 +-7.84, -10.00, 51.37, 48.63, 2.74 +-7.84, -10.00, 51.36, 48.64, 2.72 +-7.84, -10.00, 51.35, 48.65, 2.71 +-7.84, -10.00, 51.34, 48.66, 2.69 +-7.84, -10.00, 51.34, 48.66, 2.67 +-7.91, -10.00, 53.85, 46.15, 7.70 +-7.91, -10.00, 51.37, 48.63, 2.74 +-7.91, -10.00, 51.36, 48.64, 2.73 +-7.91, -10.00, 51.35, 48.65, 2.71 +-7.91, -10.00, 51.35, 48.65, 2.69 +-7.91, -10.00, 51.34, 48.66, 2.68 +-8.04, -10.00, 56.37, 43.63, 12.75 +-8.04, -10.00, 51.42, 48.58, 2.85 +-8.04, -10.00, 51.42, 48.58, 2.83 +-8.04, -10.00, 51.41, 48.59, 2.82 +-8.04, -10.00, 51.40, 48.60, 2.80 +-8.04, -10.00, 51.39, 48.61, 2.79 +-8.11, -10.00, 53.91, 46.09, 7.82 +-8.11, -10.00, 51.43, 48.57, 2.86 +-8.11, -10.00, 51.42, 48.58, 2.84 +-8.11, -10.00, 51.41, 48.59, 2.83 +-8.11, -10.00, 51.41, 48.59, 2.82 +-8.17, -10.00, 53.92, 46.08, 7.84 +-8.17, -10.00, 51.44, 48.56, 2.89 +-8.17, -10.00, 51.44, 48.56, 2.87 +-8.17, -10.00, 51.43, 48.57, 2.86 +-8.31, -10.00, 56.47, 43.53, 12.93 +-8.31, -10.00, 51.52, 48.48, 3.03 +-8.31, -10.00, 51.51, 48.49, 3.02 +-8.37, -10.00, 54.02, 45.98, 8.05 +-8.37, -10.00, 51.55, 48.45, 3.09 +-8.44, -10.00, 54.06, 45.94, 8.12 +-8.44, -10.00, 51.58, 48.42, 3.17 +-8.44, -10.00, 51.58, 48.42, 3.16 +-8.44, -10.00, 51.57, 48.43, 3.15 +-8.57, -10.00, 56.61, 43.39, 13.22 +-8.57, -10.00, 51.66, 48.34, 3.32 +-8.57, -10.00, 51.66, 48.34, 3.31 +-8.64, -10.00, 54.17, 45.83, 8.34 +-8.64, -10.00, 51.69, 48.31, 3.39 +-8.64, -10.00, 51.69, 48.31, 3.38 +-8.64, -10.00, 51.68, 48.32, 3.37 +-8.64, -10.00, 51.68, 48.32, 3.36 +-8.70, -10.00, 54.20, 45.80, 8.39 +-8.70, -10.00, 51.72, 48.28, 3.44 +-8.70, -10.00, 51.71, 48.29, 3.43 +-8.70, -10.00, 51.71, 48.29, 3.42 +-8.83, -10.00, 56.75, 43.25, 13.50 +-8.83, -10.00, 51.80, 48.20, 3.60 +-8.83, -10.00, 51.80, 48.20, 3.59 +-8.83, -10.00, 51.79, 48.21, 3.58 +-8.90, -10.00, 54.31, 45.69, 8.62 +-8.90, -10.00, 51.83, 48.17, 3.66 +-8.90, -10.00, 51.83, 48.17, 3.66 +-8.90, -10.00, 51.82, 48.18, 3.65 +-8.96, -10.00, 54.34, 45.66, 8.68 +-8.96, -10.00, 51.87, 48.13, 3.73 +-8.96, -10.00, 51.86, 48.14, 3.72 +-8.96, -10.00, 51.86, 48.14, 3.72 +-8.96, -10.00, 51.85, 48.15, 3.71 +-8.96, -10.00, 51.85, 48.15, 3.70 +-9.10, -10.00, 56.89, 43.11, 13.78 +-9.10, -10.00, 51.94, 48.06, 3.88 +-9.10, -10.00, 51.94, 48.06, 3.88 +-9.10, -10.00, 51.94, 48.06, 3.87 +-9.10, -10.00, 51.93, 48.07, 3.86 +-9.10, -10.00, 51.93, 48.07, 3.86 +-9.10, -10.00, 51.93, 48.07, 3.85 +-9.16, -10.00, 54.44, 45.56, 8.89 +-9.16, -10.00, 51.97, 48.03, 3.94 +-9.16, -10.00, 51.97, 48.03, 3.93 +-9.16, -10.00, 51.96, 48.04, 3.92 +-9.16, -10.00, 51.96, 48.04, 3.92 +-9.16, -10.00, 51.96, 48.04, 3.91 +-9.23, -10.00, 54.47, 45.53, 8.95 +-9.23, -10.00, 52.00, 48.00, 4.00 +-9.23, -10.00, 52.00, 48.00, 3.99 +-9.23, -10.00, 51.99, 48.01, 3.99 +-9.23, -10.00, 51.99, 48.01, 3.98 +-9.36, -10.00, 57.03, 42.97, 14.06 +-9.36, -10.00, 52.08, 47.92, 4.17 +-9.36, -10.00, 52.08, 47.92, 4.16 +-9.36, -10.00, 52.08, 47.92, 4.16 +-9.43, -10.00, 54.60, 45.40, 9.20 +-9.43, -10.00, 52.13, 47.87, 4.25 +-9.43, -10.00, 52.12, 47.88, 4.25 +-9.49, -10.00, 54.64, 45.36, 9.28 +-9.49, -10.00, 52.17, 47.83, 4.34 +-9.49, -10.00, 52.17, 47.83, 4.33 +-9.62, -10.00, 57.21, 42.79, 14.42 +-9.62, -10.00, 52.26, 47.74, 4.53 +-9.62, -10.00, 52.26, 47.74, 4.52 +-9.69, -10.00, 54.78, 45.22, 9.56 +-9.69, -10.00, 52.31, 47.69, 4.62 +-9.69, -10.00, 52.31, 47.69, 4.61 +-9.76, -10.00, 54.83, 45.17, 9.66 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.89, -10.00, 57.40, 42.60, 14.79 +-9.89, -10.00, 52.45, 47.55, 4.90 +-9.89, -10.00, 52.45, 47.55, 4.90 +-9.89, -10.00, 52.45, 47.55, 4.90 +-9.89, -10.00, 52.45, 47.55, 4.90 +-9.95, -10.00, 54.97, 45.03, 9.94 +-9.95, -10.00, 52.50, 47.50, 5.00 +-10.02, -10.00, 55.02, 44.98, 10.04 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.02, -10.00, 52.55, 47.45, 5.10 +-10.15, -10.00, 57.59, 42.41, 15.19 +-10.02, -10.00, 47.61, 52.39, -4.79 +-10.15, -10.00, 57.59, 42.41, 15.19 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.30 +-10.15, -10.00, 52.65, 47.35, 5.31 +-10.15, -10.00, 52.65, 47.35, 5.31 +-10.15, -10.00, 52.65, 47.35, 5.31 +-10.15, -10.00, 52.65, 47.35, 5.31 +-10.02, -10.00, 47.61, 52.39, -4.78 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-10.02, -10.00, 52.56, 47.44, 5.11 +-9.95, -10.00, 50.03, 49.97, 0.07 +-9.95, -10.00, 52.51, 47.49, 5.01 +-9.95, -10.00, 52.51, 47.49, 5.01 +-9.89, -10.00, 49.98, 50.02, -0.03 +-9.89, -10.00, 52.46, 47.54, 4.91 +-9.89, -10.00, 52.46, 47.54, 4.91 +-9.89, -10.00, 52.46, 47.54, 4.91 +-9.89, -10.00, 52.45, 47.55, 4.91 +-9.76, -10.00, 47.41, 52.59, -5.18 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.76, -10.00, 52.35, 47.65, 4.71 +-9.76, -10.00, 52.35, 47.65, 4.70 +-9.69, -10.00, 49.83, 50.17, -0.34 +-9.69, -10.00, 52.30, 47.70, 4.60 +-9.69, -10.00, 52.30, 47.70, 4.60 +-9.62, -10.00, 49.78, 50.22, -0.45 +-9.62, -10.00, 52.25, 47.75, 4.49 +-9.62, -10.00, 52.25, 47.75, 4.49 +-9.62, -10.00, 52.24, 47.76, 4.49 +-9.49, -10.00, 47.20, 52.80, -5.60 +-9.49, -10.00, 52.14, 47.86, 4.28 +-9.49, -10.00, 52.14, 47.86, 4.28 +-9.49, -10.00, 52.14, 47.86, 4.28 +-9.49, -10.00, 52.14, 47.86, 4.27 +-9.43, -10.00, 49.61, 50.39, -0.78 +-9.43, -10.00, 52.08, 47.92, 4.16 +-9.43, -10.00, 52.08, 47.92, 4.16 +-9.43, -10.00, 52.08, 47.92, 4.16 +-9.43, -10.00, 52.08, 47.92, 4.15 +-9.43, -10.00, 52.07, 47.93, 4.15 +-9.43, -10.00, 52.07, 47.93, 4.14 +-9.36, -10.00, 49.55, 50.45, -0.90 +-9.36, -10.00, 52.02, 47.98, 4.03 +-9.36, -10.00, 52.01, 47.99, 4.03 +-9.36, -10.00, 52.01, 47.99, 4.02 +-9.36, -10.00, 52.01, 47.99, 4.02 +-9.36, -10.00, 52.01, 47.99, 4.02 +-9.23, -10.00, 46.96, 53.04, -6.08 +-9.23, -10.00, 51.90, 48.10, 3.81 +-9.23, -10.00, 51.90, 48.10, 3.80 +-9.23, -10.00, 51.90, 48.10, 3.79 +-9.23, -10.00, 51.89, 48.11, 3.79 +-9.23, -10.00, 51.89, 48.11, 3.78 +-9.23, -10.00, 51.89, 48.11, 3.78 +-9.23, -10.00, 51.89, 48.11, 3.77 +-9.23, -10.00, 51.88, 48.12, 3.77 +-9.23, -10.00, 51.88, 48.12, 3.76 +-9.23, -10.00, 51.88, 48.12, 3.75 +-9.23, -10.00, 51.87, 48.13, 3.75 +-9.23, -10.00, 51.87, 48.13, 3.74 +-9.23, -10.00, 51.87, 48.13, 3.74 +-9.23, -10.00, 51.87, 48.13, 3.73 +-9.23, -10.00, 51.86, 48.14, 3.72 +-9.23, -10.00, 51.86, 48.14, 3.72 +-9.16, -10.00, 49.33, 50.67, -1.33 +-9.16, -10.00, 51.80, 48.20, 3.61 +-9.23, -10.00, 54.32, 45.68, 8.64 +-9.23, -10.00, 51.85, 48.15, 3.69 +-9.23, -10.00, 51.84, 48.16, 3.69 +-9.23, -10.00, 51.84, 48.16, 3.68 +-9.16, -10.00, 49.32, 50.68, -1.37 +-9.16, -10.00, 51.79, 48.21, 3.57 +-9.16, -10.00, 51.78, 48.22, 3.57 +-9.16, -10.00, 51.78, 48.22, 3.56 +-9.16, -10.00, 51.78, 48.22, 3.55 +-9.16, -10.00, 51.77, 48.23, 3.55 +-9.16, -10.00, 51.77, 48.23, 3.54 +-9.16, -10.00, 51.77, 48.23, 3.53 +-9.16, -10.00, 51.76, 48.24, 3.53 +-9.23, -10.00, 54.28, 45.72, 8.56 +-9.23, -10.00, 51.81, 48.19, 3.62 +-9.16, -10.00, 49.28, 50.72, -1.43 +-9.16, -10.00, 51.75, 48.25, 3.50 +-9.16, -10.00, 51.75, 48.25, 3.50 +-9.16, -10.00, 51.75, 48.25, 3.49 +-9.23, -10.00, 54.26, 45.74, 8.53 +-9.23, -10.00, 51.79, 48.21, 3.58 +-9.23, -10.00, 51.79, 48.21, 3.57 +-9.23, -10.00, 51.78, 48.22, 3.57 +-9.23, -10.00, 51.78, 48.22, 3.56 +-9.23, -10.00, 51.78, 48.22, 3.56 +-9.23, -10.00, 51.77, 48.23, 3.55 +-9.23, -10.00, 51.77, 48.23, 3.54 +-9.23, -10.00, 51.77, 48.23, 3.54 +-9.23, -10.00, 51.77, 48.23, 3.53 +-9.23, -10.00, 51.76, 48.24, 3.53 +-9.23, -10.00, 51.76, 48.24, 3.52 +-9.23, -10.00, 51.76, 48.24, 3.51 +-9.23, -10.00, 51.75, 48.25, 3.51 +-9.23, -10.00, 51.75, 48.25, 3.50 +-9.23, -10.00, 51.75, 48.25, 3.50 +-9.23, -10.00, 51.75, 48.25, 3.49 +-9.23, -10.00, 51.74, 48.26, 3.49 +-9.23, -10.00, 51.74, 48.26, 3.48 +-9.23, -10.00, 51.74, 48.26, 3.47 +-9.23, -10.00, 51.73, 48.27, 3.47 +-9.36, -10.00, 56.77, 43.23, 13.55 +-9.36, -10.00, 51.83, 48.17, 3.66 +-9.36, -10.00, 51.83, 48.17, 3.65 +-9.36, -10.00, 51.82, 48.18, 3.65 +-9.36, -10.00, 51.82, 48.18, 3.64 +-9.36, -10.00, 51.82, 48.18, 3.64 +-9.36, -10.00, 51.82, 48.18, 3.63 +-9.36, -10.00, 51.81, 48.19, 3.63 +-9.36, -10.00, 51.81, 48.19, 3.62 +-9.43, -10.00, 54.33, 45.67, 8.66 +-9.43, -10.00, 51.86, 48.14, 3.71 +-9.43, -10.00, 51.85, 48.15, 3.71 +-9.43, -10.00, 51.85, 48.15, 3.70 +-9.43, -10.00, 51.85, 48.15, 3.70 +-9.43, -10.00, 51.85, 48.15, 3.70 +-9.43, -10.00, 51.85, 48.15, 3.69 +-9.43, -10.00, 51.84, 48.16, 3.69 +-9.43, -10.00, 51.84, 48.16, 3.68 +-9.49, -10.00, 54.36, 45.64, 8.72 +-9.49, -10.00, 51.89, 48.11, 3.77 +-9.49, -10.00, 51.89, 48.11, 3.77 +-9.49, -10.00, 51.88, 48.12, 3.77 +-9.49, -10.00, 51.88, 48.12, 3.76 +-9.49, -10.00, 51.88, 48.12, 3.76 +-9.49, -10.00, 51.88, 48.12, 3.76 +-9.49, -10.00, 51.88, 48.12, 3.75 +-9.62, -10.00, 56.92, 43.08, 13.83 +-9.62, -10.00, 51.97, 48.03, 3.94 +-9.62, -10.00, 51.97, 48.03, 3.94 +-9.62, -10.00, 51.97, 48.03, 3.94 +-9.62, -10.00, 51.97, 48.03, 3.94 +-9.62, -10.00, 51.97, 48.03, 3.93 +-9.62, -10.00, 51.96, 48.04, 3.93 +-9.62, -10.00, 51.96, 48.04, 3.93 +-9.62, -10.00, 51.96, 48.04, 3.92 +-9.62, -10.00, 51.96, 48.04, 3.92 +-9.62, -10.00, 51.96, 48.04, 3.92 +-9.62, -10.00, 51.96, 48.04, 3.92 +-9.62, -10.00, 51.96, 48.04, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.90 +-9.62, -10.00, 51.95, 48.05, 3.90 +-9.62, -10.00, 51.95, 48.05, 3.90 +-9.69, -10.00, 54.47, 45.53, 8.94 +-9.69, -10.00, 52.00, 48.00, 3.99 +-9.69, -10.00, 52.00, 48.00, 3.99 +-9.69, -10.00, 51.99, 48.01, 3.99 +-9.62, -10.00, 49.47, 50.53, -1.06 +-9.62, -10.00, 51.94, 48.06, 3.88 +-9.62, -10.00, 51.94, 48.06, 3.88 +-9.62, -10.00, 51.94, 48.06, 3.88 +-9.62, -10.00, 51.94, 48.06, 3.88 +-9.62, -10.00, 51.94, 48.06, 3.87 +-9.62, -10.00, 51.93, 48.07, 3.87 +-9.62, -10.00, 51.93, 48.07, 3.87 +-9.49, -10.00, 46.89, 53.11, -6.22 +-9.49, -10.00, 51.83, 48.17, 3.66 +-9.49, -10.00, 51.83, 48.17, 3.66 +-9.49, -10.00, 51.83, 48.17, 3.65 +-9.49, -10.00, 51.82, 48.18, 3.65 +-9.49, -10.00, 51.82, 48.18, 3.65 +-9.43, -10.00, 49.30, 50.70, -1.40 +-9.43, -10.00, 51.77, 48.23, 3.54 +-9.43, -10.00, 51.77, 48.23, 3.53 +-9.43, -10.00, 51.77, 48.23, 3.53 +-9.43, -10.00, 51.76, 48.24, 3.53 +-9.36, -10.00, 49.24, 50.76, -1.52 +-9.36, -10.00, 51.71, 48.29, 3.42 +-9.36, -10.00, 51.71, 48.29, 3.41 +-9.23, -10.00, 46.66, 53.34, -6.68 +-9.23, -10.00, 51.60, 48.40, 3.20 +-9.23, -10.00, 51.60, 48.40, 3.20 +-9.23, -10.00, 51.60, 48.40, 3.19 +-9.16, -10.00, 49.07, 50.93, -1.86 +-9.16, -10.00, 51.54, 48.46, 3.08 +-9.10, -10.00, 49.02, 50.98, -1.97 +-9.10, -10.00, 51.48, 48.52, 2.97 +-9.10, -10.00, 51.48, 48.52, 2.96 +-8.96, -10.00, 46.43, 53.57, -7.13 +-8.96, -10.00, 51.37, 48.63, 2.75 +-8.96, -10.00, 51.37, 48.63, 2.74 +-8.90, -10.00, 48.84, 51.16, -2.31 +-8.90, -10.00, 51.31, 48.69, 2.62 +-8.90, -10.00, 51.31, 48.69, 2.62 +-8.83, -10.00, 48.78, 51.22, -2.44 +-8.83, -10.00, 51.25, 48.75, 2.50 +-8.83, -10.00, 51.25, 48.75, 2.49 +-8.70, -10.00, 46.20, 53.80, -7.60 +-8.70, -10.00, 51.14, 48.86, 2.27 +-8.64, -10.00, 48.61, 51.39, -2.78 +-8.64, -10.00, 51.08, 48.92, 2.15 +-8.64, -10.00, 51.07, 48.93, 2.14 +-8.64, -10.00, 51.07, 48.93, 2.13 +-8.57, -10.00, 48.54, 51.46, -2.92 +-8.57, -10.00, 51.01, 48.99, 2.01 +-8.57, -10.00, 51.00, 49.00, 2.00 +-8.57, -10.00, 51.00, 49.00, 1.99 +-8.44, -10.00, 45.95, 54.05, -8.10 +-8.44, -10.00, 50.89, 49.11, 1.77 +-8.44, -10.00, 50.88, 49.12, 1.76 +-8.44, -10.00, 50.87, 49.13, 1.75 +-8.37, -10.00, 48.35, 51.65, -3.31 +-8.37, -10.00, 50.81, 49.19, 1.62 +-8.37, -10.00, 50.81, 49.19, 1.61 +-8.37, -10.00, 50.80, 49.20, 1.60 +-8.37, -10.00, 50.79, 49.21, 1.59 +-8.31, -10.00, 48.27, 51.73, -3.47 +-8.31, -10.00, 50.73, 49.27, 1.46 +-8.31, -10.00, 50.73, 49.27, 1.45 +-8.31, -10.00, 50.72, 49.28, 1.44 +-8.31, -10.00, 50.71, 49.29, 1.43 +-8.31, -10.00, 50.71, 49.29, 1.41 +-8.31, -10.00, 50.70, 49.30, 1.40 +-8.31, -10.00, 50.69, 49.31, 1.39 +-8.17, -10.00, 45.64, 54.36, -8.71 +-8.17, -10.00, 50.58, 49.42, 1.16 +-8.31, -10.00, 55.62, 44.38, 11.23 +-8.31, -10.00, 50.67, 49.33, 1.33 +-8.31, -10.00, 50.66, 49.34, 1.32 +-8.31, -10.00, 50.65, 49.35, 1.31 +-8.31, -10.00, 50.65, 49.35, 1.30 +-8.31, -10.00, 50.64, 49.36, 1.28 +-8.31, -10.00, 50.64, 49.36, 1.27 +-8.31, -10.00, 50.63, 49.37, 1.26 +-8.31, -10.00, 50.62, 49.38, 1.25 +-8.37, -10.00, 53.14, 46.86, 6.28 +-8.37, -10.00, 50.66, 49.34, 1.32 +-8.37, -10.00, 50.65, 49.35, 1.31 +-8.37, -10.00, 50.65, 49.35, 1.30 +-8.37, -10.00, 50.64, 49.36, 1.28 +-8.44, -10.00, 53.16, 46.84, 6.31 +-8.44, -10.00, 50.68, 49.32, 1.36 +-8.44, -10.00, 50.67, 49.33, 1.35 +-8.44, -10.00, 50.67, 49.33, 1.34 +-8.57, -10.00, 55.70, 44.30, 11.41 +-8.57, -10.00, 50.76, 49.24, 1.51 +-8.57, -10.00, 50.75, 49.25, 1.50 +-8.64, -10.00, 53.27, 46.73, 6.53 +-8.64, -10.00, 50.79, 49.21, 1.58 +-8.64, -10.00, 50.78, 49.22, 1.57 +-8.70, -10.00, 53.30, 46.70, 6.60 +-8.70, -10.00, 50.82, 49.18, 1.65 +-8.70, -10.00, 50.82, 49.18, 1.64 +-8.83, -10.00, 55.86, 44.14, 11.72 +-8.83, -10.00, 50.91, 49.09, 1.82 +-8.90, -10.00, 53.43, 46.57, 6.85 +-8.90, -10.00, 50.95, 49.05, 1.90 +-8.90, -10.00, 50.95, 49.05, 1.89 +-8.96, -10.00, 53.46, 46.54, 6.93 +-8.96, -10.00, 50.99, 49.01, 1.98 +-8.96, -10.00, 50.98, 49.02, 1.97 +-9.10, -10.00, 56.02, 43.98, 12.05 +-9.10, -10.00, 51.08, 48.92, 2.15 +-9.10, -10.00, 51.07, 48.93, 2.15 +-9.16, -10.00, 53.59, 46.41, 7.18 +-9.16, -10.00, 51.12, 48.88, 2.23 +-9.16, -10.00, 51.11, 48.89, 2.23 +-9.23, -10.00, 53.63, 46.37, 7.26 +-9.23, -10.00, 51.16, 48.84, 2.31 +-9.23, -10.00, 51.15, 48.85, 2.31 +-9.23, -10.00, 51.15, 48.85, 2.30 +-9.23, -10.00, 51.15, 48.85, 2.30 +-9.36, -10.00, 56.19, 43.81, 12.38 +-9.36, -10.00, 51.24, 48.76, 2.48 +-9.36, -10.00, 51.24, 48.76, 2.48 +-9.43, -10.00, 53.76, 46.24, 7.52 +-9.43, -10.00, 51.28, 48.72, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.56 +-9.49, -10.00, 53.80, 46.20, 7.60 +-9.49, -10.00, 51.33, 48.67, 2.65 +-9.49, -10.00, 51.32, 48.68, 2.65 +-9.49, -10.00, 51.32, 48.68, 2.64 +-9.62, -10.00, 56.36, 43.64, 12.73 +-9.62, -10.00, 51.42, 48.58, 2.84 +-9.62, -10.00, 51.42, 48.58, 2.83 +-9.62, -10.00, 51.42, 48.58, 2.83 +-9.62, -10.00, 51.41, 48.59, 2.83 +-9.69, -10.00, 53.93, 46.07, 7.87 +-9.69, -10.00, 51.46, 48.54, 2.92 +-9.69, -10.00, 51.46, 48.54, 2.92 +-9.69, -10.00, 51.46, 48.54, 2.92 +-9.76, -10.00, 53.98, 46.02, 7.96 +-9.76, -10.00, 51.51, 48.49, 3.01 +-9.76, -10.00, 51.51, 48.49, 3.01 +-9.76, -10.00, 51.50, 48.50, 3.01 +-9.76, -10.00, 51.50, 48.50, 3.01 +-9.76, -10.00, 51.50, 48.50, 3.01 +-9.76, -10.00, 51.50, 48.50, 3.00 +-9.76, -10.00, 51.50, 48.50, 3.00 +-9.76, -10.00, 51.50, 48.50, 3.00 +-9.89, -10.00, 56.54, 43.46, 13.08 +-9.76, -10.00, 46.55, 53.45, -6.89 +-9.89, -10.00, 56.54, 43.46, 13.08 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.60, 48.40, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.19 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.95, -10.00, 54.11, 45.89, 8.23 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.95, -10.00, 51.64, 48.36, 3.28 +-9.89, -10.00, 49.12, 50.88, -1.77 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.18 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.59, 48.41, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.17 +-9.89, -10.00, 51.58, 48.42, 3.16 +-9.76, -10.00, 46.54, 53.46, -6.92 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.96 +-9.76, -10.00, 51.48, 48.52, 2.95 +-9.76, -10.00, 51.48, 48.52, 2.95 +-9.76, -10.00, 51.48, 48.52, 2.95 +-9.76, -10.00, 51.47, 48.53, 2.95 +-9.76, -10.00, 51.47, 48.53, 2.95 +-9.69, -10.00, 48.95, 51.05, -2.10 +-9.69, -10.00, 51.42, 48.58, 2.84 +-9.69, -10.00, 51.42, 48.58, 2.84 +-9.69, -10.00, 51.42, 48.58, 2.84 +-9.62, -10.00, 48.90, 51.10, -2.21 +-9.62, -10.00, 51.37, 48.63, 2.73 +-9.62, -10.00, 51.37, 48.63, 2.73 +-9.62, -10.00, 51.36, 48.64, 2.73 +-9.49, -10.00, 46.32, 53.68, -7.36 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.51 +-9.49, -10.00, 51.25, 48.75, 2.51 +-9.43, -10.00, 48.73, 51.27, -2.54 +-9.43, -10.00, 51.20, 48.80, 2.40 +-9.43, -10.00, 51.20, 48.80, 2.40 +-9.43, -10.00, 51.20, 48.80, 2.39 +-9.43, -10.00, 51.19, 48.81, 2.39 +-9.43, -10.00, 51.19, 48.81, 2.38 +-9.43, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 48.67, 51.33, -2.67 +-9.36, -10.00, 51.14, 48.86, 2.27 +-9.36, -10.00, 51.13, 48.87, 2.27 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.25 +-9.36, -10.00, 51.12, 48.88, 2.25 +-9.36, -10.00, 51.12, 48.88, 2.24 +-9.36, -10.00, 51.12, 48.88, 2.24 +-9.36, -10.00, 51.12, 48.88, 2.23 +-9.23, -10.00, 46.07, 53.93, -7.86 +-9.36, -10.00, 56.05, 43.95, 12.11 +-9.36, -10.00, 51.11, 48.89, 2.22 +-9.23, -10.00, 46.06, 53.94, -7.87 +-9.23, -10.00, 51.00, 49.00, 2.01 +-9.23, -10.00, 51.00, 49.00, 2.00 +-9.23, -10.00, 51.00, 49.00, 2.00 +-9.23, -10.00, 51.00, 49.00, 1.99 +-9.23, -10.00, 50.99, 49.01, 1.98 +-9.23, -10.00, 50.99, 49.01, 1.98 +-9.23, -10.00, 50.99, 49.01, 1.97 +-9.23, -10.00, 50.98, 49.02, 1.97 +-9.23, -10.00, 50.98, 49.02, 1.96 +-9.23, -10.00, 50.98, 49.02, 1.96 +-9.23, -10.00, 50.97, 49.03, 1.95 +-9.23, -10.00, 50.97, 49.03, 1.94 +-9.23, -10.00, 50.97, 49.03, 1.94 +-9.23, -10.00, 50.97, 49.03, 1.93 +-9.23, -10.00, 50.96, 49.04, 1.93 +-9.23, -10.00, 50.96, 49.04, 1.92 +-9.23, -10.00, 50.96, 49.04, 1.91 +-9.23, -10.00, 50.95, 49.05, 1.91 +-9.23, -10.00, 50.95, 49.05, 1.90 +-9.23, -10.00, 50.95, 49.05, 1.90 +-9.23, -10.00, 50.95, 49.05, 1.89 +-9.23, -10.00, 50.94, 49.06, 1.89 +-9.36, -10.00, 55.98, 44.02, 11.97 +-9.23, -10.00, 45.99, 54.01, -8.01 +-9.36, -10.00, 55.98, 44.02, 11.96 +-9.36, -10.00, 51.03, 48.97, 2.06 +-9.36, -10.00, 51.03, 48.97, 2.06 +-9.36, -10.00, 51.03, 48.97, 2.05 +-9.36, -10.00, 51.02, 48.98, 2.05 +-9.36, -10.00, 51.02, 48.98, 2.04 +-9.36, -10.00, 51.02, 48.98, 2.04 +-9.43, -10.00, 53.54, 46.46, 7.08 +-9.43, -10.00, 51.06, 48.94, 2.13 +-9.43, -10.00, 51.06, 48.94, 2.13 +-9.43, -10.00, 51.06, 48.94, 2.12 +-9.43, -10.00, 51.06, 48.94, 2.12 +-9.43, -10.00, 51.06, 48.94, 2.11 +-9.43, -10.00, 51.05, 48.95, 2.11 +-9.43, -10.00, 51.05, 48.95, 2.10 +-9.49, -10.00, 53.57, 46.43, 7.14 +-9.49, -10.00, 51.10, 48.90, 2.20 +-9.49, -10.00, 51.10, 48.90, 2.19 +-9.49, -10.00, 51.09, 48.91, 2.19 +-9.49, -10.00, 51.09, 48.91, 2.18 +-9.49, -10.00, 51.09, 48.91, 2.18 +-9.62, -10.00, 56.13, 43.87, 12.26 +-9.62, -10.00, 51.19, 48.81, 2.37 +-9.62, -10.00, 51.18, 48.82, 2.37 +-9.62, -10.00, 51.18, 48.82, 2.37 +-9.62, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 53.70, 46.30, 7.40 +-9.69, -10.00, 51.23, 48.77, 2.46 +-9.69, -10.00, 51.23, 48.77, 2.46 +-9.69, -10.00, 51.23, 48.77, 2.45 +-9.69, -10.00, 51.23, 48.77, 2.45 +-9.76, -10.00, 53.75, 46.25, 7.49 +-9.76, -10.00, 51.27, 48.73, 2.55 +-9.76, -10.00, 51.27, 48.73, 2.54 +-9.76, -10.00, 51.27, 48.73, 2.54 +-9.76, -10.00, 51.27, 48.73, 2.54 +-9.76, -10.00, 51.27, 48.73, 2.54 +-9.89, -10.00, 56.31, 43.69, 12.62 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.89, -10.00, 51.37, 48.63, 2.73 +-9.95, -10.00, 53.89, 46.11, 7.77 +-9.95, -10.00, 51.41, 48.59, 2.83 +-9.95, -10.00, 51.41, 48.59, 2.83 +-9.95, -10.00, 51.41, 48.59, 2.83 +-10.02, -10.00, 53.94, 46.06, 7.87 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.02, -10.00, 51.46, 48.54, 2.93 +-10.15, -10.00, 56.51, 43.49, 13.02 +-10.15, -10.00, 51.56, 48.44, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.15, -10.00, 51.57, 48.43, 3.13 +-10.22, -10.00, 54.09, 45.91, 8.18 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.22, -10.00, 51.62, 48.38, 3.24 +-10.28, -10.00, 54.14, 45.86, 8.29 +-10.28, -10.00, 51.67, 48.33, 3.35 +-10.28, -10.00, 51.67, 48.33, 3.35 +-10.28, -10.00, 51.68, 48.32, 3.35 +-10.28, -10.00, 51.68, 48.32, 3.35 +-10.42, -10.00, 56.72, 43.28, 13.44 +-10.42, -10.00, 51.78, 48.22, 3.56 +-10.42, -10.00, 51.78, 48.22, 3.56 +-10.42, -10.00, 51.78, 48.22, 3.56 +-10.42, -10.00, 51.78, 48.22, 3.57 +-10.42, -10.00, 51.78, 48.22, 3.57 +-10.42, -10.00, 51.79, 48.21, 3.57 +-10.42, -10.00, 51.79, 48.21, 3.58 +-10.42, -10.00, 51.79, 48.21, 3.58 +-10.42, -10.00, 51.79, 48.21, 3.58 +-10.42, -10.00, 51.79, 48.21, 3.58 +-10.42, -10.00, 51.79, 48.21, 3.59 +-10.48, -10.00, 54.32, 45.68, 8.63 +-10.48, -10.00, 51.85, 48.15, 3.69 +-10.48, -10.00, 51.85, 48.15, 3.70 +-10.48, -10.00, 51.85, 48.15, 3.70 +-10.48, -10.00, 51.85, 48.15, 3.70 +-10.48, -10.00, 51.85, 48.15, 3.71 +-10.48, -10.00, 51.86, 48.14, 3.71 +-10.48, -10.00, 51.86, 48.14, 3.72 +-10.48, -10.00, 51.86, 48.14, 3.72 +-10.48, -10.00, 51.86, 48.14, 3.72 +-10.48, -10.00, 51.86, 48.14, 3.73 +-10.48, -10.00, 51.87, 48.13, 3.73 +-10.48, -10.00, 51.87, 48.13, 3.73 +-10.48, -10.00, 51.87, 48.13, 3.74 +-10.55, -10.00, 54.39, 45.61, 8.78 +-10.55, -10.00, 51.92, 48.08, 3.84 +-10.55, -10.00, 51.92, 48.08, 3.85 +-10.55, -10.00, 51.93, 48.07, 3.85 +-10.55, -10.00, 51.93, 48.07, 3.86 +-10.55, -10.00, 51.93, 48.07, 3.86 +-10.55, -10.00, 51.93, 48.07, 3.86 +-10.55, -10.00, 51.93, 48.07, 3.87 +-10.55, -10.00, 51.94, 48.06, 3.87 +-10.55, -10.00, 51.94, 48.06, 3.88 +-10.55, -10.00, 51.94, 48.06, 3.88 +-10.68, -10.00, 56.99, 43.01, 13.97 +-10.68, -10.00, 52.04, 47.96, 4.09 +-10.68, -10.00, 52.05, 47.95, 4.09 +-10.68, -10.00, 52.05, 47.95, 4.10 +-10.55, -10.00, 47.01, 52.99, -5.98 +-10.55, -10.00, 51.95, 48.05, 3.91 +-10.68, -10.00, 57.00, 43.00, 14.00 +-10.55, -10.00, 47.02, 52.98, -5.97 +-10.68, -10.00, 57.00, 43.00, 14.01 +-10.55, -10.00, 47.02, 52.98, -5.96 +-10.68, -10.00, 57.01, 42.99, 14.02 +-10.68, -10.00, 52.07, 47.93, 4.14 +-10.68, -10.00, 52.07, 47.93, 4.14 +-10.68, -10.00, 52.07, 47.93, 4.15 +-10.68, -10.00, 52.08, 47.92, 4.15 +-10.68, -10.00, 52.08, 47.92, 4.16 +-10.68, -10.00, 52.08, 47.92, 4.16 +-10.68, -10.00, 52.08, 47.92, 4.17 +-10.68, -10.00, 52.09, 47.91, 4.17 +-10.68, -10.00, 52.09, 47.91, 4.18 +-10.68, -10.00, 52.09, 47.91, 4.18 +-10.68, -10.00, 52.09, 47.91, 4.19 +-10.55, -10.00, 47.05, 52.95, -5.89 +-10.55, -10.00, 52.00, 48.00, 4.00 +-10.55, -10.00, 52.00, 48.00, 4.00 +-10.55, -10.00, 52.00, 48.00, 4.01 +-10.55, -10.00, 52.00, 48.00, 4.01 +-10.55, -10.00, 52.01, 47.99, 4.01 +-10.55, -10.00, 52.01, 47.99, 4.02 +-10.55, -10.00, 52.01, 47.99, 4.02 +-10.55, -10.00, 52.01, 47.99, 4.03 +-10.55, -10.00, 52.02, 47.98, 4.03 +-10.55, -10.00, 52.02, 47.98, 4.03 +-10.55, -10.00, 52.02, 47.98, 4.04 +-10.55, -10.00, 52.02, 47.98, 4.04 +-10.55, -10.00, 52.02, 47.98, 4.05 +-10.55, -10.00, 52.03, 47.97, 4.05 +-10.55, -10.00, 52.03, 47.97, 4.05 +-10.55, -10.00, 52.03, 47.97, 4.06 +-10.55, -10.00, 52.03, 47.97, 4.06 +-10.55, -10.00, 52.03, 47.97, 4.07 +-10.55, -10.00, 52.04, 47.96, 4.07 +-10.55, -10.00, 52.04, 47.96, 4.08 +-10.68, -10.00, 57.08, 42.92, 14.17 +-10.55, -10.00, 47.10, 52.90, -5.80 +-10.68, -10.00, 57.09, 42.91, 14.18 +-10.68, -10.00, 52.15, 47.85, 4.29 +-10.68, -10.00, 52.15, 47.85, 4.30 +-10.68, -10.00, 52.15, 47.85, 4.30 +-10.68, -10.00, 52.15, 47.85, 4.31 +-10.68, -10.00, 52.16, 47.84, 4.31 +-10.68, -10.00, 52.16, 47.84, 4.32 +-10.68, -10.00, 52.16, 47.84, 4.32 +-10.68, -10.00, 52.16, 47.84, 4.33 +-10.68, -10.00, 52.17, 47.83, 4.33 +-10.68, -10.00, 52.17, 47.83, 4.34 +-10.68, -10.00, 52.17, 47.83, 4.34 +-10.68, -10.00, 52.17, 47.83, 4.35 +-10.68, -10.00, 52.18, 47.82, 4.35 +-10.68, -10.00, 52.18, 47.82, 4.36 +-10.68, -10.00, 52.18, 47.82, 4.36 +-10.68, -10.00, 52.18, 47.82, 4.37 +-10.68, -10.00, 52.19, 47.81, 4.37 +-10.68, -10.00, 52.19, 47.81, 4.38 +-10.68, -10.00, 52.19, 47.81, 4.38 +-10.68, -10.00, 52.19, 47.81, 4.39 +-10.68, -10.00, 52.20, 47.80, 4.39 +-10.68, -10.00, 52.20, 47.80, 4.40 +-10.74, -10.00, 54.72, 45.28, 9.45 +-10.74, -10.00, 52.25, 47.75, 4.51 +-10.74, -10.00, 52.26, 47.74, 4.52 +-10.68, -10.00, 49.74, 50.26, -0.52 +-10.68, -10.00, 52.21, 47.79, 4.43 +-10.68, -10.00, 52.22, 47.78, 4.43 +-10.68, -10.00, 52.22, 47.78, 4.44 +-10.68, -10.00, 52.22, 47.78, 4.44 +-10.68, -10.00, 52.22, 47.78, 4.45 +-10.68, -10.00, 52.23, 47.77, 4.45 +-10.68, -10.00, 52.23, 47.77, 4.46 +-10.68, -10.00, 52.23, 47.77, 4.46 +-10.68, -10.00, 52.23, 47.77, 4.47 +-10.68, -10.00, 52.24, 47.76, 4.47 +-10.68, -10.00, 52.24, 47.76, 4.48 +-10.68, -10.00, 52.24, 47.76, 4.48 +-10.68, -10.00, 52.24, 47.76, 4.49 +-10.68, -10.00, 52.25, 47.75, 4.49 +-10.68, -10.00, 52.25, 47.75, 4.50 +-10.68, -10.00, 52.25, 47.75, 4.50 +-10.68, -10.00, 52.25, 47.75, 4.51 +-10.68, -10.00, 52.26, 47.74, 4.51 +-10.68, -10.00, 52.26, 47.74, 4.52 +-10.55, -10.00, 47.22, 52.78, -5.56 +-10.68, -10.00, 57.21, 42.79, 14.41 +-10.68, -10.00, 52.27, 47.73, 4.53 +-10.55, -10.00, 47.23, 52.77, -5.55 +-10.55, -10.00, 52.17, 47.83, 4.34 +-10.55, -10.00, 52.17, 47.83, 4.35 +-10.55, -10.00, 52.18, 47.82, 4.35 +-10.55, -10.00, 52.18, 47.82, 4.36 +-10.55, -10.00, 52.18, 47.82, 4.36 +-10.55, -10.00, 52.18, 47.82, 4.36 +-10.55, -10.00, 52.18, 47.82, 4.37 +-10.55, -10.00, 52.19, 47.81, 4.37 +-10.55, -10.00, 52.19, 47.81, 4.38 +-10.68, -10.00, 57.23, 42.77, 14.47 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.60 +-10.68, -10.00, 52.30, 47.70, 4.60 +-10.68, -10.00, 52.30, 47.70, 4.61 +-10.68, -10.00, 52.31, 47.69, 4.61 +-10.68, -10.00, 52.31, 47.69, 4.62 +-10.68, -10.00, 52.31, 47.69, 4.62 +-10.68, -10.00, 52.31, 47.69, 4.63 +-10.68, -10.00, 52.32, 47.68, 4.63 +-10.68, -10.00, 52.32, 47.68, 4.64 +-10.68, -10.00, 52.32, 47.68, 4.64 +-10.68, -10.00, 52.32, 47.68, 4.65 +-10.68, -10.00, 52.33, 47.67, 4.65 +-10.68, -10.00, 52.33, 47.67, 4.66 +-10.68, -10.00, 52.33, 47.67, 4.66 +-10.68, -10.00, 52.34, 47.66, 4.67 +-10.74, -10.00, 54.86, 45.14, 9.72 +-10.74, -10.00, 52.39, 47.61, 4.78 +-10.74, -10.00, 52.39, 47.61, 4.79 +-10.74, -10.00, 52.40, 47.60, 4.79 +-10.74, -10.00, 52.40, 47.60, 4.80 +-10.74, -10.00, 52.40, 47.60, 4.80 +-10.74, -10.00, 52.40, 47.60, 4.81 +-10.81, -10.00, 54.93, 45.07, 9.86 +-10.81, -10.00, 52.46, 47.54, 4.92 +-10.81, -10.00, 52.46, 47.54, 4.93 +-10.81, -10.00, 52.47, 47.53, 4.93 +-10.81, -10.00, 52.47, 47.53, 4.94 +-10.81, -10.00, 52.47, 47.53, 4.94 +-10.94, -10.00, 57.52, 42.48, 15.04 +-10.94, -10.00, 52.58, 47.42, 5.16 +-10.94, -10.00, 52.58, 47.42, 5.16 +-10.94, -10.00, 52.58, 47.42, 5.17 +-10.94, -10.00, 52.59, 47.41, 5.18 +-10.94, -10.00, 52.59, 47.41, 5.18 +-10.94, -10.00, 52.60, 47.40, 5.19 +-11.01, -10.00, 55.12, 44.88, 10.24 +-11.01, -10.00, 52.65, 47.35, 5.30 +-11.01, -10.00, 52.66, 47.34, 5.31 +-11.01, -10.00, 52.66, 47.34, 5.32 +-11.01, -10.00, 52.66, 47.34, 5.33 +-11.01, -10.00, 52.67, 47.33, 5.33 +-11.01, -10.00, 52.67, 47.33, 5.34 +-11.07, -10.00, 55.20, 44.80, 10.39 +-11.07, -10.00, 52.73, 47.27, 5.46 +-11.07, -10.00, 52.73, 47.27, 5.47 +-11.07, -10.00, 52.74, 47.26, 5.47 +-11.07, -10.00, 52.74, 47.26, 5.48 +-11.07, -10.00, 52.74, 47.26, 5.49 +-11.21, -10.00, 57.79, 42.21, 15.58 +-11.21, -10.00, 52.85, 47.15, 5.71 +-11.21, -10.00, 52.86, 47.14, 5.71 +-11.21, -10.00, 52.86, 47.14, 5.72 +-11.21, -10.00, 52.87, 47.13, 5.73 +-11.21, -10.00, 52.87, 47.13, 5.74 +-11.21, -10.00, 52.88, 47.12, 5.75 +-11.21, -10.00, 52.88, 47.12, 5.76 +-11.21, -10.00, 52.88, 47.12, 5.77 +-11.21, -10.00, 52.89, 47.11, 5.78 +-11.21, -10.00, 52.89, 47.11, 5.79 +-11.21, -10.00, 52.90, 47.10, 5.80 +-11.21, -10.00, 52.90, 47.10, 5.80 +-11.21, -10.00, 52.91, 47.09, 5.81 +-11.21, -10.00, 52.91, 47.09, 5.82 +-11.21, -10.00, 52.92, 47.08, 5.83 +-11.21, -10.00, 52.92, 47.08, 5.84 +-11.21, -10.00, 52.93, 47.07, 5.85 +-11.21, -10.00, 52.93, 47.07, 5.86 +-11.21, -10.00, 52.93, 47.07, 5.87 +-11.21, -10.00, 52.94, 47.06, 5.88 +-11.21, -10.00, 52.94, 47.06, 5.89 +-11.21, -10.00, 52.95, 47.05, 5.90 +-11.21, -10.00, 52.95, 47.05, 5.90 +-11.21, -10.00, 52.96, 47.04, 5.91 +-11.21, -10.00, 52.96, 47.04, 5.92 +-11.07, -10.00, 47.92, 52.08, -4.15 +-11.07, -10.00, 52.87, 47.13, 5.74 +-11.07, -10.00, 52.87, 47.13, 5.75 +-11.07, -10.00, 52.88, 47.12, 5.76 +-11.07, -10.00, 52.88, 47.12, 5.77 +-11.01, -10.00, 50.36, 49.64, 0.73 +-11.01, -10.00, 52.84, 47.16, 5.68 +-11.01, -10.00, 52.84, 47.16, 5.69 +-11.01, -10.00, 52.85, 47.15, 5.70 +-11.01, -10.00, 52.85, 47.15, 5.70 +-11.01, -10.00, 52.86, 47.14, 5.71 +-10.94, -10.00, 50.34, 49.66, 0.68 +-10.94, -10.00, 52.81, 47.19, 5.63 +-10.94, -10.00, 52.82, 47.18, 5.63 +-10.94, -10.00, 52.82, 47.18, 5.64 +-10.81, -10.00, 47.78, 52.22, -4.44 +-10.81, -10.00, 52.73, 47.27, 5.46 +-10.81, -10.00, 52.73, 47.27, 5.46 +-10.81, -10.00, 52.73, 47.27, 5.47 +-10.74, -10.00, 50.22, 49.78, 0.43 +-10.74, -10.00, 52.69, 47.31, 5.38 +-10.74, -10.00, 52.69, 47.31, 5.39 +-10.74, -10.00, 52.70, 47.30, 5.39 +-10.74, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 52.70, 47.30, 5.41 +-10.68, -10.00, 50.19, 49.81, 0.37 +-10.68, -10.00, 52.66, 47.34, 5.32 +-10.68, -10.00, 52.66, 47.34, 5.32 +-10.68, 20.00, 75.00, 25.00, 50.00 +-10.68, 20.00, 75.00, 25.00, 50.00 +-10.68, 20.00, 75.00, 25.00, 50.00 +-10.68, 20.00, 75.00, 25.00, 50.00 +-10.55, 20.00, 70.69, 29.31, 41.39 +-10.55, 20.00, 75.00, 25.00, 50.00 +-10.55, 20.00, 75.00, 25.00, 50.00 +-10.55, 20.00, 75.00, 25.00, 50.00 +-10.48, 20.00, 73.57, 26.43, 47.15 +-10.42, 20.00, 73.64, 26.36, 47.28 +-10.42, 20.00, 75.00, 25.00, 50.00 +-10.28, 20.00, 71.30, 28.70, 42.59 +-10.22, 20.00, 73.83, 26.17, 47.66 +-10.15, 20.00, 73.90, 26.10, 47.79 +-10.02, 20.00, 71.44, 28.56, 42.87 +-9.95, 20.00, 73.97, 26.03, 47.94 +-9.89, 20.00, 74.03, 25.97, 48.07 +-9.69, 20.00, 69.05, 30.95, 38.11 +-9.62, 20.00, 74.06, 25.94, 48.12 +-9.43, 20.00, 69.08, 30.92, 38.15 +-9.23, 20.00, 69.04, 30.96, 38.08 +-9.10, 20.00, 71.52, 28.48, 43.04 +-8.90, 20.00, 69.01, 30.99, 38.02 +-8.70, 20.00, 68.97, 31.03, 37.94 +-8.44, 20.00, 66.41, 33.59, 32.81 +-8.31, 20.00, 71.36, 28.64, 42.71 +-8.04, 20.00, 66.32, 33.68, 32.64 +-7.78, 20.00, 66.23, 33.77, 32.45 +-7.51, 20.00, 66.13, 33.87, 32.26 +-7.25, 20.00, 66.04, 33.96, 32.07 +-6.99, 20.00, 65.94, 34.06, 31.88 +-6.72, 20.00, 65.84, 34.16, 31.68 +-6.33, 20.00, 60.70, 39.30, 21.40 +-6.06, 20.00, 65.54, 34.46, 31.09 +-5.73, 20.00, 62.92, 37.08, 25.84 +-5.41, 20.00, 62.77, 37.23, 25.54 +-5.01, 20.00, 60.09, 39.91, 20.19 +-4.68, 20.00, 62.41, 37.59, 24.82 +-4.35, 20.00, 62.26, 37.74, 24.51 +-3.96, 20.00, 59.58, 40.42, 19.16 +-3.56, 20.00, 59.37, 40.63, 18.74 +-3.16, 20.00, 59.16, 40.84, 18.32 +-2.77, 20.00, 58.95, 41.05, 17.90 +-2.31, 20.00, 56.21, 43.79, 12.43 +-1.85, 20.00, 55.95, 44.05, 11.90 +-1.45, 20.00, 58.21, 41.79, 16.41 +-1.05, 20.00, 57.99, 42.01, 15.98 +-0.53, 20.00, 52.73, 47.27, 5.45 +-0.13, 20.00, 57.45, 42.55, 14.90 +0.33, 20.00, 54.70, 45.30, 9.41 +0.86, 20.00, 51.91, 48.09, 3.82 +1.32, 20.00, 54.10, 45.90, 8.21 +1.85, 20.00, 51.30, 48.70, 2.61 +2.24, 20.00, 56.02, 43.98, 12.04 +2.70, 20.00, 53.27, 46.73, 6.53 +3.23, 20.00, 50.46, 49.54, 0.92 +3.69, 20.00, 52.65, 47.35, 5.30 +4.22, 20.00, 49.84, 50.16, -0.32 +4.61, 20.00, 54.54, 45.46, 9.09 +5.08, 20.00, 51.78, 48.22, 3.57 +5.54, 20.00, 51.49, 48.51, 2.98 +6.06, 20.00, 48.68, 51.32, -2.65 +6.46, 20.00, 53.37, 46.63, 6.75 +6.99, 20.00, 48.08, 51.92, -3.83 +7.45, 20.00, 50.26, 49.74, 0.51 +7.98, 20.00, 47.43, 52.57, -5.13 +8.50, 20.00, 47.08, 52.92, -5.84 +8.96, 20.00, 49.25, 50.75, -1.50 +9.49, 20.00, 46.42, 53.58, -7.16 +9.89, 20.00, 51.11, 48.89, 2.21 +10.42, 20.00, 45.80, 54.20, -8.40 +10.94, 20.00, 45.44, 54.56, -9.12 +11.40, 20.00, 47.60, 52.40, -4.80 +11.87, 20.00, 47.28, 52.72, -5.43 +12.26, 20.00, 49.49, 50.51, -1.02 +12.72, 20.00, 46.70, 53.30, -6.61 +13.18, 20.00, 46.38, 53.62, -7.25 +13.58, 20.00, 48.58, 51.42, -2.85 +14.04, 20.00, 45.78, 54.22, -8.44 +14.50, 20.00, 45.45, 54.55, -9.09 +14.90, 20.00, 47.65, 52.35, -4.70 +15.36, 20.00, 44.85, 55.15, -10.30 +15.82, 20.00, 44.52, 55.48, -10.96 +16.22, 20.00, 46.71, 53.29, -6.58 +16.68, 20.00, 43.90, 56.10, -12.20 +17.14, 20.00, 43.57, 56.43, -12.87 +17.47, 20.00, 48.27, 51.73, -3.45 +17.93, 20.00, 42.99, 57.01, -14.02 +18.33, 20.00, 45.17, 54.83, -9.66 +18.72, 20.00, 44.88, 55.12, -10.24 +19.12, 20.00, 44.59, 55.41, -10.83 +19.51, 20.00, 44.29, 55.71, -11.42 +19.84, 20.00, 46.52, 53.48, -6.96 +20.17, 20.00, 46.27, 53.73, -7.46 +20.57, 20.00, 43.50, 56.50, -13.00 +20.90, 20.00, 45.72, 54.28, -8.56 +21.16, 20.00, 47.99, 52.01, -4.02 +21.49, 20.00, 45.27, 54.73, -9.47 +21.75, 20.00, 47.53, 52.47, -4.93 +22.15, 20.00, 42.28, 57.72, -15.43 +22.48, 20.00, 44.50, 55.50, -11.00 +22.74, 20.00, 46.76, 53.24, -6.47 +23.07, 20.00, 44.03, 55.97, -11.93 +23.33, 20.00, 46.30, 53.70, -7.41 +23.53, 20.00, 48.61, 51.39, -2.79 +23.80, 20.00, 45.92, 54.08, -8.16 +23.99, 20.00, 48.23, 51.77, -3.54 +24.26, 20.00, 45.54, 54.46, -8.91 +24.39, 20.00, 50.37, 49.63, 0.75 +24.65, 20.00, 45.21, 54.79, -9.57 +24.79, 20.00, 50.04, 49.96, 0.08 +25.05, 20.00, 44.88, 55.12, -10.24 +25.18, 20.00, 49.71, 50.29, -0.59 +25.38, 20.00, 47.07, 52.93, -5.87 +25.58, 20.00, 46.90, 53.10, -6.21 +25.71, 20.00, 49.25, 50.75, -1.50 +25.91, 20.00, 46.61, 53.39, -6.79 +26.17, 20.00, 43.91, 56.09, -12.17 +26.24, 20.00, 51.26, 48.74, 2.51 +26.43, 20.00, 46.14, 53.86, -7.72 +26.63, 20.00, 45.97, 54.03, -8.07 +26.70, 20.00, 50.84, 49.16, 1.67 +26.76, 20.00, 50.76, 49.24, 1.52 +26.89, 20.00, 48.16, 51.84, -3.67 +26.96, 20.00, 50.56, 49.44, 1.12 +27.03, 20.00, 50.48, 49.52, 0.97 +27.03, 20.00, 52.93, 47.07, 5.86 +27.16, 20.00, 47.86, 52.14, -4.28 +27.16, 20.00, 52.78, 47.22, 5.56 +27.22, 20.00, 50.23, 49.77, 0.46 +27.22, 20.00, 52.67, 47.33, 5.35 +27.29, 20.00, 50.13, 49.87, 0.25 +27.29, 20.00, 52.57, 47.43, 5.14 +27.29, 20.00, 52.54, 47.46, 5.09 +27.29, 20.00, 52.52, 47.48, 5.03 +27.42, 20.00, 47.44, 52.56, -5.11 +27.42, 20.00, 52.36, 47.64, 4.72 +27.42, 20.00, 52.33, 47.67, 4.67 +27.42, 20.00, 52.31, 47.69, 4.61 +27.42, 20.00, 52.28, 47.72, 4.55 +27.42, 20.00, 52.25, 47.75, 4.50 +27.42, 20.00, 52.22, 47.78, 4.44 +27.42, 20.00, 52.19, 47.81, 4.39 +27.42, 20.00, 52.17, 47.83, 4.33 +27.29, 20.00, 57.18, 42.82, 14.36 +27.29, 20.00, 52.21, 47.79, 4.42 +27.22, 20.00, 54.70, 45.30, 9.41 +27.16, 20.00, 54.73, 45.27, 9.45 +27.16, 20.00, 52.23, 47.77, 4.46 +27.03, 20.00, 57.24, 42.76, 14.49 +26.96, 20.00, 54.80, 45.20, 9.59 +26.89, 20.00, 54.82, 45.18, 9.64 +26.89, 20.00, 52.32, 47.68, 4.64 +26.76, 20.00, 57.34, 42.66, 14.68 +26.76, 20.00, 52.37, 47.63, 4.74 +26.70, 20.00, 54.87, 45.13, 9.73 +26.63, 20.00, 54.89, 45.11, 9.78 +26.63, 20.00, 52.39, 47.61, 4.79 +26.50, 20.00, 57.41, 42.59, 14.82 +26.43, 20.00, 54.97, 45.03, 9.93 +26.37, 20.00, 54.99, 45.01, 9.98 +26.24, 20.00, 57.54, 42.46, 15.08 +26.17, 20.00, 55.09, 44.91, 10.19 +26.17, 20.00, 52.60, 47.40, 5.20 +26.10, 20.00, 55.10, 44.90, 10.19 +25.91, 20.00, 60.17, 39.83, 20.33 +25.84, 20.00, 55.25, 44.75, 10.50 +25.71, 20.00, 57.80, 42.20, 15.60 +25.64, 20.00, 55.36, 44.64, 10.71 +25.58, 20.00, 55.38, 44.62, 10.77 +25.44, 20.00, 57.93, 42.07, 15.87 +25.38, 20.00, 55.49, 44.51, 10.98 +25.38, 20.00, 53.00, 47.00, 6.00 +25.18, 20.00, 60.54, 39.46, 21.09 +25.18, 20.00, 53.11, 46.89, 6.22 +25.11, 20.00, 55.61, 44.39, 11.22 +25.05, 20.00, 55.64, 44.36, 11.28 +24.92, 20.00, 58.19, 41.81, 16.39 +24.92, 20.00, 53.23, 46.77, 6.46 +24.85, 20.00, 55.74, 44.26, 11.47 +24.79, 20.00, 55.77, 44.23, 11.53 +24.65, 20.00, 58.32, 41.68, 16.64 +24.65, 20.00, 53.36, 46.64, 6.72 +24.59, 20.00, 55.86, 44.14, 11.73 +24.52, 20.00, 55.90, 44.10, 11.79 +24.39, 20.00, 58.45, 41.55, 16.90 +24.39, 20.00, 53.49, 46.51, 6.98 +24.32, 20.00, 55.99, 44.01, 11.99 +24.26, 20.00, 56.03, 43.97, 12.06 +24.26, 20.00, 53.54, 46.46, 7.08 +24.26, 20.00, 53.52, 46.48, 7.05 +24.13, 20.00, 58.55, 41.45, 17.10 +24.13, 20.00, 53.59, 46.41, 7.18 +24.13, 20.00, 53.58, 46.42, 7.15 +24.06, 20.00, 56.08, 43.92, 12.17 +24.06, 20.00, 53.60, 46.40, 7.19 +24.06, 20.00, 53.58, 46.42, 7.16 +23.99, 20.00, 56.09, 43.91, 12.17 +23.99, 20.00, 53.60, 46.40, 7.20 +23.99, 20.00, 53.59, 46.41, 7.17 +23.86, 20.00, 58.61, 41.39, 17.23 +23.86, 20.00, 53.66, 46.34, 7.31 +23.86, 20.00, 53.64, 46.36, 7.28 +23.80, 20.00, 56.15, 43.85, 12.30 +23.80, 20.00, 53.66, 46.34, 7.32 +23.73, 20.00, 56.17, 43.83, 12.34 +23.73, 20.00, 53.68, 46.32, 7.37 +23.73, 20.00, 53.67, 46.33, 7.34 +23.73, 20.00, 53.66, 46.34, 7.31 +23.73, 20.00, 53.64, 46.36, 7.28 +23.73, 20.00, 53.63, 46.37, 7.25 +23.73, 20.00, 53.61, 46.39, 7.23 +23.73, 20.00, 53.60, 46.40, 7.20 +23.73, 20.00, 53.59, 46.41, 7.17 +23.73, 20.00, 53.57, 46.43, 7.14 +23.73, 20.00, 53.56, 46.44, 7.11 +23.73, 20.00, 53.54, 46.46, 7.09 +23.73, 20.00, 53.53, 46.47, 7.06 +23.73, 20.00, 53.52, 46.48, 7.03 +23.73, 20.00, 53.50, 46.50, 7.00 +23.73, 20.00, 53.49, 46.51, 6.97 +23.73, 20.00, 53.47, 46.53, 6.95 +23.73, 20.00, 53.46, 46.54, 6.92 +23.73, 20.00, 53.45, 46.55, 6.89 +23.73, 20.00, 53.43, 46.57, 6.86 +23.73, 20.00, 53.42, 46.58, 6.83 +23.80, 20.00, 50.88, 49.12, 1.76 +23.80, 20.00, 53.34, 46.66, 6.68 +23.80, 20.00, 53.33, 46.67, 6.65 +23.80, 20.00, 53.31, 46.69, 6.62 +23.86, 20.00, 50.78, 49.22, 1.55 +23.86, 20.00, 53.23, 46.77, 6.47 +23.99, 20.00, 48.17, 51.83, -3.65 +23.99, 20.00, 53.10, 46.90, 6.21 +23.99, 20.00, 53.09, 46.91, 6.18 +24.06, 20.00, 50.55, 49.45, 1.10 +24.06, 20.00, 53.01, 46.99, 6.02 +24.13, 20.00, 50.47, 49.53, 0.94 +24.13, 20.00, 52.93, 47.07, 5.86 +24.13, 20.00, 52.91, 47.09, 5.83 +24.26, 20.00, 47.85, 52.15, -4.29 +24.26, 20.00, 52.78, 47.22, 5.56 +24.26, 20.00, 52.77, 47.23, 5.53 +24.26, 20.00, 52.75, 47.25, 5.50 +24.32, 20.00, 50.21, 49.79, 0.43 +24.39, 20.00, 50.15, 49.85, 0.29 +24.39, 20.00, 52.60, 47.40, 5.20 +24.52, 20.00, 47.54, 52.46, -4.91 +24.59, 20.00, 49.95, 50.05, -0.10 +24.59, 20.00, 52.40, 47.60, 4.81 +24.65, 20.00, 49.86, 50.14, -0.27 +24.79, 20.00, 47.27, 52.73, -5.45 +24.79, 20.00, 52.20, 47.80, 4.40 +24.85, 20.00, 49.66, 50.34, -0.68 +24.85, 20.00, 52.12, 47.88, 4.23 +24.85, 20.00, 52.10, 47.90, 4.19 +24.92, 20.00, 49.56, 50.44, -0.89 +24.92, 20.00, 52.01, 47.99, 4.02 +24.92, 20.00, 51.99, 48.01, 3.98 +25.05, 20.00, 46.93, 53.07, -6.14 +25.05, 20.00, 51.86, 48.14, 3.71 +25.05, 20.00, 51.84, 48.16, 3.67 +25.11, 20.00, 49.30, 50.70, -1.41 +25.11, 20.00, 51.75, 48.25, 3.50 +25.18, 20.00, 49.21, 50.79, -1.58 +25.18, 20.00, 51.66, 48.34, 3.32 +25.31, 20.00, 46.60, 53.40, -6.80 +25.31, 20.00, 51.52, 48.48, 3.04 +25.38, 20.00, 48.98, 51.02, -2.04 +25.38, 20.00, 51.43, 48.57, 2.86 +25.38, 20.00, 51.41, 48.59, 2.82 +25.44, 20.00, 48.87, 51.13, -2.26 +25.44, 20.00, 51.32, 48.68, 2.64 +25.44, 20.00, 51.30, 48.70, 2.60 +25.44, 20.00, 51.28, 48.72, 2.56 +25.58, 20.00, 46.22, 53.78, -7.57 +25.58, 20.00, 51.14, 48.86, 2.28 +25.58, 20.00, 51.12, 48.88, 2.24 +25.58, 20.00, 51.10, 48.90, 2.20 +25.58, 20.00, 51.08, 48.92, 2.15 +25.58, 20.00, 51.06, 48.94, 2.11 +25.58, 20.00, 51.04, 48.96, 2.07 +25.58, 20.00, 51.01, 48.99, 2.03 +25.58, 20.00, 50.99, 49.01, 1.99 +25.58, 20.00, 50.97, 49.03, 1.95 +25.58, 20.00, 50.95, 49.05, 1.90 +25.58, 20.00, 50.93, 49.07, 1.86 +25.58, 20.00, 50.91, 49.09, 1.82 +25.58, 20.00, 50.89, 49.11, 1.78 +25.58, 20.00, 50.87, 49.13, 1.74 +25.58, 20.00, 50.85, 49.15, 1.69 +25.58, 20.00, 50.83, 49.17, 1.65 +25.44, 20.00, 55.85, 44.15, 11.70 +25.44, 20.00, 50.88, 49.12, 1.77 +25.44, 20.00, 50.86, 49.14, 1.73 +25.38, 20.00, 53.37, 46.63, 6.73 +25.38, 20.00, 50.87, 49.13, 1.75 +25.38, 20.00, 50.85, 49.15, 1.71 +25.31, 20.00, 53.35, 46.65, 6.71 +25.31, 20.00, 50.86, 49.14, 1.72 +25.18, 20.00, 55.89, 44.11, 11.77 +25.18, 20.00, 50.92, 49.08, 1.84 +25.11, 20.00, 53.42, 46.58, 6.85 +25.11, 20.00, 50.93, 49.07, 1.87 +25.05, 20.00, 53.44, 46.56, 6.87 +25.05, 20.00, 50.95, 49.05, 1.89 +24.92, 20.00, 55.97, 44.03, 11.94 +24.92, 20.00, 51.01, 48.99, 2.01 +24.92, 20.00, 50.99, 49.01, 1.98 +24.85, 20.00, 53.49, 46.51, 6.98 +24.85, 20.00, 51.00, 49.00, 2.00 +24.85, 20.00, 50.98, 49.02, 1.97 +24.79, 20.00, 53.49, 46.51, 6.97 +24.79, 20.00, 51.00, 49.00, 1.99 +24.79, 20.00, 50.98, 49.02, 1.96 +24.65, 20.00, 56.00, 44.00, 12.01 +24.65, 20.00, 51.04, 48.96, 2.09 +24.59, 20.00, 53.55, 46.45, 7.09 +24.59, 20.00, 51.06, 48.94, 2.12 +24.59, 20.00, 51.04, 48.96, 2.08 +24.52, 20.00, 53.55, 46.45, 7.09 +24.52, 20.00, 51.06, 48.94, 2.11 +24.39, 20.00, 56.08, 43.92, 12.17 +24.39, 20.00, 51.12, 48.88, 2.24 +24.32, 20.00, 53.63, 46.37, 7.26 +24.32, 20.00, 51.14, 48.86, 2.28 +24.26, 20.00, 53.64, 46.36, 7.29 +24.26, 20.00, 51.16, 48.84, 2.31 +24.26, 20.00, 51.14, 48.86, 2.28 +24.13, 20.00, 56.17, 43.83, 12.34 +24.13, 20.00, 51.21, 48.79, 2.42 +24.13, 20.00, 51.19, 48.81, 2.39 +24.13, 20.00, 51.18, 48.82, 2.36 +24.13, 20.00, 51.16, 48.84, 2.32 +24.06, 20.00, 53.67, 46.33, 7.34 +24.06, 20.00, 51.18, 48.82, 2.36 +24.06, 20.00, 51.17, 48.83, 2.33 +24.06, 20.00, 51.15, 48.85, 2.30 +24.06, 20.00, 51.14, 48.86, 2.27 +24.06, 20.00, 51.12, 48.88, 2.24 +23.99, 20.00, 53.63, 46.37, 7.25 +23.99, 20.00, 51.14, 48.86, 2.28 +23.99, 20.00, 51.13, 48.87, 2.25 +23.99, 20.00, 51.11, 48.89, 2.22 +23.99, 20.00, 51.10, 48.90, 2.19 +23.86, 20.00, 56.12, 43.88, 12.25 +23.86, 20.00, 51.16, 48.84, 2.33 +23.86, 20.00, 51.15, 48.85, 2.30 +23.80, 20.00, 53.66, 46.34, 7.32 +23.80, 20.00, 51.17, 48.83, 2.34 +23.80, 20.00, 51.16, 48.84, 2.31 +23.80, 20.00, 51.14, 48.86, 2.29 +23.80, 20.00, 51.13, 48.87, 2.26 +23.80, 20.00, 51.11, 48.89, 2.23 +23.80, 20.00, 51.10, 48.90, 2.20 +23.80, 20.00, 51.09, 48.91, 2.17 +23.80, 20.00, 51.07, 48.93, 2.14 +23.80, 20.00, 51.06, 48.94, 2.12 +23.80, 20.00, 51.04, 48.96, 2.09 +23.80, 20.00, 51.03, 48.97, 2.06 +23.80, 20.00, 51.01, 48.99, 2.03 +23.80, 20.00, 51.00, 49.00, 2.00 +23.80, 20.00, 50.99, 49.01, 1.97 +23.80, 20.00, 50.97, 49.03, 1.94 +23.80, 20.00, 50.96, 49.04, 1.92 +23.80, 20.00, 50.94, 49.06, 1.89 +23.80, 20.00, 50.93, 49.07, 1.86 +23.80, 20.00, 50.92, 49.08, 1.83 +23.86, 20.00, 48.38, 51.62, -3.24 +23.80, 20.00, 53.36, 46.64, 6.72 +23.80, 20.00, 50.87, 49.13, 1.74 +23.86, 20.00, 48.34, 51.66, -3.33 +23.86, 20.00, 50.79, 49.21, 1.59 +23.86, 20.00, 50.78, 49.22, 1.56 +23.86, 20.00, 50.76, 49.24, 1.53 +23.86, 20.00, 50.75, 49.25, 1.50 +23.86, 20.00, 50.74, 49.26, 1.47 +23.86, 20.00, 50.72, 49.28, 1.44 +23.86, 20.00, 50.71, 49.29, 1.41 +23.86, 20.00, 50.69, 49.31, 1.38 +23.99, 20.00, 45.63, 54.37, -8.73 +23.99, 20.00, 50.56, 49.44, 1.13 +23.99, 20.00, 50.55, 49.45, 1.10 +23.99, 20.00, 50.53, 49.47, 1.07 +23.99, 20.00, 50.52, 49.48, 1.04 +23.99, 20.00, 50.50, 49.50, 1.01 +24.06, 20.00, 47.97, 52.03, -4.07 +24.06, 20.00, 50.42, 49.58, 0.85 +24.06, 20.00, 50.41, 49.59, 0.82 +24.06, 20.00, 50.39, 49.61, 0.79 +24.06, 20.00, 50.38, 49.62, 0.76 +24.06, 20.00, 50.36, 49.64, 0.73 +24.06, 20.00, 50.35, 49.65, 0.70 +24.06, 20.00, 50.33, 49.67, 0.66 +24.13, 20.00, 47.80, 52.20, -4.41 +24.13, 20.00, 50.25, 49.75, 0.50 +24.13, 20.00, 50.24, 49.76, 0.47 +24.13, 20.00, 50.22, 49.78, 0.44 +24.13, 20.00, 50.21, 49.79, 0.41 +24.13, 20.00, 50.19, 49.81, 0.38 +24.13, 20.00, 50.17, 49.83, 0.35 +24.13, 20.00, 50.16, 49.84, 0.32 +24.26, 20.00, 45.10, 54.90, -9.80 +24.13, 20.00, 55.07, 44.93, 10.14 +24.13, 20.00, 50.11, 49.89, 0.22 +24.13, 20.00, 50.10, 49.90, 0.19 +24.13, 20.00, 50.08, 49.92, 0.16 +24.13, 20.00, 50.07, 49.93, 0.13 +24.13, 20.00, 50.05, 49.95, 0.10 +24.13, 20.00, 50.03, 49.97, 0.07 +24.13, 20.00, 50.02, 49.98, 0.04 +24.13, 20.00, 50.00, 50.00, 0.01 +24.13, 20.00, 49.99, 50.01, -0.02 +24.13, 20.00, 49.97, 50.03, -0.05 +24.26, 20.00, 44.91, 55.09, -10.17 +24.13, 20.00, 54.89, 45.11, 9.77 +24.13, 20.00, 49.93, 50.07, -0.15 +24.13, 20.00, 49.91, 50.09, -0.18 +24.13, 20.00, 49.90, 50.10, -0.21 +24.13, 20.00, 49.88, 50.12, -0.24 +24.13, 20.00, 49.86, 50.14, -0.27 +24.06, 20.00, 52.37, 47.63, 4.74 +24.06, 20.00, 49.88, 50.12, -0.23 +24.06, 20.00, 49.87, 50.13, -0.26 +23.99, 20.00, 52.37, 47.63, 4.75 +23.99, 20.00, 49.89, 50.11, -0.22 +23.99, 20.00, 49.87, 50.13, -0.25 +23.99, 20.00, 49.86, 50.14, -0.28 +23.99, 20.00, 49.84, 50.16, -0.31 +23.99, 20.00, 49.83, 50.17, -0.34 +23.86, 20.00, 54.86, 45.14, 9.71 +23.86, 20.00, 49.90, 50.10, -0.20 +23.86, 20.00, 49.88, 50.12, -0.23 +23.86, 20.00, 49.87, 50.13, -0.26 +23.86, 20.00, 49.85, 50.15, -0.29 +23.86, 20.00, 49.84, 50.16, -0.32 +23.80, 20.00, 52.35, 47.65, 4.69 +23.80, 20.00, 49.86, 50.14, -0.28 +23.80, 20.00, 49.85, 50.15, -0.31 +23.73, 20.00, 52.35, 47.65, 4.71 +23.73, 20.00, 49.87, 50.13, -0.26 +23.73, 20.00, 49.85, 50.15, -0.29 +23.60, 20.00, 54.88, 45.12, 9.77 +23.60, 20.00, 49.93, 50.07, -0.15 +23.60, 20.00, 49.91, 50.09, -0.18 +23.60, 20.00, 49.90, 50.10, -0.20 +23.60, 20.00, 49.89, 50.11, -0.23 +23.60, 20.00, 49.87, 50.13, -0.26 +23.60, 20.00, 49.86, 50.14, -0.28 +23.53, 20.00, 52.37, 47.63, 4.73 +23.60, 20.00, 47.36, 52.64, -5.28 +23.53, 20.00, 52.34, 47.66, 4.68 +23.53, 20.00, 49.85, 50.15, -0.29 +23.53, 20.00, 49.84, 50.16, -0.32 +23.53, 20.00, 49.83, 50.17, -0.34 +23.53, 20.00, 49.81, 50.19, -0.37 +23.53, 20.00, 49.80, 50.20, -0.40 +23.47, 20.00, 52.31, 47.69, 4.62 +23.47, 20.00, 49.82, 50.18, -0.35 +23.47, 20.00, 49.81, 50.19, -0.38 +23.47, 20.00, 49.80, 50.20, -0.40 +23.47, 20.00, 49.79, 50.21, -0.43 +23.33, 20.00, 54.82, 45.18, 9.63 +23.33, 20.00, 49.86, 50.14, -0.28 +23.47, 20.00, 44.80, 55.20, -10.39 +23.33, 20.00, 54.78, 45.22, 9.56 +23.33, 20.00, 49.82, 50.18, -0.36 +23.33, 20.00, 49.81, 50.19, -0.38 +23.33, 20.00, 49.80, 50.20, -0.41 +23.33, 20.00, 49.78, 50.22, -0.43 +23.33, 20.00, 49.77, 50.23, -0.46 +23.33, 20.00, 49.76, 50.24, -0.48 +23.33, 20.00, 49.75, 50.25, -0.51 +23.27, 20.00, 52.26, 47.74, 4.51 +23.27, 20.00, 49.77, 50.23, -0.46 +23.27, 20.00, 49.76, 50.24, -0.48 +23.20, 20.00, 52.27, 47.73, 4.54 +23.20, 20.00, 49.78, 50.22, -0.43 +23.20, 20.00, 49.77, 50.23, -0.45 +23.20, 20.00, 49.76, 50.24, -0.48 +23.20, 20.00, 49.75, 50.25, -0.50 +23.20, 20.00, 49.74, 50.26, -0.53 +23.20, 20.00, 49.72, 50.28, -0.55 +23.20, 20.00, 49.71, 50.29, -0.57 +23.20, 20.00, 49.70, 50.30, -0.60 +23.20, 20.00, 49.69, 50.31, -0.62 +23.20, 20.00, 49.68, 50.32, -0.65 +23.07, 20.00, 54.71, 45.29, 9.42 +23.07, 20.00, 49.75, 50.25, -0.50 +23.07, 20.00, 49.74, 50.26, -0.52 +23.01, 20.00, 52.25, 47.75, 4.50 +23.01, 20.00, 49.77, 50.23, -0.46 +23.01, 20.00, 49.76, 50.24, -0.49 +23.01, 20.00, 49.75, 50.25, -0.51 +22.94, 20.00, 52.26, 47.74, 4.51 +22.94, 20.00, 49.77, 50.23, -0.45 +22.94, 20.00, 49.76, 50.24, -0.48 +22.94, 20.00, 49.75, 50.25, -0.50 +22.81, 20.00, 54.78, 45.22, 9.57 +22.94, 20.00, 44.79, 55.21, -10.43 +22.94, 20.00, 49.72, 50.28, -0.56 +22.81, 20.00, 54.75, 45.25, 9.50 +22.94, 20.00, 44.75, 55.25, -10.49 +22.81, 20.00, 54.73, 45.27, 9.46 +22.81, 20.00, 49.77, 50.23, -0.45 +22.81, 20.00, 49.76, 50.24, -0.47 +22.81, 20.00, 49.75, 50.25, -0.49 +22.74, 20.00, 52.26, 47.74, 4.53 +22.74, 20.00, 49.78, 50.22, -0.44 +22.74, 20.00, 49.77, 50.23, -0.46 +22.68, 20.00, 52.28, 47.72, 4.57 +22.68, 20.00, 49.80, 50.20, -0.40 +22.68, 20.00, 49.79, 50.21, -0.42 +22.54, 20.00, 54.82, 45.18, 9.65 +22.68, 20.00, 44.83, 55.17, -10.34 +22.54, 20.00, 54.80, 45.20, 9.61 +22.68, 20.00, 44.81, 55.19, -10.38 +22.68, 20.00, 49.74, 50.26, -0.52 +22.68, 20.00, 49.73, 50.27, -0.54 +22.68, 20.00, 49.72, 50.28, -0.56 +22.68, 20.00, 49.71, 50.29, -0.58 +22.68, 20.00, 49.70, 50.30, -0.60 +22.68, 20.00, 49.69, 50.31, -0.62 +22.68, 20.00, 49.68, 50.32, -0.64 +22.68, 20.00, 49.67, 50.33, -0.66 +22.68, 20.00, 49.66, 50.34, -0.68 +22.54, 20.00, 54.69, 45.31, 9.39 +22.54, 20.00, 49.74, 50.26, -0.52 +22.48, 20.00, 52.25, 47.75, 4.51 +22.48, 20.00, 49.77, 50.23, -0.46 +22.48, 20.00, 49.76, 50.24, -0.47 +22.41, 20.00, 52.28, 47.72, 4.55 +22.41, 20.00, 49.79, 50.21, -0.41 +22.41, 20.00, 49.79, 50.21, -0.43 +22.41, 20.00, 49.78, 50.22, -0.45 +22.41, 20.00, 49.77, 50.23, -0.47 +22.41, 20.00, 49.76, 50.24, -0.48 +22.41, 20.00, 49.75, 50.25, -0.50 +22.41, 20.00, 49.74, 50.26, -0.52 +22.41, 20.00, 49.73, 50.27, -0.54 +22.28, 20.00, 54.77, 45.23, 9.53 +22.28, 20.00, 49.81, 50.19, -0.37 +22.28, 20.00, 49.80, 50.20, -0.39 +22.28, 20.00, 49.80, 50.20, -0.41 +22.21, 20.00, 52.31, 47.69, 4.62 +22.21, 20.00, 49.83, 50.17, -0.34 +22.21, 20.00, 49.82, 50.18, -0.36 +22.21, 20.00, 49.81, 50.19, -0.38 +22.15, 20.00, 52.33, 47.67, 4.65 +22.15, 20.00, 49.85, 50.15, -0.31 +22.15, 20.00, 49.84, 50.16, -0.33 +22.15, 20.00, 49.83, 50.17, -0.34 +22.15, 20.00, 49.82, 50.18, -0.36 +22.15, 20.00, 49.81, 50.19, -0.37 +22.15, 20.00, 49.81, 50.19, -0.39 +22.15, 20.00, 49.80, 50.20, -0.41 +22.15, 20.00, 49.79, 50.21, -0.42 +22.02, 20.00, 54.82, 45.18, 9.65 +22.02, 20.00, 49.87, 50.13, -0.25 +22.02, 20.00, 49.87, 50.13, -0.27 +22.02, 20.00, 49.86, 50.14, -0.28 +21.95, 20.00, 52.37, 47.63, 4.74 +21.95, 20.00, 49.89, 50.11, -0.22 +21.95, 20.00, 49.89, 50.11, -0.23 +21.95, 20.00, 49.88, 50.12, -0.24 +21.95, 20.00, 49.87, 50.13, -0.26 +21.95, 20.00, 49.86, 50.14, -0.27 +21.95, 20.00, 49.86, 50.14, -0.29 +21.95, 20.00, 49.85, 50.15, -0.30 +21.95, 20.00, 49.84, 50.16, -0.32 +21.95, 20.00, 49.83, 50.17, -0.33 +21.95, 20.00, 49.83, 50.17, -0.35 +21.95, 20.00, 49.82, 50.18, -0.36 +21.95, 20.00, 49.81, 50.19, -0.38 +21.95, 20.00, 49.80, 50.20, -0.39 +21.95, 20.00, 49.80, 50.20, -0.41 +21.95, 20.00, 49.79, 50.21, -0.42 +21.88, 20.00, 52.30, 47.70, 4.61 +21.95, 20.00, 47.30, 52.70, -5.39 +21.88, 20.00, 52.29, 47.71, 4.58 +21.88, 20.00, 49.81, 50.19, -0.38 +21.88, 20.00, 49.80, 50.20, -0.39 +21.88, 20.00, 49.80, 50.20, -0.41 +21.88, 20.00, 49.79, 50.21, -0.42 +21.88, 20.00, 49.78, 50.22, -0.43 +21.88, 20.00, 49.78, 50.22, -0.45 +21.88, 20.00, 49.77, 50.23, -0.46 +21.88, 20.00, 49.76, 50.24, -0.48 +21.88, 20.00, 49.75, 50.25, -0.49 +21.88, 20.00, 49.75, 50.25, -0.51 +21.88, 20.00, 49.74, 50.26, -0.52 +21.88, 20.00, 49.73, 50.27, -0.53 +21.88, 20.00, 49.73, 50.27, -0.55 +21.88, 20.00, 49.72, 50.28, -0.56 +21.88, 20.00, 49.71, 50.29, -0.58 +21.88, 20.00, 49.70, 50.30, -0.59 +21.88, 20.00, 49.70, 50.30, -0.60 +21.88, 20.00, 49.69, 50.31, -0.62 +21.88, 20.00, 49.68, 50.32, -0.63 +21.88, 20.00, 49.68, 50.32, -0.65 +21.88, 20.00, 49.67, 50.33, -0.66 +21.75, 20.00, 54.71, 45.29, 9.41 +21.75, 20.00, 49.76, 50.24, -0.49 +21.75, 20.00, 49.75, 50.25, -0.50 +21.75, 20.00, 49.74, 50.26, -0.52 +21.75, 20.00, 49.74, 50.26, -0.53 +21.69, 20.00, 52.25, 47.75, 4.50 +21.75, 20.00, 47.25, 52.75, -5.50 +21.75, 20.00, 49.72, 50.28, -0.57 +21.75, 20.00, 49.71, 50.29, -0.58 +21.75, 20.00, 49.70, 50.30, -0.59 +21.75, 20.00, 49.70, 50.30, -0.61 +21.75, 20.00, 49.69, 50.31, -0.62 +21.75, 20.00, 49.68, 50.32, -0.63 +21.75, 20.00, 49.68, 50.32, -0.65 +21.75, 20.00, 49.67, 50.33, -0.66 +21.75, 20.00, 49.66, 50.34, -0.67 +21.75, 20.00, 49.66, 50.34, -0.69 +21.75, 20.00, 49.65, 50.35, -0.70 +21.69, 20.00, 52.17, 47.83, 4.33 +21.69, 20.00, 49.69, 50.31, -0.63 +21.69, 20.00, 49.68, 50.32, -0.64 +21.69, 20.00, 49.67, 50.33, -0.65 +21.69, 20.00, 49.67, 50.33, -0.66 +21.69, 20.00, 49.66, 50.34, -0.68 +21.69, 20.00, 49.66, 50.34, -0.69 +21.69, 20.00, 49.65, 50.35, -0.70 +21.69, 20.00, 49.64, 50.36, -0.71 +21.69, 20.00, 49.64, 50.36, -0.73 +21.69, 20.00, 49.63, 50.37, -0.74 +21.69, 20.00, 49.62, 50.38, -0.75 +21.69, 20.00, 49.62, 50.38, -0.76 +21.69, 20.00, 49.61, 50.39, -0.78 +21.69, 20.00, 49.60, 50.40, -0.79 +21.69, 20.00, 49.60, 50.40, -0.80 +21.69, 20.00, 49.59, 50.41, -0.82 +21.69, 20.00, 49.59, 50.41, -0.83 +21.69, 20.00, 49.58, 50.42, -0.84 +21.69, 20.00, 49.57, 50.43, -0.85 +21.69, 20.00, 49.57, 50.43, -0.87 +21.69, 20.00, 49.56, 50.44, -0.88 +21.69, 20.00, 49.55, 50.45, -0.89 +21.69, 20.00, 49.55, 50.45, -0.90 +21.69, 20.00, 49.54, 50.46, -0.92 +21.69, 20.00, 49.54, 50.46, -0.93 +21.69, 20.00, 49.53, 50.47, -0.94 +21.69, 20.00, 49.52, 50.48, -0.95 +21.69, 20.00, 49.52, 50.48, -0.97 +21.69, 20.00, 49.51, 50.49, -0.98 +21.69, 20.00, 49.50, 50.50, -0.99 +21.69, 20.00, 49.50, 50.50, -1.01 +21.69, 20.00, 49.49, 50.51, -1.02 +21.69, 20.00, 49.48, 50.52, -1.03 +21.69, 20.00, 49.48, 50.52, -1.04 +21.69, 20.00, 49.47, 50.53, -1.06 +21.69, 20.00, 49.47, 50.53, -1.07 +21.69, 20.00, 49.46, 50.54, -1.08 +21.69, 20.00, 49.45, 50.55, -1.09 +21.69, 20.00, 49.45, 50.55, -1.11 +21.69, 20.00, 49.44, 50.56, -1.12 +21.69, 20.00, 49.43, 50.57, -1.13 +21.69, 20.00, 49.43, 50.57, -1.14 +21.69, 20.00, 49.42, 50.58, -1.16 +21.62, 20.00, 51.94, 48.06, 3.87 +21.62, 20.00, 49.46, 50.54, -1.08 +21.62, 20.00, 49.45, 50.55, -1.09 +21.62, 20.00, 49.45, 50.55, -1.11 +21.62, 20.00, 49.44, 50.56, -1.12 +21.49, 20.00, 54.48, 45.52, 8.96 +21.49, 20.00, 49.53, 50.47, -0.94 +21.49, 20.00, 49.52, 50.48, -0.95 +21.49, 20.00, 49.52, 50.48, -0.97 +21.49, 20.00, 49.51, 50.49, -0.98 +21.49, 20.00, 49.51, 50.49, -0.99 +21.49, 20.00, 49.50, 50.50, -1.00 +21.49, 20.00, 49.49, 50.51, -1.01 +21.42, 20.00, 52.01, 47.99, 4.02 +21.42, 20.00, 49.53, 50.47, -0.93 +21.42, 20.00, 49.53, 50.47, -0.94 +21.42, 20.00, 49.52, 50.48, -0.95 +21.42, 20.00, 49.52, 50.48, -0.97 +21.36, 20.00, 52.03, 47.97, 4.07 +21.36, 20.00, 49.56, 50.44, -0.89 +21.36, 20.00, 49.55, 50.45, -0.90 +21.36, 20.00, 49.55, 50.45, -0.91 +21.36, 20.00, 49.54, 50.46, -0.92 +21.36, 20.00, 49.54, 50.46, -0.93 +21.36, 20.00, 49.53, 50.47, -0.94 +21.36, 20.00, 49.53, 50.47, -0.95 +21.23, 20.00, 54.56, 45.44, 9.13 +21.23, 20.00, 49.62, 50.38, -0.77 +21.23, 20.00, 49.61, 50.39, -0.78 +21.23, 20.00, 49.61, 50.39, -0.79 +21.23, 20.00, 49.60, 50.40, -0.80 +21.23, 20.00, 49.60, 50.40, -0.81 +21.16, 20.00, 52.11, 47.89, 4.23 +21.16, 20.00, 49.64, 50.36, -0.72 +21.16, 20.00, 49.63, 50.37, -0.73 +21.09, 20.00, 52.15, 47.85, 4.30 +21.16, 20.00, 47.15, 52.85, -5.69 +21.09, 20.00, 52.14, 47.86, 4.29 +21.09, 20.00, 49.67, 50.33, -0.67 +21.16, 20.00, 47.14, 52.86, -5.72 +21.09, 20.00, 52.13, 47.87, 4.26 +21.09, 20.00, 49.65, 50.35, -0.69 +21.09, 20.00, 49.65, 50.35, -0.70 +21.09, 20.00, 49.65, 50.35, -0.71 +21.09, 20.00, 49.64, 50.36, -0.72 +21.09, 20.00, 49.64, 50.36, -0.72 +20.96, 20.00, 54.68, 45.32, 9.35 +21.09, 20.00, 44.69, 55.31, -10.63 +21.09, 20.00, 49.63, 50.37, -0.75 +21.09, 20.00, 49.62, 50.38, -0.76 +21.09, 20.00, 49.62, 50.38, -0.76 +21.09, 20.00, 49.61, 50.39, -0.77 +21.09, 20.00, 49.61, 50.39, -0.78 +21.09, 20.00, 49.61, 50.39, -0.79 +21.09, 20.00, 49.60, 50.40, -0.80 +21.09, 20.00, 49.60, 50.40, -0.81 +21.09, 20.00, 49.59, 50.41, -0.81 +21.09, 20.00, 49.59, 50.41, -0.82 +21.09, 20.00, 49.58, 50.42, -0.83 +21.09, 20.00, 49.58, 50.42, -0.84 +21.09, 20.00, 49.58, 50.42, -0.85 +21.09, 20.00, 49.57, 50.43, -0.85 +21.09, 20.00, 49.57, 50.43, -0.86 +21.09, 20.00, 49.56, 50.44, -0.87 +21.09, 20.00, 49.56, 50.44, -0.88 +21.09, 20.00, 49.56, 50.44, -0.89 +21.09, 20.00, 49.55, 50.45, -0.90 +21.09, 20.00, 49.55, 50.45, -0.90 +21.09, 20.00, 49.54, 50.46, -0.91 +21.09, 20.00, 49.54, 50.46, -0.92 +21.09, 20.00, 49.54, 50.46, -0.93 +21.09, 20.00, 49.53, 50.47, -0.94 +21.09, 20.00, 49.53, 50.47, -0.95 +21.09, 20.00, 49.52, 50.48, -0.95 +21.09, 20.00, 49.52, 50.48, -0.96 +21.09, 20.00, 49.52, 50.48, -0.97 +20.96, 20.00, 54.55, 45.45, 9.11 +21.09, 20.00, 44.56, 55.44, -10.87 +21.09, 20.00, 49.50, 50.50, -0.99 +21.09, 20.00, 49.50, 50.50, -1.00 +21.09, 20.00, 49.50, 50.50, -1.01 +21.09, 20.00, 49.49, 50.51, -1.02 +21.09, 20.00, 49.49, 50.51, -1.03 +21.09, 20.00, 49.48, 50.52, -1.03 +21.09, 20.00, 49.48, 50.52, -1.04 +21.09, 20.00, 49.47, 50.53, -1.05 +21.09, 20.00, 49.47, 50.53, -1.06 +21.09, 20.00, 49.47, 50.53, -1.07 +21.09, 20.00, 49.46, 50.54, -1.08 +21.09, 20.00, 49.46, 50.54, -1.08 +20.96, 20.00, 54.50, 45.50, 8.99 +20.96, 20.00, 49.55, 50.45, -0.90 +20.96, 20.00, 49.55, 50.45, -0.91 +20.96, 20.00, 49.54, 50.46, -0.91 +20.90, 20.00, 52.06, 47.94, 4.12 +20.90, 20.00, 49.59, 50.41, -0.83 +20.90, 20.00, 49.58, 50.42, -0.84 +20.90, 20.00, 49.58, 50.42, -0.84 +20.90, 20.00, 49.58, 50.42, -0.85 +20.90, 20.00, 49.57, 50.43, -0.86 +20.90, 20.00, 49.57, 50.43, -0.86 +20.90, 20.00, 49.57, 50.43, -0.87 +20.83, 20.00, 52.08, 47.92, 4.17 +20.83, 20.00, 49.61, 50.39, -0.78 +20.83, 20.00, 49.61, 50.39, -0.79 +20.83, 20.00, 49.60, 50.40, -0.80 +20.70, 20.00, 54.64, 45.36, 9.28 +20.70, 20.00, 49.70, 50.30, -0.61 +20.70, 20.00, 49.69, 50.31, -0.61 +20.70, 20.00, 49.69, 50.31, -0.62 +20.63, 20.00, 52.21, 47.79, 4.42 +20.63, 20.00, 49.74, 50.26, -0.53 +20.63, 20.00, 49.73, 50.27, -0.53 +20.57, 20.00, 52.25, 47.75, 4.50 +20.57, 20.00, 49.78, 50.22, -0.44 +20.57, 20.00, 49.78, 50.22, -0.45 +20.57, 20.00, 49.77, 50.23, -0.45 +20.43, 20.00, 54.81, 45.19, 9.63 +20.43, 20.00, 49.87, 50.13, -0.26 +20.43, 20.00, 49.87, 50.13, -0.26 +20.37, 20.00, 52.39, 47.61, 4.78 +20.37, 20.00, 49.91, 50.09, -0.17 +20.30, 20.00, 52.43, 47.57, 4.87 +20.37, 20.00, 47.44, 52.56, -5.12 +20.30, 20.00, 52.43, 47.57, 4.86 +20.30, 20.00, 49.96, 50.04, -0.08 +20.17, 20.00, 55.00, 45.00, 10.00 +20.17, 20.00, 50.06, 49.94, 0.11 +20.17, 20.00, 50.06, 49.94, 0.11 +20.17, 20.00, 50.06, 49.94, 0.11 +20.17, 20.00, 50.05, 49.95, 0.11 +20.10, 20.00, 52.58, 47.42, 5.15 +20.17, 20.00, 47.58, 52.42, -4.84 +20.17, 20.00, 50.05, 49.95, 0.11 +20.10, 20.00, 52.57, 47.43, 5.15 +20.10, 20.00, 50.10, 49.90, 0.20 +20.10, 20.00, 50.10, 49.90, 0.20 +20.10, 20.00, 50.10, 49.90, 0.20 +20.04, 20.00, 52.62, 47.38, 5.24 +20.04, 20.00, 50.15, 49.85, 0.30 +20.04, 20.00, 50.15, 49.85, 0.30 +19.91, 20.00, 55.19, 44.81, 10.39 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.91, 20.00, 50.25, 49.75, 0.50 +19.84, 20.00, 52.77, 47.23, 5.55 +19.84, 20.00, 50.30, 49.70, 0.61 +19.84, 20.00, 50.30, 49.70, 0.61 +19.84, 20.00, 50.30, 49.70, 0.61 +19.78, 20.00, 52.83, 47.17, 5.65 +19.78, 20.00, 50.36, 49.64, 0.71 +19.78, 20.00, 50.36, 49.64, 0.71 +19.64, 20.00, 55.40, 44.60, 10.80 +19.64, 20.00, 50.46, 49.54, 0.92 +19.64, 20.00, 50.46, 49.54, 0.92 +19.64, 20.00, 50.46, 49.54, 0.92 +19.64, 20.00, 50.46, 49.54, 0.92 +19.64, 20.00, 50.46, 49.54, 0.93 +19.64, 20.00, 50.46, 49.54, 0.93 +19.64, 20.00, 50.47, 49.53, 0.93 +19.64, 20.00, 50.47, 49.53, 0.93 +19.64, 20.00, 50.47, 49.53, 0.94 +19.64, 20.00, 50.47, 49.53, 0.94 +19.64, 20.00, 50.47, 49.53, 0.94 +19.64, 20.00, 50.47, 49.53, 0.94 +19.64, 20.00, 50.47, 49.53, 0.95 +19.64, 20.00, 50.48, 49.52, 0.95 +19.64, 20.00, 50.48, 49.52, 0.95 +19.58, 20.00, 53.00, 47.00, 6.00 +19.58, 20.00, 50.53, 49.47, 1.06 +19.58, 20.00, 50.53, 49.47, 1.06 +19.58, 20.00, 50.53, 49.47, 1.06 +19.58, 20.00, 50.53, 49.47, 1.07 +19.58, 20.00, 50.54, 49.46, 1.07 +19.51, 20.00, 53.06, 46.94, 6.12 +19.58, 20.00, 48.07, 51.93, -3.87 +19.58, 20.00, 50.54, 49.46, 1.08 +19.58, 20.00, 50.54, 49.46, 1.08 +19.58, 20.00, 50.54, 49.46, 1.09 +19.58, 20.00, 50.55, 49.45, 1.09 +19.58, 20.00, 50.55, 49.45, 1.09 +19.58, 20.00, 50.55, 49.45, 1.10 +19.51, 20.00, 53.07, 46.93, 6.14 +19.51, 20.00, 50.60, 49.40, 1.20 +19.51, 20.00, 50.60, 49.40, 1.21 +19.51, 20.00, 50.61, 49.39, 1.21 +19.51, 20.00, 50.61, 49.39, 1.21 +19.51, 20.00, 50.61, 49.39, 1.22 +19.51, 20.00, 50.61, 49.39, 1.22 +19.51, 20.00, 50.61, 49.39, 1.22 +19.51, 20.00, 50.61, 49.39, 1.23 +19.51, 20.00, 50.62, 49.38, 1.23 +19.51, 20.00, 50.62, 49.38, 1.24 +19.51, 20.00, 50.62, 49.38, 1.24 +19.51, 20.00, 50.62, 49.38, 1.24 +19.51, 20.00, 50.62, 49.38, 1.25 +19.51, 20.00, 50.63, 49.37, 1.25 +19.51, 20.00, 50.63, 49.37, 1.25 +19.51, 20.00, 50.63, 49.37, 1.26 +19.51, 20.00, 50.63, 49.37, 1.26 +19.51, 20.00, 50.63, 49.37, 1.27 +19.58, 20.00, 48.11, 51.89, -3.77 +19.58, 20.00, 50.59, 49.41, 1.17 +19.58, 20.00, 50.59, 49.41, 1.18 +19.51, 20.00, 53.11, 46.89, 6.22 +19.51, 20.00, 50.64, 49.36, 1.28 +19.51, 20.00, 50.64, 49.36, 1.29 +19.51, 20.00, 50.64, 49.36, 1.29 +19.58, 20.00, 48.12, 51.88, -3.75 +19.51, 20.00, 53.12, 46.88, 6.24 +19.58, 20.00, 48.13, 51.87, -3.74 +19.58, 20.00, 50.60, 49.40, 1.20 +19.58, 20.00, 50.60, 49.40, 1.21 +19.58, 20.00, 50.60, 49.40, 1.21 +19.58, 20.00, 50.61, 49.39, 1.21 +19.64, 20.00, 48.09, 51.91, -3.83 +19.64, 20.00, 50.56, 49.44, 1.12 +19.64, 20.00, 50.56, 49.44, 1.12 +19.64, 20.00, 50.56, 49.44, 1.12 +19.64, 20.00, 50.56, 49.44, 1.13 +19.64, 20.00, 50.57, 49.43, 1.13 +19.64, 20.00, 50.57, 49.43, 1.13 +19.64, 20.00, 50.57, 49.43, 1.14 +19.64, 20.00, 50.57, 49.43, 1.14 +19.64, 20.00, 50.57, 49.43, 1.14 +19.64, 20.00, 50.57, 49.43, 1.14 +19.64, 20.00, 50.57, 49.43, 1.15 +19.64, 20.00, 50.57, 49.43, 1.15 +19.64, 20.00, 50.58, 49.42, 1.15 +19.64, 20.00, 50.58, 49.42, 1.15 +19.64, 20.00, 50.58, 49.42, 1.16 +19.64, 20.00, 50.58, 49.42, 1.16 +19.64, 20.00, 50.58, 49.42, 1.16 +19.64, 20.00, 50.58, 49.42, 1.16 +19.64, 20.00, 50.58, 49.42, 1.17 +19.64, 20.00, 50.59, 49.41, 1.17 +19.64, 20.00, 50.59, 49.41, 1.17 +19.64, 20.00, 50.59, 49.41, 1.18 +19.64, 20.00, 50.59, 49.41, 1.18 +19.64, 20.00, 50.59, 49.41, 1.18 +19.58, 20.00, 53.11, 46.89, 6.23 +19.58, 20.00, 50.64, 49.36, 1.29 +19.58, 20.00, 50.64, 49.36, 1.29 +19.58, 20.00, 50.65, 49.35, 1.29 +19.58, 20.00, 50.65, 49.35, 1.30 +19.51, 20.00, 53.17, 46.83, 6.34 +19.58, 20.00, 48.18, 51.82, -3.64 +19.58, 20.00, 50.65, 49.35, 1.31 +19.58, 20.00, 50.65, 49.35, 1.31 +19.58, 20.00, 50.66, 49.34, 1.31 +19.58, 20.00, 50.66, 49.34, 1.32 +19.58, 20.00, 50.66, 49.34, 1.32 +19.58, 20.00, 50.66, 49.34, 1.32 +19.58, 20.00, 50.66, 49.34, 1.32 +19.58, 20.00, 50.66, 49.34, 1.33 +19.58, 20.00, 50.67, 49.33, 1.33 +19.51, 20.00, 53.19, 46.81, 6.38 +19.51, 20.00, 50.72, 49.28, 1.44 +19.51, 20.00, 50.72, 49.28, 1.44 +19.51, 20.00, 50.72, 49.28, 1.44 +19.51, 20.00, 50.72, 49.28, 1.45 +19.51, 20.00, 50.73, 49.27, 1.45 +19.51, 20.00, 50.73, 49.27, 1.46 +19.51, 20.00, 50.73, 49.27, 1.46 +19.51, 20.00, 50.73, 49.27, 1.46 +19.58, 20.00, 48.21, 51.79, -3.58 +19.58, 20.00, 50.69, 49.31, 1.37 +19.58, 20.00, 50.69, 49.31, 1.37 +19.58, 20.00, 50.69, 49.31, 1.38 +19.58, 20.00, 50.69, 49.31, 1.38 +19.64, 20.00, 48.17, 51.83, -3.66 +19.64, 20.00, 50.64, 49.36, 1.29 +19.64, 20.00, 50.64, 49.36, 1.29 +19.58, 20.00, 53.17, 46.83, 6.33 +19.58, 20.00, 50.70, 49.30, 1.39 +19.58, 20.00, 50.70, 49.30, 1.40 +19.58, 20.00, 50.70, 49.30, 1.40 +19.58, 20.00, 50.70, 49.30, 1.40 +19.58, 20.00, 50.70, 49.30, 1.41 +19.58, 20.00, 50.71, 49.29, 1.41 +19.58, 20.00, 50.71, 49.29, 1.41 +19.58, 20.00, 50.71, 49.29, 1.42 +19.64, 20.00, 48.19, 51.81, -3.62 +19.64, 20.00, 50.66, 49.34, 1.32 +19.64, 20.00, 50.66, 49.34, 1.33 +19.64, 20.00, 50.66, 49.34, 1.33 +19.64, 20.00, 50.67, 49.33, 1.33 +19.78, 20.00, 45.62, 54.38, -8.75 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.14 +19.78, 20.00, 50.57, 49.43, 1.15 +19.78, 20.00, 50.57, 49.43, 1.15 +19.78, 20.00, 50.57, 49.43, 1.15 +19.78, 20.00, 50.58, 49.42, 1.15 +19.78, 20.00, 50.58, 49.42, 1.15 +19.78, 20.00, 50.58, 49.42, 1.16 +19.84, 20.00, 48.06, 51.94, -3.89 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.06 +19.84, 20.00, 50.53, 49.47, 1.07 +19.84, 20.00, 50.53, 49.47, 1.07 +19.84, 20.00, 50.53, 49.47, 1.07 +19.84, 20.00, 50.53, 49.47, 1.07 +19.78, 20.00, 53.06, 46.94, 6.11 +19.78, 20.00, 50.59, 49.41, 1.17 +19.78, 20.00, 50.59, 49.41, 1.17 +19.78, 20.00, 50.59, 49.41, 1.17 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.18 +19.78, 20.00, 50.59, 49.41, 1.19 +19.78, 20.00, 50.59, 49.41, 1.19 +19.78, 20.00, 50.60, 49.40, 1.19 +19.78, 20.00, 50.60, 49.40, 1.19 +19.78, 20.00, 50.60, 49.40, 1.19 +19.64, 20.00, 55.64, 44.36, 11.28 +19.64, 20.00, 50.70, 49.30, 1.40 +19.64, 20.00, 50.70, 49.30, 1.40 +19.64, 20.00, 50.70, 49.30, 1.40 +19.64, 20.00, 50.70, 49.30, 1.40 +19.64, 20.00, 50.70, 49.30, 1.41 +19.58, 20.00, 53.23, 46.77, 6.45 +19.58, 20.00, 50.76, 49.24, 1.51 +19.58, 20.00, 50.76, 49.24, 1.52 +19.58, 20.00, 50.76, 49.24, 1.52 +19.58, 20.00, 50.76, 49.24, 1.52 +19.58, 20.00, 50.76, 49.24, 1.53 +19.58, 20.00, 50.76, 49.24, 1.53 +19.58, 20.00, 50.77, 49.23, 1.53 +19.58, 20.00, 50.77, 49.23, 1.53 +19.58, 20.00, 50.77, 49.23, 1.54 +19.51, 20.00, 53.29, 46.71, 6.58 +19.51, 20.00, 50.82, 49.18, 1.64 +19.51, 20.00, 50.82, 49.18, 1.65 +19.51, 20.00, 50.83, 49.17, 1.65 +19.51, 20.00, 50.83, 49.17, 1.65 +19.51, 20.00, 50.83, 49.17, 1.66 +19.51, 20.00, 50.83, 49.17, 1.66 +19.38, 20.00, 55.88, 44.12, 11.75 +19.38, 20.00, 50.93, 49.07, 1.87 +19.38, 20.00, 50.94, 49.06, 1.87 +19.38, 20.00, 50.94, 49.06, 1.88 +19.38, 20.00, 50.94, 49.06, 1.88 +19.38, 20.00, 50.94, 49.06, 1.89 +19.38, 20.00, 50.95, 49.05, 1.89 +19.38, 20.00, 50.95, 49.05, 1.90 +19.38, 20.00, 50.95, 49.05, 1.90 +19.38, 20.00, 50.95, 49.05, 1.91 +19.31, 20.00, 53.48, 46.52, 6.95 +19.31, 20.00, 51.01, 48.99, 2.02 +19.31, 20.00, 51.01, 48.99, 2.02 +19.31, 20.00, 51.01, 48.99, 2.03 +19.31, 20.00, 51.02, 48.98, 2.03 +19.31, 20.00, 51.02, 48.98, 2.04 +19.31, 20.00, 51.02, 48.98, 2.04 +19.31, 20.00, 51.02, 48.98, 2.05 +19.25, 20.00, 53.55, 46.45, 7.09 +19.25, 20.00, 51.08, 48.92, 2.16 +19.25, 20.00, 51.08, 48.92, 2.16 +19.25, 20.00, 51.08, 48.92, 2.17 +19.25, 20.00, 51.09, 48.91, 2.17 +19.12, 20.00, 56.13, 43.87, 12.27 +19.12, 20.00, 51.19, 48.81, 2.38 +19.12, 20.00, 51.20, 48.80, 2.39 +19.05, 20.00, 53.72, 46.28, 7.44 +19.05, 20.00, 51.25, 48.75, 2.50 +19.05, 20.00, 51.26, 48.74, 2.51 +18.98, 20.00, 53.78, 46.22, 7.56 +18.98, 20.00, 51.31, 48.69, 2.63 +18.85, 20.00, 56.36, 43.64, 12.72 +18.85, 20.00, 51.42, 48.58, 2.84 +18.85, 20.00, 51.42, 48.58, 2.85 +18.85, 20.00, 51.43, 48.57, 2.86 +18.85, 20.00, 51.43, 48.57, 2.87 +18.85, 20.00, 51.44, 48.56, 2.87 +18.85, 20.00, 51.44, 48.56, 2.88 +18.85, 20.00, 51.45, 48.55, 2.89 +18.79, 20.00, 53.97, 46.03, 7.94 +18.79, 20.00, 51.50, 48.50, 3.01 +18.79, 20.00, 51.51, 48.49, 3.02 +18.79, 20.00, 51.51, 48.49, 3.03 +18.79, 20.00, 51.52, 48.48, 3.04 +18.79, 20.00, 51.52, 48.48, 3.05 +18.72, 20.00, 54.05, 45.95, 8.10 +18.72, 20.00, 51.58, 48.42, 3.16 +18.72, 20.00, 51.59, 48.41, 3.17 +18.72, 20.00, 51.59, 48.41, 3.18 +18.59, 20.00, 56.64, 43.36, 13.28 +18.59, 20.00, 51.70, 48.30, 3.40 +18.59, 20.00, 51.71, 48.29, 3.41 +18.52, 20.00, 54.23, 45.77, 8.47 +18.59, 20.00, 49.25, 50.75, -1.51 +18.59, 20.00, 51.72, 48.28, 3.44 +18.59, 20.00, 51.73, 48.27, 3.46 +18.59, 20.00, 51.73, 48.27, 3.47 +18.59, 20.00, 51.74, 48.26, 3.48 +18.59, 20.00, 51.74, 48.26, 3.49 +18.59, 20.00, 51.75, 48.25, 3.50 +18.59, 20.00, 51.75, 48.25, 3.51 +18.59, 20.00, 51.76, 48.24, 3.52 +18.52, 20.00, 54.29, 45.71, 8.57 +18.52, 20.00, 51.82, 48.18, 3.64 +18.52, 20.00, 51.83, 48.17, 3.65 +18.52, 20.00, 51.83, 48.17, 3.66 +18.52, 20.00, 51.84, 48.16, 3.67 +18.46, 20.00, 54.36, 45.64, 8.73 +18.46, 20.00, 51.90, 48.10, 3.80 +18.46, 20.00, 51.90, 48.10, 3.81 +18.46, 20.00, 51.91, 48.09, 3.82 +18.46, 20.00, 51.91, 48.09, 3.83 +18.46, 20.00, 51.92, 48.08, 3.84 +18.52, 20.00, 49.40, 50.60, -1.19 +18.52, 20.00, 51.88, 48.12, 3.76 +18.52, 20.00, 51.89, 48.11, 3.78 +18.52, 20.00, 51.89, 48.11, 3.79 +18.52, 20.00, 51.90, 48.10, 3.80 +18.52, 20.00, 51.90, 48.10, 3.81 +18.52, 20.00, 51.91, 48.09, 3.82 +18.52, 20.00, 51.92, 48.08, 3.83 +18.52, 20.00, 51.92, 48.08, 3.84 +18.52, 20.00, 51.93, 48.07, 3.85 +18.52, 20.00, 51.93, 48.07, 3.86 +18.52, 20.00, 51.94, 48.06, 3.88 +18.46, 20.00, 54.46, 45.54, 8.93 +18.46, 20.00, 52.00, 48.00, 4.00 +18.46, 20.00, 52.00, 48.00, 4.01 +18.52, 20.00, 49.49, 50.51, -1.02 +18.52, 20.00, 51.97, 48.03, 3.93 +18.52, 20.00, 51.97, 48.03, 3.94 +18.59, 20.00, 49.46, 50.54, -1.09 +18.59, 20.00, 51.93, 48.07, 3.87 +18.72, 20.00, 46.89, 53.11, -6.21 +18.79, 20.00, 49.32, 50.68, -1.36 +18.79, 20.00, 51.80, 48.20, 3.60 +18.79, 20.00, 51.80, 48.20, 3.61 +18.79, 20.00, 51.81, 48.19, 3.62 +18.79, 20.00, 51.81, 48.19, 3.62 +18.79, 20.00, 51.82, 48.18, 3.63 +18.79, 20.00, 51.82, 48.18, 3.64 +18.72, 20.00, 54.35, 45.65, 8.69 +18.72, 20.00, 51.88, 48.12, 3.76 +18.72, 20.00, 51.88, 48.12, 3.77 +18.72, 20.00, 51.89, 48.11, 3.78 +18.72, 20.00, 51.89, 48.11, 3.79 +18.79, 20.00, 49.38, 50.62, -1.24 +18.79, 20.00, 51.85, 48.15, 3.71 +18.79, 20.00, 51.86, 48.14, 3.72 +18.85, 20.00, 49.34, 50.66, -1.32 +18.85, 20.00, 51.82, 48.18, 3.64 +18.98, 20.00, 46.78, 53.22, -6.44 +19.05, 20.00, 49.21, 50.79, -1.59 +19.05, 20.00, 51.68, 48.32, 3.36 +19.05, 20.00, 51.68, 48.32, 3.37 +19.05, 20.00, 51.69, 48.31, 3.38 +19.12, 20.00, 49.17, 50.83, -1.66 +19.12, 20.00, 51.64, 48.36, 3.29 +19.12, 20.00, 51.65, 48.35, 3.30 +19.12, 20.00, 51.65, 48.35, 3.30 +19.12, 20.00, 51.65, 48.35, 3.31 +19.12, 20.00, 51.66, 48.34, 3.32 +19.12, 20.00, 51.66, 48.34, 3.32 +19.12, 20.00, 51.66, 48.34, 3.33 +19.12, 20.00, 51.67, 48.33, 3.34 +19.25, 20.00, 46.63, 53.37, -6.74 +19.25, 20.00, 51.57, 48.43, 3.15 +19.31, 20.00, 49.06, 50.94, -1.89 +19.31, 20.00, 51.53, 48.47, 3.06 +19.31, 20.00, 51.53, 48.47, 3.07 +19.38, 20.00, 49.01, 50.99, -1.97 +19.38, 20.00, 51.49, 48.51, 2.98 +19.51, 20.00, 46.45, 53.55, -7.11 +19.38, 20.00, 56.44, 43.56, 12.87 +19.51, 20.00, 46.45, 53.55, -7.10 +19.51, 20.00, 51.40, 48.60, 2.79 +19.51, 20.00, 51.40, 48.60, 2.80 +19.51, 20.00, 51.40, 48.60, 2.80 +19.51, 20.00, 51.40, 48.60, 2.81 +19.51, 20.00, 51.40, 48.60, 2.81 +19.58, 20.00, 48.88, 51.12, -2.23 +19.58, 20.00, 51.36, 48.64, 2.72 +19.64, 20.00, 48.84, 51.16, -2.32 +19.64, 20.00, 51.31, 48.69, 2.62 +19.64, 20.00, 51.31, 48.69, 2.63 +19.78, 20.00, 46.27, 53.73, -7.46 +19.78, 20.00, 51.22, 48.78, 2.43 +19.78, 20.00, 51.22, 48.78, 2.43 +19.84, 20.00, 48.70, 51.30, -2.61 +19.84, 20.00, 51.17, 48.83, 2.34 +19.84, 20.00, 51.17, 48.83, 2.34 +19.91, 20.00, 48.65, 51.35, -2.70 +19.91, 20.00, 51.12, 48.88, 2.24 +19.91, 20.00, 51.12, 48.88, 2.24 +19.91, 20.00, 51.12, 48.88, 2.24 +19.91, 20.00, 51.12, 48.88, 2.24 +20.04, 20.00, 46.08, 53.92, -7.84 +19.91, 20.00, 56.07, 43.93, 12.13 +20.04, 20.00, 46.08, 53.92, -7.84 +20.04, 20.00, 51.02, 48.98, 2.04 +20.04, 20.00, 51.02, 48.98, 2.04 +20.10, 20.00, 48.50, 51.50, -3.00 +20.10, 20.00, 50.97, 49.03, 1.94 +20.10, 20.00, 50.97, 49.03, 1.94 +20.10, 20.00, 50.97, 49.03, 1.94 +20.17, 20.00, 48.45, 51.55, -3.10 +20.17, 20.00, 50.92, 49.08, 1.84 +20.17, 20.00, 50.92, 49.08, 1.84 +20.17, 20.00, 50.92, 49.08, 1.84 +20.30, 20.00, 45.88, 54.12, -8.25 +20.30, 20.00, 50.82, 49.18, 1.64 +20.17, 20.00, 55.86, 44.14, 11.72 +20.30, 20.00, 45.87, 54.13, -8.26 +20.30, 20.00, 50.82, 49.18, 1.63 +20.30, 20.00, 50.81, 49.19, 1.63 +20.30, 20.00, 50.81, 49.19, 1.63 +20.37, 20.00, 48.29, 51.71, -3.42 +20.37, 20.00, 50.76, 49.24, 1.52 +20.37, 20.00, 50.76, 49.24, 1.52 +20.37, 20.00, 50.76, 49.24, 1.52 +20.37, 20.00, 50.76, 49.24, 1.51 +20.43, 20.00, 48.23, 51.77, -3.53 +20.37, 20.00, 53.23, 46.77, 6.45 +20.43, 20.00, 48.23, 51.77, -3.54 +20.43, 20.00, 50.70, 49.30, 1.40 +20.37, 20.00, 53.22, 46.78, 6.44 +20.37, 20.00, 50.75, 49.25, 1.49 +20.37, 20.00, 50.75, 49.25, 1.49 +20.37, 20.00, 50.74, 49.26, 1.49 +20.37, 20.00, 50.74, 49.26, 1.49 +20.37, 20.00, 50.74, 49.26, 1.48 +20.37, 20.00, 50.74, 49.26, 1.48 +20.37, 20.00, 50.74, 49.26, 1.48 +20.37, 20.00, 50.74, 49.26, 1.48 +20.37, 20.00, 50.74, 49.26, 1.47 +20.37, 20.00, 50.73, 49.27, 1.47 +20.30, 20.00, 53.26, 46.74, 6.51 +20.37, 20.00, 48.26, 51.74, -3.48 +20.30, 20.00, 53.25, 46.75, 6.51 +20.30, 20.00, 50.78, 49.22, 1.56 +20.30, 20.00, 50.78, 49.22, 1.56 +20.30, 20.00, 50.78, 49.22, 1.55 +20.30, 20.00, 50.78, 49.22, 1.55 +20.30, 20.00, 50.78, 49.22, 1.55 +20.17, 20.00, 55.82, 44.18, 11.63 +20.17, 20.00, 50.87, 49.13, 1.75 +20.17, 20.00, 50.87, 49.13, 1.74 +20.17, 20.00, 50.87, 49.13, 1.74 +20.10, 20.00, 53.39, 46.61, 6.78 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.04, 20.00, 53.44, 46.56, 6.88 +20.04, 20.00, 50.97, 49.03, 1.94 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +19.91, 20.00, 56.01, 43.99, 12.02 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.84, 20.00, 53.59, 46.41, 7.18 +19.91, 20.00, 48.60, 51.40, -2.80 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.07, 48.93, 2.15 +19.91, 20.00, 51.08, 48.92, 2.15 +19.91, 20.00, 51.08, 48.92, 2.15 +19.91, 20.00, 51.08, 48.92, 2.15 +19.91, 20.00, 51.08, 48.92, 2.15 +20.04, 20.00, 46.03, 53.97, -7.93 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +19.91, 20.00, 56.02, 43.98, 12.04 +20.04, 20.00, 46.03, 53.97, -7.94 +19.91, 20.00, 56.02, 43.98, 12.04 +19.91, 20.00, 51.08, 48.92, 2.15 +20.04, 20.00, 46.03, 53.97, -7.93 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.10, 20.00, 48.45, 51.55, -3.09 +20.04, 20.00, 53.45, 46.55, 6.89 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.98, 49.02, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.04, 20.00, 50.97, 49.03, 1.95 +20.10, 20.00, 48.45, 51.55, -3.10 +20.04, 20.00, 53.45, 46.55, 6.89 +20.10, 20.00, 48.45, 51.55, -3.10 +20.10, 20.00, 50.92, 49.08, 1.85 +20.10, 20.00, 50.92, 49.08, 1.85 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.10, 20.00, 50.92, 49.08, 1.84 +20.04, 20.00, 53.44, 46.56, 6.88 +20.10, 20.00, 48.45, 51.55, -3.11 +20.04, 20.00, 53.44, 46.56, 6.88 +20.10, 20.00, 48.45, 51.55, -3.11 +20.04, 20.00, 53.44, 46.56, 6.88 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.97, 49.03, 1.93 +20.04, 20.00, 50.96, 49.04, 1.93 +19.91, 20.00, 56.01, 43.99, 12.02 +19.91, 20.00, 51.06, 48.94, 2.13 +19.91, 20.00, 51.06, 48.94, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.13 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.91, 20.00, 51.07, 48.93, 2.14 +19.84, 20.00, 53.59, 46.41, 7.18 +19.84, 20.00, 51.12, 48.88, 2.24 +19.84, 20.00, 51.12, 48.88, 2.24 +19.84, 20.00, 51.12, 48.88, 2.24 +19.78, 20.00, 53.64, 46.36, 7.28 +19.78, 20.00, 51.17, 48.83, 2.34 +19.78, 20.00, 51.17, 48.83, 2.34 +19.64, 20.00, 56.22, 43.78, 12.43 +19.78, 20.00, 46.23, 53.77, -7.54 +19.64, 20.00, 56.22, 43.78, 12.44 +19.64, 20.00, 51.28, 48.72, 2.55 +19.78, 20.00, 46.23, 53.77, -7.53 +19.64, 20.00, 56.22, 43.78, 12.44 +19.78, 20.00, 46.24, 53.76, -7.53 +19.78, 20.00, 51.18, 48.82, 2.36 +19.64, 20.00, 56.22, 43.78, 12.45 +19.78, 20.00, 46.24, 53.76, -7.52 +19.64, 20.00, 56.23, 43.77, 12.45 +19.64, 20.00, 51.28, 48.72, 2.57 +19.64, 20.00, 51.29, 48.71, 2.57 +19.64, 20.00, 51.29, 48.71, 2.57 +19.64, 20.00, 51.29, 48.71, 2.58 +19.64, 20.00, 51.29, 48.71, 2.58 +19.64, 20.00, 51.29, 48.71, 2.58 +19.64, 20.00, 51.29, 48.71, 2.59 +19.64, 20.00, 51.29, 48.71, 2.59 +19.64, 20.00, 51.30, 48.70, 2.59 +19.64, 20.00, 51.30, 48.70, 2.59 +19.64, 20.00, 51.30, 48.70, 2.60 +19.64, 20.00, 51.30, 48.70, 2.60 +19.64, 20.00, 51.30, 48.70, 2.60 +19.64, 20.00, 51.30, 48.70, 2.60 +19.64, 20.00, 51.30, 48.70, 2.61 +19.64, 20.00, 51.30, 48.70, 2.61 +19.58, 20.00, 53.83, 46.17, 7.66 +19.58, 20.00, 51.36, 48.64, 2.71 +19.58, 20.00, 51.36, 48.64, 2.72 +19.58, 20.00, 51.36, 48.64, 2.72 +19.51, 20.00, 53.88, 46.12, 7.77 +19.51, 20.00, 51.41, 48.59, 2.83 +19.58, 20.00, 48.89, 51.11, -2.21 +19.58, 20.00, 51.37, 48.63, 2.73 +19.51, 20.00, 53.89, 46.11, 7.78 +19.58, 20.00, 48.90, 51.10, -2.20 +19.58, 20.00, 51.37, 48.63, 2.74 +19.58, 20.00, 51.37, 48.63, 2.75 +19.58, 20.00, 51.38, 48.62, 2.75 +19.58, 20.00, 51.38, 48.62, 2.75 +19.58, 20.00, 51.38, 48.62, 2.76 +19.58, 20.00, 51.38, 48.62, 2.76 +19.58, 20.00, 51.38, 48.62, 2.76 +19.51, 20.00, 53.90, 46.10, 7.81 +19.51, 20.00, 51.43, 48.57, 2.87 +19.38, 20.00, 56.48, 43.52, 12.96 +19.38, 20.00, 51.54, 48.46, 3.08 +19.38, 20.00, 51.54, 48.46, 3.08 +19.31, 20.00, 54.06, 45.94, 8.13 +19.31, 20.00, 51.60, 48.40, 3.19 +19.31, 20.00, 51.60, 48.40, 3.20 +19.31, 20.00, 51.60, 48.40, 3.20 +19.31, 20.00, 51.60, 48.40, 3.21 +19.31, 20.00, 51.61, 48.39, 3.21 +19.31, 20.00, 51.61, 48.39, 3.22 +19.31, 20.00, 51.61, 48.39, 3.22 +19.31, 20.00, 51.61, 48.39, 3.23 +19.31, 20.00, 51.62, 48.38, 3.23 +19.31, 20.00, 51.62, 48.38, 3.24 +19.31, 20.00, 51.62, 48.38, 3.24 +19.31, 20.00, 51.62, 48.38, 3.25 +19.31, 20.00, 51.63, 48.37, 3.25 +19.25, 20.00, 54.15, 45.85, 8.30 +19.25, 20.00, 51.68, 48.32, 3.36 +19.25, 20.00, 51.68, 48.32, 3.37 +19.25, 20.00, 51.69, 48.31, 3.37 +19.25, 20.00, 51.69, 48.31, 3.38 +19.12, 20.00, 56.74, 43.26, 13.47 +19.12, 20.00, 51.80, 48.20, 3.59 +19.25, 20.00, 46.76, 53.24, -6.49 +19.25, 20.00, 51.70, 48.30, 3.40 +19.25, 20.00, 51.70, 48.30, 3.41 +19.25, 20.00, 51.71, 48.29, 3.42 +19.25, 20.00, 51.71, 48.29, 3.42 +19.25, 20.00, 51.71, 48.29, 3.43 +19.25, 20.00, 51.72, 48.28, 3.43 +19.25, 20.00, 51.72, 48.28, 3.44 +19.25, 20.00, 51.72, 48.28, 3.44 +19.25, 20.00, 51.72, 48.28, 3.45 +19.25, 20.00, 51.73, 48.27, 3.45 +19.12, 20.00, 56.77, 43.23, 13.55 +19.12, 20.00, 51.83, 48.17, 3.67 +19.12, 20.00, 51.84, 48.16, 3.67 +19.12, 20.00, 51.84, 48.16, 3.68 +19.12, 20.00, 51.84, 48.16, 3.69 +19.25, 20.00, 46.80, 53.20, -6.39 +19.25, 20.00, 51.75, 48.25, 3.50 +19.25, 20.00, 51.75, 48.25, 3.50 +19.25, 20.00, 51.76, 48.24, 3.51 +19.31, 20.00, 49.24, 50.76, -1.53 +19.31, 20.00, 51.71, 48.29, 3.42 +19.31, 20.00, 51.71, 48.29, 3.43 +19.31, 20.00, 51.72, 48.28, 3.43 +19.31, 20.00, 51.72, 48.28, 3.44 +19.31, 20.00, 51.72, 48.28, 3.44 +19.31, 20.00, 51.72, 48.28, 3.45 +19.25, 20.00, 54.25, 45.75, 8.50 +19.25, 20.00, 51.78, 48.22, 3.56 +19.25, 20.00, 51.78, 48.22, 3.56 +19.25, 20.00, 51.78, 48.22, 3.57 +19.25, 20.00, 51.79, 48.21, 3.57 +19.25, 20.00, 51.79, 48.21, 3.58 +19.31, 20.00, 49.27, 50.73, -1.46 +19.31, 20.00, 51.75, 48.25, 3.49 +19.31, 20.00, 51.75, 48.25, 3.50 +19.38, 20.00, 49.23, 50.77, -1.54 +19.38, 20.00, 51.70, 48.30, 3.41 +19.38, 20.00, 51.71, 48.29, 3.41 +19.38, 20.00, 51.71, 48.29, 3.42 +19.38, 20.00, 51.71, 48.29, 3.42 +19.38, 20.00, 51.71, 48.29, 3.43 +19.31, 20.00, 54.24, 45.76, 8.47 +19.38, 20.00, 49.25, 50.75, -1.51 +19.31, 20.00, 54.24, 45.76, 8.48 +19.31, 20.00, 51.77, 48.23, 3.54 +19.31, 20.00, 51.77, 48.23, 3.55 +19.31, 20.00, 51.78, 48.22, 3.56 +19.31, 20.00, 51.78, 48.22, 3.56 +19.31, 20.00, 51.78, 48.22, 3.57 +19.38, 20.00, 49.26, 50.74, -1.47 +19.38, 20.00, 51.74, 48.26, 3.48 +19.51, 20.00, 46.70, 53.30, -6.61 +19.51, 20.00, 51.64, 48.36, 3.29 +19.51, 20.00, 51.64, 48.36, 3.29 +19.51, 20.00, 51.65, 48.35, 3.29 +19.51, 20.00, 51.65, 48.35, 3.30 +19.38, 20.00, 56.69, 43.31, 13.39 +19.38, 20.00, 51.75, 48.25, 3.50 +19.38, 20.00, 51.75, 48.25, 3.51 +19.38, 20.00, 51.76, 48.24, 3.51 +19.38, 20.00, 51.76, 48.24, 3.52 +19.31, 20.00, 54.28, 45.72, 8.57 +19.38, 20.00, 49.29, 50.71, -1.42 +19.38, 20.00, 51.77, 48.23, 3.53 +19.38, 20.00, 51.77, 48.23, 3.54 +19.38, 20.00, 51.77, 48.23, 3.54 +19.38, 20.00, 51.77, 48.23, 3.55 +19.51, 20.00, 46.73, 53.27, -6.54 +19.51, 20.00, 51.68, 48.32, 3.36 +19.51, 20.00, 51.68, 48.32, 3.36 +19.51, 20.00, 51.68, 48.32, 3.36 +19.51, 20.00, 51.68, 48.32, 3.37 +19.51, 20.00, 51.69, 48.31, 3.37 +19.38, 20.00, 56.73, 43.27, 13.46 +19.38, 20.00, 51.79, 48.21, 3.58 +19.31, 20.00, 54.31, 45.69, 8.62 +19.38, 20.00, 49.32, 50.68, -1.36 +19.31, 20.00, 54.32, 45.68, 8.63 +19.31, 20.00, 51.85, 48.15, 3.70 +19.31, 20.00, 51.85, 48.15, 3.70 +19.31, 20.00, 51.85, 48.15, 3.71 +19.38, 20.00, 49.33, 50.67, -1.33 +19.38, 20.00, 51.81, 48.19, 3.62 +19.38, 20.00, 51.81, 48.19, 3.62 +19.51, 20.00, 46.77, 53.23, -6.46 +19.51, 20.00, 51.72, 48.28, 3.43 +19.58, 20.00, 49.20, 50.80, -1.61 +19.58, 20.00, 51.67, 48.33, 3.34 +19.58, 20.00, 51.67, 48.33, 3.34 +19.58, 20.00, 51.67, 48.33, 3.34 +19.51, 20.00, 54.20, 45.80, 8.39 +19.51, 20.00, 51.73, 48.27, 3.45 +19.51, 20.00, 51.73, 48.27, 3.45 +19.38, 20.00, 56.77, 43.23, 13.54 +19.51, 20.00, 46.79, 53.21, -6.42 +19.51, 20.00, 51.73, 48.27, 3.47 +19.51, 20.00, 51.74, 48.26, 3.47 +19.51, 20.00, 51.74, 48.26, 3.47 +19.51, 20.00, 51.74, 48.26, 3.48 +19.58, 20.00, 49.22, 50.78, -1.56 +19.64, 20.00, 49.17, 50.83, -1.66 +19.64, 20.00, 51.64, 48.36, 3.29 +19.78, 20.00, 46.60, 53.40, -6.80 +19.78, 20.00, 51.55, 48.45, 3.09 +19.84, 20.00, 49.03, 50.97, -1.95 +19.84, 20.00, 51.50, 48.50, 3.00 +19.84, 20.00, 51.50, 48.50, 3.00 +19.84, 20.00, 51.50, 48.50, 3.00 +19.84, 20.00, 51.50, 48.50, 3.00 +19.78, 20.00, 54.02, 45.98, 8.05 +19.78, 20.00, 51.55, 48.45, 3.10 +19.78, 20.00, 51.55, 48.45, 3.10 +19.64, 20.00, 56.60, 43.40, 13.19 +19.64, 20.00, 51.65, 48.35, 3.31 +19.64, 20.00, 51.66, 48.34, 3.31 +19.64, 20.00, 51.66, 48.34, 3.31 +19.78, 20.00, 46.61, 53.39, -6.77 +19.78, 20.00, 51.56, 48.44, 3.12 +19.84, 20.00, 49.04, 50.96, -1.92 +19.84, 20.00, 51.51, 48.49, 3.02 +19.91, 20.00, 48.99, 51.01, -2.02 +19.91, 20.00, 51.46, 48.54, 2.93 +19.91, 20.00, 51.46, 48.54, 2.93 +19.91, 20.00, 51.46, 48.54, 2.93 +20.04, 20.00, 46.42, 53.58, -7.16 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +19.91, 20.00, 56.41, 43.59, 12.81 +19.91, 20.00, 51.46, 48.54, 2.93 +19.91, 20.00, 51.46, 48.54, 2.93 +19.91, 20.00, 51.46, 48.54, 2.93 +20.04, 20.00, 46.42, 53.58, -7.16 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.04, 20.00, 51.36, 48.64, 2.73 +20.10, 20.00, 48.84, 51.16, -2.31 +20.10, 20.00, 51.31, 48.69, 2.63 +20.10, 20.00, 51.31, 48.69, 2.63 +20.10, 20.00, 51.31, 48.69, 2.63 +20.10, 20.00, 51.31, 48.69, 2.63 +20.10, 20.00, 51.31, 48.69, 2.62 +20.04, 20.00, 53.83, 46.17, 7.67 +20.04, 20.00, 51.36, 48.64, 2.72 +20.04, 20.00, 51.36, 48.64, 2.72 +20.04, 20.00, 51.36, 48.64, 2.72 +20.04, 20.00, 51.36, 48.64, 2.72 +20.10, 20.00, 48.84, 51.16, -2.32 +20.04, 20.00, 53.83, 46.17, 7.67 +20.10, 20.00, 48.84, 51.16, -2.32 +20.10, 20.00, 51.31, 48.69, 2.62 +20.10, 20.00, 51.31, 48.69, 2.62 +20.10, 20.00, 51.31, 48.69, 2.62 +20.10, 20.00, 51.31, 48.69, 2.62 +20.17, 20.00, 48.79, 51.21, -2.43 +20.17, 20.00, 51.26, 48.74, 2.52 +20.17, 20.00, 51.26, 48.74, 2.52 +20.17, 20.00, 51.26, 48.74, 2.51 +20.17, 20.00, 51.26, 48.74, 2.51 +20.17, 20.00, 51.26, 48.74, 2.51 +20.17, 20.00, 51.26, 48.74, 2.51 +20.17, 20.00, 51.25, 48.75, 2.51 +20.17, 20.00, 51.25, 48.75, 2.51 +20.17, 20.00, 51.25, 48.75, 2.51 +20.17, 20.00, 51.25, 48.75, 2.51 +20.17, 20.00, 51.25, 48.75, 2.50 +20.17, 20.00, 51.25, 48.75, 2.50 +20.17, 20.00, 51.25, 48.75, 2.50 +20.17, 20.00, 51.25, 48.75, 2.50 +20.17, 20.00, 51.25, 48.75, 2.50 +20.30, 20.00, 46.21, 53.79, -7.59 +20.30, 20.00, 51.15, 48.85, 2.30 +20.30, 20.00, 51.15, 48.85, 2.29 +20.30, 20.00, 51.15, 48.85, 2.29 +20.30, 20.00, 51.14, 48.86, 2.29 +20.17, 20.00, 56.19, 43.81, 12.37 +20.17, 20.00, 51.24, 48.76, 2.49 +20.17, 20.00, 51.24, 48.76, 2.48 +20.10, 20.00, 53.76, 46.24, 7.53 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.04, 20.00, 53.81, 46.19, 7.62 +20.04, 20.00, 51.34, 48.66, 2.68 +20.10, 20.00, 48.82, 51.18, -2.37 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.58 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.29, 48.71, 2.57 +20.10, 20.00, 51.28, 48.72, 2.57 +20.10, 20.00, 51.28, 48.72, 2.57 +20.10, 20.00, 51.28, 48.72, 2.57 +20.04, 20.00, 53.81, 46.19, 7.61 +20.04, 20.00, 51.33, 48.67, 2.67 +20.04, 20.00, 51.33, 48.67, 2.67 +20.04, 20.00, 51.33, 48.67, 2.67 +19.91, 20.00, 56.38, 43.62, 12.75 +19.91, 20.00, 51.43, 48.57, 2.86 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.91, 20.00, 51.43, 48.57, 2.87 +19.84, 20.00, 53.96, 46.04, 7.91 +19.84, 20.00, 51.49, 48.51, 2.97 +19.84, 20.00, 51.49, 48.51, 2.97 +19.84, 20.00, 51.49, 48.51, 2.97 +19.84, 20.00, 51.49, 48.51, 2.97 +19.84, 20.00, 51.49, 48.51, 2.98 +19.78, 20.00, 54.01, 45.99, 8.02 +19.78, 20.00, 51.54, 48.46, 3.08 +19.78, 20.00, 51.54, 48.46, 3.08 +19.78, 20.00, 51.54, 48.46, 3.08 +19.64, 20.00, 56.58, 43.42, 13.17 +19.64, 20.00, 51.64, 48.36, 3.28 +19.64, 20.00, 51.64, 48.36, 3.29 +19.64, 20.00, 51.64, 48.36, 3.29 +19.64, 20.00, 51.65, 48.35, 3.29 +19.64, 20.00, 51.65, 48.35, 3.29 +19.58, 20.00, 54.17, 45.83, 8.34 +19.58, 20.00, 51.70, 48.30, 3.40 +19.58, 20.00, 51.70, 48.30, 3.40 +19.58, 20.00, 51.70, 48.30, 3.41 +19.58, 20.00, 51.70, 48.30, 3.41 +19.58, 20.00, 51.71, 48.29, 3.41 +19.58, 20.00, 51.71, 48.29, 3.42 +19.58, 20.00, 51.71, 48.29, 3.42 +19.58, 20.00, 51.71, 48.29, 3.42 +19.51, 20.00, 54.23, 45.77, 8.47 +19.51, 20.00, 51.76, 48.24, 3.53 +19.51, 20.00, 51.77, 48.23, 3.53 +19.51, 20.00, 51.77, 48.23, 3.54 +19.38, 20.00, 56.81, 43.19, 13.63 +19.38, 20.00, 51.87, 48.13, 3.74 +19.38, 20.00, 51.87, 48.13, 3.75 +19.38, 20.00, 51.88, 48.12, 3.75 +19.38, 20.00, 51.88, 48.12, 3.76 +19.38, 20.00, 51.88, 48.12, 3.76 +19.51, 20.00, 46.84, 53.16, -6.32 +19.51, 20.00, 51.79, 48.21, 3.57 +19.51, 20.00, 51.79, 48.21, 3.57 +19.51, 20.00, 51.79, 48.21, 3.58 +19.51, 20.00, 51.79, 48.21, 3.58 +19.51, 20.00, 51.79, 48.21, 3.59 +19.51, 20.00, 51.79, 48.21, 3.59 +19.38, 20.00, 56.84, 43.16, 13.68 +19.38, 20.00, 51.90, 48.10, 3.80 +19.38, 20.00, 51.90, 48.10, 3.80 +19.38, 20.00, 51.90, 48.10, 3.81 +19.38, 20.00, 51.90, 48.10, 3.81 +19.31, 20.00, 54.43, 45.57, 8.86 +19.31, 20.00, 51.96, 48.04, 3.92 +19.38, 20.00, 49.44, 50.56, -1.12 +19.38, 20.00, 51.91, 48.09, 3.83 +19.38, 20.00, 51.92, 48.08, 3.83 +19.51, 20.00, 46.88, 53.12, -6.25 +19.51, 20.00, 51.82, 48.18, 3.64 +19.58, 20.00, 49.30, 50.70, -1.40 +19.58, 20.00, 51.78, 48.22, 3.55 +19.58, 20.00, 51.78, 48.22, 3.55 +19.64, 20.00, 49.26, 50.74, -1.49 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.47 +19.64, 20.00, 51.73, 48.27, 3.47 +19.64, 20.00, 51.74, 48.26, 3.47 +19.64, 20.00, 51.74, 48.26, 3.47 +19.64, 20.00, 51.74, 48.26, 3.48 +19.64, 20.00, 51.74, 48.26, 3.48 +19.78, 20.00, 46.70, 53.30, -6.60 +19.78, 20.00, 51.64, 48.36, 3.29 +19.84, 20.00, 49.12, 50.88, -1.76 +19.84, 20.00, 51.59, 48.41, 3.19 +19.84, 20.00, 51.59, 48.41, 3.19 +19.91, 20.00, 49.07, 50.93, -1.85 +19.91, 20.00, 51.55, 48.45, 3.09 +20.04, 20.00, 46.50, 53.50, -6.99 +20.04, 20.00, 51.45, 48.55, 2.89 +20.10, 20.00, 48.93, 51.07, -2.15 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.40, 48.60, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.17, 20.00, 48.87, 51.13, -2.26 +20.17, 20.00, 51.34, 48.66, 2.69 +20.17, 20.00, 51.34, 48.66, 2.69 +20.30, 20.00, 46.30, 53.70, -7.40 +20.30, 20.00, 51.24, 48.76, 2.48 +20.30, 20.00, 51.24, 48.76, 2.48 +20.30, 20.00, 51.24, 48.76, 2.48 +20.37, 20.00, 48.72, 51.28, -2.57 +20.37, 20.00, 51.19, 48.81, 2.37 +20.37, 20.00, 51.19, 48.81, 2.37 +20.37, 20.00, 51.18, 48.82, 2.37 +20.37, 20.00, 51.18, 48.82, 2.37 +20.37, 20.00, 51.18, 48.82, 2.36 +20.37, 20.00, 51.18, 48.82, 2.36 +20.37, 20.00, 51.18, 48.82, 2.36 +20.37, 20.00, 51.18, 48.82, 2.36 +20.37, 20.00, 51.18, 48.82, 2.35 +20.37, 20.00, 51.17, 48.83, 2.35 +20.37, 20.00, 51.17, 48.83, 2.35 +20.37, 20.00, 51.17, 48.83, 2.34 +20.37, 20.00, 51.17, 48.83, 2.34 +20.37, 20.00, 51.17, 48.83, 2.34 +20.37, 20.00, 51.17, 48.83, 2.34 +20.37, 20.00, 51.17, 48.83, 2.33 +20.37, 20.00, 51.17, 48.83, 2.33 +20.37, 20.00, 51.16, 48.84, 2.33 +20.37, 20.00, 51.16, 48.84, 2.33 +20.37, 20.00, 51.16, 48.84, 2.32 +20.37, 20.00, 51.16, 48.84, 2.32 +20.37, 20.00, 51.16, 48.84, 2.32 +20.37, 20.00, 51.16, 48.84, 2.31 +20.37, 20.00, 51.16, 48.84, 2.31 +20.37, 20.00, 51.15, 48.85, 2.31 +20.37, 20.00, 51.15, 48.85, 2.31 +20.30, 20.00, 53.67, 46.33, 7.35 +20.30, 20.00, 51.20, 48.80, 2.40 +20.30, 20.00, 51.20, 48.80, 2.40 +20.30, 20.00, 51.20, 48.80, 2.40 +20.17, 20.00, 56.24, 43.76, 12.48 +20.17, 20.00, 51.30, 48.70, 2.59 +20.17, 20.00, 51.29, 48.71, 2.59 +20.17, 20.00, 51.29, 48.71, 2.59 +20.10, 20.00, 53.82, 46.18, 7.63 +20.10, 20.00, 51.34, 48.66, 2.69 +20.10, 20.00, 51.34, 48.66, 2.68 +20.10, 20.00, 51.34, 48.66, 2.68 +20.10, 20.00, 51.34, 48.66, 2.68 +20.10, 20.00, 51.34, 48.66, 2.68 +20.04, 20.00, 53.86, 46.14, 7.72 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +20.04, 20.00, 51.39, 48.61, 2.78 +19.91, 20.00, 56.43, 43.57, 12.87 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.91, 20.00, 51.49, 48.51, 2.98 +19.84, 20.00, 54.01, 45.99, 8.03 +19.84, 20.00, 51.54, 48.46, 3.08 +19.84, 20.00, 51.54, 48.46, 3.08 +19.84, 20.00, 51.54, 48.46, 3.09 +19.84, 20.00, 51.54, 48.46, 3.09 +19.78, 20.00, 54.07, 45.93, 8.13 +19.84, 20.00, 49.07, 50.93, -1.85 +19.78, 20.00, 54.07, 45.93, 8.13 +19.78, 20.00, 51.60, 48.40, 3.19 +19.78, 20.00, 51.60, 48.40, 3.19 +19.78, 20.00, 51.60, 48.40, 3.19 +19.78, 20.00, 51.60, 48.40, 3.20 +19.78, 20.00, 51.60, 48.40, 3.20 +19.78, 20.00, 51.60, 48.40, 3.20 +19.78, 20.00, 51.60, 48.40, 3.20 +19.78, 20.00, 51.60, 48.40, 3.20 +19.64, 20.00, 56.65, 43.35, 13.29 +19.64, 20.00, 51.70, 48.30, 3.41 +19.64, 20.00, 51.70, 48.30, 3.41 +19.64, 20.00, 51.71, 48.29, 3.41 +19.64, 20.00, 51.71, 48.29, 3.41 +19.64, 20.00, 51.71, 48.29, 3.42 +19.64, 20.00, 51.71, 48.29, 3.42 +19.64, 20.00, 51.71, 48.29, 3.42 +19.64, 20.00, 51.71, 48.29, 3.43 +19.64, 20.00, 51.71, 48.29, 3.43 +19.64, 20.00, 51.72, 48.28, 3.43 +19.78, 20.00, 46.67, 53.33, -6.65 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.24 +19.78, 20.00, 51.62, 48.38, 3.25 +19.78, 20.00, 51.62, 48.38, 3.25 +19.78, 20.00, 51.62, 48.38, 3.25 +19.64, 20.00, 56.67, 43.33, 13.34 +19.64, 20.00, 51.73, 48.27, 3.45 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.78, 20.00, 46.69, 53.31, -6.62 +19.64, 20.00, 56.68, 43.32, 13.35 +19.78, 20.00, 46.69, 53.31, -6.62 +19.78, 20.00, 51.64, 48.36, 3.27 +19.84, 20.00, 49.11, 50.89, -1.77 +19.84, 20.00, 51.59, 48.41, 3.17 +19.84, 20.00, 51.59, 48.41, 3.18 +19.84, 20.00, 51.59, 48.41, 3.18 +19.84, 20.00, 51.59, 48.41, 3.18 +19.91, 20.00, 49.07, 50.93, -1.86 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.08 +19.91, 20.00, 51.54, 48.46, 3.09 +19.91, 20.00, 51.54, 48.46, 3.09 +19.91, 20.00, 51.54, 48.46, 3.09 +19.91, 20.00, 51.54, 48.46, 3.09 +19.91, 20.00, 51.54, 48.46, 3.09 +20.04, 20.00, 46.50, 53.50, -7.00 +20.04, 20.00, 51.44, 48.56, 2.89 +20.10, 20.00, 48.92, 51.08, -2.15 +20.10, 20.00, 51.39, 48.61, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.10, 20.00, 51.39, 48.61, 2.79 +20.17, 20.00, 48.87, 51.13, -2.26 +20.10, 20.00, 53.86, 46.14, 7.73 +20.10, 20.00, 51.39, 48.61, 2.78 +20.10, 20.00, 51.39, 48.61, 2.78 +20.17, 20.00, 48.87, 51.13, -2.26 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.68 +20.17, 20.00, 51.34, 48.66, 2.67 +20.30, 20.00, 46.29, 53.71, -7.41 +20.30, 20.00, 51.24, 48.76, 2.47 +20.30, 20.00, 51.23, 48.77, 2.47 +20.30, 20.00, 51.23, 48.77, 2.47 +20.30, 20.00, 51.23, 48.77, 2.46 +20.17, 20.00, 56.27, 43.73, 12.55 +20.17, 20.00, 51.33, 48.67, 2.66 +20.17, 20.00, 51.33, 48.67, 2.66 +20.17, 20.00, 51.33, 48.67, 2.66 +20.10, 20.00, 53.85, 46.15, 7.70 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.38, 48.62, 2.75 +20.10, 20.00, 51.37, 48.63, 2.75 +20.10, 20.00, 51.37, 48.63, 2.75 +20.17, 20.00, 48.85, 51.15, -2.29 +20.10, 20.00, 53.85, 46.15, 7.69 +20.17, 20.00, 48.85, 51.15, -2.30 +20.17, 20.00, 51.32, 48.68, 2.65 +20.17, 20.00, 51.32, 48.68, 2.64 +20.10, 20.00, 53.84, 46.16, 7.69 +20.10, 20.00, 51.37, 48.63, 2.74 +20.10, 20.00, 51.37, 48.63, 2.74 +20.10, 20.00, 51.37, 48.63, 2.74 +20.04, 20.00, 53.89, 46.11, 7.78 +20.04, 20.00, 51.42, 48.58, 2.84 +20.04, 20.00, 51.42, 48.58, 2.84 +20.04, 20.00, 51.42, 48.58, 2.84 +19.91, 20.00, 56.46, 43.54, 12.92 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.91, 20.00, 51.52, 48.48, 3.04 +19.84, 20.00, 54.04, 45.96, 8.09 +19.84, 20.00, 51.57, 48.43, 3.14 +19.84, 20.00, 51.57, 48.43, 3.14 +19.84, 20.00, 51.57, 48.43, 3.15 +19.84, 20.00, 51.57, 48.43, 3.15 +19.78, 20.00, 54.10, 45.90, 8.19 +19.78, 20.00, 51.62, 48.38, 3.25 +19.78, 20.00, 51.63, 48.37, 3.25 +19.78, 20.00, 51.63, 48.37, 3.25 +19.64, 20.00, 56.67, 43.33, 13.34 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.64, 20.00, 51.73, 48.27, 3.46 +19.58, 20.00, 54.25, 45.75, 8.51 +19.58, 20.00, 51.78, 48.22, 3.57 +19.58, 20.00, 51.78, 48.22, 3.57 +19.58, 20.00, 51.79, 48.21, 3.57 +19.58, 20.00, 51.79, 48.21, 3.58 +19.58, 20.00, 51.79, 48.21, 3.58 +19.58, 20.00, 51.79, 48.21, 3.58 +19.58, 20.00, 51.79, 48.21, 3.58 +19.58, 20.00, 51.79, 48.21, 3.59 +19.51, 20.00, 54.32, 45.68, 8.63 +19.51, 20.00, 51.85, 48.15, 3.69 +19.51, 20.00, 51.85, 48.15, 3.70 +19.51, 20.00, 51.85, 48.15, 3.70 +19.51, 20.00, 51.85, 48.15, 3.71 +19.51, 20.00, 51.85, 48.15, 3.71 +19.38, 20.00, 56.90, 43.10, 13.80 +19.38, 20.00, 51.96, 48.04, 3.92 +19.38, 20.00, 51.96, 48.04, 3.92 +19.38, 20.00, 51.96, 48.04, 3.93 +19.38, 20.00, 51.96, 48.04, 3.93 +19.38, 20.00, 51.97, 48.03, 3.93 +19.38, 20.00, 51.97, 48.03, 3.94 +19.38, 20.00, 51.97, 48.03, 3.94 +19.51, 20.00, 46.93, 53.07, -6.14 +19.38, 20.00, 56.92, 43.08, 13.84 +19.38, 20.00, 51.98, 48.02, 3.96 +19.38, 20.00, 51.98, 48.02, 3.96 +19.38, 20.00, 51.98, 48.02, 3.97 +19.38, 20.00, 51.99, 48.01, 3.97 +19.38, 20.00, 51.99, 48.01, 3.98 +19.38, 20.00, 51.99, 48.01, 3.98 +19.38, 20.00, 51.99, 48.01, 3.98 +19.38, 20.00, 51.99, 48.01, 3.99 +19.38, 20.00, 52.00, 48.00, 3.99 +19.38, 20.00, 52.00, 48.00, 4.00 +19.38, 20.00, 52.00, 48.00, 4.00 +19.38, 20.00, 52.00, 48.00, 4.01 +19.38, 20.00, 52.01, 47.99, 4.01 +19.38, 20.00, 52.01, 47.99, 4.02 +19.38, 20.00, 52.01, 47.99, 4.02 +19.38, 20.00, 52.01, 47.99, 4.03 +19.51, 20.00, 46.97, 53.03, -6.06 +19.51, 20.00, 51.92, 48.08, 3.84 +19.38, 20.00, 56.96, 43.04, 13.93 +19.51, 20.00, 46.98, 53.02, -6.04 +19.38, 20.00, 56.97, 43.03, 13.93 +19.38, 20.00, 52.03, 47.97, 4.05 +19.38, 20.00, 52.03, 47.97, 4.06 +19.38, 20.00, 52.03, 47.97, 4.06 +19.38, 20.00, 52.03, 47.97, 4.07 +19.51, 20.00, 46.99, 53.01, -6.02 +19.51, 20.00, 51.94, 48.06, 3.88 +19.51, 20.00, 51.94, 48.06, 3.88 +19.58, 20.00, 49.42, 50.58, -1.16 +19.58, 20.00, 51.89, 48.11, 3.79 +19.58, 20.00, 51.89, 48.11, 3.79 +19.58, 20.00, 51.90, 48.10, 3.79 +19.58, 20.00, 51.90, 48.10, 3.80 +19.58, 20.00, 51.90, 48.10, 3.80 +19.58, 20.00, 51.90, 48.10, 3.80 +19.58, 20.00, 51.90, 48.10, 3.81 +19.64, 20.00, 49.38, 50.62, -1.23 +19.58, 20.00, 54.38, 45.62, 8.75 +19.64, 20.00, 49.39, 50.61, -1.23 +19.64, 20.00, 51.86, 48.14, 3.72 +19.64, 20.00, 51.86, 48.14, 3.72 +19.64, 20.00, 51.86, 48.14, 3.72 +19.64, 20.00, 51.86, 48.14, 3.73 +19.64, 20.00, 51.86, 48.14, 3.73 +19.64, 20.00, 51.87, 48.13, 3.73 +19.64, 20.00, 51.87, 48.13, 3.73 +19.78, 20.00, 46.82, 53.18, -6.35 +19.78, 20.00, 51.77, 48.23, 3.54 +19.78, 20.00, 51.77, 48.23, 3.54 +19.78, 20.00, 51.77, 48.23, 3.54 +19.78, 20.00, 51.77, 48.23, 3.54 +19.78, 20.00, 51.77, 48.23, 3.55 +19.78, 20.00, 51.77, 48.23, 3.55 +19.78, 20.00, 51.77, 48.23, 3.55 +19.78, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.08, 74.92, -49.83 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.84, -15.00, 25.00, 75.00, -50.00 +19.78, -15.00, 26.56, 73.44, -46.88 +19.64, -15.00, 29.00, 71.00, -42.00 +19.64, -15.00, 25.00, 75.00, -50.00 +19.58, -15.00, 26.32, 73.68, -47.36 +19.38, -15.00, 31.28, 68.72, -37.44 +19.31, -15.00, 26.26, 73.74, -47.48 +19.25, -15.00, 26.18, 73.82, -47.64 +19.12, -15.00, 28.62, 71.38, -42.75 +18.98, -15.00, 28.59, 71.41, -42.81 +18.85, -15.00, 28.57, 71.43, -42.87 +18.59, -15.00, 33.58, 66.42, -32.84 +18.52, -15.00, 26.09, 73.91, -47.82 +18.26, -15.00, 33.58, 66.42, -32.84 +18.06, -15.00, 31.13, 68.87, -37.74 +17.93, -15.00, 28.63, 71.37, -42.73 +17.53, -15.00, 38.70, 61.30, -22.61 +17.40, -15.00, 28.79, 71.21, -42.43 +17.14, -15.00, 33.81, 66.19, -32.39 +16.74, -15.00, 38.93, 61.07, -22.14 +16.48, -15.00, 34.06, 65.94, -31.87 +16.15, -15.00, 36.67, 63.33, -26.67 +15.89, -15.00, 34.28, 65.72, -31.45 +15.42, -15.00, 41.92, 58.08, -16.15 +15.16, -15.00, 34.59, 65.41, -30.81 +14.77, -15.00, 39.72, 60.28, -20.55 +14.30, -15.00, 42.43, 57.57, -15.14 +13.97, -15.00, 37.63, 62.37, -24.75 +13.58, -15.00, 40.29, 59.71, -19.43 +13.18, -15.00, 40.48, 59.52, -19.04 +12.72, -15.00, 43.19, 56.81, -13.62 +12.26, -15.00, 43.44, 56.56, -13.13 +11.87, -15.00, 41.16, 58.84, -17.68 +11.34, -15.00, 46.40, 53.60, -7.20 +10.88, -15.00, 44.18, 55.82, -11.65 +10.35, -15.00, 46.95, 53.05, -6.10 +9.89, -15.00, 44.73, 55.27, -10.54 +9.36, -15.00, 47.51, 52.49, -4.99 +8.83, -15.00, 47.81, 52.19, -4.37 +8.31, -15.00, 48.12, 51.88, -3.76 +7.78, -15.00, 48.43, 51.57, -3.14 +7.25, -15.00, 48.74, 51.26, -2.51 +6.66, -15.00, 51.58, 48.42, 3.16 +6.13, -15.00, 49.42, 50.58, -1.15 +5.60, -15.00, 49.74, 50.26, -0.52 +5.01, -15.00, 52.58, 47.42, 5.17 +4.48, -15.00, 50.43, 49.57, 0.87 +3.96, -15.00, 50.76, 49.24, 1.52 +3.43, -15.00, 51.08, 48.92, 2.17 +2.77, -15.00, 56.46, 43.54, 12.91 +2.24, -15.00, 51.84, 48.16, 3.69 +1.65, -15.00, 54.70, 45.30, 9.39 +1.12, -15.00, 52.56, 47.44, 5.12 +0.53, -15.00, 55.42, 44.58, 10.84 +-0.13, -15.00, 58.33, 41.67, 16.66 +-0.73, -15.00, 56.25, 43.75, 12.50 +-1.45, -15.00, 61.69, 38.31, 23.37 +-2.04, -15.00, 57.14, 42.86, 14.28 +-2.77, -15.00, 62.58, 37.42, 25.16 +-3.36, -15.00, 58.04, 41.96, 16.08 +-4.09, -15.00, 63.48, 36.52, 26.97 +-4.75, -15.00, 61.47, 38.53, 22.94 +-5.27, -15.00, 56.88, 43.12, 13.77 +-6.00, -15.00, 64.81, 35.19, 29.62 +-6.59, -15.00, 60.28, 39.72, 20.56 +-7.25, -15.00, 63.22, 36.78, 26.43 +-7.84, -15.00, 61.16, 38.84, 22.33 +-8.44, -15.00, 61.58, 38.42, 23.17 +-9.10, -15.00, 64.53, 35.47, 29.05 +-9.62, -15.00, 59.96, 40.04, 19.92 +-10.28, -15.00, 65.38, 34.62, 30.76 +-10.81, -15.00, 60.82, 39.18, 21.63 +-11.47, -15.00, 66.24, 33.76, 32.48 +-12.06, -15.00, 64.20, 35.80, 28.40 +-12.66, -15.00, 64.64, 35.36, 29.28 +-13.18, -15.00, 62.56, 37.44, 25.11 +-13.84, -15.00, 67.99, 32.01, 35.98 +-14.37, -15.00, 63.44, 36.56, 26.88 +-14.96, -15.00, 66.35, 33.65, 32.71 +-15.56, -15.00, 66.80, 33.20, 33.60 +-16.08, -15.00, 64.73, 35.27, 29.46 +-16.61, -15.00, 65.13, 34.87, 30.26 +-17.14, -15.00, 65.53, 34.47, 31.07 +-17.67, -15.00, 65.94, 34.06, 31.88 +-18.19, -15.00, 66.35, 33.65, 32.70 +-18.65, -15.00, 64.24, 35.76, 28.47 +-19.18, -15.00, 67.12, 32.88, 34.24 +-19.71, -15.00, 67.53, 32.47, 35.06 +-20.24, -15.00, 67.95, 32.05, 35.89 +-20.70, -15.00, 65.84, 34.16, 31.68 +-21.09, -15.00, 63.69, 36.31, 27.38 +-21.56, -15.00, 66.53, 33.47, 33.07 +-22.02, -15.00, 66.90, 33.09, 33.81 +-22.41, -15.00, 64.76, 35.24, 29.52 +-22.87, -15.00, 67.61, 32.39, 35.21 +-23.20, -15.00, 62.94, 37.06, 25.88 +-23.60, -15.00, 65.74, 34.26, 31.48 +-23.99, -15.00, 66.07, 33.93, 32.14 +-24.39, -15.00, 66.40, 33.60, 32.80 +-24.72, -15.00, 64.21, 35.79, 28.43 +-25.05, -15.00, 64.50, 35.50, 29.00 +-25.44, -15.00, 67.31, 32.69, 34.61 +-25.71, -15.00, 62.60, 37.40, 25.20 +-26.04, -15.00, 65.36, 34.64, 30.72 +-26.30, -15.00, 63.13, 36.87, 26.26 +-26.63, -15.00, 65.89, 34.11, 31.78 +-26.89, -15.00, 63.66, 36.34, 27.32 +-27.16, -15.00, 63.91, 36.09, 27.81 +-27.42, -15.00, 64.15, 35.85, 28.30 +-27.69, -15.00, 64.40, 35.60, 28.79 +-27.95, -15.00, 64.64, 35.36, 29.28 +-28.15, -15.00, 62.37, 37.63, 24.73 +-28.41, -15.00, 65.09, 34.91, 30.17 +-28.48, -15.00, 57.77, 42.23, 15.54 +-28.74, -15.00, 65.44, 34.56, 30.87 +-28.87, -15.00, 60.64, 39.36, 21.29 +-29.00, -15.00, 60.80, 39.20, 21.59 +-29.14, -15.00, 60.95, 39.05, 21.89 +-29.27, -15.00, 61.10, 38.90, 22.20 +-29.40, -15.00, 61.25, 38.75, 22.50 +-29.53, -15.00, 61.41, 38.59, 22.81 +-29.66, -15.00, 61.56, 38.44, 23.12 +-29.73, -15.00, 59.19, 40.81, 18.38 +-29.79, -15.00, 59.30, 40.70, 18.59 +-29.79, -15.00, 56.88, 43.12, 13.76 +-29.93, -15.00, 61.98, 38.02, 23.96 +-29.99, -15.00, 59.61, 40.39, 19.23 +-29.99, -15.00, 57.20, 42.80, 14.39 +-30.06, -15.00, 59.78, 40.22, 19.55 +-30.06, -15.00, 57.36, 42.64, 14.72 +-30.06, -15.00, 57.42, 42.58, 14.83 +-30.06, -15.00, 57.47, 42.53, 14.95 +-30.06, -15.00, 57.53, 42.47, 15.06 +-30.06, -15.00, 57.59, 42.41, 15.17 +-29.99, -15.00, 55.12, 44.88, 10.24 +-29.99, -15.00, 57.65, 42.35, 15.30 +-29.99, -15.00, 57.70, 42.30, 15.41 +-29.99, -15.00, 57.76, 42.24, 15.52 +-29.93, -15.00, 55.30, 44.70, 10.59 +-29.79, -15.00, 52.78, 47.22, 5.56 +-29.79, -15.00, 57.78, 42.22, 15.56 +-29.73, -15.00, 55.31, 44.69, 10.63 +-29.66, -15.00, 55.32, 44.68, 10.64 +-29.53, -15.00, 52.80, 47.20, 5.61 +-29.53, -15.00, 57.80, 42.20, 15.60 +-29.40, -15.00, 52.81, 47.19, 5.62 +-29.27, -15.00, 52.77, 47.23, 5.53 +-29.20, -15.00, 55.24, 44.76, 10.49 +-29.14, -15.00, 55.25, 44.75, 10.49 +-29.00, -15.00, 52.73, 47.27, 5.46 +-28.87, -15.00, 52.68, 47.32, 5.36 +-28.74, -15.00, 52.63, 47.37, 5.27 +-28.67, -15.00, 55.11, 44.89, 10.22 +-28.48, -15.00, 50.07, 49.93, 0.13 +-28.41, -15.00, 55.01, 44.99, 10.02 +-28.34, -15.00, 55.01, 44.99, 10.02 +-28.21, -15.00, 52.49, 47.51, 4.98 +-28.08, -15.00, 52.44, 47.56, 4.88 +-27.95, -15.00, 52.39, 47.61, 4.78 +-27.82, -15.00, 52.34, 47.66, 4.68 +-27.62, -15.00, 49.77, 50.23, -0.47 +-27.55, -15.00, 54.71, 45.29, 9.42 +-27.36, -15.00, 49.66, 50.34, -0.68 +-27.29, -15.00, 54.60, 45.40, 9.20 +-27.09, -15.00, 49.56, 50.44, -0.89 +-26.89, -15.00, 49.45, 50.55, -1.10 +-26.76, -15.00, 51.87, 48.13, 3.74 +-26.56, -15.00, 49.29, 50.71, -1.42 +-26.50, -15.00, 54.23, 45.77, 8.46 +-26.30, -15.00, 49.18, 50.82, -1.64 +-26.10, -15.00, 49.07, 50.93, -1.85 +-26.04, -15.00, 54.01, 45.99, 8.02 +-25.97, -15.00, 54.00, 46.00, 8.00 +-25.77, -15.00, 48.95, 51.05, -2.10 +-25.58, -15.00, 48.84, 51.16, -2.32 +-25.44, -15.00, 51.25, 48.75, 2.51 +-25.31, -15.00, 51.19, 48.81, 2.38 +-25.18, -15.00, 51.13, 48.87, 2.26 +-24.98, -15.00, 48.55, 51.45, -2.90 +-24.92, -15.00, 53.48, 46.52, 6.96 +-24.72, -15.00, 48.42, 51.58, -3.15 +-24.52, -15.00, 48.31, 51.69, -3.38 +-24.46, -15.00, 53.24, 46.76, 6.48 +-24.26, -15.00, 48.18, 51.82, -3.63 +-24.13, -15.00, 50.59, 49.41, 1.18 +-23.99, -15.00, 50.53, 49.47, 1.05 +-23.93, -15.00, 52.98, 47.02, 5.97 +-23.73, -15.00, 47.92, 52.08, -4.15 +-23.60, -15.00, 50.33, 49.67, 0.66 +-23.47, -15.00, 50.26, 49.74, 0.52 +-23.33, -15.00, 50.19, 49.81, 0.39 +-23.20, -15.00, 50.13, 49.87, 0.25 +-23.07, -15.00, 50.06, 49.94, 0.11 +-22.94, -15.00, 49.99, 50.01, -0.02 +-22.87, -15.00, 52.44, 47.56, 4.88 +-22.68, -15.00, 47.38, 52.62, -5.25 +-22.54, -15.00, 49.78, 50.22, -0.44 +-22.41, -15.00, 49.71, 50.29, -0.59 +-22.35, -15.00, 52.16, 47.84, 4.31 +-22.28, -15.00, 52.13, 47.87, 4.27 +-22.15, -15.00, 49.59, 50.41, -0.82 +-22.02, -15.00, 49.52, 50.48, -0.96 +-21.88, -15.00, 49.45, 50.55, -1.11 +-21.82, -15.00, 51.89, 48.11, 3.79 +-21.75, -15.00, 51.87, 48.13, 3.74 +-21.62, -15.00, 49.32, 50.68, -1.35 +-21.56, -15.00, 51.77, 48.23, 3.54 +-21.49, -15.00, 51.74, 48.26, 3.49 +-21.36, -15.00, 49.20, 50.80, -1.60 +-21.29, -15.00, 51.64, 48.36, 3.29 +-21.23, -15.00, 51.62, 48.38, 3.24 +-21.09, -15.00, 49.07, 50.93, -1.86 +-21.03, -15.00, 51.52, 48.48, 3.03 +-20.96, -15.00, 51.49, 48.51, 2.98 +-20.83, -15.00, 48.94, 51.06, -2.12 +-20.76, -15.00, 51.38, 48.62, 2.77 +-20.70, -15.00, 51.36, 48.64, 2.71 +-20.70, -15.00, 53.85, 46.15, 7.70 +-20.57, -15.00, 48.83, 51.17, -2.35 +-20.50, -15.00, 51.27, 48.73, 2.54 +-20.43, -15.00, 51.24, 48.76, 2.48 +-20.43, -15.00, 53.73, 46.27, 7.47 +-20.30, -15.00, 48.71, 51.29, -2.58 +-20.30, -15.00, 53.67, 46.33, 7.35 +-20.24, -15.00, 51.17, 48.83, 2.34 +-20.24, -15.00, 53.66, 46.34, 7.33 +-20.17, -15.00, 51.16, 48.84, 2.32 +-20.04, -15.00, 48.61, 51.39, -2.78 +-20.04, -15.00, 53.57, 46.43, 7.15 +-19.97, -15.00, 51.07, 48.93, 2.14 +-19.97, -15.00, 53.56, 46.44, 7.12 +-19.91, -15.00, 51.06, 48.94, 2.11 +-19.91, -15.00, 53.55, 46.45, 7.10 +-19.91, -15.00, 53.57, 46.43, 7.13 +-19.78, -15.00, 48.54, 51.46, -2.92 +-19.78, -15.00, 53.50, 46.50, 7.01 +-19.71, -15.00, 51.00, 49.00, 2.00 +-19.71, -15.00, 53.49, 46.51, 6.98 +-19.71, -15.00, 53.51, 46.49, 7.01 +-19.64, -15.00, 51.00, 49.00, 2.01 +-19.64, -15.00, 53.49, 46.51, 6.98 +-19.51, -15.00, 48.47, 51.53, -3.07 +-19.51, -15.00, 53.43, 46.57, 6.85 +-19.51, -15.00, 53.44, 46.56, 6.89 +-19.51, -15.00, 53.46, 46.54, 6.92 +-19.45, -15.00, 50.96, 49.04, 1.91 +-19.45, -15.00, 53.44, 46.56, 6.89 +-19.45, -15.00, 53.46, 46.54, 6.92 +-19.45, -15.00, 53.48, 46.52, 6.96 +-19.45, -15.00, 53.49, 46.51, 6.99 +-19.38, -15.00, 50.99, 49.01, 1.98 +-19.38, -15.00, 53.48, 46.52, 6.96 +-19.38, -15.00, 53.49, 46.51, 6.99 +-19.38, -15.00, 53.51, 46.49, 7.02 +-19.25, -15.00, 48.48, 51.52, -3.03 +-19.25, -15.00, 53.44, 46.56, 6.89 +-19.25, -15.00, 53.46, 46.54, 6.92 +-19.25, -15.00, 53.48, 46.52, 6.95 +-19.25, -15.00, 53.49, 46.51, 6.98 +-19.25, -15.00, 53.51, 46.49, 7.02 +-19.25, -15.00, 53.52, 46.48, 7.05 +-19.25, -15.00, 53.54, 46.46, 7.08 +-19.25, -15.00, 53.56, 46.44, 7.11 +-19.18, -15.00, 51.05, 48.95, 2.10 +-19.18, -15.00, 53.54, 46.46, 7.07 +-19.18, -15.00, 53.55, 46.45, 7.11 +-19.18, -15.00, 53.57, 46.43, 7.14 +-19.12, -15.00, 51.06, 48.94, 2.13 +-19.12, -15.00, 53.55, 46.45, 7.10 +-19.12, -15.00, 53.57, 46.43, 7.13 +-19.12, -15.00, 53.58, 46.42, 7.16 +-19.12, -15.00, 53.60, 46.40, 7.19 +-19.12, -15.00, 53.61, 46.39, 7.22 +-19.12, -15.00, 53.63, 46.37, 7.25 +-19.12, -15.00, 53.64, 46.36, 7.29 +-18.98, -15.00, 48.62, 51.38, -2.77 +-18.98, -15.00, 53.57, 46.43, 7.15 +-18.98, -15.00, 53.59, 46.41, 7.18 +-18.98, -15.00, 53.60, 46.40, 7.21 +-18.98, -15.00, 53.62, 46.38, 7.24 +-18.92, -15.00, 51.11, 48.89, 2.22 +-18.92, -15.00, 53.60, 46.40, 7.20 +-18.92, -15.00, 53.61, 46.39, 7.23 +-18.92, -15.00, 53.63, 46.37, 7.26 +-18.92, -15.00, 53.64, 46.36, 7.29 +-18.92, -15.00, 53.66, 46.34, 7.31 +-18.92, -15.00, 53.67, 46.33, 7.34 +-18.92, -15.00, 53.69, 46.31, 7.37 +-18.92, -15.00, 53.70, 46.30, 7.40 +-18.85, -15.00, 51.19, 48.81, 2.39 +-18.85, -15.00, 53.68, 46.32, 7.36 +-18.85, -15.00, 53.70, 46.30, 7.39 +-18.85, -15.00, 53.71, 46.29, 7.42 +-18.85, -15.00, 53.72, 46.28, 7.45 +-18.85, -15.00, 53.74, 46.26, 7.48 +-18.85, -15.00, 53.75, 46.25, 7.51 +-18.85, -15.00, 53.77, 46.23, 7.54 +-18.85, -15.00, 53.78, 46.22, 7.56 +-18.85, -15.00, 53.80, 46.20, 7.59 +-18.85, -15.00, 53.81, 46.19, 7.62 +-18.72, -15.00, 48.78, 51.22, -2.44 +-18.72, -15.00, 53.74, 46.26, 7.48 +-18.72, -15.00, 53.75, 46.25, 7.51 +-18.72, -15.00, 53.77, 46.23, 7.54 +-18.72, -15.00, 53.78, 46.22, 7.56 +-18.72, -15.00, 53.80, 46.20, 7.59 +-18.72, -15.00, 53.81, 46.19, 7.62 +-18.72, -15.00, 53.82, 46.18, 7.65 +-18.72, -15.00, 53.84, 46.16, 7.68 +-18.65, -15.00, 51.33, 48.67, 2.66 +-18.65, -15.00, 53.82, 46.18, 7.63 +-18.65, -15.00, 53.83, 46.17, 7.66 +-18.59, -15.00, 51.32, 48.68, 2.64 +-18.59, -15.00, 53.81, 46.19, 7.61 +-18.59, -15.00, 53.82, 46.18, 7.64 +-18.59, -15.00, 53.83, 46.17, 7.67 +-18.65, -15.00, 56.37, 43.63, 12.74 +-18.59, -15.00, 51.39, 48.61, 2.78 +-18.59, -15.00, 53.87, 46.13, 7.75 +-18.59, -15.00, 53.89, 46.11, 7.78 +-18.59, -15.00, 53.90, 46.10, 7.80 +-18.59, -15.00, 53.91, 46.09, 7.83 +-18.59, -15.00, 53.93, 46.07, 7.86 +-18.59, -15.00, 53.94, 46.06, 7.88 +-18.59, -15.00, 53.96, 46.04, 7.91 +-18.59, -15.00, 53.97, 46.03, 7.94 +-18.59, -15.00, 53.98, 46.02, 7.96 +-18.59, -15.00, 54.00, 46.00, 7.99 +-18.59, -15.00, 54.01, 45.99, 8.02 +-18.46, -15.00, 48.98, 51.02, -2.04 +-18.46, -15.00, 53.94, 46.06, 7.87 +-18.46, -15.00, 53.95, 46.05, 7.90 +-18.46, -15.00, 53.96, 46.04, 7.92 +-18.46, -15.00, 53.97, 46.03, 7.95 +-18.46, -15.00, 53.99, 46.01, 7.98 +-18.39, -15.00, 51.48, 48.52, 2.96 +-18.39, -15.00, 53.96, 46.04, 7.93 +-18.39, -15.00, 53.98, 46.02, 7.95 +-18.39, -15.00, 53.99, 46.01, 7.98 +-18.39, -15.00, 54.00, 46.00, 8.00 +-18.39, -15.00, 54.01, 45.99, 8.03 +-18.39, -15.00, 54.03, 45.97, 8.05 +-18.39, -15.00, 54.04, 45.96, 8.08 +-18.33, -15.00, 51.53, 48.47, 3.06 +-18.39, -15.00, 56.54, 43.46, 13.07 +-18.39, -15.00, 54.08, 45.92, 8.16 +-18.39, -15.00, 54.09, 45.91, 8.18 +-18.39, -15.00, 54.10, 45.90, 8.21 +-18.33, -15.00, 51.59, 48.41, 3.19 +-18.33, -15.00, 54.08, 45.92, 8.16 +-18.33, -15.00, 54.09, 45.91, 8.18 +-18.33, -15.00, 54.10, 45.90, 8.21 +-18.33, -15.00, 54.12, 45.88, 8.23 +-18.33, -15.00, 54.13, 45.87, 8.26 +-18.33, -15.00, 54.14, 45.86, 8.28 +-18.33, -15.00, 54.15, 45.85, 8.31 +-18.33, -15.00, 54.17, 45.83, 8.33 +-18.33, -15.00, 54.18, 45.82, 8.36 +-18.33, -15.00, 54.19, 45.81, 8.38 +-18.33, -15.00, 54.20, 45.80, 8.41 +-18.19, -15.00, 49.17, 50.83, -1.65 +-18.33, -15.00, 59.17, 40.83, 18.34 +-18.19, -15.00, 49.20, 50.80, -1.61 +-18.33, -15.00, 59.20, 40.80, 18.39 +-18.33, -15.00, 54.27, 45.73, 8.53 +-18.19, -15.00, 49.23, 50.77, -1.53 +-18.19, -15.00, 54.19, 45.81, 8.38 +-18.19, -15.00, 54.20, 45.80, 8.40 +-18.19, -15.00, 54.21, 45.79, 8.43 +-18.19, -15.00, 54.23, 45.77, 8.45 +-18.19, -15.00, 54.24, 45.76, 8.48 +-18.19, -15.00, 54.25, 45.75, 8.50 +-18.19, -15.00, 54.26, 45.74, 8.52 +-18.19, -15.00, 54.27, 45.73, 8.55 +-18.13, -15.00, 51.76, 48.24, 3.53 +-18.13, -15.00, 54.25, 45.75, 8.50 +-18.13, -15.00, 54.26, 45.74, 8.52 +-18.13, -15.00, 54.27, 45.73, 8.54 +-18.13, -15.00, 54.28, 45.72, 8.57 +-18.13, -15.00, 54.29, 45.71, 8.59 +-18.13, -15.00, 54.31, 45.69, 8.61 +-18.06, -15.00, 51.80, 48.20, 3.59 +-18.06, -15.00, 54.28, 45.72, 8.56 +-18.06, -15.00, 54.29, 45.71, 8.58 +-17.93, -15.00, 49.26, 50.74, -1.48 +-17.93, -15.00, 54.21, 45.79, 8.43 +-17.93, -15.00, 54.23, 45.77, 8.45 +-17.93, -15.00, 54.24, 45.76, 8.47 +-17.93, -15.00, 54.25, 45.75, 8.50 +-17.93, -15.00, 54.26, 45.74, 8.52 +-17.93, -15.00, 54.27, 45.73, 8.54 +-17.86, -15.00, 51.76, 48.24, 3.52 +-17.86, -15.00, 54.24, 45.76, 8.48 +-17.80, -15.00, 51.73, 48.27, 3.46 +-17.80, -15.00, 54.21, 45.79, 8.43 +-17.80, -15.00, 54.22, 45.78, 8.45 +-17.80, -15.00, 54.23, 45.77, 8.47 +-17.67, -15.00, 49.20, 50.80, -1.60 +-17.67, -15.00, 54.16, 45.84, 8.31 +-17.67, -15.00, 54.17, 45.83, 8.33 +-17.60, -15.00, 51.65, 48.35, 3.31 +-17.60, -15.00, 54.14, 45.86, 8.27 +-17.53, -15.00, 51.62, 48.38, 3.25 +-17.40, -15.00, 49.06, 50.94, -1.88 +-17.40, -15.00, 54.01, 45.99, 8.03 +-17.40, -15.00, 54.02, 45.98, 8.05 +-17.40, -15.00, 54.03, 45.97, 8.07 +-17.34, -15.00, 51.52, 48.48, 3.04 +-17.34, -15.00, 54.00, 46.00, 8.00 +-17.27, -15.00, 51.49, 48.51, 2.98 +-17.27, -15.00, 53.97, 46.03, 7.94 +-17.14, -15.00, 48.93, 51.07, -2.13 +-17.14, -15.00, 53.89, 46.11, 7.77 +-17.07, -15.00, 51.37, 48.63, 2.74 +-17.07, -15.00, 53.85, 46.15, 7.70 +-17.01, -15.00, 51.34, 48.66, 2.68 +-17.01, -15.00, 53.82, 46.18, 7.63 +-16.87, -15.00, 48.78, 51.22, -2.44 +-16.87, -15.00, 53.73, 46.27, 7.46 +-16.87, -15.00, 53.74, 46.26, 7.48 +-16.81, -15.00, 51.22, 48.78, 2.45 +-16.81, -15.00, 53.70, 46.30, 7.41 +-16.74, -15.00, 51.19, 48.81, 2.38 +-16.61, -15.00, 48.62, 51.38, -2.75 +-16.61, -15.00, 53.57, 46.43, 7.15 +-16.61, -15.00, 53.58, 46.42, 7.16 +-16.55, -15.00, 51.06, 48.94, 2.13 +-16.48, -15.00, 51.02, 48.98, 2.04 +-16.48, -15.00, 53.50, 46.50, 7.00 +-16.48, -15.00, 53.50, 46.50, 7.01 +-16.35, -15.00, 48.47, 51.53, -3.07 +-16.28, -15.00, 50.89, 49.11, 1.79 +-16.28, -15.00, 53.37, 46.63, 6.74 +-16.28, -15.00, 53.37, 46.63, 6.75 +-16.22, -15.00, 50.86, 49.14, 1.72 +-16.22, -15.00, 53.33, 46.67, 6.67 +-16.08, -15.00, 48.30, 51.70, -3.41 +-16.08, -15.00, 53.24, 46.76, 6.49 +-16.08, -15.00, 53.25, 46.75, 6.50 +-16.02, -15.00, 50.73, 49.27, 1.46 +-16.02, -15.00, 53.21, 46.79, 6.41 +-15.95, -15.00, 50.69, 49.31, 1.38 +-15.95, -15.00, 53.16, 46.84, 6.33 +-15.82, -15.00, 48.12, 51.88, -3.75 +-15.82, -15.00, 53.07, 46.93, 6.14 +-15.82, -15.00, 53.07, 46.93, 6.15 +-15.75, -15.00, 50.56, 49.44, 1.11 +-15.75, -15.00, 53.03, 46.97, 6.06 +-15.75, -15.00, 53.03, 46.97, 6.07 +-15.69, -15.00, 50.51, 49.49, 1.03 +-15.69, -15.00, 52.99, 47.01, 5.98 +-15.69, -15.00, 52.99, 47.01, 5.98 +-15.56, -15.00, 47.95, 52.05, -4.10 +-15.56, -15.00, 52.90, 47.10, 5.79 +-15.56, -15.00, 52.90, 47.10, 5.80 +-15.56, -15.00, 52.90, 47.10, 5.80 +-15.49, -15.00, 50.38, 49.62, 0.76 +-15.49, -15.00, 52.85, 47.15, 5.71 +-15.49, -15.00, 52.86, 47.14, 5.71 +-15.49, -15.00, 52.86, 47.14, 5.72 +-15.42, -15.00, 50.34, 49.66, 0.68 +-15.42, -15.00, 52.81, 47.19, 5.62 +-15.42, -15.00, 52.81, 47.19, 5.63 +-15.42, -15.00, 52.82, 47.18, 5.63 +-15.42, -15.00, 52.82, 47.18, 5.63 +-15.42, -15.00, 52.82, 47.18, 5.64 +-15.29, -15.00, 47.78, 52.22, -4.45 +-15.29, -15.00, 52.72, 47.28, 5.44 +-15.29, -15.00, 52.72, 47.28, 5.45 +-15.29, -15.00, 52.72, 47.28, 5.45 +-15.29, -15.00, 52.73, 47.27, 5.45 +-15.23, -15.00, 50.20, 49.80, 0.41 +-15.23, -15.00, 52.68, 47.32, 5.36 +-15.23, -15.00, 52.68, 47.32, 5.36 +-15.23, -15.00, 52.68, 47.32, 5.36 +-15.23, -15.00, 52.68, 47.32, 5.36 +-15.16, -15.00, 50.16, 49.84, 0.32 +-15.16, -15.00, 52.63, 47.37, 5.26 +-15.16, -15.00, 52.63, 47.37, 5.26 +-15.16, -15.00, 52.63, 47.37, 5.27 +-15.16, -15.00, 52.63, 47.37, 5.27 +-15.16, -15.00, 52.63, 47.37, 5.27 +-15.16, -15.00, 52.63, 47.37, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.27 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.03, -15.00, 47.60, 52.40, -4.81 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.09 +-15.03, -15.00, 52.54, 47.46, 5.09 +-15.16, -15.00, 57.59, 42.41, 15.17 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.29 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.16, -15.00, 52.65, 47.35, 5.30 +-15.23, -15.00, 55.17, 44.83, 10.35 +-15.16, -15.00, 50.18, 49.82, 0.36 +-15.23, -15.00, 55.17, 44.83, 10.35 +-15.23, -15.00, 52.70, 47.30, 5.41 +-15.23, -15.00, 52.70, 47.30, 5.41 +-15.23, -15.00, 52.70, 47.30, 5.41 +-15.23, -15.00, 52.71, 47.29, 5.41 +-15.23, -15.00, 52.71, 47.29, 5.41 +-15.23, -15.00, 52.71, 47.29, 5.41 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.42 +-15.23, -15.00, 52.71, 47.29, 5.43 +-15.23, -15.00, 52.71, 47.29, 5.43 +-15.23, -15.00, 52.71, 47.29, 5.43 +-15.23, -15.00, 52.72, 47.28, 5.43 +-15.23, -15.00, 52.72, 47.28, 5.43 +-15.23, -15.00, 52.72, 47.28, 5.43 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.23, -15.00, 52.72, 47.28, 5.44 +-15.29, -15.00, 55.24, 44.76, 10.49 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.78, 47.22, 5.55 +-15.29, -15.00, 52.78, 47.22, 5.55 +-15.23, -15.00, 50.26, 49.74, 0.51 +-15.23, -15.00, 52.73, 47.27, 5.46 +-15.23, -15.00, 52.73, 47.27, 5.46 +-15.23, -15.00, 52.73, 47.27, 5.46 +-15.23, -15.00, 52.73, 47.27, 5.46 +-15.23, -15.00, 52.73, 47.27, 5.47 +-15.23, -15.00, 52.73, 47.27, 5.47 +-15.23, -15.00, 52.73, 47.27, 5.47 +-15.23, -15.00, 52.74, 47.26, 5.47 +-15.23, -15.00, 52.74, 47.26, 5.47 +-15.23, -15.00, 52.74, 47.26, 5.47 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.16, -15.00, 50.22, 49.78, 0.44 +-15.16, -15.00, 52.69, 47.31, 5.38 +-15.16, -15.00, 52.69, 47.31, 5.39 +-15.16, -15.00, 52.69, 47.31, 5.39 +-15.16, -15.00, 52.69, 47.31, 5.39 +-15.16, -15.00, 52.69, 47.31, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.39 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.03, -15.00, 47.66, 52.34, -4.69 +-15.03, -15.00, 52.60, 47.40, 5.20 +-15.03, -15.00, 52.60, 47.40, 5.20 +-15.03, -15.00, 52.60, 47.40, 5.20 +-14.96, -15.00, 50.08, 49.92, 0.16 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.96, -15.00, 52.55, 47.45, 5.10 +-14.90, -15.00, 50.03, 49.97, 0.05 +-14.96, -15.00, 55.02, 44.98, 10.04 +-14.90, -15.00, 50.03, 49.97, 0.05 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.90, -15.00, 52.50, 47.50, 4.99 +-14.77, -15.00, 47.45, 52.55, -5.10 +-14.77, -15.00, 52.40, 47.60, 4.79 +-14.77, -15.00, 52.39, 47.61, 4.79 +-14.77, -15.00, 52.39, 47.61, 4.79 +-14.77, -15.00, 52.39, 47.61, 4.79 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.78 +-14.77, -15.00, 52.39, 47.61, 4.77 +-14.77, -15.00, 52.39, 47.61, 4.77 +-14.70, -15.00, 49.86, 50.14, -0.27 +-14.77, -15.00, 54.86, 45.14, 9.71 +-14.77, -15.00, 52.38, 47.62, 4.77 +-14.70, -15.00, 49.86, 50.14, -0.28 +-14.70, -15.00, 52.33, 47.67, 4.66 +-14.70, -15.00, 52.33, 47.67, 4.66 +-14.70, -15.00, 52.33, 47.67, 4.66 +-14.70, -15.00, 52.33, 47.67, 4.66 +-14.70, -15.00, 52.33, 47.67, 4.65 +-14.70, -15.00, 52.33, 47.67, 4.65 +-14.70, -15.00, 52.33, 47.67, 4.65 +-14.70, -15.00, 52.32, 47.68, 4.65 +-14.70, -15.00, 52.32, 47.68, 4.65 +-14.70, -15.00, 52.32, 47.68, 4.64 +-14.70, -15.00, 52.32, 47.68, 4.64 +-14.77, -15.00, 54.84, 45.16, 9.68 +-14.77, -15.00, 52.37, 47.63, 4.74 +-14.77, -15.00, 52.37, 47.63, 4.73 +-14.77, -15.00, 52.37, 47.63, 4.73 +-14.77, -15.00, 52.37, 47.63, 4.73 +-14.70, -15.00, 49.84, 50.16, -0.31 +-14.77, -15.00, 54.84, 45.16, 9.67 +-14.77, -15.00, 52.36, 47.64, 4.73 +-14.70, -15.00, 49.84, 50.16, -0.32 +-14.77, -15.00, 54.83, 45.17, 9.67 +-14.77, -15.00, 52.36, 47.64, 4.72 +-14.77, -15.00, 52.36, 47.64, 4.72 +-14.77, -15.00, 52.36, 47.64, 4.72 +-14.77, -15.00, 52.36, 47.64, 4.71 +-14.77, -15.00, 52.36, 47.64, 4.71 +-14.77, -15.00, 52.36, 47.64, 4.71 +-14.77, -15.00, 52.35, 47.65, 4.71 +-14.77, -15.00, 52.35, 47.65, 4.71 +-14.77, -15.00, 52.35, 47.65, 4.71 +-14.90, -15.00, 57.40, 42.60, 14.79 +-14.77, -15.00, 47.41, 52.59, -5.18 +-14.77, -15.00, 52.35, 47.65, 4.70 +-14.90, -15.00, 57.39, 42.61, 14.79 +-14.90, -15.00, 52.45, 47.55, 4.90 +-14.90, -15.00, 52.45, 47.55, 4.90 +-14.90, -15.00, 52.45, 47.55, 4.90 +-14.90, -15.00, 52.45, 47.55, 4.90 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.45, 47.55, 4.89 +-14.90, -15.00, 52.44, 47.56, 4.89 +-14.90, -15.00, 52.44, 47.56, 4.89 +-14.90, -15.00, 52.44, 47.56, 4.89 +-14.90, -15.00, 52.44, 47.56, 4.89 +-14.96, -15.00, 54.96, 45.04, 9.93 +-14.96, -15.00, 52.49, 47.51, 4.99 +-14.96, -15.00, 52.49, 47.51, 4.99 +-14.96, -15.00, 52.49, 47.51, 4.99 +-14.96, -15.00, 52.49, 47.51, 4.99 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-14.96, -15.00, 52.49, 47.51, 4.98 +-15.03, -15.00, 55.01, 44.99, 10.03 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.03, -15.00, 52.54, 47.46, 5.08 +-15.16, -15.00, 57.59, 42.42, 15.17 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.16, -15.00, 52.64, 47.36, 5.28 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.16, -15.00, 52.64, 47.36, 5.29 +-15.23, -15.00, 55.17, 44.83, 10.33 +-15.23, -15.00, 52.69, 47.31, 5.39 +-15.23, -15.00, 52.70, 47.30, 5.39 +-15.23, -15.00, 52.70, 47.30, 5.39 +-15.23, -15.00, 52.70, 47.30, 5.39 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.23, -15.00, 52.70, 47.30, 5.40 +-15.29, -15.00, 55.22, 44.78, 10.45 +-15.29, -15.00, 52.75, 47.25, 5.51 +-15.29, -15.00, 52.75, 47.25, 5.51 +-15.29, -15.00, 52.76, 47.24, 5.51 +-15.29, -15.00, 52.76, 47.24, 5.51 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.52 +-15.29, -15.00, 52.76, 47.24, 5.53 +-15.29, -15.00, 52.76, 47.24, 5.53 +-15.29, -15.00, 52.77, 47.23, 5.53 +-15.29, -15.00, 52.77, 47.23, 5.53 +-15.29, -15.00, 52.77, 47.23, 5.53 +-15.29, -15.00, 52.77, 47.23, 5.54 +-15.29, -15.00, 52.77, 47.23, 5.54 +-15.29, -15.00, 52.77, 47.23, 5.54 +-15.29, -15.00, 52.77, 47.23, 5.54 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.77, 47.23, 5.55 +-15.29, -15.00, 52.78, 47.22, 5.55 +-15.42, -15.00, 57.82, 42.18, 15.64 +-15.29, -15.00, 47.83, 52.17, -4.33 +-15.29, -15.00, 52.78, 47.22, 5.56 +-15.29, -15.00, 52.78, 47.22, 5.56 +-15.29, -15.00, 52.78, 47.22, 5.56 +-15.29, -15.00, 52.78, 47.22, 5.56 +-15.29, -15.00, 52.78, 47.22, 5.57 +-15.29, -15.00, 52.78, 47.22, 5.57 +-15.29, -15.00, 52.79, 47.21, 5.57 +-15.29, -15.00, 52.79, 47.21, 5.57 +-15.29, -15.00, 52.79, 47.21, 5.58 +-15.29, -15.00, 52.79, 47.21, 5.58 +-15.23, -15.00, 50.27, 49.73, 0.54 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.48 +-15.23, -15.00, 52.74, 47.26, 5.49 +-15.23, -15.00, 52.74, 47.26, 5.49 +-15.23, -15.00, 52.74, 47.26, 5.49 +-15.23, -15.00, 52.75, 47.25, 5.49 +-15.23, -15.00, 52.75, 47.25, 5.49 +-15.16, -15.00, 50.23, 49.77, 0.45 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.16, -15.00, 52.70, 47.30, 5.40 +-15.03, -15.00, 47.66, 52.34, -4.68 +-15.03, -15.00, 52.60, 47.40, 5.21 +-15.03, -15.00, 52.60, 47.40, 5.21 +-14.96, -15.00, 50.08, 49.92, 0.16 +-14.96, -15.00, 52.55, 47.45, 5.11 +-14.96, -15.00, 52.55, 47.45, 5.11 +-14.96, -15.00, 52.55, 47.45, 5.11 +-14.96, -15.00, 52.55, 47.45, 5.11 +-14.90, -15.00, 50.03, 49.97, 0.06 +-14.90, -15.00, 52.50, 47.50, 5.01 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.90, -15.00, 52.50, 47.50, 5.00 +-14.77, -15.00, 47.46, 52.54, -5.09 +-14.77, -15.00, 52.40, 47.60, 4.80 +-14.77, -15.00, 52.40, 47.60, 4.80 +-14.70, -15.00, 49.88, 50.12, -0.25 +-14.70, -15.00, 52.35, 47.65, 4.70 +-14.70, -15.00, 52.35, 47.65, 4.69 +-14.70, -15.00, 52.35, 47.65, 4.69 +-14.70, -15.00, 52.34, 47.66, 4.69 +-14.70, -15.00, 52.34, 47.66, 4.69 +-14.63, -15.00, 49.82, 50.18, -0.36 +-14.63, -15.00, 52.29, 47.71, 4.58 +-14.63, -15.00, 52.29, 47.71, 4.58 +-14.63, -15.00, 52.29, 47.71, 4.58 +-14.63, -15.00, 52.29, 47.71, 4.57 +-14.63, -15.00, 52.29, 47.71, 4.57 +-14.50, -15.00, 47.24, 52.76, -5.52 +-14.50, -15.00, 52.18, 47.82, 4.37 +-14.50, -15.00, 52.18, 47.82, 4.36 +-14.50, -15.00, 52.18, 47.82, 4.36 +-14.50, -15.00, 52.18, 47.82, 4.35 +-14.44, -15.00, 49.65, 50.35, -0.69 +-14.44, -15.00, 52.12, 47.88, 4.25 +-14.44, -15.00, 52.12, 47.88, 4.24 +-14.44, -15.00, 52.12, 47.88, 4.24 +-14.44, -15.00, 52.12, 47.88, 4.23 +-14.44, -15.00, 52.12, 47.88, 4.23 +-14.44, -15.00, 52.11, 47.89, 4.23 +-14.44, -15.00, 52.11, 47.89, 4.22 +-14.44, -15.00, 52.11, 47.89, 4.22 +-14.44, -15.00, 52.11, 47.89, 4.21 +-14.44, -15.00, 52.10, 47.90, 4.21 +-14.44, -15.00, 52.10, 47.90, 4.20 +-14.44, -15.00, 52.10, 47.90, 4.20 +-14.44, -15.00, 52.10, 47.90, 4.20 +-14.44, -15.00, 52.10, 47.90, 4.19 +-14.37, -15.00, 49.57, 50.43, -0.86 +-14.37, -15.00, 52.04, 47.96, 4.08 +-14.37, -15.00, 52.04, 47.96, 4.08 +-14.37, -15.00, 52.04, 47.96, 4.07 +-14.37, -15.00, 52.03, 47.97, 4.07 +-14.37, -15.00, 52.03, 47.97, 4.06 +-14.37, -15.00, 52.03, 47.97, 4.06 +-14.37, -15.00, 52.03, 47.97, 4.06 +-14.37, -15.00, 52.03, 47.97, 4.05 +-14.37, -15.00, 52.02, 47.98, 4.05 +-14.37, -15.00, 52.02, 47.98, 4.04 +-14.37, -15.00, 52.02, 47.98, 4.04 +-14.37, -15.00, 52.02, 47.98, 4.03 +-14.37, -15.00, 52.01, 47.99, 4.03 +-14.37, -15.00, 52.01, 47.99, 4.02 +-14.37, -15.00, 52.01, 47.99, 4.02 +-14.37, -15.00, 52.01, 47.99, 4.01 +-14.37, -15.00, 52.00, 48.00, 4.01 +-14.37, -15.00, 52.00, 48.00, 4.00 +-14.37, -15.00, 52.00, 48.00, 4.00 +-14.24, -15.00, 46.95, 53.05, -6.09 +-14.24, -15.00, 51.89, 48.11, 3.79 +-14.24, -15.00, 51.89, 48.11, 3.78 +-14.24, -15.00, 51.89, 48.11, 3.78 +-14.24, -15.00, 51.89, 48.11, 3.77 +-14.24, -15.00, 51.88, 48.12, 3.77 +-14.24, -15.00, 51.88, 48.12, 3.76 +-14.24, -15.00, 51.88, 48.12, 3.76 +-14.24, -15.00, 51.87, 48.13, 3.75 +-14.24, -15.00, 51.87, 48.13, 3.74 +-14.24, -15.00, 51.87, 48.13, 3.74 +-14.24, -15.00, 51.87, 48.13, 3.73 +-14.24, -15.00, 51.86, 48.14, 3.73 +-14.24, -15.00, 51.86, 48.14, 3.72 +-14.24, -15.00, 51.86, 48.14, 3.72 +-14.24, -15.00, 51.85, 48.15, 3.71 +-14.24, -15.00, 51.85, 48.15, 3.70 +-14.24, -15.00, 51.85, 48.15, 3.70 +-14.24, -15.00, 51.85, 48.15, 3.69 +-14.24, -15.00, 51.84, 48.16, 3.69 +-14.24, -15.00, 51.84, 48.16, 3.68 +-14.24, -15.00, 51.84, 48.16, 3.68 +-14.24, -15.00, 51.83, 48.17, 3.67 +-14.24, -15.00, 51.83, 48.17, 3.66 +-14.24, -15.00, 51.83, 48.17, 3.66 +-14.24, -15.00, 51.83, 48.17, 3.65 +-14.24, -15.00, 51.82, 48.18, 3.65 +-14.24, -15.00, 51.82, 48.18, 3.64 +-14.24, -15.00, 51.82, 48.18, 3.64 +-14.24, -15.00, 51.81, 48.19, 3.63 +-14.24, -15.00, 51.81, 48.19, 3.62 +-14.24, -15.00, 51.81, 48.19, 3.62 +-14.24, -15.00, 51.81, 48.19, 3.61 +-14.24, -15.00, 51.80, 48.20, 3.61 +-14.24, -15.00, 51.80, 48.20, 3.60 +-14.24, -15.00, 51.80, 48.20, 3.60 +-14.24, -15.00, 51.79, 48.21, 3.59 +-14.37, -15.00, 56.84, 43.16, 13.67 +-14.37, -15.00, 51.89, 48.11, 3.78 +-14.37, -15.00, 51.89, 48.11, 3.77 +-14.37, -15.00, 51.88, 48.12, 3.77 +-14.37, -15.00, 51.88, 48.12, 3.76 +-14.37, -15.00, 51.88, 48.12, 3.76 +-14.37, -15.00, 51.88, 48.12, 3.75 +-14.37, -15.00, 51.87, 48.13, 3.75 +-14.37, -15.00, 51.87, 48.13, 3.74 +-14.44, -15.00, 54.39, 45.61, 8.78 +-14.44, -15.00, 51.92, 48.08, 3.84 +-14.44, -15.00, 51.92, 48.08, 3.83 +-14.44, -15.00, 51.91, 48.09, 3.83 +-14.44, -15.00, 51.91, 48.09, 3.82 +-14.50, -15.00, 54.43, 45.57, 8.86 +-14.50, -15.00, 51.96, 48.04, 3.91 +-14.50, -15.00, 51.96, 48.04, 3.91 +-14.50, -15.00, 51.95, 48.05, 3.91 +-14.50, -15.00, 51.95, 48.05, 3.90 +-14.50, -15.00, 51.95, 48.05, 3.90 +-14.50, -15.00, 51.95, 48.05, 3.90 +-14.63, -15.00, 56.99, 43.01, 13.98 +-14.63, -15.00, 52.04, 47.96, 4.09 +-14.63, -15.00, 52.04, 47.96, 4.08 +-14.70, -15.00, 54.56, 45.44, 9.13 +-14.70, -15.00, 52.09, 47.91, 4.18 +-14.70, -15.00, 52.09, 47.91, 4.18 +-14.70, -15.00, 52.09, 47.91, 4.17 +-14.77, -15.00, 54.61, 45.39, 9.22 +-14.77, -15.00, 52.13, 47.87, 4.27 +-14.77, -15.00, 52.13, 47.87, 4.27 +-14.77, -15.00, 52.13, 47.87, 4.27 +-14.77, -15.00, 52.13, 47.87, 4.26 +-14.77, -15.00, 52.13, 47.87, 4.26 +-14.90, -15.00, 57.17, 42.83, 14.35 +-14.90, -15.00, 52.23, 47.77, 4.46 +-14.90, -15.00, 52.23, 47.77, 4.46 +-14.90, -15.00, 52.23, 47.77, 4.46 +-14.90, -15.00, 52.23, 47.77, 4.46 +-14.96, -15.00, 54.75, 45.25, 9.50 +-14.96, -15.00, 52.28, 47.72, 4.56 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-15.03, -15.00, 54.80, 45.20, 9.60 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-15.03, -15.00, 52.33, 47.67, 4.65 +-14.96, -15.00, 49.81, 50.19, -0.39 +-15.03, -15.00, 54.80, 45.20, 9.60 +-15.03, -15.00, 52.33, 47.67, 4.65 +-14.96, -15.00, 49.81, 50.19, -0.39 +-15.03, -15.00, 54.80, 45.20, 9.60 +-14.96, -15.00, 49.81, 50.19, -0.39 +-14.96, -15.00, 52.28, 47.72, 4.56 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.96, -15.00, 52.28, 47.72, 4.55 +-14.90, -15.00, 49.75, 50.25, -0.49 +-14.90, -15.00, 52.23, 47.77, 4.45 +-14.90, -15.00, 52.23, 47.77, 4.45 +-14.90, -15.00, 52.23, 47.77, 4.45 +-14.90, -15.00, 52.23, 47.77, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.90, -15.00, 52.22, 47.78, 4.45 +-14.77, -15.00, 47.18, 52.82, -5.64 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.77, -15.00, 52.12, 47.88, 4.24 +-14.70, -15.00, 49.60, 50.40, -0.81 +-14.70, -15.00, 52.07, 47.93, 4.13 +-14.70, -15.00, 52.07, 47.93, 4.13 +-14.70, -15.00, 52.06, 47.94, 4.13 +-14.70, -15.00, 52.06, 47.94, 4.13 +-14.70, -15.00, 52.06, 47.94, 4.12 +-14.63, -15.00, 49.54, 50.46, -0.92 +-14.70, -15.00, 54.53, 45.47, 9.06 +-14.63, -15.00, 49.54, 50.46, -0.93 +-14.63, -15.00, 52.01, 47.99, 4.02 +-14.63, -15.00, 52.01, 47.99, 4.01 +-14.63, -15.00, 52.00, 48.00, 4.01 +-14.63, -15.00, 52.00, 48.00, 4.01 +-14.63, -15.00, 52.00, 48.00, 4.00 +-14.50, -15.00, 46.96, 53.04, -6.09 +-14.50, -15.00, 51.90, 48.10, 3.80 +-14.50, -15.00, 51.90, 48.10, 3.80 +-14.50, -15.00, 51.90, 48.10, 3.79 +-14.50, -15.00, 51.89, 48.11, 3.79 +-14.50, -15.00, 51.89, 48.11, 3.78 +-14.50, -15.00, 51.89, 48.11, 3.78 +-14.50, -15.00, 51.89, 48.11, 3.78 +-14.50, -15.00, 51.89, 48.11, 3.77 +-14.50, -15.00, 51.88, 48.12, 3.77 +-14.50, -15.00, 51.88, 48.12, 3.77 +-14.50, -15.00, 51.88, 48.12, 3.76 +-14.50, -15.00, 51.88, 48.12, 3.76 +-14.44, -15.00, 49.36, 50.64, -1.29 +-14.50, -15.00, 54.35, 45.65, 8.69 +-14.50, -15.00, 51.87, 48.13, 3.75 +-14.50, -15.00, 51.87, 48.13, 3.74 +-14.44, -15.00, 49.35, 50.65, -1.30 +-14.50, -15.00, 54.34, 45.66, 8.68 +-14.44, -15.00, 49.34, 50.66, -1.31 +-14.44, -15.00, 51.81, 48.19, 3.63 +-14.44, -15.00, 51.81, 48.19, 3.62 +-14.44, -15.00, 51.81, 48.19, 3.62 +-14.44, -15.00, 51.81, 48.19, 3.61 +-14.44, -15.00, 51.81, 48.19, 3.61 +-14.44, -15.00, 51.80, 48.20, 3.61 +-14.44, -15.00, 51.80, 48.20, 3.60 +-14.44, -15.00, 51.80, 48.20, 3.60 +-14.44, -15.00, 51.80, 48.20, 3.59 +-14.44, -15.00, 51.79, 48.21, 3.59 +-14.44, -15.00, 51.79, 48.21, 3.58 +-14.44, -15.00, 51.79, 48.21, 3.58 +-14.44, -15.00, 51.79, 48.21, 3.58 +-14.44, -15.00, 51.79, 48.21, 3.57 +-14.44, -15.00, 51.78, 48.22, 3.57 +-14.44, -15.00, 51.78, 48.22, 3.56 +-14.44, -15.00, 51.78, 48.22, 3.56 +-14.44, -15.00, 51.78, 48.22, 3.56 +-14.44, -15.00, 51.78, 48.22, 3.55 +-14.44, -15.00, 51.77, 48.23, 3.55 +-14.44, -15.00, 51.77, 48.23, 3.54 +-14.44, -15.00, 51.77, 48.23, 3.54 +-14.44, -15.00, 51.77, 48.23, 3.53 +-14.44, -15.00, 51.76, 48.24, 3.53 +-14.44, -15.00, 51.76, 48.24, 3.53 +-14.44, -15.00, 51.76, 48.24, 3.52 +-14.44, -15.00, 51.76, 48.24, 3.52 +-14.44, -15.00, 51.76, 48.24, 3.51 +-14.44, -15.00, 51.75, 48.25, 3.51 +-14.44, -15.00, 51.75, 48.25, 3.50 +-14.44, -15.00, 51.75, 48.25, 3.50 +-14.44, -15.00, 51.75, 48.25, 3.50 +-14.44, -15.00, 51.75, 48.25, 3.49 +-14.44, -15.00, 51.74, 48.26, 3.49 +-14.44, -15.00, 51.74, 48.26, 3.48 +-14.44, -15.00, 51.74, 48.26, 3.48 +-14.44, -15.00, 51.74, 48.26, 3.47 +-14.44, -15.00, 51.74, 48.26, 3.47 +-14.44, -15.00, 51.73, 48.27, 3.47 +-14.44, -15.00, 51.73, 48.27, 3.46 +-14.44, -15.00, 51.73, 48.27, 3.46 +-14.44, -15.00, 51.73, 48.27, 3.45 +-14.44, -15.00, 51.72, 48.28, 3.45 +-14.44, -15.00, 51.72, 48.28, 3.45 +-14.44, -15.00, 51.72, 48.28, 3.44 +-14.50, -15.00, 54.24, 45.76, 8.48 +-14.50, -15.00, 51.77, 48.23, 3.53 +-14.50, -15.00, 51.76, 48.24, 3.53 +-14.50, -15.00, 51.76, 48.24, 3.52 +-14.50, -15.00, 51.76, 48.24, 3.52 +-14.50, -15.00, 51.76, 48.24, 3.52 +-14.50, -15.00, 51.76, 48.24, 3.51 +-14.50, -15.00, 51.75, 48.25, 3.51 +-14.50, -15.00, 51.75, 48.25, 3.51 +-14.63, -15.00, 56.79, 43.21, 13.59 +-14.63, -15.00, 51.85, 48.15, 3.70 +-14.63, -15.00, 51.85, 48.15, 3.70 +-14.63, -15.00, 51.85, 48.15, 3.69 +-14.63, -15.00, 51.85, 48.15, 3.69 +-14.70, -15.00, 54.37, 45.63, 8.73 +-14.70, -15.00, 51.89, 48.11, 3.78 +-14.70, -15.00, 51.89, 48.11, 3.78 +-14.70, -15.00, 51.89, 48.11, 3.78 +-14.77, -15.00, 54.41, 45.59, 8.82 +-14.77, -15.00, 51.94, 48.06, 3.88 +-14.77, -15.00, 51.94, 48.06, 3.87 +-14.77, -15.00, 51.94, 48.06, 3.87 +-14.77, -15.00, 51.94, 48.06, 3.87 +-14.77, -15.00, 51.93, 48.07, 3.87 +-14.90, -15.00, 56.98, 43.02, 13.95 +-14.90, -15.00, 52.03, 47.97, 4.06 +-14.90, -15.00, 52.03, 47.97, 4.06 +-14.90, -15.00, 52.03, 47.97, 4.06 +-14.96, -15.00, 54.55, 45.45, 9.11 +-14.96, -15.00, 52.08, 47.92, 4.16 +-14.96, -15.00, 52.08, 47.92, 4.16 +-14.96, -15.00, 52.08, 47.92, 4.16 +-14.96, -15.00, 52.08, 47.92, 4.16 +-15.03, -15.00, 54.60, 45.40, 9.20 +-15.03, -15.00, 52.13, 47.87, 4.26 +-15.03, -15.00, 52.13, 47.87, 4.26 +-15.03, -15.00, 52.13, 47.87, 4.26 +-15.03, -15.00, 52.13, 47.87, 4.26 +-15.16, -15.00, 57.17, 42.83, 14.35 +-15.16, -15.00, 52.23, 47.77, 4.46 +-15.16, -15.00, 52.23, 47.77, 4.46 +-15.16, -15.00, 52.23, 47.77, 4.46 +-15.16, -15.00, 52.23, 47.77, 4.46 +-15.16, -15.00, 52.23, 47.77, 4.47 +-15.23, -15.00, 54.75, 45.25, 9.51 +-15.23, -15.00, 52.28, 47.72, 4.57 +-15.23, -15.00, 52.28, 47.72, 4.57 +-15.23, -15.00, 52.29, 47.71, 4.57 +-15.23, -15.00, 52.29, 47.71, 4.57 +-15.23, -15.00, 52.29, 47.71, 4.57 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.58 +-15.23, -15.00, 52.29, 47.71, 4.59 +-15.23, -15.00, 52.29, 47.71, 4.59 +-15.23, -15.00, 52.29, 47.71, 4.59 +-15.23, -15.00, 52.30, 47.70, 4.59 +-15.23, -15.00, 52.30, 47.70, 4.59 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.60 +-15.23, -15.00, 52.30, 47.70, 4.61 +-15.23, -15.00, 52.30, 47.70, 4.61 +-15.23, -15.00, 52.30, 47.70, 4.61 +-15.23, -15.00, 52.31, 47.69, 4.61 +-15.23, -15.00, 52.31, 47.69, 4.61 +-15.16, -15.00, 49.79, 50.21, -0.43 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.16, -15.00, 52.26, 47.74, 4.52 +-15.03, -15.00, 47.22, 52.78, -5.56 +-15.03, -15.00, 52.16, 47.84, 4.32 +-15.03, -15.00, 52.16, 47.84, 4.32 +-15.03, -15.00, 52.16, 47.84, 4.32 +-14.96, -15.00, 49.64, 50.36, -0.72 +-14.96, -15.00, 52.11, 47.89, 4.22 +-14.96, -15.00, 52.11, 47.89, 4.22 +-14.96, -15.00, 52.11, 47.89, 4.22 +-14.90, -15.00, 49.59, 50.41, -0.82 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.90, -15.00, 52.06, 47.94, 4.12 +-14.77, -15.00, 47.02, 52.98, -5.97 +-14.77, -15.00, 51.96, 48.04, 3.92 +-14.77, -15.00, 51.96, 48.04, 3.92 +-14.77, -15.00, 51.96, 48.04, 3.92 +-14.70, -15.00, 49.44, 50.56, -1.13 +-14.70, -15.00, 51.91, 48.09, 3.81 +-14.70, -15.00, 51.90, 48.10, 3.81 +-14.63, -15.00, 49.38, 50.62, -1.24 +-14.63, -15.00, 51.85, 48.15, 3.71 +-14.63, -15.00, 51.85, 48.15, 3.70 +-14.50, -15.00, 46.81, 53.19, -6.39 +-14.50, -15.00, 51.75, 48.25, 3.50 +-14.50, -15.00, 51.75, 48.25, 3.49 +-14.44, -15.00, 49.22, 50.78, -1.55 +-14.44, -15.00, 51.69, 48.31, 3.39 +-14.44, -15.00, 51.69, 48.31, 3.38 +-14.37, -15.00, 49.17, 50.83, -1.67 +-14.37, -15.00, 51.64, 48.36, 3.27 +-14.37, -15.00, 51.63, 48.37, 3.27 +-14.37, -15.00, 51.63, 48.37, 3.26 +-14.24, -15.00, 46.59, 53.41, -6.83 +-14.24, -15.00, 51.53, 48.47, 3.06 +-14.24, -15.00, 51.52, 48.48, 3.05 +-14.24, -15.00, 51.52, 48.48, 3.04 +-14.17, -15.00, 49.00, 51.00, -2.01 +-14.17, -15.00, 51.47, 48.53, 2.93 +-14.17, -15.00, 51.46, 48.54, 2.93 +-14.17, -15.00, 51.46, 48.54, 2.92 +-14.11, -15.00, 48.94, 51.06, -2.13 +-14.11, -15.00, 51.40, 48.60, 2.81 +-14.11, -15.00, 51.40, 48.60, 2.80 +-14.11, -15.00, 51.40, 48.60, 2.79 +-14.11, -15.00, 51.39, 48.61, 2.79 +-13.97, -15.00, 46.35, 53.65, -7.31 +-13.97, -15.00, 51.29, 48.71, 2.57 +-13.97, -15.00, 51.28, 48.72, 2.57 +-13.97, -15.00, 51.28, 48.72, 2.56 +-13.97, -15.00, 51.28, 48.72, 2.55 +-13.97, -15.00, 51.27, 48.73, 2.54 +-13.97, -15.00, 51.27, 48.73, 2.54 +-13.97, -15.00, 51.26, 48.74, 2.53 +-13.91, -15.00, 48.74, 51.26, -2.52 +-13.91, -15.00, 51.21, 48.79, 2.41 +-13.91, -15.00, 51.20, 48.80, 2.40 +-13.91, -15.00, 51.20, 48.80, 2.40 +-13.91, -15.00, 51.19, 48.81, 2.39 +-13.91, -15.00, 51.19, 48.81, 2.38 +-13.91, -15.00, 51.19, 48.81, 2.37 +-13.91, -15.00, 51.18, 48.82, 2.36 +-13.91, -15.00, 51.18, 48.82, 2.36 +-13.91, -15.00, 51.17, 48.83, 2.35 +-13.91, -15.00, 51.17, 48.83, 2.34 +-13.91, -15.00, 51.17, 48.83, 2.33 +-13.91, -15.00, 51.16, 48.84, 2.32 +-13.91, -15.00, 51.16, 48.84, 2.31 +-13.91, -15.00, 51.15, 48.85, 2.31 +-13.91, -15.00, 51.15, 48.85, 2.30 +-13.91, -15.00, 51.15, 48.85, 2.29 +-13.91, -15.00, 51.14, 48.86, 2.28 +-13.91, -15.00, 51.14, 48.86, 2.27 +-13.91, -15.00, 51.13, 48.87, 2.27 +-13.91, -15.00, 51.13, 48.87, 2.26 +-13.91, -15.00, 51.12, 48.88, 2.25 +-13.91, -15.00, 51.12, 48.88, 2.24 +-13.97, -15.00, 53.64, 46.36, 7.28 +-13.91, -15.00, 48.64, 51.36, -2.72 +-13.97, -15.00, 53.63, 46.37, 7.26 +-13.97, -15.00, 51.15, 48.85, 2.31 +-13.97, -15.00, 51.15, 48.85, 2.30 +-13.97, -15.00, 51.15, 48.85, 2.29 +-13.97, -15.00, 51.14, 48.86, 2.29 +-13.97, -15.00, 51.14, 48.86, 2.28 +-13.97, -15.00, 51.14, 48.86, 2.27 +-13.97, -15.00, 51.13, 48.87, 2.26 +-13.97, -15.00, 51.13, 48.87, 2.25 +-13.97, -15.00, 51.12, 48.88, 2.25 +-14.11, -15.00, 56.16, 43.84, 12.33 +-14.11, -15.00, 51.22, 48.78, 2.43 +-14.11, -15.00, 51.21, 48.79, 2.42 +-14.11, -15.00, 51.21, 48.79, 2.42 +-14.11, -15.00, 51.21, 48.79, 2.41 +-14.11, -15.00, 51.20, 48.80, 2.40 +-14.11, -15.00, 51.20, 48.80, 2.40 +-14.11, -15.00, 51.20, 48.80, 2.39 +-14.11, -15.00, 51.19, 48.81, 2.38 +-14.11, -15.00, 51.19, 48.81, 2.38 +-14.17, -15.00, 53.71, 46.29, 7.41 +-14.17, -15.00, 51.23, 48.77, 2.46 +-14.17, -15.00, 51.23, 48.77, 2.46 +-14.17, -15.00, 51.23, 48.77, 2.45 +-14.17, -15.00, 51.22, 48.78, 2.45 +-14.17, -15.00, 51.22, 48.78, 2.44 +-14.17, -15.00, 51.22, 48.78, 2.43 +-14.24, -15.00, 53.74, 46.26, 7.47 +-14.24, -15.00, 51.26, 48.74, 2.52 +-14.24, -15.00, 51.26, 48.74, 2.52 +-14.24, -15.00, 51.25, 48.75, 2.51 +-14.24, -15.00, 51.25, 48.75, 2.50 +-14.24, -15.00, 51.25, 48.75, 2.50 +-14.24, -15.00, 51.25, 48.75, 2.49 +-14.24, -15.00, 51.24, 48.76, 2.49 +-14.37, -15.00, 56.28, 43.72, 12.57 +-14.37, -15.00, 51.34, 48.66, 2.67 +-14.37, -15.00, 51.34, 48.66, 2.67 +-14.37, -15.00, 51.33, 48.67, 2.67 +-14.44, -15.00, 53.85, 46.15, 7.70 +-14.44, -15.00, 51.38, 48.62, 2.76 +-14.44, -15.00, 51.38, 48.62, 2.75 +-14.44, -15.00, 51.37, 48.63, 2.75 +-14.44, -15.00, 51.37, 48.63, 2.74 +-14.44, -15.00, 51.37, 48.63, 2.74 +-14.50, -15.00, 53.89, 46.11, 7.78 +-14.50, -15.00, 51.42, 48.58, 2.83 +-14.50, -15.00, 51.41, 48.59, 2.83 +-14.50, -15.00, 51.41, 48.59, 2.82 +-14.50, -15.00, 51.41, 48.59, 2.82 +-14.50, -15.00, 51.41, 48.59, 2.82 +-14.63, -15.00, 56.45, 43.55, 12.90 +-14.63, -15.00, 51.50, 48.50, 3.01 +-14.63, -15.00, 51.50, 48.50, 3.00 +-14.63, -15.00, 51.50, 48.50, 3.00 +-14.70, -15.00, 54.02, 45.98, 8.04 +-14.70, -15.00, 51.55, 48.45, 3.10 +-14.70, -15.00, 51.55, 48.45, 3.09 +-14.70, -15.00, 51.55, 48.45, 3.09 +-14.70, -15.00, 51.54, 48.46, 3.09 +-14.77, -15.00, 54.07, 45.93, 8.13 +-14.77, -15.00, 51.59, 48.41, 3.19 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.77, -15.00, 51.59, 48.41, 3.18 +-14.90, -15.00, 56.63, 43.37, 13.26 +-14.90, -15.00, 51.69, 48.31, 3.37 +-14.90, -15.00, 51.69, 48.31, 3.37 +-14.90, -15.00, 51.69, 48.31, 3.37 +-14.90, -15.00, 51.69, 48.31, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.90, -15.00, 51.68, 48.32, 3.37 +-14.96, -15.00, 54.20, 45.80, 8.41 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-15.03, -15.00, 54.25, 45.75, 8.50 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.56 +-15.03, -15.00, 51.78, 48.22, 3.57 +-15.03, -15.00, 51.78, 48.22, 3.57 +-15.03, -15.00, 51.78, 48.22, 3.57 +-14.96, -15.00, 49.26, 50.74, -1.48 +-14.96, -15.00, 51.73, 48.27, 3.47 +-14.96, -15.00, 51.73, 48.27, 3.47 +-14.96, -15.00, 51.73, 48.27, 3.47 +-14.96, -15.00, 51.73, 48.27, 3.47 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.96, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 49.21, 50.79, -1.58 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.36 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.68, 48.32, 3.35 +-14.90, -15.00, 51.67, 48.33, 3.35 +-14.77, -15.00, 46.63, 53.37, -6.74 +-14.90, -15.00, 56.62, 43.38, 13.23 +-14.77, -15.00, 46.63, 53.37, -6.74 +-14.77, -15.00, 51.57, 48.43, 3.15 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.14 +-14.77, -15.00, 51.57, 48.43, 3.13 +-14.90, -15.00, 56.61, 43.39, 13.22 +-14.77, -15.00, 46.62, 53.38, -6.76 +-14.77, -15.00, 51.57, 48.43, 3.13 +-14.77, -15.00, 51.56, 48.44, 3.13 +-14.77, -15.00, 51.56, 48.44, 3.13 +-14.77, -15.00, 51.56, 48.44, 3.13 +-14.90, -15.00, 56.61, 43.39, 13.21 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.32 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.66, 48.34, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.31 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.90, -15.00, 51.65, 48.35, 3.30 +-14.96, -15.00, 54.17, 45.83, 8.34 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.90, -15.00, 49.18, 50.82, -1.64 +-14.96, -15.00, 54.17, 45.83, 8.34 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.40 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.70, 48.30, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-14.96, -15.00, 51.69, 48.31, 3.39 +-15.03, -15.00, 54.22, 45.78, 8.43 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.74, 48.26, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.03, -15.00, 51.75, 48.25, 3.49 +-15.16, -15.00, 56.79, 43.21, 13.58 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.03, -15.00, 46.80, 53.20, -6.39 +-15.03, -15.00, 51.75, 48.25, 3.50 +-15.16, -15.00, 56.79, 43.21, 13.58 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.16, -15.00, 51.85, 48.15, 3.71 +-15.16, -15.00, 51.85, 48.15, 3.71 +-15.23, -15.00, 54.38, 45.62, 8.75 +-15.23, -15.00, 51.90, 48.10, 3.81 +-15.23, -15.00, 51.91, 48.09, 3.81 +-15.23, -15.00, 51.91, 48.09, 3.81 +-15.23, -15.00, 51.91, 48.09, 3.81 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.82 +-15.23, -15.00, 51.91, 48.09, 3.83 +-15.23, -15.00, 51.91, 48.09, 3.83 +-15.23, -15.00, 51.91, 48.09, 3.83 +-15.23, -15.00, 51.92, 48.08, 3.83 +-15.23, -15.00, 51.92, 48.08, 3.83 +-15.23, -15.00, 51.92, 48.08, 3.83 +-15.23, -15.00, 51.92, 48.08, 3.84 +-15.29, -15.00, 54.44, 45.56, 8.88 +-15.29, -15.00, 51.97, 48.03, 3.94 +-15.29, -15.00, 51.97, 48.03, 3.94 +-15.23, -15.00, 49.45, 50.55, -1.10 +-15.29, -15.00, 54.44, 45.56, 8.89 +-15.29, -15.00, 51.97, 48.03, 3.95 +-15.29, -15.00, 51.98, 48.02, 3.95 +-15.29, -15.00, 51.98, 48.02, 3.95 +-15.29, -15.00, 51.98, 48.02, 3.95 +-15.29, -15.00, 51.98, 48.02, 3.96 +-15.29, -15.00, 51.98, 48.02, 3.96 +-15.29, -15.00, 51.98, 48.02, 3.96 +-15.29, -15.00, 51.98, 48.02, 3.96 +-15.29, -15.00, 51.98, 48.02, 3.97 +-15.29, -15.00, 51.98, 48.02, 3.97 +-15.29, -15.00, 51.98, 48.02, 3.97 +-15.29, -15.00, 51.99, 48.01, 3.97 +-15.29, -15.00, 51.99, 48.01, 3.97 +-15.29, -15.00, 51.99, 48.01, 3.98 +-15.29, -15.00, 51.99, 48.01, 3.98 +-15.29, -15.00, 51.99, 48.01, 3.98 +-15.29, -15.00, 51.99, 48.01, 3.98 +-15.29, -15.00, 51.99, 48.01, 3.99 +-15.29, -15.00, 51.99, 48.01, 3.99 +-15.29, -15.00, 51.99, 48.01, 3.99 +-15.29, -15.00, 52.00, 48.00, 3.99 +-15.29, -15.00, 52.00, 48.00, 3.99 +-15.29, -15.00, 52.00, 48.00, 4.00 +-15.29, -15.00, 52.00, 48.00, 4.00 +-15.29, -15.00, 52.00, 48.00, 4.00 +-15.29, -15.00, 52.00, 48.00, 4.00 +-15.29, -15.00, 52.00, 48.00, 4.01 +-15.29, -15.00, 52.00, 48.00, 4.01 +-15.29, -15.00, 52.00, 48.00, 4.01 +-15.29, -15.00, 52.01, 47.99, 4.01 +-15.29, -15.00, 52.01, 47.99, 4.01 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.02 +-15.29, -15.00, 52.01, 47.99, 4.03 +-15.29, -15.00, 52.01, 47.99, 4.03 +-15.29, -15.00, 52.02, 47.98, 4.03 +-15.29, -15.00, 52.02, 47.98, 4.03 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.04 +-15.29, -15.00, 52.02, 47.98, 4.05 +-15.29, -15.00, 52.02, 47.98, 4.05 +-15.29, -15.00, 52.03, 47.97, 4.05 +-15.23, -15.00, 49.51, 50.49, -0.99 +-15.29, -15.00, 54.50, 45.50, 9.00 +-15.29, -15.00, 52.03, 47.97, 4.06 +-15.23, -15.00, 49.51, 50.49, -0.98 +-15.23, -15.00, 51.98, 48.02, 3.96 +-15.23, -15.00, 51.98, 48.02, 3.96 +-15.23, -15.00, 51.98, 48.02, 3.97 +-15.23, -15.00, 51.98, 48.02, 3.97 +-15.23, -15.00, 51.98, 48.02, 3.97 +-15.23, -15.00, 51.99, 48.01, 3.97 +-15.23, -15.00, 51.99, 48.01, 3.97 +-15.23, -15.00, 51.99, 48.01, 3.97 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.98 +-15.23, -15.00, 51.99, 48.01, 3.99 +-15.23, -15.00, 51.99, 48.01, 3.99 +-15.23, -15.00, 51.99, 48.01, 3.99 +-15.23, -15.00, 52.00, 48.00, 3.99 +-15.23, -15.00, 52.00, 48.00, 3.99 +-15.23, -15.00, 52.00, 48.00, 3.99 +-15.23, -15.00, 52.00, 48.00, 4.00 +-15.23, -15.00, 52.00, 48.00, 4.00 +-15.23, -15.00, 52.00, 48.00, 4.00 +-15.16, -15.00, 49.48, 50.52, -1.04 +-15.16, -15.00, 51.95, 48.05, 3.90 +-15.16, -15.00, 51.95, 48.05, 3.90 +-15.16, -15.00, 51.95, 48.05, 3.91 +-15.16, -15.00, 51.95, 48.05, 3.91 +-15.16, -15.00, 51.95, 48.05, 3.91 +-15.16, -15.00, 51.95, 48.05, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.91 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.92 +-15.16, -15.00, 51.96, 48.04, 3.93 +-15.16, -15.00, 51.96, 48.04, 3.93 +-15.16, -15.00, 51.96, 48.04, 3.93 +-15.16, -15.00, 51.96, 48.04, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.93 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.94 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.97, 48.03, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.95 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.96 +-15.16, -15.00, 51.98, 48.02, 3.97 +-15.16, -15.00, 51.98, 48.02, 3.97 +-15.16, -15.00, 51.98, 48.02, 3.97 +-15.16, -15.00, 51.98, 48.02, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.97 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.16, -15.00, 51.99, 48.01, 3.98 +-15.03, -15.00, 46.95, 53.05, -6.10 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-15.03, -15.00, 51.89, 48.11, 3.79 +-14.96, -15.00, 49.37, 50.63, -1.26 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.96, -15.00, 51.84, 48.16, 3.69 +-14.90, -15.00, 49.32, 50.68, -1.36 +-14.90, -15.00, 51.79, 48.21, 3.59 +-14.90, -15.00, 51.79, 48.21, 3.59 +-14.90, -15.00, 51.79, 48.21, 3.59 +-14.90, -15.00, 51.79, 48.21, 3.58 +-14.90, -15.00, 51.79, 48.21, 3.58 +-14.90, -15.00, 51.79, 48.21, 3.58 +-14.90, -15.00, 51.79, 48.21, 3.58 +-14.77, -15.00, 46.75, 53.25, -6.50 +-14.77, -15.00, 51.69, 48.31, 3.38 +-14.77, -15.00, 51.69, 48.31, 3.38 +-14.77, -15.00, 51.69, 48.31, 3.38 +-14.77, -15.00, 51.69, 48.31, 3.38 +-14.77, -15.00, 51.69, 48.31, 3.37 +-14.70, -15.00, 49.16, 50.84, -1.67 +-14.70, -15.00, 51.64, 48.36, 3.27 +-14.70, -15.00, 51.63, 48.37, 3.27 +-14.70, -15.00, 51.63, 48.37, 3.27 +-14.70, -15.00, 51.63, 48.37, 3.26 +-14.70, -15.00, 51.63, 48.37, 3.26 +-14.70, -15.00, 51.63, 48.37, 3.26 +-14.63, -15.00, 49.11, 50.89, -1.79 +-14.63, -15.00, 51.58, 48.42, 3.15 +-14.63, -15.00, 51.58, 48.42, 3.15 +-14.63, -15.00, 51.57, 48.43, 3.15 +-14.63, -15.00, 51.57, 48.43, 3.15 +-14.63, -15.00, 51.57, 48.43, 3.14 +-14.63, -15.00, 51.57, 48.43, 3.14 +-14.63, -15.00, 51.57, 48.43, 3.14 +-14.63, -15.00, 51.57, 48.43, 3.14 +-14.50, -15.00, 46.52, 53.48, -6.95 +-14.50, -15.00, 51.47, 48.53, 2.93 +-14.63, -15.00, 56.51, 43.49, 13.01 +-14.63, -15.00, 51.56, 48.44, 3.12 +-14.63, -15.00, 51.56, 48.44, 3.12 +-14.63, -15.00, 51.56, 48.44, 3.12 +-14.50, -15.00, 46.51, 53.49, -6.97 +-14.63, -15.00, 56.50, 43.50, 13.00 +-14.63, -15.00, 51.55, 48.45, 3.11 +-14.63, -15.00, 51.55, 48.45, 3.11 +-14.63, -15.00, 51.55, 48.45, 3.10 +-14.63, -15.00, 51.55, 48.45, 3.10 +-14.63, -15.00, 51.55, 48.45, 3.10 +-14.63, -15.00, 51.55, 48.45, 3.09 +-14.63, -15.00, 51.55, 48.45, 3.09 +-14.63, -15.00, 51.54, 48.46, 3.09 +-14.70, -15.00, 54.06, 45.94, 8.13 +-14.70, -15.00, 51.59, 48.41, 3.18 +-14.70, -15.00, 51.59, 48.41, 3.18 +-14.70, -15.00, 51.59, 48.41, 3.18 +-14.70, -15.00, 51.59, 48.41, 3.18 +-14.70, -15.00, 51.59, 48.41, 3.17 +-14.77, -15.00, 54.11, 45.89, 8.22 +-14.77, -15.00, 51.63, 48.37, 3.27 +-14.77, -15.00, 51.63, 48.37, 3.27 +-14.77, -15.00, 51.63, 48.37, 3.27 +-14.77, -15.00, 51.63, 48.37, 3.26 +-14.77, -15.00, 51.63, 48.37, 3.26 +-14.90, -15.00, 56.67, 43.33, 13.35 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.46 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.96, -15.00, 54.25, 45.75, 8.50 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.77, 48.23, 3.55 +-14.96, -15.00, 51.77, 48.23, 3.55 +-15.03, -15.00, 54.30, 45.70, 8.59 +-14.96, -15.00, 49.30, 50.70, -1.39 +-15.03, -15.00, 54.30, 45.70, 8.59 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.82, 48.18, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.65 +-15.03, -15.00, 51.83, 48.17, 3.66 +-15.03, -15.00, 51.83, 48.17, 3.66 +-15.03, -15.00, 51.83, 48.17, 3.66 +-14.96, -15.00, 49.31, 50.69, -1.39 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.56 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.96, -15.00, 51.78, 48.22, 3.55 +-14.90, -15.00, 49.26, 50.74, -1.49 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.73, 48.27, 3.45 +-14.90, -15.00, 51.72, 48.28, 3.45 +-14.90, -15.00, 51.72, 48.28, 3.45 +-14.77, -15.00, 46.68, 53.32, -6.64 +-14.77, -15.00, 51.62, 48.38, 3.25 +-14.77, -15.00, 51.62, 48.38, 3.25 +-14.77, -15.00, 51.62, 48.38, 3.24 +-14.77, -15.00, 51.62, 48.38, 3.24 +-14.77, -15.00, 51.62, 48.38, 3.24 +-14.70, -15.00, 49.10, 50.90, -1.80 +-14.70, -15.00, 51.57, 48.43, 3.14 +-14.70, -15.00, 51.57, 48.43, 3.14 +-14.70, -15.00, 51.57, 48.43, 3.13 +-14.70, -15.00, 51.57, 48.43, 3.13 +-14.70, -15.00, 51.56, 48.44, 3.13 +-14.70, -15.00, 51.56, 48.44, 3.13 +-14.63, -15.00, 49.04, 50.96, -1.92 +-14.63, -15.00, 51.51, 48.49, 3.02 +-14.63, -15.00, 51.51, 48.49, 3.02 +-14.63, -15.00, 51.51, 48.49, 3.02 +-14.63, -15.00, 51.51, 48.49, 3.01 +-14.63, -15.00, 51.51, 48.49, 3.01 +-14.63, -15.00, 51.50, 48.50, 3.01 +-14.63, -15.00, 51.50, 48.50, 3.01 +-14.63, -15.00, 51.50, 48.50, 3.00 +-14.50, -15.00, 46.46, 53.54, -7.09 +-14.50, -15.00, 51.40, 48.60, 2.80 +-14.50, -15.00, 51.40, 48.60, 2.79 +-14.50, -15.00, 51.39, 48.61, 2.79 +-14.50, -15.00, 51.39, 48.61, 2.79 +-14.50, -15.00, 51.39, 48.61, 2.78 +-14.50, -15.00, 51.39, 48.61, 2.78 +-14.50, -15.00, 51.39, 48.61, 2.78 +-14.50, -15.00, 51.39, 48.61, 2.77 +-14.50, -15.00, 51.38, 48.62, 2.77 +-14.50, -15.00, 51.38, 48.62, 2.76 +-14.50, -15.00, 51.38, 48.62, 2.76 +-14.50, -15.00, 51.38, 48.62, 2.76 +-14.50, -15.00, 51.38, 48.62, 2.75 +-14.50, -15.00, 51.37, 48.63, 2.75 +-14.50, -15.00, 51.37, 48.63, 2.75 +-14.50, -15.00, 51.37, 48.63, 2.74 +-14.50, -15.00, 51.37, 48.63, 2.74 +-14.50, -15.00, 51.37, 48.63, 2.73 +-14.50, -15.00, 51.37, 48.63, 2.73 +-14.50, -15.00, 51.36, 48.64, 2.73 +-14.50, -15.00, 51.36, 48.64, 2.72 +-14.50, -15.00, 51.36, 48.64, 2.72 +-14.50, -15.00, 51.36, 48.64, 2.72 +-14.50, -15.00, 51.36, 48.64, 2.71 +-14.50, -15.00, 51.35, 48.65, 2.71 +-14.50, -15.00, 51.35, 48.65, 2.70 +-14.50, -15.00, 51.35, 48.65, 2.70 +-14.63, -15.00, 56.39, 43.61, 12.78 +-14.63, -15.00, 51.45, 48.55, 2.89 +-14.63, -15.00, 51.44, 48.56, 2.89 +-14.63, -15.00, 51.44, 48.56, 2.89 +-14.63, -15.00, 51.44, 48.56, 2.88 +-14.63, -15.00, 51.44, 48.56, 2.88 +-14.63, -15.00, 51.44, 48.56, 2.88 +-14.63, -15.00, 51.44, 48.56, 2.88 +-14.63, -15.00, 51.44, 48.56, 2.87 +-14.70, -15.00, 53.96, 46.04, 7.91 +-14.70, -15.00, 51.48, 48.52, 2.97 +-14.70, -15.00, 51.48, 48.52, 2.97 +-14.70, -15.00, 51.48, 48.52, 2.96 +-14.70, -15.00, 51.48, 48.52, 2.96 +-14.70, -15.00, 51.48, 48.52, 2.96 +-14.70, -15.00, 51.48, 48.52, 2.96 +-14.70, -15.00, 51.48, 48.52, 2.95 +-14.70, -15.00, 51.48, 48.52, 2.95 +-14.77, -15.00, 54.00, 46.00, 7.99 +-14.77, -15.00, 51.52, 48.48, 3.05 +-14.77, -15.00, 51.52, 48.48, 3.05 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.04 +-14.77, -15.00, 51.52, 48.48, 3.03 +-14.90, -15.00, 56.56, 43.44, 13.12 +-14.77, -15.00, 46.57, 53.43, -6.86 +-14.90, -15.00, 56.56, 43.44, 13.12 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.23 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.90, -15.00, 51.61, 48.39, 3.22 +-14.96, -15.00, 54.13, 45.87, 8.26 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-14.96, -15.00, 51.66, 48.34, 3.32 +-15.03, -15.00, 54.18, 45.82, 8.36 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.03, -15.00, 51.71, 48.29, 3.42 +-15.16, -15.00, 56.75, 43.25, 13.50 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.62 +-15.16, -15.00, 51.81, 48.19, 3.63 +-15.16, -15.00, 51.81, 48.19, 3.63 +-15.16, -15.00, 51.81, 48.19, 3.63 +-15.16, -15.00, 51.81, 48.19, 3.63 +-15.16, -15.00, 51.82, 48.18, 3.63 +-15.23, -15.00, 54.34, 45.66, 8.67 +-15.23, -15.00, 51.87, 48.13, 3.73 +-15.23, -15.00, 51.87, 48.13, 3.73 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.74 +-15.23, -15.00, 51.87, 48.13, 3.75 +-15.23, -15.00, 51.87, 48.13, 3.75 +-15.23, -15.00, 51.87, 48.13, 3.75 +-15.16, -15.00, 49.35, 50.65, -1.29 +-15.16, -15.00, 51.83, 48.17, 3.65 +-15.16, -15.00, 51.83, 48.17, 3.65 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.66 +-15.16, -15.00, 51.83, 48.17, 3.67 +-15.16, -15.00, 51.83, 48.17, 3.67 +-15.16, -15.00, 51.83, 48.17, 3.67 +-15.16, -15.00, 51.83, 48.17, 3.67 +-15.16, -15.00, 51.84, 48.16, 3.67 +-15.16, -15.00, 51.84, 48.16, 3.67 +-15.16, -15.00, 51.84, 48.16, 3.67 +-15.16, -15.00, 51.84, 48.16, 3.67 +-15.03, -15.00, 46.79, 53.21, -6.41 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.03, -15.00, 51.74, 48.26, 3.48 +-15.16, -15.00, 56.78, 43.22, 13.57 +-15.16, -15.00, 51.84, 48.16, 3.68 +-15.16, -15.00, 51.84, 48.16, 3.68 +-15.16, -15.00, 51.84, 48.16, 3.68 +-15.16, -15.00, 51.84, 48.16, 3.68 +-15.16, -15.00, 51.84, 48.16, 3.69 +-15.16, -15.00, 51.84, 48.16, 3.69 +-15.16, -15.00, 51.84, 48.16, 3.69 +-15.16, -15.00, 51.84, 48.16, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.69 +-15.16, -15.00, 51.85, 48.15, 3.70 +-15.23, -15.00, 54.37, 45.63, 8.74 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.80 +-15.23, -15.00, 51.90, 48.10, 3.81 +-15.23, -15.00, 51.90, 48.10, 3.81 +-15.16, -15.00, 49.38, 50.62, -1.23 +-15.23, 0.00, 75.00, 25.00, 50.00 +-15.23, 0.00, 63.27, 36.73, 26.54 +-15.23, 0.00, 63.33, 36.67, 26.65 +-15.16, 0.00, 60.86, 39.14, 21.72 +-15.16, 0.00, 63.39, 36.61, 26.78 +-15.16, 0.00, 63.45, 36.55, 26.89 +-15.16, 0.00, 63.50, 36.50, 27.01 +-15.16, 0.00, 63.56, 36.44, 27.12 +-15.16, 0.00, 63.62, 36.38, 27.24 +-15.03, 0.00, 58.63, 41.37, 17.26 +-15.03, 0.00, 63.63, 36.37, 27.26 +-15.03, 0.00, 63.69, 36.31, 27.38 +-14.96, 0.00, 61.22, 38.78, 22.45 +-14.90, 0.00, 61.23, 38.77, 22.46 +-14.90, 0.00, 63.76, 36.24, 27.51 +-14.90, 0.00, 63.81, 36.19, 27.63 +-14.77, 0.00, 58.83, 41.17, 17.65 +-14.70, 0.00, 61.30, 38.70, 22.61 +-14.63, 0.00, 61.31, 38.69, 22.62 +-14.50, 0.00, 58.79, 41.21, 17.58 +-14.44, 0.00, 61.27, 38.73, 22.54 +-14.37, 0.00, 61.27, 38.73, 22.55 +-14.24, 0.00, 58.76, 41.24, 17.51 +-14.17, 0.00, 61.23, 38.77, 22.46 +-14.11, 0.00, 61.23, 38.77, 22.47 +-13.91, 0.00, 56.19, 43.81, 12.39 +-13.84, 0.00, 61.14, 38.86, 22.28 +-13.65, 0.00, 56.10, 43.90, 12.20 +-13.58, 0.00, 61.05, 38.95, 22.09 +-13.38, 0.00, 56.00, 44.00, 12.01 +-13.18, 0.00, 55.90, 44.10, 11.81 +-13.05, 0.00, 58.33, 41.67, 16.65 +-12.92, 0.00, 58.28, 41.72, 16.55 +-12.79, 0.00, 58.23, 41.77, 16.45 +-12.59, 0.00, 55.65, 44.35, 11.30 +-12.39, 0.00, 55.55, 44.45, 11.10 +-12.26, 0.00, 57.97, 42.03, 15.94 +-12.06, 0.00, 55.39, 44.61, 10.79 +-11.87, 0.00, 55.29, 44.71, 10.58 +-11.73, 0.00, 57.71, 42.29, 15.42 +-11.47, 0.00, 52.61, 47.39, 5.22 +-11.27, 0.00, 54.97, 45.03, 9.95 +-11.01, 0.00, 52.35, 47.65, 4.69 +-10.81, 0.00, 54.71, 45.29, 9.42 +-10.68, 0.00, 57.12, 42.88, 14.25 +-10.42, 0.00, 52.02, 47.98, 4.04 +-10.22, 0.00, 54.38, 45.62, 8.77 +-9.95, 0.00, 51.75, 48.25, 3.50 +-9.76, 0.00, 54.11, 45.89, 8.22 +-9.49, 0.00, 51.48, 48.52, 2.95 +-9.23, 0.00, 51.31, 48.69, 2.63 +-9.10, 0.00, 56.19, 43.81, 12.39 +-8.83, 0.00, 51.08, 48.92, 2.17 +-8.64, 0.00, 53.44, 46.56, 6.88 +-8.37, 0.00, 50.80, 49.20, 1.60 +-8.17, 0.00, 53.16, 46.84, 6.31 +-7.91, 0.00, 50.52, 49.48, 1.03 +-7.65, 0.00, 50.35, 49.65, 0.69 +-7.38, 0.00, 50.18, 49.82, 0.35 +-7.25, 0.00, 55.05, 44.95, 10.10 +-6.99, 0.00, 49.93, 50.07, -0.13 +-6.72, 0.00, 49.76, 50.24, -0.48 +-6.53, 0.00, 52.11, 47.89, 4.22 +-6.26, 0.00, 49.46, 50.54, -1.07 +-6.00, 0.00, 49.29, 50.71, -1.42 +-5.80, 0.00, 51.63, 48.37, 3.27 +-5.54, 0.00, 48.98, 51.02, -2.03 +-5.27, 0.00, 48.81, 51.19, -2.39 +-5.01, 0.00, 48.63, 51.37, -2.74 +-4.88, 0.00, 53.49, 46.51, 6.98 +-4.61, 0.00, 48.37, 51.63, -3.27 +-4.35, 0.00, 48.19, 51.81, -3.63 +-4.15, 0.00, 50.52, 49.48, 1.05 +-3.89, 0.00, 47.87, 52.13, -4.26 +-3.63, 0.00, 47.68, 52.32, -4.63 +-3.43, 0.00, 50.02, 49.98, 0.04 +-3.16, 0.00, 47.36, 52.64, -5.27 +-3.03, 0.00, 52.22, 47.78, 4.44 +-2.77, 0.00, 47.09, 52.91, -5.82 +-2.50, 0.00, 46.90, 53.10, -6.20 +-2.31, 0.00, 49.23, 50.77, -1.53 +-2.04, 0.00, 46.57, 53.43, -6.86 +-1.85, 0.00, 48.90, 51.10, -2.20 +-1.58, 0.00, 46.24, 53.76, -7.53 +-1.45, 0.00, 51.09, 48.91, 2.18 +-1.25, 0.00, 48.47, 51.53, -3.06 +-0.99, 0.00, 45.81, 54.19, -8.39 +-0.79, 0.00, 48.13, 51.87, -3.73 +-0.66, 0.00, 50.51, 49.49, 1.02 +-0.40, 0.00, 45.37, 54.63, -9.26 +-0.20, 0.00, 47.69, 52.31, -4.61 +0.00, 0.00, 47.54, 52.46, -4.91 +0.13, 0.00, 49.92, 50.08, -0.17 +0.40, 0.00, 44.77, 55.23, -10.45 +0.59, 0.00, 47.10, 52.90, -5.81 +0.79, 0.00, 46.94, 53.06, -6.11 +0.92, 0.00, 49.31, 50.69, -1.37 +1.12, 0.00, 46.69, 53.31, -6.62 +1.32, 0.00, 46.54, 53.46, -6.93 +1.45, 0.00, 48.90, 51.10, -2.19 +1.65, 0.00, 46.28, 53.72, -7.45 +1.85, 0.00, 46.12, 53.88, -7.76 +1.91, 0.00, 51.01, 48.99, 2.02 +2.11, 0.00, 45.91, 54.09, -8.18 +2.24, 0.00, 48.27, 51.73, -3.45 +2.44, 0.00, 45.64, 54.36, -8.71 +2.50, 0.00, 50.53, 49.47, 1.06 +2.64, 0.00, 47.95, 52.05, -4.10 +2.77, 0.00, 47.84, 52.16, -4.32 +2.97, 0.00, 45.21, 54.79, -9.58 +3.03, 0.00, 50.09, 49.91, 0.18 +3.23, 0.00, 44.99, 55.01, -10.03 +3.30, 0.00, 49.87, 50.13, -0.26 +3.43, 0.00, 47.29, 52.71, -5.43 +3.56, 0.00, 47.17, 52.83, -5.65 +3.69, 0.00, 47.06, 52.94, -5.88 +3.76, 0.00, 49.47, 50.53, -1.06 +3.96, 0.00, 44.36, 55.64, -11.28 +4.02, 0.00, 49.24, 50.76, -1.52 +4.09, 0.00, 49.18, 50.82, -1.65 +4.22, 0.00, 46.59, 53.41, -6.82 +4.28, 0.00, 49.00, 51.00, -2.01 +4.35, 0.00, 48.93, 51.07, -2.14 +4.48, 0.00, 46.34, 53.66, -7.32 +4.55, 0.00, 48.75, 51.25, -2.50 +4.61, 0.00, 48.68, 51.32, -2.64 +4.75, 0.00, 46.09, 53.91, -7.81 +4.75, 0.00, 51.02, 48.98, 2.04 +4.81, 0.00, 48.48, 51.52, -3.04 +4.88, 0.00, 48.41, 51.59, -3.18 +5.01, 0.00, 45.82, 54.18, -8.36 +5.01, 0.00, 50.75, 49.25, 1.49 +5.08, 0.00, 48.21, 51.79, -3.59 +5.08, 0.00, 50.66, 49.34, 1.32 +5.14, 0.00, 48.12, 51.88, -3.76 +5.14, 0.00, 50.57, 49.43, 1.14 +5.14, 0.00, 50.55, 49.45, 1.10 +5.27, 0.00, 45.49, 54.51, -9.02 +5.27, 0.00, 50.41, 49.59, 0.83 +5.27, 0.00, 50.39, 49.61, 0.79 +5.34, 0.00, 47.85, 52.15, -4.29 +5.34, 0.00, 50.30, 49.70, 0.61 +5.34, 0.00, 50.28, 49.72, 0.57 +5.34, 0.00, 50.26, 49.74, 0.53 +5.34, 0.00, 50.24, 49.76, 0.49 +5.34, 0.00, 50.22, 49.78, 0.45 +5.34, 0.00, 50.20, 49.80, 0.41 +5.34, 0.00, 50.18, 49.82, 0.37 +5.27, 0.00, 52.69, 47.31, 5.37 +5.27, 0.00, 50.19, 49.81, 0.39 +5.27, 0.00, 50.17, 49.83, 0.35 +5.27, 0.00, 50.15, 49.85, 0.31 +5.27, 0.00, 50.13, 49.87, 0.27 +5.27, 0.00, 50.12, 49.88, 0.23 +5.27, 0.00, 50.10, 49.90, 0.19 +5.14, 0.00, 55.12, 44.88, 10.24 +5.14, 0.00, 50.16, 49.84, 0.31 +5.14, 0.00, 50.14, 49.86, 0.27 +5.08, 0.00, 52.64, 47.36, 5.28 +5.08, 0.00, 50.15, 49.85, 0.30 +5.08, 0.00, 50.13, 49.87, 0.26 +5.08, 0.00, 50.11, 49.89, 0.22 +5.01, 0.00, 52.61, 47.39, 5.22 +5.01, 0.00, 50.12, 49.88, 0.24 +4.88, 0.00, 55.15, 44.85, 10.29 +4.88, 0.00, 50.18, 49.82, 0.37 +4.81, 0.00, 52.69, 47.31, 5.37 +4.81, 0.00, 50.20, 49.80, 0.39 +4.75, 0.00, 52.70, 47.30, 5.40 +4.75, 0.00, 50.21, 49.79, 0.42 +4.75, 0.00, 50.19, 49.81, 0.39 +4.61, 0.00, 55.22, 44.78, 10.44 +4.61, 0.00, 50.26, 49.74, 0.52 +4.55, 0.00, 52.76, 47.24, 5.52 +4.55, 0.00, 50.27, 49.73, 0.55 +4.48, 0.00, 52.78, 47.22, 5.55 +4.48, 0.00, 50.29, 49.71, 0.58 +4.48, 0.00, 50.27, 49.73, 0.54 +4.35, 0.00, 55.30, 44.70, 10.60 +4.28, 0.00, 52.86, 47.14, 5.72 +4.28, 0.00, 50.37, 49.63, 0.74 +4.22, 0.00, 52.88, 47.12, 5.75 +4.22, 0.00, 50.39, 49.61, 0.78 +4.09, 0.00, 55.42, 44.58, 10.83 +4.09, 0.00, 50.46, 49.54, 0.92 +4.02, 0.00, 52.96, 47.04, 5.93 +3.96, 0.00, 53.00, 47.00, 6.00 +3.96, 0.00, 50.51, 49.49, 1.02 +3.82, 0.00, 55.54, 44.46, 11.08 +3.82, 0.00, 50.58, 49.42, 1.16 +3.76, 0.00, 53.09, 46.91, 6.18 +3.76, 0.00, 50.60, 49.40, 1.21 +3.69, 0.00, 53.11, 46.89, 6.22 +3.69, 0.00, 50.63, 49.37, 1.25 +3.69, 0.00, 50.61, 49.39, 1.22 +3.69, 0.00, 50.60, 49.40, 1.19 +3.56, 0.00, 55.63, 44.37, 11.25 +3.56, 0.00, 50.67, 49.33, 1.34 +3.49, 0.00, 53.18, 46.82, 6.36 +3.49, 0.00, 50.69, 49.31, 1.39 +3.43, 0.00, 53.20, 46.80, 6.40 +3.43, 0.00, 50.72, 49.28, 1.43 +3.30, 0.00, 55.75, 44.25, 11.49 +3.30, 0.00, 50.79, 49.21, 1.58 +3.23, 0.00, 53.30, 46.70, 6.60 +3.23, 0.00, 50.82, 49.18, 1.63 +3.23, 0.00, 50.80, 49.20, 1.61 +3.16, 0.00, 53.31, 46.69, 6.63 +3.16, 0.00, 50.83, 49.17, 1.66 +3.03, 0.00, 55.86, 44.14, 11.72 +3.03, 0.00, 50.91, 49.09, 1.81 +3.03, 0.00, 50.89, 49.11, 1.79 +3.03, 0.00, 50.88, 49.12, 1.77 +3.03, 0.00, 50.87, 49.13, 1.74 +2.97, 0.00, 53.38, 46.62, 6.76 +2.97, 0.00, 50.90, 49.10, 1.80 +2.97, 0.00, 50.89, 49.11, 1.78 +2.90, 0.00, 53.40, 46.60, 6.80 +2.90, 0.00, 50.92, 49.08, 1.83 +2.77, 0.00, 55.95, 44.05, 11.90 +2.77, 0.00, 50.99, 49.01, 1.99 +2.77, 0.00, 50.98, 49.02, 1.97 +2.70, 0.00, 53.49, 46.51, 6.99 +2.70, 0.00, 51.01, 48.99, 2.02 +2.64, 0.00, 53.52, 46.48, 7.05 +2.64, 0.00, 51.04, 48.96, 2.08 +2.64, 0.00, 51.03, 48.97, 2.06 +2.50, 0.00, 56.07, 43.93, 12.13 +2.50, 0.00, 51.11, 48.89, 2.22 +2.50, 0.00, 51.10, 48.90, 2.21 +2.50, 0.00, 51.09, 48.91, 2.19 +2.50, 0.00, 51.08, 48.92, 2.17 +2.50, 0.00, 51.07, 48.93, 2.15 +2.44, 0.00, 53.59, 46.41, 7.17 +2.44, 0.00, 51.11, 48.89, 2.21 +2.44, 0.00, 51.10, 48.90, 2.19 +2.44, 0.00, 51.09, 48.91, 2.17 +2.44, 0.00, 51.08, 48.92, 2.16 +2.44, 0.00, 51.07, 48.93, 2.14 +2.37, 0.00, 53.58, 46.42, 7.16 +2.37, 0.00, 51.10, 48.90, 2.20 +2.37, 0.00, 51.09, 48.91, 2.18 +2.37, 0.00, 51.08, 48.92, 2.17 +2.37, 0.00, 51.07, 48.93, 2.15 +2.24, 0.00, 56.11, 43.89, 12.22 +2.24, 0.00, 51.16, 48.84, 2.31 +2.24, 0.00, 51.15, 48.85, 2.30 +2.24, 0.00, 51.14, 48.86, 2.28 +2.24, 0.00, 51.13, 48.87, 2.26 +2.24, 0.00, 51.12, 48.88, 2.24 +2.24, 0.00, 51.11, 48.89, 2.23 +2.24, 0.00, 51.11, 48.89, 2.21 +2.18, 0.00, 53.62, 46.38, 7.24 +2.24, 0.00, 48.62, 51.38, -2.77 +2.18, 0.00, 53.60, 46.40, 7.20 +2.18, 0.00, 51.12, 48.88, 2.24 +2.18, 0.00, 51.11, 48.89, 2.23 +2.18, 0.00, 51.11, 48.89, 2.21 +2.18, 0.00, 51.10, 48.90, 2.20 +2.11, 0.00, 53.61, 46.39, 7.22 +2.11, 0.00, 51.13, 48.87, 2.26 +2.11, 0.00, 51.12, 48.88, 2.25 +2.11, 0.00, 51.12, 48.88, 2.23 +2.11, 0.00, 51.11, 48.89, 2.22 +2.11, 0.00, 51.10, 48.90, 2.20 +2.11, 0.00, 51.09, 48.91, 2.18 +2.11, 0.00, 51.08, 48.92, 2.17 +1.98, 0.00, 56.12, 43.88, 12.24 +1.98, 0.00, 51.17, 48.83, 2.34 +1.98, 0.00, 51.16, 48.84, 2.32 +1.98, 0.00, 51.15, 48.85, 2.31 +1.98, 0.00, 51.15, 48.85, 2.29 +1.98, 0.00, 51.14, 48.86, 2.28 +1.98, 0.00, 51.13, 48.87, 2.26 +1.91, 0.00, 53.65, 46.35, 7.29 +1.91, 0.00, 51.17, 48.83, 2.33 +1.91, 0.00, 51.16, 48.84, 2.32 +1.91, 0.00, 51.15, 48.85, 2.30 +1.91, 0.00, 51.14, 48.86, 2.29 +1.91, 0.00, 51.14, 48.86, 2.27 +1.91, 0.00, 51.13, 48.87, 2.26 +1.91, 0.00, 51.12, 48.88, 2.25 +1.91, 0.00, 51.12, 48.88, 2.23 +1.91, 0.00, 51.11, 48.89, 2.22 +1.91, 0.00, 51.10, 48.90, 2.20 +1.91, 0.00, 51.09, 48.91, 2.19 +1.91, 0.00, 51.09, 48.91, 2.17 +1.91, 0.00, 51.08, 48.92, 2.16 +1.91, 0.00, 51.07, 48.93, 2.15 +1.91, 0.00, 51.07, 48.93, 2.13 +1.91, 0.00, 51.06, 48.94, 2.12 +1.91, 0.00, 51.05, 48.95, 2.10 +1.91, 0.00, 51.04, 48.96, 2.09 +1.91, 0.00, 51.04, 48.96, 2.07 +1.91, 0.00, 51.03, 48.97, 2.06 +1.91, 0.00, 51.02, 48.98, 2.05 +1.91, 0.00, 51.02, 48.98, 2.03 +1.85, 0.00, 53.53, 46.47, 7.06 +1.85, 0.00, 51.05, 48.95, 2.10 +1.85, 0.00, 51.04, 48.96, 2.09 +1.85, 0.00, 51.04, 48.96, 2.07 +1.85, 0.00, 51.03, 48.97, 2.06 +1.85, 0.00, 51.02, 48.98, 2.05 +1.85, 0.00, 51.02, 48.98, 2.03 +1.85, 0.00, 51.01, 48.99, 2.02 +1.85, 0.00, 51.00, 49.00, 2.01 +1.85, 0.00, 51.00, 49.00, 1.99 +1.85, 0.00, 50.99, 49.01, 1.98 +1.85, 0.00, 50.98, 49.02, 1.96 +1.85, 0.00, 50.97, 49.03, 1.95 +1.85, 0.00, 50.97, 49.03, 1.94 +1.91, 0.00, 48.44, 51.56, -3.12 +1.91, 0.00, 50.90, 49.10, 1.81 +1.91, 0.00, 50.90, 49.10, 1.79 +1.91, 0.00, 50.89, 49.11, 1.78 +1.91, 0.00, 50.88, 49.12, 1.77 +1.85, 0.00, 53.40, 46.60, 6.79 +1.85, 0.00, 50.92, 49.08, 1.84 +1.85, 0.00, 50.91, 49.09, 1.82 +1.85, 0.00, 50.90, 49.10, 1.81 +1.85, 0.00, 50.90, 49.10, 1.79 +1.85, 0.00, 50.89, 49.11, 1.78 +1.85, 0.00, 50.88, 49.12, 1.77 +1.85, 0.00, 50.88, 49.12, 1.75 +1.85, 0.00, 50.87, 49.13, 1.74 +1.85, 0.00, 50.86, 49.14, 1.73 +1.91, 0.00, 48.33, 51.67, -3.33 +1.91, 0.00, 50.80, 49.20, 1.60 +1.91, 0.00, 50.79, 49.21, 1.58 +1.91, 0.00, 50.78, 49.22, 1.57 +1.91, 0.00, 50.78, 49.22, 1.56 +1.91, 0.00, 50.77, 49.23, 1.54 +1.91, 0.00, 50.76, 49.24, 1.53 +1.91, 0.00, 50.76, 49.24, 1.51 +1.98, 0.00, 48.23, 51.77, -3.55 +1.98, 0.00, 50.69, 49.31, 1.38 +1.98, 0.00, 50.68, 49.32, 1.37 +1.98, 0.00, 50.68, 49.32, 1.35 +1.98, 0.00, 50.67, 49.33, 1.34 +1.98, 0.00, 50.66, 49.34, 1.32 +1.98, 0.00, 50.65, 49.35, 1.31 +1.98, 0.00, 50.65, 49.35, 1.29 +1.98, 0.00, 50.64, 49.36, 1.28 +1.98, 0.00, 50.63, 49.37, 1.26 +1.98, 0.00, 50.63, 49.37, 1.25 +1.98, 0.00, 50.62, 49.38, 1.24 +1.98, 0.00, 50.61, 49.39, 1.22 +1.98, 0.00, 50.60, 49.40, 1.21 +1.98, 0.00, 50.60, 49.40, 1.19 +1.98, 0.00, 50.59, 49.41, 1.18 +1.98, 0.00, 50.58, 49.42, 1.16 +1.98, 0.00, 50.57, 49.43, 1.15 +1.98, 0.00, 50.57, 49.43, 1.13 +1.98, 0.00, 50.56, 49.44, 1.12 +1.98, 0.00, 50.55, 49.45, 1.10 +1.98, 0.00, 50.54, 49.46, 1.09 +1.98, 0.00, 50.54, 49.46, 1.07 +1.98, 0.00, 50.53, 49.47, 1.06 +1.98, 0.00, 50.52, 49.48, 1.04 +1.98, 0.00, 50.51, 49.49, 1.03 +1.98, 0.00, 50.51, 49.49, 1.01 +1.98, 0.00, 50.50, 49.50, 1.00 +1.98, 0.00, 50.49, 49.51, 0.98 +1.98, 0.00, 50.48, 49.52, 0.97 +1.98, 0.00, 50.48, 49.52, 0.95 +1.98, 0.00, 50.47, 49.53, 0.94 +1.98, 0.00, 50.46, 49.54, 0.92 +1.98, 0.00, 50.45, 49.55, 0.91 +1.98, 0.00, 50.45, 49.55, 0.89 +1.98, 0.00, 50.44, 49.56, 0.88 +1.98, 0.00, 50.43, 49.57, 0.86 +1.98, 0.00, 50.42, 49.58, 0.85 +1.91, 0.00, 52.94, 47.06, 5.88 +1.91, 0.00, 50.46, 49.54, 0.92 +1.91, 0.00, 50.45, 49.55, 0.91 +1.91, 0.00, 50.45, 49.55, 0.89 +1.91, 0.00, 50.44, 49.56, 0.88 +1.91, 0.00, 50.43, 49.57, 0.86 +1.91, 0.00, 50.42, 49.58, 0.85 +1.91, 0.00, 50.42, 49.58, 0.83 +1.91, 0.00, 50.41, 49.59, 0.82 +1.91, 0.00, 50.40, 49.60, 0.81 +1.91, 0.00, 50.40, 49.60, 0.79 +1.91, 0.00, 50.39, 49.61, 0.78 +1.91, 0.00, 50.38, 49.62, 0.76 +1.91, 0.00, 50.37, 49.63, 0.75 +1.91, 0.00, 50.37, 49.63, 0.73 +1.91, 0.00, 50.36, 49.64, 0.72 +1.91, 0.00, 50.35, 49.65, 0.70 +1.91, 0.00, 50.35, 49.65, 0.69 +1.91, 0.00, 50.34, 49.66, 0.68 +1.91, 0.00, 50.33, 49.67, 0.66 +1.91, 0.00, 50.32, 49.68, 0.65 +1.85, 0.00, 52.84, 47.16, 5.68 +1.85, 0.00, 50.36, 49.64, 0.72 +1.85, 0.00, 50.35, 49.65, 0.70 +1.85, 0.00, 50.35, 49.65, 0.69 +1.85, 0.00, 50.34, 49.66, 0.68 +1.85, 0.00, 50.33, 49.67, 0.66 +1.85, 0.00, 50.32, 49.68, 0.65 +1.85, 0.00, 50.32, 49.68, 0.64 +1.85, 0.00, 50.31, 49.69, 0.62 +1.85, 0.00, 50.30, 49.70, 0.61 +1.85, 0.00, 50.30, 49.70, 0.59 +1.85, 0.00, 50.29, 49.71, 0.58 +1.85, 0.00, 50.28, 49.72, 0.57 +1.85, 0.00, 50.28, 49.72, 0.55 +1.85, 0.00, 50.27, 49.73, 0.54 +1.85, 0.00, 50.26, 49.74, 0.52 +1.85, 0.00, 50.26, 49.74, 0.51 +1.85, 0.00, 50.25, 49.75, 0.50 +1.85, 0.00, 50.24, 49.76, 0.48 +1.85, 0.00, 50.23, 49.77, 0.47 +1.71, 0.00, 55.27, 44.73, 10.54 +1.71, 0.00, 50.32, 49.68, 0.64 +1.71, 0.00, 50.31, 49.69, 0.63 +1.71, 0.00, 50.31, 49.69, 0.62 +1.71, 0.00, 50.30, 49.70, 0.60 +1.71, 0.00, 50.30, 49.70, 0.59 +1.65, 0.00, 52.81, 47.19, 5.62 +1.65, 0.00, 50.33, 49.67, 0.66 +1.71, 0.00, 47.80, 52.20, -4.39 +1.71, 0.00, 50.27, 49.73, 0.54 +1.71, 0.00, 50.26, 49.74, 0.53 +1.71, 0.00, 50.26, 49.74, 0.51 +1.71, 0.00, 50.25, 49.75, 0.50 +1.65, 0.00, 52.77, 47.23, 5.53 +1.71, 0.00, 47.77, 52.23, -4.47 +1.65, 0.00, 52.75, 47.25, 5.51 +1.65, 0.00, 50.28, 49.72, 0.55 +1.65, 0.00, 50.27, 49.73, 0.54 +1.65, 0.00, 50.26, 49.74, 0.53 +1.65, 0.00, 50.26, 49.74, 0.51 +1.65, 0.00, 50.25, 49.75, 0.50 +1.65, 0.00, 50.24, 49.76, 0.49 +1.65, 0.00, 50.24, 49.76, 0.48 +1.58, 0.00, 52.75, 47.25, 5.51 +1.58, 0.00, 50.28, 49.72, 0.55 +1.58, 0.00, 50.27, 49.73, 0.54 +1.58, 0.00, 50.26, 49.74, 0.53 +1.58, 0.00, 50.26, 49.74, 0.52 +1.58, 0.00, 50.25, 49.75, 0.50 +1.58, 0.00, 50.25, 49.75, 0.49 +1.58, 0.00, 50.24, 49.76, 0.48 +1.58, 0.00, 50.23, 49.77, 0.47 +1.58, 0.00, 50.23, 49.77, 0.46 +1.58, 0.00, 50.22, 49.78, 0.44 +1.58, 0.00, 50.22, 49.78, 0.43 +1.58, 0.00, 50.21, 49.79, 0.42 +1.58, 0.00, 50.20, 49.80, 0.41 +1.58, 0.00, 50.20, 49.80, 0.40 +1.58, 0.00, 50.19, 49.81, 0.38 +1.58, 0.00, 50.19, 49.81, 0.37 +1.58, 0.00, 50.18, 49.82, 0.36 +1.58, 0.00, 50.17, 49.83, 0.35 +1.58, 0.00, 50.17, 49.83, 0.34 +1.58, 0.00, 50.16, 49.84, 0.33 +1.58, 0.00, 50.16, 49.84, 0.31 +1.58, 0.00, 50.15, 49.85, 0.30 +1.58, 0.00, 50.15, 49.85, 0.29 +1.58, 0.00, 50.14, 49.86, 0.28 +1.58, 0.00, 50.13, 49.87, 0.27 +1.58, 0.00, 50.13, 49.87, 0.25 +1.58, 0.00, 50.12, 49.88, 0.24 +1.58, 0.00, 50.12, 49.88, 0.23 +1.58, 0.00, 50.11, 49.89, 0.22 +1.58, 0.00, 50.10, 49.90, 0.21 +1.58, 0.00, 50.10, 49.90, 0.20 +1.58, 0.00, 50.09, 49.91, 0.18 +1.58, 0.00, 50.09, 49.91, 0.17 +1.58, 0.00, 50.08, 49.92, 0.16 +1.58, 0.00, 50.07, 49.93, 0.15 +1.58, 0.00, 50.07, 49.93, 0.14 +1.58, 0.00, 50.06, 49.94, 0.12 +1.58, 0.00, 50.06, 49.94, 0.11 +1.58, 0.00, 50.05, 49.95, 0.10 +1.58, 0.00, 50.04, 49.96, 0.09 +1.58, 0.00, 50.04, 49.96, 0.08 +1.58, 0.00, 50.03, 49.97, 0.06 +1.58, 0.00, 50.03, 49.97, 0.05 +1.58, 0.00, 50.02, 49.98, 0.04 +1.58, 0.00, 50.01, 49.99, 0.03 +1.58, 0.00, 50.01, 49.99, 0.02 +1.58, 0.00, 50.00, 50.00, 0.01 +1.58, 0.00, 50.00, 50.00, -0.01 +1.58, 0.00, 49.99, 50.01, -0.02 +1.58, 0.00, 49.98, 50.02, -0.03 +1.58, 0.00, 49.98, 50.02, -0.04 +1.58, 0.00, 49.97, 50.03, -0.05 +1.45, 0.00, 55.01, 44.99, 10.02 +1.45, 0.00, 50.06, 49.94, 0.12 +1.45, 0.00, 50.06, 49.94, 0.11 +1.45, 0.00, 50.05, 49.95, 0.10 +1.45, 0.00, 50.04, 49.96, 0.09 +1.45, 0.00, 50.04, 49.96, 0.08 +1.45, 0.00, 50.03, 49.97, 0.07 +1.45, 0.00, 50.03, 49.97, 0.06 +1.45, 0.00, 50.02, 49.98, 0.05 +1.45, 0.00, 50.02, 49.98, 0.03 +1.45, 0.00, 50.01, 49.99, 0.02 +1.45, 0.00, 50.01, 49.99, 0.01 +1.45, 0.00, 50.00, 50.00, 0.00 +1.45, 0.00, 50.00, 50.00, -0.01 +1.45, 0.00, 49.99, 50.01, -0.02 +1.38, 0.00, 52.51, 47.49, 5.01 +1.38, 0.00, 50.03, 49.97, 0.06 +1.38, 0.00, 50.02, 49.98, 0.05 +1.38, 0.00, 50.02, 49.98, 0.04 +1.32, 0.00, 52.54, 47.46, 5.07 +1.32, 0.00, 50.06, 49.94, 0.12 +1.32, 0.00, 50.05, 49.95, 0.11 +1.32, 0.00, 50.05, 49.95, 0.10 +1.32, 0.00, 50.04, 49.96, 0.09 +1.32, 0.00, 50.04, 49.96, 0.08 +1.32, 0.00, 50.03, 49.97, 0.07 +1.32, 0.00, 50.03, 49.97, 0.06 +1.32, 0.00, 50.02, 49.98, 0.05 +1.32, 0.00, 50.02, 49.98, 0.04 +1.32, 0.00, 50.01, 49.99, 0.03 +1.32, 0.00, 50.01, 49.99, 0.02 +1.19, 0.00, 55.05, 44.95, 10.09 +1.19, 0.00, 50.10, 49.90, 0.20 +1.19, 0.00, 50.09, 49.91, 0.19 +1.19, 0.00, 50.09, 49.91, 0.18 +1.19, 0.00, 50.09, 49.91, 0.17 +1.19, 0.00, 50.08, 49.92, 0.16 +1.19, 0.00, 50.08, 49.92, 0.15 +1.19, 0.00, 50.07, 49.93, 0.14 +1.12, 0.00, 52.59, 47.41, 5.18 +1.12, 0.00, 50.11, 49.89, 0.23 +1.12, 0.00, 50.11, 49.89, 0.22 +1.12, 0.00, 50.10, 49.90, 0.21 +1.05, 0.00, 52.62, 47.38, 5.24 +1.05, 0.00, 50.15, 49.85, 0.29 +1.05, 0.00, 50.14, 49.86, 0.29 +1.05, 0.00, 50.14, 49.86, 0.28 +1.05, 0.00, 50.13, 49.87, 0.27 +1.05, 0.00, 50.13, 49.87, 0.26 +1.05, 0.00, 50.13, 49.87, 0.25 +1.05, 0.00, 50.12, 49.88, 0.25 +0.92, 0.00, 55.16, 44.84, 10.32 +0.92, 0.00, 50.21, 49.79, 0.43 +0.92, 0.00, 50.21, 49.79, 0.42 +0.92, 0.00, 50.21, 49.79, 0.42 +0.92, 0.00, 50.20, 49.80, 0.41 +0.86, 0.00, 52.72, 47.28, 5.45 +0.86, 0.00, 50.25, 49.75, 0.49 +0.86, 0.00, 50.24, 49.76, 0.49 +0.79, 0.00, 52.76, 47.24, 5.53 +0.79, 0.00, 50.29, 49.71, 0.58 +0.79, 0.00, 50.28, 49.72, 0.57 +0.79, 0.00, 50.28, 49.72, 0.56 +0.66, 0.00, 55.32, 44.68, 10.64 +0.66, 0.00, 50.38, 49.62, 0.75 +0.66, 0.00, 50.37, 49.63, 0.75 +0.66, 0.00, 50.37, 49.63, 0.74 +0.66, 0.00, 50.37, 49.63, 0.74 +0.66, 0.00, 50.37, 49.63, 0.73 +0.66, 0.00, 50.36, 49.64, 0.73 +0.66, 0.00, 50.36, 49.64, 0.72 +0.66, 0.00, 50.36, 49.64, 0.72 +0.59, 0.00, 52.88, 47.12, 5.75 +0.59, 0.00, 50.40, 49.60, 0.81 +0.59, 0.00, 50.40, 49.60, 0.80 +0.59, 0.00, 50.40, 49.60, 0.80 +0.59, 0.00, 50.40, 49.60, 0.79 +0.53, 0.00, 52.92, 47.08, 5.83 +0.53, 0.00, 50.44, 49.56, 0.88 +0.53, 0.00, 50.44, 49.56, 0.88 +0.53, 0.00, 50.44, 49.56, 0.88 +0.40, 0.00, 55.48, 44.52, 10.96 +0.40, 0.00, 50.53, 49.47, 1.07 +0.40, 0.00, 50.53, 49.47, 1.07 +0.40, 0.00, 50.53, 49.47, 1.06 +0.40, 0.00, 50.53, 49.47, 1.06 +0.33, 0.00, 53.05, 46.95, 6.10 +0.33, 0.00, 50.58, 49.42, 1.15 +0.33, 0.00, 50.58, 49.42, 1.15 +0.33, 0.00, 50.57, 49.43, 1.15 +0.33, 0.00, 50.57, 49.43, 1.15 +0.26, 0.00, 53.09, 46.91, 6.19 +0.26, 0.00, 50.62, 49.38, 1.24 +0.26, 0.00, 50.62, 49.38, 1.24 +0.13, 0.00, 55.66, 44.34, 11.32 +0.13, 0.00, 50.72, 49.28, 1.43 +0.07, 0.00, 53.24, 46.76, 6.48 +0.07, 0.00, 50.77, 49.23, 1.53 +0.07, 0.00, 50.77, 49.23, 1.53 +0.00, 0.00, 53.29, 46.71, 6.57 +0.00, 0.00, 50.82, 49.18, 1.63 +0.00, 0.00, 50.82, 49.18, 1.63 +0.00, 0.00, 50.82, 49.18, 1.63 +-0.13, 0.00, 55.86, 44.14, 11.72 +-0.13, 0.00, 50.92, 49.08, 1.83 +-0.13, 0.00, 50.92, 49.08, 1.83 +-0.20, 0.00, 53.44, 46.56, 6.88 +-0.20, 0.00, 50.97, 49.03, 1.93 +-0.20, 0.00, 50.97, 49.03, 1.93 +-0.20, 0.00, 50.97, 49.03, 1.94 +-0.26, 0.00, 53.49, 46.51, 6.98 +-0.26, 0.00, 51.02, 48.98, 2.04 +-0.26, 0.00, 51.02, 48.98, 2.04 +-0.40, 0.00, 56.06, 43.94, 12.13 +-0.40, 0.00, 51.12, 48.88, 2.24 +-0.40, 0.00, 51.12, 48.88, 2.25 +-0.46, 0.00, 53.65, 46.35, 7.29 +-0.46, 0.00, 51.18, 48.82, 2.35 +-0.53, 0.00, 53.70, 46.30, 7.40 +-0.53, 0.00, 51.23, 48.77, 2.46 +-0.53, 0.00, 51.23, 48.77, 2.46 +-0.66, 0.00, 56.28, 43.72, 12.55 +-0.66, 0.00, 51.34, 48.66, 2.67 +-0.66, 0.00, 51.34, 48.66, 2.68 +-0.66, 0.00, 51.34, 48.66, 2.68 +-0.66, 0.00, 51.34, 48.66, 2.69 +-0.73, 0.00, 53.87, 46.13, 7.73 +-0.73, 0.00, 51.40, 48.60, 2.80 +-0.73, 0.00, 51.40, 48.60, 2.80 +-0.79, 0.00, 53.93, 46.07, 7.85 +-0.79, 0.00, 51.46, 48.54, 2.91 +-0.79, 0.00, 51.46, 48.54, 2.92 +-0.92, 0.00, 56.51, 43.49, 13.01 +-0.92, 0.00, 51.57, 48.43, 3.13 +-0.92, 0.00, 51.57, 48.43, 3.14 +-0.99, 0.00, 54.09, 45.91, 8.19 +-0.99, 0.00, 51.63, 48.37, 3.25 +-0.99, 0.00, 51.63, 48.37, 3.26 +-0.99, 0.00, 51.63, 48.37, 3.27 +-1.05, 0.00, 54.16, 45.84, 8.32 +-1.05, 0.00, 51.69, 48.31, 3.38 +-1.05, 0.00, 51.69, 48.31, 3.39 +-1.05, 0.00, 51.70, 48.30, 3.40 +-1.05, 0.00, 51.70, 48.30, 3.40 +-1.19, 0.00, 56.75, 43.25, 13.50 +-1.19, 0.00, 51.81, 48.19, 3.62 +-1.19, 0.00, 51.81, 48.19, 3.63 +-1.19, 0.00, 51.82, 48.18, 3.64 +-1.19, 0.00, 51.82, 48.18, 3.65 +-1.25, 0.00, 54.35, 45.65, 8.70 +-1.25, 0.00, 51.88, 48.12, 3.76 +-1.25, 0.00, 51.89, 48.11, 3.77 +-1.25, 0.00, 51.89, 48.11, 3.78 +-1.25, 0.00, 51.90, 48.10, 3.79 +-1.25, 0.00, 51.90, 48.10, 3.80 +-1.25, 0.00, 51.91, 48.09, 3.81 +-1.32, 0.00, 54.43, 45.57, 8.86 +-1.32, 0.00, 51.96, 48.04, 3.93 +-1.32, 0.00, 51.97, 48.03, 3.94 +-1.32, 0.00, 51.97, 48.03, 3.95 +-1.32, 0.00, 51.98, 48.02, 3.96 +-1.32, 0.00, 51.98, 48.02, 3.97 +-1.32, 0.00, 51.99, 48.01, 3.98 +-1.32, 0.00, 51.99, 48.01, 3.99 +-1.32, 0.00, 52.00, 48.00, 4.00 +-1.32, 0.00, 52.00, 48.00, 4.01 +-1.32, 0.00, 52.01, 47.99, 4.02 +-1.32, 0.00, 52.01, 47.99, 4.03 +-1.32, 0.00, 52.02, 47.98, 4.04 +-1.32, 0.00, 52.02, 47.98, 4.05 +-1.32, 0.00, 52.03, 47.97, 4.06 +-1.32, 0.00, 52.03, 47.97, 4.07 +-1.32, 0.00, 52.04, 47.96, 4.08 +-1.32, 0.00, 52.04, 47.96, 4.09 +-1.32, 0.00, 52.05, 47.95, 4.10 +-1.32, 0.00, 52.05, 47.95, 4.11 +-1.25, 0.00, 49.54, 50.46, -0.93 +-1.25, 0.00, 52.01, 47.99, 4.03 +-1.25, 0.00, 52.02, 47.98, 4.04 +-1.25, 0.00, 52.02, 47.98, 4.05 +-1.25, 0.00, 52.03, 47.97, 4.06 +-1.25, 0.00, 52.03, 47.97, 4.07 +-1.25, 0.00, 52.04, 47.96, 4.07 +-1.25, 0.00, 52.04, 47.96, 4.08 +-1.19, 0.00, 49.53, 50.47, -0.95 +-1.19, 0.00, 52.00, 48.00, 4.00 +-1.25, 0.00, 54.53, 45.47, 9.06 +-1.19, 0.00, 49.54, 50.46, -0.92 +-1.19, 0.00, 52.02, 47.98, 4.03 +-1.19, 0.00, 52.02, 47.98, 4.04 +-1.19, 0.00, 52.02, 47.98, 4.05 +-1.05, 0.00, 46.99, 53.01, -6.03 +-1.05, 0.00, 51.93, 48.07, 3.87 +-1.05, 0.00, 51.94, 48.06, 3.87 +-1.05, 0.00, 51.94, 48.06, 3.88 +-0.99, 0.00, 49.42, 50.58, -1.15 +-0.99, 0.00, 51.90, 48.10, 3.80 +-0.99, 0.00, 51.90, 48.10, 3.81 +-0.92, 0.00, 49.38, 50.62, -1.23 +-0.92, 0.00, 51.86, 48.14, 3.72 +-0.92, 0.00, 51.86, 48.14, 3.73 +-0.92, 0.00, 51.87, 48.13, 3.73 +-0.92, 0.00, 51.87, 48.13, 3.74 +-0.92, 0.00, 51.87, 48.13, 3.75 +-0.92, 0.00, 51.88, 48.12, 3.75 +-0.92, 0.00, 51.88, 48.12, 3.76 +-0.92, 0.00, 51.88, 48.12, 3.77 +-0.92, 0.00, 51.89, 48.11, 3.78 +-0.79, 0.00, 46.85, 53.15, -6.30 +-0.79, 0.00, 51.79, 48.21, 3.59 +-0.79, 0.00, 51.80, 48.20, 3.60 +-0.79, 0.00, 51.80, 48.20, 3.60 +-0.79, 0.00, 51.80, 48.20, 3.61 +-0.79, 0.00, 51.81, 48.19, 3.61 +-0.73, 0.00, 49.29, 50.71, -1.42 +-0.73, 0.00, 51.76, 48.24, 3.53 +-0.73, 0.00, 51.77, 48.23, 3.53 +-0.73, 0.00, 51.77, 48.23, 3.54 +-0.66, 0.00, 49.25, 50.75, -1.50 +-0.66, 0.00, 51.72, 48.28, 3.45 +-0.66, 0.00, 51.73, 48.27, 3.45 +-0.66, 0.00, 51.73, 48.27, 3.46 +-0.66, 0.00, 51.73, 48.27, 3.46 +-0.66, 0.00, 51.73, 48.27, 3.47 +-0.66, 0.00, 51.74, 48.26, 3.47 +-0.66, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 51.74, 48.26, 3.49 +-0.66, 0.00, 51.75, 48.25, 3.49 +-0.66, 0.00, 51.75, 48.25, 3.50 +-0.53, 0.00, 46.71, 53.29, -6.58 +-0.53, 0.00, 51.65, 48.35, 3.31 +-0.53, 0.00, 51.66, 48.34, 3.31 +-0.53, 0.00, 51.66, 48.34, 3.31 +-0.53, 0.00, 51.66, 48.34, 3.32 +-0.53, 0.00, 51.66, 48.34, 3.32 +-0.46, 0.00, 49.14, 50.86, -1.72 +-0.46, 0.00, 51.62, 48.38, 3.23 +-0.46, 0.00, 51.62, 48.38, 3.23 +-0.46, 0.00, 51.62, 48.38, 3.24 +-0.46, 0.00, 51.62, 48.38, 3.24 +-0.46, 0.00, 51.62, 48.38, 3.24 +-0.46, 0.00, 51.62, 48.38, 3.25 +-0.46, 0.00, 51.63, 48.37, 3.25 +-0.40, 0.00, 49.11, 50.89, -1.79 +-0.40, 0.00, 51.58, 48.42, 3.16 +-0.40, 0.00, 51.58, 48.42, 3.16 +-0.40, 0.00, 51.58, 48.42, 3.16 +-0.40, 0.00, 51.58, 48.42, 3.17 +-0.40, 0.00, 51.59, 48.41, 3.17 +-0.26, 0.00, 46.54, 53.46, -6.91 +-0.26, 0.00, 51.49, 48.51, 2.98 +-0.26, 0.00, 51.49, 48.51, 2.98 +-0.26, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 48.97, 51.03, -2.06 +-0.20, 0.00, 51.44, 48.56, 2.88 +-0.20, 0.00, 51.44, 48.56, 2.89 +-0.20, 0.00, 51.44, 48.56, 2.89 +-0.20, 0.00, 51.44, 48.56, 2.89 +-0.20, 0.00, 51.45, 48.55, 2.89 +-0.13, 0.00, 48.92, 51.08, -2.15 +-0.13, 0.00, 51.40, 48.60, 2.79 +-0.13, 0.00, 51.40, 48.60, 2.79 +-0.13, 0.00, 51.40, 48.60, 2.80 +0.00, 0.00, 46.36, 53.64, -7.29 +0.00, 0.00, 51.30, 48.70, 2.60 +0.00, 0.00, 51.30, 48.70, 2.60 +0.00, 0.00, 51.30, 48.70, 2.60 +0.00, 0.00, 51.30, 48.70, 2.60 +0.00, 0.00, 51.30, 48.70, 2.60 +0.07, 0.00, 48.78, 51.22, -2.45 +0.07, 0.00, 51.25, 48.75, 2.50 +0.07, 0.00, 51.25, 48.75, 2.50 +0.13, 0.00, 48.73, 51.27, -2.55 +0.13, 0.00, 51.20, 48.80, 2.40 +0.13, 0.00, 51.20, 48.80, 2.40 +0.13, 0.00, 51.20, 48.80, 2.39 +0.26, 0.00, 46.15, 53.85, -7.69 +0.26, 0.00, 51.10, 48.90, 2.19 +0.26, 0.00, 51.10, 48.90, 2.19 +0.26, 0.00, 51.09, 48.91, 2.19 +0.33, 0.00, 48.57, 51.43, -2.86 +0.33, 0.00, 51.04, 48.96, 2.09 +0.33, 0.00, 51.04, 48.96, 2.08 +0.33, 0.00, 51.04, 48.96, 2.08 +0.40, 0.00, 48.52, 51.48, -2.97 +0.40, 0.00, 50.99, 49.01, 1.98 +0.40, 0.00, 50.99, 49.01, 1.97 +0.40, 0.00, 50.98, 49.02, 1.97 +0.40, 0.00, 50.98, 49.02, 1.97 +0.53, 0.00, 45.94, 54.06, -8.12 +0.53, 0.00, 50.88, 49.12, 1.76 +0.53, 0.00, 50.88, 49.12, 1.76 +0.53, 0.00, 50.88, 49.12, 1.75 +0.59, 0.00, 48.35, 51.65, -3.29 +0.59, 0.00, 50.82, 49.18, 1.65 +0.59, 0.00, 50.82, 49.18, 1.64 +0.59, 0.00, 50.82, 49.18, 1.64 +0.59, 0.00, 50.82, 49.18, 1.63 +0.59, 0.00, 50.81, 49.19, 1.63 +0.59, 0.00, 50.81, 49.19, 1.62 +0.59, 0.00, 50.81, 49.19, 1.62 +0.66, 0.00, 48.29, 51.71, -3.43 +0.66, 0.00, 50.75, 49.25, 1.51 +0.66, 0.00, 50.75, 49.25, 1.50 +0.66, 0.00, 50.75, 49.25, 1.50 +0.66, 0.00, 50.75, 49.25, 1.49 +0.66, 0.00, 50.74, 49.26, 1.49 +0.66, 0.00, 50.74, 49.26, 1.48 +0.66, 0.00, 50.74, 49.26, 1.48 +0.66, 0.00, 50.74, 49.26, 1.48 +0.66, 0.00, 50.74, 49.26, 1.47 +0.66, 0.00, 50.73, 49.27, 1.47 +0.66, 0.00, 50.73, 49.27, 1.46 +0.66, 0.00, 50.73, 49.27, 1.46 +0.66, 0.00, 50.73, 49.27, 1.45 +0.66, 0.00, 50.72, 49.28, 1.45 +0.79, 0.00, 45.68, 54.32, -8.65 +0.66, 0.00, 55.66, 44.34, 11.32 +0.79, 0.00, 45.67, 54.33, -8.66 +0.79, 0.00, 50.61, 49.39, 1.22 +0.79, 0.00, 50.61, 49.39, 1.22 +0.79, 0.00, 50.61, 49.39, 1.21 +0.79, 0.00, 50.60, 49.40, 1.21 +0.79, 0.00, 50.60, 49.40, 1.20 +0.66, 0.00, 55.64, 44.36, 11.28 +0.66, 0.00, 50.69, 49.31, 1.39 +0.66, 0.00, 50.69, 49.31, 1.38 +0.66, 0.00, 50.69, 49.31, 1.38 +0.66, 0.00, 50.69, 49.31, 1.37 +0.66, 0.00, 50.68, 49.32, 1.37 +0.66, 0.00, 50.68, 49.32, 1.36 +0.66, 0.00, 50.68, 49.32, 1.36 +0.66, 0.00, 50.68, 49.32, 1.35 +0.66, 0.00, 50.67, 49.33, 1.35 +0.66, 0.00, 50.67, 49.33, 1.34 +0.59, 0.00, 53.19, 46.81, 6.38 +0.59, 0.00, 50.72, 49.28, 1.43 +0.59, 0.00, 50.72, 49.28, 1.43 +0.59, 0.00, 50.71, 49.29, 1.43 +0.59, 0.00, 50.71, 49.29, 1.42 +0.59, 0.00, 50.71, 49.29, 1.42 +0.59, 0.00, 50.71, 49.29, 1.41 +0.59, 0.00, 50.70, 49.30, 1.41 +0.59, 0.00, 50.70, 49.30, 1.40 +0.53, 0.00, 53.22, 46.78, 6.44 +0.53, 0.00, 50.75, 49.25, 1.49 +0.53, 0.00, 50.75, 49.25, 1.49 +0.53, 0.00, 50.74, 49.26, 1.49 +0.53, 0.00, 50.74, 49.26, 1.48 +0.53, 0.00, 50.74, 49.26, 1.48 +0.53, 0.00, 50.74, 49.26, 1.47 +0.53, 0.00, 50.74, 49.26, 1.47 +0.53, 0.00, 50.73, 49.27, 1.47 +0.53, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 55.77, 44.23, 11.55 +0.40, 0.00, 50.83, 49.17, 1.65 +0.40, 0.00, 50.83, 49.17, 1.65 +0.40, 0.00, 50.82, 49.18, 1.65 +0.40, 0.00, 50.82, 49.18, 1.65 +0.40, 0.00, 50.82, 49.18, 1.64 +0.40, 0.00, 50.82, 49.18, 1.64 +0.40, 0.00, 50.82, 49.18, 1.64 +0.40, 0.00, 50.82, 49.18, 1.63 +0.40, 0.00, 50.82, 49.18, 1.63 +0.40, 0.00, 50.81, 49.19, 1.63 +0.40, 0.00, 50.81, 49.19, 1.62 +0.33, 0.00, 53.33, 46.67, 6.67 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.71 +0.33, 0.00, 50.86, 49.14, 1.71 +0.40, 0.00, 48.33, 51.67, -3.33 +0.33, 0.00, 53.32, 46.68, 6.65 +0.40, 0.00, 48.33, 51.67, -3.34 +0.33, 0.00, 53.32, 46.68, 6.64 +0.33, 0.00, 50.85, 49.15, 1.70 +0.33, 0.00, 50.85, 49.15, 1.70 +0.33, 0.00, 50.85, 49.15, 1.69 +0.33, 0.00, 50.85, 49.15, 1.69 +0.33, 0.00, 50.84, 49.16, 1.69 +0.33, 0.00, 50.84, 49.16, 1.69 +0.33, 0.00, 50.84, 49.16, 1.68 +0.26, 0.00, 53.36, 46.64, 6.72 +0.26, 0.00, 50.89, 49.11, 1.78 +0.26, 0.00, 50.89, 49.11, 1.78 +0.26, 0.00, 50.89, 49.11, 1.77 +0.26, 0.00, 50.89, 49.11, 1.77 +0.26, 0.00, 50.89, 49.11, 1.77 +0.26, 0.00, 50.88, 49.12, 1.77 +0.26, 0.00, 50.88, 49.12, 1.77 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.76 +0.26, 0.00, 50.88, 49.12, 1.75 +0.13, 0.00, 55.92, 44.08, 11.84 +0.13, 0.00, 50.98, 49.02, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.95 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.94 +0.13, 0.00, 50.97, 49.03, 1.93 +0.13, 0.00, 50.97, 49.03, 1.93 +0.13, 0.00, 50.97, 49.03, 1.93 +0.13, 0.00, 50.97, 49.03, 1.93 +0.07, 0.00, 53.49, 46.51, 6.97 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.07, 0.00, 51.01, 48.99, 2.03 +0.13, 0.00, 48.49, 51.51, -3.02 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.92 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.96, 49.04, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.13, 0.00, 50.95, 49.05, 1.91 +0.26, 0.00, 45.91, 54.09, -8.18 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.70 +0.26, 0.00, 50.85, 49.15, 1.69 +0.26, 0.00, 50.85, 49.15, 1.69 +0.13, 0.00, 55.89, 44.11, 11.78 +0.13, 0.00, 50.94, 49.06, 1.89 +0.13, 0.00, 50.94, 49.06, 1.89 +0.13, 0.00, 50.94, 49.06, 1.89 +0.13, 0.00, 50.94, 49.06, 1.88 +0.13, 0.00, 50.94, 49.06, 1.88 +0.13, 0.00, 50.94, 49.06, 1.88 +0.26, 0.00, 45.90, 54.10, -8.20 +0.26, 0.00, 50.84, 49.16, 1.68 +0.26, 0.00, 50.84, 49.16, 1.68 +0.26, 0.00, 50.84, 49.16, 1.68 +0.26, 0.00, 50.84, 49.16, 1.67 +0.26, 0.00, 50.84, 49.16, 1.67 +0.26, 0.00, 50.84, 49.16, 1.67 +0.26, 0.00, 50.83, 49.17, 1.67 +0.26, 0.00, 50.83, 49.17, 1.67 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.26, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 55.87, 44.13, 11.74 +0.26, 0.00, 45.88, 54.12, -8.24 +0.26, 0.00, 50.83, 49.17, 1.65 +0.26, 0.00, 50.82, 49.18, 1.65 +0.26, 0.00, 50.82, 49.18, 1.65 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 50.82, 49.18, 1.63 +0.26, 0.00, 50.82, 49.18, 1.63 +0.26, 0.00, 50.82, 49.18, 1.63 +0.26, 0.00, 50.81, 49.19, 1.63 +0.26, 0.00, 50.81, 49.19, 1.63 +0.26, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 55.85, 44.15, 11.71 +0.13, 0.00, 50.91, 49.09, 1.82 +0.13, 0.00, 50.91, 49.09, 1.82 +0.13, 0.00, 50.91, 49.09, 1.82 +0.13, 0.00, 50.91, 49.09, 1.82 +0.13, 0.00, 50.91, 49.09, 1.82 +0.26, 0.00, 45.86, 54.14, -8.27 +0.13, 0.00, 55.85, 44.15, 11.70 +0.26, 0.00, 45.86, 54.14, -8.27 +0.26, 0.00, 50.81, 49.19, 1.61 +0.26, 0.00, 50.80, 49.20, 1.61 +0.26, 0.00, 50.80, 49.20, 1.61 +0.26, 0.00, 50.80, 49.20, 1.61 +0.26, 0.00, 50.80, 49.20, 1.60 +0.13, 0.00, 55.84, 44.16, 11.69 +0.13, 0.00, 50.90, 49.10, 1.80 +0.13, 0.00, 50.90, 49.10, 1.80 +0.13, 0.00, 50.90, 49.10, 1.80 +0.13, 0.00, 50.90, 49.10, 1.80 +0.07, 0.00, 53.42, 46.58, 6.84 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.95, 49.05, 1.89 +0.07, 0.00, 50.94, 49.06, 1.89 +0.07, 0.00, 50.94, 49.06, 1.89 +0.07, 0.00, 50.94, 49.06, 1.89 +0.07, 0.00, 50.94, 49.06, 1.89 +0.00, 0.00, 53.47, 46.53, 6.93 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +0.00, 0.00, 50.99, 49.01, 1.99 +-0.13, 0.00, 56.04, 43.96, 12.07 +-0.13, 0.00, 51.09, 48.91, 2.19 +-0.13, 0.00, 51.09, 48.91, 2.19 +0.00, 0.00, 46.05, 53.95, -7.90 +-0.13, 0.00, 56.04, 43.96, 12.08 +-0.13, 0.00, 51.09, 48.91, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.19 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.20, 0.00, 53.62, 46.38, 7.24 +-0.13, 0.00, 48.63, 51.37, -2.74 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.13, 0.00, 51.10, 48.90, 2.20 +-0.20, 0.00, 53.62, 46.38, 7.25 +-0.13, 0.00, 48.63, 51.37, -2.74 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +0.00, 0.00, 46.06, 53.94, -7.87 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +-0.13, 0.00, 56.05, 43.95, 12.10 +-0.13, 0.00, 51.11, 48.89, 2.22 +-0.13, 0.00, 51.11, 48.89, 2.22 +0.00, 0.00, 46.07, 53.93, -7.87 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.00, 0.00, 51.01, 48.99, 2.02 +0.07, 0.00, 48.49, 51.51, -3.02 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.92 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.07, 0.00, 50.96, 49.04, 1.91 +0.00, 0.00, 53.48, 46.52, 6.95 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +0.00, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 56.05, 43.95, 12.10 +-0.13, 0.00, 51.10, 48.90, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.13, 0.00, 51.11, 48.89, 2.21 +-0.20, 0.00, 53.63, 46.37, 7.26 +-0.20, 0.00, 51.16, 48.84, 2.31 +-0.20, 0.00, 51.16, 48.84, 2.31 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.20, 0.00, 51.16, 48.84, 2.32 +-0.26, 0.00, 53.68, 46.32, 7.37 +-0.26, 0.00, 51.21, 48.79, 2.43 +-0.26, 0.00, 51.21, 48.79, 2.43 +-0.26, 0.00, 51.22, 48.78, 2.43 +-0.26, 0.00, 51.22, 48.78, 2.43 +-0.26, 0.00, 51.22, 48.78, 2.43 +-0.26, 0.00, 51.22, 48.78, 2.44 +-0.26, 0.00, 51.22, 48.78, 2.44 +-0.40, 0.00, 56.26, 43.74, 12.53 +-0.40, 0.00, 51.32, 48.68, 2.64 +-0.40, 0.00, 51.32, 48.68, 2.64 +-0.40, 0.00, 51.32, 48.68, 2.65 +-0.40, 0.00, 51.33, 48.67, 2.65 +-0.40, 0.00, 51.33, 48.67, 2.65 +-0.40, 0.00, 51.33, 48.67, 2.66 +-0.40, 0.00, 51.33, 48.67, 2.66 +-0.40, 0.00, 51.33, 48.67, 2.66 +-0.40, 0.00, 51.33, 48.67, 2.67 +-0.40, 0.00, 51.33, 48.67, 2.67 +-0.40, 0.00, 51.34, 48.66, 2.67 +-0.40, 0.00, 51.34, 48.66, 2.67 +-0.40, 0.00, 51.34, 48.66, 2.68 +-0.46, 0.00, 53.86, 46.14, 7.72 +-0.46, 0.00, 51.39, 48.61, 2.78 +-0.46, 0.00, 51.39, 48.61, 2.79 +-0.46, 0.00, 51.40, 48.60, 2.79 +-0.46, 0.00, 51.40, 48.60, 2.79 +-0.46, 0.00, 51.40, 48.60, 2.80 +-0.46, 0.00, 51.40, 48.60, 2.80 +-0.46, 0.00, 51.40, 48.60, 2.80 +-0.46, 0.00, 51.40, 48.60, 2.81 +-0.46, 0.00, 51.41, 48.59, 2.81 +-0.46, 0.00, 51.41, 48.59, 2.81 +-0.46, 0.00, 51.41, 48.59, 2.82 +-0.46, 0.00, 51.41, 48.59, 2.82 +-0.46, 0.00, 51.41, 48.59, 2.82 +-0.40, 0.00, 48.89, 51.11, -2.21 +-0.40, 0.00, 51.37, 48.63, 2.73 +-0.40, 0.00, 51.37, 48.63, 2.73 +-0.40, 0.00, 51.37, 48.63, 2.74 +-0.40, 0.00, 51.37, 48.63, 2.74 +-0.40, 0.00, 51.37, 48.63, 2.74 +-0.46, 0.00, 53.89, 46.11, 7.79 +-0.46, 0.00, 51.42, 48.58, 2.85 +-0.46, 0.00, 51.43, 48.57, 2.85 +-0.46, 0.00, 51.43, 48.57, 2.86 +-0.46, 0.00, 51.43, 48.57, 2.86 +-0.46, 0.00, 51.43, 48.57, 2.86 +-0.46, 0.00, 51.43, 48.57, 2.87 +-0.46, 0.00, 51.44, 48.56, 2.87 +-0.46, 0.00, 51.44, 48.56, 2.87 +-0.46, 0.00, 51.44, 48.56, 2.88 +-0.40, 0.00, 48.92, 51.08, -2.16 +-0.40, 0.00, 51.39, 48.61, 2.78 +-0.40, 0.00, 51.39, 48.61, 2.79 +-0.26, 0.00, 46.35, 53.65, -7.30 +-0.26, 0.00, 51.30, 48.70, 2.59 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.60 +-0.26, 0.00, 51.30, 48.70, 2.61 +-0.26, 0.00, 51.30, 48.70, 2.61 +-0.26, 0.00, 51.30, 48.70, 2.61 +-0.26, 0.00, 51.31, 48.69, 2.61 +-0.26, 0.00, 51.31, 48.69, 2.61 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.20, 0.00, 48.79, 51.21, -2.42 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.13, 0.00, 48.74, 51.26, -2.51 +-0.13, 0.00, 51.22, 48.78, 2.43 +-0.13, 0.00, 51.22, 48.78, 2.43 +-0.13, 0.00, 51.22, 48.78, 2.43 +-0.13, 0.00, 51.22, 48.78, 2.43 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +0.00, 0.00, 46.18, 53.82, -7.64 +0.00, 0.00, 51.12, 48.88, 2.25 +0.00, 0.00, 51.12, 48.88, 2.25 +0.00, 0.00, 51.12, 48.88, 2.25 +0.07, 0.00, 48.60, 51.40, -2.80 +0.07, 0.00, 51.07, 48.93, 2.15 +0.13, 0.00, 48.55, 51.45, -2.90 +0.13, 0.00, 51.02, 48.98, 2.05 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.03 +0.26, 0.00, 45.97, 54.03, -8.05 +0.26, 0.00, 50.92, 49.08, 1.83 +0.26, 0.00, 50.92, 49.08, 1.83 +0.33, 0.00, 48.39, 51.61, -3.21 +0.33, 0.00, 50.86, 49.14, 1.73 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.40, 0.00, 48.34, 51.66, -3.32 +0.40, 0.00, 50.81, 49.19, 1.62 +0.40, 0.00, 50.81, 49.19, 1.61 +0.40, 0.00, 50.81, 49.19, 1.61 +0.40, 0.00, 50.80, 49.20, 1.61 +0.40, 0.00, 50.80, 49.20, 1.61 +0.40, 0.00, 50.80, 49.20, 1.60 +0.40, 0.00, 50.80, 49.20, 1.60 +0.40, 0.00, 50.80, 49.20, 1.60 +0.40, 0.00, 50.80, 49.20, 1.59 +0.40, 0.00, 50.80, 49.20, 1.59 +0.40, 0.00, 50.79, 49.21, 1.59 +0.40, 0.00, 50.79, 49.21, 1.58 +0.53, 0.00, 45.75, 54.25, -8.50 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.37 +0.59, 0.00, 48.16, 51.84, -3.68 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.25 +0.59, 0.00, 50.63, 49.37, 1.25 +0.59, 0.00, 50.62, 49.38, 1.25 +0.59, 0.00, 50.62, 49.38, 1.24 +0.59, 0.00, 50.62, 49.38, 1.24 +0.59, 0.00, 50.62, 49.38, 1.23 +0.59, 0.00, 50.61, 49.39, 1.23 +0.59, 0.00, 50.61, 49.39, 1.22 +0.59, 0.00, 50.61, 49.39, 1.22 +0.59, 0.00, 50.61, 49.39, 1.21 +0.59, 0.00, 50.61, 49.39, 1.21 +0.59, 0.00, 50.60, 49.40, 1.21 +0.66, 0.00, 48.08, 51.92, -3.84 +0.66, 0.00, 50.55, 49.45, 1.10 +0.66, 0.00, 50.55, 49.45, 1.09 +0.66, 0.00, 50.54, 49.46, 1.09 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.07 +0.79, 0.00, 45.49, 54.51, -9.02 +0.79, 0.00, 50.43, 49.57, 0.86 +0.66, 0.00, 55.47, 44.53, 10.94 +0.66, 0.00, 50.53, 49.47, 1.05 +0.66, 0.00, 50.52, 49.48, 1.05 +0.66, 0.00, 50.52, 49.48, 1.04 +0.66, 0.00, 50.52, 49.48, 1.04 +0.66, 0.00, 50.52, 49.48, 1.03 +0.66, 0.00, 50.51, 49.49, 1.03 +0.66, 0.00, 50.51, 49.49, 1.02 +0.66, 0.00, 50.51, 49.49, 1.02 +0.66, 0.00, 50.51, 49.49, 1.01 +0.66, 0.00, 50.50, 49.50, 1.01 +0.66, 0.00, 50.50, 49.50, 1.00 +0.66, 0.00, 50.50, 49.50, 1.00 +0.79, 0.00, 45.45, 54.55, -9.10 +0.79, 0.00, 50.39, 49.61, 0.79 +0.79, 0.00, 50.39, 49.61, 0.78 +0.79, 0.00, 50.39, 49.61, 0.77 +0.79, 0.00, 50.38, 49.62, 0.77 +0.66, 0.00, 55.42, 44.58, 10.85 +0.66, 0.00, 50.48, 49.52, 0.96 +0.66, 0.00, 50.48, 49.52, 0.95 +0.66, 0.00, 50.47, 49.53, 0.95 +0.66, 0.00, 50.47, 49.53, 0.94 +0.59, 0.00, 52.99, 47.01, 5.98 +0.59, 0.00, 50.52, 49.48, 1.03 +0.59, 0.00, 50.51, 49.49, 1.03 +0.59, 0.00, 50.51, 49.49, 1.02 +0.59, 0.00, 50.51, 49.49, 1.02 +0.59, 0.00, 50.51, 49.49, 1.01 +0.59, 0.00, 50.50, 49.50, 1.01 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 0.99 +0.59, 0.00, 50.49, 49.51, 0.99 +0.59, 0.00, 50.49, 49.51, 0.98 +0.59, 0.00, 50.49, 49.51, 0.98 +0.59, 0.00, 50.49, 49.51, 0.97 +0.53, 0.00, 53.01, 46.99, 6.01 +0.53, 0.00, 50.53, 49.47, 1.06 +0.53, 0.00, 50.53, 49.47, 1.06 +0.53, 0.00, 50.53, 49.47, 1.06 +0.40, 0.00, 55.57, 44.43, 11.14 +0.40, 0.00, 50.62, 49.38, 1.25 +0.40, 0.00, 50.62, 49.38, 1.25 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.23 +0.40, 0.00, 50.62, 49.38, 1.23 +0.40, 0.00, 50.61, 49.39, 1.23 +0.40, 0.00, 50.61, 49.39, 1.22 +0.40, 0.00, 50.61, 49.39, 1.22 +0.40, 0.00, 50.61, 49.39, 1.22 +0.40, 0.00, 50.61, 49.39, 1.22 +0.33, 0.00, 53.13, 46.87, 6.26 +0.33, 0.00, 50.65, 49.35, 1.31 +0.33, 0.00, 50.65, 49.35, 1.31 +0.33, 0.00, 50.65, 49.35, 1.31 +0.33, 0.00, 50.65, 49.35, 1.30 +0.26, 0.00, 53.17, 46.83, 6.34 +0.26, 0.00, 50.70, 49.30, 1.40 +0.26, 0.00, 50.70, 49.30, 1.40 +0.26, 0.00, 50.70, 49.30, 1.39 +0.26, 0.00, 50.70, 49.30, 1.39 +0.26, 0.00, 50.69, 49.31, 1.39 +0.13, 0.00, 55.74, 44.26, 11.47 +0.13, 0.00, 50.79, 49.21, 1.59 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.13, 0.00, 50.79, 49.21, 1.58 +0.07, 0.00, 53.31, 46.69, 6.62 +0.07, 0.00, 50.84, 49.16, 1.68 +0.07, 0.00, 50.84, 49.16, 1.68 +0.07, 0.00, 50.84, 49.16, 1.68 +0.00, 0.00, 53.36, 46.64, 6.72 +0.00, 0.00, 50.89, 49.11, 1.77 +0.00, 0.00, 50.89, 49.11, 1.77 +0.00, 0.00, 50.89, 49.11, 1.77 +0.00, 0.00, 50.89, 49.11, 1.77 +0.00, 0.00, 50.89, 49.11, 1.77 +-0.13, 0.00, 55.93, 44.07, 11.86 +-0.13, 0.00, 50.99, 49.01, 1.97 +-0.13, 0.00, 50.99, 49.01, 1.97 +-0.13, 0.00, 50.99, 49.01, 1.98 +-0.13, 0.00, 50.99, 49.01, 1.98 +-0.13, 0.00, 50.99, 49.01, 1.98 +-0.13, 0.00, 50.99, 49.01, 1.98 +-0.20, 0.00, 53.51, 46.49, 7.02 +-0.20, 0.00, 51.04, 48.96, 2.08 +-0.20, 0.00, 51.04, 48.96, 2.08 +-0.20, 0.00, 51.04, 48.96, 2.08 +-0.20, 0.00, 51.04, 48.96, 2.09 +-0.20, 0.00, 51.04, 48.96, 2.09 +-0.26, 0.00, 53.57, 46.43, 7.13 +-0.26, 0.00, 51.09, 48.91, 2.19 +-0.26, 0.00, 51.10, 48.90, 2.19 +-0.40, 0.00, 56.14, 43.86, 12.28 +-0.40, 0.00, 51.20, 48.80, 2.40 +-0.40, 0.00, 51.20, 48.80, 2.40 +-0.40, 0.00, 51.20, 48.80, 2.40 +-0.40, 0.00, 51.20, 48.80, 2.40 +-0.40, 0.00, 51.20, 48.80, 2.41 +-0.40, 0.00, 51.20, 48.80, 2.41 +-0.40, 0.00, 51.21, 48.79, 2.41 +-0.46, 0.00, 53.73, 46.27, 7.46 +-0.46, 0.00, 51.26, 48.74, 2.52 +-0.46, 0.00, 51.26, 48.74, 2.52 +-0.46, 0.00, 51.26, 48.74, 2.53 +-0.46, 0.00, 51.26, 48.74, 2.53 +-0.46, 0.00, 51.27, 48.73, 2.53 +-0.46, 0.00, 51.27, 48.73, 2.54 +-0.46, 0.00, 51.27, 48.73, 2.54 +-0.53, 0.00, 53.79, 46.21, 7.59 +-0.53, 0.00, 51.32, 48.68, 2.65 +-0.53, 0.00, 51.33, 48.67, 2.65 +-0.66, 0.00, 56.37, 43.63, 12.74 +-0.66, 0.00, 51.43, 48.57, 2.86 +-0.66, 0.00, 51.43, 48.57, 2.86 +-0.66, 0.00, 51.43, 48.57, 2.87 +-0.66, 0.00, 51.44, 48.56, 2.87 +-0.73, 0.00, 53.96, 46.04, 7.92 +-0.73, 0.00, 51.49, 48.51, 2.98 +-0.73, 0.00, 51.49, 48.51, 2.99 +-0.73, 0.00, 51.50, 48.50, 2.99 +-0.73, 0.00, 51.50, 48.50, 3.00 +-0.73, 0.00, 51.50, 48.50, 3.00 +-0.73, 0.00, 51.50, 48.50, 3.01 +-0.73, 0.00, 51.51, 48.49, 3.02 +-0.73, 0.00, 51.51, 48.49, 3.02 +-0.73, 0.00, 51.51, 48.49, 3.03 +-0.73, 0.00, 51.52, 48.48, 3.03 +-0.79, 0.00, 54.04, 45.96, 8.08 +-0.79, 0.00, 51.57, 48.43, 3.14 +-0.79, 0.00, 51.57, 48.43, 3.15 +-0.79, 0.00, 51.58, 48.42, 3.15 +-0.79, 0.00, 51.58, 48.42, 3.16 +-0.79, 0.00, 51.58, 48.42, 3.17 +-0.79, 0.00, 51.59, 48.41, 3.17 +-0.79, 0.00, 51.59, 48.41, 3.18 +-0.92, 0.00, 56.64, 43.36, 13.27 +-0.92, 0.00, 51.69, 48.31, 3.39 +-0.92, 0.00, 51.70, 48.30, 3.40 +-0.92, 0.00, 51.70, 48.30, 3.40 +-0.92, 0.00, 51.71, 48.29, 3.41 +-0.92, 0.00, 51.71, 48.29, 3.42 +-0.92, 0.00, 51.71, 48.29, 3.42 +-0.92, 0.00, 51.72, 48.28, 3.43 +-0.92, 0.00, 51.72, 48.28, 3.44 +-0.79, 0.00, 46.68, 53.32, -6.64 +-0.79, 0.00, 51.63, 48.37, 3.25 +-0.79, 0.00, 51.63, 48.37, 3.26 +-0.79, 0.00, 51.63, 48.37, 3.26 +-0.79, 0.00, 51.63, 48.37, 3.27 +-0.79, 0.00, 51.64, 48.36, 3.28 +-0.79, 0.00, 51.64, 48.36, 3.28 +-0.79, 0.00, 51.64, 48.36, 3.29 +-0.79, 0.00, 51.65, 48.35, 3.29 +-0.79, 0.00, 51.65, 48.35, 3.30 +-0.79, 0.00, 51.65, 48.35, 3.31 +-0.92, 0.00, 56.70, 43.30, 13.40 +-0.92, 0.00, 51.76, 48.24, 3.52 +-0.92, 0.00, 51.76, 48.24, 3.52 +-0.92, 0.00, 51.77, 48.23, 3.53 +-0.79, 0.00, 46.73, 53.27, -6.55 +-0.79, 0.00, 51.67, 48.33, 3.34 +-0.79, 0.00, 51.68, 48.32, 3.35 +-0.79, 0.00, 51.68, 48.32, 3.36 +-0.79, 0.00, 51.68, 48.32, 3.36 +-0.73, 0.00, 49.16, 50.84, -1.67 +-0.73, 0.00, 51.64, 48.36, 3.27 +-0.73, 0.00, 51.64, 48.36, 3.28 +-0.73, 0.00, 51.64, 48.36, 3.29 +-0.73, 0.00, 51.65, 48.35, 3.29 +-0.73, 0.00, 51.65, 48.35, 3.30 +-0.73, 0.00, 51.65, 48.35, 3.30 +-0.73, 0.00, 51.65, 48.35, 3.31 +-0.73, 0.00, 51.66, 48.34, 3.31 +-0.73, 0.00, 51.66, 48.34, 3.32 +-0.73, 0.00, 51.66, 48.34, 3.32 +-0.73, 0.00, 51.66, 48.34, 3.33 +-0.73, 0.00, 51.67, 48.33, 3.33 +-0.73, 0.00, 51.67, 48.33, 3.34 +-0.73, 0.00, 51.67, 48.33, 3.35 +-0.73, 0.00, 51.68, 48.32, 3.35 +-0.73, 0.00, 51.68, 48.32, 3.36 +-0.73, 0.00, 51.68, 48.32, 3.36 +-0.66, 0.00, 49.16, 50.84, -1.68 +-0.66, 0.00, 51.64, 48.36, 3.27 +-0.66, 0.00, 51.64, 48.36, 3.28 +-0.66, 0.00, 51.64, 48.36, 3.28 +-0.66, 0.00, 51.64, 48.36, 3.29 +-0.66, 0.00, 51.65, 48.35, 3.29 +-0.66, 0.00, 51.65, 48.35, 3.30 +-0.66, 0.00, 51.65, 48.35, 3.30 +-0.66, 0.00, 51.65, 48.35, 3.31 +-0.66, 0.00, 51.66, 48.34, 3.31 +-0.66, 0.00, 51.66, 48.34, 3.32 +-0.66, 0.00, 51.66, 48.34, 3.32 +-0.66, 0.00, 51.66, 48.34, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.34 +-0.66, 0.00, 51.67, 48.33, 3.34 +-0.66, 0.00, 51.67, 48.33, 3.35 +-0.66, 0.00, 51.68, 48.32, 3.35 +-0.66, 0.00, 51.68, 48.32, 3.36 +-0.66, 0.00, 51.68, 48.32, 3.36 +-0.66, 0.00, 51.68, 48.32, 3.37 +-0.53, 0.00, 46.64, 53.36, -6.71 +-0.53, 0.00, 51.59, 48.41, 3.18 +-0.53, 0.00, 51.59, 48.41, 3.18 +-0.46, 0.00, 49.07, 50.93, -1.86 +-0.53, 0.00, 54.07, 45.93, 8.13 +-0.53, 0.00, 51.60, 48.40, 3.19 +-0.46, 0.00, 49.08, 50.92, -1.85 +-0.53, 0.00, 54.07, 45.93, 8.14 +-0.53, 0.00, 51.60, 48.40, 3.20 +-0.53, 0.00, 51.60, 48.40, 3.21 +-0.53, 0.00, 51.61, 48.39, 3.21 +-0.53, 0.00, 51.61, 48.39, 3.22 +-0.53, 0.00, 51.61, 48.39, 3.22 +-0.53, 0.00, 51.61, 48.39, 3.22 +-0.53, 0.00, 51.61, 48.39, 3.23 +-0.53, 0.00, 51.62, 48.38, 3.23 +-0.53, 0.00, 51.62, 48.38, 3.24 +-0.53, 0.00, 51.62, 48.38, 3.24 +-0.46, 0.00, 49.10, 50.90, -1.80 +-0.46, 0.00, 51.57, 48.43, 3.15 +-0.46, 0.00, 51.58, 48.42, 3.15 +-0.46, 0.00, 51.58, 48.42, 3.15 +-0.40, 0.00, 49.06, 50.94, -1.89 +-0.40, 0.00, 51.53, 48.47, 3.06 +-0.40, 0.00, 51.53, 48.47, 3.06 +-0.40, 0.00, 51.53, 48.47, 3.07 +-0.40, 0.00, 51.53, 48.47, 3.07 +-0.40, 0.00, 51.54, 48.46, 3.07 +-0.40, 0.00, 51.54, 48.46, 3.08 +-0.40, 0.00, 51.54, 48.46, 3.08 +-0.40, 0.00, 51.54, 48.46, 3.08 +-0.40, 0.00, 51.54, 48.46, 3.08 +-0.46, 0.00, 54.07, 45.93, 8.13 +-0.40, 0.00, 49.07, 50.93, -1.85 +-0.46, 0.00, 54.07, 45.93, 8.14 +-0.40, 0.00, 49.08, 50.92, -1.85 +-0.40, 0.00, 51.55, 48.45, 3.10 +-0.40, 0.00, 51.55, 48.45, 3.10 +-0.26, 0.00, 46.51, 53.49, -6.98 +-0.26, 0.00, 51.45, 48.55, 2.91 +-0.26, 0.00, 51.46, 48.54, 2.91 +-0.26, 0.00, 51.46, 48.54, 2.91 +-0.26, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 48.94, 51.06, -2.13 +-0.20, 0.00, 51.41, 48.59, 2.82 +-0.20, 0.00, 51.41, 48.59, 2.82 +-0.20, 0.00, 51.41, 48.59, 2.82 +-0.20, 0.00, 51.41, 48.59, 2.82 +-0.20, 0.00, 51.41, 48.59, 2.83 +-0.20, 0.00, 51.41, 48.59, 2.83 +-0.20, 0.00, 51.41, 48.59, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.83 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.20, 0.00, 51.42, 48.58, 2.84 +-0.13, 0.00, 48.90, 51.10, -2.20 +-0.13, 0.00, 51.37, 48.63, 2.75 +-0.13, 0.00, 51.37, 48.63, 2.75 +-0.13, 0.00, 51.37, 48.63, 2.75 +-0.13, 0.00, 51.37, 48.63, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.75 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.76 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.38, 48.62, 2.77 +-0.13, 0.00, 51.39, 48.61, 2.77 +-0.13, 0.00, 51.39, 48.61, 2.77 +-0.13, 0.00, 51.39, 48.61, 2.77 +-0.13, 0.00, 51.39, 48.61, 2.77 +0.00, 0.00, 46.34, 53.66, -7.31 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +0.00, 0.00, 51.29, 48.71, 2.58 +-0.13, 0.00, 56.33, 43.67, 12.66 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.39, 48.61, 2.79 +-0.13, 0.00, 51.40, 48.60, 2.79 +-0.20, 0.00, 53.92, 46.08, 7.83 +-0.20, 0.00, 51.45, 48.55, 2.89 +-0.20, 0.00, 51.45, 48.55, 2.89 +-0.20, 0.00, 51.45, 48.55, 2.89 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.90 +-0.20, 0.00, 51.45, 48.55, 2.91 +-0.20, 0.00, 51.45, 48.55, 2.91 +-0.20, 0.00, 51.45, 48.55, 2.91 +-0.20, 0.00, 51.45, 48.55, 2.91 +-0.20, 0.00, 51.46, 48.54, 2.91 +-0.20, 0.00, 51.46, 48.54, 2.91 +-0.20, 0.00, 51.46, 48.54, 2.91 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.20, 0.00, 51.46, 48.54, 2.92 +-0.26, 0.00, 53.98, 46.02, 7.97 +-0.26, 0.00, 51.51, 48.49, 3.03 +-0.26, 0.00, 51.51, 48.49, 3.03 +-0.26, 0.00, 51.51, 48.49, 3.03 +-0.26, 0.00, 51.52, 48.48, 3.03 +-0.26, 0.00, 51.52, 48.48, 3.03 +-0.26, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 49.00, 51.00, -2.01 +-0.20, 0.00, 51.47, 48.53, 2.94 +-0.20, 0.00, 51.47, 48.53, 2.94 +-0.20, 0.00, 51.47, 48.53, 2.94 +-0.20, 0.00, 51.47, 48.53, 2.94 +-0.20, 0.00, 51.47, 48.53, 2.95 +-0.20, 0.00, 51.47, 48.53, 2.95 +-0.20, 0.00, 51.47, 48.53, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.95 +-0.20, 0.00, 51.48, 48.52, 2.96 +-0.26, 0.00, 54.00, 46.00, 8.00 +-0.20, 0.00, 49.01, 50.99, -1.98 +-0.26, 0.00, 54.00, 46.00, 8.00 +-0.26, 0.00, 51.53, 48.47, 3.06 +-0.26, 0.00, 51.53, 48.47, 3.06 +-0.26, 0.00, 51.53, 48.47, 3.07 +-0.20, 0.00, 49.01, 50.99, -1.97 +-0.20, 0.00, 51.49, 48.51, 2.97 +-0.20, 0.00, 51.49, 48.51, 2.97 +-0.20, 0.00, 51.49, 48.51, 2.97 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.98 +-0.20, 0.00, 51.49, 48.51, 2.99 +-0.20, 0.00, 51.49, 48.51, 2.99 +-0.20, 0.00, 51.49, 48.51, 2.99 +-0.20, 0.00, 51.49, 48.51, 2.99 +-0.20, 0.00, 51.50, 48.50, 2.99 +-0.26, 0.00, 54.02, 45.98, 8.04 +-0.26, 0.00, 51.55, 48.45, 3.09 +-0.26, 0.00, 51.55, 48.45, 3.10 +-0.26, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 49.03, 50.97, -1.94 +-0.20, 0.00, 51.50, 48.50, 3.00 +-0.20, 0.00, 51.50, 48.50, 3.00 +-0.20, 0.00, 51.50, 48.50, 3.01 +-0.20, 0.00, 51.50, 48.50, 3.01 +-0.20, 0.00, 51.50, 48.50, 3.01 +-0.20, 0.00, 51.50, 48.50, 3.01 +-0.20, 0.00, 51.51, 48.49, 3.01 +-0.20, 0.00, 51.51, 48.49, 3.01 +-0.20, 0.00, 51.51, 48.49, 3.01 +-0.20, 0.00, 51.51, 48.49, 3.02 +-0.20, 0.00, 51.51, 48.49, 3.02 +-0.20, 0.00, 51.51, 48.49, 3.02 +-0.26, 0.00, 54.03, 45.97, 8.06 +-0.26, 0.00, 51.56, 48.44, 3.12 +-0.26, 0.00, 51.56, 48.44, 3.12 +-0.26, 0.00, 51.56, 48.44, 3.13 +-0.26, 0.00, 51.56, 48.44, 3.13 +-0.26, 0.00, 51.56, 48.44, 3.13 +-0.26, 0.00, 51.57, 48.43, 3.13 +-0.26, 0.00, 51.57, 48.43, 3.13 +-0.20, 0.00, 49.05, 50.95, -1.91 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.04 +-0.20, 0.00, 51.52, 48.48, 3.05 +-0.20, 0.00, 51.52, 48.48, 3.05 +-0.26, 0.00, 54.05, 45.95, 8.09 +-0.26, 0.00, 51.58, 48.42, 3.15 +-0.26, 0.00, 51.58, 48.42, 3.15 +-0.26, 0.00, 51.58, 48.42, 3.15 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 51.58, 48.42, 3.17 +-0.20, 0.00, 49.06, 50.94, -1.87 +-0.20, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.08 +-0.20, 0.00, 51.54, 48.46, 3.09 +-0.20, 0.00, 51.54, 48.46, 3.09 +-0.20, 0.00, 51.54, 48.46, 3.09 +-0.20, 0.00, 51.54, 48.46, 3.09 +-0.20, 0.00, 51.55, 48.45, 3.09 +-0.20, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 49.03, 50.97, -1.95 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.50, 48.50, 3.01 +-0.13, 0.00, 51.51, 48.49, 3.01 +0.00, 0.00, 46.46, 53.54, -7.07 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.00, 0.00, 51.41, 48.59, 2.81 +0.07, 0.00, 48.88, 51.12, -2.23 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.36, 48.64, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.07, 0.00, 51.35, 48.65, 2.71 +0.13, 0.00, 48.83, 51.17, -2.34 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.59 +0.13, 0.00, 51.29, 48.71, 2.58 +0.13, 0.00, 51.29, 48.71, 2.58 +0.26, 0.00, 46.25, 53.75, -7.50 +0.26, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 51.19, 48.81, 2.37 +0.26, 0.00, 51.19, 48.81, 2.37 +0.26, 0.00, 51.18, 48.82, 2.37 +0.26, 0.00, 51.18, 48.82, 2.37 +0.26, 0.00, 51.18, 48.82, 2.37 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 51.18, 48.82, 2.35 +0.26, 0.00, 51.18, 48.82, 2.35 +0.26, 0.00, 51.18, 48.82, 2.35 +0.26, 0.00, 51.17, 48.83, 2.35 +0.33, 0.00, 48.65, 51.35, -2.70 +0.26, 0.00, 53.64, 46.36, 7.29 +0.33, 0.00, 48.65, 51.35, -2.70 +0.33, 0.00, 51.12, 48.88, 2.24 +0.26, 0.00, 53.64, 46.36, 7.28 +0.26, 0.00, 51.17, 48.83, 2.33 +0.26, 0.00, 51.17, 48.83, 2.33 +0.26, 0.00, 51.17, 48.83, 2.33 +0.26, 0.00, 51.16, 48.84, 2.33 +0.26, 0.00, 51.16, 48.84, 2.33 +0.26, 0.00, 51.16, 48.84, 2.32 +0.33, 0.00, 48.64, 51.36, -2.72 +0.26, 0.00, 53.63, 46.37, 7.26 +0.33, 0.00, 48.64, 51.36, -2.72 +0.33, 0.00, 51.11, 48.89, 2.22 +0.33, 0.00, 51.11, 48.89, 2.21 +0.33, 0.00, 51.11, 48.89, 2.21 +0.33, 0.00, 51.10, 48.90, 2.21 +0.33, 0.00, 51.10, 48.90, 2.21 +0.33, 0.00, 51.10, 48.90, 2.20 +0.33, 0.00, 51.10, 48.90, 2.20 +0.33, 0.00, 51.10, 48.90, 2.20 +0.33, 0.00, 51.10, 48.90, 2.20 +0.33, 0.00, 51.10, 48.90, 2.19 +0.33, 0.00, 51.10, 48.90, 2.19 +0.33, 0.00, 51.09, 48.91, 2.19 +0.33, 0.00, 51.09, 48.91, 2.19 +0.33, 0.00, 51.09, 48.91, 2.18 +0.33, 0.00, 51.09, 48.91, 2.18 +0.33, 0.00, 51.09, 48.91, 2.18 +0.33, 0.00, 51.09, 48.91, 2.18 +0.33, 0.00, 51.09, 48.91, 2.17 +0.33, 0.00, 51.09, 48.91, 2.17 +0.33, 0.00, 51.08, 48.92, 2.17 +0.33, 0.00, 51.08, 48.92, 2.17 +0.33, 0.00, 51.08, 48.92, 2.16 +0.33, 0.00, 51.08, 48.92, 2.16 +0.33, 0.00, 51.08, 48.92, 2.16 +0.40, 0.00, 48.56, 51.44, -2.89 +0.40, 0.00, 51.03, 48.97, 2.06 +0.40, 0.00, 51.03, 48.97, 2.05 +0.40, 0.00, 51.02, 48.98, 2.05 +0.40, 0.00, 51.02, 48.98, 2.05 +0.40, 0.00, 51.02, 48.98, 2.04 +0.40, 0.00, 51.02, 48.98, 2.04 +0.40, 0.00, 51.02, 48.98, 2.04 +0.40, 0.00, 51.02, 48.98, 2.03 +0.40, 0.00, 51.02, 48.98, 2.03 +0.53, 0.00, 45.97, 54.03, -8.06 +0.53, 0.00, 50.91, 49.09, 1.83 +0.53, 0.00, 50.91, 49.09, 1.82 +0.53, 0.00, 50.91, 49.09, 1.82 +0.53, 0.00, 50.91, 49.09, 1.81 +0.59, 0.00, 48.38, 51.62, -3.23 +0.59, 0.00, 50.85, 49.15, 1.71 +0.59, 0.00, 50.85, 49.15, 1.70 +0.59, 0.00, 50.85, 49.15, 1.70 +0.59, 0.00, 50.85, 49.15, 1.69 +0.66, 0.00, 48.32, 51.68, -3.36 +0.66, 0.00, 50.79, 49.21, 1.58 +0.66, 0.00, 50.79, 49.21, 1.58 +0.66, 0.00, 50.79, 49.21, 1.57 +0.66, 0.00, 50.78, 49.22, 1.57 +0.66, 0.00, 50.78, 49.22, 1.56 +0.79, 0.00, 45.74, 54.26, -8.53 +0.79, 0.00, 50.68, 49.32, 1.35 +0.79, 0.00, 50.67, 49.33, 1.35 +0.79, 0.00, 50.67, 49.33, 1.34 +0.79, 0.00, 50.67, 49.33, 1.34 +0.79, 0.00, 50.67, 49.33, 1.33 +0.79, 0.00, 50.66, 49.34, 1.32 +0.86, 0.00, 48.14, 51.86, -3.72 +0.86, 0.00, 50.61, 49.39, 1.21 +0.86, 0.00, 50.60, 49.40, 1.21 +0.86, 0.00, 50.60, 49.40, 1.20 +0.86, 0.00, 50.60, 49.40, 1.19 +0.86, 0.00, 50.59, 49.41, 1.19 +0.86, 0.00, 50.59, 49.41, 1.18 +0.86, 0.00, 50.59, 49.41, 1.17 +0.92, 0.00, 48.06, 51.94, -3.88 +0.92, 0.00, 50.53, 49.47, 1.06 +0.92, 0.00, 50.53, 49.47, 1.05 +0.92, 0.00, 50.52, 49.48, 1.05 +0.92, 0.00, 50.52, 49.48, 1.04 +0.92, 0.00, 50.52, 49.48, 1.03 +0.92, 0.00, 50.51, 49.49, 1.03 +0.92, 0.00, 50.51, 49.49, 1.02 +0.92, 0.00, 50.51, 49.49, 1.01 +0.92, 0.00, 50.50, 49.50, 1.01 +0.92, 0.00, 50.50, 49.50, 1.00 +0.92, 0.00, 50.50, 49.50, 0.99 +0.92, 0.00, 50.49, 49.51, 0.99 +0.92, 0.00, 50.49, 49.51, 0.98 +0.92, 0.00, 50.49, 49.51, 0.97 +0.92, 0.00, 50.48, 49.52, 0.96 +0.92, 0.00, 50.48, 49.52, 0.96 +0.92, 0.00, 50.48, 49.52, 0.95 +0.92, 0.00, 50.47, 49.53, 0.94 +0.92, 0.00, 50.47, 49.53, 0.94 +0.92, 0.00, 50.47, 49.53, 0.93 +0.86, 0.00, 52.98, 47.02, 5.97 +0.86, 0.00, 50.51, 49.49, 1.02 +0.86, 0.00, 50.50, 49.50, 1.01 +0.86, 0.00, 50.50, 49.50, 1.00 +0.86, 0.00, 50.50, 49.50, 1.00 +0.86, 0.00, 50.50, 49.50, 0.99 +0.79, 0.00, 53.01, 46.99, 6.03 +0.79, 0.00, 50.54, 49.46, 1.08 +0.79, 0.00, 50.54, 49.46, 1.07 +0.79, 0.00, 50.53, 49.47, 1.07 +0.79, 0.00, 50.53, 49.47, 1.06 +0.79, 0.00, 50.53, 49.47, 1.05 +0.66, 0.00, 55.57, 44.43, 11.13 +0.66, 0.00, 50.62, 49.38, 1.24 +0.66, 0.00, 50.62, 49.38, 1.24 +0.66, 0.00, 50.62, 49.38, 1.23 +0.66, 0.00, 50.61, 49.39, 1.23 +0.66, 0.00, 50.61, 49.39, 1.22 +0.66, 0.00, 50.61, 49.39, 1.22 +0.66, 0.00, 50.61, 49.39, 1.21 +0.66, 0.00, 50.60, 49.40, 1.21 +0.66, 0.00, 50.60, 49.40, 1.20 +0.66, 0.00, 50.60, 49.40, 1.20 +0.59, 0.00, 53.12, 46.88, 6.24 +0.59, 0.00, 50.64, 49.36, 1.29 +0.59, 0.00, 50.64, 49.36, 1.28 +0.59, 0.00, 50.64, 49.36, 1.28 +0.59, 0.00, 50.64, 49.36, 1.27 +0.59, 0.00, 50.63, 49.37, 1.27 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.26 +0.59, 0.00, 50.63, 49.37, 1.25 +0.53, 0.00, 53.15, 46.85, 6.29 +0.53, 0.00, 50.67, 49.33, 1.34 +0.53, 0.00, 50.67, 49.33, 1.34 +0.53, 0.00, 50.67, 49.33, 1.33 +0.53, 0.00, 50.67, 49.33, 1.33 +0.53, 0.00, 50.66, 49.34, 1.33 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.31 +0.53, 0.00, 50.66, 49.34, 1.31 +0.59, 0.00, 48.13, 51.87, -3.74 +0.53, 0.00, 53.12, 46.88, 6.25 +0.53, 0.00, 50.65, 49.35, 1.30 +0.53, 0.00, 50.65, 49.35, 1.29 +0.53, 0.00, 50.65, 49.35, 1.29 +0.53, 0.00, 50.64, 49.36, 1.29 +0.53, 0.00, 50.64, 49.36, 1.28 +0.40, 0.00, 55.68, 44.32, 11.37 +0.40, 0.00, 50.74, 49.26, 1.47 +0.40, 0.00, 50.74, 49.26, 1.47 +0.40, 0.00, 50.73, 49.27, 1.47 +0.40, 0.00, 50.73, 49.27, 1.47 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.45 +0.40, 0.00, 50.73, 49.27, 1.45 +0.53, 0.00, 45.68, 54.32, -8.64 +0.53, 0.00, 50.62, 49.38, 1.25 +0.53, 0.00, 50.62, 49.38, 1.24 +0.53, 0.00, 50.62, 49.38, 1.24 +0.53, 0.00, 50.62, 49.38, 1.23 +0.53, 0.00, 50.61, 49.39, 1.23 +0.40, 0.00, 55.66, 44.34, 11.31 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.41 +0.40, 0.00, 50.70, 49.30, 1.41 +0.33, 0.00, 53.22, 46.78, 6.45 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.49 +0.33, 0.00, 50.75, 49.25, 1.49 +0.40, 0.00, 48.22, 51.78, -3.55 +0.33, 0.00, 53.21, 46.79, 6.43 +0.40, 0.00, 48.22, 51.78, -3.56 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.37 +0.40, 0.00, 50.69, 49.31, 1.37 +0.40, 0.00, 50.68, 49.32, 1.37 +0.33, 0.00, 53.20, 46.80, 6.41 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.45 +0.33, 0.00, 50.73, 49.27, 1.45 +0.33, 0.00, 50.72, 49.28, 1.45 +0.33, 0.00, 50.72, 49.28, 1.45 +0.33, 0.00, 50.72, 49.28, 1.44 +0.33, 0.00, 50.72, 49.28, 1.44 +0.33, 0.00, 50.72, 49.28, 1.44 +0.33, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 48.19, 51.81, -3.61 +0.33, 0.00, 53.19, 46.81, 6.37 +0.33, 0.00, 50.71, 49.29, 1.43 +0.33, 0.00, 50.71, 49.29, 1.43 +0.33, 0.00, 50.71, 49.29, 1.42 +0.33, 0.00, 50.71, 49.29, 1.42 +0.33, 0.00, 50.71, 49.29, 1.42 +0.33, 0.00, 50.71, 49.29, 1.42 +0.26, 0.00, 53.23, 46.77, 6.46 +0.26, 0.00, 50.76, 49.24, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 50.75, 49.25, 1.49 +0.26, 0.00, 50.75, 49.25, 1.49 +0.26, 0.00, 50.75, 49.25, 1.49 +0.26, 0.00, 50.74, 49.26, 1.49 +0.26, 0.00, 50.74, 49.26, 1.49 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.47 +0.26, 0.00, 50.74, 49.26, 1.47 +0.26, 0.00, 50.74, 49.26, 1.47 +0.26, 0.00, 50.73, 49.27, 1.47 +0.26, 0.00, 50.73, 49.27, 1.47 +0.26, 0.00, 50.73, 49.27, 1.46 +0.13, 0.00, 55.77, 44.23, 11.55 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.66 +0.13, 0.00, 50.83, 49.17, 1.65 +0.13, 0.00, 50.83, 49.17, 1.65 +0.13, 0.00, 50.83, 49.17, 1.65 +0.13, 0.00, 50.83, 49.17, 1.65 +0.26, 0.00, 45.78, 54.22, -8.44 +0.26, 0.00, 50.72, 49.28, 1.45 +0.13, 0.00, 55.77, 44.23, 11.53 +0.13, 0.00, 50.82, 49.18, 1.65 +0.13, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 45.78, 54.22, -8.44 +0.26, 0.00, 50.72, 49.28, 1.44 +0.13, 0.00, 55.76, 44.24, 11.53 +0.13, 0.00, 50.82, 49.18, 1.64 +0.26, 0.00, 45.78, 54.22, -8.45 +0.13, 0.00, 55.76, 44.24, 11.52 +0.13, 0.00, 50.82, 49.18, 1.63 +0.26, 0.00, 45.77, 54.23, -8.45 +0.13, 0.00, 55.76, 44.24, 11.52 +0.26, 0.00, 45.77, 54.23, -8.46 +0.26, 0.00, 50.72, 49.28, 1.43 +0.13, 0.00, 55.76, 44.24, 11.51 +0.13, 0.00, 50.81, 49.19, 1.63 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.13, 0.00, 50.81, 49.19, 1.62 +0.07, 0.00, 53.33, 46.67, 6.66 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 50.85, 49.15, 1.71 +0.07, 0.00, 50.85, 49.15, 1.71 +0.07, 0.00, 50.85, 49.15, 1.71 +0.00, 0.00, 53.38, 46.62, 6.75 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +0.00, 0.00, 50.90, 49.10, 1.81 +-0.13, 0.00, 55.95, 44.05, 11.89 +-0.13, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 51.01, 48.99, 2.01 +-0.13, 0.00, 51.01, 48.99, 2.01 +-0.20, 0.00, 53.53, 46.47, 7.06 +-0.20, 0.00, 51.06, 48.94, 2.11 +-0.20, 0.00, 51.06, 48.94, 2.11 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.20, 0.00, 51.06, 48.94, 2.12 +-0.26, 0.00, 53.58, 46.42, 7.17 +-0.26, 0.00, 51.11, 48.89, 2.23 +-0.26, 0.00, 51.11, 48.89, 2.23 +-0.26, 0.00, 51.12, 48.88, 2.23 +-0.26, 0.00, 51.12, 48.88, 2.23 +-0.26, 0.00, 51.12, 48.88, 2.23 +-0.40, 0.00, 56.16, 43.84, 12.32 +-0.40, 0.00, 51.22, 48.78, 2.44 +-0.40, 0.00, 51.22, 48.78, 2.44 +-0.40, 0.00, 51.22, 48.78, 2.44 +-0.40, 0.00, 51.22, 48.78, 2.45 +-0.40, 0.00, 51.23, 48.77, 2.45 +-0.40, 0.00, 51.23, 48.77, 2.45 +-0.46, 0.00, 53.75, 46.25, 7.50 +-0.46, 0.00, 51.28, 48.72, 2.56 +-0.46, 0.00, 51.28, 48.72, 2.56 +-0.46, 0.00, 51.28, 48.72, 2.57 +-0.46, 0.00, 51.28, 48.72, 2.57 +-0.46, 0.00, 51.29, 48.71, 2.57 +-0.46, 0.00, 51.29, 48.71, 2.58 +-0.46, 0.00, 51.29, 48.71, 2.58 +-0.46, 0.00, 51.29, 48.71, 2.58 +-0.46, 0.00, 51.29, 48.71, 2.59 +-0.46, 0.00, 51.29, 48.71, 2.59 +-0.46, 0.00, 51.30, 48.70, 2.59 +-0.46, 0.00, 51.30, 48.70, 2.60 +-0.46, 0.00, 51.30, 48.70, 2.60 +-0.46, 0.00, 51.30, 48.70, 2.60 +-0.46, 0.00, 51.30, 48.70, 2.61 +-0.46, 0.00, 51.31, 48.69, 2.61 +-0.46, 0.00, 51.31, 48.69, 2.61 +-0.46, 0.00, 51.31, 48.69, 2.62 +-0.46, 0.00, 51.31, 48.69, 2.62 +-0.46, 0.00, 51.31, 48.69, 2.62 +-0.46, 0.00, 51.31, 48.69, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.65 +-0.46, 0.00, 51.32, 48.68, 2.65 +-0.46, 0.00, 51.33, 48.67, 2.65 +-0.46, 0.00, 51.33, 48.67, 2.66 +-0.46, 0.00, 51.33, 48.67, 2.66 +-0.46, 0.00, 51.33, 48.67, 2.66 +-0.46, 0.00, 51.33, 48.67, 2.67 +-0.46, 0.00, 51.33, 48.67, 2.67 +-0.53, 0.00, 53.86, 46.14, 7.72 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.46, 0.00, 48.87, 51.13, -2.26 +-0.53, 0.00, 53.87, 46.13, 7.74 +-0.53, 0.00, 51.40, 48.60, 2.80 +-0.46, 0.00, 48.88, 51.12, -2.24 +-0.46, 0.00, 51.35, 48.65, 2.70 +-0.46, 0.00, 51.35, 48.65, 2.71 +-0.46, 0.00, 51.36, 48.64, 2.71 +-0.46, 0.00, 51.36, 48.64, 2.71 +-0.46, 0.00, 51.36, 48.64, 2.72 +-0.46, 0.00, 51.36, 48.64, 2.72 +-0.46, 0.00, 51.36, 48.64, 2.72 +-0.46, 0.00, 51.36, 48.64, 2.73 +-0.46, 0.00, 51.37, 48.63, 2.73 +-0.46, 0.00, 51.37, 48.63, 2.73 +-0.53, 0.00, 53.89, 46.11, 7.78 +-0.53, 0.00, 51.42, 48.58, 2.84 +-0.53, 0.00, 51.42, 48.58, 2.85 +-0.53, 0.00, 51.42, 48.58, 2.85 +-0.53, 0.00, 51.43, 48.57, 2.85 +-0.53, 0.00, 51.43, 48.57, 2.86 +-0.53, 0.00, 51.43, 48.57, 2.86 +-0.53, 0.00, 51.43, 48.57, 2.87 +-0.53, 0.00, 51.43, 48.57, 2.87 +-0.53, 0.00, 51.44, 48.56, 2.87 +-0.53, 0.00, 51.44, 48.56, 2.88 +-0.53, 0.00, 51.44, 48.56, 2.88 +-0.53, 0.00, 51.44, 48.56, 2.89 +-0.53, 0.00, 51.44, 48.56, 2.89 +-0.53, 0.00, 51.45, 48.55, 2.89 +-0.53, 0.00, 51.45, 48.55, 2.90 +-0.53, 0.00, 51.45, 48.55, 2.90 +-0.53, 0.00, 51.45, 48.55, 2.90 +-0.53, 0.00, 51.45, 48.55, 2.91 +-0.53, 0.00, 51.46, 48.54, 2.91 +-0.53, 0.00, 51.46, 48.54, 2.92 +-0.53, 0.00, 51.46, 48.54, 2.92 +-0.53, 0.00, 51.46, 48.54, 2.92 +-0.66, 0.00, 56.51, 43.49, 13.02 +-0.66, 0.00, 51.57, 48.43, 3.13 +-0.66, 0.00, 51.57, 48.43, 3.14 +-0.66, 0.00, 51.57, 48.43, 3.14 +-0.66, 0.00, 51.57, 48.43, 3.15 +-0.66, 0.00, 51.58, 48.42, 3.15 +-0.66, 0.00, 51.58, 48.42, 3.16 +-0.66, 0.00, 51.58, 48.42, 3.16 +-0.66, 0.00, 51.58, 48.42, 3.17 +-0.66, 0.00, 51.59, 48.41, 3.17 +-0.66, 0.00, 51.59, 48.41, 3.18 +-0.66, 0.00, 51.59, 48.41, 3.18 +-0.53, 0.00, 46.55, 53.45, -6.90 +-0.53, 0.00, 51.50, 48.50, 2.99 +-0.53, 0.00, 51.50, 48.50, 3.00 +-0.53, 0.00, 51.50, 48.50, 3.00 +-0.53, 0.00, 51.50, 48.50, 3.00 +-0.53, 0.00, 51.50, 48.50, 3.01 +-0.53, 0.00, 51.51, 48.49, 3.01 +-0.53, 0.00, 51.51, 48.49, 3.02 +-0.53, 0.00, 51.51, 48.49, 3.02 +-0.53, 0.00, 51.51, 48.49, 3.02 +-0.66, 0.00, 56.56, 43.44, 13.11 +-0.66, 0.00, 51.62, 48.38, 3.23 +-0.66, 0.00, 51.62, 48.38, 3.24 +-0.66, 0.00, 51.62, 48.38, 3.24 +-0.66, 0.00, 51.62, 48.38, 3.25 +-0.66, 0.00, 51.63, 48.37, 3.25 +-0.66, 0.00, 51.63, 48.37, 3.26 +-0.53, 0.00, 46.59, 53.41, -6.83 +-0.53, 0.00, 51.53, 48.47, 3.07 +-0.53, 0.00, 51.53, 48.47, 3.07 +-0.53, 0.00, 51.54, 48.46, 3.07 +-0.53, 0.00, 51.54, 48.46, 3.08 +-0.53, 0.00, 51.54, 48.46, 3.08 +-0.53, 0.00, 51.54, 48.46, 3.09 +-0.53, 0.00, 51.54, 48.46, 3.09 +-0.53, 0.00, 51.55, 48.45, 3.09 +-0.53, 0.00, 51.55, 48.45, 3.10 +-0.53, 0.00, 51.55, 48.45, 3.10 +-0.53, 0.00, 51.55, 48.45, 3.11 +-0.53, 0.00, 51.55, 48.45, 3.11 +-0.53, 0.00, 51.56, 48.44, 3.11 +-0.53, 0.00, 51.56, 48.44, 3.12 +-0.66, 0.00, 56.60, 43.40, 13.21 +-0.66, 0.00, 51.66, 48.34, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.33 +-0.66, 0.00, 51.67, 48.33, 3.34 +-0.66, 0.00, 51.67, 48.33, 3.34 +-0.66, 0.00, 51.67, 48.33, 3.35 +-0.53, 0.00, 46.63, 53.37, -6.73 +-0.66, 0.00, 56.62, 43.38, 13.25 +-0.66, 0.00, 51.68, 48.32, 3.36 +-0.53, 0.00, 46.64, 53.36, -6.72 +-0.53, 0.00, 51.59, 48.41, 3.17 +-0.53, 0.00, 51.59, 48.41, 3.18 +-0.53, 0.00, 51.59, 48.41, 3.18 +-0.53, 0.00, 51.59, 48.41, 3.19 +-0.66, 0.00, 56.64, 43.36, 13.28 +-0.53, 0.00, 46.65, 53.35, -6.69 +-0.66, 0.00, 56.64, 43.36, 13.28 +-0.66, 0.00, 51.70, 48.30, 3.40 +-0.66, 0.00, 51.70, 48.30, 3.41 +-0.66, 0.00, 51.71, 48.29, 3.41 +-0.66, 0.00, 51.71, 48.29, 3.42 +-0.66, 0.00, 51.71, 48.29, 3.42 +-0.66, 0.00, 51.71, 48.29, 3.43 +-0.66, 0.00, 51.72, 48.28, 3.43 +-0.66, 0.00, 51.72, 48.28, 3.44 +-0.66, 0.00, 51.72, 48.28, 3.44 +-0.66, 0.00, 51.72, 48.28, 3.45 +-0.73, 0.00, 54.25, 45.75, 8.49 +-0.73, 0.00, 51.78, 48.22, 3.56 +-0.73, 0.00, 51.78, 48.22, 3.56 +-0.73, 0.00, 51.78, 48.22, 3.57 +-0.73, 0.00, 51.79, 48.21, 3.57 +-0.73, 0.00, 51.79, 48.21, 3.58 +-0.73, 0.00, 51.79, 48.21, 3.58 +-0.73, 0.00, 51.79, 48.21, 3.59 +-0.73, 0.00, 51.80, 48.20, 3.59 +-0.73, 0.00, 51.80, 48.20, 3.60 +-0.73, 0.00, 51.80, 48.20, 3.61 +-0.73, 0.00, 51.81, 48.19, 3.61 +-0.73, 0.00, 51.81, 48.19, 3.62 +-0.73, 0.00, 51.81, 48.19, 3.62 +-0.73, 0.00, 51.81, 48.19, 3.63 +-0.79, 0.00, 54.34, 45.66, 8.68 +-0.79, 0.00, 51.87, 48.13, 3.74 +-0.79, 0.00, 51.87, 48.13, 3.74 +-0.79, 0.00, 51.87, 48.13, 3.75 +-0.79, 0.00, 51.88, 48.12, 3.76 +-0.79, 0.00, 51.88, 48.12, 3.76 +-0.92, 0.00, 56.93, 43.07, 13.85 +-0.79, 0.00, 46.94, 53.06, -6.11 +-0.92, 0.00, 56.93, 43.07, 13.87 +-0.92, 0.00, 51.99, 48.01, 3.99 +-0.92, 0.00, 52.00, 48.00, 3.99 +-0.92, 0.00, 52.00, 48.00, 4.00 +-0.92, 0.00, 52.00, 48.00, 4.01 +-0.92, 0.00, 52.01, 47.99, 4.01 +-0.92, 0.00, 52.01, 47.99, 4.02 +-0.92, 0.00, 52.01, 47.99, 4.03 +-0.99, 0.00, 54.54, 45.46, 9.08 +-0.92, 0.00, 49.55, 50.45, -0.90 +-0.99, 0.00, 54.55, 45.45, 9.09 +-0.99, 0.00, 52.08, 47.92, 4.16 +-0.99, 0.00, 52.08, 47.92, 4.16 +-0.99, 0.00, 52.09, 47.91, 4.17 +-0.99, 0.00, 52.09, 47.91, 4.18 +-0.99, 0.00, 52.09, 47.91, 4.19 +-0.99, 0.00, 52.10, 47.90, 4.19 +-0.99, 0.00, 52.10, 47.90, 4.20 +-0.99, 0.00, 52.10, 47.90, 4.21 +-0.99, 0.00, 52.11, 47.89, 4.21 +-0.99, 0.00, 52.11, 47.89, 4.22 +-0.99, 0.00, 52.11, 47.89, 4.23 +-0.99, 0.00, 52.12, 47.88, 4.24 +-0.99, 0.00, 52.12, 47.88, 4.24 +-0.99, 0.00, 52.13, 47.87, 4.25 +-0.99, 0.00, 52.13, 47.87, 4.26 +-0.99, 0.00, 52.13, 47.87, 4.27 +-0.99, 0.00, 52.14, 47.86, 4.27 +-0.99, 0.00, 52.14, 47.86, 4.28 +-0.99, 0.00, 52.14, 47.86, 4.29 +-0.99, 0.00, 52.15, 47.85, 4.30 +-1.05, 0.00, 54.67, 45.33, 9.35 +-1.05, 0.00, 52.21, 47.79, 4.41 +-1.05, 0.00, 52.21, 47.79, 4.42 +-1.05, 0.00, 52.21, 47.79, 4.43 +-1.05, 0.00, 52.22, 47.78, 4.43 +-1.05, 0.00, 52.22, 47.78, 4.44 +-1.05, 0.00, 52.23, 47.77, 4.45 +-1.05, 0.00, 52.23, 47.77, 4.46 +-1.05, 0.00, 52.23, 47.77, 4.47 +-1.05, 0.00, 52.24, 47.76, 4.47 +-1.05, 0.00, 52.24, 47.76, 4.48 +-0.99, 0.00, 49.72, 50.28, -0.55 +-0.99, 0.00, 52.20, 47.80, 4.40 +-0.99, 0.00, 52.20, 47.80, 4.41 +-0.99, 0.00, 52.21, 47.79, 4.41 +-0.99, 0.00, 52.21, 47.79, 4.42 +-0.99, 0.00, 52.21, 47.79, 4.43 +-0.99, 0.00, 52.22, 47.78, 4.44 +-0.99, 0.00, 52.22, 47.78, 4.44 +-0.99, 0.00, 52.23, 47.77, 4.45 +-0.99, 0.00, 52.23, 47.77, 4.46 +-0.99, 0.00, 52.23, 47.77, 4.47 +-0.99, 0.00, 52.24, 47.76, 4.47 +-0.99, 0.00, 52.24, 47.76, 4.48 +-0.92, 0.00, 49.72, 50.28, -0.56 +-0.92, 0.00, 52.20, 47.80, 4.39 +-0.92, 0.00, 52.20, 47.80, 4.40 +-0.92, 0.00, 52.20, 47.80, 4.41 +-0.92, 0.00, 52.21, 47.79, 4.42 +-0.92, 0.00, 52.21, 47.79, 4.42 +-0.79, 0.00, 47.17, 52.83, -5.66 +-0.79, 0.00, 52.12, 47.88, 4.24 +-0.79, 0.00, 52.12, 47.88, 4.24 +-0.79, 0.00, 52.12, 47.88, 4.25 +-0.79, 0.00, 52.13, 47.87, 4.25 +-0.79, 0.00, 52.13, 47.87, 4.26 +-0.73, 0.00, 49.61, 50.39, -0.78 +-0.73, 0.00, 52.09, 47.91, 4.17 +-0.73, 0.00, 52.09, 47.91, 4.18 +-0.73, 0.00, 52.09, 47.91, 4.18 +-0.66, 0.00, 49.57, 50.43, -0.85 +-0.66, 0.00, 52.05, 47.95, 4.09 +-0.66, 0.00, 52.05, 47.95, 4.10 +-0.66, 0.00, 52.05, 47.95, 4.10 +-0.66, 0.00, 52.05, 47.95, 4.11 +-0.66, 0.00, 52.06, 47.94, 4.11 +-0.53, 0.00, 47.02, 52.98, -5.97 +-0.53, 0.00, 51.96, 48.04, 3.92 +-0.53, 0.00, 51.96, 48.04, 3.93 +-0.53, 0.00, 51.97, 48.03, 3.93 +-0.53, 0.00, 51.97, 48.03, 3.94 +-0.53, 0.00, 51.97, 48.03, 3.94 +-0.46, 0.00, 49.45, 50.55, -1.10 +-0.46, 0.00, 51.92, 48.08, 3.85 +-0.46, 0.00, 51.93, 48.07, 3.85 +-0.46, 0.00, 51.93, 48.07, 3.86 +-0.46, 0.00, 51.93, 48.07, 3.86 +-0.40, 0.00, 49.41, 50.59, -1.18 +-0.40, 0.00, 51.88, 48.12, 3.77 +-0.40, 0.00, 51.88, 48.12, 3.77 +-0.40, 0.00, 51.89, 48.11, 3.77 +-0.40, 0.00, 51.89, 48.11, 3.77 +-0.26, 0.00, 46.85, 53.15, -6.31 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.59 +-0.26, 0.00, 51.79, 48.21, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.20, 0.00, 49.28, 50.72, -1.45 +-0.26, 0.00, 54.27, 45.73, 8.54 +-0.20, 0.00, 49.28, 50.72, -1.44 +-0.20, 0.00, 51.75, 48.25, 3.50 +-0.20, 0.00, 51.75, 48.25, 3.50 +-0.20, 0.00, 51.75, 48.25, 3.51 +-0.20, 0.00, 51.75, 48.25, 3.51 +-0.20, 0.00, 51.75, 48.25, 3.51 +-0.20, 0.00, 51.75, 48.25, 3.51 +-0.13, 0.00, 49.23, 50.77, -1.53 +-0.13, 0.00, 51.71, 48.29, 3.41 +-0.13, 0.00, 51.71, 48.29, 3.41 +0.00, 0.00, 46.66, 53.34, -6.67 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.00, 0.00, 51.61, 48.39, 3.22 +0.07, 0.00, 49.09, 50.91, -1.83 +0.07, 0.00, 51.56, 48.44, 3.12 +0.07, 0.00, 51.56, 48.44, 3.12 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.56, 48.44, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.07, 0.00, 51.55, 48.45, 3.11 +0.13, 0.00, 49.03, 50.97, -1.94 +0.13, 0.00, 51.50, 48.50, 3.01 +0.13, 0.00, 51.50, 48.50, 3.01 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 54.02, 45.98, 8.04 +0.07, 0.00, 51.55, 48.45, 3.09 +0.07, 0.00, 51.55, 48.45, 3.09 +0.07, 0.00, 51.55, 48.45, 3.09 +0.13, 0.00, 49.03, 50.97, -1.95 +0.07, 0.00, 54.02, 45.98, 8.04 +0.13, 0.00, 49.02, 50.98, -1.95 +0.13, 0.00, 51.50, 48.50, 2.99 +0.13, 0.00, 51.50, 48.50, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.99 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.98 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.49, 48.51, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.97 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.13, 0.00, 51.48, 48.52, 2.96 +0.07, 0.00, 54.00, 46.00, 8.00 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.53, 48.47, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.05 +0.07, 0.00, 51.52, 48.48, 3.04 +0.00, 0.00, 54.04, 45.96, 8.09 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +0.00, 0.00, 51.57, 48.43, 3.14 +-0.13, 0.00, 56.62, 43.38, 13.23 +-0.13, 0.00, 51.67, 48.33, 3.34 +-0.13, 0.00, 51.67, 48.33, 3.34 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.67, 48.33, 3.35 +-0.13, 0.00, 51.68, 48.32, 3.35 +-0.20, 0.00, 54.20, 45.80, 8.39 +-0.20, 0.00, 51.73, 48.27, 3.45 +-0.20, 0.00, 51.73, 48.27, 3.45 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.46 +-0.20, 0.00, 51.73, 48.27, 3.47 +-0.20, 0.00, 51.73, 48.27, 3.47 +-0.20, 0.00, 51.73, 48.27, 3.47 +-0.20, 0.00, 51.73, 48.27, 3.47 +-0.26, 0.00, 54.26, 45.74, 8.51 +-0.26, 0.00, 51.79, 48.21, 3.57 +-0.26, 0.00, 51.79, 48.21, 3.57 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.58 +-0.26, 0.00, 51.79, 48.21, 3.59 +-0.26, 0.00, 51.79, 48.21, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.59 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.60 +-0.26, 0.00, 51.80, 48.20, 3.61 +-0.26, 0.00, 51.80, 48.20, 3.61 +-0.40, 0.00, 56.85, 43.15, 13.70 +-0.40, 0.00, 51.91, 48.09, 3.81 +-0.40, 0.00, 51.91, 48.09, 3.82 +-0.40, 0.00, 51.91, 48.09, 3.82 +-0.40, 0.00, 51.91, 48.09, 3.82 +-0.26, 0.00, 46.87, 53.13, -6.26 +-0.26, 0.00, 51.81, 48.19, 3.63 +-0.26, 0.00, 51.81, 48.19, 3.63 +-0.26, 0.00, 51.82, 48.18, 3.63 +-0.26, 0.00, 51.82, 48.18, 3.63 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.64 +-0.26, 0.00, 51.82, 48.18, 3.65 +-0.26, 0.00, 51.82, 48.18, 3.65 +-0.26, 0.00, 51.83, 48.17, 3.65 +-0.26, 0.00, 51.83, 48.17, 3.65 +-0.26, 0.00, 51.83, 48.17, 3.65 +-0.20, 0.00, 49.31, 50.69, -1.39 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.56 +-0.20, 0.00, 51.78, 48.22, 3.57 +-0.20, 0.00, 51.78, 48.22, 3.57 +-0.20, 0.00, 51.78, 48.22, 3.57 +-0.20, 0.00, 51.79, 48.21, 3.57 +-0.13, 0.00, 49.26, 50.74, -1.47 +-0.13, 0.00, 51.74, 48.26, 3.47 +-0.13, 0.00, 51.74, 48.26, 3.47 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +-0.13, 0.00, 51.74, 48.26, 3.48 +0.00, 0.00, 46.70, 53.30, -6.60 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 49.12, 50.88, -1.76 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 51.59, 48.41, 3.18 +0.13, 0.00, 49.07, 50.93, -1.87 +0.13, 0.00, 51.54, 48.46, 3.08 +0.13, 0.00, 51.54, 48.46, 3.08 +0.13, 0.00, 51.54, 48.46, 3.08 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.54, 48.46, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.07 +0.13, 0.00, 51.53, 48.47, 3.06 +0.13, 0.00, 51.53, 48.47, 3.06 +0.13, 0.00, 51.53, 48.47, 3.06 +0.13, 0.00, 51.53, 48.47, 3.06 +0.26, 0.00, 46.49, 53.51, -7.03 +0.26, 0.00, 51.43, 48.57, 2.86 +0.26, 0.00, 51.43, 48.57, 2.86 +0.26, 0.00, 51.43, 48.57, 2.86 +0.26, 0.00, 51.43, 48.57, 2.85 +0.26, 0.00, 51.43, 48.57, 2.85 +0.33, 0.00, 48.90, 51.10, -2.19 +0.26, 0.00, 53.90, 46.10, 7.79 +0.33, 0.00, 48.90, 51.10, -2.20 +0.33, 0.00, 51.37, 48.63, 2.74 +0.33, 0.00, 51.37, 48.63, 2.74 +0.33, 0.00, 51.37, 48.63, 2.74 +0.33, 0.00, 51.37, 48.63, 2.74 +0.33, 0.00, 51.37, 48.63, 2.73 +0.33, 0.00, 51.37, 48.63, 2.73 +0.33, 0.00, 51.36, 48.64, 2.73 +0.33, 0.00, 51.36, 48.64, 2.73 +0.33, 0.00, 51.36, 48.64, 2.72 +0.33, 0.00, 51.36, 48.64, 2.72 +0.40, 0.00, 48.84, 51.16, -2.32 +0.40, 0.00, 51.31, 48.69, 2.62 +0.40, 0.00, 51.31, 48.69, 2.61 +0.40, 0.00, 51.31, 48.69, 2.61 +0.40, 0.00, 51.30, 48.70, 2.61 +0.40, 0.00, 51.30, 48.70, 2.60 +0.40, 0.00, 51.30, 48.70, 2.60 +0.40, 0.00, 51.30, 48.70, 2.60 +0.40, 0.00, 51.30, 48.70, 2.60 +0.40, 0.00, 51.30, 48.70, 2.59 +0.40, 0.00, 51.29, 48.71, 2.59 +0.40, 0.00, 51.29, 48.71, 2.59 +0.33, 0.00, 53.81, 46.19, 7.63 +0.33, 0.00, 51.34, 48.66, 2.68 +0.33, 0.00, 51.34, 48.66, 2.68 +0.33, 0.00, 51.34, 48.66, 2.68 +0.33, 0.00, 51.34, 48.66, 2.67 +0.33, 0.00, 51.34, 48.66, 2.67 +0.33, 0.00, 51.33, 48.67, 2.67 +0.33, 0.00, 51.33, 48.67, 2.67 +0.33, 0.00, 51.33, 48.67, 2.66 +0.33, 0.00, 51.33, 48.67, 2.66 +0.33, 0.00, 51.33, 48.67, 2.66 +0.33, 0.00, 51.33, 48.67, 2.66 +0.33, 0.00, 51.33, 48.67, 2.65 +0.33, 0.00, 51.33, 48.67, 2.65 +0.33, 0.00, 51.32, 48.68, 2.65 +0.33, 0.00, 51.32, 48.68, 2.65 +0.26, 0.00, 53.84, 46.16, 7.69 +0.26, 0.00, 51.37, 48.63, 2.74 +0.26, 0.00, 51.37, 48.63, 2.74 +0.26, 0.00, 51.37, 48.63, 2.74 +0.26, 0.00, 51.37, 48.63, 2.74 +0.13, 0.00, 56.41, 43.59, 12.82 +0.13, 0.00, 51.47, 48.53, 2.93 +0.13, 0.00, 51.47, 48.53, 2.93 +0.13, 0.00, 51.46, 48.54, 2.93 +0.13, 0.00, 51.46, 48.54, 2.93 +0.07, 0.00, 53.99, 46.01, 7.97 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.00, 0.00, 54.03, 45.97, 8.06 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +0.00, 0.00, 51.56, 48.44, 3.12 +-0.13, 0.00, 56.60, 43.40, 13.21 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.33 +-0.13, 0.00, 51.66, 48.34, 3.33 +0.00, 0.00, 46.62, 53.38, -6.76 +-0.13, 0.00, 56.61, 43.39, 13.21 +0.00, 0.00, 46.62, 53.38, -6.76 +-0.13, 0.00, 56.61, 43.39, 13.22 +0.00, 0.00, 46.62, 53.38, -6.76 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 56.61, 43.39, 13.22 +-0.13, 0.00, 51.67, 48.33, 3.33 +-0.13, 0.00, 51.67, 48.33, 3.33 +-0.13, 0.00, 51.67, 48.33, 3.33 +0.00, 0.00, 46.62, 53.38, -6.75 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.00, 0.00, 51.57, 48.43, 3.13 +0.07, 0.00, 49.05, 50.95, -1.91 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.52, 48.48, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.03 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.13, 0.00, 48.99, 51.01, -2.02 +0.13, 0.00, 51.46, 48.54, 2.92 +0.07, 0.00, 53.98, 46.02, 7.96 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.02 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.51, 48.49, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.01 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.07, 0.00, 51.50, 48.50, 3.00 +0.13, 0.00, 48.98, 51.02, -2.05 +0.13, 0.00, 51.45, 48.55, 2.90 +0.13, 0.00, 51.45, 48.55, 2.90 +0.13, 0.00, 51.45, 48.55, 2.90 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.45, 48.55, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.89 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.88 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.86 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.43, 48.57, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.85 +0.13, 0.00, 51.42, 48.58, 2.84 +0.13, 0.00, 51.42, 48.58, 2.84 +0.13, 0.00, 51.42, 48.58, 2.84 +0.26, 0.00, 46.38, 53.62, -7.25 +0.26, 0.00, 51.32, 48.68, 2.64 +0.26, 0.00, 51.32, 48.68, 2.64 +0.26, 0.00, 51.32, 48.68, 2.64 +0.26, 0.00, 51.32, 48.68, 2.63 +0.26, 0.00, 51.32, 48.68, 2.63 +0.26, 0.00, 51.32, 48.68, 2.63 +0.26, 0.00, 51.31, 48.69, 2.63 +0.26, 0.00, 51.31, 48.69, 2.63 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.62 +0.26, 0.00, 51.31, 48.69, 2.61 +0.26, 0.00, 51.31, 48.69, 2.61 +0.26, 0.00, 51.31, 48.69, 2.61 +0.26, 0.00, 51.30, 48.70, 2.61 +0.26, 0.00, 51.30, 48.70, 2.61 +0.26, 0.00, 51.30, 48.70, 2.60 +0.33, 0.00, 48.78, 51.22, -2.44 +0.26, 0.00, 53.77, 46.23, 7.54 +0.33, 0.00, 48.78, 51.22, -2.44 +0.33, 0.00, 51.25, 48.75, 2.50 +0.26, 0.00, 53.77, 46.23, 7.54 +0.26, 0.00, 51.30, 48.70, 2.59 +0.26, 0.00, 51.29, 48.71, 2.59 +0.26, 0.00, 51.29, 48.71, 2.59 +0.26, 0.00, 51.29, 48.71, 2.59 +0.26, 0.00, 51.29, 48.71, 2.58 +0.26, 0.00, 51.29, 48.71, 2.58 +0.33, 0.00, 48.77, 51.23, -2.46 +0.33, 0.00, 51.24, 48.76, 2.48 +0.33, 0.00, 51.24, 48.76, 2.48 +0.33, 0.00, 51.24, 48.76, 2.47 +0.33, 0.00, 51.24, 48.76, 2.47 +0.33, 0.00, 51.23, 48.77, 2.47 +0.33, 0.00, 51.23, 48.77, 2.47 +0.33, 0.00, 51.23, 48.77, 2.46 +0.33, 0.00, 51.23, 48.77, 2.46 +0.33, 0.00, 51.23, 48.77, 2.46 +0.33, 0.00, 51.23, 48.77, 2.46 +0.33, 0.00, 51.23, 48.77, 2.45 +0.33, 0.00, 51.23, 48.77, 2.45 +0.33, 0.00, 51.22, 48.78, 2.45 +0.33, 0.00, 51.22, 48.78, 2.45 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 53.74, 46.26, 7.48 +0.33, 0.00, 48.74, 51.26, -2.51 +0.33, 0.00, 51.21, 48.79, 2.43 +0.33, 0.00, 51.21, 48.79, 2.43 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.41 +0.33, 0.00, 51.21, 48.79, 2.41 +0.33, 0.00, 51.20, 48.80, 2.41 +0.33, 0.00, 51.20, 48.80, 2.41 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.39 +0.26, 0.00, 53.72, 46.28, 7.43 +0.33, 0.00, 48.72, 51.28, -2.55 +0.33, 0.00, 51.19, 48.81, 2.39 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.37 +0.33, 0.00, 51.19, 48.81, 2.37 +0.33, 0.00, 51.18, 48.82, 2.37 +0.33, 0.00, 51.18, 48.82, 2.37 +0.33, 0.00, 51.18, 48.82, 2.36 +0.26, 0.00, 53.70, 46.30, 7.41 +0.26, 0.00, 51.23, 48.77, 2.46 +0.26, 0.00, 51.23, 48.77, 2.46 +0.26, 0.00, 51.23, 48.77, 2.46 +0.26, 0.00, 51.23, 48.77, 2.45 +0.26, 0.00, 51.23, 48.77, 2.45 +0.26, 0.00, 51.23, 48.77, 2.45 +0.26, 0.00, 51.22, 48.78, 2.45 +0.26, 0.00, 51.22, 48.78, 2.45 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.44 +0.26, 0.00, 51.22, 48.78, 2.43 +0.26, 0.00, 51.22, 48.78, 2.43 +0.26, 0.00, 51.22, 48.78, 2.43 +0.33, 0.00, 48.69, 51.31, -2.61 +0.26, 0.00, 53.68, 46.32, 7.37 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 51.21, 48.79, 2.41 +0.26, 0.00, 51.21, 48.79, 2.41 +0.26, 0.00, 51.20, 48.80, 2.41 +0.26, 0.00, 51.20, 48.80, 2.41 +0.13, 0.00, 56.25, 43.75, 12.49 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.60 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.13, 0.00, 51.30, 48.70, 2.59 +0.07, 0.00, 53.82, 46.18, 7.64 +0.07, 0.00, 51.35, 48.65, 2.69 +0.07, 0.00, 51.35, 48.65, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.07, 0.00, 51.34, 48.66, 2.69 +0.00, 0.00, 53.86, 46.14, 7.73 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +0.00, 0.00, 51.39, 48.61, 2.78 +-0.13, 0.00, 56.44, 43.56, 12.87 +-0.13, 0.00, 51.49, 48.51, 2.98 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.49, 48.51, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 2.99 +-0.13, 0.00, 51.50, 48.50, 3.00 +-0.20, 0.00, 54.02, 45.98, 8.04 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 51.55, 48.45, 3.11 +-0.20, 0.00, 51.55, 48.45, 3.11 +-0.20, 0.00, 51.55, 48.45, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.11 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 51.56, 48.44, 3.13 +-0.13, 0.00, 49.04, 50.96, -1.92 +-0.20, 0.00, 54.04, 45.96, 8.07 +-0.20, 0.00, 51.56, 48.44, 3.13 +-0.20, 0.00, 51.57, 48.43, 3.13 +-0.20, 0.00, 51.57, 48.43, 3.13 +-0.20, 0.00, 51.57, 48.43, 3.13 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 51.57, 48.43, 3.15 +-0.20, 0.00, 51.57, 48.43, 3.15 +-0.20, 0.00, 51.57, 48.43, 3.15 +-0.20, 0.00, 51.58, 48.42, 3.15 +-0.20, 0.00, 51.58, 48.42, 3.15 +-0.20, 0.00, 51.58, 48.42, 3.15 +-0.20, 0.00, 51.58, 48.42, 3.15 +-0.13, 0.00, 49.06, 50.94, -1.89 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +0.00, 0.00, 46.50, 53.50, -7.01 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +0.00, 0.00, 51.44, 48.56, 2.88 +-0.13, 0.00, 56.48, 43.52, 12.97 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.08 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.20, 0.00, 54.07, 45.93, 8.14 +-0.20, 0.00, 51.60, 48.40, 3.20 +-0.20, 0.00, 51.60, 48.40, 3.20 +-0.26, 0.00, 54.12, 45.88, 8.24 +-0.26, 0.00, 51.65, 48.35, 3.30 +-0.26, 0.00, 51.65, 48.35, 3.30 +-0.26, 0.00, 51.65, 48.35, 3.30 +-0.26, 0.00, 51.65, 48.35, 3.31 +-0.26, 0.00, 51.65, 48.35, 3.31 +-0.26, 0.00, 51.66, 48.34, 3.31 +-0.26, 0.00, 51.66, 48.34, 3.31 +-0.26, 0.00, 51.66, 48.34, 3.31 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.32 +-0.26, 0.00, 51.66, 48.34, 3.33 +-0.26, 0.00, 51.66, 48.34, 3.33 +-0.26, 0.00, 51.67, 48.33, 3.33 +-0.26, 0.00, 51.67, 48.33, 3.33 +-0.26, 0.00, 51.67, 48.33, 3.33 +-0.26, 0.00, 51.67, 48.33, 3.34 +-0.40, 0.00, 56.71, 43.29, 13.42 +-0.40, 0.00, 51.77, 48.23, 3.54 +-0.40, 0.00, 51.77, 48.23, 3.54 +-0.26, 0.00, 46.73, 53.27, -6.54 +-0.26, 0.00, 51.67, 48.33, 3.35 +-0.26, 0.00, 51.68, 48.32, 3.35 +-0.26, 0.00, 51.68, 48.32, 3.35 +-0.20, 0.00, 49.16, 50.84, -1.69 +-0.20, 0.00, 51.63, 48.37, 3.26 +-0.20, 0.00, 51.63, 48.37, 3.26 +-0.20, 0.00, 51.63, 48.37, 3.26 +-0.13, 0.00, 49.11, 50.89, -1.78 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.59, 48.41, 3.17 +0.00, 0.00, 46.54, 53.46, -6.91 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.07, 0.00, 48.96, 51.04, -2.07 +0.07, 0.00, 51.44, 48.56, 2.87 +0.07, 0.00, 51.44, 48.56, 2.87 +0.13, 0.00, 48.91, 51.09, -2.17 +0.13, 0.00, 51.39, 48.61, 2.77 +0.13, 0.00, 51.39, 48.61, 2.77 +0.13, 0.00, 51.38, 48.62, 2.77 +0.26, 0.00, 46.34, 53.66, -7.32 +0.26, 0.00, 51.28, 48.72, 2.57 +0.26, 0.00, 51.28, 48.72, 2.57 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.55 +0.26, 0.00, 51.28, 48.72, 2.55 +0.26, 0.00, 51.28, 48.72, 2.55 +0.26, 0.00, 51.27, 48.73, 2.55 +0.26, 0.00, 51.27, 48.73, 2.55 +0.26, 0.00, 51.27, 48.73, 2.54 +0.33, 0.00, 48.75, 51.25, -2.50 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.44 +0.33, 0.00, 51.22, 48.78, 2.43 +0.33, 0.00, 51.22, 48.78, 2.43 +0.33, 0.00, 51.21, 48.79, 2.43 +0.33, 0.00, 51.21, 48.79, 2.43 +0.33, 0.00, 51.21, 48.79, 2.42 +0.33, 0.00, 51.21, 48.79, 2.42 +0.26, 0.00, 53.73, 46.27, 7.46 +0.26, 0.00, 51.26, 48.74, 2.52 +0.26, 0.00, 51.26, 48.74, 2.51 +0.26, 0.00, 51.26, 48.74, 2.51 +0.26, 0.00, 51.25, 48.75, 2.51 +0.26, 0.00, 51.25, 48.75, 2.51 +0.26, 0.00, 51.25, 48.75, 2.51 +0.26, 0.00, 51.25, 48.75, 2.50 +0.33, 0.00, 48.73, 51.27, -2.54 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.40 +0.33, 0.00, 51.20, 48.80, 2.39 +0.33, 0.00, 51.20, 48.80, 2.39 +0.33, 0.00, 51.19, 48.81, 2.39 +0.33, 0.00, 51.19, 48.81, 2.39 +0.33, 0.00, 51.19, 48.81, 2.38 +0.26, 0.00, 53.71, 46.29, 7.42 +0.26, 0.00, 51.24, 48.76, 2.48 +0.26, 0.00, 51.24, 48.76, 2.48 +0.26, 0.00, 51.24, 48.76, 2.47 +0.13, 0.00, 56.28, 43.72, 12.56 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.67 +0.13, 0.00, 51.33, 48.67, 2.66 +0.13, 0.00, 51.33, 48.67, 2.66 +0.13, 0.00, 51.33, 48.67, 2.66 +0.13, 0.00, 51.33, 48.67, 2.66 +0.13, 0.00, 51.33, 48.67, 2.66 +0.07, 0.00, 53.85, 46.15, 7.70 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.00, 0.00, 53.90, 46.10, 7.80 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +0.00, 0.00, 51.43, 48.57, 2.86 +-0.13, 0.00, 56.47, 43.53, 12.94 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.20, 0.00, 54.05, 45.95, 8.10 +-0.20, 0.00, 51.58, 48.42, 3.16 +-0.20, 0.00, 51.58, 48.42, 3.16 +-0.20, 0.00, 51.58, 48.42, 3.16 +-0.26, 0.00, 54.10, 45.90, 8.21 +-0.26, 0.00, 51.63, 48.37, 3.26 +-0.26, 0.00, 51.63, 48.37, 3.27 +-0.26, 0.00, 51.63, 48.37, 3.27 +-0.26, 0.00, 51.64, 48.36, 3.27 +-0.26, 0.00, 51.64, 48.36, 3.27 +-0.26, 0.00, 51.64, 48.36, 3.27 +-0.40, 0.00, 56.68, 43.32, 13.36 +-0.40, 0.00, 51.74, 48.26, 3.48 +-0.40, 0.00, 51.74, 48.26, 3.48 +-0.40, 0.00, 51.74, 48.26, 3.48 +-0.40, 0.00, 51.74, 48.26, 3.49 +-0.40, 0.00, 51.75, 48.25, 3.49 +-0.40, 0.00, 51.75, 48.25, 3.49 +-0.40, 0.00, 51.75, 48.25, 3.50 +-0.46, 0.00, 54.27, 45.73, 8.54 +-0.46, 0.00, 51.80, 48.20, 3.60 +-0.46, 0.00, 51.80, 48.20, 3.61 +-0.46, 0.00, 51.80, 48.20, 3.61 +-0.46, 0.00, 51.81, 48.19, 3.61 +-0.53, 0.00, 54.33, 45.67, 8.66 +-0.53, 0.00, 51.86, 48.14, 3.72 +-0.53, 0.00, 51.86, 48.14, 3.72 +-0.53, 0.00, 51.86, 48.14, 3.73 +-0.53, 0.00, 51.87, 48.13, 3.73 +-0.53, 0.00, 51.87, 48.13, 3.73 +-0.53, 0.00, 51.87, 48.13, 3.74 +-0.53, 0.00, 51.87, 48.13, 3.74 +-0.53, 0.00, 51.87, 48.13, 3.75 +-0.53, 0.00, 51.88, 48.12, 3.75 +-0.53, 0.00, 51.88, 48.12, 3.75 +-0.53, 0.00, 51.88, 48.12, 3.76 +-0.53, 0.00, 51.88, 48.12, 3.76 +-0.53, 0.00, 51.88, 48.12, 3.77 +-0.53, 0.00, 51.89, 48.11, 3.77 +-0.66, 0.00, 56.93, 43.07, 13.86 +-0.66, 0.00, 51.99, 48.01, 3.98 +-0.66, 0.00, 51.99, 48.01, 3.98 +-0.66, 0.00, 51.99, 48.01, 3.99 +-0.66, 0.00, 52.00, 48.00, 3.99 +-0.66, 0.00, 52.00, 48.00, 4.00 +-0.66, 0.00, 52.00, 48.00, 4.00 +-0.66, 0.00, 52.00, 48.00, 4.01 +-0.66, 0.00, 52.01, 47.99, 4.01 +-0.53, 0.00, 46.97, 53.03, -6.07 +-0.53, 0.00, 51.91, 48.09, 3.82 +-0.53, 0.00, 51.91, 48.09, 3.83 +-0.53, 0.00, 51.92, 48.08, 3.83 +-0.53, 0.00, 51.92, 48.08, 3.83 +-0.53, 0.00, 51.92, 48.08, 3.84 +-0.53, 0.00, 51.92, 48.08, 3.84 +-0.53, 0.00, 51.92, 48.08, 3.85 +-0.53, 0.00, 51.93, 48.07, 3.85 +-0.53, 0.00, 51.93, 48.07, 3.85 +-0.53, 0.00, 51.93, 48.07, 3.86 +-0.53, 0.00, 51.93, 48.07, 3.86 +-0.53, 0.00, 51.93, 48.07, 3.87 +-0.53, 0.00, 51.94, 48.06, 3.87 +-0.53, 0.00, 51.94, 48.06, 3.87 +-0.53, 0.00, 51.94, 48.06, 3.88 +-0.46, 0.00, 49.42, 50.58, -1.16 +-0.46, 0.00, 51.89, 48.11, 3.79 +-0.46, 0.00, 51.89, 48.11, 3.79 +-0.40, 0.00, 49.38, 50.62, -1.25 +-0.40, 0.00, 51.85, 48.15, 3.70 +-0.40, 0.00, 51.85, 48.15, 3.70 +-0.26, 0.00, 46.81, 53.19, -6.38 +-0.26, 0.00, 51.75, 48.25, 3.51 +-0.26, 0.00, 51.75, 48.25, 3.51 +-0.20, 0.00, 49.23, 50.77, -1.53 +-0.20, 0.00, 51.71, 48.29, 3.41 +-0.20, 0.00, 51.71, 48.29, 3.41 +-0.20, 0.00, 51.71, 48.29, 3.42 +-0.20, 0.00, 51.71, 48.29, 3.42 +-0.20, 0.00, 51.71, 48.29, 3.42 +-0.13, 0.00, 49.19, 50.81, -1.62 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +-0.13, 0.00, 51.66, 48.34, 3.32 +0.00, 0.00, 46.62, 53.38, -6.76 +0.00, 0.00, 51.56, 48.44, 3.13 +0.00, 0.00, 51.56, 48.44, 3.13 +0.07, 0.00, 49.04, 50.96, -1.92 +0.07, 0.00, 51.51, 48.49, 3.03 +0.13, 0.00, 48.99, 51.01, -2.02 +0.13, 0.00, 51.46, 48.54, 2.93 +0.26, 0.00, 46.42, 53.58, -7.16 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.72 +0.26, 0.00, 51.36, 48.64, 2.71 +0.33, 0.00, 48.83, 51.17, -2.33 +0.33, 0.00, 51.31, 48.69, 2.61 +0.33, 0.00, 51.30, 48.70, 2.61 +0.33, 0.00, 51.30, 48.70, 2.61 +0.40, 0.00, 48.78, 51.22, -2.44 +0.40, 0.00, 51.25, 48.75, 2.50 +0.40, 0.00, 51.25, 48.75, 2.50 +0.40, 0.00, 51.25, 48.75, 2.49 +0.53, 0.00, 46.20, 53.80, -7.59 +0.53, 0.00, 51.14, 48.86, 2.29 +0.53, 0.00, 51.14, 48.86, 2.28 +0.53, 0.00, 51.14, 48.86, 2.28 +0.53, 0.00, 51.14, 48.86, 2.28 +0.53, 0.00, 51.14, 48.86, 2.27 +0.59, 0.00, 48.61, 51.39, -2.77 +0.59, 0.00, 51.08, 48.92, 2.17 +0.59, 0.00, 51.08, 48.92, 2.16 +0.53, 0.00, 53.60, 46.40, 7.20 +0.53, 0.00, 51.13, 48.87, 2.25 +0.53, 0.00, 51.12, 48.88, 2.25 +0.53, 0.00, 51.12, 48.88, 2.24 +0.53, 0.00, 51.12, 48.88, 2.24 +0.53, 0.00, 51.12, 48.88, 2.24 +0.53, 0.00, 51.12, 48.88, 2.23 +0.40, 0.00, 56.16, 43.84, 12.31 +0.53, 0.00, 46.17, 53.83, -7.66 +0.40, 0.00, 56.15, 43.85, 12.31 +0.40, 0.00, 51.21, 48.79, 2.42 +0.40, 0.00, 51.21, 48.79, 2.41 +0.40, 0.00, 51.21, 48.79, 2.41 +0.40, 0.00, 51.20, 48.80, 2.41 +0.40, 0.00, 51.20, 48.80, 2.41 +0.40, 0.00, 51.20, 48.80, 2.40 +0.40, 0.00, 51.20, 48.80, 2.40 +0.40, 0.00, 51.20, 48.80, 2.40 +0.40, 0.00, 51.20, 48.80, 2.39 +0.33, 0.00, 53.72, 46.28, 7.43 +0.33, 0.00, 51.24, 48.76, 2.49 +0.26, 0.00, 53.76, 46.24, 7.53 +0.26, 0.00, 51.29, 48.71, 2.58 +0.26, 0.00, 51.29, 48.71, 2.58 +0.13, 0.00, 56.33, 43.67, 12.66 +0.13, 0.00, 51.39, 48.61, 2.78 +0.13, 0.00, 51.39, 48.61, 2.77 +0.07, 0.00, 53.91, 46.09, 7.82 +0.07, 0.00, 51.44, 48.56, 2.87 +0.07, 0.00, 51.44, 48.56, 2.87 +0.07, 0.00, 51.44, 48.56, 2.87 +0.07, 0.00, 51.44, 48.56, 2.87 +0.00, 0.00, 53.96, 46.04, 7.91 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +0.00, 0.00, 51.49, 48.51, 2.97 +-0.13, 0.00, 56.53, 43.47, 13.06 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.20, 0.00, 54.11, 45.89, 8.21 +-0.20, 0.00, 51.64, 48.36, 3.27 +-0.20, 0.00, 51.64, 48.36, 3.27 +-0.26, 0.00, 54.16, 45.84, 8.32 +-0.26, 0.00, 51.69, 48.31, 3.38 +-0.40, 0.00, 56.73, 43.27, 13.46 +-0.40, 0.00, 51.79, 48.21, 3.58 +-0.40, 0.00, 51.79, 48.21, 3.58 +-0.46, 0.00, 54.31, 45.69, 8.63 +-0.46, 0.00, 51.84, 48.16, 3.69 +-0.46, 0.00, 51.85, 48.15, 3.69 +-0.53, 0.00, 54.37, 45.63, 8.74 +-0.53, 0.00, 51.90, 48.10, 3.80 +-0.53, 0.00, 51.90, 48.10, 3.80 +-0.53, 0.00, 51.90, 48.10, 3.81 +-0.53, 0.00, 51.91, 48.09, 3.81 +-0.66, 0.00, 56.95, 43.05, 13.90 +-0.66, 0.00, 52.01, 47.99, 4.02 +-0.66, 0.00, 52.01, 47.99, 4.02 +-0.73, 0.00, 54.54, 45.46, 9.07 +-0.73, 0.00, 52.07, 47.93, 4.13 +-0.73, 0.00, 52.07, 47.93, 4.14 +-0.79, 0.00, 54.59, 45.41, 9.19 +-0.79, 0.00, 52.12, 47.88, 4.25 +-0.79, 0.00, 52.13, 47.87, 4.26 +-0.79, 0.00, 52.13, 47.87, 4.26 +-0.92, 0.00, 57.18, 42.82, 14.35 +-0.92, 0.00, 52.24, 47.76, 4.47 +-0.92, 0.00, 52.24, 47.76, 4.48 +-0.92, 0.00, 52.24, 47.76, 4.49 +-0.92, 0.00, 52.25, 47.75, 4.49 +-0.99, 0.00, 54.77, 45.23, 9.54 +-0.99, 0.00, 52.30, 47.70, 4.61 +-0.99, 0.00, 52.31, 47.69, 4.61 +-0.99, 0.00, 52.31, 47.69, 4.62 +-0.99, 0.00, 52.31, 47.69, 4.63 +-0.99, 0.00, 52.32, 47.68, 4.64 +-0.99, 0.00, 52.32, 47.68, 4.64 +-0.99, 0.00, 52.33, 47.67, 4.65 +-0.99, 0.00, 52.33, 47.67, 4.66 +-0.99, 0.00, 52.33, 47.67, 4.67 +-0.99, 0.00, 52.34, 47.66, 4.67 +-0.99, 0.00, 52.34, 47.66, 4.68 +-0.99, 0.00, 52.34, 47.66, 4.69 +-0.99, 0.00, 52.35, 47.65, 4.70 +-0.99, 0.00, 52.35, 47.65, 4.70 +-0.99, 0.00, 52.36, 47.64, 4.71 +-0.99, 0.00, 52.36, 47.64, 4.72 +-0.99, 0.00, 52.36, 47.64, 4.73 +-0.99, 0.00, 52.37, 47.63, 4.73 +-0.99, 0.00, 52.37, 47.63, 4.74 +-0.99, 0.00, 52.37, 47.63, 4.75 +-0.99, 0.00, 52.38, 47.62, 4.76 +-0.99, 0.00, 52.38, 47.62, 4.76 +-0.99, 0.00, 52.39, 47.61, 4.77 +-0.99, 0.00, 52.39, 47.61, 4.78 +-0.99, 0.00, 52.39, 47.61, 4.79 +-0.99, 0.00, 52.40, 47.60, 4.79 +-0.99, 0.00, 52.40, 47.60, 4.80 +-0.99, 0.00, 52.40, 47.60, 4.81 +-0.99, 0.00, 52.41, 47.59, 4.81 +-0.99, 0.00, 52.41, 47.59, 4.82 +-0.99, 0.00, 52.41, 47.59, 4.83 +-0.99, 0.00, 52.42, 47.58, 4.84 +-0.99, 0.00, 52.42, 47.58, 4.84 +-0.92, 0.00, 49.90, 50.10, -0.19 +-0.92, 0.00, 52.38, 47.62, 4.76 +-0.92, 0.00, 52.38, 47.62, 4.77 +-0.92, 0.00, 52.39, 47.61, 4.77 +-0.79, 0.00, 47.35, 52.65, -5.31 +-0.79, 0.00, 52.29, 47.71, 4.59 +-0.79, 0.00, 52.30, 47.70, 4.59 +-0.79, 0.00, 52.30, 47.70, 4.60 +-0.79, 0.00, 52.30, 47.70, 4.61 +-0.79, 0.00, 52.31, 47.69, 4.61 +-0.73, 0.00, 49.79, 50.21, -0.43 +-0.73, 0.00, 52.26, 47.74, 4.52 +-0.73, 0.00, 52.26, 47.74, 4.53 +-0.73, 0.00, 52.27, 47.73, 4.53 +-0.73, 0.00, 52.27, 47.73, 4.54 +-0.73, 0.00, 52.27, 47.73, 4.54 +-0.73, 0.00, 52.28, 47.72, 4.55 +-0.66, 0.00, 49.76, 50.24, -0.49 +-0.66, 0.00, 52.23, 47.77, 4.46 +-0.66, 0.00, 52.23, 47.77, 4.47 +-0.66, 0.00, 52.24, 47.76, 4.47 +-0.66, 0.00, 52.24, 47.76, 4.48 +-0.66, 0.00, 52.24, 47.76, 4.48 +-0.66, 0.00, 52.24, 47.76, 4.49 +-0.66, 0.00, 52.25, 47.75, 4.49 +-0.53, 0.00, 47.20, 52.80, -5.59 +-0.53, 0.00, 52.15, 47.85, 4.30 +-0.53, 0.00, 52.15, 47.85, 4.30 +-0.53, 0.00, 52.15, 47.85, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.33 +-0.46, 0.00, 49.64, 50.36, -0.71 +-0.46, 0.00, 52.12, 47.88, 4.24 +-0.46, 0.00, 52.12, 47.88, 4.24 +-0.46, 0.00, 52.12, 47.88, 4.24 +-0.46, 0.00, 52.12, 47.88, 4.25 +-0.46, 0.00, 52.13, 47.87, 4.25 +-0.46, 0.00, 52.13, 47.87, 4.25 +-0.40, 0.00, 49.61, 50.39, -0.79 +-0.40, 0.00, 52.08, 47.92, 4.16 +-0.40, 0.00, 52.08, 47.92, 4.16 +-0.40, 0.00, 52.08, 47.92, 4.17 +-0.40, 0.00, 52.08, 47.92, 4.17 +-0.40, 0.00, 52.09, 47.91, 4.17 +-0.40, 0.00, 52.09, 47.91, 4.18 +-0.40, 0.00, 52.09, 47.91, 4.18 +-0.40, 0.00, 52.09, 47.91, 4.18 +-0.40, 0.00, 52.09, 47.91, 4.18 +-0.40, 0.00, 52.09, 47.91, 4.19 +-0.40, 0.00, 52.10, 47.90, 4.19 +-0.26, 0.00, 47.05, 52.95, -5.89 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.00 +-0.26, 0.00, 52.00, 48.00, 4.01 +-0.26, 0.00, 52.00, 48.00, 4.01 +-0.26, 0.00, 52.01, 47.99, 4.01 +-0.26, 0.00, 52.01, 47.99, 4.01 +-0.20, 0.00, 49.49, 50.51, -1.03 +-0.20, 0.00, 51.96, 48.04, 3.92 +-0.20, 0.00, 51.96, 48.04, 3.92 +-0.26, 0.00, 54.48, 45.52, 8.96 +-0.20, 0.00, 49.49, 50.51, -1.02 +-0.26, 0.00, 54.48, 45.52, 8.97 +-0.26, 0.00, 52.01, 47.99, 4.02 +-0.26, 0.00, 52.01, 47.99, 4.03 +-0.26, 0.00, 52.01, 47.99, 4.03 +-0.20, 0.00, 49.49, 50.51, -1.01 +-0.20, 0.00, 51.97, 48.03, 3.93 +-0.20, 0.00, 51.97, 48.03, 3.93 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.20, 0.00, 51.97, 48.03, 3.95 +-0.20, 0.00, 51.97, 48.03, 3.95 +-0.20, 0.00, 51.97, 48.03, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.95 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.20, 0.00, 51.98, 48.02, 3.96 +-0.13, 0.00, 49.46, 50.54, -1.08 +-0.13, 0.00, 51.93, 48.07, 3.87 +-0.13, 0.00, 51.93, 48.07, 3.87 +-0.13, 0.00, 51.93, 48.07, 3.87 +0.00, 0.00, 46.89, 53.11, -6.22 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.00, 0.00, 51.83, 48.17, 3.67 +0.07, 0.00, 49.31, 50.69, -1.37 +0.07, 0.00, 51.78, 48.22, 3.57 +0.13, 0.00, 49.26, 50.74, -1.47 +0.13, 0.00, 51.73, 48.27, 3.47 +0.26, 0.00, 46.69, 53.31, -6.62 +0.26, 0.00, 51.63, 48.37, 3.27 +0.26, 0.00, 51.63, 48.37, 3.27 +0.33, 0.00, 49.11, 50.89, -1.78 +0.33, 0.00, 51.58, 48.42, 3.16 +0.33, 0.00, 51.58, 48.42, 3.16 +0.33, 0.00, 51.58, 48.42, 3.16 +0.40, 0.00, 49.06, 50.94, -1.89 +0.40, 0.00, 51.53, 48.47, 3.05 +0.40, 0.00, 51.52, 48.48, 3.05 +0.40, 0.00, 51.52, 48.48, 3.05 +0.40, 0.00, 51.52, 48.48, 3.04 +0.40, 0.00, 51.52, 48.48, 3.04 +0.40, 0.00, 51.52, 48.48, 3.04 +0.40, 0.00, 51.52, 48.48, 3.03 +0.53, 0.00, 46.47, 53.53, -7.06 +0.53, 0.00, 51.41, 48.59, 2.83 +0.59, 0.00, 48.89, 51.11, -2.22 +0.59, 0.00, 51.36, 48.64, 2.72 +0.59, 0.00, 51.36, 48.64, 2.72 +0.66, 0.00, 48.83, 51.17, -2.33 +0.66, 0.00, 51.30, 48.70, 2.61 +0.79, 0.00, 46.26, 53.74, -7.48 +0.79, 0.00, 51.20, 48.80, 2.40 +0.79, 0.00, 51.20, 48.80, 2.39 +0.79, 0.00, 51.19, 48.81, 2.39 +0.79, 0.00, 51.19, 48.81, 2.38 +0.79, 0.00, 51.19, 48.81, 2.37 +0.79, 0.00, 51.18, 48.82, 2.37 +0.79, 0.00, 51.18, 48.82, 2.36 +0.79, 0.00, 51.18, 48.82, 2.36 +0.79, 0.00, 51.18, 48.82, 2.35 +0.79, 0.00, 51.17, 48.83, 2.34 +0.86, 0.00, 48.65, 51.35, -2.70 +0.86, 0.00, 51.12, 48.88, 2.23 +0.86, 0.00, 51.11, 48.89, 2.23 +0.92, 0.00, 48.59, 51.41, -2.82 +0.92, 0.00, 51.06, 48.94, 2.11 +1.05, 0.00, 46.01, 53.99, -7.98 +1.05, 0.00, 50.95, 49.05, 1.90 +1.05, 0.00, 50.95, 49.05, 1.89 +1.12, 0.00, 48.42, 51.58, -3.16 +1.12, 0.00, 50.89, 49.11, 1.78 +1.12, 0.00, 50.88, 49.12, 1.77 +1.12, 0.00, 50.88, 49.12, 1.76 +1.12, 0.00, 50.88, 49.12, 1.75 +1.12, 0.00, 50.87, 49.13, 1.74 +1.12, 0.00, 50.87, 49.13, 1.73 +1.05, 0.00, 53.38, 46.62, 6.77 +1.12, 0.00, 48.39, 51.61, -3.23 +1.12, 0.00, 50.85, 49.15, 1.71 +1.12, 0.00, 50.85, 49.15, 1.70 +1.12, 0.00, 50.85, 49.15, 1.69 +1.12, 0.00, 50.84, 49.16, 1.68 +1.12, 0.00, 50.84, 49.16, 1.68 +1.19, 0.00, 48.31, 51.69, -3.38 +1.19, 0.00, 50.78, 49.22, 1.56 +1.19, 0.00, 50.78, 49.22, 1.55 +1.19, 0.00, 50.77, 49.23, 1.54 +1.19, 0.00, 50.77, 49.23, 1.53 +1.32, 0.00, 45.72, 54.28, -8.56 +1.32, 0.00, 50.66, 49.34, 1.31 +1.32, 0.00, 50.65, 49.35, 1.31 +1.32, 0.00, 50.65, 49.35, 1.30 +1.19, 0.00, 55.69, 44.31, 11.37 +1.19, 0.00, 50.74, 49.26, 1.48 +1.19, 0.00, 50.73, 49.27, 1.47 +1.19, 0.00, 50.73, 49.27, 1.46 +1.19, 0.00, 50.72, 49.28, 1.45 +1.12, 0.00, 53.24, 46.76, 6.48 +1.12, 0.00, 50.77, 49.23, 1.53 +1.12, 0.00, 50.76, 49.24, 1.52 +1.19, 0.00, 48.24, 51.76, -3.53 +1.19, 0.00, 50.70, 49.30, 1.41 +1.19, 0.00, 50.70, 49.30, 1.40 +1.19, 0.00, 50.69, 49.31, 1.39 +1.19, 0.00, 50.69, 49.31, 1.38 +1.32, 0.00, 45.64, 54.36, -8.72 +1.32, 0.00, 50.58, 49.42, 1.16 +1.32, 0.00, 50.58, 49.42, 1.15 +1.32, 0.00, 50.57, 49.43, 1.14 +1.19, 0.00, 55.61, 44.39, 11.22 +1.19, 0.00, 50.66, 49.34, 1.32 +1.19, 0.00, 50.66, 49.34, 1.31 +1.12, 0.00, 53.17, 46.83, 6.35 +1.12, 0.00, 50.70, 49.30, 1.39 +1.12, 0.00, 50.69, 49.31, 1.39 +1.12, 0.00, 50.69, 49.31, 1.38 +1.05, 0.00, 53.21, 46.79, 6.41 +1.05, 0.00, 50.73, 49.27, 1.46 +1.05, 0.00, 50.73, 49.27, 1.45 +0.92, 0.00, 55.77, 44.23, 11.53 +0.92, 0.00, 50.82, 49.18, 1.64 +0.92, 0.00, 50.81, 49.19, 1.63 +0.92, 0.00, 50.81, 49.19, 1.62 +0.92, 0.00, 50.81, 49.19, 1.62 +0.92, 0.00, 50.80, 49.20, 1.61 +0.92, 0.00, 50.80, 49.20, 1.60 +0.92, 0.00, 50.80, 49.20, 1.60 +0.92, 0.00, 50.79, 49.21, 1.59 +0.86, 0.00, 53.31, 46.69, 6.62 +0.86, 0.00, 50.84, 49.16, 1.67 +0.86, 0.00, 50.83, 49.17, 1.67 +0.86, 0.00, 50.83, 49.17, 1.66 +0.79, 0.00, 53.35, 46.65, 6.70 +0.79, 0.00, 50.87, 49.13, 1.75 +0.79, 0.00, 50.87, 49.13, 1.74 +0.66, 0.00, 55.91, 44.09, 11.82 +0.66, 0.00, 50.97, 49.03, 1.93 +0.59, 0.00, 53.48, 46.52, 6.97 +0.59, 0.00, 51.01, 48.99, 2.02 +0.59, 0.00, 51.01, 48.99, 2.02 +0.53, 0.00, 53.53, 46.47, 7.05 +0.53, 0.00, 51.05, 48.95, 2.11 +0.53, 0.00, 51.05, 48.95, 2.10 +0.53, 0.00, 51.05, 48.95, 2.10 +0.40, 0.00, 56.09, 43.91, 12.18 +0.40, 0.00, 51.15, 48.85, 2.29 +0.40, 0.00, 51.14, 48.86, 2.29 +0.40, 0.00, 51.14, 48.86, 2.28 +0.33, 0.00, 53.66, 46.34, 7.33 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.38 +0.33, 0.00, 51.19, 48.81, 2.37 +0.33, 0.00, 51.19, 48.81, 2.37 +0.26, 0.00, 53.71, 46.29, 7.41 +0.26, 0.00, 51.23, 48.77, 2.47 +0.26, 0.00, 51.23, 48.77, 2.46 +0.26, 0.00, 51.23, 48.77, 2.46 +0.13, 0.00, 56.27, 43.73, 12.55 +0.13, 0.00, 51.33, 48.67, 2.66 +0.07, 0.00, 53.85, 46.15, 7.70 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.76 +0.07, 0.00, 51.38, 48.62, 2.75 +0.00, 0.00, 53.90, 46.10, 7.80 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +0.00, 0.00, 51.43, 48.57, 2.85 +-0.13, 0.00, 56.47, 43.53, 12.94 +-0.13, 0.00, 51.53, 48.47, 3.05 +-0.13, 0.00, 51.53, 48.47, 3.05 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.06 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.53, 48.47, 3.07 +-0.13, 0.00, 51.54, 48.46, 3.07 +-0.20, 0.00, 54.06, 45.94, 8.12 +-0.20, 0.00, 51.59, 48.41, 3.17 +-0.20, 0.00, 51.59, 48.41, 3.17 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.20, 0.00, 51.59, 48.41, 3.18 +-0.13, 0.00, 49.07, 50.93, -1.86 +-0.20, 0.00, 54.06, 45.94, 8.13 +-0.13, 0.00, 49.07, 50.93, -1.86 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.54, 48.46, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.09 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.20, 0.00, 54.07, 45.93, 8.14 +-0.20, 0.00, 51.60, 48.40, 3.20 +-0.13, 0.00, 49.08, 50.92, -1.84 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.10 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.55, 48.45, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.11 +-0.13, 0.00, 51.56, 48.44, 3.12 +-0.20, 0.00, 54.08, 45.92, 8.16 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.22 +-0.20, 0.00, 51.61, 48.39, 3.23 +-0.20, 0.00, 51.61, 48.39, 3.23 +-0.13, 0.00, 49.09, 50.91, -1.82 +-0.13, 0.00, 51.56, 48.44, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.13 +-0.13, 0.00, 51.57, 48.43, 3.14 +-0.13, 0.00, 51.57, 48.43, 3.14 +-0.13, 0.00, 51.57, 48.43, 3.14 +-0.20, 0.00, 54.09, 45.91, 8.18 +-0.20, 0.00, 51.62, 48.38, 3.24 +-0.20, 0.00, 51.62, 48.38, 3.24 +-0.20, 0.00, 51.62, 48.38, 3.24 +-0.20, 0.00, 51.62, 48.38, 3.24 +-0.20, 0.00, 51.62, 48.38, 3.25 +-0.20, 0.00, 51.62, 48.38, 3.25 +-0.20, 0.00, 51.62, 48.38, 3.25 +-0.20, 0.00, 51.62, 48.38, 3.25 +-0.20, 0.00, 51.63, 48.37, 3.25 +-0.20, 0.00, 51.63, 48.37, 3.25 +-0.13, 0.00, 49.11, 50.89, -1.79 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.16 +-0.13, 0.00, 51.58, 48.42, 3.17 +-0.13, 0.00, 51.58, 48.42, 3.17 +0.00, 0.00, 46.54, 53.46, -6.92 +0.00, 0.00, 51.48, 48.52, 2.97 +0.00, 0.00, 51.48, 48.52, 2.97 +0.00, 0.00, 51.48, 48.52, 2.97 +0.00, 0.00, 51.48, 48.52, 2.97 +0.07, 0.00, 48.96, 51.04, -2.07 +0.07, 0.00, 51.43, 48.57, 2.87 +0.07, 0.00, 51.43, 48.57, 2.87 +0.07, 0.00, 51.43, 48.57, 2.87 +0.13, 0.00, 48.91, 51.09, -2.18 +0.13, 0.00, 51.38, 48.62, 2.77 +0.13, 0.00, 51.38, 48.62, 2.77 +0.13, 0.00, 51.38, 48.62, 2.77 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.13, 0.00, 51.38, 48.62, 2.76 +0.26, 0.00, 46.34, 53.66, -7.33 +0.26, 0.00, 51.28, 48.72, 2.56 +0.26, 0.00, 51.28, 48.72, 2.55 +0.26, 0.00, 51.28, 48.72, 2.55 +0.33, 0.00, 48.75, 51.25, -2.49 +0.33, 0.00, 51.22, 48.78, 2.45 +0.40, 0.00, 48.70, 51.30, -2.60 +0.40, 0.00, 51.17, 48.83, 2.34 +0.40, 0.00, 51.17, 48.83, 2.34 +0.40, 0.00, 51.17, 48.83, 2.34 +0.40, 0.00, 51.17, 48.83, 2.34 +0.40, 0.00, 51.17, 48.83, 2.33 +0.40, 0.00, 51.16, 48.84, 2.33 +0.53, 0.00, 46.12, 53.88, -7.76 +0.53, 0.00, 51.06, 48.94, 2.12 +0.53, 0.00, 51.06, 48.94, 2.12 +0.53, 0.00, 51.06, 48.94, 2.12 +0.53, 0.00, 51.06, 48.94, 2.11 +0.53, 0.00, 51.05, 48.95, 2.11 +0.59, 0.00, 48.53, 51.47, -2.94 +0.59, 0.00, 51.00, 49.00, 2.00 +0.59, 0.00, 51.00, 49.00, 2.00 +0.59, 0.00, 51.00, 49.00, 1.99 +0.59, 40.00, 75.00, 25.00, 50.00 +0.59, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.66, 40.00, 75.00, 25.00, 50.00 +0.79, 40.00, 75.00, 25.00, 50.00 +0.79, 40.00, 75.00, 25.00, 50.00 +0.79, 40.00, 75.00, 25.00, 50.00 +0.86, 40.00, 75.00, 25.00, 50.00 +0.92, 40.00, 75.00, 25.00, 50.00 +0.92, 40.00, 75.00, 25.00, 50.00 +1.12, 40.00, 75.00, 25.00, 50.00 +1.19, 40.00, 75.00, 25.00, 50.00 +1.32, 40.00, 75.00, 25.00, 50.00 +1.38, 40.00, 75.00, 25.00, 50.00 +1.58, 40.00, 75.00, 25.00, 50.00 +1.71, 40.00, 75.00, 25.00, 50.00 +1.85, 40.00, 75.00, 25.00, 50.00 +1.98, 40.00, 75.00, 25.00, 50.00 +2.24, 40.00, 73.23, 26.77, 46.46 +2.44, 40.00, 75.00, 25.00, 50.00 +2.64, 40.00, 75.00, 25.00, 50.00 +2.90, 40.00, 73.16, 26.84, 46.31 +3.03, 40.00, 75.00, 25.00, 50.00 +3.30, 40.00, 73.14, 26.86, 46.27 +3.69, 40.00, 68.03, 31.97, 36.06 +3.82, 40.00, 75.00, 25.00, 50.00 +4.09, 40.00, 72.95, 27.05, 45.90 +4.48, 40.00, 67.84, 32.16, 35.68 +4.81, 40.00, 70.20, 29.80, 40.40 +5.08, 40.00, 72.60, 27.40, 45.21 +5.54, 40.00, 64.97, 35.03, 29.94 +5.80, 40.00, 72.32, 27.68, 44.63 +6.20, 40.00, 67.20, 32.80, 34.41 +6.59, 40.00, 67.03, 32.97, 34.06 +6.92, 40.00, 69.38, 30.62, 38.76 +7.38, 40.00, 64.21, 35.79, 28.43 +7.78, 40.00, 66.51, 33.49, 33.02 +8.24, 40.00, 63.81, 36.19, 27.62 +8.70, 40.00, 63.58, 36.42, 27.16 +9.23, 40.00, 60.83, 39.17, 21.66 +9.62, 40.00, 65.59, 34.41, 31.18 +10.15, 40.00, 60.36, 39.64, 20.73 +10.68, 40.00, 60.08, 39.92, 20.15 +11.21, 40.00, 59.79, 40.21, 19.58 +11.73, 40.00, 59.50, 40.50, 19.00 +12.26, 40.00, 59.21, 40.79, 18.42 +12.72, 40.00, 61.44, 38.56, 22.87 +13.32, 40.00, 56.15, 43.85, 12.30 +13.84, 40.00, 58.32, 41.68, 16.65 +14.37, 40.00, 58.02, 41.98, 16.05 +14.90, 40.00, 57.72, 42.28, 15.44 +15.56, 40.00, 52.38, 47.62, 4.75 +16.08, 40.00, 57.01, 42.99, 14.03 +16.68, 40.00, 54.18, 45.82, 8.37 +17.20, 40.00, 56.35, 43.65, 12.69 +17.80, 40.00, 53.51, 46.49, 7.02 +18.46, 40.00, 50.63, 49.37, 1.25 +19.05, 40.00, 52.73, 47.27, 5.46 +19.64, 40.00, 52.36, 47.64, 4.73 +20.30, 40.00, 49.47, 50.53, -1.06 +20.83, 40.00, 54.09, 45.91, 8.18 +21.42, 40.00, 51.24, 48.76, 2.49 +22.02, 40.00, 50.87, 49.13, 1.73 +22.54, 40.00, 53.01, 46.99, 6.02 +23.07, 40.00, 52.68, 47.32, 5.35 +23.73, 40.00, 47.30, 52.70, -5.40 +24.26, 40.00, 51.91, 48.09, 3.81 +24.79, 40.00, 51.57, 48.43, 3.14 +25.38, 40.00, 48.71, 51.29, -2.59 +25.91, 40.00, 50.84, 49.16, 1.67 +26.50, 40.00, 47.97, 52.03, -4.06 +27.16, 40.00, 45.05, 54.95, -9.90 +27.69, 40.00, 49.65, 50.35, -0.71 +28.28, 40.00, 46.77, 53.23, -6.45 +28.81, 40.00, 48.89, 51.11, -2.22 +29.40, 40.00, 46.01, 53.99, -7.97 +29.93, 40.00, 48.13, 51.87, -3.74 +30.45, 40.00, 47.77, 52.23, -4.46 +30.92, 40.00, 49.93, 50.07, -0.14 +31.44, 40.00, 47.09, 52.91, -5.81 +31.97, 40.00, 46.73, 53.27, -6.54 +32.43, 40.00, 48.88, 51.12, -2.24 +32.83, 40.00, 51.08, 48.92, 2.17 +33.35, 40.00, 45.77, 54.23, -8.46 +33.75, 40.00, 50.44, 49.56, 0.88 +34.15, 40.00, 50.17, 49.83, 0.33 +34.61, 40.00, 47.37, 52.63, -5.26 +35.13, 40.00, 44.52, 55.48, -10.96 +35.60, 40.00, 46.66, 53.34, -6.68 +36.12, 40.00, 43.81, 56.19, -12.38 +36.52, 40.00, 48.47, 51.53, -3.06 +36.98, 40.00, 45.66, 54.34, -8.68 +37.44, 40.00, 45.33, 54.67, -9.35 +37.77, 40.00, 50.03, 49.97, 0.06 +38.23, 40.00, 44.75, 55.25, -10.51 +38.56, 40.00, 49.45, 50.55, -1.10 +38.89, 40.00, 49.21, 50.79, -1.59 +39.16, 40.00, 51.48, 48.52, 2.97 +39.55, 40.00, 46.24, 53.76, -7.51 +39.81, 40.00, 50.99, 49.01, 1.98 +40.08, 40.00, 50.79, 49.21, 1.59 +40.41, 40.00, 48.07, 51.93, -3.85 +40.67, 40.00, 50.34, 49.66, 0.69 +40.94, 40.00, 50.14, 49.86, 0.29 +41.13, 40.00, 52.46, 47.54, 4.92 +41.13, 40.00, 59.87, 40.13, 19.75 +41.13, 40.00, 59.87, 40.13, 19.74 +40.94, 40.00, 67.43, 32.57, 34.86 +40.87, 40.00, 62.53, 37.47, 25.07 +40.74, 40.00, 65.10, 34.90, 30.20 +40.61, 40.00, 65.20, 34.80, 30.39 +40.47, 40.00, 65.29, 34.71, 30.59 +40.67, 40.00, 52.78, 47.22, 5.57 +40.94, 40.00, 50.11, 49.89, 0.22 +40.94, 40.00, 59.99, 40.01, 19.99 +40.87, 40.00, 62.51, 37.49, 25.03 +40.94, 40.00, 57.52, 42.48, 15.03 +40.87, 40.00, 62.51, 37.49, 25.01 +40.74, 40.00, 65.07, 34.93, 30.15 +40.67, 40.00, 62.65, 37.35, 25.30 +40.47, 40.00, 67.74, 32.26, 35.48 +40.34, 40.00, 65.37, 34.63, 30.73 +40.14, 40.00, 67.99, 32.01, 35.97 +39.88, 40.00, 70.66, 29.34, 41.31 +39.62, 40.00, 70.85, 29.15, 41.71 +39.35, 40.00, 71.05, 28.95, 42.11 +39.16, 40.00, 68.73, 31.27, 37.47 +39.02, 40.00, 66.36, 33.64, 32.73 +38.83, 40.00, 68.99, 31.01, 37.98 +38.76, 40.00, 64.10, 35.90, 28.20 +38.63, 40.00, 66.68, 33.32, 33.35 +38.56, 40.00, 64.26, 35.74, 28.52 +38.56, 40.00, 61.79, 38.21, 23.58 +38.56, 40.00, 61.80, 38.20, 23.59 +38.56, 40.00, 61.80, 38.20, 23.61 +38.50, 40.00, 64.33, 35.67, 28.66 +38.50, 40.00, 61.86, 38.14, 23.73 +38.50, 40.00, 61.87, 38.13, 23.74 +38.36, 40.00, 66.92, 33.08, 33.84 +38.30, 40.00, 64.50, 35.50, 29.00 +38.30, 40.00, 62.04, 37.96, 24.07 +38.23, 40.00, 64.56, 35.44, 29.13 +38.10, 40.00, 67.14, 32.86, 34.28 +38.10, 40.00, 62.21, 37.79, 24.41 +38.03, 40.00, 64.73, 35.27, 29.47 +38.03, 40.00, 62.27, 37.73, 24.54 +38.03, 40.00, 62.28, 37.72, 24.55 +38.03, 40.00, 62.28, 37.72, 24.57 +38.10, 40.00, 59.77, 40.23, 19.54 +38.23, 40.00, 57.21, 42.79, 14.41 +38.30, 40.00, 59.63, 40.37, 19.27 +38.36, 40.00, 59.59, 40.41, 19.18 +38.56, 40.00, 54.50, 45.50, 9.01 +38.63, 40.00, 59.40, 40.60, 18.81 +38.76, 40.00, 56.84, 43.16, 13.68 +38.89, 40.00, 56.74, 43.26, 13.49 +38.89, 40.00, 61.69, 38.31, 23.38 +39.02, 40.00, 56.65, 43.35, 13.30 +39.09, 40.00, 59.08, 40.92, 18.16 +39.16, 40.00, 59.03, 40.97, 18.06 +39.29, 40.00, 56.46, 43.54, 12.93 +39.29, 40.00, 61.41, 38.59, 22.82 +39.42, 40.00, 56.37, 43.63, 12.74 +39.55, 40.00, 56.27, 43.73, 12.55 +39.62, 40.00, 58.70, 41.30, 17.39 +39.81, 40.00, 53.61, 46.39, 7.21 +39.88, 40.00, 58.50, 41.50, 17.00 +40.08, 40.00, 53.41, 46.59, 6.82 +40.21, 40.00, 55.78, 44.22, 11.56 +40.41, 40.00, 53.16, 46.84, 6.32 +40.47, 40.00, 58.05, 41.95, 16.10 +40.67, 40.00, 52.96, 47.04, 5.91 +40.87, 40.00, 52.80, 47.20, 5.61 +41.00, 40.00, 55.17, 44.83, 10.35 +41.13, 40.00, 55.07, 44.93, 10.14 +41.20, 40.00, 57.49, 42.51, 14.98 +41.26, 40.00, 57.43, 42.57, 14.87 +41.20, 40.00, 62.42, 37.58, 24.85 +41.20, 40.00, 59.95, 40.05, 19.89 +41.13, 40.00, 62.46, 37.54, 24.93 +41.00, 40.00, 65.03, 34.97, 30.06 +40.94, 40.00, 62.60, 37.40, 25.21 +40.87, 40.00, 62.65, 37.35, 25.30 +40.74, 40.00, 65.22, 34.78, 30.44 +40.74, 40.00, 60.27, 39.73, 20.54 +40.94, 40.00, 52.70, 47.30, 5.41 +40.94, 40.00, 60.12, 39.88, 20.23 +41.00, 40.00, 57.59, 42.41, 15.18 +41.00, 40.00, 60.06, 39.94, 20.12 +41.13, 40.00, 55.01, 44.99, 10.03 +41.13, 40.00, 59.95, 40.05, 19.91 +41.13, 40.00, 59.95, 40.05, 19.90 +41.13, 40.00, 59.94, 40.06, 19.89 +41.00, 40.00, 64.98, 35.02, 29.97 +41.00, 40.00, 60.04, 39.96, 20.07 +40.94, 40.00, 62.55, 37.45, 25.11 +40.74, 40.00, 67.64, 32.36, 35.29 +40.61, 40.00, 65.27, 34.73, 30.54 +40.47, 40.00, 65.36, 34.64, 30.73 +40.41, 40.00, 62.94, 37.06, 25.88 +40.34, 40.00, 62.99, 37.01, 25.98 +40.21, 40.00, 65.56, 34.44, 31.12 +40.21, 40.00, 60.61, 39.39, 21.23 +40.21, 40.00, 60.61, 39.39, 21.23 +40.34, 40.00, 55.57, 44.43, 11.14 +40.34, 40.00, 60.51, 39.49, 21.02 +40.41, 40.00, 57.99, 42.01, 15.98 +40.47, 40.00, 57.94, 42.06, 15.88 +40.61, 40.00, 55.36, 44.64, 10.73 +40.61, 40.00, 60.31, 39.69, 20.61 +40.67, 40.00, 57.78, 42.22, 15.57 +40.74, 40.00, 57.73, 42.27, 15.46 +40.74, 40.00, 60.20, 39.80, 20.40 +40.74, 40.00, 60.20, 39.80, 20.39 +40.74, 40.00, 60.19, 39.81, 20.39 +40.87, 40.00, 55.15, 44.85, 10.30 +40.74, 40.00, 65.13, 34.87, 30.26 +40.87, 40.00, 55.14, 44.86, 10.28 +40.87, 40.00, 60.08, 39.92, 20.17 +40.94, 40.00, 57.56, 42.44, 15.12 +40.94, 40.00, 60.03, 39.97, 20.05 +41.00, 40.00, 57.50, 42.50, 15.00 +41.13, 40.00, 54.93, 45.07, 9.85 +41.20, 40.00, 57.34, 42.66, 14.69 +41.20, 40.00, 59.81, 40.19, 19.62 +41.20, 40.00, 59.81, 40.19, 19.61 +41.20, 40.00, 59.80, 40.20, 19.60 +41.20, 40.00, 59.80, 40.20, 19.60 +41.13, 40.00, 62.32, 37.68, 24.63 +41.13, 40.00, 59.84, 40.16, 19.68 +41.13, 40.00, 59.83, 40.17, 19.67 +41.00, 40.00, 64.87, 35.13, 29.75 +41.13, 40.00, 54.88, 45.12, 9.77 +41.13, 40.00, 59.82, 40.18, 19.64 +41.13, 40.00, 59.82, 40.18, 19.64 +41.13, 40.00, 59.81, 40.19, 19.63 +41.13, 40.00, 59.81, 40.19, 19.62 +41.13, 40.00, 59.81, 40.19, 19.61 +41.13, 40.00, 59.80, 40.20, 19.60 +41.13, 40.00, 59.80, 40.20, 19.59 +41.13, 40.00, 59.79, 40.21, 19.59 +41.13, 40.00, 59.79, 40.21, 19.58 +41.00, 40.00, 64.83, 35.17, 29.65 +40.94, 40.00, 62.40, 37.60, 24.80 +40.94, 40.00, 59.93, 40.07, 19.85 +40.94, 40.00, 59.92, 40.08, 19.84 +40.87, 40.00, 62.44, 37.56, 24.88 +40.74, 40.00, 65.01, 34.99, 30.02 +40.74, 40.00, 60.06, 39.94, 20.12 +40.74, 40.00, 60.06, 39.94, 20.12 +40.74, 40.00, 60.06, 39.94, 20.11 +40.74, 40.00, 60.05, 39.95, 20.11 +40.87, 40.00, 55.01, 44.99, 10.02 +40.94, 40.00, 57.43, 42.57, 14.85 +40.94, 40.00, 59.90, 40.10, 19.79 +40.94, 40.00, 59.89, 40.11, 19.78 +41.00, 40.00, 57.37, 42.63, 14.73 +41.13, 40.00, 54.79, 45.21, 9.58 +41.20, 40.00, 57.21, 42.79, 14.42 +41.26, 40.00, 57.16, 42.84, 14.31 +41.26, 40.00, 59.62, 40.38, 19.24 +41.26, 40.00, 59.62, 40.38, 19.24 +41.20, 40.00, 62.13, 37.87, 24.27 +41.20, 40.00, 59.66, 40.34, 19.32 +41.20, 40.00, 59.65, 40.35, 19.31 +41.13, 40.00, 62.17, 37.83, 24.34 +41.00, 40.00, 64.74, 35.26, 29.48 +41.00, 40.00, 59.79, 40.21, 19.58 +40.94, 40.00, 62.31, 37.69, 24.62 +40.94, 40.00, 59.83, 40.17, 19.67 +41.00, 40.00, 57.31, 42.69, 14.61 +41.00, 40.00, 59.78, 40.22, 19.55 +41.13, 40.00, 54.73, 45.27, 9.46 +41.20, 40.00, 57.15, 42.85, 14.29 +41.20, 40.00, 59.61, 40.39, 19.23 +41.26, 40.00, 57.09, 42.91, 14.18 +41.26, 40.00, 59.56, 40.44, 19.11 +41.26, 40.00, 59.55, 40.45, 19.10 +41.26, 40.00, 59.55, 40.45, 19.09 +41.20, 40.00, 62.06, 37.94, 24.13 +41.20, 40.00, 59.59, 40.41, 19.17 +41.13, 40.00, 62.10, 37.90, 24.21 +41.13, 40.00, 59.63, 40.37, 19.25 +41.00, 40.00, 64.67, 35.33, 29.33 +40.94, 40.00, 62.24, 37.76, 24.48 +40.94, 40.00, 59.76, 40.24, 19.53 +40.94, 40.00, 59.76, 40.24, 19.52 +40.94, 40.00, 59.76, 40.24, 19.52 +40.94, 40.00, 59.75, 40.25, 19.51 +41.00, 40.00, 57.23, 42.77, 14.46 +41.00, 40.00, 59.70, 40.30, 19.39 +41.13, 40.00, 54.65, 45.35, 9.30 +41.20, 40.00, 57.07, 42.93, 14.14 +41.26, 40.00, 57.01, 42.99, 14.03 +41.26, 40.00, 59.48, 40.52, 18.96 +41.26, 40.00, 59.48, 40.52, 18.95 +41.26, 40.00, 59.47, 40.53, 18.94 +41.20, 40.00, 61.99, 38.01, 23.98 +41.20, 40.00, 59.51, 40.49, 19.02 +41.20, 40.00, 59.51, 40.49, 19.02 +41.13, 40.00, 62.02, 37.98, 24.05 +41.13, 40.00, 59.55, 40.45, 19.10 +41.13, 40.00, 59.54, 40.46, 19.09 +41.13, 40.00, 59.54, 40.46, 19.08 +41.13, 40.00, 59.54, 40.46, 19.07 +41.13, 40.00, 59.53, 40.47, 19.06 +41.20, 40.00, 57.01, 42.99, 14.01 +41.20, 40.00, 59.47, 40.53, 18.95 +41.20, 40.00, 59.47, 40.53, 18.94 +41.20, 40.00, 59.46, 40.54, 18.93 +41.26, 40.00, 56.94, 43.06, 13.88 +41.20, 40.00, 61.93, 38.07, 23.85 +41.26, 40.00, 56.93, 43.07, 13.86 +41.20, 40.00, 61.92, 38.08, 23.84 +41.20, 40.00, 59.44, 40.56, 18.88 +41.13, 40.00, 61.96, 38.04, 23.92 +41.13, 40.00, 59.48, 40.52, 18.96 +41.13, 40.00, 59.48, 40.52, 18.96 +41.13, 40.00, 59.47, 40.53, 18.95 +41.13, 40.00, 59.47, 40.53, 18.94 +41.13, 40.00, 59.47, 40.53, 18.93 +41.13, 40.00, 59.46, 40.54, 18.92 +41.13, 40.00, 59.46, 40.54, 18.91 +41.20, 40.00, 56.93, 43.07, 13.86 +41.20, 40.00, 59.40, 40.60, 18.80 +41.20, 40.00, 59.39, 40.61, 18.79 +41.20, 40.00, 59.39, 40.61, 18.78 +41.20, 40.00, 59.38, 40.62, 18.77 +41.20, 40.00, 59.38, 40.62, 18.76 +41.20, 40.00, 59.38, 40.62, 18.75 +41.20, 40.00, 59.37, 40.63, 18.74 +41.13, 40.00, 61.89, 38.11, 23.78 +41.13, 40.00, 59.41, 40.59, 18.82 +41.13, 40.00, 59.41, 40.59, 18.82 +41.13, 40.00, 59.40, 40.60, 18.81 +41.13, 40.00, 59.40, 40.60, 18.80 +41.13, 40.00, 59.40, 40.60, 18.79 +41.13, 40.00, 59.39, 40.61, 18.78 +41.13, 40.00, 59.39, 40.61, 18.77 +41.20, 40.00, 56.86, 43.14, 13.72 +41.20, 40.00, 59.33, 40.67, 18.66 +41.20, 40.00, 59.32, 40.68, 18.65 +41.20, 40.00, 59.32, 40.68, 18.64 +41.20, 40.00, 59.31, 40.69, 18.63 +41.20, 40.00, 59.31, 40.69, 18.62 +41.20, 40.00, 59.31, 40.69, 18.61 +41.20, 40.00, 59.30, 40.70, 18.60 +41.20, 40.00, 59.30, 40.70, 18.59 +41.20, 40.00, 59.29, 40.71, 18.58 +41.13, 40.00, 61.81, 38.19, 23.62 +41.20, 40.00, 56.81, 43.19, 13.62 +41.20, 40.00, 59.28, 40.72, 18.56 +41.20, 40.00, 59.27, 40.73, 18.55 +41.20, 40.00, 59.27, 40.73, 18.54 +41.20, 40.00, 59.27, 40.73, 18.53 +41.20, 40.00, 59.26, 40.74, 18.52 +41.20, 40.00, 59.26, 40.74, 18.51 +41.20, 40.00, 59.25, 40.75, 18.50 +41.20, 40.00, 59.25, 40.75, 18.50 +41.20, 40.00, 59.24, 40.76, 18.49 +41.20, 40.00, 59.24, 40.76, 18.48 +41.20, 40.00, 59.23, 40.77, 18.47 +41.20, 40.00, 59.23, 40.77, 18.46 +41.20, 40.00, 59.23, 40.77, 18.45 +41.20, 40.00, 59.22, 40.78, 18.44 +41.20, 40.00, 59.22, 40.78, 18.43 +41.20, 40.00, 59.21, 40.79, 18.42 +41.20, 40.00, 59.21, 40.79, 18.41 +41.20, 40.00, 59.20, 40.80, 18.41 +41.20, 40.00, 59.20, 40.80, 18.40 +41.20, 40.00, 59.19, 40.81, 18.39 +41.20, 40.00, 59.19, 40.81, 18.38 +41.20, 40.00, 59.18, 40.82, 18.37 +41.20, 40.00, 59.18, 40.82, 18.36 +41.20, 40.00, 59.18, 40.82, 18.35 +41.20, 40.00, 59.17, 40.83, 18.34 +41.20, 40.00, 59.17, 40.83, 18.33 +41.20, 40.00, 59.16, 40.84, 18.32 +41.20, 40.00, 59.16, 40.84, 18.32 +41.20, 40.00, 59.15, 40.85, 18.31 +41.20, 40.00, 59.15, 40.85, 18.30 +41.20, 40.00, 59.14, 40.86, 18.29 +41.20, 40.00, 59.14, 40.86, 18.28 +41.20, 40.00, 59.14, 40.86, 18.27 +41.20, 40.00, 59.13, 40.87, 18.26 +41.20, 40.00, 59.13, 40.87, 18.25 +41.20, 40.00, 59.12, 40.88, 18.24 +41.20, 40.00, 59.12, 40.88, 18.23 +41.20, 40.00, 59.11, 40.89, 18.23 +41.20, 40.00, 59.11, 40.89, 18.22 +41.20, 40.00, 59.10, 40.90, 18.21 +41.20, 40.00, 59.10, 40.90, 18.20 +41.20, 40.00, 59.09, 40.91, 18.19 +41.20, 40.00, 59.09, 40.91, 18.18 +41.20, 40.00, 59.09, 40.91, 18.17 +41.20, 40.00, 59.08, 40.92, 18.16 +41.20, 40.00, 59.08, 40.92, 18.15 +41.20, 40.00, 59.07, 40.93, 18.14 +41.20, 40.00, 59.07, 40.93, 18.14 +41.20, 40.00, 59.06, 40.94, 18.13 +41.20, 40.00, 59.06, 40.94, 18.12 +41.20, 40.00, 59.05, 40.95, 18.11 +41.20, 40.00, 59.05, 40.95, 18.10 +41.20, 40.00, 59.05, 40.95, 18.09 +41.20, 40.00, 59.04, 40.96, 18.08 +41.20, 40.00, 59.04, 40.96, 18.07 +41.20, 40.00, 59.03, 40.97, 18.06 +41.20, 40.00, 59.03, 40.97, 18.05 +41.20, 40.00, 59.02, 40.98, 18.05 +41.20, 40.00, 59.02, 40.98, 18.04 +41.20, 40.00, 59.01, 40.99, 18.03 +41.20, 40.00, 59.01, 40.99, 18.02 +41.20, 40.00, 59.00, 41.00, 18.01 +41.20, 40.00, 59.00, 41.00, 18.00 +41.20, 40.00, 59.00, 41.00, 17.99 +41.20, 40.00, 58.99, 41.01, 17.98 +41.20, 40.00, 58.99, 41.01, 17.97 +41.20, 40.00, 58.98, 41.02, 17.96 +41.20, 40.00, 58.98, 41.02, 17.96 +41.20, 40.00, 58.97, 41.03, 17.95 +41.20, 40.00, 58.97, 41.03, 17.94 +41.13, 40.00, 61.49, 38.51, 22.97 +41.20, 40.00, 56.49, 43.51, 12.98 +41.20, 40.00, 58.96, 41.04, 17.91 +41.20, 40.00, 58.95, 41.05, 17.90 +41.20, 40.00, 58.95, 41.05, 17.89 +41.20, 40.00, 58.94, 41.06, 17.88 +41.20, 40.00, 58.94, 41.06, 17.88 +41.20, 40.00, 58.93, 41.07, 17.87 +41.20, 40.00, 58.93, 41.07, 17.86 +41.20, 40.00, 58.92, 41.08, 17.85 +41.20, 40.00, 58.92, 41.08, 17.84 +41.20, 40.00, 58.92, 41.08, 17.83 +41.20, 40.00, 58.91, 41.09, 17.82 +41.20, 40.00, 58.91, 41.09, 17.81 +41.20, 40.00, 58.90, 41.10, 17.80 +41.20, 40.00, 58.90, 41.10, 17.79 +41.20, 40.00, 58.89, 41.11, 17.79 +41.20, 40.00, 58.89, 41.11, 17.78 +41.20, 40.00, 58.88, 41.12, 17.77 +41.20, 40.00, 58.88, 41.12, 17.76 +41.20, 40.00, 58.87, 41.13, 17.75 +41.20, 40.00, 58.87, 41.13, 17.74 +41.20, 40.00, 58.87, 41.13, 17.73 +41.20, 40.00, 58.86, 41.14, 17.72 +41.20, 40.00, 58.86, 41.14, 17.71 +41.20, 40.00, 58.85, 41.15, 17.70 +41.20, 40.00, 58.85, 41.15, 17.70 +41.20, 40.00, 58.84, 41.16, 17.69 +41.20, 40.00, 58.84, 41.16, 17.68 +41.20, 40.00, 58.83, 41.17, 17.67 +41.20, 40.00, 58.83, 41.17, 17.66 +41.20, 40.00, 58.83, 41.17, 17.65 +41.20, 40.00, 58.82, 41.18, 17.64 +41.20, 40.00, 58.82, 41.18, 17.63 +41.20, 40.00, 58.81, 41.19, 17.62 +41.20, 40.00, 58.81, 41.19, 17.61 +41.20, 40.00, 58.80, 41.20, 17.61 +41.20, 40.00, 58.80, 41.20, 17.60 +41.20, 40.00, 58.79, 41.21, 17.59 +41.20, 40.00, 58.79, 41.21, 17.58 +41.20, 40.00, 58.78, 41.22, 17.57 +41.20, 40.00, 58.78, 41.22, 17.56 +41.20, 40.00, 58.78, 41.22, 17.55 +41.20, 40.00, 58.77, 41.23, 17.54 +41.20, 40.00, 58.77, 41.23, 17.53 +41.20, 40.00, 58.76, 41.24, 17.52 +41.20, 40.00, 58.76, 41.24, 17.52 +41.20, 40.00, 58.75, 41.25, 17.51 +41.20, 40.00, 58.75, 41.25, 17.50 +41.20, 40.00, 58.74, 41.26, 17.49 +41.20, 40.00, 58.74, 41.26, 17.48 +41.20, 40.00, 58.74, 41.26, 17.47 +41.20, 40.00, 58.73, 41.27, 17.46 +41.20, 40.00, 58.73, 41.27, 17.45 +41.20, 40.00, 58.72, 41.28, 17.44 +41.20, 40.00, 58.72, 41.28, 17.43 +41.20, 40.00, 58.71, 41.29, 17.43 +41.20, 40.00, 58.71, 41.29, 17.42 +41.20, 40.00, 58.70, 41.30, 17.41 +41.20, 40.00, 58.70, 41.30, 17.40 +41.20, 40.00, 58.69, 41.31, 17.39 +41.20, 40.00, 58.69, 41.31, 17.38 +41.20, 40.00, 58.69, 41.31, 17.37 +41.20, 40.00, 58.68, 41.32, 17.36 +41.20, 40.00, 58.68, 41.32, 17.35 +41.20, 40.00, 58.67, 41.33, 17.34 +41.20, 40.00, 58.67, 41.33, 17.34 +41.20, 40.00, 58.66, 41.34, 17.33 +41.20, 40.00, 58.66, 41.34, 17.32 +41.20, 40.00, 58.65, 41.35, 17.31 +41.20, 40.00, 58.65, 41.35, 17.30 +41.20, 40.00, 58.65, 41.35, 17.29 +41.20, 40.00, 58.64, 41.36, 17.28 +41.20, 40.00, 58.64, 41.36, 17.27 +41.20, 40.00, 58.63, 41.37, 17.26 +41.20, 40.00, 58.63, 41.37, 17.25 +41.20, 40.00, 58.62, 41.38, 17.25 +41.20, 40.00, 58.62, 41.38, 17.24 +41.20, 40.00, 58.61, 41.39, 17.23 +41.20, 40.00, 58.61, 41.39, 17.22 +41.20, 40.00, 58.61, 41.39, 17.21 +41.20, 40.00, 58.60, 41.40, 17.20 +41.20, 40.00, 58.60, 41.40, 17.19 +41.20, 40.00, 58.59, 41.41, 17.18 +41.20, 40.00, 58.59, 41.41, 17.17 +41.20, 40.00, 58.58, 41.42, 17.17 +41.20, 40.00, 58.58, 41.42, 17.16 +41.20, 40.00, 58.57, 41.43, 17.15 +41.20, 40.00, 58.57, 41.43, 17.14 +41.20, 40.00, 58.56, 41.44, 17.13 +41.20, 40.00, 58.56, 41.44, 17.12 +41.20, 40.00, 58.56, 41.44, 17.11 +41.20, 40.00, 58.55, 41.45, 17.10 +41.20, 40.00, 58.55, 41.45, 17.09 +41.20, 40.00, 58.54, 41.46, 17.08 +41.20, 40.00, 58.54, 41.46, 17.08 +41.20, 40.00, 58.53, 41.47, 17.07 +41.20, 40.00, 58.53, 41.47, 17.06 +41.20, 40.00, 58.52, 41.48, 17.05 +41.20, 40.00, 58.52, 41.48, 17.04 +41.20, 40.00, 58.52, 41.48, 17.03 +41.20, 40.00, 58.51, 41.49, 17.02 +41.20, 40.00, 58.51, 41.49, 17.01 +41.20, 40.00, 58.50, 41.50, 17.00 +41.20, 40.00, 58.50, 41.50, 16.99 +41.20, 40.00, 58.49, 41.51, 16.99 +41.20, 40.00, 58.49, 41.51, 16.98 +41.20, 40.00, 58.48, 41.52, 16.97 +41.20, 40.00, 58.48, 41.52, 16.96 +41.20, 40.00, 58.47, 41.53, 16.95 +41.20, 40.00, 58.47, 41.53, 16.94 +41.13, 40.00, 60.99, 39.01, 21.97 +41.20, 40.00, 55.99, 44.01, 11.98 +41.20, 40.00, 58.46, 41.54, 16.91 +41.20, 40.00, 58.45, 41.55, 16.90 +41.20, 40.00, 58.45, 41.55, 16.90 +41.20, 40.00, 58.44, 41.56, 16.89 +41.20, 40.00, 58.44, 41.56, 16.88 +41.20, 40.00, 58.43, 41.57, 16.87 +41.20, 40.00, 58.43, 41.57, 16.86 +41.20, 40.00, 58.43, 41.57, 16.85 +41.20, 40.00, 58.42, 41.58, 16.84 +41.20, 40.00, 58.42, 41.58, 16.83 +41.20, 40.00, 58.41, 41.59, 16.82 +41.20, 40.00, 58.41, 41.59, 16.81 +41.20, 40.00, 58.40, 41.60, 16.81 +41.20, 40.00, 58.40, 41.60, 16.80 +41.20, 40.00, 58.39, 41.61, 16.79 +41.20, 40.00, 58.39, 41.61, 16.78 +41.20, 40.00, 58.38, 41.62, 16.77 +41.20, 40.00, 58.38, 41.62, 16.76 +41.20, 40.00, 58.38, 41.62, 16.75 +41.20, 40.00, 58.37, 41.63, 16.74 +41.20, 40.00, 58.37, 41.63, 16.73 +41.20, 40.00, 58.36, 41.64, 16.73 +41.20, 40.00, 58.36, 41.64, 16.72 +41.20, 40.00, 58.35, 41.65, 16.71 +41.20, 40.00, 58.35, 41.65, 16.70 +41.20, 40.00, 58.34, 41.66, 16.69 +41.20, 40.00, 58.34, 41.66, 16.68 +41.20, 40.00, 58.34, 41.66, 16.67 +41.20, 40.00, 58.33, 41.67, 16.66 +41.20, 40.00, 58.33, 41.67, 16.65 +41.20, 40.00, 58.32, 41.68, 16.64 +41.20, 40.00, 58.32, 41.68, 16.64 +41.20, 40.00, 58.31, 41.69, 16.63 +41.20, 40.00, 58.31, 41.69, 16.62 +41.20, 40.00, 58.30, 41.70, 16.61 +41.20, 40.00, 58.30, 41.70, 16.60 +41.20, 40.00, 58.30, 41.70, 16.59 +41.20, 40.00, 58.29, 41.71, 16.58 +41.20, 40.00, 58.29, 41.71, 16.57 +41.20, 40.00, 58.28, 41.72, 16.56 +41.20, 40.00, 58.28, 41.72, 16.55 +41.20, 40.00, 58.27, 41.73, 16.55 +41.20, 40.00, 58.27, 41.73, 16.54 +41.20, 40.00, 58.26, 41.74, 16.53 +41.20, 40.00, 58.26, 41.74, 16.52 +41.20, 40.00, 58.25, 41.75, 16.51 +41.20, 40.00, 58.25, 41.75, 16.50 +41.20, 40.00, 58.25, 41.75, 16.49 +41.20, 40.00, 58.24, 41.76, 16.48 +41.20, 40.00, 58.24, 41.76, 16.47 +41.20, 40.00, 58.23, 41.77, 16.46 +41.20, 40.00, 58.23, 41.77, 16.46 +41.20, 40.00, 58.22, 41.78, 16.45 +41.20, 40.00, 58.22, 41.78, 16.44 +41.20, 40.00, 58.21, 41.79, 16.43 +41.20, 40.00, 58.21, 41.79, 16.42 +41.20, 40.00, 58.21, 41.79, 16.41 +41.20, 40.00, 58.20, 41.80, 16.40 +41.20, 40.00, 58.20, 41.80, 16.39 +41.20, 40.00, 58.19, 41.81, 16.38 +41.20, 40.00, 58.19, 41.81, 16.37 +41.20, 40.00, 58.18, 41.82, 16.37 +41.20, 40.00, 58.18, 41.82, 16.36 +41.20, 40.00, 58.17, 41.83, 16.35 +41.20, 40.00, 58.17, 41.83, 16.34 +41.20, 40.00, 58.16, 41.84, 16.33 +41.20, 40.00, 58.16, 41.84, 16.32 +41.20, 40.00, 58.16, 41.84, 16.31 +41.20, 40.00, 58.15, 41.85, 16.30 +41.20, 40.00, 58.15, 41.85, 16.29 +41.20, 40.00, 58.14, 41.86, 16.28 +41.20, 40.00, 58.14, 41.86, 16.28 +41.20, 40.00, 58.13, 41.87, 16.27 +41.20, 40.00, 58.13, 41.87, 16.26 +41.20, 40.00, 58.12, 41.88, 16.25 +41.20, 40.00, 58.12, 41.88, 16.24 +41.20, 40.00, 58.12, 41.88, 16.23 +41.20, 40.00, 58.11, 41.89, 16.22 +41.20, 40.00, 58.11, 41.89, 16.21 +41.20, 40.00, 58.10, 41.90, 16.20 +41.20, 40.00, 58.10, 41.90, 16.19 +41.20, 40.00, 58.09, 41.91, 16.19 +41.20, 40.00, 58.09, 41.91, 16.18 +41.20, 40.00, 58.08, 41.92, 16.17 +41.13, 40.00, 60.60, 39.40, 21.20 +41.13, 40.00, 58.12, 41.88, 16.25 +41.13, 40.00, 58.12, 41.88, 16.24 +41.13, 40.00, 58.12, 41.88, 16.23 +41.13, 40.00, 58.11, 41.89, 16.22 +41.13, 40.00, 58.11, 41.89, 16.22 +41.13, 40.00, 58.10, 41.90, 16.21 +41.20, 40.00, 55.58, 44.42, 11.16 +41.20, 40.00, 58.05, 41.95, 16.09 +41.20, 40.00, 58.04, 41.96, 16.08 +41.20, 40.00, 58.04, 41.96, 16.07 +41.20, 40.00, 58.03, 41.97, 16.06 +41.20, 40.00, 58.03, 41.97, 16.05 +41.20, 40.00, 58.02, 41.98, 16.05 +41.20, 40.00, 58.02, 41.98, 16.04 +41.20, 40.00, 58.01, 41.99, 16.03 +41.20, 40.00, 58.01, 41.99, 16.02 +41.20, 40.00, 58.00, 42.00, 16.01 +41.20, 40.00, 58.00, 42.00, 16.00 +41.13, 40.00, 60.52, 39.48, 21.03 +41.20, 40.00, 55.52, 44.48, 11.04 +41.20, 40.00, 57.99, 42.01, 15.97 +41.20, 40.00, 57.98, 42.02, 15.96 +41.20, 40.00, 57.98, 42.02, 15.96 +41.20, 40.00, 57.97, 42.03, 15.95 +41.20, 40.00, 57.97, 42.03, 15.94 +41.20, 40.00, 57.96, 42.04, 15.93 +41.20, 40.00, 57.96, 42.04, 15.92 +41.20, 40.00, 57.96, 42.04, 15.91 +41.20, 40.00, 57.95, 42.05, 15.90 +41.20, 40.00, 57.95, 42.05, 15.89 +41.20, 40.00, 57.94, 42.06, 15.88 +41.20, 40.00, 57.94, 42.06, 15.87 +41.20, 40.00, 57.93, 42.07, 15.87 +41.20, 40.00, 57.93, 42.07, 15.86 +41.13, 40.00, 60.45, 39.55, 20.89 +41.20, 40.00, 55.45, 44.55, 10.90 +41.13, 40.00, 60.44, 39.56, 20.87 +41.13, 40.00, 57.96, 42.04, 15.92 +41.13, 40.00, 57.96, 42.04, 15.91 +41.20, 40.00, 55.43, 44.57, 10.86 +41.20, 40.00, 57.90, 42.10, 15.80 +41.20, 40.00, 57.89, 42.11, 15.79 +41.20, 40.00, 57.89, 42.11, 15.78 +41.20, 40.00, 57.88, 42.12, 15.77 +41.20, 40.00, 57.88, 42.12, 15.76 +41.20, 40.00, 57.88, 42.12, 15.75 +41.20, 40.00, 57.87, 42.13, 15.74 +41.20, 40.00, 57.87, 42.13, 15.73 +41.20, 40.00, 57.86, 42.14, 15.72 +41.20, 40.00, 57.86, 42.14, 15.72 +41.13, 40.00, 60.37, 39.63, 20.75 +41.20, 40.00, 55.38, 44.62, 10.75 +41.13, 40.00, 60.37, 39.63, 20.73 +41.20, 40.00, 55.37, 44.63, 10.74 +41.13, 40.00, 60.36, 39.64, 20.71 +41.20, 40.00, 55.36, 44.64, 10.72 +41.20, 40.00, 57.83, 42.17, 15.65 +41.20, 40.00, 57.82, 42.18, 15.64 +41.20, 40.00, 57.82, 42.18, 15.64 +41.20, 40.00, 57.81, 42.19, 15.63 +41.20, 40.00, 57.81, 42.19, 15.62 +41.20, 40.00, 57.80, 42.20, 15.61 +41.20, 40.00, 57.80, 42.20, 15.60 +41.20, 40.00, 57.80, 42.20, 15.59 +41.20, 40.00, 57.79, 42.21, 15.58 +41.20, 40.00, 57.79, 42.21, 15.57 +41.20, 40.00, 57.78, 42.22, 15.56 +41.20, 40.00, 57.78, 42.22, 15.55 +41.13, 40.00, 60.29, 39.71, 20.59 +41.13, 40.00, 57.82, 42.18, 15.64 +41.13, 40.00, 57.81, 42.19, 15.63 +41.13, 40.00, 57.81, 42.19, 15.62 +41.20, 40.00, 55.28, 44.72, 10.57 +41.20, 40.00, 57.75, 42.25, 15.50 +41.20, 40.00, 57.75, 42.25, 15.49 +41.20, 40.00, 57.74, 42.26, 15.48 +41.20, 40.00, 57.74, 42.26, 15.48 +41.20, 40.00, 57.73, 42.27, 15.47 +41.20, 40.00, 57.73, 42.27, 15.46 +41.20, 40.00, 57.72, 42.28, 15.45 +41.20, 40.00, 57.72, 42.28, 15.44 +41.20, 40.00, 57.72, 42.28, 15.43 +41.20, 40.00, 57.71, 42.29, 15.42 +41.20, 40.00, 57.71, 42.29, 15.41 +41.13, 40.00, 60.22, 39.78, 20.45 +41.20, 40.00, 55.23, 44.77, 10.45 +41.20, 40.00, 57.69, 42.31, 15.39 +41.20, 40.00, 57.69, 42.31, 15.38 +41.20, 40.00, 57.68, 42.32, 15.37 +41.20, 40.00, 57.68, 42.32, 15.36 +41.20, 40.00, 57.68, 42.32, 15.35 +41.20, 40.00, 57.67, 42.33, 15.34 +41.20, 40.00, 57.67, 42.33, 15.33 +41.20, 40.00, 57.66, 42.34, 15.32 +41.20, 40.00, 57.66, 42.34, 15.31 +41.20, 40.00, 57.65, 42.35, 15.31 +41.20, 40.00, 57.65, 42.35, 15.30 +41.20, 40.00, 57.64, 42.36, 15.29 +41.20, 40.00, 57.64, 42.36, 15.28 +41.20, 40.00, 57.63, 42.37, 15.27 +41.20, 40.00, 57.63, 42.37, 15.26 +41.20, 40.00, 57.63, 42.37, 15.25 +41.20, 40.00, 57.62, 42.38, 15.24 +41.20, 40.00, 57.62, 42.38, 15.23 +41.20, 40.00, 57.61, 42.39, 15.22 +41.20, 40.00, 57.61, 42.39, 15.22 +41.13, 40.00, 60.12, 39.88, 20.25 +41.20, 40.00, 55.13, 44.87, 10.25 +41.20, 40.00, 57.59, 42.41, 15.19 +41.20, 40.00, 57.59, 42.41, 15.18 +41.20, 40.00, 57.59, 42.41, 15.17 +41.20, 40.00, 57.58, 42.42, 15.16 +41.20, 40.00, 57.58, 42.42, 15.15 +41.20, 40.00, 57.57, 42.43, 15.14 +41.20, 40.00, 57.57, 42.43, 15.14 +41.20, 40.00, 57.56, 42.44, 15.13 +41.20, 40.00, 57.56, 42.44, 15.12 +41.20, 40.00, 57.55, 42.45, 15.11 +41.20, 40.00, 57.55, 42.45, 15.10 +41.20, 40.00, 57.55, 42.45, 15.09 +41.20, 40.00, 57.54, 42.46, 15.08 +41.20, 40.00, 57.54, 42.46, 15.07 +41.20, 40.00, 57.53, 42.47, 15.06 +41.20, 40.00, 57.53, 42.47, 15.05 +41.20, 40.00, 57.52, 42.48, 15.05 +41.13, 40.00, 60.04, 39.96, 20.08 +41.20, 40.00, 55.04, 44.96, 10.08 +41.20, 40.00, 57.51, 42.49, 15.02 +41.20, 40.00, 57.50, 42.50, 15.01 +41.20, 40.00, 57.50, 42.50, 15.00 +41.20, 40.00, 57.50, 42.50, 14.99 +41.20, 40.00, 57.49, 42.51, 14.98 +41.20, 40.00, 57.49, 42.51, 14.97 +41.20, 40.00, 57.48, 42.52, 14.96 +41.20, 40.00, 57.48, 42.52, 14.96 +41.20, 40.00, 57.47, 42.53, 14.95 +41.20, 40.00, 57.47, 42.53, 14.94 +41.20, 40.00, 57.46, 42.54, 14.93 +41.20, 40.00, 57.46, 42.54, 14.92 +41.20, 40.00, 57.46, 42.54, 14.91 +41.20, 40.00, 57.45, 42.55, 14.90 +41.20, 40.00, 57.45, 42.55, 14.89 +41.20, 40.00, 57.44, 42.56, 14.88 +41.20, 40.00, 57.44, 42.56, 14.87 +41.20, 40.00, 57.43, 42.57, 14.87 +41.20, 40.00, 57.43, 42.57, 14.86 +41.20, 40.00, 57.42, 42.58, 14.85 +41.20, 40.00, 57.42, 42.58, 14.84 +41.20, 40.00, 57.41, 42.59, 14.83 +41.20, 40.00, 57.41, 42.59, 14.82 +41.20, 40.00, 57.41, 42.59, 14.81 +41.20, 40.00, 57.40, 42.60, 14.80 +41.20, 40.00, 57.40, 42.60, 14.79 +41.20, 40.00, 57.39, 42.61, 14.78 +41.20, 40.00, 57.39, 42.61, 14.78 +41.20, 40.00, 57.38, 42.62, 14.77 +41.20, 40.00, 57.38, 42.62, 14.76 +41.20, 40.00, 57.37, 42.63, 14.75 +41.13, 40.00, 59.89, 40.11, 19.78 +41.20, 40.00, 54.89, 45.11, 9.79 +41.13, 40.00, 59.88, 40.12, 19.77 +41.13, 40.00, 57.41, 42.59, 14.81 +41.13, 40.00, 57.40, 42.60, 14.80 +41.13, 40.00, 57.40, 42.60, 14.80 +41.13, 40.00, 57.39, 42.61, 14.79 +41.13, 40.00, 57.39, 42.61, 14.78 +41.13, 40.00, 57.39, 42.61, 14.77 +41.13, 40.00, 57.38, 42.62, 14.76 +41.13, 40.00, 57.38, 42.62, 14.75 +41.20, 40.00, 54.85, 45.15, 9.70 +41.20, 40.00, 57.32, 42.68, 14.64 +41.20, 40.00, 57.31, 42.69, 14.63 +41.20, 40.00, 57.31, 42.69, 14.62 +41.20, 40.00, 57.31, 42.69, 14.61 +41.20, 40.00, 57.30, 42.70, 14.60 +41.20, 40.00, 57.30, 42.70, 14.59 +41.20, 40.00, 57.29, 42.71, 14.58 +41.13, 40.00, 59.81, 40.19, 19.62 +41.20, 40.00, 54.81, 45.19, 9.62 +41.20, 40.00, 57.28, 42.72, 14.56 +41.13, 40.00, 59.80, 40.20, 19.59 +41.13, 40.00, 57.32, 42.68, 14.64 +41.20, 40.00, 54.79, 45.21, 9.59 +41.13, 40.00, 59.78, 40.22, 19.56 +41.20, 40.00, 54.78, 45.22, 9.57 +41.13, 40.00, 59.77, 40.23, 19.55 +41.13, 40.00, 57.30, 42.70, 14.60 +41.20, 40.00, 54.77, 45.23, 9.54 +41.20, 40.00, 57.24, 42.76, 14.48 +41.20, 40.00, 57.23, 42.77, 14.47 +41.20, 40.00, 57.23, 42.77, 14.46 +41.20, 40.00, 57.23, 42.77, 14.45 +41.20, 40.00, 57.22, 42.78, 14.44 +41.13, 40.00, 59.74, 40.26, 19.48 +41.20, 40.00, 54.74, 45.26, 9.48 +41.20, 40.00, 57.21, 42.79, 14.42 +41.20, 40.00, 57.20, 42.80, 14.41 +41.20, 40.00, 57.20, 42.80, 14.40 +41.20, 40.00, 57.19, 42.81, 14.39 +41.20, 40.00, 57.19, 42.81, 14.38 +41.20, 40.00, 57.19, 42.81, 14.37 +41.20, 40.00, 57.18, 42.82, 14.36 +41.20, 40.00, 57.18, 42.82, 14.35 +41.20, 40.00, 57.17, 42.83, 14.34 +41.20, 40.00, 57.17, 42.83, 14.33 +41.20, 40.00, 57.16, 42.84, 14.33 +41.20, 40.00, 57.16, 42.84, 14.32 +41.20, 40.00, 57.15, 42.85, 14.31 +41.20, 40.00, 57.15, 42.85, 14.30 +41.20, 40.00, 57.14, 42.86, 14.29 +41.20, 40.00, 57.14, 42.86, 14.28 +41.20, 40.00, 57.14, 42.86, 14.27 +41.20, 40.00, 57.13, 42.87, 14.26 +41.20, 40.00, 57.13, 42.87, 14.25 +41.20, 40.00, 57.12, 42.88, 14.24 +41.20, 40.00, 57.12, 42.88, 14.24 +41.20, 40.00, 57.11, 42.89, 14.23 +41.20, 40.00, 57.11, 42.89, 14.22 +41.20, 40.00, 57.10, 42.90, 14.21 +41.20, 40.00, 57.10, 42.90, 14.20 +41.20, 40.00, 57.10, 42.90, 14.19 +41.20, 40.00, 57.09, 42.91, 14.18 +41.20, 40.00, 57.09, 42.91, 14.17 +41.20, 40.00, 57.08, 42.92, 14.16 +41.20, 40.00, 57.08, 42.92, 14.16 +41.20, 40.00, 57.07, 42.93, 14.15 +41.13, 40.00, 59.59, 40.41, 19.18 +41.20, 40.00, 54.59, 45.41, 9.18 +41.20, 40.00, 57.06, 42.94, 14.12 +41.20, 40.00, 57.06, 42.94, 14.11 +41.20, 40.00, 57.05, 42.95, 14.10 +41.20, 40.00, 57.05, 42.95, 14.09 +41.20, 40.00, 57.04, 42.96, 14.08 +41.20, 40.00, 57.04, 42.96, 14.07 +41.20, 40.00, 57.03, 42.97, 14.07 +41.20, 40.00, 57.03, 42.97, 14.06 +41.20, 40.00, 57.02, 42.98, 14.05 +41.20, 40.00, 57.02, 42.98, 14.04 +41.20, 40.00, 57.01, 42.99, 14.03 +41.20, 40.00, 57.01, 42.99, 14.02 +41.20, 40.00, 57.01, 42.99, 14.01 +41.20, 40.00, 57.00, 43.00, 14.00 +41.20, 40.00, 57.00, 43.00, 13.99 +41.20, 40.00, 56.99, 43.01, 13.98 +41.20, 40.00, 56.99, 43.01, 13.98 +41.20, 40.00, 56.98, 43.02, 13.97 +41.20, 40.00, 56.98, 43.02, 13.96 +41.20, 40.00, 56.97, 43.03, 13.95 +41.20, 40.00, 56.97, 43.03, 13.94 +41.20, 40.00, 56.97, 43.03, 13.93 +41.20, 40.00, 56.96, 43.04, 13.92 +41.20, 40.00, 56.96, 43.04, 13.91 +41.20, 40.00, 56.95, 43.05, 13.90 +41.20, 40.00, 56.95, 43.05, 13.89 +41.20, 40.00, 56.94, 43.06, 13.89 +41.20, 40.00, 56.94, 43.06, 13.88 +41.20, 40.00, 56.93, 43.07, 13.87 +41.20, 40.00, 56.93, 43.07, 13.86 +41.20, 40.00, 56.92, 43.08, 13.85 +41.20, 40.00, 56.92, 43.08, 13.84 +41.20, 40.00, 56.92, 43.08, 13.83 +41.20, 40.00, 56.91, 43.09, 13.82 +41.20, 40.00, 56.91, 43.09, 13.81 +41.20, 40.00, 56.90, 43.10, 13.80 +41.20, 40.00, 56.90, 43.10, 13.80 +41.20, 40.00, 56.89, 43.11, 13.79 +41.20, 40.00, 56.89, 43.11, 13.78 +41.20, 40.00, 56.88, 43.12, 13.77 +41.20, 40.00, 56.88, 43.12, 13.76 +41.20, 40.00, 56.88, 43.12, 13.75 +41.20, 40.00, 56.87, 43.13, 13.74 +41.20, 40.00, 56.87, 43.13, 13.73 +41.20, 40.00, 56.86, 43.14, 13.72 +41.20, 40.00, 56.86, 43.14, 13.72 +41.20, 40.00, 56.85, 43.15, 13.71 +41.20, 40.00, 56.85, 43.15, 13.70 +41.20, 40.00, 56.84, 43.16, 13.69 +41.20, 40.00, 56.84, 43.16, 13.68 +41.20, 40.00, 56.84, 43.16, 13.67 +41.20, 40.00, 56.83, 43.17, 13.66 +41.20, 40.00, 56.83, 43.17, 13.65 +41.20, 40.00, 56.82, 43.18, 13.64 +41.20, 40.00, 56.82, 43.18, 13.63 +41.20, 40.00, 56.81, 43.19, 13.63 +41.20, 40.00, 56.81, 43.19, 13.62 +41.20, 40.00, 56.80, 43.20, 13.61 +41.20, 40.00, 56.80, 43.20, 13.60 +41.20, 40.00, 56.79, 43.21, 13.59 +41.20, 40.00, 56.79, 43.21, 13.58 +41.20, 40.00, 56.79, 43.21, 13.57 +41.20, 40.00, 56.78, 43.22, 13.56 +41.20, 40.00, 56.78, 43.22, 13.55 +41.20, 40.00, 56.77, 43.23, 13.54 +41.20, 40.00, 56.77, 43.23, 13.54 +41.20, 40.00, 56.76, 43.24, 13.53 +41.20, 40.00, 56.76, 43.24, 13.52 +41.20, 40.00, 56.75, 43.25, 13.51 +41.20, 40.00, 56.75, 43.25, 13.50 +41.20, 40.00, 56.75, 43.25, 13.49 +41.20, 40.00, 56.74, 43.26, 13.48 +41.20, 40.00, 56.74, 43.26, 13.47 +41.20, 40.00, 56.73, 43.27, 13.46 +41.20, 40.00, 56.73, 43.27, 13.45 +41.20, 40.00, 56.72, 43.28, 13.45 +41.20, 40.00, 56.72, 43.28, 13.44 +41.20, 40.00, 56.71, 43.29, 13.43 +41.20, 40.00, 56.71, 43.29, 13.42 +41.20, 40.00, 56.70, 43.30, 13.41 +41.20, 40.00, 56.70, 43.30, 13.40 +41.20, 40.00, 56.70, 43.30, 13.39 +41.20, 40.00, 56.69, 43.31, 13.38 +41.20, 40.00, 56.69, 43.31, 13.37 +41.20, 40.00, 56.68, 43.32, 13.36 +41.20, 40.00, 56.68, 43.32, 13.36 +41.20, 40.00, 56.67, 43.33, 13.35 +41.20, 40.00, 56.67, 43.33, 13.34 +41.20, 40.00, 56.66, 43.34, 13.33 +41.20, 40.00, 56.66, 43.34, 13.32 +41.20, 40.00, 56.66, 43.34, 13.31 +41.20, 40.00, 56.65, 43.35, 13.30 +41.20, 40.00, 56.65, 43.35, 13.29 +41.20, 40.00, 56.64, 43.36, 13.28 +41.20, 40.00, 56.64, 43.36, 13.27 +41.20, 40.00, 56.63, 43.37, 13.27 +41.20, 40.00, 56.63, 43.37, 13.26 +41.20, 40.00, 56.62, 43.38, 13.25 +41.20, 40.00, 56.62, 43.38, 13.24 +41.20, 40.00, 56.61, 43.39, 13.23 +41.20, 40.00, 56.61, 43.39, 13.22 +41.20, 40.00, 56.61, 43.39, 13.21 +41.20, 40.00, 56.60, 43.40, 13.20 +41.20, 40.00, 56.60, 43.40, 13.19 +41.20, 40.00, 56.59, 43.41, 13.18 +41.20, 40.00, 56.59, 43.41, 13.18 +41.13, 40.00, 59.10, 40.90, 18.21 +41.20, 40.00, 54.11, 45.89, 8.21 +41.20, 40.00, 56.57, 43.43, 13.15 +41.20, 40.00, 56.57, 43.43, 13.14 +41.20, 40.00, 56.57, 43.43, 13.13 +41.20, 40.00, 56.56, 43.44, 13.12 +41.20, 40.00, 56.56, 43.44, 13.11 +41.20, 40.00, 56.55, 43.45, 13.10 +41.20, 40.00, 56.55, 43.45, 13.10 +41.20, 40.00, 56.54, 43.46, 13.09 +41.20, 40.00, 56.54, 43.46, 13.08 +41.20, 40.00, 56.53, 43.47, 13.07 +41.13, 40.00, 59.05, 40.95, 18.10 +41.13, 40.00, 56.58, 43.42, 13.15 +41.13, 40.00, 56.57, 43.43, 13.14 +41.13, 40.00, 56.57, 43.43, 13.13 +41.13, 40.00, 56.56, 43.44, 13.12 +41.13, 40.00, 56.56, 43.44, 13.12 +41.20, 40.00, 54.03, 45.97, 8.06 +41.20, 40.00, 56.50, 43.50, 13.00 +41.20, 40.00, 56.50, 43.50, 12.99 +41.20, 40.00, 56.49, 43.51, 12.98 +41.20, 40.00, 56.49, 43.51, 12.97 +41.20, 40.00, 56.48, 43.52, 12.96 +41.20, 40.00, 56.48, 43.52, 12.95 +41.20, 40.00, 56.47, 43.53, 12.95 +41.20, 40.00, 56.47, 43.53, 12.94 +41.20, 40.00, 56.46, 43.54, 12.93 +41.20, 40.00, 56.46, 43.54, 12.92 +41.20, 40.00, 56.45, 43.55, 12.91 +41.20, 40.00, 56.45, 43.55, 12.90 +41.20, 40.00, 56.45, 43.55, 12.89 +41.13, 40.00, 58.96, 41.04, 17.93 +41.20, 40.00, 53.97, 46.03, 7.93 +41.13, 40.00, 58.95, 41.05, 17.91 +41.20, 40.00, 53.96, 46.04, 7.91 +41.13, 40.00, 58.95, 41.05, 17.89 +41.13, 40.00, 56.47, 43.53, 12.94 +41.20, 40.00, 53.94, 46.06, 7.89 +41.20, 40.00, 56.41, 43.59, 12.82 +41.20, 40.00, 56.41, 43.59, 12.81 +41.20, 40.00, 56.40, 43.60, 12.80 +41.20, 40.00, 56.40, 43.60, 12.79 +41.20, 40.00, 56.39, 43.61, 12.79 +41.13, 40.00, 58.91, 41.09, 17.82 +41.20, 40.00, 53.91, 46.09, 7.82 +41.13, 40.00, 58.90, 41.10, 17.80 +41.13, 40.00, 56.42, 43.58, 12.85 +41.13, 40.00, 56.42, 43.58, 12.84 +41.13, 40.00, 56.42, 43.58, 12.83 +41.13, 40.00, 56.41, 43.59, 12.82 +41.13, 40.00, 56.41, 43.59, 12.82 +41.13, 40.00, 56.40, 43.60, 12.81 +41.20, 40.00, 53.88, 46.12, 7.76 +41.20, 40.00, 56.35, 43.65, 12.69 +41.20, 40.00, 56.34, 43.66, 12.68 +41.13, 40.00, 58.86, 41.14, 17.72 +41.20, 40.00, 53.86, 46.14, 7.72 +41.20, 40.00, 56.33, 43.67, 12.66 +41.20, 40.00, 56.32, 43.68, 12.65 +41.20, 40.00, 56.32, 43.68, 12.64 +41.13, 40.00, 58.84, 41.16, 17.67 +41.20, 40.00, 53.84, 46.16, 7.68 +41.13, 40.00, 58.83, 41.17, 17.65 +41.13, 40.00, 56.35, 43.65, 12.70 +41.13, 40.00, 56.35, 43.65, 12.69 +41.13, 40.00, 56.34, 43.66, 12.68 +41.13, 40.00, 56.34, 43.66, 12.68 +41.13, 40.00, 56.33, 43.67, 12.67 +41.13, 40.00, 56.33, 43.67, 12.66 +41.13, 40.00, 56.33, 43.67, 12.65 +41.13, 40.00, 56.32, 43.68, 12.64 +41.13, 40.00, 56.32, 43.68, 12.63 +41.13, 40.00, 56.31, 43.69, 12.62 +41.13, 40.00, 56.31, 43.69, 12.62 +41.20, 40.00, 53.78, 46.22, 7.56 +41.13, 40.00, 58.77, 41.23, 17.54 +41.13, 40.00, 56.30, 43.70, 12.59 +41.13, 40.00, 56.29, 43.71, 12.58 +41.13, 40.00, 56.29, 43.71, 12.57 +41.13, 40.00, 56.28, 43.72, 12.57 +41.13, 40.00, 56.28, 43.72, 12.56 +41.13, 40.00, 56.27, 43.73, 12.55 +41.13, 40.00, 56.27, 43.73, 12.54 +41.13, 40.00, 56.27, 43.73, 12.53 +41.13, 40.00, 56.26, 43.74, 12.52 +41.13, 40.00, 56.26, 43.74, 12.51 +41.13, 40.00, 56.25, 43.75, 12.51 +41.13, 40.00, 56.25, 43.75, 12.50 +41.13, 40.00, 56.24, 43.76, 12.49 +41.13, 40.00, 56.24, 43.76, 12.48 +41.13, 40.00, 56.24, 43.76, 12.47 +41.13, 40.00, 56.23, 43.77, 12.46 +41.13, 40.00, 56.23, 43.77, 12.45 +41.13, 40.00, 56.22, 43.78, 12.45 +41.13, 40.00, 56.22, 43.78, 12.44 +41.13, 40.00, 56.21, 43.79, 12.43 +41.13, 40.00, 56.21, 43.79, 12.42 +41.13, 40.00, 56.21, 43.79, 12.41 +41.13, 40.00, 56.20, 43.80, 12.40 +41.13, 40.00, 56.20, 43.80, 12.40 +41.13, 40.00, 56.19, 43.81, 12.39 +41.13, 40.00, 56.19, 43.81, 12.38 +41.13, 40.00, 56.18, 43.82, 12.37 +41.13, 40.00, 56.18, 43.82, 12.36 +41.13, 40.00, 56.18, 43.82, 12.35 +41.13, 40.00, 56.17, 43.83, 12.34 +41.20, 40.00, 53.65, 46.35, 7.29 +41.20, 40.00, 56.11, 43.89, 12.23 +41.20, 40.00, 56.11, 43.89, 12.22 +41.13, 40.00, 58.63, 41.37, 17.25 +41.13, 40.00, 56.15, 43.85, 12.30 +41.13, 40.00, 56.15, 43.85, 12.29 +41.13, 40.00, 56.14, 43.86, 12.28 +41.13, 40.00, 56.14, 43.86, 12.27 +41.13, 40.00, 56.13, 43.87, 12.27 +41.13, 40.00, 56.13, 43.87, 12.26 +41.13, 40.00, 56.12, 43.88, 12.25 +41.13, 40.00, 56.12, 43.88, 12.24 +41.13, 40.00, 56.12, 43.88, 12.23 +41.13, 40.00, 56.11, 43.89, 12.22 +41.13, 40.00, 56.11, 43.89, 12.22 +41.13, 40.00, 56.10, 43.90, 12.21 +41.13, 40.00, 56.10, 43.90, 12.20 +41.13, 40.00, 56.09, 43.91, 12.19 +41.13, 40.00, 56.09, 43.91, 12.18 +41.13, 40.00, 56.09, 43.91, 12.17 +41.13, 40.00, 56.08, 43.92, 12.16 +41.13, 40.00, 56.08, 43.92, 12.16 +41.13, 40.00, 56.07, 43.93, 12.15 +41.13, 40.00, 56.07, 43.93, 12.14 +41.13, 40.00, 56.07, 43.93, 12.13 +41.13, 40.00, 56.06, 43.94, 12.12 +41.13, 40.00, 56.06, 43.94, 12.11 +41.13, 40.00, 56.05, 43.95, 12.10 +41.13, 40.00, 56.05, 43.95, 12.10 +41.13, 40.00, 56.04, 43.96, 12.09 +41.13, 40.00, 56.04, 43.96, 12.08 +41.13, 40.00, 56.04, 43.96, 12.07 +41.13, 40.00, 56.03, 43.97, 12.06 +41.20, 40.00, 53.51, 46.49, 7.01 +41.13, 40.00, 58.49, 41.51, 16.99 +41.20, 40.00, 53.50, 46.50, 6.99 +41.13, 40.00, 58.49, 41.51, 16.97 +41.13, 40.00, 56.01, 43.99, 12.02 +41.13, 40.00, 56.01, 43.99, 12.01 +41.13, 40.00, 56.00, 44.00, 12.00 +41.13, 40.00, 56.00, 44.00, 11.99 +41.13, 40.00, 55.99, 44.01, 11.98 +41.13, 40.00, 55.99, 44.01, 11.98 +41.13, 40.00, 55.98, 44.02, 11.97 +41.13, 40.00, 55.98, 44.02, 11.96 +41.13, 40.00, 55.98, 44.02, 11.95 +41.13, 40.00, 55.97, 44.03, 11.94 +41.13, 40.00, 55.97, 44.03, 11.93 +41.13, 40.00, 55.96, 44.04, 11.93 +41.13, 40.00, 55.96, 44.04, 11.92 +41.13, 40.00, 55.95, 44.05, 11.91 +41.00, 40.00, 60.99, 39.01, 21.99 +41.13, 40.00, 51.00, 49.00, 2.00 +41.13, 40.00, 55.94, 44.06, 11.88 +41.13, 40.00, 55.94, 44.06, 11.88 +41.00, 40.00, 60.98, 39.02, 21.95 +41.13, 40.00, 50.99, 49.01, 1.97 +41.00, 40.00, 60.97, 39.03, 21.94 +41.00, 40.00, 56.02, 43.98, 12.04 +41.00, 40.00, 56.02, 43.98, 12.03 +41.00, 40.00, 56.01, 43.99, 12.03 +41.00, 40.00, 56.01, 43.99, 12.02 +41.00, 40.00, 56.01, 43.99, 12.01 +41.00, 40.00, 56.00, 44.00, 12.00 +41.13, 40.00, 50.96, 49.04, 1.91 +41.13, 40.00, 55.89, 44.11, 11.79 +41.13, 40.00, 55.89, 44.11, 11.78 +41.13, 40.00, 55.89, 44.11, 11.77 +41.13, 40.00, 55.88, 44.12, 11.76 +41.13, 40.00, 55.88, 44.12, 11.76 +41.00, 40.00, 60.92, 39.08, 21.83 +41.00, 40.00, 55.97, 44.03, 11.94 +41.13, 40.00, 50.92, 49.08, 1.84 +41.00, 40.00, 60.91, 39.09, 21.81 +41.00, 40.00, 55.96, 44.04, 11.92 +41.00, 40.00, 55.95, 44.05, 11.91 +41.00, 40.00, 55.95, 44.05, 11.90 +41.13, 40.00, 50.90, 49.10, 1.81 +41.13, 40.00, 55.84, 44.16, 11.69 +41.13, 40.00, 55.84, 44.16, 11.68 +41.13, 40.00, 55.83, 44.17, 11.67 +41.13, 40.00, 55.83, 44.17, 11.66 +41.13, 40.00, 55.83, 44.17, 11.65 +41.13, 40.00, 55.82, 44.18, 11.64 +41.20, 40.00, 53.30, 46.70, 6.59 +41.20, 40.00, 55.76, 44.24, 11.53 +41.20, 40.00, 55.76, 44.24, 11.52 +41.13, 40.00, 58.28, 41.72, 16.55 +41.13, 40.00, 55.80, 44.20, 11.60 +41.13, 40.00, 55.80, 44.20, 11.59 +41.13, 40.00, 55.79, 44.21, 11.58 +41.13, 40.00, 55.79, 44.21, 11.57 +41.13, 40.00, 55.78, 44.22, 11.56 +41.13, 40.00, 55.78, 44.22, 11.56 +41.13, 40.00, 55.77, 44.23, 11.55 +41.13, 40.00, 55.77, 44.23, 11.54 +41.13, 40.00, 55.77, 44.23, 11.53 +41.13, 40.00, 55.76, 44.24, 11.52 +41.13, 40.00, 55.76, 44.24, 11.51 +41.13, 40.00, 55.75, 44.25, 11.51 +41.20, 40.00, 53.23, 46.77, 6.45 +41.13, 40.00, 58.22, 41.78, 16.43 +41.13, 40.00, 55.74, 44.26, 11.48 +41.13, 40.00, 55.74, 44.26, 11.47 +41.13, 40.00, 55.73, 44.27, 11.46 +41.13, 40.00, 55.73, 44.27, 11.45 +41.13, 40.00, 55.72, 44.28, 11.45 +41.13, 40.00, 55.72, 44.28, 11.44 +41.00, 40.00, 60.76, 39.24, 21.51 +41.00, 40.00, 55.81, 44.19, 11.62 +41.00, 40.00, 55.81, 44.19, 11.61 +41.00, 40.00, 55.80, 44.20, 11.60 +41.00, 40.00, 55.80, 44.20, 11.60 +41.00, 40.00, 55.79, 44.21, 11.59 +41.00, 40.00, 55.79, 44.21, 11.58 +41.00, 40.00, 55.79, 44.21, 11.57 +41.00, 40.00, 55.78, 44.22, 11.57 +41.00, 40.00, 55.78, 44.22, 11.56 +41.13, 40.00, 50.73, 49.27, 1.47 +41.13, 40.00, 55.67, 44.33, 11.34 +41.13, 40.00, 55.67, 44.33, 11.34 +41.00, 40.00, 60.71, 39.29, 21.41 +41.13, 40.00, 50.72, 49.28, 1.43 +41.13, 40.00, 55.66, 44.34, 11.31 +41.00, 40.00, 60.69, 39.31, 21.39 +41.00, 40.00, 55.75, 44.25, 11.49 +41.00, 40.00, 55.74, 44.26, 11.49 +41.00, 40.00, 55.74, 44.26, 11.48 +41.00, 40.00, 55.74, 44.26, 11.47 +41.00, 40.00, 55.73, 44.27, 11.46 +41.00, 40.00, 55.73, 44.27, 11.46 +41.00, 40.00, 55.72, 44.28, 11.45 +41.13, 40.00, 50.68, 49.32, 1.36 +41.13, 40.00, 55.62, 44.38, 11.23 +41.13, 40.00, 55.61, 44.39, 11.23 +41.13, 40.00, 55.61, 44.39, 11.22 +41.13, 40.00, 55.60, 44.40, 11.21 +41.13, 40.00, 55.60, 44.40, 11.20 +41.20, 40.00, 53.07, 46.93, 6.15 +41.20, 40.00, 55.54, 44.46, 11.08 +41.20, 40.00, 55.54, 44.46, 11.07 +41.20, 40.00, 55.53, 44.47, 11.07 +41.20, 40.00, 55.53, 44.47, 11.06 +41.13, 40.00, 58.05, 41.95, 16.09 +41.13, 40.00, 55.57, 44.43, 11.14 +41.13, 40.00, 55.57, 44.43, 11.13 +41.20, 40.00, 53.04, 46.96, 6.08 +41.13, 40.00, 58.03, 41.97, 16.06 +41.13, 40.00, 55.55, 44.45, 11.10 +41.13, 40.00, 55.55, 44.45, 11.10 +41.13, 40.00, 55.54, 44.46, 11.09 +41.13, 40.00, 55.54, 44.46, 11.08 +41.13, 40.00, 55.54, 44.46, 11.07 +41.20, 40.00, 53.01, 46.99, 6.02 +41.20, 40.00, 55.48, 44.52, 10.95 +41.20, 40.00, 55.47, 44.53, 10.94 +41.20, 40.00, 55.47, 44.53, 10.94 +41.20, 40.00, 55.46, 44.54, 10.93 +41.20, 40.00, 55.46, 44.54, 10.92 +41.13, 40.00, 57.98, 42.02, 15.95 +41.13, 40.00, 55.50, 44.50, 11.00 +41.13, 40.00, 55.50, 44.50, 10.99 +41.13, 40.00, 55.49, 44.51, 10.98 +41.13, 40.00, 55.49, 44.51, 10.97 +41.13, 40.00, 55.48, 44.52, 10.97 +41.13, 40.00, 55.48, 44.52, 10.96 +41.13, 40.00, 55.47, 44.53, 10.95 +41.13, 40.00, 55.47, 44.53, 10.94 +41.13, 40.00, 55.47, 44.53, 10.93 +41.13, 40.00, 55.46, 44.54, 10.92 +41.13, 40.00, 55.46, 44.54, 10.91 +41.13, 40.00, 55.45, 44.55, 10.91 +41.13, 40.00, 55.45, 44.55, 10.90 +41.13, 40.00, 55.44, 44.56, 10.89 +41.13, 40.00, 55.44, 44.56, 10.88 +41.13, 40.00, 55.44, 44.56, 10.87 +41.13, 40.00, 55.43, 44.57, 10.86 +41.13, 40.00, 55.43, 44.57, 10.86 +41.13, 40.00, 55.42, 44.58, 10.85 +41.13, 40.00, 55.42, 44.58, 10.84 +41.00, 40.00, 60.46, 39.54, 20.92 +41.00, 40.00, 55.51, 44.49, 11.02 +41.00, 40.00, 55.51, 44.49, 11.01 +41.00, 40.00, 55.50, 44.50, 11.01 +41.00, 40.00, 55.50, 44.50, 11.00 +41.00, 40.00, 55.50, 44.50, 10.99 +41.00, 40.00, 55.49, 44.51, 10.98 +40.94, 40.00, 58.01, 41.99, 16.02 +40.94, 40.00, 55.53, 44.47, 11.07 +40.94, 40.00, 55.53, 44.47, 11.06 +40.94, 40.00, 55.53, 44.47, 11.05 +40.94, 40.00, 55.52, 44.48, 11.05 +40.94, 40.00, 55.52, 44.48, 11.04 +40.94, 40.00, 55.52, 44.48, 11.03 +40.94, 40.00, 55.51, 44.49, 11.03 +40.94, 40.00, 55.51, 44.49, 11.02 +40.94, 40.00, 55.51, 44.49, 11.01 +40.94, 40.00, 55.50, 44.50, 11.00 +40.94, 40.00, 55.50, 44.50, 11.00 +40.94, 40.00, 55.50, 44.50, 10.99 +40.94, 40.00, 55.49, 44.51, 10.98 +40.94, 40.00, 55.49, 44.51, 10.98 +40.94, 40.00, 55.48, 44.52, 10.97 +40.94, 40.00, 55.48, 44.52, 10.96 +40.94, 40.00, 55.48, 44.52, 10.96 +40.94, 40.00, 55.47, 44.53, 10.95 +40.94, 40.00, 55.47, 44.53, 10.94 +40.94, 40.00, 55.47, 44.53, 10.93 +40.94, 40.00, 55.46, 44.54, 10.93 +40.94, 40.00, 55.46, 44.54, 10.92 +40.94, 40.00, 55.46, 44.54, 10.91 +40.94, 40.00, 55.45, 44.55, 10.91 +40.94, 40.00, 55.45, 44.55, 10.90 +40.94, 40.00, 55.45, 44.55, 10.89 +40.94, 40.00, 55.44, 44.56, 10.89 +40.94, 40.00, 55.44, 44.56, 10.88 +40.94, 40.00, 55.44, 44.56, 10.87 +40.94, 40.00, 55.43, 44.57, 10.86 +40.94, 40.00, 55.43, 44.57, 10.86 +40.94, 40.00, 55.43, 44.57, 10.85 +41.00, 40.00, 52.90, 47.10, 5.80 +40.94, 40.00, 57.89, 42.11, 15.78 +41.00, 40.00, 52.89, 47.11, 5.79 +41.00, 40.00, 55.36, 44.64, 10.72 +41.00, 40.00, 55.36, 44.64, 10.71 +41.00, 40.00, 55.35, 44.65, 10.71 +40.94, 40.00, 57.87, 42.13, 15.74 +40.94, 40.00, 55.40, 44.60, 10.79 +40.94, 40.00, 55.39, 44.61, 10.79 +40.94, 40.00, 55.39, 44.61, 10.78 +40.94, 40.00, 55.39, 44.61, 10.77 +40.94, 40.00, 55.38, 44.62, 10.76 +40.94, 40.00, 55.38, 44.62, 10.76 +41.00, 40.00, 52.85, 47.15, 5.71 +41.00, 40.00, 55.32, 44.68, 10.64 +41.00, 40.00, 55.32, 44.68, 10.64 +41.00, 40.00, 55.31, 44.69, 10.63 +41.00, 40.00, 55.31, 44.69, 10.62 +41.00, 40.00, 55.31, 44.69, 10.61 +41.13, 40.00, 50.26, 49.74, 0.52 +41.13, 40.00, 55.20, 44.80, 10.40 +41.00, 40.00, 60.24, 39.76, 20.48 +41.00, 40.00, 55.29, 44.71, 10.58 +41.00, 40.00, 55.29, 44.71, 10.57 +41.00, 40.00, 55.28, 44.72, 10.57 +41.00, 40.00, 55.28, 44.72, 10.56 +41.00, 40.00, 55.28, 44.72, 10.55 +41.00, 40.00, 55.27, 44.73, 10.54 +40.94, 40.00, 57.79, 42.21, 15.58 +40.94, 40.00, 55.31, 44.69, 10.63 +40.94, 40.00, 55.31, 44.69, 10.62 +40.94, 40.00, 55.31, 44.69, 10.61 +40.94, 40.00, 55.30, 44.70, 10.61 +40.94, 40.00, 55.30, 44.70, 10.60 +40.94, 40.00, 55.30, 44.70, 10.59 +40.94, 40.00, 55.29, 44.71, 10.59 +40.94, 40.00, 55.29, 44.71, 10.58 +41.00, 40.00, 52.76, 47.24, 5.53 +40.94, 40.00, 57.75, 42.25, 15.51 +40.94, 40.00, 55.28, 44.72, 10.56 +40.94, 40.00, 55.28, 44.72, 10.55 +40.94, 40.00, 55.27, 44.73, 10.54 +40.94, 40.00, 55.27, 44.73, 10.54 +40.94, 40.00, 55.26, 44.74, 10.53 +40.87, 40.00, 57.78, 42.22, 15.57 +40.87, 40.00, 55.31, 44.69, 10.62 +40.87, 40.00, 55.30, 44.70, 10.61 +40.87, 40.00, 55.30, 44.70, 10.60 +40.87, 40.00, 55.30, 44.70, 10.60 +40.87, 40.00, 55.29, 44.71, 10.59 +40.87, 40.00, 55.29, 44.71, 10.58 +40.87, 40.00, 55.29, 44.71, 10.58 +40.87, 40.00, 55.28, 44.72, 10.57 +40.87, 40.00, 55.28, 44.72, 10.56 +40.87, 40.00, 55.28, 44.72, 10.56 +40.87, 40.00, 55.28, 44.72, 10.55 +40.87, 40.00, 55.27, 44.73, 10.54 +40.87, 40.00, 55.27, 44.73, 10.54 +40.87, 40.00, 55.27, 44.73, 10.53 +40.87, 40.00, 55.26, 44.74, 10.52 +40.74, 40.00, 60.30, 39.70, 20.60 +40.74, 40.00, 55.36, 44.64, 10.71 +40.87, 40.00, 50.31, 49.69, 0.62 +40.74, 40.00, 60.29, 39.71, 20.59 +40.74, 40.00, 55.35, 44.65, 10.69 +40.74, 40.00, 55.34, 44.66, 10.69 +40.87, 40.00, 50.30, 49.70, 0.60 +40.87, 40.00, 55.24, 44.76, 10.48 +40.87, 40.00, 55.24, 44.76, 10.47 +40.87, 40.00, 55.23, 44.77, 10.46 +40.87, 40.00, 55.23, 44.77, 10.46 +40.87, 40.00, 55.23, 44.77, 10.45 +40.87, 40.00, 55.22, 44.78, 10.44 +40.87, 40.00, 55.22, 44.78, 10.44 +40.87, 40.00, 55.22, 44.78, 10.43 +40.94, 40.00, 52.69, 47.31, 5.38 +40.94, 40.00, 55.16, 44.84, 10.32 +40.94, 40.00, 55.16, 44.84, 10.31 +40.94, 40.00, 55.15, 44.85, 10.30 +40.94, 40.00, 55.15, 44.85, 10.30 +40.94, 40.00, 55.15, 44.85, 10.29 +40.94, 40.00, 55.14, 44.86, 10.28 +40.94, 40.00, 55.14, 44.86, 10.28 +40.94, 40.00, 55.13, 44.87, 10.27 +40.94, 40.00, 55.13, 44.87, 10.26 +40.94, 40.00, 55.13, 44.87, 10.26 +40.94, 40.00, 55.12, 44.88, 10.25 +40.94, 40.00, 55.12, 44.88, 10.24 +40.94, 40.00, 55.12, 44.88, 10.23 +41.00, 40.00, 52.59, 47.41, 5.18 +40.94, 40.00, 57.58, 42.42, 15.16 +41.00, 40.00, 52.58, 47.42, 5.17 +41.00, 40.00, 55.05, 44.95, 10.11 +41.00, 40.00, 55.05, 44.95, 10.10 +41.00, 40.00, 55.05, 44.95, 10.09 +41.00, 40.00, 55.04, 44.96, 10.08 +41.00, 40.00, 55.04, 44.96, 10.08 +41.00, 40.00, 55.03, 44.97, 10.07 +41.00, 40.00, 55.03, 44.97, 10.06 +41.00, 40.00, 55.03, 44.97, 10.05 +41.00, 40.00, 55.02, 44.98, 10.05 +41.00, 40.00, 55.02, 44.98, 10.04 +41.00, 40.00, 55.02, 44.98, 10.03 +41.00, 40.00, 55.01, 44.99, 10.02 +41.13, 40.00, 49.96, 50.04, -0.07 +41.00, 40.00, 59.95, 40.05, 19.90 +41.00, 40.00, 55.00, 45.00, 10.00 +41.00, 40.00, 55.00, 45.00, 9.99 +41.00, 40.00, 54.99, 45.01, 9.98 +41.00, 40.00, 54.99, 45.01, 9.98 +41.00, 40.00, 54.98, 45.02, 9.97 +41.00, 40.00, 54.98, 45.02, 9.96 +41.00, 40.00, 54.98, 45.02, 9.95 +41.00, 40.00, 54.97, 45.03, 9.95 +41.00, 40.00, 54.97, 45.03, 9.94 +41.00, 40.00, 54.97, 45.03, 9.93 +41.00, 40.00, 54.96, 45.04, 9.92 +40.94, 40.00, 57.48, 42.52, 14.96 +41.00, 40.00, 52.48, 47.52, 4.97 +40.94, 40.00, 57.47, 42.53, 14.95 +40.94, 40.00, 55.00, 45.00, 10.00 +40.94, 40.00, 54.99, 45.01, 9.99 +40.94, 40.00, 54.99, 45.01, 9.98 +41.00, 40.00, 52.47, 47.53, 4.93 +41.00, 40.00, 54.93, 45.07, 9.87 +41.00, 40.00, 54.93, 45.07, 9.86 +41.00, 40.00, 54.93, 45.07, 9.85 +41.00, 40.00, 54.92, 45.08, 9.84 +41.00, 40.00, 54.92, 45.08, 9.84 +41.00, 40.00, 54.91, 45.09, 9.83 +41.00, 40.00, 54.91, 45.09, 9.82 +40.94, 40.00, 57.43, 42.57, 14.86 +41.00, 40.00, 52.43, 47.57, 4.86 +40.94, 40.00, 57.42, 42.58, 14.84 +40.94, 40.00, 54.95, 45.05, 9.89 +40.94, 40.00, 54.94, 45.06, 9.89 +40.94, 40.00, 54.94, 45.06, 9.88 +40.94, 40.00, 54.94, 45.06, 9.87 +40.94, 40.00, 54.93, 45.07, 9.86 +40.94, 40.00, 54.93, 45.07, 9.86 +40.94, 40.00, 54.93, 45.07, 9.85 +40.94, 40.00, 54.92, 45.08, 9.84 +40.94, 40.00, 54.92, 45.08, 9.84 +40.94, 40.00, 54.91, 45.09, 9.83 +40.94, 40.00, 54.91, 45.09, 9.82 +40.94, 40.00, 54.91, 45.09, 9.82 +41.00, 40.00, 52.38, 47.62, 4.77 +40.94, 40.00, 57.37, 42.63, 14.74 +41.00, 40.00, 52.38, 47.62, 4.75 +41.00, 40.00, 54.84, 45.16, 9.69 +41.00, 40.00, 54.84, 45.16, 9.68 +41.00, 40.00, 54.84, 45.16, 9.67 +41.00, 40.00, 54.83, 45.17, 9.66 +41.00, 40.00, 54.83, 45.17, 9.66 +41.00, 40.00, 54.82, 45.18, 9.65 +41.00, 40.00, 54.82, 45.18, 9.64 +41.00, 40.00, 54.82, 45.18, 9.63 +41.00, 40.00, 54.81, 45.19, 9.63 +41.00, 40.00, 54.81, 45.19, 9.62 +41.00, 40.00, 54.81, 45.19, 9.61 +41.00, 40.00, 54.80, 45.20, 9.60 +41.00, 40.00, 54.80, 45.20, 9.60 +41.00, 40.00, 54.79, 45.21, 9.59 +41.00, 40.00, 54.79, 45.21, 9.58 +41.00, 40.00, 54.79, 45.21, 9.57 +41.00, 40.00, 54.78, 45.22, 9.57 +41.00, 40.00, 54.78, 45.22, 9.56 +41.00, 40.00, 54.78, 45.22, 9.55 +41.00, 40.00, 54.77, 45.23, 9.54 +41.00, 40.00, 54.77, 45.23, 9.54 +41.00, 40.00, 54.76, 45.24, 9.53 +41.00, 40.00, 54.76, 45.24, 9.52 +41.00, 40.00, 54.76, 45.24, 9.51 +41.00, 40.00, 54.75, 45.25, 9.51 +41.00, 40.00, 54.75, 45.25, 9.50 +41.00, 40.00, 54.75, 45.25, 9.49 +41.00, 40.00, 54.74, 45.26, 9.48 +41.00, 40.00, 54.74, 45.26, 9.48 +41.00, 40.00, 54.73, 45.27, 9.47 +41.00, 40.00, 54.73, 45.27, 9.46 +41.00, 40.00, 54.73, 45.27, 9.45 +40.94, 40.00, 57.25, 42.75, 14.49 +40.94, 40.00, 54.77, 45.23, 9.54 +40.94, 40.00, 54.77, 45.23, 9.53 +40.94, 40.00, 54.76, 45.24, 9.53 +40.94, 40.00, 54.76, 45.24, 9.52 +40.94, 40.00, 54.76, 45.24, 9.51 +40.94, 40.00, 54.75, 45.25, 9.50 +40.94, 40.00, 54.75, 45.25, 9.50 +40.87, 40.00, 57.27, 42.73, 14.53 +40.87, 40.00, 54.79, 45.21, 9.58 +40.87, 40.00, 54.79, 45.21, 9.58 +40.87, 40.00, 54.78, 45.22, 9.57 +40.94, 40.00, 52.26, 47.74, 4.52 +40.94, 40.00, 54.73, 45.27, 9.46 +40.94, 40.00, 54.72, 45.28, 9.45 +40.94, 40.00, 54.72, 45.28, 9.44 +40.87, 40.00, 57.24, 42.76, 14.48 +40.87, 40.00, 54.76, 45.24, 9.53 +40.87, 40.00, 54.76, 45.24, 9.52 +40.87, 40.00, 54.76, 45.24, 9.52 +40.87, 40.00, 54.75, 45.25, 9.51 +40.87, 40.00, 54.75, 45.25, 9.50 +40.87, 40.00, 54.75, 45.25, 9.50 +40.87, 40.00, 54.74, 45.26, 9.49 +40.87, 40.00, 54.74, 45.26, 9.48 +40.74, 40.00, 59.78, 40.22, 19.56 +40.74, 40.00, 54.83, 45.17, 9.67 +40.74, 40.00, 54.83, 45.17, 9.66 +40.74, 40.00, 54.83, 45.17, 9.66 +40.74, 40.00, 54.83, 45.17, 9.65 +40.74, 40.00, 54.82, 45.18, 9.65 +40.74, 40.00, 54.82, 45.18, 9.64 +40.74, 40.00, 54.82, 45.18, 9.64 +40.74, 40.00, 54.82, 45.18, 9.63 +40.74, 40.00, 54.81, 45.19, 9.63 +40.74, 40.00, 54.81, 45.19, 9.62 +40.74, 40.00, 54.81, 45.19, 9.61 +40.74, 40.00, 54.80, 45.20, 9.61 +40.74, 40.00, 54.80, 45.20, 9.60 +40.74, 40.00, 54.80, 45.20, 9.60 +40.74, 40.00, 54.80, 45.20, 9.59 +40.74, 40.00, 54.79, 45.21, 9.59 +40.74, 40.00, 54.79, 45.21, 9.58 +40.74, 40.00, 54.79, 45.21, 9.58 +40.74, 40.00, 54.79, 45.21, 9.57 +40.74, 40.00, 54.78, 45.22, 9.56 +40.74, 40.00, 54.78, 45.22, 9.56 +40.74, 40.00, 54.78, 45.22, 9.55 +40.74, 40.00, 54.77, 45.23, 9.55 +40.74, 40.00, 54.77, 45.23, 9.54 +40.74, 40.00, 54.77, 45.23, 9.54 +40.74, 40.00, 54.77, 45.23, 9.53 +40.74, 40.00, 54.76, 45.24, 9.53 +40.74, 40.00, 54.76, 45.24, 9.52 +40.74, 40.00, 54.76, 45.24, 9.52 +40.87, 40.00, 49.71, 50.29, -0.58 +40.87, 40.00, 54.65, 45.35, 9.30 +40.87, 40.00, 54.65, 45.35, 9.30 +40.87, 40.00, 54.65, 45.35, 9.29 +40.87, 40.00, 54.64, 45.36, 9.28 +40.87, 40.00, 54.64, 45.36, 9.28 +40.94, 40.00, 52.11, 47.89, 4.23 +40.87, 40.00, 57.10, 42.90, 14.21 +40.94, 40.00, 52.11, 47.89, 4.21 +40.94, 40.00, 54.58, 45.42, 9.15 +40.94, 40.00, 54.57, 45.43, 9.14 +40.94, 40.00, 54.57, 45.43, 9.14 +40.94, 40.00, 54.57, 45.43, 9.13 +40.94, 40.00, 54.56, 45.44, 9.12 +40.94, 40.00, 54.56, 45.44, 9.12 +40.94, 40.00, 54.55, 45.45, 9.11 +40.94, 40.00, 54.55, 45.45, 9.10 +40.94, 40.00, 54.55, 45.45, 9.10 +41.00, 40.00, 52.02, 47.98, 4.05 +41.00, 40.00, 54.49, 45.51, 8.98 +41.00, 40.00, 54.49, 45.51, 8.97 +41.00, 40.00, 54.48, 45.52, 8.97 +41.00, 40.00, 54.48, 45.52, 8.96 +41.13, 40.00, 49.43, 50.57, -1.13 +41.13, 40.00, 54.37, 45.63, 8.74 +41.13, 40.00, 54.37, 45.63, 8.74 +41.13, 40.00, 54.36, 45.64, 8.73 +41.13, 40.00, 54.36, 45.64, 8.72 +41.13, 40.00, 54.36, 45.64, 8.71 +41.13, 40.00, 54.35, 45.65, 8.70 +41.13, 40.00, 54.35, 45.65, 8.69 +41.13, 40.00, 54.34, 45.66, 8.68 +41.13, 40.00, 54.34, 45.66, 8.68 +41.13, 40.00, 54.33, 45.67, 8.67 +41.13, 40.00, 54.33, 45.67, 8.66 +41.13, 40.00, 54.33, 45.67, 8.65 +41.13, 40.00, 54.32, 45.68, 8.64 +41.13, 40.00, 54.32, 45.68, 8.63 +41.13, 40.00, 54.31, 45.69, 8.63 +41.13, 40.00, 54.31, 45.69, 8.62 +41.13, 40.00, 54.30, 45.70, 8.61 +41.13, 40.00, 54.30, 45.70, 8.60 +41.00, 40.00, 59.34, 40.66, 18.68 +41.13, 40.00, 49.35, 50.65, -1.30 +41.00, 40.00, 59.33, 40.67, 18.66 +41.00, 40.00, 54.38, 45.62, 8.77 +41.00, 40.00, 54.38, 45.62, 8.76 +41.00, 40.00, 54.38, 45.62, 8.75 +40.94, 40.00, 56.89, 43.11, 13.79 +40.94, 40.00, 54.42, 45.58, 8.84 +40.94, 40.00, 54.41, 45.59, 8.83 +40.94, 40.00, 54.41, 45.59, 8.82 +40.94, 40.00, 54.41, 45.59, 8.82 +40.94, 40.00, 54.40, 45.60, 8.81 +40.94, 40.00, 54.40, 45.60, 8.80 +40.87, 40.00, 56.92, 43.08, 13.84 +40.87, 40.00, 54.44, 45.56, 8.89 +40.87, 40.00, 54.44, 45.56, 8.88 +40.87, 40.00, 54.44, 45.56, 8.87 +40.87, 40.00, 54.43, 45.57, 8.87 +40.87, 40.00, 54.43, 45.57, 8.86 +40.87, 40.00, 54.43, 45.57, 8.85 +40.74, 40.00, 59.47, 40.53, 18.93 +40.74, 40.00, 54.52, 45.48, 9.04 +40.74, 40.00, 54.52, 45.48, 9.04 +40.74, 40.00, 54.52, 45.48, 9.03 +40.67, 40.00, 57.03, 42.97, 14.07 +40.74, 40.00, 52.04, 47.96, 4.08 +40.67, 40.00, 57.03, 42.97, 14.06 +40.67, 40.00, 54.55, 45.45, 9.11 +40.67, 40.00, 54.55, 45.45, 9.10 +40.67, 40.00, 54.55, 45.45, 9.10 +40.67, 40.00, 54.55, 45.45, 9.09 +40.67, 40.00, 54.54, 45.46, 9.09 +40.67, 40.00, 54.54, 45.46, 9.08 +40.67, 40.00, 54.54, 45.46, 9.08 +40.67, 40.00, 54.54, 45.46, 9.07 +40.67, 40.00, 54.53, 45.47, 9.07 +40.67, 40.00, 54.53, 45.47, 9.06 +40.67, 40.00, 54.53, 45.47, 9.06 +40.61, 40.00, 57.05, 42.95, 14.10 +40.61, 40.00, 54.57, 45.43, 9.15 +40.61, 40.00, 54.57, 45.43, 9.14 +40.61, 40.00, 54.57, 45.43, 9.14 +40.61, 40.00, 54.57, 45.43, 9.13 +40.61, 40.00, 54.56, 45.44, 9.13 +40.61, 40.00, 54.56, 45.44, 9.13 +40.61, 40.00, 54.56, 45.44, 9.12 +40.67, 40.00, 52.04, 47.96, 4.07 +40.67, 40.00, 54.51, 45.49, 9.01 +40.67, 40.00, 54.50, 45.50, 9.01 +40.67, 40.00, 54.50, 45.50, 9.00 +40.67, 40.00, 54.50, 45.50, 9.00 +40.67, 40.00, 54.50, 45.50, 8.99 +40.67, 40.00, 54.49, 45.51, 8.99 +40.67, 40.00, 54.49, 45.51, 8.98 +40.74, 40.00, 51.97, 48.03, 3.93 +40.74, 40.00, 54.44, 45.56, 8.87 +40.74, 40.00, 54.43, 45.57, 8.87 +40.74, 40.00, 54.43, 45.57, 8.86 +40.74, 40.00, 54.43, 45.57, 8.86 +40.74, 40.00, 54.42, 45.58, 8.85 +40.74, 40.00, 54.42, 45.58, 8.84 +40.87, 40.00, 49.38, 50.62, -1.25 +40.87, 40.00, 54.32, 45.68, 8.63 +40.87, 40.00, 54.31, 45.69, 8.63 +40.87, 40.00, 54.31, 45.69, 8.62 +40.94, 40.00, 51.79, 48.21, 3.57 +40.94, 40.00, 54.25, 45.75, 8.51 +40.94, 40.00, 54.25, 45.75, 8.50 +40.94, 40.00, 54.25, 45.75, 8.49 +40.94, 40.00, 54.24, 45.76, 8.49 +40.94, 40.00, 54.24, 45.76, 8.48 +40.94, 40.00, 54.24, 45.76, 8.47 +40.94, 40.00, 54.23, 45.77, 8.47 +40.94, 40.00, 54.23, 45.77, 8.46 +40.94, 40.00, 54.23, 45.77, 8.45 +40.94, 40.00, 54.22, 45.78, 8.44 +40.94, 40.00, 54.22, 45.78, 8.44 +40.94, 40.00, 54.22, 45.78, 8.43 +40.94, 40.00, 54.21, 45.79, 8.42 +40.94, 40.00, 54.21, 45.79, 8.42 +40.94, 40.00, 54.20, 45.80, 8.41 +40.94, 40.00, 54.20, 45.80, 8.40 +40.94, 40.00, 54.20, 45.80, 8.40 +40.94, 40.00, 54.19, 45.81, 8.39 +40.94, 40.00, 54.19, 45.81, 8.38 +40.94, 40.00, 54.19, 45.81, 8.37 +40.94, 40.00, 54.18, 45.82, 8.37 +40.94, 40.00, 54.18, 45.82, 8.36 +40.94, 40.00, 54.18, 45.82, 8.35 +40.94, 40.00, 54.17, 45.83, 8.35 +40.94, 40.00, 54.17, 45.83, 8.34 +40.94, 40.00, 54.17, 45.83, 8.33 +40.94, 40.00, 54.16, 45.84, 8.33 +40.94, 40.00, 54.16, 45.84, 8.32 +40.94, 40.00, 54.16, 45.84, 8.31 +40.94, 40.00, 54.15, 45.85, 8.30 +40.94, 40.00, 54.15, 45.85, 8.30 +40.94, 40.00, 54.14, 45.86, 8.29 +40.87, 40.00, 56.66, 43.34, 13.33 +40.87, 40.00, 54.19, 45.81, 8.38 +40.87, 40.00, 54.18, 45.82, 8.37 +40.87, 40.00, 54.18, 45.82, 8.36 +40.87, 40.00, 54.18, 45.82, 8.36 +40.87, 40.00, 54.17, 45.83, 8.35 +40.74, 40.00, 59.21, 40.79, 18.43 +40.74, 40.00, 54.27, 45.73, 8.54 +40.74, 40.00, 54.27, 45.73, 8.53 +40.74, 40.00, 54.26, 45.74, 8.53 +40.74, 40.00, 54.26, 45.74, 8.52 +40.74, 40.00, 54.26, 45.74, 8.51 +40.74, 40.00, 54.25, 45.75, 8.51 +40.74, 40.00, 54.25, 45.75, 8.50 +40.74, 40.00, 54.25, 45.75, 8.50 +40.74, 40.00, 54.25, 45.75, 8.49 +40.74, 40.00, 54.24, 45.76, 8.49 +40.74, 40.00, 54.24, 45.76, 8.48 +40.74, 40.00, 54.24, 45.76, 8.48 +40.74, 40.00, 54.24, 45.76, 8.47 +40.74, 40.00, 54.23, 45.77, 8.46 +40.74, 40.00, 54.23, 45.77, 8.46 +40.74, 40.00, 54.23, 45.77, 8.45 +40.74, 40.00, 54.22, 45.78, 8.45 +40.74, 40.00, 54.22, 45.78, 8.44 +40.74, 40.00, 54.22, 45.78, 8.44 +40.74, 40.00, 54.22, 45.78, 8.43 +40.74, 40.00, 54.21, 45.79, 8.43 +40.74, 40.00, 54.21, 45.79, 8.42 +40.74, 40.00, 54.21, 45.79, 8.41 +40.74, 40.00, 54.20, 45.80, 8.41 +40.74, 40.00, 54.20, 45.80, 8.40 +40.74, 40.00, 54.20, 45.80, 8.40 +40.74, 40.00, 54.20, 45.80, 8.39 +40.74, 40.00, 54.19, 45.81, 8.39 +40.87, 40.00, 49.15, 50.85, -1.70 +40.87, 40.00, 54.09, 45.91, 8.18 +40.87, 40.00, 54.08, 45.92, 8.17 +40.87, 40.00, 54.08, 45.92, 8.16 +40.87, 40.00, 54.08, 45.92, 8.16 +40.94, 40.00, 51.55, 48.45, 3.11 +40.94, 40.00, 54.02, 45.98, 8.04 +40.94, 40.00, 54.02, 45.98, 8.04 +40.94, 40.00, 54.01, 45.99, 8.03 +40.94, 40.00, 54.01, 45.99, 8.02 +40.94, 40.00, 54.01, 45.99, 8.02 +40.94, 40.00, 54.00, 46.00, 8.01 +40.94, 40.00, 54.00, 46.00, 8.00 +40.94, 40.00, 54.00, 46.00, 7.99 +40.94, 40.00, 53.99, 46.01, 7.99 +40.94, 40.00, 53.99, 46.01, 7.98 +40.87, 40.00, 56.51, 43.49, 13.02 +40.94, 40.00, 51.51, 48.49, 3.02 +40.94, 40.00, 53.98, 46.02, 7.96 +40.94, 40.00, 53.98, 46.02, 7.95 +40.94, 40.00, 53.97, 46.03, 7.95 +40.94, 40.00, 53.97, 46.03, 7.94 +40.94, 40.00, 53.97, 46.03, 7.93 +40.94, 40.00, 53.96, 46.04, 7.93 +40.94, 40.00, 53.96, 46.04, 7.92 +40.94, 40.00, 53.96, 46.04, 7.91 +40.94, 40.00, 53.95, 46.05, 7.90 +41.00, 40.00, 51.43, 48.57, 2.85 +40.94, 40.00, 56.42, 43.58, 12.83 +40.94, 40.00, 53.94, 46.06, 7.88 +41.00, 40.00, 51.42, 48.58, 2.83 +41.00, 40.00, 53.88, 46.12, 7.77 +41.00, 40.00, 53.88, 46.12, 7.76 +41.00, 40.00, 53.88, 46.12, 7.75 +41.00, 40.00, 53.87, 46.13, 7.75 +41.00, 40.00, 53.87, 46.13, 7.74 +41.00, 40.00, 53.87, 46.13, 7.73 +41.00, 40.00, 53.86, 46.14, 7.72 +41.00, 40.00, 53.86, 46.14, 7.72 +41.00, 40.00, 53.85, 46.15, 7.71 +41.00, 40.00, 53.85, 46.15, 7.70 +41.00, 40.00, 53.85, 46.15, 7.69 +41.00, 40.00, 53.84, 46.16, 7.69 +41.00, 40.00, 53.84, 46.16, 7.68 +41.00, 40.00, 53.84, 46.16, 7.67 +41.00, 40.00, 53.83, 46.17, 7.66 +41.00, 40.00, 53.83, 46.17, 7.66 +41.00, 40.00, 53.82, 46.18, 7.65 +41.00, 40.00, 53.82, 46.18, 7.64 +41.00, 40.00, 53.82, 46.18, 7.63 +40.94, 40.00, 56.33, 43.67, 12.67 +41.00, 40.00, 51.34, 48.66, 2.68 +41.00, 40.00, 53.81, 46.19, 7.61 +41.00, 40.00, 53.80, 46.20, 7.60 +40.94, 40.00, 56.32, 43.68, 12.64 +40.94, 40.00, 53.84, 46.16, 7.69 +40.94, 40.00, 53.84, 46.16, 7.68 +40.94, 40.00, 53.84, 46.16, 7.67 +40.94, 40.00, 53.83, 46.17, 7.67 +40.94, 40.00, 53.83, 46.17, 7.66 +40.94, 40.00, 53.83, 46.17, 7.65 +40.94, 40.00, 53.82, 46.18, 7.65 +40.94, 40.00, 53.82, 46.18, 7.64 +40.94, 40.00, 53.82, 46.18, 7.63 +40.94, 40.00, 53.81, 46.19, 7.63 +40.94, 40.00, 53.81, 46.19, 7.62 +40.94, 40.00, 53.81, 46.19, 7.61 +40.94, 40.00, 53.80, 46.20, 7.60 +40.94, 40.00, 53.80, 46.20, 7.60 +40.94, 40.00, 53.80, 46.20, 7.59 +40.87, 40.00, 56.31, 43.69, 12.63 +40.94, 40.00, 51.32, 48.68, 2.63 +40.87, 40.00, 56.31, 43.69, 12.61 +40.87, 40.00, 53.83, 46.17, 7.66 +40.87, 40.00, 53.83, 46.17, 7.66 +40.87, 40.00, 53.82, 46.18, 7.65 +40.87, 40.00, 53.82, 46.18, 7.64 +40.87, 40.00, 53.82, 46.18, 7.64 +40.87, 40.00, 53.82, 46.18, 7.63 +40.87, 40.00, 53.81, 46.19, 7.62 +40.87, 40.00, 53.81, 46.19, 7.62 +40.87, 40.00, 53.81, 46.19, 7.61 +40.87, 40.00, 53.80, 46.20, 7.60 +40.87, 40.00, 53.80, 46.20, 7.60 +40.87, 40.00, 53.80, 46.20, 7.59 +40.87, 40.00, 53.79, 46.21, 7.58 +40.74, 40.00, 58.83, 41.17, 17.66 +40.74, 40.00, 53.89, 46.11, 7.77 +40.74, 40.00, 53.88, 46.12, 7.77 +40.74, 40.00, 53.88, 46.12, 7.76 +40.74, 40.00, 53.88, 46.12, 7.75 +40.74, 40.00, 53.87, 46.13, 7.75 +40.74, 40.00, 53.87, 46.13, 7.74 +40.74, 40.00, 53.87, 46.13, 7.74 +40.67, 40.00, 56.39, 43.61, 12.78 +40.67, 40.00, 53.91, 46.09, 7.83 +40.67, 40.00, 53.91, 46.09, 7.82 +40.67, 40.00, 53.91, 46.09, 7.82 +40.67, 40.00, 53.91, 46.09, 7.81 +40.67, 40.00, 53.90, 46.10, 7.81 +40.67, 40.00, 53.90, 46.10, 7.80 +40.67, 40.00, 53.90, 46.10, 7.80 +40.67, 40.00, 53.90, 46.10, 7.79 +40.67, 40.00, 53.89, 46.11, 7.79 +40.67, 40.00, 53.89, 46.11, 7.78 +40.67, 40.00, 53.89, 46.11, 7.78 +40.67, 40.00, 53.89, 46.11, 7.77 +40.67, 40.00, 53.88, 46.12, 7.77 +40.67, 40.00, 53.88, 46.12, 7.76 +40.67, 40.00, 53.88, 46.12, 7.76 +40.67, 40.00, 53.88, 46.12, 7.75 +40.67, 40.00, 53.87, 46.13, 7.75 +40.67, 40.00, 53.87, 46.13, 7.74 +40.67, 40.00, 53.87, 46.13, 7.74 +40.67, 40.00, 53.87, 46.13, 7.73 +40.61, 40.00, 56.38, 43.62, 12.77 +40.61, 40.00, 53.91, 46.09, 7.82 +40.61, 40.00, 53.91, 46.09, 7.82 +40.61, 40.00, 53.91, 46.09, 7.81 +40.61, 40.00, 53.90, 46.10, 7.81 +40.61, 40.00, 53.90, 46.10, 7.80 +40.61, 40.00, 53.90, 46.10, 7.80 +40.61, 40.00, 53.90, 46.10, 7.79 +40.61, 40.00, 53.89, 46.11, 7.79 +40.61, 40.00, 53.89, 46.11, 7.78 +40.67, 40.00, 51.37, 48.63, 2.74 +40.67, 40.00, 53.84, 46.16, 7.68 +40.67, 40.00, 53.84, 46.16, 7.67 +40.67, 40.00, 53.83, 46.17, 7.67 +40.67, 40.00, 53.83, 46.17, 7.66 +40.67, 40.00, 53.83, 46.17, 7.66 +40.67, 40.00, 53.83, 46.17, 7.65 +40.67, 40.00, 53.82, 46.18, 7.65 +40.61, 40.00, 56.34, 43.66, 12.68 +40.61, 40.00, 53.87, 46.13, 7.74 +40.61, 40.00, 53.87, 46.13, 7.73 +40.61, 40.00, 53.86, 46.14, 7.73 +40.61, 40.00, 53.86, 46.14, 7.72 +40.61, 40.00, 53.86, 46.14, 7.72 +40.61, 40.00, 53.86, 46.14, 7.71 +40.61, 40.00, 53.85, 46.15, 7.71 +40.61, 40.00, 53.85, 46.15, 7.70 +40.61, 40.00, 53.85, 46.15, 7.70 +40.67, 40.00, 51.33, 48.67, 2.65 +40.67, 40.00, 53.80, 46.20, 7.59 +40.67, 40.00, 53.79, 46.21, 7.59 +40.67, 40.00, 53.79, 46.21, 7.58 +40.61, 40.00, 56.31, 43.69, 12.62 +40.61, 40.00, 53.83, 46.17, 7.67 +40.67, 40.00, 51.31, 48.69, 2.62 +40.61, 40.00, 56.30, 43.70, 12.60 +40.61, 40.00, 53.83, 46.17, 7.66 +40.61, 40.00, 53.83, 46.17, 7.65 +40.61, 40.00, 53.82, 46.18, 7.65 +40.61, 40.00, 53.82, 46.18, 7.64 +40.61, 40.00, 53.82, 46.18, 7.64 +40.61, 40.00, 53.82, 46.18, 7.63 +40.61, 40.00, 53.81, 46.19, 7.63 +40.61, 40.00, 53.81, 46.19, 7.62 +40.61, 40.00, 53.81, 46.19, 7.62 +40.61, 40.00, 53.81, 46.19, 7.61 +40.67, 40.00, 51.28, 48.72, 2.57 +40.67, 40.00, 53.75, 46.25, 7.51 +40.67, 40.00, 53.75, 46.25, 7.50 +40.67, 40.00, 53.75, 46.25, 7.50 +40.67, 40.00, 53.75, 46.25, 7.49 +40.67, 40.00, 53.74, 46.26, 7.49 +40.67, 40.00, 53.74, 46.26, 7.48 +40.67, 40.00, 53.74, 46.26, 7.48 +40.67, 40.00, 53.74, 46.26, 7.47 +40.67, 40.00, 53.73, 46.27, 7.47 +40.67, 40.00, 53.73, 46.27, 7.46 +40.67, 40.00, 53.73, 46.27, 7.46 +40.67, 40.00, 53.73, 46.27, 7.45 +40.67, 40.00, 53.72, 46.28, 7.45 +40.67, 40.00, 53.72, 46.28, 7.44 +40.67, 40.00, 53.72, 46.28, 7.44 +40.67, 40.00, 53.72, 46.28, 7.43 +40.67, 40.00, 53.71, 46.29, 7.43 +40.67, 40.00, 53.71, 46.29, 7.42 +40.67, 40.00, 53.71, 46.29, 7.42 +40.67, 40.00, 53.71, 46.29, 7.41 +40.67, 40.00, 53.70, 46.30, 7.41 +40.67, 40.00, 53.70, 46.30, 7.40 +40.67, 40.00, 53.70, 46.30, 7.40 +40.67, 40.00, 53.70, 46.30, 7.39 +40.67, 40.00, 53.69, 46.31, 7.39 +40.67, 40.00, 53.69, 46.31, 7.38 +40.67, 40.00, 53.69, 46.31, 7.38 +40.67, 40.00, 53.69, 46.31, 7.37 +40.67, 40.00, 53.68, 46.32, 7.37 +40.67, 40.00, 53.68, 46.32, 7.36 +40.67, 40.00, 53.68, 46.32, 7.35 +40.67, 40.00, 53.67, 46.33, 7.35 +40.67, 40.00, 53.67, 46.33, 7.34 +40.67, 40.00, 53.67, 46.33, 7.34 +40.67, 40.00, 53.67, 46.33, 7.33 +40.67, 40.00, 53.66, 46.34, 7.33 +40.67, 40.00, 53.66, 46.34, 7.32 +40.67, 40.00, 53.66, 46.34, 7.32 +40.67, 40.00, 53.66, 46.34, 7.31 +40.67, 40.00, 53.65, 46.35, 7.31 +40.67, 40.00, 53.65, 46.35, 7.30 +40.67, 40.00, 53.65, 46.35, 7.30 +40.67, 40.00, 53.65, 46.35, 7.29 +40.61, 40.00, 56.17, 43.83, 12.33 +40.61, 40.00, 53.69, 46.31, 7.38 +40.61, 40.00, 53.69, 46.31, 7.38 +40.61, 40.00, 53.69, 46.31, 7.38 +40.61, 40.00, 53.69, 46.31, 7.37 +40.61, 40.00, 53.68, 46.32, 7.37 +40.61, 40.00, 53.68, 46.32, 7.36 +40.61, 40.00, 53.68, 46.32, 7.36 +40.61, 40.00, 53.68, 46.32, 7.35 +40.61, 40.00, 53.67, 46.33, 7.35 +40.47, 40.00, 58.71, 41.29, 17.43 +40.47, 40.00, 53.77, 46.23, 7.54 +40.47, 40.00, 53.77, 46.23, 7.54 +40.47, 40.00, 53.77, 46.23, 7.53 +40.47, 40.00, 53.76, 46.24, 7.53 +40.47, 40.00, 53.76, 46.24, 7.52 +40.47, 40.00, 53.76, 46.24, 7.52 +40.61, 40.00, 48.72, 51.28, -2.57 +40.47, 40.00, 58.70, 41.30, 17.40 +40.61, 40.00, 48.71, 51.29, -2.58 +40.61, 40.00, 53.65, 46.35, 7.31 +40.47, 40.00, 58.69, 41.31, 17.39 +40.61, 40.00, 48.71, 51.29, -2.59 +40.61, 40.00, 53.65, 46.35, 7.29 +40.61, 40.00, 53.64, 46.36, 7.29 +40.61, 40.00, 53.64, 46.36, 7.28 +40.47, 40.00, 58.68, 41.32, 17.37 +40.61, 40.00, 48.69, 51.31, -2.61 +40.47, 40.00, 58.68, 41.32, 17.36 +40.47, 40.00, 53.73, 46.27, 7.47 +40.47, 40.00, 53.73, 46.27, 7.46 +40.47, 40.00, 53.73, 46.27, 7.46 +40.47, 40.00, 53.73, 46.27, 7.46 +40.47, 40.00, 53.73, 46.27, 7.45 +40.47, 40.00, 53.72, 46.28, 7.45 +40.47, 40.00, 53.72, 46.28, 7.45 +40.47, 40.00, 53.72, 46.28, 7.44 +40.47, 40.00, 53.72, 46.28, 7.44 +40.47, 40.00, 53.72, 46.28, 7.43 +40.47, 40.00, 53.72, 46.28, 7.43 +40.47, 40.00, 53.71, 46.29, 7.43 +40.61, 40.00, 48.67, 51.33, -2.66 +40.61, 40.00, 53.61, 46.39, 7.22 +40.61, 40.00, 53.61, 46.39, 7.22 +40.61, 40.00, 53.61, 46.39, 7.21 +40.61, 40.00, 53.60, 46.40, 7.21 +40.67, 40.00, 51.08, 48.92, 2.16 +40.67, 40.00, 53.55, 46.45, 7.10 +40.61, 40.00, 56.07, 43.93, 12.14 +40.61, 40.00, 53.59, 46.41, 7.19 +40.67, 40.00, 51.07, 48.93, 2.14 +40.61, 40.00, 56.06, 43.94, 12.12 +40.61, 40.00, 53.59, 46.41, 7.17 +40.67, 40.00, 51.06, 48.94, 2.13 +40.67, 40.00, 53.53, 46.47, 7.07 +40.67, 40.00, 53.53, 46.47, 7.06 +40.67, 40.00, 53.53, 46.47, 7.05 +40.67, 40.00, 53.52, 46.48, 7.05 +40.67, 40.00, 53.52, 46.48, 7.04 +40.67, 40.00, 53.52, 46.48, 7.04 +40.67, 40.00, 53.52, 46.48, 7.03 +40.67, 40.00, 53.51, 46.49, 7.03 +40.74, 40.00, 50.99, 49.01, 1.98 +40.74, 40.00, 53.46, 46.54, 6.92 +40.74, 40.00, 53.46, 46.54, 6.91 +40.74, 40.00, 53.45, 46.55, 6.91 +40.74, 40.00, 53.45, 46.55, 6.90 +40.74, 40.00, 53.45, 46.55, 6.90 +40.74, 40.00, 53.45, 46.55, 6.89 +40.74, 40.00, 53.44, 46.56, 6.89 +40.87, 40.00, 48.40, 51.60, -3.21 +40.87, 40.00, 53.34, 46.66, 6.68 +40.87, 40.00, 53.33, 46.67, 6.67 +40.87, 40.00, 53.33, 46.67, 6.66 +40.87, 40.00, 53.33, 46.67, 6.66 +40.87, 40.00, 53.32, 46.68, 6.65 +40.87, 40.00, 53.32, 46.68, 6.64 +40.87, 40.00, 53.32, 46.68, 6.64 +40.94, 40.00, 50.79, 49.21, 1.59 +40.94, 40.00, 53.26, 46.74, 6.52 +40.94, 40.00, 53.26, 46.74, 6.52 +40.94, 40.00, 53.25, 46.75, 6.51 +40.94, 40.00, 53.25, 46.75, 6.50 +40.94, 40.00, 53.25, 46.75, 6.50 +40.94, 40.00, 53.24, 46.76, 6.49 +40.94, 40.00, 53.24, 46.76, 6.48 +40.94, 40.00, 53.24, 46.76, 6.47 +40.94, 40.00, 53.23, 46.77, 6.47 +40.94, 40.00, 53.23, 46.77, 6.46 +40.94, 40.00, 53.23, 46.77, 6.45 +40.94, 40.00, 53.22, 46.78, 6.45 +40.94, 40.00, 53.22, 46.78, 6.44 +40.94, 40.00, 53.22, 46.78, 6.43 +40.94, 40.00, 53.21, 46.79, 6.43 +40.94, 40.00, 53.21, 46.79, 6.42 +40.94, 40.00, 53.21, 46.79, 6.41 +40.94, 40.00, 53.20, 46.80, 6.40 +40.94, 40.00, 53.20, 46.80, 6.40 +40.94, 40.00, 53.20, 46.80, 6.39 +40.87, 40.00, 55.71, 44.29, 11.43 +40.87, -10.00, 25.00, 75.00, -50.00 +40.87, -10.00, 25.00, 75.00, -50.00 +40.74, -10.00, 25.00, 75.00, -50.00 +40.74, -10.00, 25.00, 75.00, -50.00 +40.74, -10.00, 25.00, 75.00, -50.00 +40.67, -10.00, 25.00, 75.00, -50.00 +40.67, -10.00, 25.00, 75.00, -50.00 +40.67, -10.00, 25.00, 75.00, -50.00 +40.67, -10.00, 25.00, 75.00, -50.00 +40.61, -10.00, 25.00, 75.00, -50.00 +40.61, -10.00, 25.00, 75.00, -50.00 +40.47, -10.00, 25.00, 75.00, -50.00 +40.41, -10.00, 25.00, 75.00, -50.00 +40.34, -10.00, 25.00, 75.00, -50.00 +40.14, -10.00, 25.00, 75.00, -50.00 +40.08, -10.00, 25.00, 75.00, -50.00 +39.88, -10.00, 25.00, 75.00, -50.00 +39.68, -10.00, 25.00, 75.00, -50.00 +39.55, -10.00, 25.00, 75.00, -50.00 +39.35, -10.00, 25.00, 75.00, -50.00 +39.09, -10.00, 25.00, 75.00, -50.00 +38.89, -10.00, 25.00, 75.00, -50.00 +38.63, -10.00, 25.00, 75.00, -50.00 +38.50, -10.00, 25.00, 75.00, -50.00 +38.10, -10.00, 27.96, 72.04, -44.08 +37.97, -10.00, 25.00, 75.00, -50.00 +37.57, -10.00, 28.00, 72.00, -44.01 +37.31, -10.00, 25.00, 75.00, -50.00 +36.98, -10.00, 25.62, 74.38, -48.77 +36.72, -10.00, 25.00, 75.00, -50.00 +36.39, -10.00, 25.71, 74.29, -48.58 +35.99, -10.00, 28.31, 71.69, -43.39 +35.60, -10.00, 28.43, 71.57, -43.13 +35.20, -10.00, 28.56, 71.44, -42.88 +34.67, -10.00, 33.73, 66.27, -32.54 +34.28, -10.00, 28.92, 71.08, -42.16 +33.82, -10.00, 31.57, 68.43, -36.86 +33.29, -10.00, 34.28, 65.72, -31.45 +32.76, -10.00, 34.51, 65.49, -30.98 +32.23, -10.00, 34.75, 65.25, -30.50 +31.71, -10.00, 34.99, 65.01, -30.02 +31.18, -10.00, 35.23, 64.77, -29.54 +30.59, -10.00, 37.99, 62.01, -24.01 +30.06, -10.00, 35.77, 64.23, -28.46 +29.53, -10.00, 36.01, 63.99, -27.97 +28.87, -10.00, 41.31, 58.69, -17.39 +28.28, -10.00, 39.14, 60.86, -21.73 +27.75, -10.00, 36.92, 63.08, -26.16 +27.16, -10.00, 39.70, 60.30, -20.61 +26.43, -10.00, 45.05, 54.95, -9.91 +25.84, -10.00, 40.41, 59.59, -19.17 +25.11, -10.00, 45.77, 54.23, -8.46 +24.39, -10.00, 46.18, 53.82, -7.63 +23.73, -10.00, 44.08, 55.92, -11.84 +22.94, -10.00, 49.49, 50.51, -1.01 +22.15, -10.00, 49.97, 50.03, -0.07 +21.42, -10.00, 47.92, 52.08, -4.16 +20.57, -10.00, 53.39, 46.61, 6.79 +19.78, -10.00, 51.40, 48.60, 2.81 +19.05, -10.00, 49.37, 50.63, -1.27 +18.26, -10.00, 52.33, 47.67, 4.65 +17.47, -10.00, 52.82, 47.18, 5.63 +16.68, -10.00, 53.31, 46.69, 6.62 +15.95, -10.00, 51.28, 48.72, 2.57 +15.29, -10.00, 49.21, 50.79, -1.58 +14.50, -10.00, 54.66, 45.34, 9.31 +13.71, -10.00, 55.16, 44.84, 10.32 +12.99, -10.00, 53.15, 46.85, 6.29 +12.13, -10.00, 58.65, 41.35, 17.30 +11.34, -10.00, 56.69, 43.31, 13.38 +10.55, -10.00, 57.21, 42.79, 14.41 +9.62, -10.00, 62.77, 37.23, 25.54 +8.83, -10.00, 58.35, 41.65, 16.70 +7.98, -10.00, 61.40, 38.60, 22.79 +7.12, -10.00, 61.97, 38.03, 23.95 +6.33, -10.00, 60.03, 39.97, 20.07 +5.41, -10.00, 65.61, 34.39, 31.22 +4.61, -10.00, 61.21, 38.79, 22.41 +3.76, -10.00, 64.27, 35.73, 28.54 +2.97, -10.00, 62.34, 37.66, 24.69 +2.11, -10.00, 65.41, 34.59, 30.82 +1.32, -10.00, 63.49, 36.51, 26.98 +0.53, -10.00, 64.04, 35.96, 28.09 +-0.20, -10.00, 62.08, 37.92, 24.16 +-0.99, -10.00, 65.11, 34.89, 30.22 +-1.78, -10.00, 65.67, 34.33, 31.35 +-2.50, -10.00, 63.72, 36.28, 27.43 +-3.30, -10.00, 66.76, 33.24, 33.51 +-3.96, -10.00, 62.29, 37.71, 24.57 +-4.68, -10.00, 65.28, 34.72, 30.56 +-5.47, -10.00, 68.33, 31.67, 36.66 +-6.20, -10.00, 66.39, 33.61, 32.77 +-6.99, -10.00, 69.44, 30.56, 38.88 +-7.65, -10.00, 64.98, 35.02, 29.96 +-8.37, -10.00, 67.99, 32.01, 35.98 +-9.10, -10.00, 68.53, 31.47, 37.07 +-9.76, -10.00, 66.55, 33.45, 33.11 +-10.48, -10.00, 69.57, 30.43, 39.14 +-11.21, -10.00, 70.12, 29.88, 40.24 +-11.87, -10.00, 68.15, 31.85, 36.30 +-12.59, -10.00, 71.17, 28.83, 42.35 +-13.18, -10.00, 66.69, 33.31, 33.38 +-13.84, -10.00, 69.67, 30.33, 39.34 +-14.44, -10.00, 67.66, 32.34, 35.32 +-15.03, -10.00, 68.12, 31.88, 36.24 +-15.56, -10.00, 66.07, 33.93, 32.13 +-16.22, -10.00, 71.53, 28.47, 43.06 +-16.81, -10.00, 69.53, 30.47, 39.05 +-17.40, -10.00, 70.00, 30.00, 40.00 +-17.93, -10.00, 67.95, 32.05, 35.91 +-18.46, -10.00, 68.38, 31.62, 36.76 +-18.98, -10.00, 68.81, 31.19, 37.62 +-19.51, -10.00, 69.24, 30.76, 38.48 +-19.97, -10.00, 67.15, 32.85, 34.30 +-20.50, -10.00, 70.06, 29.94, 40.12 +-20.96, -10.00, 67.97, 32.03, 35.95 +-21.36, -10.00, 65.84, 34.16, 31.68 +-21.82, -10.00, 68.70, 31.30, 37.41 +-22.28, -10.00, 69.10, 30.90, 38.19 +-22.68, -10.00, 66.97, 33.03, 33.94 +-22.94, -10.00, 62.27, 37.73, 24.54 +-23.40, -10.00, 70.08, 29.92, 40.16 +-23.73, -10.00, 65.44, 34.56, 30.87 +-23.99, -10.00, 63.22, 36.78, 26.43 +-24.39, -10.00, 68.51, 31.49, 37.02 +-24.72, -10.00, 66.34, 33.66, 32.68 +-24.98, -10.00, 64.12, 35.88, 28.24 +-25.31, -10.00, 66.90, 33.10, 33.80 +-25.58, -10.00, 64.68, 35.32, 29.37 +-25.84, -10.00, 64.94, 35.06, 29.88 +-26.10, -10.00, 65.20, 34.80, 30.40 +-26.37, -10.00, 65.46, 34.54, 30.92 +-26.56, -10.00, 63.20, 36.80, 26.39 +-26.83, -10.00, 65.93, 34.07, 31.86 +-27.03, -10.00, 63.67, 36.33, 27.34 +-27.16, -10.00, 61.36, 38.64, 22.72 +-27.36, -10.00, 64.05, 35.95, 28.09 +-27.55, -10.00, 64.26, 35.74, 28.52 +-27.69, -10.00, 61.95, 38.05, 23.91 +-27.82, -10.00, 62.12, 37.88, 24.24 +-27.88, -10.00, 59.76, 40.24, 19.53 +-27.95, -10.00, 59.88, 40.12, 19.76 +-28.15, -10.00, 65.04, 34.96, 30.08 +-28.21, -10.00, 60.21, 39.79, 20.43 +-28.34, -10.00, 62.85, 37.15, 25.71 +-28.41, -10.00, 60.50, 39.50, 21.00 +-28.41, -10.00, 58.10, 41.90, 16.20 +-28.48, -10.00, 60.69, 39.31, 21.38 +-28.48, -10.00, 58.29, 41.71, 16.57 +-28.48, -10.00, 58.35, 41.65, 16.71 +-28.61, -10.00, 63.47, 36.53, 26.93 +-28.61, -10.00, 58.59, 41.41, 17.19 +-28.48, -10.00, 53.62, 46.38, 7.24 +-28.61, -10.00, 63.68, 36.32, 27.35 +-28.48, -10.00, 53.76, 46.24, 7.52 +-28.48, -10.00, 58.77, 41.23, 17.54 +-28.41, -10.00, 56.32, 43.68, 12.64 +-28.41, -10.00, 58.86, 41.14, 17.72 +-28.34, -10.00, 56.41, 43.59, 12.82 +-28.21, -10.00, 53.91, 46.09, 7.81 +-28.15, -10.00, 56.40, 43.60, 12.79 +-28.08, -10.00, 56.41, 43.59, 12.83 +-27.95, -10.00, 53.91, 46.09, 7.82 +-27.95, -10.00, 58.92, 41.08, 17.84 +-27.82, -10.00, 53.95, 46.05, 7.89 +-27.82, -10.00, 58.96, 41.04, 17.91 +-27.62, -10.00, 51.46, 48.54, 2.92 +-27.55, -10.00, 56.42, 43.58, 12.84 +-27.42, -10.00, 53.91, 46.09, 7.83 +-27.29, -10.00, 53.88, 46.12, 7.76 +-27.16, -10.00, 53.85, 46.15, 7.69 +-27.03, -10.00, 53.81, 46.19, 7.62 +-26.83, -10.00, 51.25, 48.75, 2.51 +-26.76, -10.00, 56.21, 43.79, 12.42 +-26.56, -10.00, 51.18, 48.82, 2.36 +-26.50, -10.00, 56.14, 43.86, 12.27 +-26.30, -10.00, 51.11, 48.89, 2.21 +-26.04, -10.00, 48.50, 51.50, -3.01 +-25.97, -10.00, 55.92, 44.08, 11.84 +-25.77, -10.00, 50.89, 49.11, 1.78 +-25.58, -10.00, 50.80, 49.20, 1.60 +-25.44, -10.00, 53.23, 46.77, 6.46 +-25.25, -10.00, 50.67, 49.33, 1.33 +-25.05, -10.00, 50.58, 49.42, 1.15 +-24.92, -10.00, 53.00, 47.00, 6.01 +-24.79, -10.00, 52.96, 47.04, 5.92 +-24.65, -10.00, 52.92, 47.08, 5.83 +-24.46, -10.00, 50.35, 49.65, 0.70 +-24.26, -10.00, 50.26, 49.74, 0.51 +-23.99, -10.00, 47.64, 52.36, -4.72 +-23.93, -10.00, 55.06, 44.94, 10.11 +-23.66, -10.00, 47.50, 52.50, -5.01 +-23.47, -10.00, 49.87, 50.13, -0.26 +-23.40, -10.00, 54.81, 45.19, 9.63 +-23.14, -10.00, 47.25, 52.75, -5.50 +-22.94, -10.00, 49.62, 50.38, -0.76 +-22.87, -10.00, 54.56, 45.44, 9.13 +-22.61, -10.00, 47.00, 53.00, -6.00 +-22.41, -10.00, 49.37, 50.63, -1.26 +-22.28, -10.00, 51.79, 48.21, 3.57 +-22.15, -10.00, 51.73, 48.27, 3.47 +-21.88, -10.00, 46.64, 53.36, -6.73 +-21.82, -10.00, 54.05, 45.95, 8.10 +-21.62, -10.00, 49.00, 51.00, -2.00 +-21.49, -10.00, 51.42, 48.58, 2.83 +-21.29, -10.00, 48.84, 51.16, -2.33 +-21.09, -10.00, 48.73, 51.27, -2.54 +-20.96, -10.00, 51.14, 48.86, 2.29 +-20.76, -10.00, 48.56, 51.44, -2.87 +-20.57, -10.00, 48.46, 51.54, -3.09 +-20.43, -10.00, 50.87, 49.13, 1.74 +-20.24, -10.00, 48.29, 51.71, -3.43 +-20.04, -10.00, 48.18, 51.82, -3.65 +-19.97, -10.00, 53.11, 46.89, 6.22 +-19.78, -10.00, 48.05, 51.95, -3.90 +-19.64, -10.00, 50.46, 49.54, 0.92 +-19.51, -10.00, 50.40, 49.60, 0.80 +-19.38, -10.00, 50.33, 49.67, 0.67 +-19.25, -10.00, 50.27, 49.73, 0.54 +-19.12, -10.00, 50.21, 49.79, 0.41 +-18.92, -10.00, 47.62, 52.38, -4.76 +-18.85, -10.00, 52.55, 47.45, 5.09 +-18.65, -10.00, 47.49, 52.51, -5.03 +-18.59, -10.00, 52.41, 47.59, 4.83 +-18.39, -10.00, 47.35, 52.65, -5.29 +-18.33, -10.00, 52.28, 47.72, 4.56 +-18.13, -10.00, 47.22, 52.78, -5.57 +-18.06, -10.00, 52.14, 47.86, 4.28 +-17.86, -10.00, 47.08, 52.92, -5.84 +-17.80, -10.00, 52.00, 48.00, 4.00 +-17.67, -10.00, 49.46, 50.54, -1.08 +-17.53, -10.00, 49.39, 50.61, -1.22 +-17.40, -10.00, 49.32, 50.68, -1.36 +-17.34, -10.00, 51.77, 48.23, 3.54 +-17.27, -10.00, 51.75, 48.25, 3.49 +-17.07, -10.00, 46.68, 53.32, -6.64 +-17.01, -10.00, 51.60, 48.40, 3.20 +-16.87, -10.00, 49.06, 50.94, -1.89 +-16.81, -10.00, 51.50, 48.50, 3.01 +-16.61, -10.00, 46.44, 53.56, -7.13 +-16.61, -10.00, 53.88, 46.12, 7.75 +-16.48, -10.00, 48.86, 51.14, -2.28 +-16.48, -10.00, 53.83, 46.17, 7.65 +-16.28, -10.00, 46.29, 53.71, -7.43 +-16.28, -10.00, 53.73, 46.27, 7.45 +-16.08, -10.00, 46.18, 53.82, -7.63 +-16.08, -10.00, 53.62, 46.38, 7.25 +-16.02, -10.00, 51.12, 48.88, 2.25 +-15.95, -10.00, 51.10, 48.90, 2.19 +-15.82, -10.00, 48.55, 51.45, -2.90 +-15.75, -10.00, 50.99, 49.01, 1.98 +-15.75, -10.00, 53.49, 46.51, 6.97 +-15.69, -10.00, 50.99, 49.01, 1.97 +-15.56, -10.00, 48.44, 51.56, -3.13 +-15.56, -10.00, 53.40, 46.60, 6.80 +-15.49, -10.00, 50.90, 49.10, 1.80 +-15.42, -10.00, 50.87, 49.13, 1.74 +-15.42, -10.00, 53.36, 46.64, 6.73 +-15.29, -10.00, 48.34, 51.66, -3.32 +-15.29, -10.00, 53.30, 46.70, 6.61 +-15.23, -10.00, 50.80, 49.20, 1.60 +-15.16, -10.00, 50.77, 49.23, 1.54 +-15.16, -10.00, 53.26, 46.74, 6.53 +-15.03, -10.00, 48.24, 51.76, -3.52 +-15.03, -10.00, 53.20, 46.80, 6.40 +-15.03, -10.00, 53.22, 46.78, 6.44 +-14.96, -10.00, 50.72, 49.28, 1.44 +-14.90, -10.00, 50.69, 49.31, 1.37 +-14.90, -10.00, 53.18, 46.82, 6.35 +-14.90, -10.00, 53.20, 46.80, 6.39 +-14.77, -10.00, 48.17, 51.83, -3.66 +-14.77, -10.00, 53.13, 46.87, 6.27 +-14.70, -10.00, 50.63, 49.37, 1.26 +-14.70, -10.00, 53.12, 46.88, 6.24 +-14.70, -10.00, 53.14, 46.86, 6.27 +-14.63, -10.00, 50.63, 49.37, 1.26 +-14.63, -10.00, 53.12, 46.88, 6.24 +-14.63, -10.00, 53.14, 46.86, 6.28 +-14.50, -10.00, 48.11, 51.89, -3.77 +-14.50, -10.00, 53.07, 46.93, 6.15 +-14.44, -10.00, 50.57, 49.43, 1.14 +-14.44, -10.00, 53.06, 46.94, 6.12 +-14.44, -10.00, 53.07, 46.93, 6.15 +-14.37, -10.00, 50.57, 49.43, 1.14 +-14.37, -10.00, 53.06, 46.94, 6.12 +-14.37, -10.00, 53.07, 46.93, 6.15 +-14.37, -10.00, 53.09, 46.91, 6.18 +-14.24, -10.00, 48.06, 51.94, -3.87 +-14.24, -10.00, 53.02, 46.98, 6.05 +-14.24, -10.00, 53.04, 46.96, 6.08 +-14.24, -10.00, 53.06, 46.94, 6.11 +-14.17, -10.00, 50.55, 49.45, 1.10 +-14.17, -10.00, 53.04, 46.96, 6.07 +-14.17, -10.00, 53.05, 46.95, 6.11 +-14.11, -10.00, 50.55, 49.45, 1.09 +-14.11, -10.00, 53.03, 46.97, 6.07 +-14.11, -10.00, 53.05, 46.95, 6.10 +-13.97, -10.00, 48.02, 51.98, -3.96 +-13.97, -10.00, 52.98, 47.02, 5.96 +-13.97, -10.00, 53.00, 47.00, 5.99 +-13.97, -10.00, 53.01, 46.99, 6.02 +-13.97, -10.00, 53.02, 46.98, 6.05 +-13.91, -10.00, 50.52, 49.48, 1.04 +-13.91, -10.00, 53.00, 47.00, 6.01 +-13.91, -10.00, 53.02, 46.98, 6.04 +-13.91, -10.00, 53.03, 46.97, 6.07 +-13.91, -10.00, 53.05, 46.95, 6.10 +-13.84, -10.00, 50.54, 49.46, 1.08 +-13.84, -10.00, 53.03, 46.97, 6.06 +-13.84, -10.00, 53.04, 46.96, 6.09 +-13.84, -10.00, 53.06, 46.94, 6.11 +-13.84, -10.00, 53.07, 46.93, 6.14 +-13.84, -10.00, 53.09, 46.91, 6.17 +-13.71, -10.00, 48.06, 51.94, -3.89 +-13.71, -10.00, 53.01, 46.99, 6.03 +-13.71, -10.00, 53.03, 46.97, 6.06 +-13.71, -10.00, 53.04, 46.96, 6.09 +-13.71, -10.00, 53.06, 46.94, 6.11 +-13.71, -10.00, 53.07, 46.93, 6.14 +-13.71, -10.00, 53.08, 46.92, 6.17 +-13.65, -10.00, 50.58, 49.42, 1.15 +-13.65, -10.00, 53.06, 46.94, 6.12 +-13.65, -10.00, 53.08, 46.92, 6.15 +-13.65, -10.00, 53.09, 46.91, 6.18 +-13.65, -10.00, 53.10, 46.90, 6.21 +-13.58, -10.00, 50.60, 49.40, 1.19 +-13.58, -10.00, 53.08, 46.92, 6.16 +-13.58, -10.00, 53.09, 46.91, 6.19 +-13.58, -10.00, 53.11, 46.89, 6.21 +-13.58, -10.00, 53.12, 46.88, 6.24 +-13.58, -10.00, 53.13, 46.87, 6.27 +-13.45, -10.00, 48.10, 51.90, -3.79 +-13.45, -10.00, 53.06, 46.94, 6.12 +-13.45, -10.00, 53.07, 46.93, 6.15 +-13.45, -10.00, 53.09, 46.91, 6.17 +-13.45, -10.00, 53.10, 46.90, 6.20 +-13.38, -10.00, 50.59, 49.41, 1.18 +-13.38, -10.00, 53.08, 46.92, 6.15 +-13.38, -10.00, 53.09, 46.91, 6.18 +-13.32, -10.00, 50.58, 49.42, 1.16 +-13.32, -10.00, 53.06, 46.94, 6.13 +-13.32, -10.00, 53.08, 46.92, 6.15 +-13.32, -10.00, 53.09, 46.91, 6.18 +-13.18, -10.00, 48.06, 51.94, -3.88 +-13.18, -10.00, 53.01, 46.99, 6.03 +-13.18, -10.00, 53.03, 46.97, 6.05 +-13.12, -10.00, 50.52, 49.48, 1.03 +-13.12, -10.00, 53.00, 47.00, 6.00 +-13.12, -10.00, 53.01, 46.99, 6.02 +-13.05, -10.00, 50.50, 49.50, 1.00 +-13.05, -10.00, 52.98, 47.02, 5.97 +-13.05, -10.00, 53.00, 47.00, 5.99 +-13.05, -10.00, 53.01, 46.99, 6.02 +-13.05, -10.00, 53.02, 46.98, 6.04 +-12.92, -10.00, 47.99, 52.01, -4.02 +-12.92, -10.00, 52.94, 47.06, 5.88 +-12.85, -10.00, 50.43, 49.57, 0.86 +-12.85, -10.00, 52.91, 47.09, 5.83 +-12.85, -10.00, 52.93, 47.07, 5.85 +-12.79, -10.00, 50.41, 49.59, 0.83 +-12.79, -10.00, 52.90, 47.10, 5.79 +-12.66, -10.00, 47.86, 52.14, -4.27 +-12.66, -10.00, 52.82, 47.18, 5.64 +-12.66, -10.00, 52.83, 47.17, 5.65 +-12.59, -10.00, 50.32, 49.68, 0.63 +-12.59, -10.00, 52.80, 47.20, 5.59 +-12.59, -10.00, 52.81, 47.19, 5.61 +-12.52, -10.00, 50.30, 49.70, 0.59 +-12.39, -10.00, 47.73, 52.27, -4.53 +-12.39, -10.00, 52.69, 47.31, 5.37 +-12.39, -10.00, 52.70, 47.30, 5.39 +-12.39, -10.00, 52.70, 47.30, 5.41 +-12.33, -10.00, 50.19, 49.81, 0.38 +-12.33, -10.00, 52.67, 47.33, 5.34 +-12.26, -10.00, 50.16, 49.84, 0.32 +-12.26, -10.00, 52.64, 47.36, 5.28 +-12.13, -10.00, 47.61, 52.39, -4.79 +-12.13, -10.00, 52.56, 47.44, 5.11 +-12.06, -10.00, 50.04, 49.96, 0.09 +-12.06, -10.00, 52.52, 47.48, 5.05 +-12.06, -10.00, 52.53, 47.47, 5.06 +-12.00, -10.00, 50.02, 49.98, 0.03 +-12.00, -10.00, 52.50, 47.50, 4.99 +-12.00, -10.00, 52.50, 47.50, 5.01 +-11.87, -10.00, 47.47, 52.53, -5.06 +-11.87, -10.00, 52.42, 47.58, 4.84 +-11.87, -10.00, 52.43, 47.57, 4.85 +-11.87, -10.00, 52.43, 47.57, 4.87 +-11.80, -10.00, 49.92, 50.08, -0.16 +-11.80, -10.00, 52.40, 47.60, 4.79 +-11.80, -10.00, 52.40, 47.60, 4.81 +-11.73, -10.00, 49.89, 50.11, -0.22 +-11.73, -10.00, 52.37, 47.63, 4.73 +-11.73, -10.00, 52.37, 47.63, 4.75 +-11.73, -10.00, 52.38, 47.62, 4.76 +-11.73, -10.00, 52.39, 47.61, 4.77 +-11.73, -10.00, 52.39, 47.61, 4.79 +-11.60, -10.00, 47.36, 52.64, -5.29 +-11.60, -10.00, 52.31, 47.69, 4.61 +-11.60, -10.00, 52.31, 47.69, 4.62 +-11.60, -10.00, 52.32, 47.68, 4.64 +-11.60, -10.00, 52.32, 47.68, 4.65 +-11.60, -10.00, 52.33, 47.67, 4.66 +-11.54, -10.00, 49.81, 50.19, -0.37 +-11.54, -10.00, 52.29, 47.71, 4.58 +-11.54, -10.00, 52.30, 47.70, 4.60 +-11.54, -10.00, 52.30, 47.70, 4.61 +-11.54, -10.00, 52.31, 47.69, 4.62 +-11.54, -10.00, 52.32, 47.68, 4.63 +-11.54, -10.00, 52.32, 47.68, 4.64 +-11.54, -10.00, 52.33, 47.67, 4.65 +-11.54, -10.00, 52.33, 47.67, 4.67 +-11.54, -10.00, 52.34, 47.66, 4.68 +-11.54, -10.00, 52.34, 47.66, 4.69 +-11.54, -10.00, 52.35, 47.65, 4.70 +-11.54, -10.00, 52.36, 47.64, 4.71 +-11.54, -10.00, 52.36, 47.64, 4.72 +-11.60, -10.00, 54.89, 45.11, 9.78 +-11.60, -10.00, 52.42, 47.58, 4.85 +-11.60, -10.00, 52.43, 47.57, 4.86 +-11.60, -10.00, 52.43, 47.57, 4.87 +-11.60, -10.00, 52.44, 47.56, 4.88 +-11.60, -10.00, 52.45, 47.55, 4.89 +-11.60, -10.00, 52.45, 47.55, 4.91 +-11.60, -10.00, 52.46, 47.54, 4.92 +-11.60, -10.00, 52.46, 47.54, 4.93 +-11.60, -10.00, 52.47, 47.53, 4.94 +-11.73, -10.00, 57.52, 42.48, 15.04 +-11.73, -10.00, 52.58, 47.42, 5.17 +-11.73, -10.00, 52.59, 47.41, 5.18 +-11.73, -10.00, 52.60, 47.40, 5.19 +-11.73, -10.00, 52.60, 47.40, 5.20 +-11.73, -10.00, 52.61, 47.39, 5.22 +-11.73, -10.00, 52.62, 47.38, 5.23 +-11.73, -10.00, 52.62, 47.38, 5.24 +-11.73, -10.00, 52.63, 47.37, 5.26 +-11.73, -10.00, 52.63, 47.37, 5.27 +-11.73, -10.00, 52.64, 47.36, 5.28 +-11.73, -10.00, 52.65, 47.35, 5.30 +-11.73, -10.00, 52.65, 47.35, 5.31 +-11.73, -10.00, 52.66, 47.34, 5.32 +-11.73, -10.00, 52.67, 47.33, 5.33 +-11.73, -10.00, 52.67, 47.33, 5.35 +-11.73, -10.00, 52.68, 47.32, 5.36 +-11.73, -10.00, 52.69, 47.31, 5.37 +-11.73, -10.00, 52.69, 47.31, 5.39 +-11.73, -10.00, 52.70, 47.30, 5.40 +-11.80, -10.00, 55.23, 44.77, 10.46 +-11.73, -10.00, 50.24, 49.76, 0.48 +-11.80, -10.00, 55.24, 44.76, 10.48 +-11.80, -10.00, 52.78, 47.22, 5.55 +-11.80, -10.00, 52.78, 47.22, 5.57 +-11.80, -10.00, 52.79, 47.21, 5.58 +-11.80, -10.00, 52.80, 47.20, 5.59 +-11.80, -10.00, 52.80, 47.20, 5.61 +-11.80, -10.00, 52.81, 47.19, 5.62 +-11.80, -10.00, 52.82, 47.18, 5.63 +-11.80, -10.00, 52.82, 47.18, 5.65 +-11.80, -10.00, 52.83, 47.17, 5.66 +-11.80, -10.00, 52.84, 47.16, 5.67 +-11.80, -10.00, 52.84, 47.16, 5.69 +-11.87, -10.00, 55.37, 44.63, 10.74 +-11.87, -10.00, 52.91, 47.09, 5.81 +-11.87, -10.00, 52.91, 47.09, 5.83 +-11.87, -10.00, 52.92, 47.08, 5.84 +-11.87, -10.00, 52.93, 47.07, 5.86 +-11.87, -10.00, 52.93, 47.07, 5.87 +-11.87, -10.00, 52.94, 47.06, 5.88 +-11.87, -10.00, 52.95, 47.05, 5.90 +-11.87, -10.00, 52.96, 47.04, 5.91 +-11.87, -10.00, 52.96, 47.04, 5.93 +-11.87, -10.00, 52.97, 47.03, 5.94 +-11.87, -10.00, 52.98, 47.02, 5.95 +-11.87, -10.00, 52.98, 47.02, 5.97 +-11.87, -10.00, 52.99, 47.01, 5.98 +-11.87, -10.00, 53.00, 47.00, 6.00 +-11.87, -10.00, 53.00, 47.00, 6.01 +-11.87, -10.00, 53.01, 46.99, 6.02 +-11.87, -10.00, 53.02, 46.98, 6.04 +-11.87, -10.00, 53.03, 46.97, 6.05 +-11.87, -10.00, 53.03, 46.97, 6.07 +-11.87, -10.00, 53.04, 46.96, 6.08 +-11.87, -10.00, 53.05, 46.95, 6.09 +-11.87, -10.00, 53.05, 46.95, 6.11 +-11.87, -10.00, 53.06, 46.94, 6.12 +-11.87, -10.00, 53.07, 46.93, 6.14 +-11.87, -10.00, 53.07, 46.93, 6.15 +-11.87, -10.00, 53.08, 46.92, 6.16 +-11.87, -10.00, 53.09, 46.91, 6.18 +-11.87, -10.00, 53.10, 46.90, 6.19 +-11.87, -10.00, 53.10, 46.90, 6.21 +-11.87, -10.00, 53.11, 46.89, 6.22 +-11.87, -10.00, 53.12, 46.88, 6.23 +-11.87, -10.00, 53.12, 46.88, 6.25 +-11.87, -10.00, 53.13, 46.87, 6.26 +-11.87, -10.00, 53.14, 46.86, 6.28 +-11.87, -10.00, 53.14, 46.86, 6.29 +-11.87, -10.00, 53.15, 46.85, 6.30 +-11.87, -10.00, 53.16, 46.84, 6.32 +-11.87, -10.00, 53.17, 46.83, 6.33 +-11.87, -10.00, 53.17, 46.83, 6.35 +-11.80, -10.00, 50.66, 49.34, 1.32 +-11.87, -10.00, 55.66, 44.34, 11.32 +-11.80, -10.00, 50.67, 49.33, 1.34 +-11.80, -10.00, 53.15, 46.85, 6.30 +-11.80, -10.00, 53.16, 46.84, 6.31 +-11.80, -10.00, 53.16, 46.84, 6.33 +-11.80, -10.00, 53.17, 46.83, 6.34 +-11.73, -10.00, 50.66, 49.34, 1.31 +-11.73, -10.00, 53.13, 46.87, 6.27 +-11.73, -10.00, 53.14, 46.86, 6.28 +-11.73, -10.00, 53.15, 46.85, 6.29 +-11.73, -10.00, 53.15, 46.85, 6.31 +-11.73, -10.00, 53.16, 46.84, 6.32 +-11.73, -10.00, 53.17, 46.83, 6.33 +-11.73, -10.00, 53.17, 46.83, 6.35 +-11.73, -10.00, 53.18, 46.82, 6.36 +-11.60, -10.00, 48.14, 51.86, -3.71 +-11.60, -10.00, 53.09, 46.91, 6.19 +-11.60, -10.00, 53.10, 46.90, 6.20 +-11.54, -10.00, 50.58, 49.42, 1.17 +-11.54, -10.00, 53.06, 46.94, 6.12 +-11.54, -10.00, 53.07, 46.93, 6.13 +-11.54, -10.00, 53.07, 46.93, 6.15 +-11.47, -10.00, 50.56, 49.44, 1.11 +-11.47, -10.00, 53.03, 46.97, 6.07 +-11.47, -10.00, 53.04, 46.96, 6.08 +-11.34, -10.00, 48.00, 52.00, -4.00 +-11.34, -10.00, 52.95, 47.05, 5.90 +-11.27, -10.00, 50.43, 49.57, 0.87 +-11.27, -10.00, 52.91, 47.09, 5.82 +-11.27, -10.00, 52.92, 47.08, 5.83 +-11.21, -10.00, 50.40, 49.60, 0.80 +-11.21, -10.00, 52.88, 47.12, 5.75 +-11.21, -10.00, 52.88, 47.12, 5.76 +-11.07, -10.00, 47.84, 52.16, -4.32 +-11.07, -10.00, 52.79, 47.21, 5.58 +-11.07, -10.00, 52.79, 47.21, 5.59 +-11.01, -10.00, 50.28, 49.72, 0.55 +-11.01, -10.00, 52.75, 47.25, 5.50 +-10.94, -10.00, 50.23, 49.77, 0.47 +-10.81, -10.00, 47.67, 52.33, -4.67 +-10.81, -10.00, 52.61, 47.39, 5.22 +-10.81, -10.00, 52.62, 47.38, 5.23 +-10.74, -10.00, 50.10, 49.90, 0.19 +-10.68, -10.00, 50.05, 49.95, 0.10 +-10.68, -10.00, 52.52, 47.48, 5.05 +-10.55, -10.00, 47.48, 52.52, -5.03 +-10.55, -10.00, 52.43, 47.57, 4.86 +-10.55, -10.00, 52.43, 47.57, 4.86 +-10.48, -10.00, 49.91, 50.09, -0.18 +-10.48, -10.00, 52.39, 47.61, 4.77 +-10.42, -10.00, 49.87, 50.13, -0.27 +-10.42, -10.00, 52.34, 47.66, 4.68 +-10.28, -10.00, 47.30, 52.70, -5.40 +-10.28, -10.00, 52.24, 47.76, 4.49 +-10.22, -10.00, 49.72, 50.28, -0.56 +-10.22, -10.00, 52.20, 47.80, 4.39 +-10.15, -10.00, 49.67, 50.33, -0.65 +-10.15, -10.00, 52.15, 47.85, 4.29 +-10.02, -10.00, 47.10, 52.90, -5.79 +-10.02, -10.00, 52.05, 47.95, 4.10 +-10.02, -10.00, 52.05, 47.95, 4.10 +-9.95, -10.00, 49.53, 50.47, -0.95 +-9.89, -10.00, 49.48, 50.52, -1.05 +-9.89, -10.00, 51.95, 48.05, 3.90 +-9.89, -10.00, 51.95, 48.05, 3.90 +-9.76, -10.00, 46.90, 53.10, -6.19 +-9.76, -10.00, 51.85, 48.15, 3.69 +-9.76, -10.00, 51.85, 48.15, 3.69 +-9.76, -10.00, 51.85, 48.15, 3.69 +-9.69, -10.00, 49.32, 50.68, -1.35 +-9.69, -10.00, 51.79, 48.21, 3.59 +-9.69, -10.00, 51.79, 48.21, 3.58 +-9.62, -10.00, 49.27, 50.73, -1.46 +-9.62, -10.00, 51.74, 48.26, 3.48 +-9.62, -10.00, 51.74, 48.26, 3.48 +-9.62, -10.00, 51.74, 48.26, 3.47 +-9.49, -10.00, 46.69, 53.31, -6.61 +-9.49, -10.00, 51.63, 48.37, 3.27 +-9.49, -10.00, 51.63, 48.37, 3.27 +-9.49, -10.00, 51.63, 48.37, 3.26 +-9.49, -10.00, 51.63, 48.37, 3.26 +-9.49, -10.00, 51.63, 48.37, 3.25 +-9.43, -10.00, 49.10, 50.90, -1.79 +-9.43, -10.00, 51.57, 48.43, 3.15 +-9.43, -10.00, 51.57, 48.43, 3.14 +-9.43, -10.00, 51.57, 48.43, 3.14 +-9.43, -10.00, 51.57, 48.43, 3.13 +-9.43, -10.00, 51.56, 48.44, 3.13 +-9.43, -10.00, 51.56, 48.44, 3.12 +-9.43, -10.00, 51.56, 48.44, 3.12 +-9.43, -10.00, 51.56, 48.44, 3.12 +-9.43, -10.00, 51.56, 48.44, 3.11 +-9.43, -10.00, 51.55, 48.45, 3.11 +-9.43, -10.00, 51.55, 48.45, 3.10 +-9.43, -10.00, 51.55, 48.45, 3.10 +-9.43, -10.00, 51.55, 48.45, 3.09 +-9.49, -10.00, 54.07, 45.93, 8.13 +-9.49, -10.00, 51.59, 48.41, 3.19 +-9.49, -10.00, 51.59, 48.41, 3.18 +-9.49, -10.00, 51.59, 48.41, 3.18 +-9.49, -10.00, 51.59, 48.41, 3.17 +-9.62, -10.00, 56.63, 43.37, 13.26 +-9.62, -10.00, 51.68, 48.32, 3.37 +-9.62, -10.00, 51.68, 48.32, 3.36 +-9.62, -10.00, 51.68, 48.32, 3.36 +-9.69, -10.00, 54.20, 45.80, 8.40 +-9.69, -10.00, 51.73, 48.27, 3.46 +-9.69, -10.00, 51.73, 48.27, 3.45 +-9.69, -10.00, 51.73, 48.27, 3.45 +-9.76, -10.00, 54.25, 45.75, 8.49 +-9.76, -10.00, 51.77, 48.23, 3.55 +-9.76, -10.00, 51.77, 48.23, 3.54 +-9.76, -10.00, 51.77, 48.23, 3.54 +-9.89, -10.00, 56.81, 43.19, 13.63 +-9.89, -10.00, 51.87, 48.13, 3.74 +-9.89, -10.00, 51.87, 48.13, 3.74 +-9.89, -10.00, 51.87, 48.13, 3.74 +-9.95, -10.00, 54.39, 45.61, 8.78 +-10.02, -10.00, 54.44, 45.56, 8.88 +-10.02, -10.00, 51.97, 48.03, 3.93 +-10.02, -10.00, 51.97, 48.03, 3.93 +-10.02, -10.00, 51.97, 48.03, 3.93 +-10.02, -10.00, 51.97, 48.03, 3.93 +-10.15, -10.00, 57.01, 42.99, 14.02 +-10.15, -10.00, 52.07, 47.93, 4.13 +-10.15, -10.00, 52.07, 47.93, 4.14 +-10.22, -10.00, 54.59, 45.41, 9.18 +-10.22, -10.00, 52.12, 47.88, 4.24 +-10.22, -10.00, 52.12, 47.88, 4.24 +-10.22, -10.00, 52.12, 47.88, 4.24 +-10.28, -10.00, 54.64, 45.36, 9.29 +-10.28, -10.00, 52.17, 47.83, 4.34 +-10.28, -10.00, 52.17, 47.83, 4.35 +-10.28, -10.00, 52.17, 47.83, 4.35 +-10.42, -10.00, 57.22, 42.78, 14.44 +-10.42, -10.00, 52.28, 47.72, 4.55 +-10.42, -10.00, 52.28, 47.72, 4.56 +-10.42, -10.00, 52.28, 47.72, 4.56 +-10.48, -10.00, 54.80, 45.20, 9.61 +-10.48, -10.00, 52.33, 47.67, 4.66 +-10.48, -10.00, 52.33, 47.67, 4.67 +-10.48, -10.00, 52.34, 47.66, 4.67 +-10.48, -10.00, 52.34, 47.66, 4.68 +-10.48, -10.00, 52.34, 47.66, 4.68 +-10.48, -10.00, 52.34, 47.66, 4.68 +-10.55, -10.00, 54.86, 45.14, 9.73 +-10.55, -10.00, 52.40, 47.60, 4.79 +-10.55, -10.00, 52.40, 47.60, 4.79 +-10.55, -10.00, 52.40, 47.60, 4.80 +-10.55, -10.00, 52.40, 47.60, 4.80 +-10.55, -10.00, 52.40, 47.60, 4.81 +-10.55, -10.00, 52.41, 47.59, 4.81 +-10.68, -10.00, 57.45, 42.55, 14.90 +-10.68, -10.00, 52.51, 47.49, 5.02 +-10.68, -10.00, 52.51, 47.49, 5.02 +-10.68, -10.00, 52.51, 47.49, 5.03 +-10.68, -10.00, 52.52, 47.48, 5.03 +-10.68, -10.00, 52.52, 47.48, 5.04 +-10.68, -10.00, 52.52, 47.48, 5.04 +-10.68, -10.00, 52.52, 47.48, 5.05 +-10.68, -10.00, 52.53, 47.47, 5.05 +-10.68, -10.00, 52.53, 47.47, 5.06 +-10.68, -10.00, 52.53, 47.47, 5.06 +-10.68, -10.00, 52.53, 47.47, 5.07 +-10.74, -10.00, 55.06, 44.94, 10.12 +-10.74, -10.00, 52.59, 47.41, 5.18 +-10.74, -10.00, 52.59, 47.41, 5.19 +-10.74, -10.00, 52.60, 47.40, 5.19 +-10.74, -10.00, 52.60, 47.40, 5.20 +-10.74, -10.00, 52.60, 47.40, 5.20 +-10.74, -10.00, 52.60, 47.40, 5.21 +-10.74, -10.00, 52.61, 47.39, 5.21 +-10.74, -10.00, 52.61, 47.39, 5.22 +-10.74, -10.00, 52.61, 47.39, 5.22 +-10.74, -10.00, 52.61, 47.39, 5.23 +-10.74, -10.00, 52.62, 47.38, 5.24 +-10.74, -10.00, 52.62, 47.38, 5.24 +-10.74, -10.00, 52.62, 47.38, 5.25 +-10.74, -10.00, 52.63, 47.37, 5.25 +-10.74, -10.00, 52.63, 47.37, 5.26 +-10.74, -10.00, 52.63, 47.37, 5.26 +-10.74, -10.00, 52.63, 47.37, 5.27 +-10.74, -10.00, 52.64, 47.36, 5.27 +-10.81, -10.00, 55.16, 44.84, 10.32 +-10.74, -10.00, 50.17, 49.83, 0.34 +-10.81, -10.00, 55.17, 44.83, 10.33 +-10.81, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 50.18, 49.82, 0.36 +-10.74, -10.00, 52.65, 47.35, 5.31 +-10.81, -10.00, 55.18, 44.82, 10.36 +-10.81, -10.00, 52.71, 47.29, 5.42 +-10.81, -10.00, 52.71, 47.29, 5.43 +-10.81, -10.00, 52.72, 47.28, 5.43 +-10.81, -10.00, 52.72, 47.28, 5.44 +-10.81, -10.00, 52.72, 47.28, 5.44 +-10.81, -10.00, 52.73, 47.27, 5.45 +-10.81, -10.00, 52.73, 47.27, 5.46 +-10.74, -10.00, 50.21, 49.79, 0.42 +-10.74, -10.00, 52.68, 47.32, 5.37 +-10.74, -10.00, 52.69, 47.31, 5.37 +-10.74, -10.00, 52.69, 47.31, 5.38 +-10.74, -10.00, 52.69, 47.31, 5.39 +-10.74, -10.00, 52.70, 47.30, 5.39 +-10.74, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 52.70, 47.30, 5.40 +-10.74, -10.00, 52.70, 47.30, 5.41 +-10.74, -10.00, 52.71, 47.29, 5.41 +-10.74, -10.00, 52.71, 47.29, 5.42 +-10.74, -10.00, 52.71, 47.29, 5.43 +-10.74, -10.00, 52.72, 47.28, 5.43 +-10.74, -10.00, 52.72, 47.28, 5.44 +-10.74, -10.00, 52.72, 47.28, 5.44 +-10.68, -10.00, 50.20, 49.80, 0.40 +-10.74, -10.00, 55.20, 44.80, 10.40 +-10.68, -10.00, 50.21, 49.79, 0.41 +-10.68, -10.00, 52.68, 47.32, 5.36 +-10.68, -10.00, 52.68, 47.32, 5.37 +-10.68, -10.00, 52.69, 47.31, 5.37 +-10.68, -10.00, 52.69, 47.31, 5.38 +-10.68, -10.00, 52.69, 47.31, 5.38 +-10.68, -10.00, 52.69, 47.31, 5.39 +-10.68, -10.00, 52.70, 47.30, 5.39 +-10.68, -10.00, 52.70, 47.30, 5.40 +-10.68, -10.00, 52.70, 47.30, 5.40 +-10.68, -10.00, 52.70, 47.30, 5.41 +-10.55, -10.00, 47.66, 52.34, -4.67 +-10.55, -10.00, 52.61, 47.39, 5.22 +-10.55, -10.00, 52.61, 47.39, 5.22 +-10.55, -10.00, 52.61, 47.39, 5.23 +-10.55, -10.00, 52.62, 47.38, 5.23 +-10.55, -10.00, 52.62, 47.38, 5.24 +-10.55, -10.00, 52.62, 47.38, 5.24 +-10.55, -10.00, 52.62, 47.38, 5.24 +-10.55, -10.00, 52.62, 47.38, 5.25 +-10.55, -10.00, 52.63, 47.37, 5.25 +-10.55, -10.00, 52.63, 47.37, 5.26 +-10.55, -10.00, 52.63, 47.37, 5.26 +-10.48, -10.00, 50.11, 49.89, 0.22 +-10.48, -10.00, 52.58, 47.42, 5.17 +-10.48, -10.00, 52.59, 47.41, 5.17 +-10.48, -10.00, 52.59, 47.41, 5.18 +-10.48, -10.00, 52.59, 47.41, 5.18 +-10.42, -10.00, 50.07, 49.93, 0.14 +-10.42, -10.00, 52.54, 47.46, 5.09 +-10.42, -10.00, 52.55, 47.45, 5.09 +-10.42, -10.00, 52.55, 47.45, 5.09 +-10.42, -10.00, 52.55, 47.45, 5.10 +-10.42, -10.00, 52.55, 47.45, 5.10 +-10.28, -10.00, 47.51, 52.49, -4.98 +-10.28, -10.00, 52.45, 47.55, 4.91 +-10.28, -10.00, 52.45, 47.55, 4.91 +-10.28, -10.00, 52.46, 47.54, 4.91 +-10.28, -10.00, 52.46, 47.54, 4.91 +-10.22, -10.00, 49.94, 50.06, -0.13 +-10.22, -10.00, 52.41, 47.59, 4.82 +-10.22, -10.00, 52.41, 47.59, 4.82 +-10.22, -10.00, 52.41, 47.59, 4.82 +-10.15, -10.00, 49.89, 50.11, -0.22 +-10.15, -10.00, 52.36, 47.64, 4.72 +-10.15, -10.00, 52.36, 47.64, 4.73 +-10.15, -10.00, 52.36, 47.64, 4.73 +-10.15, -10.00, 52.36, 47.64, 4.73 +-10.02, -10.00, 47.32, 52.68, -5.36 +-10.02, -10.00, 52.26, 47.74, 4.53 +-10.02, -10.00, 52.26, 47.74, 4.53 +-10.02, -10.00, 52.27, 47.73, 4.53 +-10.02, -10.00, 52.27, 47.73, 4.53 +-9.95, -10.00, 49.74, 50.26, -0.51 +-9.95, -10.00, 52.22, 47.78, 4.43 +-9.95, -10.00, 52.22, 47.78, 4.43 +-9.89, -10.00, 49.69, 50.31, -0.61 +-9.89, -10.00, 52.16, 47.84, 4.33 +-9.89, -10.00, 52.16, 47.84, 4.33 +-9.76, -10.00, 47.12, 52.88, -5.76 +-9.76, -10.00, 52.06, 47.94, 4.13 +-9.76, -10.00, 52.06, 47.94, 4.13 +-9.76, -10.00, 52.06, 47.94, 4.12 +-9.69, -10.00, 49.54, 50.46, -0.92 +-9.69, -10.00, 52.01, 47.99, 4.02 +-9.69, -10.00, 52.01, 47.99, 4.02 +-9.69, -10.00, 52.01, 47.99, 4.02 +-9.62, -10.00, 49.49, 50.51, -1.03 +-9.62, -10.00, 51.96, 48.04, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.91 +-9.62, -10.00, 51.95, 48.05, 3.91 +-9.49, -10.00, 46.91, 53.09, -6.18 +-9.49, -10.00, 51.85, 48.15, 3.70 +-9.49, -10.00, 51.85, 48.15, 3.70 +-9.49, -10.00, 51.85, 48.15, 3.69 +-9.49, -10.00, 51.84, 48.16, 3.69 +-9.43, -10.00, 49.32, 50.68, -1.36 +-9.43, -10.00, 51.79, 48.21, 3.58 +-9.43, -10.00, 51.79, 48.21, 3.58 +-9.43, -10.00, 51.79, 48.21, 3.57 +-9.36, -10.00, 49.26, 50.74, -1.47 +-9.36, -10.00, 51.73, 48.27, 3.46 +-9.36, -10.00, 51.73, 48.27, 3.46 +-9.36, -10.00, 51.73, 48.27, 3.45 +-9.36, -10.00, 51.72, 48.28, 3.45 +-9.36, -10.00, 51.72, 48.28, 3.44 +-9.36, -10.00, 51.72, 48.28, 3.44 +-9.36, -10.00, 51.72, 48.28, 3.44 +-9.36, -10.00, 51.72, 48.28, 3.43 +-9.36, -10.00, 51.71, 48.29, 3.43 +-9.36, -10.00, 51.71, 48.29, 3.42 +-9.36, -10.00, 51.71, 48.29, 3.42 +-9.36, -10.00, 51.71, 48.29, 3.41 +-9.36, -10.00, 51.70, 48.30, 3.41 +-9.36, -10.00, 51.70, 48.30, 3.40 +-9.36, -10.00, 51.70, 48.30, 3.40 +-9.36, -10.00, 51.70, 48.30, 3.39 +-9.36, -10.00, 51.69, 48.31, 3.39 +-9.36, -10.00, 51.69, 48.31, 3.38 +-9.36, -10.00, 51.69, 48.31, 3.38 +-9.36, -10.00, 51.69, 48.31, 3.37 +-9.36, -10.00, 51.68, 48.32, 3.37 +-9.36, -10.00, 51.68, 48.32, 3.36 +-9.43, -10.00, 54.20, 45.80, 8.40 +-9.43, -10.00, 51.73, 48.27, 3.45 +-9.43, -10.00, 51.72, 48.28, 3.45 +-9.43, -10.00, 51.72, 48.28, 3.45 +-9.43, -10.00, 51.72, 48.28, 3.44 +-9.43, -10.00, 51.72, 48.28, 3.44 +-9.43, -10.00, 51.72, 48.28, 3.43 +-9.43, -10.00, 51.71, 48.29, 3.43 +-9.43, -10.00, 51.71, 48.29, 3.42 +-9.43, -10.00, 51.71, 48.29, 3.42 +-9.36, -10.00, 49.19, 50.81, -1.63 +-9.36, -10.00, 51.66, 48.34, 3.31 +-9.36, -10.00, 51.65, 48.35, 3.31 +-9.36, -10.00, 51.65, 48.35, 3.30 +-9.36, -10.00, 51.65, 48.35, 3.30 +-9.36, -10.00, 51.65, 48.35, 3.29 +-9.36, -10.00, 51.64, 48.36, 3.29 +-9.23, -10.00, 46.60, 53.40, -6.80 +-9.36, -10.00, 56.58, 43.42, 13.16 +-9.23, -10.00, 46.59, 53.41, -6.82 +-9.23, -10.00, 51.53, 48.47, 3.07 +-9.23, -10.00, 51.53, 48.47, 3.06 +-9.23, -10.00, 51.53, 48.47, 3.06 +-9.23, -10.00, 51.52, 48.48, 3.05 +-9.23, -10.00, 51.52, 48.48, 3.04 +-9.23, -10.00, 51.52, 48.48, 3.04 +-9.23, -10.00, 51.52, 48.48, 3.03 +-9.16, -10.00, 48.99, 51.01, -2.02 +-9.16, -10.00, 51.46, 48.54, 2.92 +-9.16, -10.00, 51.46, 48.54, 2.91 +-9.10, -10.00, 48.93, 51.07, -2.14 +-9.10, -10.00, 51.40, 48.60, 2.80 +-9.10, -10.00, 51.40, 48.60, 2.80 +-9.10, -10.00, 51.39, 48.61, 2.79 +-9.10, -10.00, 51.39, 48.61, 2.78 +-9.10, -10.00, 51.39, 48.61, 2.77 +-8.96, -10.00, 46.34, 53.66, -7.32 +-8.96, -10.00, 51.28, 48.72, 2.56 +-8.96, -10.00, 51.28, 48.72, 2.55 +-8.96, -10.00, 51.27, 48.73, 2.55 +-8.96, -10.00, 51.27, 48.73, 2.54 +-8.90, -10.00, 48.74, 51.26, -2.51 +-8.90, -10.00, 51.21, 48.79, 2.42 +-8.90, -10.00, 51.21, 48.79, 2.41 +-8.90, -10.00, 51.20, 48.80, 2.41 +-8.83, -10.00, 48.68, 51.32, -2.65 +-8.83, -10.00, 51.15, 48.85, 2.29 +-8.83, -10.00, 51.14, 48.86, 2.28 +-8.70, -10.00, 46.09, 53.91, -7.81 +-8.70, -10.00, 51.03, 48.97, 2.06 +-8.70, -10.00, 51.03, 48.97, 2.05 +-8.70, -10.00, 51.02, 48.98, 2.04 +-8.70, -10.00, 51.02, 48.98, 2.03 +-8.70, -10.00, 51.01, 48.99, 2.03 +-8.70, -10.00, 51.01, 48.99, 2.02 +-8.70, -10.00, 51.00, 49.00, 2.01 +-8.70, -10.00, 51.00, 49.00, 2.00 +-8.64, -10.00, 48.47, 51.53, -3.06 +-8.70, -10.00, 53.46, 46.54, 6.92 +-8.64, -10.00, 48.46, 51.54, -3.08 +-8.70, -10.00, 53.45, 46.55, 6.90 +-8.64, -10.00, 48.45, 51.55, -3.10 +-8.64, -10.00, 50.92, 49.08, 1.84 +-8.64, -10.00, 50.91, 49.09, 1.83 +-8.64, -10.00, 50.91, 49.09, 1.82 +-8.64, -10.00, 50.90, 49.10, 1.81 +-8.64, -10.00, 50.90, 49.10, 1.80 +-8.64, -10.00, 50.89, 49.11, 1.79 +-8.64, -10.00, 50.89, 49.11, 1.78 +-8.64, -10.00, 50.88, 49.12, 1.76 +-8.64, -10.00, 50.88, 49.12, 1.75 +-8.64, -10.00, 50.87, 49.13, 1.74 +-8.64, -10.00, 50.87, 49.13, 1.73 +-8.64, -10.00, 50.86, 49.14, 1.72 +-8.70, -10.00, 53.38, 46.62, 6.76 +-8.70, -10.00, 50.90, 49.10, 1.80 +-8.70, -10.00, 50.90, 49.10, 1.79 +-8.70, -10.00, 50.89, 49.11, 1.78 +-8.70, -10.00, 50.89, 49.11, 1.77 +-8.70, -10.00, 50.88, 49.12, 1.76 +-8.70, -10.00, 50.88, 49.12, 1.75 +-8.70, -10.00, 50.87, 49.13, 1.74 +-8.70, -10.00, 50.87, 49.13, 1.74 +-8.83, -10.00, 55.91, 44.09, 11.81 +-8.83, -10.00, 50.96, 49.04, 1.92 +-8.83, -10.00, 50.95, 49.05, 1.91 +-8.83, -10.00, 50.95, 49.05, 1.90 +-8.83, -10.00, 50.94, 49.06, 1.89 +-8.83, -10.00, 50.94, 49.06, 1.88 +-8.83, -10.00, 50.94, 49.06, 1.87 +-8.83, -10.00, 50.93, 49.07, 1.86 +-8.83, -10.00, 50.93, 49.07, 1.85 +-8.90, -10.00, 53.44, 46.56, 6.89 +-8.90, -10.00, 50.97, 49.03, 1.94 +-8.90, -10.00, 50.96, 49.04, 1.93 +-8.90, -10.00, 50.96, 49.04, 1.92 +-8.90, -10.00, 50.96, 49.04, 1.91 +-8.90, -10.00, 50.95, 49.05, 1.90 +-8.90, -10.00, 50.95, 49.05, 1.90 +-8.96, -10.00, 53.47, 46.53, 6.93 +-8.96, -10.00, 50.99, 49.01, 1.98 +-8.96, -10.00, 50.99, 49.01, 1.97 +-8.96, -10.00, 50.98, 49.02, 1.96 +-8.96, -10.00, 50.98, 49.02, 1.96 +-9.10, -10.00, 56.02, 43.98, 12.03 +-9.10, -10.00, 51.07, 48.93, 2.14 +-9.10, -10.00, 51.07, 48.93, 2.13 +-9.16, -10.00, 53.58, 46.42, 7.17 +-9.16, -10.00, 51.11, 48.89, 2.22 +-9.16, -10.00, 51.11, 48.89, 2.21 +-9.23, -10.00, 53.62, 46.38, 7.25 +-9.23, -10.00, 51.15, 48.85, 2.30 +-9.23, -10.00, 51.15, 48.85, 2.29 +-9.36, -10.00, 56.19, 43.81, 12.37 +-9.36, -10.00, 51.24, 48.76, 2.48 +-9.43, -10.00, 53.76, 46.24, 7.52 +-9.43, -10.00, 51.29, 48.71, 2.57 +-9.49, -10.00, 53.81, 46.19, 7.61 +-9.49, -10.00, 51.33, 48.67, 2.66 +-9.62, -10.00, 56.37, 43.63, 12.75 +-9.62, -10.00, 51.43, 48.57, 2.86 +-9.69, -10.00, 53.95, 46.05, 7.90 +-9.69, -10.00, 51.48, 48.52, 2.95 +-9.76, -10.00, 54.00, 46.00, 7.99 +-9.76, -10.00, 51.52, 48.48, 3.05 +-9.89, -10.00, 56.57, 43.43, 13.13 +-9.89, -10.00, 51.62, 48.38, 3.24 +-9.95, -10.00, 54.14, 45.86, 8.28 +-10.02, -10.00, 54.19, 45.81, 8.38 +-10.02, -10.00, 51.72, 48.28, 3.44 +-10.02, -10.00, 51.72, 48.28, 3.44 +-10.15, -10.00, 56.76, 43.24, 13.53 +-10.15, -10.00, 51.82, 48.18, 3.64 +-10.22, -10.00, 54.34, 45.66, 8.68 +-10.22, -10.00, 51.87, 48.13, 3.74 +-10.28, -10.00, 54.39, 45.61, 8.79 +-10.28, -10.00, 51.92, 48.08, 3.84 +-10.42, -10.00, 56.97, 43.03, 13.93 +-10.42, -10.00, 52.02, 47.98, 4.05 +-10.48, -10.00, 54.55, 45.45, 9.10 +-10.48, -10.00, 52.08, 47.92, 4.15 +-10.48, -10.00, 52.08, 47.92, 4.16 +-10.55, -10.00, 54.60, 45.40, 9.21 +-10.55, -10.00, 52.13, 47.87, 4.27 +-10.55, -10.00, 52.13, 47.87, 4.27 +-10.55, -10.00, 52.14, 47.86, 4.27 +-10.68, -10.00, 57.18, 42.82, 14.36 +-10.68, -10.00, 52.24, 47.76, 4.48 +-10.68, -10.00, 52.24, 47.76, 4.49 +-10.68, -10.00, 52.25, 47.75, 4.49 +-10.68, -10.00, 52.25, 47.75, 4.50 +-10.68, -10.00, 52.25, 47.75, 4.50 +-10.68, -10.00, 52.25, 47.75, 4.51 +-10.74, -10.00, 54.78, 45.22, 9.56 +-10.68, -10.00, 49.79, 50.21, -0.43 +-10.74, -10.00, 54.78, 45.22, 9.57 +-10.74, -10.00, 52.31, 47.69, 4.63 +-10.74, -10.00, 52.32, 47.68, 4.63 +-10.74, -10.00, 52.32, 47.68, 4.64 +-10.74, -10.00, 52.32, 47.68, 4.64 +-10.68, -10.00, 49.80, 50.20, -0.39 +-10.74, -10.00, 54.80, 45.20, 9.60 +-10.68, -10.00, 49.81, 50.19, -0.38 +-10.68, -10.00, 52.28, 47.72, 4.57 +-10.68, -10.00, 52.29, 47.71, 4.57 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.58 +-10.68, -10.00, 52.29, 47.71, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.59 +-10.68, -10.00, 52.30, 47.70, 4.60 +-10.68, -10.00, 52.30, 47.70, 4.60 +-10.68, -10.00, 52.30, 47.70, 4.61 +-10.68, -10.00, 52.31, 47.69, 4.61 +-10.68, -10.00, 52.31, 47.69, 4.62 +-10.55, -10.00, 47.27, 52.73, -5.46 +-10.55, -10.00, 52.21, 47.79, 4.43 +-10.55, -10.00, 52.22, 47.78, 4.43 +-10.55, -10.00, 52.22, 47.78, 4.44 +-10.55, -10.00, 52.22, 47.78, 4.44 +-10.55, -10.00, 52.22, 47.78, 4.44 +-10.48, -10.00, 49.70, 50.30, -0.59 +-10.48, -10.00, 52.18, 47.82, 4.35 +-10.48, -10.00, 52.18, 47.82, 4.36 +-10.48, -10.00, 52.18, 47.82, 4.36 +-10.48, -10.00, 52.18, 47.82, 4.36 +-10.42, -10.00, 49.66, 50.34, -0.68 +-10.42, -10.00, 52.14, 47.86, 4.27 +-10.42, -10.00, 52.14, 47.86, 4.27 +-10.42, -10.00, 52.14, 47.86, 4.28 +-10.28, -10.00, 47.10, 52.90, -5.81 +-10.28, -10.00, 52.04, 47.96, 4.08 +-10.28, -10.00, 52.04, 47.96, 4.09 +-10.28, -10.00, 52.04, 47.96, 4.09 +-10.22, -10.00, 49.52, 50.48, -0.95 +-10.22, -10.00, 52.00, 48.00, 3.99 +-10.22, -10.00, 52.00, 48.00, 3.99 +-10.22, -10.00, 52.00, 48.00, 4.00 +-10.15, -10.00, 49.48, 50.52, -1.05 +-10.15, -10.00, 51.95, 48.05, 3.90 +-10.15, -10.00, 51.95, 48.05, 3.90 +-10.15, -10.00, 51.95, 48.05, 3.90 +-10.02, -10.00, 46.91, 53.09, -6.18 +-10.02, -10.00, 51.85, 48.15, 3.70 +-10.02, -10.00, 51.85, 48.15, 3.70 +-10.02, -10.00, 51.85, 48.15, 3.70 +-10.02, -10.00, 51.85, 48.15, 3.70 +-9.95, -10.00, 49.33, 50.67, -1.34 +-9.89, -10.00, 49.28, 50.72, -1.44 +-9.89, -10.00, 51.75, 48.25, 3.50 +-9.89, -10.00, 51.75, 48.25, 3.50 +-9.76, -10.00, 46.71, 53.29, -6.58 +-9.76, -10.00, 51.65, 48.35, 3.30 +-9.76, -10.00, 51.65, 48.35, 3.30 +-9.76, -10.00, 51.65, 48.35, 3.30 +-9.76, -10.00, 51.65, 48.35, 3.30 +-9.69, -10.00, 49.13, 50.87, -1.75 +-9.69, -10.00, 51.60, 48.40, 3.19 +-9.69, -10.00, 51.60, 48.40, 3.19 +-9.69, -10.00, 51.59, 48.41, 3.19 +-9.62, -10.00, 49.07, 50.93, -1.86 +-9.62, -10.00, 51.54, 48.46, 3.08 +-9.62, -10.00, 51.54, 48.46, 3.08 +-9.62, -10.00, 51.54, 48.46, 3.08 +-9.49, -10.00, 46.49, 53.51, -7.01 +-9.49, -10.00, 51.44, 48.56, 2.87 +-9.49, -10.00, 51.43, 48.57, 2.87 +-9.43, -10.00, 48.91, 51.09, -2.18 +-9.43, -10.00, 51.38, 48.62, 2.76 +-9.43, -10.00, 51.38, 48.62, 2.76 +-9.43, -10.00, 51.38, 48.62, 2.75 +-9.36, -10.00, 48.85, 51.15, -2.29 +-9.36, -10.00, 51.32, 48.68, 2.64 +-9.36, -10.00, 51.32, 48.68, 2.64 +-9.36, -10.00, 51.32, 48.68, 2.63 +-9.36, -10.00, 51.32, 48.68, 2.63 +-9.36, -10.00, 51.31, 48.69, 2.63 +-9.36, -10.00, 51.31, 48.69, 2.62 +-9.23, -10.00, 46.26, 53.74, -7.47 +-9.23, -10.00, 51.21, 48.79, 2.41 +-9.23, -10.00, 51.20, 48.80, 2.41 +-9.23, -10.00, 51.20, 48.80, 2.40 +-9.23, -10.00, 51.20, 48.80, 2.39 +-9.23, -10.00, 51.19, 48.81, 2.39 +-9.23, -10.00, 51.19, 48.81, 2.38 +-9.23, -10.00, 51.19, 48.81, 2.38 +-9.23, -10.00, 51.19, 48.81, 2.37 +-9.23, -10.00, 51.18, 48.82, 2.36 +-9.23, -10.00, 51.18, 48.82, 2.36 +-9.23, -10.00, 51.18, 48.82, 2.35 +-9.23, -10.00, 51.17, 48.83, 2.35 +-9.23, -10.00, 51.17, 48.83, 2.34 +-9.23, -10.00, 51.17, 48.83, 2.34 +-9.23, -10.00, 51.17, 48.83, 2.33 +-9.23, -10.00, 51.16, 48.84, 2.32 +-9.23, -10.00, 51.16, 48.84, 2.32 +-9.23, -10.00, 51.16, 48.84, 2.31 +-9.36, -10.00, 56.20, 43.80, 12.39 +-9.36, -10.00, 51.25, 48.75, 2.50 +-9.36, -10.00, 51.25, 48.75, 2.50 +-9.36, -10.00, 51.25, 48.75, 2.49 +-9.36, -10.00, 51.24, 48.76, 2.49 +-9.43, -10.00, 53.76, 46.24, 7.52 +-9.43, -10.00, 51.29, 48.71, 2.58 +-9.43, -10.00, 51.29, 48.71, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.57 +-9.49, -10.00, 53.80, 46.20, 7.61 +-9.49, -10.00, 51.33, 48.67, 2.66 +-9.49, -10.00, 51.33, 48.67, 2.66 +-9.49, -10.00, 51.33, 48.67, 2.65 +-9.62, -10.00, 56.37, 43.63, 12.73 +-9.62, -10.00, 51.42, 48.58, 2.84 +-9.62, -10.00, 51.42, 48.58, 2.84 +-9.62, -10.00, 51.42, 48.58, 2.84 +-9.69, -10.00, 53.94, 46.06, 7.88 +-9.69, -10.00, 51.47, 48.53, 2.93 +-9.69, -10.00, 51.47, 48.53, 2.93 +-9.76, -10.00, 53.99, 46.01, 7.97 +-9.76, -10.00, 51.51, 48.49, 3.03 +-9.76, -10.00, 51.51, 48.49, 3.02 +-9.76, -10.00, 51.51, 48.49, 3.02 +-9.76, -10.00, 51.51, 48.49, 3.02 +-9.89, -10.00, 56.55, 43.45, 13.10 +-9.89, -10.00, 51.61, 48.39, 3.22 +-9.89, -10.00, 51.61, 48.39, 3.22 +-9.95, -10.00, 54.13, 45.87, 8.26 +-9.95, -10.00, 51.66, 48.34, 3.31 +-10.02, -10.00, 54.18, 45.82, 8.36 +-10.02, -10.00, 51.71, 48.29, 3.41 +-10.02, -10.00, 51.71, 48.29, 3.41 +-10.02, -10.00, 51.71, 48.29, 3.41 +-10.02, -10.00, 51.71, 48.29, 3.41 +-10.15, -10.00, 56.75, 43.25, 13.50 +-10.15, -10.00, 51.81, 48.19, 3.61 +-10.15, -10.00, 51.81, 48.19, 3.61 +-10.15, -10.00, 51.81, 48.19, 3.62 +-10.22, -10.00, 54.33, 45.67, 8.66 +-10.22, -10.00, 51.86, 48.14, 3.72 +-10.22, -10.00, 51.86, 48.14, 3.72 +-10.28, -10.00, 54.38, 45.62, 8.76 +-10.28, -10.00, 51.91, 48.09, 3.82 +-10.28, -10.00, 51.91, 48.09, 3.82 +-10.28, -10.00, 51.91, 48.09, 3.83 +-10.28, -10.00, 51.91, 48.09, 3.83 +-10.28, -10.00, 51.92, 48.08, 3.83 +-10.28, -10.00, 51.92, 48.08, 3.83 +-10.42, -10.00, 56.96, 43.04, 13.92 +-10.42, -10.00, 52.02, 47.98, 4.04 +-10.42, -10.00, 52.02, 47.98, 4.04 +-10.42, -10.00, 52.02, 47.98, 4.04 +-10.42, -10.00, 52.02, 47.98, 4.05 +-10.42, -10.00, 52.02, 47.98, 4.05 +-10.42, -10.00, 52.03, 47.97, 4.05 +-10.42, -10.00, 52.03, 47.97, 4.06 +-10.42, -10.00, 52.03, 47.97, 4.06 +-10.42, -10.00, 52.03, 47.97, 4.06 +-10.42, -10.00, 52.03, 47.97, 4.06 +-10.42, -10.00, 52.03, 47.97, 4.07 +-10.42, -10.00, 52.04, 47.96, 4.07 +-10.42, -10.00, 52.04, 47.96, 4.07 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.09 +-10.42, -10.00, 52.04, 47.96, 4.09 +-10.42, -10.00, 52.05, 47.95, 4.09 +-10.42, -10.00, 52.05, 47.95, 4.10 +-10.28, -10.00, 47.01, 52.99, -5.99 +-10.28, -10.00, 51.95, 48.05, 3.90 +-10.28, -10.00, 51.95, 48.05, 3.90 +-10.28, -10.00, 51.95, 48.05, 3.91 +-10.28, -10.00, 51.95, 48.05, 3.91 +-10.28, -10.00, 51.96, 48.04, 3.91 +-10.28, -10.00, 51.96, 48.04, 3.91 +-10.28, -10.00, 51.96, 48.04, 3.92 +-10.28, -10.00, 51.96, 48.04, 3.92 +-10.28, -10.00, 51.96, 48.04, 3.92 +-10.28, -10.00, 51.96, 48.04, 3.92 +-10.22, -10.00, 49.44, 50.56, -1.12 +-10.22, -10.00, 51.91, 48.09, 3.83 +-10.22, -10.00, 51.91, 48.09, 3.83 +-10.22, -10.00, 51.91, 48.09, 3.83 +-10.22, -10.00, 51.92, 48.08, 3.83 +-10.22, -10.00, 51.92, 48.08, 3.83 +-10.22, -10.00, 51.92, 48.08, 3.83 +-10.15, -10.00, 49.40, 50.60, -1.21 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.74 +-10.15, -10.00, 51.87, 48.13, 3.75 +-10.02, -10.00, 46.83, 53.17, -6.34 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-10.02, -10.00, 51.77, 48.23, 3.55 +-9.95, -10.00, 49.25, 50.75, -1.49 +-9.95, -10.00, 51.72, 48.28, 3.45 +-9.95, -10.00, 51.72, 48.28, 3.45 +-9.95, -10.00, 51.72, 48.28, 3.45 +-9.89, -10.00, 49.20, 50.80, -1.60 +-9.89, -10.00, 51.67, 48.33, 3.35 +-9.89, -10.00, 51.67, 48.33, 3.35 +-9.89, -10.00, 51.67, 48.33, 3.35 +-9.89, -10.00, 51.67, 48.33, 3.35 +-9.89, -10.00, 51.67, 48.33, 3.34 +-9.89, -10.00, 51.67, 48.33, 3.34 +-9.76, -10.00, 46.63, 53.37, -6.74 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.76, -10.00, 51.57, 48.43, 3.14 +-9.69, -10.00, 49.04, 50.96, -1.91 +-9.69, -10.00, 51.52, 48.48, 3.03 +-9.69, -10.00, 51.51, 48.49, 3.03 +-9.62, -10.00, 48.99, 51.01, -2.02 +-9.62, -10.00, 51.46, 48.54, 2.92 +-9.62, -10.00, 51.46, 48.54, 2.92 +-9.62, -10.00, 51.46, 48.54, 2.92 +-9.62, -10.00, 51.46, 48.54, 2.92 +-9.62, -10.00, 51.46, 48.54, 2.91 +-9.62, -10.00, 51.46, 48.54, 2.91 +-9.49, -10.00, 46.41, 53.59, -7.18 +-9.49, -10.00, 51.35, 48.65, 2.71 +-9.49, -10.00, 51.35, 48.65, 2.70 +-9.49, -10.00, 51.35, 48.65, 2.70 +-9.49, -10.00, 51.35, 48.65, 2.69 +-9.43, -10.00, 48.82, 51.18, -2.35 +-9.43, -10.00, 51.29, 48.71, 2.59 +-9.43, -10.00, 51.29, 48.71, 2.58 +-9.43, -10.00, 51.29, 48.71, 2.58 +-9.43, -10.00, 51.29, 48.71, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.57 +-9.43, -10.00, 51.28, 48.72, 2.56 +-9.36, -10.00, 48.76, 51.24, -2.48 +-9.36, -10.00, 51.23, 48.77, 2.46 +-9.43, -10.00, 53.75, 46.25, 7.49 +-9.36, -10.00, 48.75, 51.25, -2.50 +-9.43, -10.00, 53.74, 46.26, 7.49 +-9.36, -10.00, 48.75, 51.25, -2.51 +-9.36, -10.00, 51.22, 48.78, 2.43 +-9.43, -10.00, 53.74, 46.26, 7.47 +-9.36, -10.00, 48.74, 51.26, -2.52 +-9.36, -10.00, 51.21, 48.79, 2.42 +-9.36, -10.00, 51.21, 48.79, 2.41 +-9.36, -10.00, 51.20, 48.80, 2.41 +-9.36, -10.00, 51.20, 48.80, 2.41 +-9.36, -10.00, 51.20, 48.80, 2.40 +-9.36, -10.00, 51.20, 48.80, 2.40 +-9.36, -10.00, 51.20, 48.80, 2.39 +-9.36, -10.00, 51.19, 48.81, 2.39 +-9.36, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 51.19, 48.81, 2.37 +-9.36, -10.00, 51.18, 48.82, 2.37 +-9.43, -10.00, 53.70, 46.30, 7.41 +-9.43, -10.00, 51.23, 48.77, 2.46 +-9.43, -10.00, 51.23, 48.77, 2.45 +-9.43, -10.00, 51.22, 48.78, 2.45 +-9.43, -10.00, 51.22, 48.78, 2.44 +-9.43, -10.00, 51.22, 48.78, 2.44 +-9.43, -10.00, 51.22, 48.78, 2.44 +-9.43, -10.00, 51.22, 48.78, 2.43 +-9.49, -10.00, 53.73, 46.27, 7.47 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.52 +-9.49, -10.00, 51.26, 48.74, 2.51 +-9.49, -10.00, 51.26, 48.74, 2.51 +-9.49, -10.00, 51.25, 48.75, 2.51 +-9.62, -10.00, 56.29, 43.71, 12.59 +-9.62, -10.00, 51.35, 48.65, 2.70 +-9.62, -10.00, 51.35, 48.65, 2.70 +-9.62, -10.00, 51.35, 48.65, 2.69 +-9.69, -10.00, 53.87, 46.13, 7.73 +-9.69, -10.00, 51.39, 48.61, 2.79 +-9.69, -10.00, 51.39, 48.61, 2.79 +-9.76, -10.00, 53.91, 46.09, 7.83 +-9.76, -10.00, 51.44, 48.56, 2.88 +-9.76, -10.00, 51.44, 48.56, 2.88 +-9.76, -10.00, 51.44, 48.56, 2.88 +-9.76, -10.00, 51.44, 48.56, 2.88 +-9.89, -10.00, 56.48, 43.52, 12.96 +-9.89, -10.00, 51.54, 48.46, 3.07 +-9.89, -10.00, 51.54, 48.46, 3.07 +-9.89, -10.00, 51.53, 48.47, 3.07 +-9.89, -10.00, 51.53, 48.47, 3.07 +-9.95, -10.00, 54.06, 45.94, 8.11 +-9.95, -10.00, 51.58, 48.42, 3.17 +-9.95, -10.00, 51.58, 48.42, 3.17 +-10.02, -10.00, 54.10, 45.90, 8.21 +-10.02, -10.00, 51.63, 48.37, 3.27 +-10.02, -10.00, 51.63, 48.37, 3.27 +-10.02, -10.00, 51.63, 48.37, 3.27 +-10.02, -10.00, 51.63, 48.37, 3.27 +-10.15, -10.00, 56.68, 43.32, 13.35 +-10.15, -10.00, 51.73, 48.27, 3.47 +-10.15, -10.00, 51.73, 48.27, 3.47 +-10.15, -10.00, 51.73, 48.27, 3.47 +-10.15, -10.00, 51.73, 48.27, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.47 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.48 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.75, 48.25, 3.49 +-10.15, -10.00, 51.75, 48.25, 3.49 +-10.15, -10.00, 51.75, 48.25, 3.49 +-10.15, -10.00, 51.75, 48.25, 3.49 +-10.02, -10.00, 46.70, 53.30, -6.59 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-10.02, -10.00, 51.65, 48.35, 3.30 +-9.95, -10.00, 49.13, 50.87, -1.75 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.95, -10.00, 51.60, 48.40, 3.20 +-9.89, -10.00, 49.08, 50.92, -1.85 +-9.95, -10.00, 54.07, 45.93, 8.14 +-9.89, -10.00, 49.08, 50.92, -1.85 +-9.89, -10.00, 51.55, 48.45, 3.10 +-9.89, -10.00, 51.55, 48.45, 3.09 +-9.89, -10.00, 51.55, 48.45, 3.09 +-9.89, -10.00, 51.55, 48.45, 3.09 +-9.95, -10.00, 54.07, 45.93, 8.14 +-9.95, -10.00, 51.60, 48.40, 3.19 +-9.95, -10.00, 51.60, 48.40, 3.19 +-9.95, -10.00, 51.60, 48.40, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-9.95, -10.00, 51.59, 48.41, 3.19 +-10.02, -10.00, 54.12, 45.88, 8.23 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.02, -10.00, 51.64, 48.36, 3.29 +-10.15, -10.00, 56.69, 43.31, 13.37 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.15, -10.00, 51.74, 48.26, 3.49 +-10.22, -10.00, 54.27, 45.73, 8.53 +-10.22, -10.00, 51.80, 48.20, 3.59 +-10.22, -10.00, 51.80, 48.20, 3.59 +-10.22, -10.00, 51.80, 48.20, 3.59 +-10.22, -10.00, 51.80, 48.20, 3.60 +-10.22, -10.00, 51.80, 48.20, 3.60 +-10.28, -10.00, 54.32, 45.68, 8.64 +-10.28, -10.00, 51.85, 48.15, 3.70 +-10.28, -10.00, 51.85, 48.15, 3.70 +-10.28, -10.00, 51.85, 48.15, 3.70 +-10.28, -10.00, 51.85, 48.15, 3.71 +-10.28, -10.00, 51.85, 48.15, 3.71 +-10.42, -10.00, 56.90, 43.10, 13.80 +-10.42, -10.00, 51.96, 48.04, 3.91 +-10.42, -10.00, 51.96, 48.04, 3.92 +-10.42, -10.00, 51.96, 48.04, 3.92 +-10.48, -10.00, 54.48, 45.52, 8.97 +-10.48, -10.00, 52.01, 47.99, 4.03 +-10.48, -10.00, 52.01, 47.99, 4.03 +-10.48, -10.00, 52.02, 47.98, 4.03 +-10.48, -10.00, 52.02, 47.98, 4.04 +-10.55, -10.00, 54.54, 45.46, 9.08 +-10.55, -10.00, 52.07, 47.93, 4.14 +-10.55, -10.00, 52.07, 47.93, 4.15 +-10.55, -10.00, 52.08, 47.92, 4.15 +-10.55, -10.00, 52.08, 47.92, 4.16 +-10.55, -10.00, 52.08, 47.92, 4.16 +-10.55, -10.00, 52.08, 47.92, 4.16 +-10.55, -10.00, 52.08, 47.92, 4.17 +-10.55, -10.00, 52.09, 47.91, 4.17 +-10.55, -10.00, 52.09, 47.91, 4.18 +-10.55, -10.00, 52.09, 47.91, 4.18 +-10.55, -10.00, 52.09, 47.91, 4.18 +-10.55, -10.00, 52.09, 47.91, 4.19 +-10.55, -10.00, 52.10, 47.90, 4.19 +-10.55, -10.00, 52.10, 47.90, 4.20 +-10.68, -10.00, 57.14, 42.86, 14.29 +-10.55, -10.00, 47.16, 52.84, -5.68 +-10.68, -10.00, 57.15, 42.85, 14.30 +-10.55, -10.00, 47.16, 52.84, -5.67 +-10.55, -10.00, 52.11, 47.89, 4.22 +-10.55, -10.00, 52.11, 47.89, 4.22 +-10.55, -10.00, 52.11, 47.89, 4.23 +-10.55, -10.00, 52.12, 47.88, 4.23 +-10.55, -10.00, 52.12, 47.88, 4.24 +-10.55, -10.00, 52.12, 47.88, 4.24 +-10.55, -10.00, 52.12, 47.88, 4.24 +-10.55, -10.00, 52.12, 47.88, 4.25 +-10.55, -10.00, 52.13, 47.87, 4.25 +-10.48, -10.00, 49.61, 50.39, -0.79 +-10.48, -10.00, 52.08, 47.92, 4.16 +-10.48, -10.00, 52.08, 47.92, 4.16 +-10.48, -10.00, 52.08, 47.92, 4.17 +-10.48, -10.00, 52.09, 47.91, 4.17 +-10.42, -10.00, 49.57, 50.43, -0.87 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.42, -10.00, 52.04, 47.96, 4.08 +-10.28, -10.00, 47.00, 53.00, -6.00 +-10.28, -10.00, 51.95, 48.05, 3.89 +-10.28, -10.00, 51.95, 48.05, 3.89 +-10.28, -10.00, 51.95, 48.05, 3.90 +-10.22, -10.00, 49.43, 50.57, -1.15 +-10.22, -10.00, 51.90, 48.10, 3.80 +-10.22, -10.00, 51.90, 48.10, 3.80 +-10.22, -10.00, 51.90, 48.10, 3.80 +-10.15, -10.00, 49.38, 50.62, -1.24 +-10.15, -10.00, 51.85, 48.15, 3.71 +-10.15, -10.00, 51.85, 48.15, 3.71 +-10.02, -10.00, 46.81, 53.19, -6.38 +-10.02, -10.00, 51.75, 48.25, 3.51 +-10.02, -10.00, 51.75, 48.25, 3.51 +-10.02, -10.00, 51.76, 48.24, 3.51 +-10.02, -10.00, 51.76, 48.24, 3.51 +-10.02, -10.00, 51.76, 48.24, 3.51 +-10.02, -10.00, 51.76, 48.24, 3.51 +-9.95, -10.00, 49.23, 50.77, -1.53 +-9.95, -10.00, 51.71, 48.29, 3.41 +-9.95, -10.00, 51.71, 48.29, 3.41 +-9.89, -10.00, 49.18, 50.82, -1.63 +-9.89, -10.00, 51.66, 48.34, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.31 +-9.89, -10.00, 51.65, 48.35, 3.30 +-9.89, -10.00, 51.65, 48.35, 3.30 +-9.89, -10.00, 51.65, 48.35, 3.30 +-9.95, -10.00, 54.17, 45.83, 8.34 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-10.02, -10.00, 54.22, 45.78, 8.44 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-10.02, -10.00, 51.75, 48.25, 3.50 +-9.95, -10.00, 49.23, 50.77, -1.54 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.95, -10.00, 51.70, 48.30, 3.40 +-9.89, -10.00, 49.18, 50.82, -1.65 +-9.95, -10.00, 54.17, 45.83, 8.34 +-9.89, -10.00, 49.18, 50.82, -1.65 +-9.89, -10.00, 51.65, 48.35, 3.29 +-9.89, -10.00, 51.65, 48.35, 3.29 +-9.89, -10.00, 51.65, 48.35, 3.29 +-9.89, -10.00, 51.65, 48.35, 3.29 +-9.76, -10.00, 46.60, 53.40, -6.80 +-9.76, -10.00, 51.55, 48.45, 3.09 +-9.76, -10.00, 51.54, 48.46, 3.09 +-9.76, -10.00, 51.54, 48.46, 3.09 +-9.76, -10.00, 51.54, 48.46, 3.09 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.76, -10.00, 51.54, 48.46, 3.08 +-9.69, -10.00, 49.02, 50.98, -1.97 +-9.69, -10.00, 51.49, 48.51, 2.97 +-9.69, -10.00, 51.49, 48.51, 2.97 +-9.69, -10.00, 51.48, 48.52, 2.97 +-9.69, -10.00, 51.48, 48.52, 2.97 +-9.62, -10.00, 48.96, 51.04, -2.08 +-9.62, -10.00, 51.43, 48.57, 2.86 +-9.62, -10.00, 51.43, 48.57, 2.86 +-9.62, -10.00, 51.43, 48.57, 2.86 +-9.62, -10.00, 51.43, 48.57, 2.85 +-9.62, -10.00, 51.42, 48.58, 2.85 +-9.49, -10.00, 46.38, 53.62, -7.24 +-9.49, -10.00, 51.32, 48.68, 2.64 +-9.49, -10.00, 51.32, 48.68, 2.64 +-9.49, -10.00, 51.32, 48.68, 2.64 +-9.49, -10.00, 51.32, 48.68, 2.63 +-9.49, -10.00, 51.31, 48.69, 2.63 +-9.49, -10.00, 51.31, 48.69, 2.63 +-9.49, -10.00, 51.31, 48.69, 2.62 +-9.49, -10.00, 51.31, 48.69, 2.62 +-9.43, -10.00, 48.79, 51.21, -2.43 +-9.43, -10.00, 51.26, 48.74, 2.51 +-9.43, -10.00, 51.25, 48.75, 2.51 +-9.43, -10.00, 51.25, 48.75, 2.50 +-9.43, -10.00, 51.25, 48.75, 2.50 +-9.43, -10.00, 51.25, 48.75, 2.49 +-9.43, -10.00, 51.24, 48.76, 2.49 +-9.36, -10.00, 48.72, 51.28, -2.56 +-9.36, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 51.19, 48.81, 2.38 +-9.36, -10.00, 51.19, 48.81, 2.37 +-9.36, -10.00, 51.18, 48.82, 2.37 +-9.36, -10.00, 51.18, 48.82, 2.36 +-9.36, -10.00, 51.18, 48.82, 2.36 +-9.36, -10.00, 51.18, 48.82, 2.35 +-9.36, -10.00, 51.17, 48.83, 2.35 +-9.36, -10.00, 51.17, 48.83, 2.34 +-9.36, -10.00, 51.17, 48.83, 2.34 +-9.36, -10.00, 51.17, 48.83, 2.33 +-9.36, -10.00, 51.16, 48.84, 2.33 +-9.36, -10.00, 51.16, 48.84, 2.32 +-9.36, -10.00, 51.16, 48.84, 2.32 +-9.36, -10.00, 51.16, 48.84, 2.31 +-9.36, -10.00, 51.15, 48.85, 2.31 +-9.36, -10.00, 51.15, 48.85, 2.30 +-9.36, -10.00, 51.15, 48.85, 2.30 +-9.36, -10.00, 51.15, 48.85, 2.29 +-9.36, -10.00, 51.14, 48.86, 2.29 +-9.36, -10.00, 51.14, 48.86, 2.28 +-9.36, -10.00, 51.14, 48.86, 2.28 +-9.36, -10.00, 51.14, 48.86, 2.27 +-9.36, -10.00, 51.13, 48.87, 2.27 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.26 +-9.36, -10.00, 51.13, 48.87, 2.25 +-9.36, -10.00, 51.12, 48.88, 2.25 +-9.36, -10.00, 51.12, 48.88, 2.24 +-9.36, -10.00, 51.12, 48.88, 2.24 +-9.36, -10.00, 51.12, 48.88, 2.23 +-9.36, -10.00, 51.11, 48.89, 2.23 +-9.36, -10.00, 51.11, 48.89, 2.22 +-9.36, -10.00, 51.11, 48.89, 2.22 +-9.36, -10.00, 51.11, 48.89, 2.21 +-9.36, -10.00, 51.10, 48.90, 2.21 +-9.36, -10.00, 51.10, 48.90, 2.20 +-9.36, -10.00, 51.10, 48.90, 2.20 +-9.36, -10.00, 51.10, 48.90, 2.19 +-9.36, -10.00, 51.09, 48.91, 2.19 +-9.36, -10.00, 51.09, 48.91, 2.18 +-9.36, -10.00, 51.09, 48.91, 2.18 +-9.36, -10.00, 51.09, 48.91, 2.17 +-9.23, -10.00, 46.04, 53.96, -7.92 +-9.23, -10.00, 50.98, 49.02, 1.96 +-9.23, -10.00, 50.98, 49.02, 1.96 +-9.23, -10.00, 50.98, 49.02, 1.95 +-9.23, -10.00, 50.97, 49.03, 1.95 +-9.23, -10.00, 50.97, 49.03, 1.94 +-9.23, -10.00, 50.97, 49.03, 1.94 +-9.23, -10.00, 50.96, 49.04, 1.93 +-9.23, -10.00, 50.96, 49.04, 1.92 +-9.23, -10.00, 50.96, 49.04, 1.92 +-9.23, -10.00, 50.96, 49.04, 1.91 +-9.23, -10.00, 50.95, 49.05, 1.91 +-9.23, -10.00, 50.95, 49.05, 1.90 +-9.23, -10.00, 50.95, 49.05, 1.90 +-9.23, -10.00, 50.94, 49.06, 1.89 +-9.23, -10.00, 50.94, 49.06, 1.88 +-9.23, -10.00, 50.94, 49.06, 1.88 +-9.36, -10.00, 55.98, 44.02, 11.96 +-9.36, -10.00, 51.03, 48.97, 2.07 +-9.36, -10.00, 51.03, 48.97, 2.06 +-9.36, -10.00, 51.03, 48.97, 2.06 +-9.36, -10.00, 51.03, 48.97, 2.05 +-9.36, -10.00, 51.02, 48.98, 2.05 +-9.36, -10.00, 51.02, 48.98, 2.04 +-9.36, -10.00, 51.02, 48.98, 2.04 +-9.36, -10.00, 51.02, 48.98, 2.03 +-9.36, -10.00, 51.01, 48.99, 2.03 +-9.43, -10.00, 53.53, 46.47, 7.07 +-9.43, -10.00, 51.06, 48.94, 2.12 +-9.43, -10.00, 51.06, 48.94, 2.11 +-9.43, -10.00, 51.05, 48.95, 2.11 +-9.43, -10.00, 51.05, 48.95, 2.10 +-9.43, -10.00, 51.05, 48.95, 2.10 +-9.43, -10.00, 51.05, 48.95, 2.10 +-9.43, -10.00, 51.05, 48.95, 2.09 +-9.43, -10.00, 51.04, 48.96, 2.09 +-9.43, -10.00, 51.04, 48.96, 2.08 +-9.49, -10.00, 53.56, 46.44, 7.12 +-9.49, -10.00, 51.09, 48.91, 2.17 +-9.49, -10.00, 51.09, 48.91, 2.17 +-9.49, -10.00, 51.08, 48.92, 2.17 +-9.49, -10.00, 51.08, 48.92, 2.16 +-9.49, -10.00, 51.08, 48.92, 2.16 +-9.49, -10.00, 51.08, 48.92, 2.16 +-9.49, -10.00, 51.08, 48.92, 2.15 +-9.49, -10.00, 51.07, 48.93, 2.15 +-9.62, -10.00, 56.12, 43.88, 12.23 +-9.62, -10.00, 51.17, 48.83, 2.34 +-9.62, -10.00, 51.17, 48.83, 2.34 +-9.62, -10.00, 51.17, 48.83, 2.33 +-9.62, -10.00, 51.17, 48.83, 2.33 +-9.62, -10.00, 51.16, 48.84, 2.33 +-9.62, -10.00, 51.16, 48.84, 2.33 +-9.62, -10.00, 51.16, 48.84, 2.32 +-9.62, -10.00, 51.16, 48.84, 2.32 +-9.62, -10.00, 51.16, 48.84, 2.32 +-9.62, -10.00, 51.16, 48.84, 2.31 +-9.62, -10.00, 51.16, 48.84, 2.31 +-9.62, -10.00, 51.15, 48.85, 2.31 +-9.62, -10.00, 51.15, 48.85, 2.31 +-9.62, -10.00, 51.15, 48.85, 2.30 +-9.62, -10.00, 51.15, 48.85, 2.30 +-9.69, -10.00, 53.67, 46.33, 7.34 +-9.62, -10.00, 48.68, 51.32, -2.65 +-9.69, -10.00, 53.67, 46.33, 7.34 +-9.62, -10.00, 48.67, 51.33, -2.65 +-9.69, -10.00, 53.67, 46.33, 7.33 +-9.69, -10.00, 51.19, 48.81, 2.38 +-9.69, -10.00, 51.19, 48.81, 2.38 +-9.62, -10.00, 48.67, 51.33, -2.66 +-9.62, -10.00, 51.14, 48.86, 2.28 +-9.69, -10.00, 53.66, 46.34, 7.32 +-9.69, -10.00, 51.19, 48.81, 2.37 +-9.69, -10.00, 51.18, 48.82, 2.37 +-9.69, -10.00, 51.18, 48.82, 2.37 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.36 +-9.69, -10.00, 51.18, 48.82, 2.35 +-9.69, -10.00, 51.18, 48.82, 2.35 +-9.69, -10.00, 51.17, 48.83, 2.35 +-9.69, -10.00, 51.17, 48.83, 2.35 +-9.69, -10.00, 51.17, 48.83, 2.34 +-9.62, -10.00, 48.65, 51.35, -2.70 +-9.62, -10.00, 51.12, 48.88, 2.24 +-9.62, -10.00, 51.12, 48.88, 2.24 +-9.62, -10.00, 51.12, 48.88, 2.23 +-9.62, -10.00, 51.12, 48.88, 2.23 +-9.62, -10.00, 51.11, 48.89, 2.23 +-9.62, -10.00, 51.11, 48.89, 2.23 +-9.62, -10.00, 51.11, 48.89, 2.22 +-9.62, -10.00, 51.11, 48.89, 2.22 +-9.49, -10.00, 46.07, 53.93, -7.87 +-9.49, -10.00, 51.01, 48.99, 2.01 +-9.49, -10.00, 51.01, 48.99, 2.01 +-9.49, -10.00, 51.00, 49.00, 2.01 +-9.49, -10.00, 51.00, 49.00, 2.00 +-9.49, -10.00, 51.00, 49.00, 2.00 +-9.49, -10.00, 51.00, 49.00, 2.00 +-9.49, -10.00, 51.00, 49.00, 1.99 +-9.49, -10.00, 50.99, 49.01, 1.99 +-9.49, -10.00, 50.99, 49.01, 1.98 +-9.49, -10.00, 50.99, 49.01, 1.98 +-9.43, -10.00, 48.47, 51.53, -3.07 +-9.43, -10.00, 50.94, 49.06, 1.87 +-9.43, -10.00, 50.93, 49.07, 1.87 +-9.43, -10.00, 50.93, 49.07, 1.86 +-9.43, -10.00, 50.93, 49.07, 1.86 +-9.43, -10.00, 50.93, 49.07, 1.86 +-9.43, -10.00, 50.93, 49.07, 1.85 +-9.43, -10.00, 50.92, 49.08, 1.85 +-9.43, -10.00, 50.92, 49.08, 1.84 +-9.43, -10.00, 50.92, 49.08, 1.84 +-9.43, -10.00, 50.92, 49.08, 1.83 +-9.43, -10.00, 50.91, 49.09, 1.83 +-9.43, -10.00, 50.91, 49.09, 1.83 +-9.43, -10.00, 50.91, 49.09, 1.82 +-9.43, -10.00, 50.91, 49.09, 1.82 +-9.43, -10.00, 50.91, 49.09, 1.81 +-9.36, -10.00, 48.38, 51.62, -3.24 +-9.36, -10.00, 50.85, 49.15, 1.70 +-9.36, -10.00, 50.85, 49.15, 1.70 +-9.36, -10.00, 50.85, 49.15, 1.69 +-9.36, -10.00, 50.84, 49.16, 1.69 +-9.36, -10.00, 50.84, 49.16, 1.68 +-9.36, -10.00, 50.84, 49.16, 1.68 +-9.36, -10.00, 50.84, 49.16, 1.68 +-9.43, -10.00, 53.36, 46.64, 6.71 +-9.43, -10.00, 50.88, 49.12, 1.77 +-9.43, -10.00, 50.88, 49.12, 1.76 +-9.43, -10.00, 50.88, 49.12, 1.76 +-9.43, -10.00, 50.88, 49.12, 1.75 +-9.43, -10.00, 50.87, 49.13, 1.75 +-9.36, -10.00, 48.35, 51.65, -3.30 +-9.43, -10.00, 53.34, 46.66, 6.68 +-9.43, -10.00, 50.87, 49.13, 1.73 +-9.43, -10.00, 50.87, 49.13, 1.73 +-9.43, -10.00, 50.86, 49.14, 1.73 +-9.43, -10.00, 50.86, 49.14, 1.72 +-9.43, -10.00, 50.86, 49.14, 1.72 +-9.43, -10.00, 50.86, 49.14, 1.71 +-9.43, -10.00, 50.85, 49.15, 1.71 +-9.43, -10.00, 50.85, 49.15, 1.70 +-9.43, -10.00, 50.85, 49.15, 1.70 +-9.43, -10.00, 50.85, 49.15, 1.70 +-9.49, -10.00, 53.37, 46.63, 6.73 +-9.49, -10.00, 50.89, 49.11, 1.79 +-9.49, -10.00, 50.89, 49.11, 1.78 +-9.49, -10.00, 50.89, 49.11, 1.78 +-9.49, -10.00, 50.89, 49.11, 1.78 +-9.49, -10.00, 50.89, 49.11, 1.77 +-9.49, -10.00, 50.88, 49.12, 1.77 +-9.49, -10.00, 50.88, 49.12, 1.76 +-9.62, -10.00, 55.92, 44.08, 11.85 +-9.62, -10.00, 50.98, 49.02, 1.96 +-9.62, -10.00, 50.98, 49.02, 1.95 +-9.62, -10.00, 50.98, 49.02, 1.95 +-9.62, -10.00, 50.97, 49.03, 1.95 +-9.62, -10.00, 50.97, 49.03, 1.95 +-9.62, -10.00, 50.97, 49.03, 1.94 +-9.62, -10.00, 50.97, 49.03, 1.94 +-9.62, -10.00, 50.97, 49.03, 1.94 +-9.69, -10.00, 53.49, 46.51, 6.98 +-9.62, -10.00, 48.49, 51.51, -3.01 +-9.69, -10.00, 53.49, 46.51, 6.97 +-9.69, -10.00, 51.01, 48.99, 2.03 +-9.69, -10.00, 51.01, 48.99, 2.02 +-9.69, -10.00, 51.01, 48.99, 2.02 +-9.69, -10.00, 51.01, 48.99, 2.02 +-9.69, -10.00, 51.01, 48.99, 2.02 +-9.69, -10.00, 51.01, 48.99, 2.01 +-9.69, -10.00, 51.01, 48.99, 2.01 +-9.69, -10.00, 51.00, 49.00, 2.01 +-9.69, -10.00, 51.00, 49.00, 2.01 +-9.69, -10.00, 51.00, 49.00, 2.00 +-9.69, -10.00, 51.00, 49.00, 2.00 +-9.69, -10.00, 51.00, 49.00, 2.00 +-9.76, -10.00, 53.52, 46.48, 7.04 +-9.69, -10.00, 48.53, 51.47, -2.95 +-9.76, -10.00, 53.52, 46.48, 7.04 +-9.76, -10.00, 51.05, 48.95, 2.09 +-9.76, -10.00, 51.04, 48.96, 2.09 +-9.76, -10.00, 51.04, 48.96, 2.09 +-9.76, -10.00, 51.04, 48.96, 2.09 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.08 +-9.76, -10.00, 51.04, 48.96, 2.07 +-9.76, -10.00, 51.04, 48.96, 2.07 +-9.76, -10.00, 51.04, 48.96, 2.07 +-9.76, -10.00, 51.03, 48.97, 2.07 +-9.76, -10.00, 51.03, 48.97, 2.07 +-9.76, -10.00, 51.03, 48.97, 2.07 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.06 +-9.76, -10.00, 51.03, 48.97, 2.05 +-9.76, -10.00, 51.03, 48.97, 2.05 +-9.76, -10.00, 51.03, 48.97, 2.05 +-9.76, -10.00, 51.02, 48.98, 2.05 +-9.76, -10.00, 51.02, 48.98, 2.05 +-9.76, -10.00, 51.02, 48.98, 2.05 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.04 +-9.76, -10.00, 51.02, 48.98, 2.03 +-9.76, -10.00, 51.02, 48.98, 2.03 +-9.76, -10.00, 51.02, 48.98, 2.03 +-9.76, -10.00, 51.01, 48.99, 2.03 +-9.76, -10.00, 51.01, 48.99, 2.03 +-9.76, -10.00, 51.01, 48.99, 2.03 +-9.69, -10.00, 48.49, 51.51, -3.02 +-9.69, -10.00, 50.96, 49.04, 1.92 +-9.69, -10.00, 50.96, 49.04, 1.92 +-9.69, -10.00, 50.96, 49.04, 1.92 +-9.69, -10.00, 50.96, 49.04, 1.91 +-9.69, -10.00, 50.96, 49.04, 1.91 +-9.69, -10.00, 50.96, 49.04, 1.91 +-9.69, -10.00, 50.95, 49.05, 1.91 +-9.69, -10.00, 50.95, 49.05, 1.91 +-9.69, -10.00, 50.95, 49.05, 1.90 +-9.62, -10.00, 48.43, 51.57, -3.14 +-9.62, -10.00, 50.90, 49.10, 1.80 +-9.62, -10.00, 50.90, 49.10, 1.80 +-9.62, -10.00, 50.90, 49.10, 1.79 +-9.62, -10.00, 50.90, 49.10, 1.79 +-9.62, -10.00, 50.89, 49.11, 1.79 +-9.62, -10.00, 50.89, 49.11, 1.78 +-9.62, -10.00, 50.89, 49.11, 1.78 +-9.62, -10.00, 50.89, 49.11, 1.78 +-9.62, -10.00, 50.89, 49.11, 1.78 +-9.62, -10.00, 50.89, 49.11, 1.77 +-9.62, -10.00, 50.89, 49.11, 1.77 +-9.62, -10.00, 50.88, 49.12, 1.77 +-9.62, -10.00, 50.88, 49.12, 1.76 +-9.62, -10.00, 50.88, 49.12, 1.76 +-9.69, -10.00, 53.40, 46.60, 6.80 +-9.69, -10.00, 50.93, 49.07, 1.86 +-9.62, -10.00, 48.41, 51.59, -3.19 +-9.69, -10.00, 53.40, 46.60, 6.80 +-9.69, -10.00, 50.92, 49.08, 1.85 +-9.69, -10.00, 50.92, 49.08, 1.85 +-9.69, -10.00, 50.92, 49.08, 1.84 +-9.76, -10.00, 53.44, 46.56, 6.89 +-9.76, -10.00, 50.97, 49.03, 1.94 +-9.76, -10.00, 50.97, 49.03, 1.94 +-9.76, -10.00, 50.97, 49.03, 1.94 +-9.76, -10.00, 50.97, 49.03, 1.93 +-9.76, -10.00, 50.97, 49.03, 1.93 +-9.76, -10.00, 50.97, 49.03, 1.93 +-9.76, -10.00, 50.96, 49.04, 1.93 +-9.89, -10.00, 56.01, 43.99, 12.01 +-9.89, -10.00, 51.06, 48.94, 2.12 +-9.89, -10.00, 51.06, 48.94, 2.12 +-9.89, -10.00, 51.06, 48.94, 2.12 +-9.89, -10.00, 51.06, 48.94, 2.12 +-9.95, -10.00, 53.58, 46.42, 7.16 +-9.95, -10.00, 51.11, 48.89, 2.22 +-10.02, -10.00, 53.63, 46.37, 7.26 +-10.02, -10.00, 51.16, 48.84, 2.32 +-10.02, -10.00, 51.16, 48.84, 2.32 +-10.02, -10.00, 51.16, 48.84, 2.32 +-10.02, -10.00, 51.16, 48.84, 2.32 +-10.15, -10.00, 56.20, 43.80, 12.41 +-10.15, -10.00, 51.26, 48.74, 2.52 +-10.15, -10.00, 51.26, 48.74, 2.52 +-10.22, -10.00, 53.78, 46.22, 7.57 +-10.22, -10.00, 51.31, 48.69, 2.62 +-10.22, -10.00, 51.31, 48.69, 2.62 +-10.22, -10.00, 51.31, 48.69, 2.63 +-10.28, -10.00, 53.84, 46.16, 7.67 +-10.28, -10.00, 51.36, 48.64, 2.73 +-10.28, -10.00, 51.37, 48.63, 2.73 +-10.28, -10.00, 51.37, 48.63, 2.73 +-10.28, -10.00, 51.37, 48.63, 2.74 +-10.42, -10.00, 56.41, 43.59, 12.82 +-10.42, -10.00, 51.47, 48.53, 2.94 +-10.42, -10.00, 51.47, 48.53, 2.94 +-10.42, -10.00, 51.47, 48.53, 2.95 +-10.48, -10.00, 54.00, 46.00, 7.99 +-10.48, -10.00, 51.53, 48.47, 3.05 +-10.48, -10.00, 51.53, 48.47, 3.06 +-10.48, -10.00, 51.53, 48.47, 3.06 +-10.55, -10.00, 54.05, 45.95, 8.11 +-10.55, -10.00, 51.58, 48.42, 3.17 +-10.55, -10.00, 51.59, 48.41, 3.17 +-10.55, -10.00, 51.59, 48.41, 3.17 +-10.55, -10.00, 51.59, 48.41, 3.18 +-10.55, -10.00, 51.59, 48.41, 3.18 +-10.55, -10.00, 51.59, 48.41, 3.19 +-10.68, -10.00, 56.64, 43.36, 13.28 +-10.68, -10.00, 51.70, 48.30, 3.39 +-10.68, -10.00, 51.70, 48.30, 3.40 +-10.68, -10.00, 51.70, 48.30, 3.41 +-10.68, -10.00, 51.71, 48.29, 3.41 +-10.68, -10.00, 51.71, 48.29, 3.42 +-10.68, -10.00, 51.71, 48.29, 3.42 +-10.68, -10.00, 51.71, 48.29, 3.43 +-10.68, -10.00, 51.72, 48.28, 3.43 +-10.68, -10.00, 51.72, 48.28, 3.44 +-10.68, -10.00, 51.72, 48.28, 3.44 +-10.74, -10.00, 54.24, 45.76, 8.49 +-10.68, -10.00, 49.25, 50.75, -1.49 +-10.74, -10.00, 54.25, 45.75, 8.50 +-10.74, -10.00, 51.78, 48.22, 3.56 +-10.74, -10.00, 51.78, 48.22, 3.57 +-10.74, -10.00, 51.79, 48.21, 3.57 +-10.74, -10.00, 51.79, 48.21, 3.58 +-10.74, -10.00, 51.79, 48.21, 3.58 +-10.74, -10.00, 51.79, 48.21, 3.59 +-10.68, -10.00, 49.28, 50.72, -1.45 +-10.68, -10.00, 51.75, 48.25, 3.50 +-10.68, -10.00, 51.75, 48.25, 3.51 +-10.68, -10.00, 51.76, 48.24, 3.51 +-10.68, -10.00, 51.76, 48.24, 3.52 +-10.68, -10.00, 51.76, 48.24, 3.52 +-10.68, -10.00, 51.76, 48.24, 3.53 +-10.68, -10.00, 51.77, 48.23, 3.53 +-10.68, -10.00, 51.77, 48.23, 3.54 +-10.68, -10.00, 51.77, 48.23, 3.54 +-10.68, -10.00, 51.77, 48.23, 3.55 +-10.68, -10.00, 51.78, 48.22, 3.55 +-10.68, -10.00, 51.78, 48.22, 3.56 +-10.68, -10.00, 51.78, 48.22, 3.56 +-10.68, -10.00, 51.78, 48.22, 3.57 +-10.68, -10.00, 51.79, 48.21, 3.57 +-10.68, -10.00, 51.79, 48.21, 3.58 +-10.68, -10.00, 51.79, 48.21, 3.58 +-10.68, -10.00, 51.79, 48.21, 3.59 +-10.68, -10.00, 51.80, 48.20, 3.59 +-10.68, -10.00, 51.80, 48.20, 3.60 +-10.68, -10.00, 51.80, 48.20, 3.60 +-10.68, -10.00, 51.80, 48.20, 3.61 +-10.68, -10.00, 51.81, 48.19, 3.61 +-10.68, -10.00, 51.81, 48.19, 3.62 +-10.68, -10.00, 51.81, 48.19, 3.62 +-10.68, -10.00, 51.81, 48.19, 3.63 +-10.55, -10.00, 46.77, 53.23, -6.45 +-10.55, -10.00, 51.72, 48.28, 3.44 +-10.55, -10.00, 51.72, 48.28, 3.44 +-10.55, -10.00, 51.72, 48.28, 3.45 +-10.55, -10.00, 51.73, 48.27, 3.45 +-10.55, -10.00, 51.73, 48.27, 3.45 +-10.55, -10.00, 51.73, 48.27, 3.46 +-10.55, -10.00, 51.73, 48.27, 3.46 +-10.55, -10.00, 51.73, 48.27, 3.47 +-10.55, -10.00, 51.74, 48.26, 3.47 +-10.55, -10.00, 51.74, 48.26, 3.48 +-10.55, -10.00, 51.74, 48.26, 3.48 +-10.55, -10.00, 51.74, 48.26, 3.48 +-10.55, -10.00, 51.74, 48.26, 3.49 +-10.55, -10.00, 51.75, 48.25, 3.49 +-10.55, -10.00, 51.75, 48.25, 3.50 +-10.55, -10.00, 51.75, 48.25, 3.50 +-10.55, -10.00, 51.75, 48.25, 3.50 +-10.55, -10.00, 51.75, 48.25, 3.51 +-10.55, -10.00, 51.76, 48.24, 3.51 +-10.55, -10.00, 51.76, 48.24, 3.52 +-10.55, -10.00, 51.76, 48.24, 3.52 +-10.55, -10.00, 51.76, 48.24, 3.52 +-10.55, -10.00, 51.76, 48.24, 3.53 +-10.55, -10.00, 51.77, 48.23, 3.53 +-10.55, -10.00, 51.77, 48.23, 3.54 +-10.55, -10.00, 51.77, 48.23, 3.54 +-10.55, -10.00, 51.77, 48.23, 3.54 +-10.55, -10.00, 51.77, 48.23, 3.55 +-10.55, -10.00, 51.78, 48.22, 3.55 +-10.55, -10.00, 51.78, 48.22, 3.56 +-10.55, -10.00, 51.78, 48.22, 3.56 +-10.55, -10.00, 51.78, 48.22, 3.57 +-10.55, -10.00, 51.78, 48.22, 3.57 +-10.55, -10.00, 51.79, 48.21, 3.57 +-10.55, -10.00, 51.79, 48.21, 3.58 +-10.55, -10.00, 51.79, 48.21, 3.58 +-10.55, -10.00, 51.79, 48.21, 3.59 +-10.55, -10.00, 51.80, 48.20, 3.59 +-10.55, -10.00, 51.80, 48.20, 3.59 +-10.55, -10.00, 51.80, 48.20, 3.60 +-10.55, -10.00, 51.80, 48.20, 3.60 +-10.55, -10.00, 51.80, 48.20, 3.61 +-10.55, -10.00, 51.81, 48.19, 3.61 +-10.55, -10.00, 51.81, 48.19, 3.61 +-10.55, -10.00, 51.81, 48.19, 3.62 +-10.55, -10.00, 51.81, 48.19, 3.62 +-10.55, -10.00, 51.81, 48.19, 3.63 +-10.55, -10.00, 51.82, 48.18, 3.63 +-10.55, -10.00, 51.82, 48.18, 3.64 +-10.55, -10.00, 51.82, 48.18, 3.64 +-10.55, -10.00, 51.82, 48.18, 3.64 +-10.55, -10.00, 51.82, 48.18, 3.65 +-10.55, -10.00, 51.83, 48.17, 3.65 +-10.55, -10.00, 51.83, 48.17, 3.66 +-10.55, -10.00, 51.83, 48.17, 3.66 +-10.55, -10.00, 51.83, 48.17, 3.66 +-10.55, -10.00, 51.83, 48.17, 3.67 +-10.55, -10.00, 51.84, 48.16, 3.67 +-10.55, -10.00, 51.84, 48.16, 3.68 +-10.55, -10.00, 51.84, 48.16, 3.68 +-10.55, -10.00, 51.84, 48.16, 3.68 +-10.55, -10.00, 51.84, 48.16, 3.69 +-10.55, -10.00, 51.85, 48.15, 3.69 +-10.55, -10.00, 51.85, 48.15, 3.70 +-10.48, -10.00, 49.33, 50.67, -1.34 +-10.48, -10.00, 51.80, 48.20, 3.61 +-10.48, -10.00, 51.80, 48.20, 3.61 +-10.48, -10.00, 51.81, 48.19, 3.61 +-10.48, -10.00, 51.81, 48.19, 3.62 +-10.42, -10.00, 49.29, 50.71, -1.42 +-10.42, -10.00, 51.76, 48.24, 3.52 +-10.42, -10.00, 51.76, 48.24, 3.53 +-10.42, -10.00, 51.76, 48.24, 3.53 +-10.42, -10.00, 51.77, 48.23, 3.53 +-10.42, -10.00, 51.77, 48.23, 3.54 +-10.42, -10.00, 51.77, 48.23, 3.54 +-10.42, -10.00, 51.77, 48.23, 3.54 +-10.28, -10.00, 46.73, 53.27, -6.54 +-10.28, -10.00, 51.67, 48.33, 3.35 +-10.28, -10.00, 51.68, 48.32, 3.35 +-10.28, -30.00, 25.00, 75.00, -50.00 +-10.28, -30.00, 36.53, 63.47, -26.95 +-10.28, -30.00, 36.45, 63.55, -27.09 +-10.28, -30.00, 36.38, 63.62, -27.24 +-10.28, -30.00, 36.31, 63.69, -27.39 +-10.22, -30.00, 33.71, 66.29, -32.58 +-10.22, -30.00, 36.11, 63.89, -27.78 +-10.22, -30.00, 36.03, 63.97, -27.93 +-10.22, -30.00, 35.96, 64.04, -28.08 +-10.28, -30.00, 38.41, 61.59, -23.19 +-10.28, -30.00, 35.86, 64.14, -28.28 +-10.28, -30.00, 35.79, 64.21, -28.43 +-10.42, -30.00, 40.76, 59.24, -18.49 +-10.42, -30.00, 35.74, 64.26, -28.52 +-10.48, -30.00, 38.19, 61.81, -23.63 +-10.55, -30.00, 38.16, 61.84, -23.67 +-10.68, -30.00, 40.66, 59.34, -18.68 +-10.68, -30.00, 35.65, 64.35, -28.71 +-10.81, -30.00, 40.62, 59.38, -18.77 +-10.94, -30.00, 40.64, 59.36, -18.71 +-11.01, -30.00, 38.15, 61.85, -23.70 +-11.07, -30.00, 38.13, 61.87, -23.74 +-11.27, -30.00, 43.15, 56.85, -13.70 +-11.34, -30.00, 38.19, 61.81, -23.63 +-11.54, -30.00, 43.21, 56.79, -13.58 +-11.73, -30.00, 43.29, 56.71, -13.42 +-11.87, -30.00, 40.85, 59.15, -18.30 +-12.06, -30.00, 43.40, 56.60, -13.20 +-12.26, -30.00, 43.48, 56.52, -13.03 +-12.39, -30.00, 41.04, 58.96, -17.91 +-12.59, -30.00, 43.60, 56.40, -12.80 +-12.85, -30.00, 46.20, 53.80, -7.59 +-13.05, -30.00, 43.82, 56.18, -12.37 +-13.32, -30.00, 46.42, 53.58, -7.15 +-13.58, -30.00, 46.56, 53.44, -6.88 +-13.71, -30.00, 41.65, 58.35, -16.69 +-13.97, -30.00, 46.74, 53.26, -6.53 +-14.24, -30.00, 46.87, 53.13, -6.25 +-14.50, -30.00, 47.01, 52.99, -5.97 +-14.90, -30.00, 52.20, 47.80, 4.40 +-15.03, -30.00, 42.35, 57.65, -15.29 +-15.42, -30.00, 52.48, 47.52, 4.96 +-15.69, -30.00, 47.68, 52.32, -4.63 +-16.02, -30.00, 50.35, 49.65, 0.70 +-16.28, -30.00, 48.02, 51.98, -3.95 +-16.61, -30.00, 50.69, 49.31, 1.39 +-17.01, -30.00, 53.41, 46.59, 6.82 +-17.27, -30.00, 48.62, 51.38, -2.76 +-17.60, -30.00, 51.29, 48.71, 2.58 +-17.93, -30.00, 51.49, 48.51, 2.99 +-18.19, -30.00, 49.17, 50.83, -1.65 +-18.59, -30.00, 54.37, 45.63, 8.74 +-18.92, -30.00, 52.11, 47.89, 4.21 +-19.25, -30.00, 52.31, 47.69, 4.63 +-19.64, -30.00, 55.04, 44.96, 10.09 +-19.97, -30.00, 52.78, 47.22, 5.56 +-20.30, -30.00, 52.99, 47.01, 5.98 +-20.70, -30.00, 55.72, 44.28, 11.45 +-21.03, -30.00, 53.47, 46.53, 6.93 +-21.36, -30.00, 53.68, 46.32, 7.36 +-21.75, -30.00, 56.42, 43.58, 12.84 +-22.15, -30.00, 56.69, 43.31, 13.37 +-22.54, -30.00, 56.95, 43.05, 13.91 +-22.87, -30.00, 54.70, 45.30, 9.41 +-23.20, -30.00, 54.92, 45.08, 9.85 +-23.60, -30.00, 57.67, 42.33, 15.34 +-23.93, -30.00, 55.42, 44.58, 10.84 +-24.39, -30.00, 60.69, 39.31, 21.38 +-24.72, -30.00, 55.97, 44.03, 11.95 +-25.05, -30.00, 56.20, 43.80, 12.41 +-25.44, -30.00, 58.95, 41.05, 17.91 +-25.77, -30.00, 56.71, 43.29, 13.43 +-26.10, -30.00, 56.95, 43.05, 13.89 +-26.50, -30.00, 59.70, 40.30, 19.40 +-26.83, -30.00, 57.47, 42.53, 14.93 +-27.16, -30.00, 57.70, 42.30, 15.40 +-27.55, -30.00, 60.46, 39.54, 20.92 +-27.88, -30.00, 58.23, 41.77, 16.46 +-28.21, -30.00, 58.47, 41.53, 16.94 +-28.48, -30.00, 56.19, 43.81, 12.38 +-28.87, -30.00, 61.43, 38.57, 22.85 +-29.20, -30.00, 59.20, 40.80, 18.40 +-29.47, -30.00, 56.92, 43.08, 13.84 +-29.79, -30.00, 59.64, 40.36, 19.28 +-30.06, -30.00, 57.37, 42.63, 14.73 +-30.32, -30.00, 57.56, 42.44, 15.13 +-30.59, -30.00, 57.76, 42.24, 15.53 +-30.85, -30.00, 57.97, 42.03, 15.93 +-31.25, -30.00, 63.21, 36.79, 26.42 +-31.51, -30.00, 58.47, 41.53, 16.94 +-31.77, -30.00, 58.67, 41.33, 17.35 +-31.90, -30.00, 53.84, 46.16, 7.67 +-32.17, -30.00, 58.99, 41.01, 17.97 +-32.43, -30.00, 59.19, 40.81, 18.39 +-32.70, -30.00, 59.40, 40.60, 18.80 +-32.89, -30.00, 57.09, 42.91, 14.18 +-33.09, -30.00, 57.25, 42.75, 14.50 +-33.35, -30.00, 59.93, 40.07, 19.86 +-33.49, -30.00, 55.10, 44.90, 10.20 +-33.68, -30.00, 57.73, 42.27, 15.47 +-33.95, -30.00, 60.42, 39.58, 20.84 +-34.01, -30.00, 53.07, 46.93, 6.13 +-34.21, -30.00, 58.17, 41.83, 16.35 +-34.41, -30.00, 58.34, 41.66, 16.68 +-34.54, -30.00, 55.98, 44.02, 11.97 +-34.74, -30.00, 58.62, 41.38, 17.24 +-34.80, -30.00, 53.74, 46.26, 7.49 +-34.94, -30.00, 56.33, 43.67, 12.67 +-35.07, -30.00, 56.45, 43.55, 12.90 +-35.27, -30.00, 59.09, 40.91, 18.18 +-35.33, -30.00, 54.22, 45.78, 8.43 +-35.46, -30.00, 56.81, 43.19, 13.62 +-35.53, -30.00, 54.41, 45.59, 8.81 +-35.60, -30.00, 54.48, 45.52, 8.95 +-35.79, -30.00, 59.59, 40.41, 19.18 +-35.86, -30.00, 54.72, 45.28, 9.44 +-35.86, -30.00, 52.27, 47.73, 4.54 +-35.99, -30.00, 57.33, 42.67, 14.67 +-36.06, -30.00, 54.93, 45.07, 9.87 +-36.12, -30.00, 55.01, 44.99, 10.01 +-36.25, -30.00, 57.60, 42.40, 15.20 +-36.32, -30.00, 55.20, 44.80, 10.40 +-36.32, -30.00, 52.75, 47.25, 5.51 +-36.32, -30.00, 52.78, 47.22, 5.56 +-36.39, -30.00, 55.32, 44.68, 10.65 +-36.52, -30.00, 57.92, 42.08, 15.84 +-36.52, -30.00, 53.00, 47.00, 6.00 +-36.52, -30.00, 53.02, 46.98, 6.05 +-36.52, -30.00, 53.05, 46.95, 6.10 +-36.52, -30.00, 53.07, 46.93, 6.14 +-36.52, -30.00, 53.10, 46.90, 6.19 +-36.58, -30.00, 55.64, 44.36, 11.29 +-36.58, -30.00, 53.20, 46.80, 6.39 +-36.58, -30.00, 53.22, 46.78, 6.44 +-36.58, -30.00, 53.24, 46.76, 6.49 +-36.58, -30.00, 53.27, 46.73, 6.54 +-36.58, -30.00, 53.29, 46.71, 6.59 +-36.58, -30.00, 53.32, 46.68, 6.64 +-36.52, -30.00, 50.82, 49.18, 1.64 +-36.52, -30.00, 53.32, 46.68, 6.64 +-36.52, -30.00, 53.34, 46.66, 6.69 +-36.52, -30.00, 53.37, 46.63, 6.73 +-36.39, -30.00, 48.35, 51.65, -3.30 +-36.32, -30.00, 50.79, 49.21, 1.59 +-36.25, -30.00, 50.77, 49.23, 1.54 +-36.12, -30.00, 48.22, 51.78, -3.56 +-36.12, -30.00, 53.19, 46.81, 6.38 +-36.06, -30.00, 50.69, 49.31, 1.38 +-36.06, -30.00, 53.18, 46.82, 6.37 +-35.99, -30.00, 50.68, 49.32, 1.37 +-35.86, -30.00, 48.14, 51.86, -3.73 +-35.86, -30.00, 53.10, 46.90, 6.20 +-35.79, -30.00, 50.60, 49.40, 1.20 +-35.73, -30.00, 50.57, 49.43, 1.15 +-35.60, -30.00, 48.02, 51.98, -3.95 +-35.53, -30.00, 50.47, 49.53, 0.94 +-35.46, -30.00, 50.44, 49.56, 0.88 +-35.33, -30.00, 47.89, 52.11, -4.22 +-35.27, -30.00, 50.33, 49.67, 0.66 +-35.20, -30.00, 50.30, 49.70, 0.60 +-35.07, -30.00, 47.75, 52.25, -4.50 +-35.07, -30.00, 52.71, 47.29, 5.42 +-34.94, -30.00, 47.69, 52.31, -4.63 +-34.94, -30.00, 52.65, 47.35, 5.30 +-34.80, -30.00, 47.62, 52.38, -4.75 +-34.74, -30.00, 50.06, 49.94, 0.13 +-34.67, -30.00, 50.03, 49.97, 0.07 +-34.67, -30.00, 52.52, 47.48, 5.04 +-34.54, -30.00, 47.50, 52.50, -5.01 +-34.48, -30.00, 49.94, 50.06, -0.13 +-34.48, -30.00, 52.42, 47.58, 4.85 +-34.41, -30.00, 49.92, 50.08, -0.16 +-34.28, -30.00, 47.37, 52.63, -5.27 +-34.21, -30.00, 49.80, 50.20, -0.39 +-34.15, -30.00, 49.77, 50.23, -0.46 +-34.01, -30.00, 47.21, 52.79, -5.57 +-34.01, -30.00, 52.17, 47.83, 4.35 +-33.95, -30.00, 49.67, 50.33, -0.67 +-33.88, -30.00, 49.63, 50.37, -0.74 +-33.75, -30.00, 47.07, 52.93, -5.85 +-33.75, -30.00, 52.03, 47.97, 4.06 +-33.68, -30.00, 49.52, 50.48, -0.95 +-33.68, -30.00, 52.01, 47.99, 4.02 +-33.62, -30.00, 49.50, 50.50, -0.99 +-33.49, -30.00, 46.94, 53.06, -6.11 +-33.49, -30.00, 51.90, 48.10, 3.80 +-33.42, -30.00, 49.39, 50.61, -1.21 +-33.42, -30.00, 51.88, 48.12, 3.76 +-33.35, -30.00, 49.37, 50.63, -1.26 +-33.35, -30.00, 51.85, 48.15, 3.71 +-33.22, -30.00, 46.82, 53.18, -6.35 +-33.22, -30.00, 51.78, 48.22, 3.56 +-33.16, -30.00, 49.27, 50.73, -1.46 +-33.16, -30.00, 51.75, 48.25, 3.51 +-33.09, -30.00, 49.24, 50.76, -1.51 +-33.09, -30.00, 51.73, 48.27, 3.45 +-33.09, -30.00, 51.74, 48.26, 3.48 +-32.96, -30.00, 46.71, 53.29, -6.59 +-32.96, -30.00, 51.66, 48.34, 3.32 +-32.96, -30.00, 51.67, 48.33, 3.35 +-32.89, -30.00, 49.16, 50.84, -1.67 +-32.89, -30.00, 51.65, 48.35, 3.29 +-32.89, -30.00, 51.66, 48.34, 3.31 +-32.89, -30.00, 51.67, 48.33, 3.33 +-32.89, -30.00, 51.68, 48.32, 3.36 +-32.89, -30.00, 51.69, 48.31, 3.38 +-32.83, -30.00, 49.18, 50.82, -1.64 +-32.83, -30.00, 51.66, 48.34, 3.32 +-32.83, -30.00, 51.67, 48.33, 3.34 +-32.83, -30.00, 51.68, 48.32, 3.36 +-32.70, -30.00, 46.65, 53.35, -6.70 +-32.70, -30.00, 51.60, 48.40, 3.21 +-32.70, -30.00, 51.61, 48.39, 3.23 +-32.70, -30.00, 51.62, 48.38, 3.25 +-32.70, -30.00, 51.63, 48.37, 3.27 +-32.70, -30.00, 51.64, 48.36, 3.29 +-32.70, -30.00, 51.65, 48.35, 3.31 +-32.70, -30.00, 51.66, 48.34, 3.33 +-32.70, -30.00, 51.67, 48.33, 3.35 +-32.70, -30.00, 51.68, 48.32, 3.37 +-32.70, -30.00, 51.69, 48.31, 3.39 +-32.70, -30.00, 51.70, 48.30, 3.41 +-32.70, -30.00, 51.71, 48.29, 3.43 +-32.70, -30.00, 51.72, 48.28, 3.45 +-32.70, -30.00, 51.73, 48.27, 3.47 +-32.70, -30.00, 51.74, 48.26, 3.49 +-32.70, -30.00, 51.75, 48.25, 3.51 +-32.70, -30.00, 51.76, 48.24, 3.53 +-32.70, -30.00, 51.77, 48.23, 3.55 +-32.83, -30.00, 56.83, 43.17, 13.66 +-32.83, -30.00, 51.89, 48.11, 3.79 +-32.83, -30.00, 51.91, 48.09, 3.81 +-32.83, -30.00, 51.92, 48.08, 3.83 +-32.83, -30.00, 51.93, 48.07, 3.85 +-32.89, -30.00, 54.46, 45.54, 8.92 +-32.89, -30.00, 52.00, 48.00, 4.00 +-32.89, -30.00, 52.01, 47.99, 4.02 +-32.89, -30.00, 52.02, 47.98, 4.04 +-32.89, -30.00, 52.03, 47.97, 4.06 +-32.89, -30.00, 52.04, 47.96, 4.08 +-32.89, -30.00, 52.05, 47.95, 4.10 +-32.89, -30.00, 52.06, 47.94, 4.13 +-32.89, -30.00, 52.07, 47.93, 4.15 +-32.89, -30.00, 52.08, 47.92, 4.17 +-32.89, -30.00, 52.10, 47.90, 4.19 +-32.96, -30.00, 54.63, 45.37, 9.26 +-32.89, -30.00, 49.65, 50.35, -0.71 +-32.96, -30.00, 54.65, 45.35, 9.30 +-32.96, -30.00, 52.19, 47.81, 4.38 +-32.96, -30.00, 52.20, 47.80, 4.40 +-32.96, -30.00, 52.21, 47.79, 4.42 +-32.96, -30.00, 52.22, 47.78, 4.44 +-32.96, -30.00, 52.23, 47.77, 4.47 +-32.96, -30.00, 52.24, 47.76, 4.49 +-33.09, -30.00, 57.30, 42.70, 14.60 +-33.09, -30.00, 52.37, 47.63, 4.73 +-33.09, -30.00, 52.38, 47.62, 4.76 +-33.09, -30.00, 52.39, 47.61, 4.78 +-33.09, -30.00, 52.40, 47.60, 4.80 +-33.09, -30.00, 52.41, 47.59, 4.83 +-33.09, -30.00, 52.42, 47.58, 4.85 +-32.96, -30.00, 47.39, 52.61, -5.21 +-32.96, -30.00, 52.35, 47.65, 4.70 +-32.96, -30.00, 52.36, 47.64, 4.72 +-32.96, -30.00, 52.37, 47.63, 4.74 +-33.09, -30.00, 57.42, 42.58, 14.85 +-33.09, -30.00, 52.49, 47.51, 4.98 +-33.09, -30.00, 52.50, 47.50, 5.01 +-33.09, -30.00, 52.52, 47.48, 5.03 +-33.09, -30.00, 52.53, 47.47, 5.05 +-33.09, -30.00, 52.54, 47.46, 5.08 +-33.09, -30.00, 52.55, 47.45, 5.10 +-33.09, -30.00, 52.56, 47.44, 5.12 +-33.09, -30.00, 52.57, 47.43, 5.15 +-32.96, -30.00, 47.54, 52.46, -4.92 +-33.09, -30.00, 57.54, 42.46, 15.08 +-32.96, -30.00, 47.56, 52.44, -4.87 +-32.96, -30.00, 52.52, 47.48, 5.04 +-32.96, -30.00, 52.53, 47.47, 5.06 +-32.96, -30.00, 52.54, 47.46, 5.08 +-32.96, -30.00, 52.55, 47.45, 5.11 +-32.96, -30.00, 52.56, 47.44, 5.13 +-32.96, -30.00, 52.57, 47.43, 5.15 +-32.89, -30.00, 50.06, 49.94, 0.13 +-32.89, -30.00, 52.55, 47.45, 5.09 +-32.89, -30.00, 52.56, 47.44, 5.12 +-32.89, -30.00, 52.57, 47.43, 5.14 +-32.89, -30.00, 52.58, 47.42, 5.16 +-32.89, -30.00, 52.59, 47.41, 5.18 +-32.89, -30.00, 52.60, 47.40, 5.20 +-32.83, -30.00, 50.09, 49.91, 0.18 +-32.83, -30.00, 52.57, 47.43, 5.15 +-32.83, -30.00, 52.58, 47.42, 5.17 +-32.83, -30.00, 52.59, 47.41, 5.19 +-32.83, -30.00, 52.60, 47.40, 5.21 +-32.70, -30.00, 47.57, 52.43, -4.86 +-32.70, -30.00, 52.53, 47.47, 5.05 +-32.70, -30.00, 52.54, 47.46, 5.07 +-32.70, -30.00, 52.55, 47.45, 5.09 +-32.70, -30.00, 52.56, 47.44, 5.11 +-32.63, -30.00, 50.05, 49.95, 0.09 +-32.63, -30.00, 52.53, 47.47, 5.05 +-32.63, -30.00, 52.54, 47.46, 5.07 +-32.56, -30.00, 50.02, 49.98, 0.05 +-32.56, -30.00, 52.51, 47.49, 5.01 +-32.56, -30.00, 52.52, 47.48, 5.03 +-32.43, -30.00, 47.48, 52.52, -5.04 +-32.43, -30.00, 52.44, 47.56, 4.87 +-32.43, -30.00, 52.44, 47.56, 4.89 +-32.43, -30.00, 52.45, 47.55, 4.91 +-32.43, -30.00, 52.46, 47.54, 4.93 +-32.43, -30.00, 52.47, 47.53, 4.94 +-32.43, -30.00, 52.48, 47.52, 4.96 +-32.37, -30.00, 49.97, 50.03, -0.06 +-32.37, -30.00, 52.45, 47.55, 4.90 +-32.37, -30.00, 52.46, 47.54, 4.92 +-32.37, -30.00, 52.47, 47.53, 4.93 +-32.30, -30.00, 49.95, 50.05, -0.09 +-32.30, -30.00, 52.43, 47.57, 4.87 +-32.30, -30.00, 52.44, 47.56, 4.89 +-32.30, -30.00, 52.45, 47.55, 4.90 +-32.17, -30.00, 47.42, 52.58, -5.16 +-32.17, -30.00, 52.37, 47.63, 4.74 +-32.17, -30.00, 52.38, 47.62, 4.76 +-32.17, -30.00, 52.39, 47.61, 4.77 +-32.17, -30.00, 52.39, 47.61, 4.79 +-32.17, -30.00, 52.40, 47.60, 4.80 +-32.17, -30.00, 52.41, 47.59, 4.82 +-32.17, -30.00, 52.42, 47.58, 4.84 +-32.17, -30.00, 52.43, 47.57, 4.85 +-32.17, -30.00, 52.43, 47.57, 4.87 +-32.10, -30.00, 49.92, 50.08, -0.16 +-32.10, -30.00, 52.40, 47.60, 4.80 +-32.10, -30.00, 52.41, 47.59, 4.82 +-32.04, -30.00, 49.90, 50.10, -0.21 +-32.04, -30.00, 52.37, 47.63, 4.75 +-32.04, -30.00, 52.38, 47.62, 4.76 +-31.90, -30.00, 47.35, 52.65, -5.31 +-31.90, -30.00, 52.30, 47.70, 4.60 +-31.90, -30.00, 52.30, 47.70, 4.61 +-31.90, -30.00, 52.31, 47.69, 4.62 +-31.90, -30.00, 52.32, 47.68, 4.64 +-31.90, -30.00, 52.33, 47.67, 4.65 +-31.90, -30.00, 52.33, 47.67, 4.67 +-31.90, -30.00, 52.34, 47.66, 4.68 +-31.90, -30.00, 52.35, 47.65, 4.70 +-31.90, -30.00, 52.35, 47.65, 4.71 +-31.84, -30.00, 49.84, 50.16, -0.32 +-31.84, -30.00, 52.32, 47.68, 4.64 +-31.84, -30.00, 52.33, 47.67, 4.65 +-31.84, -30.00, 52.33, 47.67, 4.67 +-31.77, -30.00, 49.82, 50.18, -0.36 +-31.77, -30.00, 52.30, 47.70, 4.59 +-31.77, -30.00, 52.30, 47.70, 4.61 +-31.77, -30.00, 52.31, 47.69, 4.62 +-31.77, -30.00, 52.32, 47.68, 4.63 +-31.77, -30.00, 52.32, 47.68, 4.65 +-31.64, -30.00, 47.29, 52.71, -5.43 +-31.64, -30.00, 52.24, 47.76, 4.47 +-31.64, -30.00, 52.24, 47.76, 4.49 +-31.64, -30.00, 52.25, 47.75, 4.50 +-31.64, -30.00, 52.26, 47.74, 4.51 +-31.64, -30.00, 52.26, 47.74, 4.52 +-31.64, -30.00, 52.27, 47.73, 4.54 +-31.57, -30.00, 49.75, 50.25, -0.50 +-31.57, -30.00, 52.23, 47.77, 4.46 +-31.57, -30.00, 52.24, 47.76, 4.47 +-31.57, -30.00, 52.24, 47.76, 4.48 +-31.51, -30.00, 49.73, 50.27, -0.55 +-31.51, -30.00, 52.20, 47.80, 4.41 +-31.51, -30.00, 52.21, 47.79, 4.42 +-31.51, -30.00, 52.21, 47.79, 4.43 +-31.51, -30.00, 52.22, 47.78, 4.44 +-31.51, -30.00, 52.23, 47.77, 4.45 +-31.51, -30.00, 52.23, 47.77, 4.46 +-31.51, -30.00, 52.24, 47.76, 4.48 +-31.51, -30.00, 52.24, 47.76, 4.49 +-31.51, -30.00, 52.25, 47.75, 4.50 +-31.51, -30.00, 52.25, 47.75, 4.51 +-31.51, -30.00, 52.26, 47.74, 4.52 +-31.38, -30.00, 47.22, 52.78, -5.55 +-31.38, -30.00, 52.17, 47.83, 4.34 +-31.38, -30.00, 52.18, 47.82, 4.35 +-31.38, -30.00, 52.18, 47.82, 4.36 +-31.38, -30.00, 52.19, 47.81, 4.37 +-31.31, -30.00, 49.67, 50.33, -0.66 +-31.31, -30.00, 52.15, 47.85, 4.30 +-31.31, -30.00, 52.15, 47.85, 4.30 +-31.31, -30.00, 52.16, 47.84, 4.31 +-31.31, -30.00, 52.16, 47.84, 4.32 +-31.38, -30.00, 54.69, 45.31, 9.38 +-31.31, -30.00, 49.70, 50.30, -0.60 +-31.31, -30.00, 52.18, 47.82, 4.35 +-31.31, -30.00, 52.18, 47.82, 4.36 +-31.31, -30.00, 52.19, 47.81, 4.37 +-31.31, -30.00, 52.19, 47.81, 4.38 +-31.31, -30.00, 52.20, 47.80, 4.39 +-31.31, -30.00, 52.20, 47.80, 4.40 +-31.25, -30.00, 49.69, 50.31, -0.63 +-31.25, -30.00, 52.16, 47.84, 4.32 +-31.25, -30.00, 52.17, 47.83, 4.33 +-31.11, -30.00, 47.13, 52.87, -5.74 +-31.11, -30.00, 52.08, 47.92, 4.15 +-31.11, -30.00, 52.08, 47.92, 4.16 +-31.11, -30.00, 52.08, 47.92, 4.17 +-31.11, -30.00, 52.09, 47.91, 4.18 +-31.11, -30.00, 52.09, 47.91, 4.19 +-31.11, -30.00, 52.10, 47.90, 4.19 +-31.11, -30.00, 52.10, 47.90, 4.20 +-31.11, -30.00, 52.11, 47.89, 4.21 +-31.11, -30.00, 52.11, 47.89, 4.22 +-31.11, -30.00, 52.11, 47.89, 4.23 +-31.05, -30.00, 49.60, 50.40, -0.81 +-31.05, -30.00, 52.07, 47.93, 4.14 +-31.05, -30.00, 52.08, 47.92, 4.15 +-30.98, -30.00, 49.56, 50.44, -0.88 +-30.98, -30.00, 52.03, 47.97, 4.07 +-30.98, -30.00, 52.04, 47.96, 4.07 +-30.98, -30.00, 52.04, 47.96, 4.08 +-30.98, -30.00, 52.04, 47.96, 4.09 +-30.98, -30.00, 52.05, 47.95, 4.10 +-30.85, -30.00, 47.01, 52.99, -5.98 +-30.98, -30.00, 57.00, 43.00, 14.00 +-30.98, -30.00, 52.06, 47.94, 4.12 +-30.98, -30.00, 52.06, 47.94, 4.13 +-30.98, -30.00, 52.07, 47.93, 4.13 +-30.98, -30.00, 52.07, 47.93, 4.14 +-30.98, -30.00, 52.07, 47.93, 4.15 +-30.85, -30.00, 47.03, 52.97, -5.93 +-30.85, -30.00, 51.98, 48.02, 3.96 +-30.85, -30.00, 51.98, 48.02, 3.97 +-30.85, -30.00, 51.99, 48.01, 3.98 +-30.78, -30.00, 49.47, 50.53, -1.06 +-30.78, -30.00, 51.94, 48.06, 3.89 +-30.78, -30.00, 51.95, 48.05, 3.89 +-30.78, -30.00, 51.95, 48.05, 3.90 +-30.78, -30.00, 51.95, 48.05, 3.91 +-30.78, -30.00, 51.96, 48.04, 3.91 +-30.85, -30.00, 54.48, 45.52, 8.96 +-30.85, -30.00, 52.01, 47.99, 4.02 +-30.85, -30.00, 52.01, 47.99, 4.03 +-30.85, -30.00, 52.02, 47.98, 4.04 +-30.85, -30.00, 52.02, 47.98, 4.04 +-30.85, -30.00, 52.02, 47.98, 4.05 +-30.85, -30.00, 52.03, 47.97, 4.06 +-30.85, -30.00, 52.03, 47.97, 4.06 +-30.85, -30.00, 52.03, 47.97, 4.07 +-30.85, -30.00, 52.04, 47.96, 4.07 +-30.85, -30.00, 52.04, 47.96, 4.08 +-30.85, -30.00, 52.04, 47.96, 4.09 +-30.85, -30.00, 52.05, 47.95, 4.09 +-30.85, -30.00, 52.05, 47.95, 4.10 +-30.85, -30.00, 52.05, 47.95, 4.11 +-30.85, -30.00, 52.06, 47.94, 4.11 +-30.98, -30.00, 57.10, 42.90, 14.21 +-30.98, -30.00, 52.16, 47.84, 4.32 +-30.98, -30.00, 52.17, 47.83, 4.33 +-30.98, -30.00, 52.17, 47.83, 4.34 +-30.98, -30.00, 52.17, 47.83, 4.35 +-30.98, -30.00, 52.18, 47.82, 4.35 +-30.98, -30.00, 52.18, 47.82, 4.36 +-31.05, -30.00, 54.71, 45.29, 9.41 +-30.98, -30.00, 49.72, 50.28, -0.57 +-31.05, -30.00, 54.71, 45.29, 9.43 +-30.98, -30.00, 49.72, 50.28, -0.55 +-30.98, -30.00, 52.20, 47.80, 4.40 +-30.98, -30.00, 52.20, 47.80, 4.41 +-30.98, -30.00, 52.21, 47.79, 4.41 +-30.98, -30.00, 52.21, 47.79, 4.42 +-31.05, -30.00, 54.74, 45.26, 9.47 +-31.05, -30.00, 52.27, 47.73, 4.54 +-31.05, -30.00, 52.27, 47.73, 4.54 +-31.05, -30.00, 52.28, 47.72, 4.55 +-31.11, -30.00, 54.80, 45.20, 9.60 +-31.11, -30.00, 52.33, 47.67, 4.67 +-31.11, -30.00, 52.34, 47.66, 4.68 +-31.11, -30.00, 52.34, 47.66, 4.68 +-31.11, -30.00, 52.35, 47.65, 4.69 +-31.11, -30.00, 52.35, 47.65, 4.70 +-31.11, -30.00, 52.35, 47.65, 4.71 +-31.11, -30.00, 52.36, 47.64, 4.72 +-31.11, -30.00, 52.36, 47.64, 4.73 +-31.11, -30.00, 52.37, 47.63, 4.73 +-31.11, -30.00, 52.37, 47.63, 4.74 +-31.11, -30.00, 52.38, 47.62, 4.75 +-31.11, -30.00, 52.38, 47.62, 4.76 +-31.11, -30.00, 52.38, 47.62, 4.77 +-31.11, -30.00, 52.39, 47.61, 4.78 +-31.25, -30.00, 57.44, 42.56, 14.87 +-31.25, -30.00, 52.50, 47.50, 4.99 +-31.25, -30.00, 52.50, 47.50, 5.00 +-31.25, -30.00, 52.51, 47.49, 5.01 +-31.25, -30.00, 52.51, 47.49, 5.02 +-31.25, -30.00, 52.51, 47.49, 5.03 +-31.25, -30.00, 52.52, 47.48, 5.04 +-31.25, -30.00, 52.52, 47.48, 5.05 +-31.11, -30.00, 47.49, 52.51, -5.03 +-31.11, -30.00, 52.43, 47.57, 4.87 +-31.11, -30.00, 52.44, 47.56, 4.88 +-31.11, -30.00, 52.44, 47.56, 4.88 +-31.11, -30.00, 52.45, 47.55, 4.89 +-31.11, -30.00, 52.45, 47.55, 4.90 +-31.11, -30.00, 52.45, 47.55, 4.91 +-31.11, -30.00, 52.46, 47.54, 4.92 +-31.11, -30.00, 52.46, 47.54, 4.93 +-31.11, -30.00, 52.47, 47.53, 4.93 +-31.11, -30.00, 52.47, 47.53, 4.94 +-31.11, -30.00, 52.48, 47.52, 4.95 +-31.11, -30.00, 52.48, 47.52, 4.96 +-31.11, -30.00, 52.48, 47.52, 4.97 +-31.11, -30.00, 52.49, 47.51, 4.98 +-31.11, -30.00, 52.49, 47.51, 4.98 +-31.11, -30.00, 52.50, 47.50, 4.99 +-31.11, -30.00, 52.50, 47.50, 5.00 +-31.11, -30.00, 52.50, 47.50, 5.01 +-31.11, -30.00, 52.51, 47.49, 5.02 +-31.05, -30.00, 49.99, 50.01, -0.02 +-31.05, -30.00, 52.47, 47.53, 4.93 +-31.05, -30.00, 52.47, 47.53, 4.94 +-31.05, -30.00, 52.48, 47.52, 4.95 +-31.05, -30.00, 52.48, 47.52, 4.96 +-31.05, -30.00, 52.48, 47.52, 4.97 +-31.05, -30.00, 52.49, 47.51, 4.97 +-31.05, -30.00, 52.49, 47.51, 4.98 +-31.05, -30.00, 52.49, 47.51, 4.99 +-31.11, -30.00, 55.02, 44.98, 10.04 +-31.11, -30.00, 52.55, 47.45, 5.11 +-31.05, -30.00, 50.04, 49.96, 0.07 +-31.05, -30.00, 52.51, 47.49, 5.02 +-31.11, -30.00, 55.04, 44.96, 10.07 +-31.05, -30.00, 50.05, 49.95, 0.09 +-31.05, -30.00, 52.52, 47.48, 5.05 +-31.05, -30.00, 52.53, 47.47, 5.05 +-31.05, -30.00, 52.53, 47.47, 5.06 +-31.05, -30.00, 52.53, 47.47, 5.07 +-31.05, -30.00, 52.54, 47.46, 5.08 +-31.05, -30.00, 52.54, 47.46, 5.09 +-31.05, -30.00, 52.55, 47.45, 5.09 +-31.05, -30.00, 52.55, 47.45, 5.10 +-31.05, -30.00, 52.55, 47.45, 5.11 +-31.05, -30.00, 52.56, 47.44, 5.12 +-31.05, -30.00, 52.56, 47.44, 5.12 +-31.05, -30.00, 52.57, 47.43, 5.13 +-31.05, -30.00, 52.57, 47.43, 5.14 +-31.05, -30.00, 52.57, 47.43, 5.15 +-31.05, -30.00, 52.58, 47.42, 5.16 +-31.05, -30.00, 52.58, 47.42, 5.16 +-31.05, -30.00, 52.59, 47.41, 5.17 +-31.05, -30.00, 52.59, 47.41, 5.18 +-31.05, -30.00, 52.59, 47.41, 5.19 +-31.05, -30.00, 52.60, 47.40, 5.20 +-31.05, -30.00, 52.60, 47.40, 5.20 +-31.05, -30.00, 52.61, 47.39, 5.21 +-31.05, -30.00, 52.61, 47.39, 5.22 +-31.05, -30.00, 52.61, 47.39, 5.23 +-31.05, -30.00, 52.62, 47.38, 5.23 +-31.05, -30.00, 52.62, 47.38, 5.24 +-31.05, -30.00, 52.63, 47.37, 5.25 +-31.05, -30.00, 52.63, 47.37, 5.26 +-31.05, -30.00, 52.63, 47.37, 5.27 +-31.05, -30.00, 52.64, 47.36, 5.27 +-31.05, -30.00, 52.64, 47.36, 5.28 +-31.05, -30.00, 52.64, 47.36, 5.29 +-31.05, -30.00, 52.65, 47.35, 5.30 +-31.05, -30.00, 52.65, 47.35, 5.31 +-30.98, -30.00, 50.13, 49.87, 0.27 +-30.98, -30.00, 52.61, 47.39, 5.22 +-31.05, -30.00, 55.14, 44.86, 10.27 +-31.05, -30.00, 52.67, 47.33, 5.34 +-31.05, -30.00, 52.67, 47.33, 5.34 +-31.05, -30.00, 52.68, 47.32, 5.35 +-31.05, -30.00, 52.68, 47.32, 5.36 +-31.05, -30.00, 52.68, 47.32, 5.37 +-31.05, -30.00, 52.69, 47.31, 5.37 +-31.05, -30.00, 52.69, 47.31, 5.38 +-31.05, -30.00, 52.70, 47.30, 5.39 +-31.05, -30.00, 52.70, 47.30, 5.40 +-31.05, -30.00, 52.70, 47.30, 5.41 +-31.05, -30.00, 52.71, 47.29, 5.41 +-30.98, -30.00, 50.19, 49.81, 0.38 +-30.98, -30.00, 52.67, 47.33, 5.33 +-30.98, -30.00, 52.67, 47.33, 5.34 +-30.98, -30.00, 52.67, 47.33, 5.34 +-30.98, -30.00, 52.68, 47.32, 5.35 +-30.98, -30.00, 52.68, 47.32, 5.36 +-30.98, -30.00, 52.68, 47.32, 5.37 +-30.98, -30.00, 52.69, 47.31, 5.37 +-30.98, -30.00, 52.69, 47.31, 5.38 +-30.98, -30.00, 52.69, 47.31, 5.39 +-30.98, -30.00, 52.70, 47.30, 5.40 +-30.98, -30.00, 52.70, 47.30, 5.40 +-30.98, -30.00, 52.71, 47.29, 5.41 +-30.98, -30.00, 52.71, 47.29, 5.42 +-30.98, -30.00, 52.71, 47.29, 5.43 +-30.98, -30.00, 52.72, 47.28, 5.43 +-30.98, -30.00, 52.72, 47.28, 5.44 +-30.98, -30.00, 52.72, 47.28, 5.45 +-30.98, -30.00, 52.73, 47.27, 5.46 +-30.98, -30.00, 52.73, 47.27, 5.46 +-30.98, -30.00, 52.73, 47.27, 5.47 +-30.98, -30.00, 52.74, 47.26, 5.48 +-30.85, -30.00, 47.70, 52.30, -4.60 +-30.98, -30.00, 57.69, 42.31, 15.38 +-30.85, -30.00, 47.71, 52.29, -4.59 +-30.98, -30.00, 57.70, 42.30, 15.39 +-30.98, -30.00, 52.76, 47.24, 5.51 +-30.98, -30.00, 52.76, 47.24, 5.52 +-30.85, -30.00, 47.72, 52.28, -4.56 +-30.85, -30.00, 52.67, 47.33, 5.33 +-30.85, -30.00, 52.67, 47.33, 5.34 +-30.85, -30.00, 52.67, 47.33, 5.35 +-30.85, -30.00, 52.68, 47.32, 5.35 +-30.78, -30.00, 50.16, 49.84, 0.32 +-30.78, -30.00, 52.63, 47.37, 5.27 +-30.78, -30.00, 52.64, 47.36, 5.27 +-30.78, -30.00, 52.64, 47.36, 5.28 +-30.78, -30.00, 52.64, 47.36, 5.28 +-30.78, -30.00, 52.64, 47.36, 5.29 +-30.78, -30.00, 52.65, 47.35, 5.30 +-30.78, -30.00, 52.65, 47.35, 5.30 +-30.78, -30.00, 52.65, 47.35, 5.31 +-30.78, -30.00, 52.66, 47.34, 5.31 +-30.72, -30.00, 50.14, 49.86, 0.28 +-30.72, -30.00, 52.61, 47.39, 5.23 +-30.72, -30.00, 52.62, 47.38, 5.23 +-30.72, -30.00, 52.62, 47.38, 5.24 +-30.72, -30.00, 52.62, 47.38, 5.24 +-30.72, -30.00, 52.62, 47.38, 5.25 +-30.72, -30.00, 52.63, 47.37, 5.25 +-30.59, -30.00, 47.59, 52.41, -4.83 +-30.59, -30.00, 52.53, 47.47, 5.06 +-30.59, -30.00, 52.53, 47.47, 5.07 +-30.59, -30.00, 52.54, 47.46, 5.07 +-30.59, -30.00, 52.54, 47.46, 5.08 +-30.59, -30.00, 52.54, 47.46, 5.08 +-30.59, -30.00, 52.54, 47.46, 5.09 +-30.59, -30.00, 52.54, 47.46, 5.09 +-30.59, -30.00, 52.55, 47.45, 5.09 +-30.59, -30.00, 52.55, 47.45, 5.10 +-30.59, -30.00, 52.55, 47.45, 5.10 +-30.59, -30.00, 52.55, 47.45, 5.11 +-30.59, -30.00, 52.56, 47.44, 5.11 +-30.59, -30.00, 52.56, 47.44, 5.12 +-30.59, -30.00, 52.56, 47.44, 5.12 +-30.59, -30.00, 52.56, 47.44, 5.12 +-30.59, -30.00, 52.56, 47.44, 5.13 +-30.52, -30.00, 50.05, 49.95, 0.09 +-30.52, -30.00, 52.52, 47.48, 5.04 +-30.59, -30.00, 55.04, 44.96, 10.09 +-30.52, -30.00, 50.05, 49.95, 0.10 +-30.52, -30.00, 52.53, 47.47, 5.05 +-30.59, -30.00, 55.05, 44.95, 10.10 +-30.59, -30.00, 52.58, 47.42, 5.16 +-30.52, -30.00, 50.06, 49.94, 0.12 +-30.52, -30.00, 52.53, 47.47, 5.07 +-30.52, -30.00, 52.54, 47.46, 5.07 +-30.52, -30.00, 52.54, 47.46, 5.07 +-30.52, -30.00, 52.54, 47.46, 5.08 +-30.52, -30.00, 52.54, 47.46, 5.08 +-30.52, -30.00, 52.54, 47.46, 5.09 +-30.45, -30.00, 50.02, 49.98, 0.05 +-30.45, -30.00, 52.50, 47.50, 4.99 +-30.45, -30.00, 52.50, 47.50, 5.00 +-30.45, -30.00, 52.50, 47.50, 5.00 +-30.45, -30.00, 52.50, 47.50, 5.00 +-30.45, -30.00, 52.50, 47.50, 5.01 +-30.45, -30.00, 52.51, 47.49, 5.01 +-30.45, -30.00, 52.51, 47.49, 5.01 +-30.45, -30.00, 52.51, 47.49, 5.02 +-30.45, -30.00, 52.51, 47.49, 5.02 +-30.45, -30.00, 52.51, 47.49, 5.03 +-30.45, -30.00, 52.51, 47.49, 5.03 +-30.32, -30.00, 47.47, 52.53, -5.05 +-30.32, -30.00, 52.42, 47.58, 4.84 +-30.32, -30.00, 52.42, 47.58, 4.84 +-30.32, -30.00, 52.42, 47.58, 4.84 +-30.32, -30.00, 52.42, 47.58, 4.84 +-30.32, -30.00, 52.42, 47.58, 4.85 +-30.32, -30.00, 52.42, 47.58, 4.85 +-30.26, -30.00, 49.90, 50.10, -0.19 +-30.26, -30.00, 52.38, 47.62, 4.75 +-30.26, -30.00, 52.38, 47.62, 4.75 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.76 +-30.26, -30.00, 52.38, 47.62, 4.77 +-30.26, -30.00, 52.38, 47.62, 4.77 +-30.19, -30.00, 49.86, 50.14, -0.27 +-30.19, -30.00, 52.34, 47.66, 4.67 +-30.19, -30.00, 52.34, 47.66, 4.67 +-30.19, -30.00, 52.34, 47.66, 4.67 +-30.19, -30.00, 52.34, 47.66, 4.68 +-30.06, -30.00, 47.30, 52.70, -5.41 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-30.06, -30.00, 52.24, 47.76, 4.48 +-29.99, -30.00, 49.72, 50.28, -0.56 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.99, -30.00, 52.19, 47.81, 4.38 +-29.93, -30.00, 49.67, 50.33, -0.66 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.93, -30.00, 52.14, 47.86, 4.28 +-29.79, -30.00, 47.10, 52.90, -5.81 +-29.79, -30.00, 52.04, 47.96, 4.08 +-29.79, -30.00, 52.04, 47.96, 4.07 +-29.79, -30.00, 52.04, 47.96, 4.07 +-29.79, -30.00, 52.04, 47.96, 4.07 +-29.79, -30.00, 52.04, 47.96, 4.07 +-29.79, -30.00, 52.03, 47.97, 4.07 +-29.79, -30.00, 52.03, 47.97, 4.07 +-29.79, -30.00, 52.03, 47.97, 4.07 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.06 +-29.79, -30.00, 52.03, 47.97, 4.05 +-29.79, -30.00, 52.03, 47.97, 4.05 +-29.73, -30.00, 49.50, 50.50, -0.99 +-29.73, -30.00, 51.98, 48.02, 3.95 +-29.73, -30.00, 51.97, 48.03, 3.95 +-29.73, -30.00, 51.97, 48.03, 3.95 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 51.97, 48.03, 3.93 +-29.73, -30.00, 51.97, 48.03, 3.93 +-29.73, -30.00, 51.97, 48.03, 3.93 +-29.73, -30.00, 51.96, 48.04, 3.93 +-29.73, -30.00, 51.96, 48.04, 3.93 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.92 +-29.73, -30.00, 51.96, 48.04, 3.91 +-29.73, -30.00, 51.96, 48.04, 3.91 +-29.66, -30.00, 49.43, 50.57, -1.13 +-29.73, -30.00, 54.43, 45.57, 8.85 +-29.66, -30.00, 49.43, 50.57, -1.14 +-29.66, -30.00, 51.90, 48.10, 3.80 +-29.66, -30.00, 51.90, 48.10, 3.80 +-29.73, -30.00, 54.42, 45.58, 8.84 +-29.73, -30.00, 51.95, 48.05, 3.90 +-29.73, -30.00, 51.95, 48.05, 3.89 +-29.73, -30.00, 51.95, 48.05, 3.89 +-29.73, -30.00, 51.94, 48.06, 3.89 +-29.73, -30.00, 51.94, 48.06, 3.89 +-29.73, -30.00, 51.94, 48.06, 3.89 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.88 +-29.73, -30.00, 51.94, 48.06, 3.87 +-29.73, -30.00, 51.94, 48.06, 3.87 +-29.73, -30.00, 51.93, 48.07, 3.87 +-29.73, -30.00, 51.93, 48.07, 3.87 +-29.73, -30.00, 51.93, 48.07, 3.87 +-29.73, -30.00, 51.93, 48.07, 3.86 +-29.73, -30.00, 51.93, 48.07, 3.86 +-29.73, -30.00, 51.93, 48.07, 3.86 +-29.73, -30.00, 51.93, 48.07, 3.86 +-29.79, -30.00, 54.45, 45.55, 8.90 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 57.01, 42.99, 14.02 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.07, 47.93, 4.13 +-29.93, -30.00, 52.06, 47.94, 4.13 +-29.93, -30.00, 52.06, 47.94, 4.13 +-29.99, -30.00, 54.59, 45.41, 9.17 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-29.99, -30.00, 52.11, 47.89, 4.23 +-30.06, -30.00, 54.64, 45.36, 9.27 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.06, -30.00, 52.16, 47.84, 4.33 +-30.19, -30.00, 57.21, 42.79, 14.42 +-30.19, -30.00, 52.27, 47.73, 4.53 +-30.06, -30.00, 47.22, 52.78, -5.55 +-30.19, -30.00, 57.21, 42.79, 14.42 +-30.19, -30.00, 52.27, 47.73, 4.53 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.54 +-30.19, -30.00, 52.27, 47.73, 4.55 +-30.19, -30.00, 52.27, 47.73, 4.55 +-30.19, -30.00, 52.27, 47.73, 4.55 +-30.19, -30.00, 52.27, 47.73, 4.55 +-30.19, -30.00, 52.28, 47.72, 4.55 +-30.19, -30.00, 52.28, 47.72, 4.55 +-30.19, -30.00, 52.28, 47.72, 4.55 +-30.06, -30.00, 47.23, 52.77, -5.53 +-30.19, -30.00, 57.22, 42.78, 14.44 +-30.06, -30.00, 47.24, 52.76, -5.53 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.36 +-30.06, -30.00, 52.18, 47.82, 4.37 +-30.06, -30.00, 52.18, 47.82, 4.37 +-30.06, -30.00, 52.18, 47.82, 4.37 +-29.99, -30.00, 49.66, 50.34, -0.68 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-30.06, -30.00, 54.66, 45.34, 9.31 +-29.99, -30.00, 49.66, 50.34, -0.68 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-30.06, -30.00, 54.66, 45.34, 9.31 +-29.99, -30.00, 49.66, 50.34, -0.68 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.99, -30.00, 52.13, 47.87, 4.27 +-29.93, -30.00, 49.61, 50.39, -0.78 +-29.93, -30.00, 52.08, 47.92, 4.17 +-29.99, -30.00, 54.60, 45.40, 9.21 +-29.93, -30.00, 49.61, 50.39, -0.78 +-29.93, -30.00, 52.08, 47.92, 4.17 +-29.93, -30.00, 52.08, 47.92, 4.17 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.93, -30.00, 52.08, 47.92, 4.16 +-29.79, -30.00, 47.04, 52.96, -5.93 +-29.79, -30.00, 51.98, 48.02, 3.96 +-29.79, -30.00, 51.98, 48.02, 3.96 +-29.79, -30.00, 51.98, 48.02, 3.96 +-29.79, -30.00, 51.98, 48.02, 3.96 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.98, 48.02, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.95 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.79, -30.00, 51.97, 48.03, 3.94 +-29.73, -30.00, 49.45, 50.55, -1.10 +-29.73, -30.00, 51.92, 48.08, 3.84 +-29.73, -30.00, 51.92, 48.08, 3.84 +-29.73, -30.00, 51.92, 48.08, 3.83 +-29.73, -30.00, 51.92, 48.08, 3.83 +-29.73, -30.00, 51.91, 48.09, 3.83 +-29.73, -30.00, 51.91, 48.09, 3.83 +-29.73, -30.00, 51.91, 48.09, 3.83 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.82 +-29.73, -30.00, 51.91, 48.09, 3.81 +-29.73, -30.00, 51.91, 48.09, 3.81 +-29.73, -30.00, 51.90, 48.10, 3.81 +-29.73, -30.00, 51.90, 48.10, 3.81 +-29.73, -30.00, 51.90, 48.10, 3.81 +-29.66, -30.00, 49.38, 50.62, -1.24 +-29.66, -30.00, 51.85, 48.15, 3.70 +-29.66, -30.00, 51.85, 48.15, 3.70 +-29.66, -30.00, 51.85, 48.15, 3.70 +-29.66, -30.00, 51.85, 48.15, 3.69 +-29.66, -30.00, 51.85, 48.15, 3.69 +-29.66, -30.00, 51.84, 48.16, 3.69 +-29.66, -30.00, 51.84, 48.16, 3.69 +-29.73, -30.00, 54.36, 45.64, 8.73 +-29.73, -30.00, 51.89, 48.11, 3.78 +-29.73, -30.00, 51.89, 48.11, 3.78 +-29.73, -30.00, 51.89, 48.11, 3.78 +-29.73, -30.00, 51.89, 48.11, 3.77 +-29.73, -30.00, 51.89, 48.11, 3.77 +-29.73, -30.00, 51.89, 48.11, 3.77 +-29.73, -30.00, 51.88, 48.12, 3.77 +-29.73, -30.00, 51.88, 48.12, 3.77 +-29.73, -30.00, 51.88, 48.12, 3.76 +-29.73, -30.00, 51.88, 48.12, 3.76 +-29.66, -30.00, 49.36, 50.64, -1.28 +-29.66, -30.00, 51.83, 48.17, 3.66 +-29.66, -30.00, 51.83, 48.17, 3.66 +-29.73, -30.00, 54.35, 45.65, 8.70 +-29.73, -30.00, 51.88, 48.12, 3.75 +-29.73, -30.00, 51.87, 48.13, 3.75 +-29.73, -30.00, 51.87, 48.13, 3.75 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.73, -30.00, 51.87, 48.13, 3.74 +-29.79, -30.00, 54.39, 45.61, 8.78 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.73, -30.00, 49.39, 50.61, -1.21 +-29.79, -30.00, 54.39, 45.61, 8.77 +-29.73, -30.00, 49.39, 50.61, -1.22 +-29.73, -30.00, 51.86, 48.14, 3.73 +-29.73, -30.00, 51.86, 48.14, 3.72 +-29.73, -30.00, 51.86, 48.14, 3.72 +-29.79, -30.00, 54.38, 45.62, 8.76 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 56.95, 43.05, 13.89 +-29.93, -30.00, 52.00, 48.00, 4.01 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.93, -30.00, 52.00, 48.00, 4.00 +-29.99, -30.00, 54.52, 45.48, 9.04 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-30.06, -30.00, 54.57, 45.43, 9.14 +-29.99, -30.00, 49.58, 50.42, -0.85 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-29.99, -30.00, 52.05, 47.95, 4.10 +-30.06, -30.00, 54.57, 45.43, 9.14 +-29.99, -30.00, 49.58, 50.42, -0.85 +-30.06, -30.00, 54.57, 45.43, 9.14 +-30.06, -30.00, 52.10, 47.90, 4.20 +-30.06, -30.00, 52.10, 47.90, 4.20 +-30.06, -30.00, 52.10, 47.90, 4.20 +-30.06, -30.00, 52.10, 47.90, 4.20 +-30.19, -30.00, 57.14, 42.86, 14.29 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.26, -30.00, 54.73, 45.27, 9.47 +-30.26, -30.00, 52.26, 47.74, 4.53 +-30.19, -30.00, 49.74, 50.26, -0.52 +-30.19, -30.00, 52.21, 47.79, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.43 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.44 +-30.19, -30.00, 52.22, 47.78, 4.45 +-30.06, -30.00, 47.18, 52.82, -5.64 +-30.06, -30.00, 52.12, 47.88, 4.25 +-30.06, -30.00, 52.12, 47.88, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-30.06, -30.00, 52.13, 47.87, 4.25 +-29.99, -30.00, 49.60, 50.40, -0.79 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.99, -30.00, 52.08, 47.92, 4.15 +-29.93, -30.00, 49.55, 50.45, -0.89 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.03, 47.97, 4.05 +-29.93, -30.00, 52.02, 47.98, 4.05 +-29.93, -30.00, 52.02, 47.98, 4.05 +-29.79, -30.00, 46.98, 53.02, -6.04 +-29.79, -30.00, 51.92, 48.08, 3.85 +-29.79, -30.00, 51.92, 48.08, 3.85 +-29.79, -30.00, 51.92, 48.08, 3.85 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.84 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.79, -30.00, 51.92, 48.08, 3.83 +-29.79, -30.00, 51.91, 48.09, 3.83 +-29.79, -30.00, 51.91, 48.09, 3.83 +-29.79, -30.00, 51.91, 48.09, 3.83 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.73, -30.00, 49.38, 50.62, -1.23 +-29.79, -30.00, 54.38, 45.62, 8.75 +-29.79, -30.00, 51.90, 48.10, 3.81 +-29.79, -30.00, 51.90, 48.10, 3.81 +-29.79, -30.00, 51.90, 48.10, 3.81 +-29.79, -30.00, 51.90, 48.10, 3.80 +-29.79, -30.00, 51.90, 48.10, 3.80 +-29.79, -30.00, 51.90, 48.10, 3.80 +-29.73, -30.00, 49.38, 50.62, -1.24 +-29.79, -30.00, 54.37, 45.63, 8.74 +-29.79, -30.00, 51.90, 48.10, 3.80 +-29.73, -30.00, 49.38, 50.62, -1.25 +-29.79, -30.00, 54.37, 45.63, 8.74 +-29.79, -30.00, 51.90, 48.10, 3.79 +-29.79, -30.00, 51.89, 48.11, 3.79 +-29.79, -30.00, 51.89, 48.11, 3.79 +-29.79, -30.00, 51.89, 48.11, 3.79 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.78 +-29.79, -30.00, 51.89, 48.11, 3.77 +-29.79, -30.00, 51.89, 48.11, 3.77 +-29.79, -30.00, 51.89, 48.11, 3.77 +-29.79, -30.00, 51.89, 48.11, 3.77 +-29.79, -30.00, 51.88, 48.12, 3.77 +-29.79, -30.00, 51.88, 48.12, 3.77 +-29.79, -30.00, 51.88, 48.12, 3.77 +-29.79, -30.00, 51.88, 48.12, 3.76 +-29.79, -30.00, 51.88, 48.12, 3.76 +-29.79, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 56.92, 43.08, 13.85 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.96 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.98, 48.02, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.95 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.99, -30.00, 52.02, 47.98, 4.04 +-29.99, -30.00, 52.02, 47.98, 4.04 +-29.93, -30.00, 49.50, 50.50, -1.01 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.93, -30.00, 49.50, 50.50, -1.01 +-29.93, -30.00, 51.97, 48.03, 3.93 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.93, -30.00, 49.49, 50.51, -1.01 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.93, -30.00, 49.49, 50.51, -1.01 +-29.99, -30.00, 54.49, 45.51, 8.98 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 52.01, 47.99, 4.03 +-29.99, -30.00, 52.01, 47.99, 4.03 +-29.99, -30.00, 52.01, 47.99, 4.03 +-29.99, -30.00, 52.01, 47.99, 4.03 +-30.06, -30.00, 54.54, 45.46, 9.07 +-30.06, -30.00, 52.06, 47.94, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.13 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.06, -30.00, 52.07, 47.93, 4.14 +-30.19, -30.00, 57.11, 42.89, 14.22 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.19, -30.00, 52.17, 47.83, 4.34 +-30.06, -30.00, 47.13, 52.87, -5.74 +-30.06, -30.00, 52.07, 47.93, 4.15 +-30.19, -30.00, 57.12, 42.88, 14.23 +-30.06, -30.00, 47.13, 52.87, -5.74 +-30.19, -30.00, 57.12, 42.88, 14.24 +-30.19, -30.00, 52.17, 47.83, 4.35 +-30.19, -30.00, 52.18, 47.82, 4.35 +-30.19, -30.00, 52.18, 47.82, 4.35 +-30.19, -30.00, 52.18, 47.82, 4.35 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.36 +-30.19, -30.00, 52.18, 47.82, 4.37 +-30.19, -30.00, 52.18, 47.82, 4.37 +-30.19, -30.00, 52.18, 47.82, 4.37 +-30.19, -30.00, 52.18, 47.82, 4.37 +-30.19, -30.00, 52.19, 47.81, 4.37 +-30.19, -30.00, 52.19, 47.81, 4.37 +-30.19, -30.00, 52.19, 47.81, 4.37 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.38 +-30.19, -30.00, 52.19, 47.81, 4.39 +-30.19, -30.00, 52.19, 47.81, 4.39 +-30.19, -30.00, 52.19, 47.81, 4.39 +-30.19, -30.00, 52.19, 47.81, 4.39 +-30.19, -30.00, 52.20, 47.80, 4.39 +-30.19, -30.00, 52.20, 47.80, 4.39 +-30.19, -30.00, 52.20, 47.80, 4.39 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.40 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.20, 47.80, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.41 +-30.19, -30.00, 52.21, 47.79, 4.42 +-30.06, -30.00, 47.17, 52.83, -5.67 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 52.11, 47.89, 4.22 +-29.99, -30.00, 49.59, 50.41, -0.82 +-29.99, -30.00, 52.06, 47.94, 4.12 +-29.99, -30.00, 52.06, 47.94, 4.12 +-29.99, -30.00, 52.06, 47.94, 4.12 +-29.93, -30.00, 49.54, 50.46, -0.92 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.93, -30.00, 52.01, 47.99, 4.02 +-29.79, -30.00, 46.97, 53.03, -6.07 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.82 +-29.79, -30.00, 51.91, 48.09, 3.81 +-29.73, -30.00, 49.38, 50.62, -1.23 +-29.73, -30.00, 51.86, 48.14, 3.71 +-29.73, -30.00, 51.85, 48.15, 3.71 +-29.73, -30.00, 51.85, 48.15, 3.71 +-29.73, -30.00, 51.85, 48.15, 3.71 +-29.73, -30.00, 51.85, 48.15, 3.70 +-29.73, -30.00, 51.85, 48.15, 3.70 +-29.73, -30.00, 51.85, 48.15, 3.70 +-29.73, -30.00, 51.85, 48.15, 3.70 +-29.66, -30.00, 49.33, 50.67, -1.35 +-29.73, -30.00, 54.32, 45.68, 8.64 +-29.73, -30.00, 51.85, 48.15, 3.69 +-29.73, -30.00, 51.84, 48.16, 3.69 +-29.73, -30.00, 51.84, 48.16, 3.69 +-29.73, -30.00, 51.84, 48.16, 3.68 +-29.66, -30.00, 49.32, 50.68, -1.36 +-29.66, -30.00, 51.79, 48.21, 3.58 +-29.66, -30.00, 51.79, 48.21, 3.58 +-29.66, -30.00, 51.79, 48.21, 3.58 +-29.66, -30.00, 51.79, 48.21, 3.57 +-29.53, -30.00, 46.74, 53.26, -6.52 +-29.53, -30.00, 51.68, 48.32, 3.37 +-29.53, -30.00, 51.68, 48.32, 3.37 +-29.53, -30.00, 51.68, 48.32, 3.36 +-29.53, -30.00, 51.68, 48.32, 3.36 +-29.53, -30.00, 51.68, 48.32, 3.35 +-29.53, -30.00, 51.68, 48.32, 3.35 +-29.53, -30.00, 51.67, 48.33, 3.35 +-29.53, -30.00, 51.67, 48.33, 3.34 +-29.53, -30.00, 51.67, 48.33, 3.34 +-29.66, -30.00, 56.71, 43.29, 13.42 +-29.66, -30.00, 51.77, 48.23, 3.53 +-29.66, -30.00, 51.77, 48.23, 3.53 +-29.66, -30.00, 51.76, 48.24, 3.53 +-29.66, -30.00, 51.76, 48.24, 3.53 +-29.66, -30.00, 51.76, 48.24, 3.52 +-29.66, -30.00, 51.76, 48.24, 3.52 +-29.53, -30.00, 46.72, 53.28, -6.57 +-29.53, -30.00, 51.66, 48.34, 3.32 +-29.53, -30.00, 51.66, 48.34, 3.31 +-29.53, -30.00, 51.65, 48.35, 3.31 +-29.53, -30.00, 51.65, 48.35, 3.31 +-29.53, -30.00, 51.65, 48.35, 3.30 +-29.53, -30.00, 51.65, 48.35, 3.30 +-29.53, -30.00, 51.65, 48.35, 3.29 +-29.53, -30.00, 51.65, 48.35, 3.29 +-29.66, -30.00, 56.69, 43.31, 13.37 +-29.66, -30.00, 51.74, 48.26, 3.48 +-29.66, -30.00, 51.74, 48.26, 3.48 +-29.66, -30.00, 51.74, 48.26, 3.48 +-29.66, -30.00, 51.74, 48.26, 3.48 +-29.66, -30.00, 51.74, 48.26, 3.47 +-29.66, -30.00, 51.74, 48.26, 3.47 +-29.73, -30.00, 54.26, 45.74, 8.51 +-29.66, -30.00, 49.26, 50.74, -1.48 +-29.66, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 51.73, 48.27, 3.45 +-29.66, -30.00, 51.73, 48.27, 3.45 +-29.73, -30.00, 54.25, 45.75, 8.49 +-29.73, -30.00, 51.77, 48.23, 3.55 +-29.73, -30.00, 51.77, 48.23, 3.54 +-29.73, -30.00, 51.77, 48.23, 3.54 +-29.79, -30.00, 54.29, 45.71, 8.58 +-29.79, -30.00, 51.82, 48.18, 3.64 +-29.79, -30.00, 51.82, 48.18, 3.64 +-29.79, -30.00, 51.82, 48.18, 3.63 +-29.79, -30.00, 51.82, 48.18, 3.63 +-29.79, -30.00, 51.82, 48.18, 3.63 +-29.79, -30.00, 51.82, 48.18, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.61 +-29.93, -30.00, 56.85, 43.15, 13.70 +-29.93, -30.00, 51.91, 48.09, 3.81 +-29.93, -30.00, 51.91, 48.09, 3.81 +-29.93, -30.00, 51.91, 48.09, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.99, -30.00, 54.43, 45.57, 8.85 +-29.99, -30.00, 51.95, 48.05, 3.91 +-29.93, -30.00, 49.43, 50.57, -1.14 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.93, -30.00, 51.90, 48.10, 3.81 +-29.99, -30.00, 54.42, 45.58, 8.85 +-29.99, -30.00, 51.95, 48.05, 3.90 +-29.99, -30.00, 51.95, 48.05, 3.90 +-29.99, -30.00, 51.95, 48.05, 3.90 +-29.99, -30.00, 51.95, 48.05, 3.90 +-30.06, -30.00, 54.47, 45.53, 8.95 +-30.06, -30.00, 52.00, 48.00, 4.00 +-30.06, -30.00, 52.00, 48.00, 4.00 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.00, 48.00, 4.01 +-30.06, -30.00, 52.01, 47.99, 4.01 +-30.06, -30.00, 52.01, 47.99, 4.01 +-30.06, -30.00, 52.01, 47.99, 4.01 +-30.06, -30.00, 52.01, 47.99, 4.01 +-30.19, -30.00, 57.05, 42.95, 14.10 +-30.19, -30.00, 52.11, 47.89, 4.21 +-30.19, -30.00, 52.11, 47.89, 4.21 +-30.19, -30.00, 52.11, 47.89, 4.21 +-30.19, -30.00, 52.11, 47.89, 4.22 +-30.19, -30.00, 52.11, 47.89, 4.22 +-30.19, -30.00, 52.11, 47.89, 4.22 +-30.19, -30.00, 52.11, 47.89, 4.22 +-30.06, -30.00, 47.07, 52.93, -5.86 +-30.06, -30.00, 52.01, 47.99, 4.02 +-30.06, -30.00, 52.01, 47.99, 4.02 +-30.06, -30.00, 52.01, 47.99, 4.02 +-30.06, -30.00, 52.01, 47.99, 4.02 +-30.06, -30.00, 52.01, 47.99, 4.03 +-30.06, -30.00, 52.01, 47.99, 4.03 +-30.19, -30.00, 57.06, 42.94, 14.11 +-30.06, -30.00, 47.07, 52.93, -5.86 +-30.19, -30.00, 57.06, 42.94, 14.11 +-30.19, -30.00, 52.11, 47.89, 4.23 +-30.06, -30.00, 47.07, 52.93, -5.86 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-30.06, -30.00, 52.02, 47.98, 4.03 +-29.99, -30.00, 49.50, 50.50, -1.01 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-30.06, -30.00, 54.49, 45.51, 8.98 +-29.99, -30.00, 49.50, 50.50, -1.01 +-29.99, -30.00, 51.97, 48.03, 3.94 +-30.06, -30.00, 54.49, 45.51, 8.98 +-29.99, -30.00, 49.50, 50.50, -1.01 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.99, -30.00, 51.97, 48.03, 3.94 +-29.93, -30.00, 49.45, 50.55, -1.11 +-29.93, -30.00, 51.92, 48.08, 3.84 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.92, 48.08, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.93, -30.00, 51.91, 48.09, 3.83 +-29.79, -30.00, 46.87, 53.13, -6.26 +-29.79, -30.00, 51.81, 48.19, 3.63 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.62 +-29.79, -30.00, 51.81, 48.19, 3.61 +-29.79, -30.00, 51.81, 48.19, 3.61 +-29.79, -30.00, 51.81, 48.19, 3.61 +-29.79, -30.00, 51.80, 48.20, 3.61 +-29.79, -30.00, 51.80, 48.20, 3.61 +-29.79, -30.00, 51.80, 48.20, 3.61 +-29.79, -30.00, 51.80, 48.20, 3.60 +-29.79, -30.00, 51.80, 48.20, 3.60 +-29.79, -30.00, 51.80, 48.20, 3.60 +-29.79, -30.00, 51.80, 48.20, 3.60 +-29.73, -30.00, 49.28, 50.72, -1.44 +-29.73, -30.00, 51.75, 48.25, 3.50 +-29.73, -30.00, 51.75, 48.25, 3.50 +-29.73, -30.00, 51.75, 48.25, 3.49 +-29.73, -30.00, 51.75, 48.25, 3.49 +-29.73, -30.00, 51.74, 48.26, 3.49 +-29.79, -30.00, 54.27, 45.73, 8.53 +-29.79, -30.00, 51.79, 48.21, 3.59 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.58 +-29.79, -30.00, 51.79, 48.21, 3.57 +-29.73, -30.00, 49.26, 50.74, -1.47 +-29.73, -30.00, 51.74, 48.26, 3.47 +-29.73, -30.00, 51.73, 48.27, 3.47 +-29.73, -30.00, 51.73, 48.27, 3.47 +-29.73, -30.00, 51.73, 48.27, 3.47 +-29.73, -30.00, 51.73, 48.27, 3.46 +-29.73, -30.00, 51.73, 48.27, 3.46 +-29.66, -30.00, 49.21, 50.79, -1.58 +-29.66, -30.00, 51.68, 48.32, 3.36 +-29.66, -30.00, 51.68, 48.32, 3.35 +-29.66, -30.00, 51.68, 48.32, 3.35 +-29.73, -30.00, 54.20, 45.80, 8.39 +-29.73, -30.00, 51.72, 48.28, 3.45 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.43 +-29.66, -30.00, 49.19, 50.81, -1.61 +-29.66, -30.00, 51.67, 48.33, 3.33 +-29.66, -30.00, 51.66, 48.34, 3.33 +-29.53, -30.00, 46.62, 53.38, -6.76 +-29.53, -30.00, 51.56, 48.44, 3.12 +-29.53, -30.00, 51.56, 48.44, 3.12 +-29.53, -30.00, 51.56, 48.44, 3.12 +-29.53, -30.00, 51.56, 48.44, 3.11 +-29.53, -30.00, 51.55, 48.45, 3.11 +-29.53, -30.00, 51.55, 48.45, 3.11 +-29.53, -30.00, 51.55, 48.45, 3.10 +-29.53, -30.00, 51.55, 48.45, 3.10 +-29.53, -30.00, 51.55, 48.45, 3.10 +-29.53, -30.00, 51.55, 48.45, 3.09 +-29.53, -30.00, 51.54, 48.46, 3.09 +-29.53, -30.00, 51.54, 48.46, 3.08 +-29.53, -30.00, 51.54, 48.46, 3.08 +-29.53, -30.00, 51.54, 48.46, 3.08 +-29.47, -30.00, 49.02, 50.98, -1.97 +-29.53, -30.00, 54.01, 45.99, 8.01 +-29.47, -30.00, 49.01, 50.99, -1.98 +-29.53, -30.00, 54.00, 46.00, 8.01 +-29.53, -30.00, 51.53, 48.47, 3.06 +-29.53, -30.00, 51.53, 48.47, 3.06 +-29.53, -30.00, 51.53, 48.47, 3.05 +-29.53, -30.00, 51.52, 48.48, 3.05 +-29.53, -30.00, 51.52, 48.48, 3.05 +-29.53, -30.00, 51.52, 48.48, 3.04 +-29.53, -30.00, 51.52, 48.48, 3.04 +-29.53, -30.00, 51.52, 48.48, 3.03 +-29.53, -30.00, 51.52, 48.48, 3.03 +-29.53, -30.00, 51.51, 48.49, 3.03 +-29.53, -30.00, 51.51, 48.49, 3.02 +-29.53, -30.00, 51.51, 48.49, 3.02 +-29.53, -30.00, 51.51, 48.49, 3.02 +-29.53, -30.00, 51.51, 48.49, 3.01 +-29.53, -30.00, 51.51, 48.49, 3.01 +-29.53, -30.00, 51.50, 48.50, 3.01 +-29.53, -30.00, 51.50, 48.50, 3.00 +-29.53, -30.00, 51.50, 48.50, 3.00 +-29.53, -30.00, 51.50, 48.50, 3.00 +-29.66, -30.00, 56.54, 43.46, 13.08 +-29.66, -30.00, 51.59, 48.41, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.73, -30.00, 54.11, 45.89, 8.22 +-29.73, -30.00, 51.64, 48.36, 3.28 +-29.73, -30.00, 51.64, 48.36, 3.28 +-29.73, -30.00, 51.64, 48.36, 3.27 +-29.79, -30.00, 54.16, 45.84, 8.32 +-29.73, -30.00, 49.16, 50.84, -1.67 +-29.73, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 54.15, 45.85, 8.31 +-29.73, -30.00, 49.16, 50.84, -1.68 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 54.15, 45.85, 8.30 +-29.79, -30.00, 51.68, 48.32, 3.35 +-29.79, -30.00, 51.68, 48.32, 3.35 +-29.79, -30.00, 51.67, 48.33, 3.35 +-29.79, -30.00, 51.67, 48.33, 3.35 +-29.93, -30.00, 56.72, 43.28, 13.43 +-29.93, -30.00, 51.77, 48.23, 3.54 +-29.93, -30.00, 51.77, 48.23, 3.54 +-29.99, -30.00, 54.29, 45.71, 8.59 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-29.99, -30.00, 51.82, 48.18, 3.64 +-30.06, -30.00, 54.34, 45.66, 8.69 +-30.06, -30.00, 51.87, 48.13, 3.74 +-30.06, -30.00, 51.87, 48.13, 3.74 +-30.06, -30.00, 51.87, 48.13, 3.74 +-30.19, -30.00, 56.92, 43.08, 13.83 +-30.19, -30.00, 51.97, 48.03, 3.94 +-30.19, -30.00, 51.97, 48.03, 3.95 +-30.26, -30.00, 54.50, 45.50, 8.99 +-30.26, -30.00, 52.02, 47.98, 4.05 +-30.26, -30.00, 52.03, 47.97, 4.05 +-30.26, -30.00, 52.03, 47.97, 4.05 +-30.32, -30.00, 54.55, 45.45, 9.10 +-30.32, -30.00, 52.08, 47.92, 4.16 +-30.32, -30.00, 52.08, 47.92, 4.16 +-30.32, -30.00, 52.08, 47.92, 4.16 +-30.32, -30.00, 52.08, 47.92, 4.16 +-30.32, -30.00, 52.08, 47.92, 4.17 +-30.32, -30.00, 52.08, 47.92, 4.17 +-30.32, -30.00, 52.09, 47.91, 4.17 +-30.32, -30.00, 52.09, 47.91, 4.17 +-30.32, -30.00, 52.09, 47.91, 4.17 +-30.32, -30.00, 52.09, 47.91, 4.18 +-30.45, -30.00, 57.13, 42.87, 14.27 +-30.45, -30.00, 52.19, 47.81, 4.38 +-30.45, -30.00, 52.19, 47.81, 4.39 +-30.45, -30.00, 52.19, 47.81, 4.39 +-30.45, -30.00, 52.20, 47.80, 4.39 +-30.45, -30.00, 52.20, 47.80, 4.40 +-30.45, -30.00, 52.20, 47.80, 4.40 +-30.45, -30.00, 52.20, 47.80, 4.40 +-30.45, -30.00, 52.20, 47.80, 4.41 +-30.45, -30.00, 52.20, 47.80, 4.41 +-30.45, -30.00, 52.21, 47.79, 4.41 +-30.45, -30.00, 52.21, 47.79, 4.42 +-30.45, -30.00, 52.21, 47.79, 4.42 +-30.45, -30.00, 52.21, 47.79, 4.42 +-30.45, -30.00, 52.21, 47.79, 4.43 +-30.45, -30.00, 52.21, 47.79, 4.43 +-30.45, -30.00, 52.22, 47.78, 4.43 +-30.45, -30.00, 52.22, 47.78, 4.44 +-30.45, -30.00, 52.22, 47.78, 4.44 +-30.45, -30.00, 52.22, 47.78, 4.44 +-30.45, -30.00, 52.22, 47.78, 4.45 +-30.45, -30.00, 52.23, 47.77, 4.45 +-30.45, -30.00, 52.23, 47.77, 4.45 +-30.45, -30.00, 52.23, 47.77, 4.46 +-30.45, -30.00, 52.23, 47.77, 4.46 +-30.45, -30.00, 52.23, 47.77, 4.46 +-30.45, -30.00, 52.23, 47.77, 4.47 +-30.45, -30.00, 52.24, 47.76, 4.47 +-30.45, -30.00, 52.24, 47.76, 4.47 +-30.45, -30.00, 52.24, 47.76, 4.48 +-30.45, -30.00, 52.24, 47.76, 4.48 +-30.45, -30.00, 52.24, 47.76, 4.48 +-30.32, -30.00, 47.20, 52.80, -5.60 +-30.32, -30.00, 52.15, 47.85, 4.29 +-30.32, -30.00, 52.15, 47.85, 4.29 +-30.45, -30.00, 57.19, 42.81, 14.38 +-30.45, -30.00, 52.25, 47.75, 4.50 +-30.45, -30.00, 52.25, 47.75, 4.50 +-30.45, -30.00, 52.25, 47.75, 4.51 +-30.32, -30.00, 47.21, 52.79, -5.58 +-30.32, -30.00, 52.16, 47.84, 4.31 +-30.32, -30.00, 52.16, 47.84, 4.31 +-30.32, -30.00, 52.16, 47.84, 4.32 +-30.32, -30.00, 52.16, 47.84, 4.32 +-30.32, -30.00, 52.16, 47.84, 4.32 +-30.32, -30.00, 52.16, 47.84, 4.32 +-30.26, -30.00, 49.64, 50.36, -0.72 +-30.26, -30.00, 52.11, 47.89, 4.23 +-30.26, -30.00, 52.12, 47.88, 4.23 +-30.26, -30.00, 52.12, 47.88, 4.23 +-30.26, -30.00, 52.12, 47.88, 4.23 +-30.26, -30.00, 52.12, 47.88, 4.24 +-30.26, -30.00, 52.12, 47.88, 4.24 +-30.26, -30.00, 52.12, 47.88, 4.24 +-30.26, -30.00, 52.12, 47.88, 4.24 +-30.19, -30.00, 49.60, 50.40, -0.80 +-30.19, -30.00, 52.07, 47.93, 4.15 +-30.19, -30.00, 52.07, 47.93, 4.15 +-30.19, -30.00, 52.07, 47.93, 4.15 +-30.19, -30.00, 52.08, 47.92, 4.15 +-30.19, -30.00, 52.08, 47.92, 4.15 +-30.19, -30.00, 52.08, 47.92, 4.15 +-30.06, -30.00, 47.03, 52.97, -5.93 +-30.06, -30.00, 51.98, 48.02, 3.96 +-30.06, -30.00, 51.98, 48.02, 3.96 +-30.06, -30.00, 51.98, 48.02, 3.96 +-30.06, -30.00, 51.98, 48.02, 3.96 +-29.99, -30.00, 49.46, 50.54, -1.08 +-30.06, -30.00, 54.45, 45.55, 8.90 +-29.99, -30.00, 49.46, 50.54, -1.08 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-30.06, -30.00, 54.45, 45.55, 8.90 +-29.99, -30.00, 49.46, 50.54, -1.08 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.99, -30.00, 51.93, 48.07, 3.86 +-29.93, -30.00, 49.41, 50.59, -1.18 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.76 +-29.93, -30.00, 51.88, 48.12, 3.75 +-29.93, -30.00, 51.88, 48.12, 3.75 +-29.93, -30.00, 51.88, 48.12, 3.75 +-29.79, -30.00, 46.83, 53.17, -6.33 +-29.79, -30.00, 51.78, 48.22, 3.55 +-29.79, -30.00, 51.78, 48.22, 3.55 +-29.79, -30.00, 51.77, 48.23, 3.55 +-29.79, -30.00, 51.77, 48.23, 3.55 +-29.73, -30.00, 49.25, 50.75, -1.50 +-29.73, -30.00, 51.72, 48.28, 3.45 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.44 +-29.73, -30.00, 51.72, 48.28, 3.43 +-29.73, -30.00, 51.72, 48.28, 3.43 +-29.73, -30.00, 51.71, 48.29, 3.43 +-29.73, -30.00, 51.71, 48.29, 3.43 +-29.73, -30.00, 51.71, 48.29, 3.42 +-29.73, -30.00, 51.71, 48.29, 3.42 +-29.73, -30.00, 51.71, 48.29, 3.42 +-29.66, -30.00, 49.19, 50.81, -1.62 +-29.66, -30.00, 51.66, 48.34, 3.32 +-29.66, -30.00, 51.66, 48.34, 3.31 +-29.66, -30.00, 51.66, 48.34, 3.31 +-29.66, -30.00, 51.65, 48.35, 3.31 +-29.66, -30.00, 51.65, 48.35, 3.31 +-29.66, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 51.65, 48.35, 3.29 +-29.66, -30.00, 51.65, 48.35, 3.29 +-29.73, -30.00, 54.17, 45.83, 8.33 +-29.73, -30.00, 51.69, 48.31, 3.39 +-29.66, -30.00, 49.17, 50.83, -1.66 +-29.66, -30.00, 51.64, 48.36, 3.28 +-29.66, -30.00, 51.64, 48.36, 3.28 +-29.66, -30.00, 51.64, 48.36, 3.28 +-29.66, -30.00, 51.64, 48.36, 3.27 +-29.66, -30.00, 51.64, 48.36, 3.27 +-29.66, -30.00, 51.63, 48.37, 3.27 +-29.66, -30.00, 51.63, 48.37, 3.27 +-29.66, -30.00, 51.63, 48.37, 3.26 +-29.66, -30.00, 51.63, 48.37, 3.26 +-29.66, -30.00, 51.63, 48.37, 3.26 +-29.66, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 54.15, 45.85, 8.30 +-29.73, -30.00, 51.68, 48.32, 3.35 +-29.73, -30.00, 51.67, 48.33, 3.35 +-29.73, -30.00, 51.67, 48.33, 3.35 +-29.73, -30.00, 51.67, 48.33, 3.35 +-29.73, -30.00, 51.67, 48.33, 3.34 +-29.73, -30.00, 51.67, 48.33, 3.34 +-29.73, -30.00, 51.67, 48.33, 3.34 +-29.73, -30.00, 51.67, 48.33, 3.34 +-29.66, -30.00, 49.15, 50.85, -1.71 +-29.66, -30.00, 51.62, 48.38, 3.23 +-29.66, -30.00, 51.62, 48.38, 3.23 +-29.66, -30.00, 51.61, 48.39, 3.23 +-29.66, -30.00, 51.61, 48.39, 3.23 +-29.66, -30.00, 51.61, 48.39, 3.22 +-29.66, -30.00, 51.61, 48.39, 3.22 +-29.66, -30.00, 51.61, 48.39, 3.22 +-29.73, -30.00, 54.13, 45.87, 8.26 +-29.73, -30.00, 51.66, 48.34, 3.31 +-29.73, -30.00, 51.66, 48.34, 3.31 +-29.73, -30.00, 51.65, 48.35, 3.31 +-29.73, -30.00, 51.65, 48.35, 3.31 +-29.73, -30.00, 51.65, 48.35, 3.31 +-29.73, -30.00, 51.65, 48.35, 3.30 +-29.73, -30.00, 51.65, 48.35, 3.30 +-29.73, -30.00, 51.65, 48.35, 3.30 +-29.73, -30.00, 51.65, 48.35, 3.30 +-29.66, -30.00, 49.13, 50.87, -1.75 +-29.66, -30.00, 51.60, 48.40, 3.19 +-29.66, -30.00, 51.60, 48.40, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.19 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.66, -30.00, 51.59, 48.41, 3.18 +-29.73, -30.00, 54.11, 45.89, 8.22 +-29.73, -30.00, 51.64, 48.36, 3.27 +-29.73, -30.00, 51.63, 48.37, 3.27 +-29.73, -30.00, 51.63, 48.37, 3.27 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.73, -30.00, 51.63, 48.37, 3.26 +-29.66, -30.00, 49.11, 50.89, -1.78 +-29.66, -30.00, 51.58, 48.42, 3.16 +-29.66, -30.00, 51.58, 48.42, 3.15 +-29.66, -30.00, 51.58, 48.42, 3.15 +-29.66, -30.00, 51.57, 48.43, 3.15 +-29.66, -30.00, 51.57, 48.43, 3.15 +-29.66, -30.00, 51.57, 48.43, 3.14 +-29.66, -30.00, 51.57, 48.43, 3.14 +-29.66, -30.00, 51.57, 48.43, 3.14 +-29.66, -30.00, 51.57, 48.43, 3.14 +-29.66, -30.00, 51.57, 48.43, 3.13 +-29.66, -30.00, 51.57, 48.43, 3.13 +-29.73, -30.00, 54.09, 45.91, 8.17 +-29.73, -30.00, 51.61, 48.39, 3.23 +-29.73, -30.00, 51.61, 48.39, 3.22 +-29.73, -30.00, 51.61, 48.39, 3.22 +-29.66, -30.00, 49.09, 50.91, -1.82 +-29.66, -30.00, 51.56, 48.44, 3.12 +-29.66, -30.00, 51.56, 48.44, 3.12 +-29.66, -30.00, 51.56, 48.44, 3.11 +-29.66, -30.00, 51.56, 48.44, 3.11 +-29.66, -30.00, 51.55, 48.45, 3.11 +-29.66, -30.00, 51.55, 48.45, 3.11 +-29.66, -30.00, 51.55, 48.45, 3.10 +-29.66, -30.00, 51.55, 48.45, 3.10 +-29.73, -30.00, 54.07, 45.93, 8.14 +-29.73, -30.00, 51.60, 48.40, 3.20 +-29.73, -30.00, 51.60, 48.40, 3.19 +-29.73, -30.00, 51.60, 48.40, 3.19 +-29.73, -30.00, 51.59, 48.41, 3.19 +-29.73, -30.00, 51.59, 48.41, 3.19 +-29.73, -30.00, 51.59, 48.41, 3.18 +-29.73, -30.00, 51.59, 48.41, 3.18 +-29.73, -30.00, 51.59, 48.41, 3.18 +-29.79, -30.00, 54.11, 45.89, 8.22 +-29.73, -30.00, 49.12, 50.88, -1.77 +-29.79, -30.00, 54.11, 45.89, 8.22 +-29.79, -30.00, 51.64, 48.36, 3.27 +-29.79, -30.00, 51.64, 48.36, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.27 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.79, -30.00, 51.63, 48.37, 3.26 +-29.93, -30.00, 56.67, 43.33, 13.34 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.73, 48.27, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.99, -30.00, 54.25, 45.75, 8.49 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-30.06, -30.00, 54.30, 45.70, 8.59 +-30.06, -30.00, 51.82, 48.18, 3.65 +-30.06, -30.00, 51.82, 48.18, 3.65 +-30.06, -30.00, 51.82, 48.18, 3.65 +-30.06, -30.00, 51.82, 48.18, 3.65 +-30.06, -30.00, 51.82, 48.18, 3.65 +-29.99, -30.00, 49.30, 50.70, -1.39 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.99, -30.00, 51.77, 48.23, 3.55 +-29.93, -30.00, 49.25, 50.75, -1.49 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.45 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.93, -30.00, 49.25, 50.75, -1.51 +-29.93, -30.00, 51.72, 48.28, 3.44 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.93, -30.00, 49.25, 50.75, -1.51 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.99, -30.00, 51.77, 48.23, 3.54 +-29.93, -30.00, 49.25, 50.75, -1.51 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.93, -30.00, 49.25, 50.75, -1.51 +-29.99, -30.00, 54.24, 45.76, 8.48 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-30.06, -30.00, 54.29, 45.71, 8.58 +-29.99, -30.00, 49.30, 50.70, -1.41 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-29.99, -30.00, 51.77, 48.23, 3.53 +-30.06, -30.00, 54.29, 45.71, 8.58 +-29.99, -30.00, 49.30, 50.70, -1.41 +-30.06, -30.00, 54.29, 45.71, 8.58 +-30.06, -30.00, 51.82, 48.18, 3.63 +-30.06, -30.00, 51.82, 48.18, 3.63 +-30.06, -30.00, 51.82, 48.18, 3.63 +-30.06, -30.00, 51.82, 48.18, 3.64 +-30.06, -30.00, 51.82, 48.18, 3.64 +-30.19, -30.00, 56.86, 43.14, 13.72 +-30.19, -30.00, 51.92, 48.08, 3.84 +-30.19, -30.00, 51.92, 48.08, 3.84 +-30.19, -30.00, 51.92, 48.08, 3.84 +-30.19, 0.00, 75.00, 25.00, 50.00 +-30.19, 0.00, 74.65, 25.35, 49.29 +-30.19, 0.00, 74.76, 25.24, 49.52 +-30.19, 0.00, 74.87, 25.13, 49.74 +-30.19, 0.00, 74.99, 25.01, 49.97 +-30.06, 0.00, 70.06, 29.94, 40.11 +-30.06, 0.00, 75.00, 25.00, 50.00 +-30.06, 0.00, 75.00, 25.00, 50.00 +-30.06, 0.00, 75.00, 25.00, 50.00 +-30.06, 0.00, 75.00, 25.00, 50.00 +-29.99, 0.00, 73.04, 26.96, 46.08 +-29.99, 0.00, 75.00, 25.00, 50.00 +-29.93, 0.00, 73.22, 26.78, 46.43 +-29.93, 0.00, 75.00, 25.00, 50.00 +-29.79, 0.00, 70.87, 29.13, 41.74 +-29.73, 0.00, 73.40, 26.60, 46.81 +-29.66, 0.00, 73.47, 26.53, 46.93 +-29.53, 0.00, 71.01, 28.99, 42.01 +-29.47, 0.00, 73.54, 26.46, 47.08 +-29.27, 0.00, 68.56, 31.44, 37.11 +-29.14, 0.00, 71.04, 28.96, 42.08 +-29.00, 0.00, 71.05, 28.95, 42.10 +-28.74, 0.00, 66.01, 33.99, 32.03 +-28.61, 0.00, 70.97, 29.03, 41.93 +-28.41, 0.00, 68.45, 31.55, 36.91 +-28.21, 0.00, 68.41, 31.59, 36.82 +-27.95, 0.00, 65.85, 34.15, 31.69 +-27.82, 0.00, 70.79, 29.21, 41.59 +-27.55, 0.00, 65.76, 34.24, 31.51 +-27.36, 0.00, 68.18, 31.82, 36.37 +-27.03, 0.00, 63.09, 36.91, 26.19 +-26.83, 0.00, 67.99, 32.01, 35.98 +-26.50, 0.00, 62.90, 37.10, 25.80 +-26.24, 0.00, 65.27, 34.73, 30.54 +-25.84, 0.00, 60.13, 39.87, 20.25 +-25.58, 0.00, 64.97, 35.03, 29.94 +-25.25, 0.00, 62.34, 37.66, 24.69 +-24.92, 0.00, 62.19, 37.81, 24.38 +-24.52, 0.00, 59.51, 40.49, 19.03 +-24.19, 0.00, 61.83, 38.17, 23.66 +-23.86, 0.00, 61.67, 38.33, 23.34 +-23.47, 0.00, 58.99, 41.01, 17.98 +-23.07, 0.00, 58.78, 41.22, 17.56 +-22.68, 0.00, 58.57, 41.43, 17.14 +-22.28, 0.00, 58.36, 41.64, 16.71 +-21.82, 0.00, 55.62, 44.38, 11.24 +-21.49, 0.00, 60.40, 39.60, 20.79 +-21.03, 0.00, 55.19, 44.81, 10.37 +-20.50, 0.00, 52.40, 47.60, 4.79 +-20.17, 0.00, 59.64, 40.36, 19.28 +-19.71, 0.00, 54.42, 45.58, 8.85 +-19.18, 0.00, 51.63, 48.37, 3.26 +-18.72, 0.00, 53.82, 46.18, 7.65 +-18.19, 0.00, 51.03, 48.97, 2.05 +-17.80, 0.00, 55.74, 44.26, 11.48 +-17.27, 0.00, 50.46, 49.54, 0.93 +-16.74, 0.00, 50.13, 49.87, 0.26 +-16.28, 0.00, 52.32, 47.68, 4.64 +-15.82, 0.00, 52.03, 47.97, 4.06 +-15.29, 0.00, 49.22, 50.78, -1.56 +-14.77, 0.00, 48.88, 51.12, -2.24 +-14.24, 0.00, 48.54, 51.46, -2.92 +-13.84, 0.00, 53.24, 46.76, 6.48 +-13.32, 0.00, 47.95, 52.05, -4.10 +-12.85, 0.00, 50.12, 49.88, 0.25 +-12.33, 0.00, 47.30, 52.70, -5.40 +-11.80, 0.00, 46.95, 53.05, -6.10 +-11.27, 0.00, 46.60, 53.40, -6.80 +-10.74, 0.00, 46.24, 53.76, -7.51 +-10.22, 0.00, 45.89, 54.11, -8.23 +-9.69, 0.00, 45.53, 54.47, -8.95 +-9.23, 0.00, 47.69, 52.31, -4.63 +-8.70, 0.00, 44.85, 55.15, -10.30 +-8.31, 0.00, 49.53, 50.47, -0.94 +-7.78, 0.00, 44.22, 55.78, -11.56 +-7.32, 0.00, 46.37, 53.63, -7.25 +-6.79, 0.00, 43.53, 56.47, -12.94 +-6.26, 0.00, 43.16, 56.84, -13.68 +-5.80, 0.00, 45.31, 54.69, -9.39 +-5.41, 0.00, 47.50, 52.50, -4.99 +-4.88, 0.00, 42.18, 57.82, -15.64 +-4.42, 0.00, 44.32, 55.68, -11.35 +-3.89, 0.00, 41.47, 58.53, -17.06 +-3.43, 0.00, 43.61, 56.39, -12.78 +-3.03, 0.00, 45.80, 54.20, -8.41 +-2.57, 0.00, 42.99, 57.01, -14.02 +-2.04, 0.00, 40.13, 59.87, -19.74 +-1.58, 0.00, 42.26, 57.74, -15.48 +-1.19, 0.00, 44.44, 55.56, -11.12 +-0.73, 0.00, 41.62, 58.38, -16.75 +-0.40, 0.00, 46.32, 53.68, -7.35 +0.07, 0.00, 41.03, 58.97, -17.93 +0.53, 0.00, 40.68, 59.32, -18.63 +0.86, 0.00, 45.38, 54.62, -9.24 +1.32, 0.00, 40.08, 59.92, -19.83 +1.71, 0.00, 42.25, 57.75, -15.50 +2.11, 0.00, 41.95, 58.05, -16.11 +2.44, 0.00, 44.16, 55.84, -11.67 +2.90, 0.00, 38.86, 61.14, -22.28 +3.23, 0.00, 43.55, 56.45, -12.91 +3.56, 0.00, 43.29, 56.71, -13.43 +3.96, 0.00, 40.50, 59.50, -18.99 +4.28, 0.00, 42.71, 57.29, -14.58 +4.61, 0.00, 42.45, 57.55, -15.11 +5.01, 0.00, 39.66, 60.34, -20.68 +5.27, 0.00, 44.39, 55.61, -11.23 +5.60, 0.00, 41.65, 58.35, -16.71 +5.93, 0.00, 41.38, 58.62, -17.25 +6.20, 0.00, 43.63, 56.37, -12.75 +6.59, 0.00, 38.36, 61.64, -23.28 +6.86, 0.00, 43.08, 56.92, -13.84 +7.19, 0.00, 40.34, 59.66, -19.33 +7.45, 0.00, 42.58, 57.42, -14.83 +7.71, 0.00, 42.36, 57.64, -15.29 +7.98, 0.00, 42.13, 57.87, -15.74 +8.24, 0.00, 41.90, 58.10, -16.20 +8.44, 0.00, 44.19, 55.81, -11.62 +8.70, 0.00, 41.49, 58.51, -17.02 +8.96, 0.00, 41.26, 58.74, -17.48 +9.10, 0.00, 46.07, 53.93, -7.86 +9.29, 0.00, 43.41, 56.59, -13.17 +9.56, 0.00, 40.71, 59.29, -18.58 +9.76, 0.00, 43.00, 57.00, -14.01 +9.89, 0.00, 45.33, 54.67, -9.34 +10.09, 0.00, 42.67, 57.33, -14.65 +10.28, 0.00, 42.49, 57.51, -15.03 +10.42, 0.00, 44.82, 55.18, -10.36 +10.61, 0.00, 42.16, 57.84, -15.68 +10.68, 0.00, 47.01, 52.99, -5.97 +10.88, 0.00, 41.88, 58.12, -16.24 +11.07, 0.00, 41.69, 58.31, -16.62 +11.14, 0.00, 46.54, 53.46, -6.91 +11.21, 0.00, 46.45, 53.55, -7.09 +11.40, 0.00, 41.32, 58.68, -17.36 +11.47, 0.00, 46.17, 53.83, -7.66 +11.60, 0.00, 43.56, 56.44, -12.89 +11.67, 0.00, 45.93, 54.07, -8.13 +11.87, 0.00, 40.80, 59.20, -18.41 +11.87, 0.00, 48.17, 51.83, -3.66 +11.93, 0.00, 45.60, 54.40, -8.80 +12.00, 0.00, 45.51, 54.49, -8.98 +12.13, 0.00, 42.89, 57.11, -14.22 +12.19, 0.00, 45.27, 54.73, -9.46 +12.26, 0.00, 45.17, 54.83, -9.65 +12.26, 0.00, 47.60, 52.40, -4.80 +12.39, 0.00, 42.51, 57.49, -14.98 +12.39, 0.00, 47.41, 52.59, -5.19 +12.39, 0.00, 47.36, 52.64, -5.28 +12.39, 0.00, 47.31, 52.69, -5.37 +12.46, 0.00, 44.75, 55.25, -10.51 +12.46, 0.00, 47.17, 52.83, -5.66 +12.46, 0.00, 47.12, 52.88, -5.75 +12.46, 0.00, 47.08, 52.92, -5.84 +12.46, 0.00, 47.03, 52.97, -5.94 +12.46, 0.00, 46.98, 53.02, -6.03 +12.46, 0.00, 46.94, 53.06, -6.12 +12.46, 0.00, 46.89, 53.11, -6.22 +12.46, 0.00, 46.84, 53.16, -6.31 +12.39, 0.00, 49.32, 50.68, -1.36 +12.39, 0.00, 46.80, 53.20, -6.40 +12.39, 0.00, 46.75, 53.25, -6.49 +12.26, 0.00, 51.75, 48.25, 3.50 +12.26, 0.00, 46.76, 53.24, -6.48 +12.19, 0.00, 49.24, 50.76, -1.53 +12.19, 0.00, 46.72, 53.28, -6.56 +12.13, 0.00, 49.20, 50.80, -1.61 +12.00, 0.00, 51.72, 48.28, 3.44 +11.93, 0.00, 49.25, 50.75, -1.49 +11.93, 0.00, 46.74, 53.26, -6.53 +11.87, 0.00, 49.21, 50.79, -1.57 +11.87, 0.00, 46.70, 53.30, -6.61 +11.67, 0.00, 54.22, 45.78, 8.44 +11.67, 0.00, 46.76, 53.24, -6.48 +11.60, 0.00, 49.24, 50.76, -1.53 +11.47, 0.00, 51.76, 48.24, 3.53 +11.34, 0.00, 51.82, 48.18, 3.64 +11.21, 0.00, 51.88, 48.12, 3.75 +11.14, 0.00, 49.41, 50.59, -1.17 +11.14, 0.00, 46.90, 53.10, -6.20 +11.07, 0.00, 49.38, 50.62, -1.24 +10.94, 0.00, 51.91, 48.09, 3.82 +10.88, 0.00, 49.45, 50.55, -1.11 +10.81, 0.00, 49.45, 50.55, -1.09 +10.61, 0.00, 54.51, 45.49, 9.01 +10.55, 0.00, 49.57, 50.43, -0.85 +10.42, 0.00, 52.10, 47.90, 4.21 +10.35, 0.00, 49.64, 50.36, -0.71 +10.28, 0.00, 49.65, 50.35, -0.69 +10.15, 0.00, 52.19, 47.81, 4.37 +10.02, 0.00, 52.25, 47.75, 4.50 +9.89, 0.00, 52.31, 47.69, 4.62 +9.82, 0.00, 49.85, 50.15, -0.30 +9.62, 0.00, 54.91, 45.09, 9.81 +9.56, 0.00, 49.98, 50.02, -0.05 +9.49, 0.00, 49.99, 50.01, -0.02 +9.29, 0.00, 55.05, 44.95, 10.10 +9.23, 0.00, 50.12, 49.88, 0.24 +9.10, 0.00, 52.66, 47.34, 5.31 +9.03, 0.00, 50.20, 49.80, 0.40 +8.83, 0.00, 55.26, 44.74, 10.52 +8.77, 0.00, 50.33, 49.67, 0.66 +8.70, 0.00, 50.35, 49.65, 0.69 +8.57, 0.00, 52.89, 47.11, 5.77 +8.50, 0.00, 50.43, 49.57, 0.86 +8.31, 0.00, 55.49, 44.51, 10.99 +8.24, 0.00, 50.57, 49.43, 1.13 +8.17, 0.00, 50.59, 49.41, 1.17 +8.04, 0.00, 53.13, 46.87, 6.25 +7.91, 0.00, 53.20, 46.80, 6.39 +7.78, 0.00, 53.27, 46.73, 6.53 +7.65, 0.00, 53.34, 46.66, 6.67 +7.51, 0.00, 53.41, 46.59, 6.81 +7.45, 0.00, 50.96, 49.04, 1.91 +7.25, 0.00, 56.02, 43.98, 12.04 +7.19, 0.00, 51.10, 48.90, 2.20 +7.12, 0.00, 51.12, 48.88, 2.25 +6.99, 0.00, 53.67, 46.33, 7.33 +6.86, 0.00, 53.74, 46.26, 7.48 +6.72, 0.00, 53.81, 46.19, 7.63 +6.66, 0.00, 51.37, 48.63, 2.73 +6.59, 0.00, 51.39, 48.61, 2.78 +6.46, 0.00, 53.94, 46.06, 7.88 +6.39, 0.00, 51.49, 48.51, 2.98 +6.33, 0.00, 51.52, 48.48, 3.03 +6.20, 0.00, 54.06, 45.94, 8.13 +6.13, 0.00, 51.62, 48.38, 3.24 +5.93, 0.00, 56.69, 43.31, 13.38 +5.87, 0.00, 51.77, 48.23, 3.55 +5.80, 0.00, 51.80, 48.20, 3.60 +5.67, 0.00, 54.35, 45.65, 8.70 +5.60, 0.00, 51.91, 48.09, 3.81 +5.54, 0.00, 51.94, 48.06, 3.87 +5.41, 0.00, 54.49, 45.51, 8.97 +5.34, 0.00, 52.04, 47.96, 4.09 +5.27, 0.00, 52.07, 47.93, 4.15 +5.14, 0.00, 54.62, 45.38, 9.25 +5.14, 0.00, 49.66, 50.34, -0.68 +5.08, 0.00, 52.16, 47.84, 4.33 +5.01, 0.00, 52.19, 47.81, 4.39 +4.88, 0.00, 54.75, 45.25, 9.49 +4.88, 0.00, 49.78, 50.22, -0.43 +4.81, 0.00, 52.29, 47.71, 4.58 +4.75, 0.00, 52.32, 47.68, 4.64 +4.61, 0.00, 54.87, 45.13, 9.75 +4.61, 0.00, 49.91, 50.09, -0.18 +4.48, 0.00, 54.94, 45.06, 9.88 +4.48, 0.00, 49.98, 50.02, -0.05 +4.35, 0.00, 55.00, 45.00, 10.01 +4.28, 0.00, 52.57, 47.43, 5.13 +4.28, 0.00, 50.08, 49.92, 0.15 +4.22, 0.00, 52.58, 47.42, 5.17 +4.22, 0.00, 50.09, 49.91, 0.19 +4.09, 0.00, 55.12, 44.88, 10.24 +4.02, 0.00, 52.68, 47.32, 5.37 +4.02, 0.00, 50.20, 49.80, 0.40 +4.02, 0.00, 50.18, 49.82, 0.37 +3.96, 0.00, 52.69, 47.31, 5.38 +3.96, 0.00, 50.20, 49.80, 0.40 +3.82, 0.00, 55.23, 44.77, 10.46 +3.82, 0.00, 50.27, 49.73, 0.55 +3.76, 0.00, 52.78, 47.22, 5.56 +3.76, 0.00, 50.29, 49.71, 0.59 +3.76, 0.00, 50.28, 49.72, 0.56 +3.69, 0.00, 52.79, 47.21, 5.57 +3.69, 0.00, 50.30, 49.70, 0.60 +3.69, 0.00, 50.29, 49.71, 0.58 +3.69, 0.00, 50.27, 49.73, 0.55 +3.56, 0.00, 55.30, 44.70, 10.61 +3.56, 0.00, 50.35, 49.65, 0.69 +3.49, 0.00, 52.85, 47.15, 5.71 +3.49, 0.00, 50.37, 49.63, 0.74 +3.49, 0.00, 50.36, 49.64, 0.71 +3.43, 0.00, 52.86, 47.14, 5.73 +3.43, 0.00, 50.38, 49.62, 0.76 +3.43, 0.00, 50.37, 49.63, 0.73 +3.43, 0.00, 50.35, 49.65, 0.71 +3.30, 0.00, 55.38, 44.62, 10.77 +3.30, 0.00, 50.43, 49.57, 0.86 +3.30, 0.00, 50.42, 49.58, 0.83 +3.30, 0.00, 50.40, 49.60, 0.81 +3.30, 0.00, 50.39, 49.61, 0.78 +3.30, 0.00, 50.38, 49.62, 0.76 +3.30, 0.00, 50.37, 49.63, 0.73 +3.30, 0.00, 50.35, 49.65, 0.71 +3.30, 0.00, 50.34, 49.66, 0.68 +3.30, 0.00, 50.33, 49.67, 0.66 +3.30, 0.00, 50.32, 49.68, 0.63 +3.30, 0.00, 50.30, 49.70, 0.61 +3.23, 0.00, 52.81, 47.19, 5.63 +3.23, 0.00, 50.33, 49.67, 0.66 +3.23, 0.00, 50.32, 49.68, 0.64 +3.23, 0.00, 50.31, 49.69, 0.61 +3.23, 0.00, 50.29, 49.71, 0.59 +3.16, 0.00, 52.80, 47.20, 5.61 +3.16, 0.00, 50.32, 49.68, 0.64 +3.16, 0.00, 50.31, 49.69, 0.61 +3.16, 0.00, 50.30, 49.70, 0.59 +3.16, 0.00, 50.28, 49.72, 0.57 +3.16, 0.00, 50.27, 49.73, 0.54 +3.16, 0.00, 50.26, 49.74, 0.52 +3.16, 0.00, 50.25, 49.75, 0.50 +3.16, 0.00, 50.24, 49.76, 0.47 +3.16, 0.00, 50.22, 49.78, 0.45 +3.16, 0.00, 50.21, 49.79, 0.43 +3.16, 0.00, 50.20, 49.80, 0.40 +3.16, 0.00, 50.19, 49.81, 0.38 +3.16, 0.00, 50.18, 49.82, 0.35 +3.16, 0.00, 50.17, 49.83, 0.33 +3.03, 0.00, 55.20, 44.80, 10.39 +3.03, 0.00, 50.24, 49.76, 0.48 +3.03, 0.00, 50.23, 49.77, 0.46 +3.03, 0.00, 50.22, 49.78, 0.44 +3.03, 0.00, 50.21, 49.79, 0.41 +3.03, 0.00, 50.20, 49.80, 0.39 +3.03, 0.00, 50.18, 49.82, 0.37 +3.03, 0.00, 50.17, 49.83, 0.35 +3.03, 0.00, 50.16, 49.84, 0.32 +3.03, 0.00, 50.15, 49.85, 0.30 +3.03, 0.00, 50.14, 49.86, 0.28 +3.03, 0.00, 50.13, 49.87, 0.25 +2.97, 0.00, 52.64, 47.36, 5.28 +2.97, 0.00, 50.15, 49.85, 0.31 +2.97, 0.00, 50.14, 49.86, 0.29 +2.97, 0.00, 50.13, 49.87, 0.26 +2.97, 0.00, 50.12, 49.88, 0.24 +2.90, 0.00, 52.63, 47.37, 5.26 +2.90, 0.00, 50.15, 49.85, 0.30 +2.90, 0.00, 50.14, 49.86, 0.28 +2.90, 0.00, 50.13, 49.87, 0.25 +2.77, 0.00, 55.16, 44.84, 10.32 +2.77, 0.00, 50.21, 49.79, 0.41 +2.77, 0.00, 50.19, 49.81, 0.39 +2.77, 0.00, 50.18, 49.82, 0.37 +2.77, 0.00, 50.17, 49.83, 0.35 +2.77, 0.00, 50.16, 49.84, 0.33 +2.70, 0.00, 52.68, 47.32, 5.35 +2.70, 0.00, 50.19, 49.81, 0.39 +2.70, 0.00, 50.18, 49.82, 0.37 +2.70, 0.00, 50.17, 49.83, 0.35 +2.70, 0.00, 50.16, 49.84, 0.33 +2.70, 0.00, 50.15, 49.85, 0.30 +2.64, 0.00, 52.66, 47.34, 5.33 +2.70, 0.00, 47.66, 52.34, -4.68 +2.64, 0.00, 52.64, 47.36, 5.29 +2.64, 0.00, 50.16, 49.84, 0.32 +2.64, 0.00, 50.15, 49.85, 0.30 +2.50, 0.00, 55.19, 44.81, 10.37 +2.50, 0.00, 50.23, 49.77, 0.46 +2.50, 0.00, 50.22, 49.78, 0.45 +2.50, 0.00, 50.21, 49.79, 0.43 +2.44, 0.00, 52.73, 47.27, 5.45 +2.44, 0.00, 50.24, 49.76, 0.49 +2.44, 0.00, 50.24, 49.76, 0.47 +2.44, 0.00, 50.23, 49.77, 0.45 +2.44, 0.00, 50.22, 49.78, 0.43 +2.44, 0.00, 50.21, 49.79, 0.42 +2.44, 0.00, 50.20, 49.80, 0.40 +2.44, 0.00, 50.19, 49.81, 0.38 +2.44, 0.00, 50.18, 49.82, 0.36 +2.44, 0.00, 50.17, 49.83, 0.34 +2.37, 0.00, 52.68, 47.32, 5.37 +2.37, 0.00, 50.20, 49.80, 0.41 +2.37, 0.00, 50.19, 49.81, 0.39 +2.24, 0.00, 55.23, 44.77, 10.46 +2.24, 0.00, 50.28, 49.72, 0.55 +2.24, 0.00, 50.27, 49.73, 0.54 +2.18, 0.00, 52.78, 47.22, 5.56 +2.18, 0.00, 50.30, 49.70, 0.60 +2.18, 0.00, 50.29, 49.71, 0.59 +2.18, 0.00, 50.28, 49.72, 0.57 +2.11, 0.00, 52.80, 47.20, 5.60 +2.11, 0.00, 50.32, 49.68, 0.64 +2.11, 0.00, 50.31, 49.69, 0.62 +2.11, 0.00, 50.30, 49.70, 0.60 +2.11, 0.00, 50.29, 49.71, 0.59 +1.98, 0.00, 55.33, 44.67, 10.66 +1.98, 0.00, 50.38, 49.62, 0.76 +1.98, 0.00, 50.37, 49.63, 0.74 +1.98, 0.00, 50.36, 49.64, 0.73 +1.91, 0.00, 52.88, 47.12, 5.76 +1.91, 0.00, 50.40, 49.60, 0.80 +1.91, 0.00, 50.39, 49.61, 0.78 +1.85, 0.00, 52.91, 47.09, 5.81 +1.85, 0.00, 50.43, 49.57, 0.85 +1.85, 0.00, 50.42, 49.58, 0.84 +1.85, 0.00, 50.41, 49.59, 0.83 +1.85, 0.00, 50.41, 49.59, 0.81 +1.71, 0.00, 55.44, 44.56, 10.89 +1.71, 0.00, 50.49, 49.51, 0.99 +1.71, 0.00, 50.49, 49.51, 0.97 +1.71, 0.00, 50.48, 49.52, 0.96 +1.71, 0.00, 50.47, 49.53, 0.95 +1.71, 0.00, 50.47, 49.53, 0.93 +1.65, 0.00, 52.98, 47.02, 5.96 +1.65, 0.00, 50.50, 49.50, 1.01 +1.65, 0.00, 50.50, 49.50, 1.00 +1.65, 0.00, 50.49, 49.51, 0.98 +1.65, 0.00, 50.49, 49.51, 0.97 +1.58, 0.00, 53.00, 47.00, 6.00 +1.58, 0.00, 50.52, 49.48, 1.05 +1.58, 0.00, 50.52, 49.48, 1.03 +1.45, 0.00, 55.55, 44.45, 11.11 +1.45, 0.00, 50.61, 49.39, 1.21 +1.45, 0.00, 50.60, 49.40, 1.20 +1.38, 0.00, 53.12, 46.88, 6.23 +1.38, 0.00, 50.64, 49.36, 1.28 +1.38, 0.00, 50.63, 49.37, 1.27 +1.38, 0.00, 50.63, 49.37, 1.26 +1.38, 0.00, 50.62, 49.38, 1.25 +1.32, 0.00, 53.14, 46.86, 6.28 +1.32, 0.00, 50.66, 49.34, 1.33 +1.32, 0.00, 50.66, 49.34, 1.32 +1.32, 0.00, 50.65, 49.35, 1.31 +1.32, 0.00, 50.65, 49.35, 1.30 +1.32, 0.00, 50.64, 49.36, 1.29 +1.32, 0.00, 50.64, 49.36, 1.28 +1.32, 0.00, 50.63, 49.37, 1.27 +1.32, 0.00, 50.63, 49.37, 1.26 +1.19, 0.00, 55.67, 44.33, 11.33 +1.19, 0.00, 50.72, 49.28, 1.44 +1.19, 0.00, 50.71, 49.29, 1.43 +1.19, 0.00, 50.71, 49.29, 1.42 +1.12, 0.00, 53.23, 46.77, 6.45 +1.12, 0.00, 50.75, 49.25, 1.50 +1.12, 0.00, 50.75, 49.25, 1.49 +1.12, 0.00, 50.74, 49.26, 1.48 +1.12, 0.00, 50.74, 49.26, 1.48 +1.05, 0.00, 53.25, 46.75, 6.51 +1.05, 0.00, 50.78, 49.22, 1.56 +1.05, 0.00, 50.78, 49.22, 1.55 +1.05, 0.00, 50.77, 49.23, 1.54 +1.05, 0.00, 50.77, 49.23, 1.53 +1.05, 0.00, 50.76, 49.24, 1.53 +1.05, 0.00, 50.76, 49.24, 1.52 +0.92, 0.00, 55.80, 44.20, 11.60 +1.05, 0.00, 45.81, 54.19, -8.38 +0.92, 0.00, 55.79, 44.21, 11.58 +0.92, 0.00, 50.84, 49.16, 1.69 +0.92, 0.00, 50.84, 49.16, 1.68 +0.92, 0.00, 50.84, 49.16, 1.67 +0.86, 0.00, 53.36, 46.64, 6.71 +0.86, 0.00, 50.88, 49.12, 1.76 +0.86, 0.00, 50.88, 49.12, 1.75 +0.86, 0.00, 50.87, 49.13, 1.75 +0.86, 0.00, 50.87, 49.13, 1.74 +0.86, 0.00, 50.87, 49.13, 1.73 +0.86, 0.00, 50.86, 49.14, 1.73 +0.79, 0.00, 53.38, 46.62, 6.76 +0.79, 0.00, 50.91, 49.09, 1.81 +0.79, 0.00, 50.90, 49.10, 1.81 +0.79, 0.00, 50.90, 49.10, 1.80 +0.79, 0.00, 50.90, 49.10, 1.80 +0.79, 0.00, 50.90, 49.10, 1.79 +0.66, 0.00, 55.94, 44.06, 11.87 +0.79, 0.00, 45.95, 54.05, -8.11 +0.66, 0.00, 55.93, 44.07, 11.86 +0.66, 0.00, 50.98, 49.02, 1.97 +0.66, 0.00, 50.98, 49.02, 1.96 +0.66, 0.00, 50.98, 49.02, 1.96 +0.66, 0.00, 50.98, 49.02, 1.95 +0.66, 0.00, 50.97, 49.03, 1.95 +0.66, 0.00, 50.97, 49.03, 1.94 +0.66, 0.00, 50.97, 49.03, 1.94 +0.66, 0.00, 50.97, 49.03, 1.93 +0.66, 0.00, 50.96, 49.04, 1.93 +0.59, 0.00, 53.48, 46.52, 6.97 +0.66, 0.00, 48.49, 51.51, -3.02 +0.59, 0.00, 53.48, 46.52, 6.96 +0.66, 0.00, 48.48, 51.52, -3.03 +0.59, 0.00, 53.47, 46.53, 6.95 +0.59, 0.00, 51.00, 49.00, 2.00 +0.59, 0.00, 51.00, 49.00, 2.00 +0.59, 0.00, 51.00, 49.00, 1.99 +0.59, 0.00, 50.99, 49.01, 1.99 +0.59, 0.00, 50.99, 49.01, 1.98 +0.59, 0.00, 50.99, 49.01, 1.98 +0.59, 0.00, 50.99, 49.01, 1.97 +0.59, 0.00, 50.98, 49.02, 1.97 +0.59, 0.00, 50.98, 49.02, 1.96 +0.59, 0.00, 50.98, 49.02, 1.96 +0.59, 0.00, 50.98, 49.02, 1.96 +0.59, 0.00, 50.98, 49.02, 1.95 +0.59, 0.00, 50.97, 49.03, 1.95 +0.59, 0.00, 50.97, 49.03, 1.94 +0.59, 0.00, 50.97, 49.03, 1.94 +0.59, 0.00, 50.97, 49.03, 1.93 +0.59, 0.00, 50.96, 49.04, 1.93 +0.59, 0.00, 50.96, 49.04, 1.92 +0.59, 0.00, 50.96, 49.04, 1.92 +0.66, 0.00, 48.44, 51.56, -3.13 +0.66, 0.00, 50.91, 49.09, 1.81 +0.66, 0.00, 50.90, 49.10, 1.81 +0.66, 0.00, 50.90, 49.10, 1.80 +0.66, 0.00, 50.90, 49.10, 1.80 +0.66, 0.00, 50.90, 49.10, 1.79 +0.66, 0.00, 50.89, 49.11, 1.79 +0.66, 0.00, 50.89, 49.11, 1.78 +0.66, 0.00, 50.89, 49.11, 1.78 +0.66, 0.00, 50.89, 49.11, 1.77 +0.66, 0.00, 50.88, 49.12, 1.77 +0.66, 0.00, 50.88, 49.12, 1.76 +0.79, 0.00, 45.83, 54.17, -8.33 +0.79, 0.00, 50.78, 49.22, 1.55 +0.79, 0.00, 50.77, 49.23, 1.55 +0.79, 0.00, 50.77, 49.23, 1.54 +0.79, 0.00, 50.77, 49.23, 1.53 +0.79, 0.00, 50.76, 49.24, 1.53 +0.79, 0.00, 50.76, 49.24, 1.52 +0.86, 0.00, 48.24, 51.76, -3.53 +0.86, 0.00, 50.71, 49.29, 1.41 +0.86, 0.00, 50.70, 49.30, 1.40 +0.86, 0.00, 50.70, 49.30, 1.40 +0.86, 0.00, 50.70, 49.30, 1.39 +0.86, 0.00, 50.69, 49.31, 1.38 +0.86, 0.00, 50.69, 49.31, 1.38 +0.86, 0.00, 50.69, 49.31, 1.37 +0.86, 0.00, 50.68, 49.32, 1.37 +0.86, 0.00, 50.68, 49.32, 1.36 +0.86, 0.00, 50.68, 49.32, 1.35 +0.92, 0.00, 48.15, 51.85, -3.70 +0.92, 0.00, 50.62, 49.38, 1.24 +0.92, 0.00, 50.62, 49.38, 1.23 +0.92, 0.00, 50.61, 49.39, 1.23 +0.92, 0.00, 50.61, 49.39, 1.22 +1.05, 0.00, 45.56, 54.44, -8.87 +1.05, 0.00, 50.50, 49.50, 1.01 +1.05, 0.00, 50.50, 49.50, 1.00 +1.05, 0.00, 50.49, 49.51, 0.99 +1.12, 0.00, 47.97, 52.03, -4.06 +1.12, 0.00, 50.44, 49.56, 0.87 +1.12, 0.00, 50.43, 49.57, 0.87 +1.12, 0.00, 50.43, 49.57, 0.86 +1.12, 0.00, 50.42, 49.58, 0.85 +1.12, 0.00, 50.42, 49.58, 0.84 +1.12, 0.00, 50.42, 49.58, 0.83 +1.19, 0.00, 47.89, 52.11, -4.22 +1.19, 0.00, 50.36, 49.64, 0.72 +1.19, 0.00, 50.35, 49.65, 0.71 +1.19, 0.00, 50.35, 49.65, 0.70 +1.19, 0.00, 50.34, 49.66, 0.69 +1.19, 0.00, 50.34, 49.66, 0.68 +1.32, 0.00, 45.29, 54.71, -9.42 +1.32, 0.00, 50.23, 49.77, 0.46 +1.32, 0.00, 50.23, 49.77, 0.45 +1.32, 0.00, 50.22, 49.78, 0.44 +1.32, 0.00, 50.22, 49.78, 0.43 +1.32, 0.00, 50.21, 49.79, 0.42 +1.32, 0.00, 50.21, 49.79, 0.41 +1.38, 0.00, 47.68, 52.32, -4.64 +1.38, 0.00, 50.15, 49.85, 0.29 +1.38, 0.00, 50.14, 49.86, 0.28 +1.38, 0.00, 50.14, 49.86, 0.27 +1.38, 0.00, 50.13, 49.87, 0.26 +1.38, 0.00, 50.13, 49.87, 0.25 +1.32, 0.00, 52.64, 47.36, 5.28 +1.32, 0.00, 50.17, 49.83, 0.33 +1.32, 0.00, 50.16, 49.84, 0.32 +1.32, 0.00, 50.16, 49.84, 0.31 +1.38, 0.00, 47.63, 52.37, -4.74 +1.32, 0.00, 52.62, 47.38, 5.23 +1.38, 0.00, 47.62, 52.38, -4.76 +1.38, 0.00, 50.09, 49.91, 0.17 +1.38, 0.00, 50.08, 49.92, 0.16 +1.38, 0.00, 50.08, 49.92, 0.15 +1.38, 0.00, 50.07, 49.93, 0.14 +1.38, 0.00, 50.06, 49.94, 0.13 +1.38, 0.00, 50.06, 49.94, 0.12 +1.32, 0.00, 52.58, 47.42, 5.15 +1.32, 0.00, 50.10, 49.90, 0.20 +1.32, 0.00, 50.09, 49.91, 0.19 +1.32, 0.00, 50.09, 49.91, 0.18 +1.32, 0.00, 50.08, 49.92, 0.17 +1.32, 0.00, 50.08, 49.92, 0.16 +1.32, 0.00, 50.07, 49.93, 0.15 +1.19, 0.00, 55.11, 44.89, 10.23 +1.19, 0.00, 50.16, 49.84, 0.33 +1.19, 0.00, 50.16, 49.84, 0.32 +1.19, 0.00, 50.16, 49.84, 0.31 +1.19, 0.00, 50.15, 49.85, 0.30 +1.12, 0.00, 52.67, 47.33, 5.34 +1.12, 0.00, 50.19, 49.81, 0.38 +1.12, 0.00, 50.19, 49.81, 0.38 +1.12, 0.00, 50.18, 49.82, 0.37 +1.05, 0.00, 52.70, 47.30, 5.40 +1.05, 0.00, 50.23, 49.77, 0.45 +1.05, 0.00, 50.22, 49.78, 0.44 +1.05, 0.00, 50.22, 49.78, 0.43 +1.05, 0.00, 50.21, 49.79, 0.43 +0.92, 0.00, 55.25, 44.75, 10.51 +0.92, 0.00, 50.31, 49.69, 0.61 +0.92, 0.00, 50.30, 49.70, 0.60 +0.86, 0.00, 52.82, 47.18, 5.64 +0.86, 0.00, 50.34, 49.66, 0.69 +0.86, 0.00, 50.34, 49.66, 0.68 +0.86, 0.00, 50.34, 49.66, 0.68 +0.79, 0.00, 52.86, 47.14, 5.71 +0.79, 0.00, 50.38, 49.62, 0.76 +0.79, 0.00, 50.38, 49.62, 0.76 +0.79, 0.00, 50.38, 49.62, 0.75 +0.66, 0.00, 55.42, 44.58, 10.83 +0.66, 0.00, 50.47, 49.53, 0.94 +0.66, 0.00, 50.47, 49.53, 0.93 +0.66, 0.00, 50.46, 49.54, 0.93 +0.66, 0.00, 50.46, 49.54, 0.92 +0.59, 0.00, 52.98, 47.02, 5.96 +0.66, 0.00, 47.99, 52.01, -4.03 +0.59, 0.00, 52.98, 47.02, 5.95 +0.59, 0.00, 50.50, 49.50, 1.01 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 0.99 +0.53, 0.00, 53.02, 46.98, 6.03 +0.53, 0.00, 50.54, 49.46, 1.08 +0.53, 0.00, 50.54, 49.46, 1.08 +0.53, 0.00, 50.54, 49.46, 1.08 +0.53, 0.00, 50.54, 49.46, 1.07 +0.53, 0.00, 50.53, 49.47, 1.07 +0.53, 0.00, 50.53, 49.47, 1.06 +0.53, 0.00, 50.53, 49.47, 1.06 +0.40, 0.00, 55.57, 44.43, 11.14 +0.40, 0.00, 50.63, 49.37, 1.25 +0.40, 0.00, 50.62, 49.38, 1.25 +0.40, 0.00, 50.62, 49.38, 1.25 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.24 +0.40, 0.00, 50.62, 49.38, 1.23 +0.33, 0.00, 53.14, 46.86, 6.27 +0.33, 0.00, 50.66, 49.34, 1.33 +0.33, 0.00, 50.66, 49.34, 1.32 +0.33, 0.00, 50.66, 49.34, 1.32 +0.33, 0.00, 50.66, 49.34, 1.32 +0.33, 0.00, 50.66, 49.34, 1.32 +0.40, 0.00, 48.14, 51.86, -3.73 +0.33, 0.00, 53.13, 46.87, 6.26 +0.40, 0.00, 48.13, 51.87, -3.73 +0.40, 0.00, 50.60, 49.40, 1.21 +0.40, 0.00, 50.60, 49.40, 1.20 +0.33, 0.00, 53.12, 46.88, 6.24 +0.40, 0.00, 48.13, 51.87, -3.75 +0.40, 0.00, 50.60, 49.40, 1.20 +0.40, 0.00, 50.60, 49.40, 1.19 +0.40, 0.00, 50.59, 49.41, 1.19 +0.40, 0.00, 50.59, 49.41, 1.19 +0.40, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 50.59, 49.41, 1.17 +0.40, 0.00, 50.58, 49.42, 1.17 +0.40, 0.00, 50.58, 49.42, 1.17 +0.40, 0.00, 50.58, 49.42, 1.16 +0.40, 0.00, 50.58, 49.42, 1.16 +0.40, 0.00, 50.58, 49.42, 1.16 +0.53, 0.00, 45.53, 54.47, -8.93 +0.53, 0.00, 50.48, 49.52, 0.95 +0.53, 0.00, 50.47, 49.53, 0.95 +0.53, 0.00, 50.47, 49.53, 0.94 +0.53, 0.00, 50.47, 49.53, 0.94 +0.53, 0.00, 50.47, 49.53, 0.94 +0.53, 0.00, 50.47, 49.53, 0.93 +0.53, 0.00, 50.46, 49.54, 0.93 +0.59, 0.00, 47.94, 52.06, -4.12 +0.59, 0.00, 50.41, 49.59, 0.82 +0.59, 0.00, 50.41, 49.59, 0.82 +0.59, 0.00, 50.41, 49.59, 0.81 +0.59, 0.00, 50.40, 49.60, 0.81 +0.59, 0.00, 50.40, 49.60, 0.80 +0.59, 0.00, 50.40, 49.60, 0.80 +0.66, 0.00, 47.88, 52.12, -4.25 +0.66, 0.00, 50.34, 49.66, 0.69 +0.66, 0.00, 50.34, 49.66, 0.68 +0.66, 0.00, 50.34, 49.66, 0.68 +0.66, 0.00, 50.34, 49.66, 0.67 +0.66, 0.00, 50.33, 49.67, 0.67 +0.79, 0.00, 45.29, 54.71, -9.42 +0.79, 0.00, 50.23, 49.77, 0.46 +0.79, 0.00, 50.23, 49.77, 0.45 +0.79, 0.00, 50.22, 49.78, 0.45 +0.79, 0.00, 50.22, 49.78, 0.44 +0.79, 0.00, 50.22, 49.78, 0.44 +0.86, 0.00, 47.69, 52.31, -4.61 +0.86, 0.00, 50.16, 49.84, 0.32 +0.86, 0.00, 50.16, 49.84, 0.32 +0.86, 0.00, 50.16, 49.84, 0.31 +0.86, 0.00, 50.15, 49.85, 0.30 +0.86, 0.00, 50.15, 49.85, 0.30 +0.92, 0.00, 47.62, 52.38, -4.75 +0.92, 0.00, 50.09, 49.91, 0.19 +0.92, 0.00, 50.09, 49.91, 0.18 +0.92, 0.00, 50.09, 49.91, 0.17 +0.92, 0.00, 50.08, 49.92, 0.16 +1.05, 0.00, 45.04, 54.96, -9.93 +1.05, 0.00, 49.98, 50.02, -0.05 +1.05, 0.00, 49.97, 50.03, -0.06 +1.05, 0.00, 49.97, 50.03, -0.06 +1.05, 0.00, 49.96, 50.04, -0.07 +1.05, 0.00, 49.96, 50.04, -0.08 +1.05, 0.00, 49.96, 50.04, -0.09 +1.05, 0.00, 49.95, 50.05, -0.10 +1.05, 0.00, 49.95, 50.05, -0.10 +1.05, 0.00, 49.94, 50.06, -0.11 +1.05, 0.00, 49.94, 50.06, -0.12 +1.05, 0.00, 49.94, 50.06, -0.13 +1.05, 0.00, 49.93, 50.07, -0.14 +1.12, 0.00, 47.41, 52.59, -5.19 +1.12, 0.00, 49.87, 50.13, -0.25 +1.12, 0.00, 49.87, 50.13, -0.26 +1.12, 0.00, 49.87, 50.13, -0.27 +1.12, 0.00, 49.86, 50.14, -0.28 +1.12, 0.00, 49.86, 50.14, -0.28 +1.12, 0.00, 49.85, 50.15, -0.29 +1.12, 0.00, 49.85, 50.15, -0.30 +1.05, 0.00, 52.37, 47.63, 4.73 +1.05, 0.00, 49.89, 50.11, -0.22 +1.05, 0.00, 49.89, 50.11, -0.23 +1.05, 0.00, 49.88, 50.12, -0.23 +1.05, 0.00, 49.88, 50.12, -0.24 +1.05, 0.00, 49.87, 50.13, -0.25 +1.05, 0.00, 49.87, 50.13, -0.26 +1.05, 0.00, 49.87, 50.13, -0.27 +1.05, 0.00, 49.86, 50.14, -0.27 +1.05, 0.00, 49.86, 50.14, -0.28 +0.92, 0.00, 54.90, 45.10, 9.80 +1.05, 0.00, 44.91, 55.09, -10.18 +1.05, 0.00, 49.85, 50.15, -0.30 +1.05, 0.00, 49.84, 50.16, -0.31 +0.92, 0.00, 54.88, 45.12, 9.77 +0.92, 0.00, 49.94, 50.06, -0.13 +0.92, 0.00, 49.93, 50.07, -0.14 +0.92, 0.00, 49.93, 50.07, -0.14 +0.92, 0.00, 49.93, 50.07, -0.15 +0.92, 0.00, 49.92, 50.08, -0.16 +0.92, 0.00, 49.92, 50.08, -0.16 +0.92, 0.00, 49.91, 50.09, -0.17 +0.86, 0.00, 52.43, 47.57, 4.87 +0.86, 0.00, 49.96, 50.04, -0.08 +0.86, 0.00, 49.95, 50.05, -0.09 +0.86, 0.00, 49.95, 50.05, -0.10 +0.86, 0.00, 49.95, 50.05, -0.10 +0.86, 0.00, 49.95, 50.05, -0.11 +0.86, 0.00, 49.94, 50.06, -0.12 +0.86, 0.00, 49.94, 50.06, -0.12 +0.86, 0.00, 49.94, 50.06, -0.13 +0.86, 0.00, 49.93, 50.07, -0.14 +0.86, 0.00, 49.93, 50.07, -0.14 +0.86, 0.00, 49.93, 50.07, -0.15 +0.86, 0.00, 49.92, 50.08, -0.15 +0.86, 0.00, 49.92, 50.08, -0.16 +0.86, 0.00, 49.92, 50.08, -0.17 +0.86, 0.00, 49.91, 50.09, -0.17 +0.79, 0.00, 52.43, 47.57, 4.86 +0.79, 0.00, 49.96, 50.04, -0.09 +0.86, 0.00, 47.43, 52.57, -5.14 +0.79, 0.00, 52.42, 47.58, 4.84 +0.86, 0.00, 47.43, 52.57, -5.15 +0.86, 0.00, 49.89, 50.11, -0.21 +0.86, 0.00, 49.89, 50.11, -0.22 +0.86, 0.00, 49.89, 50.11, -0.22 +0.86, 0.00, 49.88, 50.12, -0.23 +0.86, 0.00, 49.88, 50.12, -0.24 +0.86, 0.00, 49.88, 50.12, -0.24 +0.79, 0.00, 52.40, 47.60, 4.79 +0.79, 0.00, 49.92, 50.08, -0.16 +0.79, 0.00, 49.92, 50.08, -0.16 +0.79, 0.00, 49.92, 50.08, -0.17 +0.79, 0.00, 49.91, 50.09, -0.17 +0.79, 0.00, 49.91, 50.09, -0.18 +0.79, 0.00, 49.91, 50.09, -0.19 +0.79, 0.00, 49.90, 50.10, -0.19 +0.79, 0.00, 49.90, 50.10, -0.20 +0.79, 0.00, 49.90, 50.10, -0.20 +0.79, 0.00, 49.90, 50.10, -0.21 +0.79, 0.00, 49.89, 50.11, -0.22 +0.79, 0.00, 49.89, 50.11, -0.22 +0.79, 0.00, 49.89, 50.11, -0.23 +0.79, 0.00, 49.88, 50.12, -0.23 +0.79, 0.00, 49.88, 50.12, -0.24 +0.79, 0.00, 49.88, 50.12, -0.25 +0.79, 0.00, 49.87, 50.13, -0.25 +0.79, 0.00, 49.87, 50.13, -0.26 +0.79, 0.00, 49.87, 50.13, -0.26 +0.79, 0.00, 49.87, 50.13, -0.27 +0.79, 0.00, 49.86, 50.14, -0.28 +0.79, 0.00, 49.86, 50.14, -0.28 +0.66, 0.00, 54.90, 45.10, 9.80 +0.66, 0.00, 49.95, 50.05, -0.09 +0.66, 0.00, 49.95, 50.05, -0.10 +0.66, 0.00, 49.95, 50.05, -0.10 +0.66, 0.00, 49.95, 50.05, -0.11 +0.66, 0.00, 49.94, 50.06, -0.11 +0.66, 0.00, 49.94, 50.06, -0.12 +0.66, 0.00, 49.94, 50.06, -0.12 +0.66, 0.00, 49.94, 50.06, -0.13 +0.66, 0.00, 49.93, 50.07, -0.13 +0.79, 0.00, 44.89, 55.11, -10.22 +0.79, 0.00, 49.83, 50.17, -0.34 +0.66, 0.00, 54.87, 45.13, 9.74 +0.66, 0.00, 49.92, 50.08, -0.15 +0.66, 0.00, 49.92, 50.08, -0.16 +0.66, 0.00, 49.92, 50.08, -0.16 +0.66, 0.00, 49.92, 50.08, -0.17 +0.66, 0.00, 49.91, 50.09, -0.17 +0.66, 0.00, 49.91, 50.09, -0.18 +0.66, 0.00, 49.91, 50.09, -0.18 +0.66, 0.00, 49.91, 50.09, -0.19 +0.66, 0.00, 49.90, 50.10, -0.19 +0.66, 0.00, 49.90, 50.10, -0.20 +0.66, 0.00, 49.90, 50.10, -0.20 +0.66, 0.00, 49.90, 50.10, -0.21 +0.66, 0.00, 49.89, 50.11, -0.21 +0.66, 0.00, 49.89, 50.11, -0.22 +0.66, 0.00, 49.89, 50.11, -0.22 +0.66, 0.00, 49.89, 50.11, -0.23 +0.66, 0.00, 49.88, 50.12, -0.23 +0.66, 0.00, 49.88, 50.12, -0.24 +0.66, 0.00, 49.88, 50.12, -0.24 +0.66, 0.00, 49.88, 50.12, -0.25 +0.66, 0.00, 49.87, 50.13, -0.25 +0.66, 0.00, 49.87, 50.13, -0.26 +0.59, 0.00, 52.39, 47.61, 4.78 +0.59, 0.00, 49.92, 50.08, -0.17 +0.59, 0.00, 49.91, 50.09, -0.17 +0.59, 0.00, 49.91, 50.09, -0.18 +0.59, 0.00, 49.91, 50.09, -0.18 +0.59, 0.00, 49.91, 50.09, -0.19 +0.59, 0.00, 49.90, 50.10, -0.19 +0.59, 0.00, 49.90, 50.10, -0.19 +0.59, 0.00, 49.90, 50.10, -0.20 +0.59, 0.00, 49.90, 50.10, -0.20 +0.59, 0.00, 49.90, 50.10, -0.21 +0.59, 0.00, 49.89, 50.11, -0.21 +0.59, 0.00, 49.89, 50.11, -0.22 +0.59, 0.00, 49.89, 50.11, -0.22 +0.59, 0.00, 49.89, 50.11, -0.23 +0.59, 0.00, 49.88, 50.12, -0.23 +0.59, 0.00, 49.88, 50.12, -0.23 +0.59, 0.00, 49.88, 50.12, -0.24 +0.53, 0.00, 52.40, 47.60, 4.80 +0.53, 0.00, 49.93, 50.07, -0.15 +0.53, 0.00, 49.92, 50.08, -0.15 +0.53, 0.00, 49.92, 50.08, -0.16 +0.53, 0.00, 49.92, 50.08, -0.16 +0.53, 0.00, 49.92, 50.08, -0.16 +0.53, 0.00, 49.92, 50.08, -0.17 +0.53, 0.00, 49.91, 50.09, -0.17 +0.53, 0.00, 49.91, 50.09, -0.18 +0.53, 0.00, 49.91, 50.09, -0.18 +0.53, 0.00, 49.91, 50.09, -0.18 +0.53, 0.00, 49.91, 50.09, -0.19 +0.53, 0.00, 49.90, 50.10, -0.19 +0.53, 0.00, 49.90, 50.10, -0.20 +0.53, 0.00, 49.90, 50.10, -0.20 +0.40, 0.00, 54.94, 45.06, 9.88 +0.40, 0.00, 50.00, 50.00, -0.01 +0.40, 0.00, 49.99, 50.01, -0.01 +0.40, 0.00, 49.99, 50.01, -0.01 +0.40, 0.00, 49.99, 50.01, -0.02 +0.40, 0.00, 49.99, 50.01, -0.02 +0.40, 0.00, 49.99, 50.01, -0.02 +0.40, 0.00, 49.99, 50.01, -0.03 +0.40, 0.00, 49.99, 50.01, -0.03 +0.40, 0.00, 49.98, 50.02, -0.03 +0.40, 0.00, 49.98, 50.02, -0.03 +0.40, 0.00, 49.98, 50.02, -0.04 +0.40, 0.00, 49.98, 50.02, -0.04 +0.40, 0.00, 49.98, 50.02, -0.04 +0.40, 0.00, 49.98, 50.02, -0.05 +0.40, 0.00, 49.98, 50.02, -0.05 +0.33, 0.00, 52.50, 47.50, 4.99 +0.33, 0.00, 50.02, 49.98, 0.04 +0.33, 0.00, 50.02, 49.98, 0.04 +0.33, 0.00, 50.02, 49.98, 0.04 +0.33, 0.00, 50.02, 49.98, 0.04 +0.33, 0.00, 50.02, 49.98, 0.03 +0.26, 0.00, 52.54, 47.46, 5.08 +0.26, 0.00, 50.06, 49.94, 0.13 +0.26, 0.00, 50.06, 49.94, 0.13 +0.26, 0.00, 50.06, 49.94, 0.13 +0.26, 0.00, 50.06, 49.94, 0.12 +0.26, 0.00, 50.06, 49.94, 0.12 +0.26, 0.00, 50.06, 49.94, 0.12 +0.26, 0.00, 50.06, 49.94, 0.12 +0.33, 0.00, 47.54, 52.46, -4.93 +0.26, 0.00, 52.53, 47.47, 5.06 +0.26, 0.00, 50.06, 49.94, 0.11 +0.26, 0.00, 50.05, 49.95, 0.11 +0.26, 0.00, 50.05, 49.95, 0.11 +0.26, 0.00, 50.05, 49.95, 0.11 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.10 +0.26, 0.00, 50.05, 49.95, 0.09 +0.26, 0.00, 50.05, 49.95, 0.09 +0.26, 0.00, 50.04, 49.96, 0.09 +0.26, 0.00, 50.04, 49.96, 0.09 +0.26, 0.00, 50.04, 49.96, 0.09 +0.26, 0.00, 50.04, 49.96, 0.08 +0.26, 0.00, 50.04, 49.96, 0.08 +0.26, 0.00, 50.04, 49.96, 0.08 +0.26, 0.00, 50.04, 49.96, 0.08 +0.13, 0.00, 55.08, 44.92, 10.16 +0.13, 0.00, 50.14, 49.86, 0.27 +0.13, 0.00, 50.14, 49.86, 0.27 +0.13, 0.00, 50.14, 49.86, 0.27 +0.13, 0.00, 50.14, 49.86, 0.27 +0.13, 0.00, 50.13, 49.87, 0.27 +0.07, 0.00, 52.66, 47.34, 5.31 +0.13, 0.00, 47.66, 52.34, -4.68 +0.07, 0.00, 52.66, 47.34, 5.31 +0.07, 0.00, 50.18, 49.82, 0.37 +0.13, 0.00, 47.66, 52.34, -4.68 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.13, 0.00, 50.13, 49.87, 0.26 +0.07, 0.00, 52.65, 47.35, 5.30 +0.07, 0.00, 50.18, 49.82, 0.36 +0.07, 0.00, 50.18, 49.82, 0.36 +0.00, 0.00, 52.70, 47.30, 5.40 +0.00, 0.00, 50.23, 49.77, 0.46 +0.00, 0.00, 50.23, 49.77, 0.46 +0.00, 0.00, 50.23, 49.77, 0.46 +0.00, 0.00, 50.23, 49.77, 0.46 +-0.13, 0.00, 55.27, 44.73, 10.54 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.13, 0.00, 50.33, 49.67, 0.66 +-0.20, 0.00, 52.85, 47.15, 5.71 +-0.20, 0.00, 50.38, 49.62, 0.77 +-0.26, 0.00, 52.91, 47.09, 5.81 +-0.26, 0.00, 50.43, 49.57, 0.87 +-0.26, 0.00, 50.44, 49.56, 0.87 +-0.26, 0.00, 50.44, 49.56, 0.87 +-0.40, 0.00, 55.48, 44.52, 10.96 +-0.40, 0.00, 50.54, 49.46, 1.08 +-0.40, 0.00, 50.54, 49.46, 1.08 +-0.40, 0.00, 50.54, 49.46, 1.08 +-0.40, 0.00, 50.54, 49.46, 1.09 +-0.40, 0.00, 50.54, 49.46, 1.09 +-0.40, 0.00, 50.55, 49.45, 1.09 +-0.40, 0.00, 50.55, 49.45, 1.09 +-0.40, 0.00, 50.55, 49.45, 1.10 +-0.40, 0.00, 50.55, 49.45, 1.10 +-0.40, 0.00, 50.55, 49.45, 1.10 +-0.46, 0.00, 53.08, 46.93, 6.15 +-0.46, 0.00, 50.60, 49.40, 1.21 +-0.46, 0.00, 50.61, 49.39, 1.21 +-0.46, 0.00, 50.61, 49.39, 1.22 +-0.53, 0.00, 53.13, 46.87, 6.26 +-0.53, 0.00, 50.66, 49.34, 1.32 +-0.53, 0.00, 50.66, 49.34, 1.33 +-0.53, 0.00, 50.67, 49.33, 1.33 +-0.53, 0.00, 50.67, 49.33, 1.34 +-0.53, 0.00, 50.67, 49.33, 1.34 +-0.53, 0.00, 50.67, 49.33, 1.34 +-0.53, 0.00, 50.67, 49.33, 1.35 +-0.53, 0.00, 50.68, 49.32, 1.35 +-0.66, 0.00, 55.72, 44.28, 11.44 +-0.53, 0.00, 45.74, 54.26, -8.53 +-0.66, 0.00, 55.73, 44.27, 11.45 +-0.53, 0.00, 45.74, 54.26, -8.52 +-0.66, 0.00, 55.73, 44.27, 11.46 +-0.66, 0.00, 50.79, 49.21, 1.58 +-0.66, 0.00, 50.79, 49.21, 1.58 +-0.66, 0.00, 50.79, 49.21, 1.59 +-0.66, 0.00, 50.80, 49.20, 1.59 +-0.66, 0.00, 50.80, 49.20, 1.60 +-0.66, 0.00, 50.80, 49.20, 1.60 +-0.66, 0.00, 50.80, 49.20, 1.61 +-0.66, 0.00, 50.81, 49.19, 1.61 +-0.66, 0.00, 50.81, 49.19, 1.62 +-0.66, 0.00, 50.81, 49.19, 1.62 +-0.66, 0.00, 50.81, 49.19, 1.63 +-0.66, 0.00, 50.82, 49.18, 1.63 +-0.66, 0.00, 50.82, 49.18, 1.64 +-0.66, 0.00, 50.82, 49.18, 1.64 +-0.66, 0.00, 50.82, 49.18, 1.65 +-0.53, 0.00, 45.78, 54.22, -8.44 +-0.53, 0.00, 50.73, 49.27, 1.46 +-0.66, 0.00, 55.77, 44.23, 11.55 +-0.53, 0.00, 45.79, 54.21, -8.42 +-0.53, 0.00, 50.73, 49.27, 1.47 +-0.53, 0.00, 50.74, 49.26, 1.47 +-0.53, 0.00, 50.74, 49.26, 1.48 +-0.53, 0.00, 50.74, 49.26, 1.48 +-0.53, 0.00, 50.74, 49.26, 1.48 +-0.53, 0.00, 50.74, 49.26, 1.49 +-0.53, 0.00, 50.75, 49.25, 1.49 +-0.53, 0.00, 50.75, 49.25, 1.50 +-0.53, 0.00, 50.75, 49.25, 1.50 +-0.53, 0.00, 50.75, 49.25, 1.50 +-0.53, 0.00, 50.75, 49.25, 1.51 +-0.53, 0.00, 50.76, 49.24, 1.51 +-0.46, 0.00, 48.24, 51.76, -3.53 +-0.46, 0.00, 50.71, 49.29, 1.42 +-0.46, 0.00, 50.71, 49.29, 1.42 +-0.46, 0.00, 50.71, 49.29, 1.43 +-0.46, 0.00, 50.72, 49.28, 1.43 +-0.46, 0.00, 50.72, 49.28, 1.43 +-0.46, 0.00, 50.72, 49.28, 1.44 +-0.46, 0.00, 50.72, 49.28, 1.44 +-0.46, 0.00, 50.72, 49.28, 1.44 +-0.46, 0.00, 50.72, 49.28, 1.45 +-0.46, 0.00, 50.73, 49.27, 1.45 +-0.40, 0.00, 48.21, 51.79, -3.59 +-0.40, 0.00, 50.68, 49.32, 1.36 +-0.40, 0.00, 50.68, 49.32, 1.36 +-0.40, 0.00, 50.68, 49.32, 1.36 +-0.40, 0.00, 50.68, 49.32, 1.37 +-0.40, 0.00, 50.69, 49.31, 1.37 +-0.40, 0.00, 50.69, 49.31, 1.37 +-0.26, 0.00, 45.64, 54.36, -8.71 +-0.40, 0.00, 55.63, 44.37, 11.27 +-0.40, 0.00, 50.69, 49.31, 1.38 +-0.40, 0.00, 50.69, 49.31, 1.38 +-0.40, 0.00, 50.69, 49.31, 1.39 +-0.40, 0.00, 50.70, 49.30, 1.39 +-0.40, 0.00, 50.70, 49.30, 1.39 +-0.26, 0.00, 45.65, 54.35, -8.69 +-0.40, 0.00, 55.64, 44.36, 11.29 +-0.26, 0.00, 45.66, 54.34, -8.69 +-0.26, 0.00, 50.60, 49.40, 1.20 +-0.26, 0.00, 50.60, 49.40, 1.21 +-0.26, 0.00, 50.60, 49.40, 1.21 +-0.26, 0.00, 50.61, 49.39, 1.21 +-0.26, 0.00, 50.61, 49.39, 1.21 +-0.26, 0.00, 50.61, 49.39, 1.21 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.22 +-0.26, 0.00, 50.61, 49.39, 1.23 +-0.26, 0.00, 50.61, 49.39, 1.23 +-0.26, 0.00, 50.61, 49.39, 1.23 +-0.26, 0.00, 50.62, 49.38, 1.23 +-0.26, 0.00, 50.62, 49.38, 1.23 +-0.26, 0.00, 50.62, 49.38, 1.24 +-0.40, 0.00, 55.66, 44.34, 11.32 +-0.26, 0.00, 45.68, 54.32, -8.65 +-0.40, 0.00, 55.66, 44.34, 11.33 +-0.40, 0.00, 50.72, 49.28, 1.44 +-0.40, 0.00, 50.72, 49.28, 1.45 +-0.40, 0.00, 50.73, 49.27, 1.45 +-0.40, 0.00, 50.73, 49.27, 1.45 +-0.40, 0.00, 50.73, 49.27, 1.46 +-0.40, 0.00, 50.73, 49.27, 1.46 +-0.40, 0.00, 50.73, 49.27, 1.46 +-0.40, 0.00, 50.73, 49.27, 1.47 +-0.40, 0.00, 50.73, 49.27, 1.47 +-0.46, 0.00, 53.26, 46.74, 6.51 +-0.46, 0.00, 50.79, 49.21, 1.57 +-0.46, 0.00, 50.79, 49.21, 1.58 +-0.46, 0.00, 50.79, 49.21, 1.58 +-0.46, 0.00, 50.79, 49.21, 1.58 +-0.46, 0.00, 50.79, 49.21, 1.59 +-0.46, 0.00, 50.80, 49.20, 1.59 +-0.46, 0.00, 50.80, 49.20, 1.59 +-0.46, 0.00, 50.80, 49.20, 1.60 +-0.46, 0.00, 50.80, 49.20, 1.60 +-0.53, 0.00, 53.32, 46.68, 6.65 +-0.53, 0.00, 50.85, 49.15, 1.71 +-0.53, 0.00, 50.86, 49.14, 1.71 +-0.53, 0.00, 50.86, 49.14, 1.72 +-0.53, 0.00, 50.86, 49.14, 1.72 +-0.53, 0.00, 50.86, 49.14, 1.72 +-0.53, 0.00, 50.86, 49.14, 1.73 +-0.53, 0.00, 50.87, 49.13, 1.73 +-0.53, 0.00, 50.87, 49.13, 1.74 +-0.53, 0.00, 50.87, 49.13, 1.74 +-0.53, 0.00, 50.87, 49.13, 1.74 +-0.66, 0.00, 55.92, 44.08, 11.83 +-0.66, 0.00, 50.98, 49.02, 1.95 +-0.66, 0.00, 50.98, 49.02, 1.96 +-0.66, 0.00, 50.98, 49.02, 1.96 +-0.66, 0.00, 50.98, 49.02, 1.97 +-0.66, 0.00, 50.99, 49.01, 1.97 +-0.66, 0.00, 50.99, 49.01, 1.98 +-0.66, 0.00, 50.99, 49.01, 1.98 +-0.66, 0.00, 50.99, 49.01, 1.99 +-0.66, 0.00, 51.00, 49.00, 1.99 +-0.66, 0.00, 51.00, 49.00, 2.00 +-0.66, 0.00, 51.00, 49.00, 2.00 +-0.66, 0.00, 51.00, 49.00, 2.01 +-0.66, 0.00, 51.01, 48.99, 2.01 +-0.66, 0.00, 51.01, 48.99, 2.02 +-0.66, 0.00, 51.01, 48.99, 2.02 +-0.66, 0.00, 51.01, 48.99, 2.03 +-0.66, 0.00, 51.02, 48.98, 2.03 +-0.66, 0.00, 51.02, 48.98, 2.04 +-0.66, 0.00, 51.02, 48.98, 2.04 +-0.66, 0.00, 51.02, 48.98, 2.05 +-0.66, 0.00, 51.03, 48.97, 2.05 +-0.66, 0.00, 51.03, 48.97, 2.06 +-0.66, 0.00, 51.03, 48.97, 2.06 +-0.66, 0.00, 51.03, 48.97, 2.07 +-0.66, 0.00, 51.04, 48.96, 2.07 +-0.66, 0.00, 51.04, 48.96, 2.08 +-0.66, 0.00, 51.04, 48.96, 2.08 +-0.66, 0.00, 51.04, 48.96, 2.09 +-0.66, 0.00, 51.05, 48.95, 2.09 +-0.66, 0.00, 51.05, 48.95, 2.10 +-0.66, 0.00, 51.05, 48.95, 2.10 +-0.66, 0.00, 51.05, 48.95, 2.10 +-0.66, 0.00, 51.05, 48.95, 2.11 +-0.66, 0.00, 51.06, 48.94, 2.11 +-0.66, 0.00, 51.06, 48.94, 2.12 +-0.66, 0.00, 51.06, 48.94, 2.12 +-0.66, 0.00, 51.06, 48.94, 2.13 +-0.66, 0.00, 51.07, 48.93, 2.13 +-0.66, 0.00, 51.07, 48.93, 2.14 +-0.66, 0.00, 51.07, 48.93, 2.14 +-0.66, 0.00, 51.07, 48.93, 2.15 +-0.66, 0.00, 51.08, 48.92, 2.15 +-0.66, 0.00, 51.08, 48.92, 2.16 +-0.66, 0.00, 51.08, 48.92, 2.16 +-0.66, 0.00, 51.08, 48.92, 2.17 +-0.66, 0.00, 51.09, 48.91, 2.17 +-0.66, 0.00, 51.09, 48.91, 2.18 +-0.66, 0.00, 51.09, 48.91, 2.18 +-0.66, 0.00, 51.09, 48.91, 2.19 +-0.66, 0.00, 51.10, 48.90, 2.19 +-0.66, 0.00, 51.10, 48.90, 2.20 +-0.53, 0.00, 46.06, 53.94, -7.88 +-0.66, 0.00, 56.05, 43.95, 12.10 +-0.66, 0.00, 51.11, 48.89, 2.21 +-0.66, 0.00, 51.11, 48.89, 2.22 +-0.66, 0.00, 51.11, 48.89, 2.22 +-0.66, 0.00, 51.11, 48.89, 2.23 +-0.66, 0.00, 51.12, 48.88, 2.23 +-0.66, 0.00, 51.12, 48.88, 2.24 +-0.66, 0.00, 51.12, 48.88, 2.24 +-0.66, 0.00, 51.12, 48.88, 2.25 +-0.66, 0.00, 51.13, 48.87, 2.25 +-0.66, 0.00, 51.13, 48.87, 2.26 +-0.53, 0.00, 46.09, 53.91, -7.82 +-0.66, 0.00, 56.08, 43.92, 12.15 +-0.66, 0.00, 51.14, 48.86, 2.27 +-0.66, 0.00, 51.14, 48.86, 2.28 +-0.53, 0.00, 46.10, 53.90, -7.81 +-0.66, 0.00, 56.09, 43.91, 12.17 +-0.66, 0.00, 51.14, 48.86, 2.29 +-0.66, 0.00, 51.15, 48.85, 2.29 +-0.66, 0.00, 51.15, 48.85, 2.30 +-0.66, 0.00, 51.15, 48.85, 2.30 +-0.66, 0.00, 51.15, 48.85, 2.31 +-0.66, 0.00, 51.16, 48.84, 2.31 +-0.66, 0.00, 51.16, 48.84, 2.32 +-0.66, 0.00, 51.16, 48.84, 2.32 +-0.66, 0.00, 51.16, 48.84, 2.33 +-0.66, 0.00, 51.17, 48.83, 2.33 +-0.66, 0.00, 51.17, 48.83, 2.34 +-0.66, 0.00, 51.17, 48.83, 2.34 +-0.66, 0.00, 51.17, 48.83, 2.35 +-0.66, 0.00, 51.18, 48.82, 2.35 +-0.66, 0.00, 51.18, 48.82, 2.36 +-0.66, 0.00, 51.18, 48.82, 2.36 +-0.66, 0.00, 51.18, 48.82, 2.37 +-0.66, 0.00, 51.19, 48.81, 2.37 +-0.66, 0.00, 51.19, 48.81, 2.38 +-0.66, 0.00, 51.19, 48.81, 2.38 +-0.66, 0.00, 51.19, 48.81, 2.39 +-0.66, 0.00, 51.20, 48.80, 2.39 +-0.66, 0.00, 51.20, 48.80, 2.40 +-0.66, 0.00, 51.20, 48.80, 2.40 +-0.66, 0.00, 51.20, 48.80, 2.41 +-0.66, 0.00, 51.21, 48.79, 2.41 +-0.66, 0.00, 51.21, 48.79, 2.42 +-0.73, 0.00, 53.73, 46.27, 7.47 +-0.73, 0.00, 51.26, 48.74, 2.53 +-0.73, 0.00, 51.27, 48.73, 2.53 +-0.66, 0.00, 48.75, 51.25, -2.50 +-0.73, 0.00, 53.74, 46.26, 7.49 +-0.73, 0.00, 51.27, 48.73, 2.55 +-0.73, 0.00, 51.28, 48.72, 2.55 +-0.73, 0.00, 51.28, 48.72, 2.56 +-0.73, 0.00, 51.28, 48.72, 2.57 +-0.73, 0.00, 51.29, 48.71, 2.57 +-0.73, 0.00, 51.29, 48.71, 2.58 +-0.73, 0.00, 51.29, 48.71, 2.58 +-0.73, 0.00, 51.29, 48.71, 2.59 +-0.73, 0.00, 51.30, 48.70, 2.59 +-0.73, 0.00, 51.30, 48.70, 2.60 +-0.73, 0.00, 51.30, 48.70, 2.60 +-0.73, 0.00, 51.30, 48.70, 2.61 +-0.79, 0.00, 53.83, 46.17, 7.66 +-0.73, 0.00, 48.84, 51.16, -2.32 +-0.73, 0.00, 51.31, 48.69, 2.63 +-0.73, 0.00, 51.32, 48.68, 2.63 +-0.73, 0.00, 51.32, 48.68, 2.64 +-0.79, 0.00, 53.84, 46.16, 7.69 +-0.79, 0.00, 51.37, 48.63, 2.75 +-0.79, 0.00, 51.38, 48.62, 2.75 +-0.79, 0.00, 51.38, 48.62, 2.76 +-0.79, 0.00, 51.38, 48.62, 2.77 +-0.79, 0.00, 51.39, 48.61, 2.77 +-0.79, 0.00, 51.39, 48.61, 2.78 +-0.79, 0.00, 51.39, 48.61, 2.78 +-0.79, 0.00, 51.39, 48.61, 2.79 +-0.92, 0.00, 56.44, 43.56, 12.88 +-0.92, 0.00, 51.50, 48.50, 3.00 +-0.92, 0.00, 51.50, 48.50, 3.01 +-0.92, 0.00, 51.51, 48.49, 3.01 +-0.92, 0.00, 51.51, 48.49, 3.02 +-0.92, 0.00, 51.51, 48.49, 3.03 +-0.92, 0.00, 51.52, 48.48, 3.04 +-0.79, 0.00, 46.48, 53.52, -7.04 +-0.79, 0.00, 51.42, 48.58, 2.85 +-0.79, 0.00, 51.43, 48.57, 2.86 +-0.79, 0.00, 51.43, 48.57, 2.86 +-0.79, 0.00, 51.43, 48.57, 2.87 +-0.79, 0.00, 51.44, 48.56, 2.87 +-0.92, 0.00, 56.48, 43.52, 12.97 +-0.92, 0.00, 51.54, 48.46, 3.08 +-0.92, 0.00, 51.55, 48.45, 3.09 +-0.92, 0.00, 51.55, 48.45, 3.10 +-0.92, 0.00, 51.55, 48.45, 3.11 +-0.92, 0.00, 51.56, 48.44, 3.11 +-0.92, 0.00, 51.56, 48.44, 3.12 +-0.92, 0.00, 51.56, 48.44, 3.13 +-0.92, 0.00, 51.57, 48.43, 3.13 +-0.92, 0.00, 51.57, 48.43, 3.14 +-0.92, 0.00, 51.57, 48.43, 3.15 +-0.92, 0.00, 51.58, 48.42, 3.15 +-0.92, 0.00, 51.58, 48.42, 3.16 +-0.92, 0.00, 51.58, 48.42, 3.17 +-0.92, 0.00, 51.59, 48.41, 3.17 +-0.92, 0.00, 51.59, 48.41, 3.18 +-0.92, 0.00, 51.59, 48.41, 3.19 +-0.92, 0.00, 51.60, 48.40, 3.20 +-0.92, 0.00, 51.60, 48.40, 3.20 +-0.92, 0.00, 51.60, 48.40, 3.21 +-0.92, 0.00, 51.61, 48.39, 3.22 +-0.99, 0.00, 54.13, 45.87, 8.27 +-0.99, 0.00, 51.67, 48.33, 3.33 +-0.99, 0.00, 51.67, 48.33, 3.34 +-0.99, 0.00, 51.67, 48.33, 3.34 +-0.99, 0.00, 51.68, 48.32, 3.35 +-0.99, 0.00, 51.68, 48.32, 3.36 +-0.99, 0.00, 51.68, 48.32, 3.37 +-0.99, 0.00, 51.69, 48.31, 3.37 +-0.99, 0.00, 51.69, 48.31, 3.38 +-0.99, 0.00, 51.69, 48.31, 3.39 +-0.92, 0.00, 49.18, 50.82, -1.65 +-0.92, 0.00, 51.65, 48.35, 3.30 +-0.92, 0.00, 51.66, 48.34, 3.31 +-0.92, 0.00, 51.66, 48.34, 3.32 +-0.92, 0.00, 51.66, 48.34, 3.33 +-0.92, 0.00, 51.67, 48.33, 3.33 +-0.92, 0.00, 51.67, 48.33, 3.34 +-0.99, 0.00, 54.19, 45.81, 8.39 +-0.99, 0.00, 51.73, 48.27, 3.45 +-0.99, 0.00, 51.73, 48.27, 3.46 +-0.99, 0.00, 51.73, 48.27, 3.47 +-0.99, 0.00, 51.74, 48.26, 3.47 +-0.99, 0.00, 51.74, 48.26, 3.48 +-0.99, 0.00, 51.74, 48.26, 3.49 +-0.99, 0.00, 51.75, 48.25, 3.50 +-0.99, 0.00, 51.75, 48.25, 3.50 +-0.92, 0.00, 49.23, 50.77, -1.53 +-0.99, 0.00, 54.23, 45.77, 8.46 +-0.92, 0.00, 49.24, 50.76, -1.52 +-0.92, 0.00, 51.72, 48.28, 3.43 +-0.92, 0.00, 51.72, 48.28, 3.44 +-0.92, 0.00, 51.72, 48.28, 3.45 +-0.92, 0.00, 51.73, 48.27, 3.45 +-0.92, 0.00, 51.73, 48.27, 3.46 +-0.92, 0.00, 51.73, 48.27, 3.47 +-0.79, 0.00, 46.69, 53.31, -6.61 +-0.79, 0.00, 51.64, 48.36, 3.28 +-0.79, 0.00, 51.64, 48.36, 3.29 +-0.79, 0.00, 51.65, 48.35, 3.29 +-0.79, 0.00, 51.65, 48.35, 3.30 +-0.79, 0.00, 51.65, 48.35, 3.31 +-0.79, 0.00, 51.66, 48.34, 3.31 +-0.79, 0.00, 51.66, 48.34, 3.32 +-0.73, 0.00, 49.14, 50.86, -1.72 +-0.73, 0.00, 51.62, 48.38, 3.23 +-0.73, 0.00, 51.62, 48.38, 3.24 +-0.66, 0.00, 49.10, 50.90, -1.80 +-0.66, 0.00, 51.57, 48.43, 3.15 +-0.66, 0.00, 51.58, 48.42, 3.15 +-0.66, 0.00, 51.58, 48.42, 3.16 +-0.53, 0.00, 46.54, 53.46, -6.92 +-0.66, 0.00, 56.53, 43.47, 13.05 +-0.53, 0.00, 46.54, 53.46, -6.92 +-0.53, 0.00, 51.49, 48.51, 2.98 +-0.53, 0.00, 51.49, 48.51, 2.98 +-0.53, 0.00, 51.49, 48.51, 2.98 +-0.53, 0.00, 51.49, 48.51, 2.99 +-0.53, 0.00, 51.50, 48.50, 2.99 +-0.46, 0.00, 48.98, 51.02, -2.05 +-0.46, 0.00, 51.45, 48.55, 2.90 +-0.46, 0.00, 51.45, 48.55, 2.90 +-0.40, 0.00, 48.93, 51.07, -2.14 +-0.40, 0.00, 51.40, 48.60, 2.81 +-0.40, 0.00, 51.41, 48.59, 2.81 +-0.26, 0.00, 46.36, 53.64, -7.27 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.26, 0.00, 51.31, 48.69, 2.62 +-0.20, 0.00, 48.79, 51.21, -2.42 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.20, 0.00, 51.26, 48.74, 2.53 +-0.20, 0.00, 51.27, 48.73, 2.53 +-0.20, 0.00, 51.27, 48.73, 2.53 +-0.20, 0.00, 51.27, 48.73, 2.53 +-0.20, 0.00, 51.27, 48.73, 2.53 +-0.13, 0.00, 48.75, 51.25, -2.51 +-0.13, 0.00, 51.22, 48.78, 2.44 +-0.13, 0.00, 51.22, 48.78, 2.44 +0.00, 0.00, 46.18, 53.82, -7.65 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.00, 0.00, 51.12, 48.88, 2.24 +0.07, 0.00, 48.60, 51.40, -2.80 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.07, 0.00, 51.07, 48.93, 2.14 +0.13, 0.00, 48.55, 51.45, -2.91 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.04 +0.13, 0.00, 51.02, 48.98, 2.03 +0.26, 0.00, 45.97, 54.03, -8.05 +0.26, 0.00, 50.92, 49.08, 1.83 +0.26, 0.00, 50.92, 49.08, 1.83 +0.26, 0.00, 50.91, 49.09, 1.83 +0.26, 0.00, 50.91, 49.09, 1.83 +0.33, 0.00, 48.39, 51.61, -3.22 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.72 +0.33, 0.00, 50.86, 49.14, 1.71 +0.33, 0.00, 50.86, 49.14, 1.71 +0.33, 0.00, 50.85, 49.15, 1.71 +0.33, 0.00, 50.85, 49.15, 1.71 +0.33, 0.00, 50.85, 49.15, 1.70 +0.33, 0.00, 50.85, 49.15, 1.70 +0.40, 0.00, 48.33, 51.67, -3.34 +0.40, 0.00, 50.80, 49.20, 1.60 +0.40, 0.00, 50.80, 49.20, 1.59 +0.40, 0.00, 50.80, 49.20, 1.59 +0.53, 0.00, 45.75, 54.25, -8.50 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.38 +0.53, 0.00, 50.69, 49.31, 1.37 +0.53, 0.00, 50.68, 49.32, 1.37 +0.53, 0.00, 50.68, 49.32, 1.36 +0.53, 0.00, 50.68, 49.32, 1.36 +0.53, 0.00, 50.68, 49.32, 1.36 +0.53, 0.00, 50.68, 49.32, 1.35 +0.40, 0.00, 55.72, 44.28, 11.44 +0.40, 0.00, 50.77, 49.23, 1.54 +0.53, 0.00, 45.73, 54.27, -8.54 +0.40, 0.00, 55.71, 44.29, 11.43 +0.53, 0.00, 45.72, 54.28, -8.55 +0.53, 0.00, 50.67, 49.33, 1.33 +0.53, 0.00, 50.66, 49.34, 1.33 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.32 +0.53, 0.00, 50.66, 49.34, 1.31 +0.53, 0.00, 50.65, 49.35, 1.31 +0.53, 0.00, 50.65, 49.35, 1.30 +0.53, 0.00, 50.65, 49.35, 1.30 +0.53, 0.00, 50.65, 49.35, 1.30 +0.53, 0.00, 50.65, 49.35, 1.29 +0.53, 0.00, 50.64, 49.36, 1.29 +0.40, 0.00, 55.69, 44.31, 11.37 +0.40, 0.00, 50.74, 49.26, 1.48 +0.40, 0.00, 50.74, 49.26, 1.48 +0.40, 0.00, 50.74, 49.26, 1.47 +0.40, 0.00, 50.74, 49.26, 1.47 +0.40, 0.00, 50.73, 49.27, 1.47 +0.40, 0.00, 50.73, 49.27, 1.47 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.46 +0.40, 0.00, 50.73, 49.27, 1.45 +0.40, 0.00, 50.73, 49.27, 1.45 +0.40, 0.00, 50.72, 49.28, 1.45 +0.40, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 50.72, 49.28, 1.44 +0.40, 0.00, 50.72, 49.28, 1.43 +0.40, 0.00, 50.72, 49.28, 1.43 +0.40, 0.00, 50.71, 49.29, 1.43 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.42 +0.40, 0.00, 50.71, 49.29, 1.41 +0.40, 0.00, 50.70, 49.30, 1.41 +0.40, 0.00, 50.70, 49.30, 1.41 +0.40, 0.00, 50.70, 49.30, 1.40 +0.40, 0.00, 50.70, 49.30, 1.40 +0.40, 0.00, 50.70, 49.30, 1.40 +0.40, 0.00, 50.70, 49.30, 1.39 +0.40, 0.00, 50.70, 49.30, 1.39 +0.40, 0.00, 50.69, 49.31, 1.39 +0.40, 0.00, 50.69, 49.31, 1.39 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.38 +0.40, 0.00, 50.69, 49.31, 1.37 +0.40, 0.00, 50.69, 49.31, 1.37 +0.40, 0.00, 50.68, 49.32, 1.37 +0.40, 0.00, 50.68, 49.32, 1.36 +0.40, 0.00, 50.68, 49.32, 1.36 +0.53, 0.00, 45.64, 54.36, -8.73 +0.53, 0.00, 50.58, 49.42, 1.16 +0.53, 0.00, 50.58, 49.42, 1.15 +0.53, 0.00, 50.57, 49.43, 1.15 +0.53, 0.00, 50.57, 49.43, 1.14 +0.53, 0.00, 50.57, 49.43, 1.14 +0.53, 0.00, 50.57, 49.43, 1.14 +0.53, 0.00, 50.57, 49.43, 1.13 +0.59, 0.00, 48.04, 51.96, -3.91 +0.53, 0.00, 53.03, 46.97, 6.07 +0.53, 0.00, 50.56, 49.44, 1.12 +0.53, 0.00, 50.56, 49.44, 1.12 +0.53, 0.00, 50.56, 49.44, 1.11 +0.53, 0.00, 50.55, 49.45, 1.11 +0.53, 0.00, 50.55, 49.45, 1.10 +0.59, 0.00, 48.03, 51.97, -3.94 +0.59, 0.00, 50.50, 49.50, 1.00 +0.59, 0.00, 50.50, 49.50, 0.99 +0.59, 0.00, 50.49, 49.51, 0.99 +0.59, 0.00, 50.49, 49.51, 0.98 +0.59, 0.00, 50.49, 49.51, 0.98 +0.59, 0.00, 50.49, 49.51, 0.97 +0.59, 0.00, 50.48, 49.52, 0.97 +0.59, 0.00, 50.48, 49.52, 0.97 +0.59, 0.00, 50.48, 49.52, 0.96 +0.59, 0.00, 50.48, 49.52, 0.96 +0.66, 0.00, 47.95, 52.05, -4.09 +0.66, 0.00, 50.42, 49.58, 0.85 +0.66, 0.00, 50.42, 49.58, 0.84 +0.66, 0.00, 50.42, 49.58, 0.84 +0.66, 0.00, 50.42, 49.58, 0.83 +0.66, 0.00, 50.41, 49.59, 0.83 +0.66, 0.00, 50.41, 49.59, 0.82 +0.66, 0.00, 50.41, 49.59, 0.82 +0.66, 0.00, 50.41, 49.59, 0.81 +0.66, 0.00, 50.40, 49.60, 0.81 +0.66, 0.00, 50.40, 49.60, 0.80 +0.66, 0.00, 50.40, 49.60, 0.80 +0.66, 0.00, 50.40, 49.60, 0.79 +0.66, 0.00, 50.39, 49.61, 0.79 +0.66, 0.00, 50.39, 49.61, 0.78 +0.66, 0.00, 50.39, 49.61, 0.78 +0.66, 0.00, 50.39, 49.61, 0.77 +0.79, 0.00, 45.34, 54.66, -9.32 +0.79, 0.00, 50.28, 49.72, 0.56 +0.79, 0.00, 50.28, 49.72, 0.56 +0.79, 0.00, 50.28, 49.72, 0.55 +0.79, 0.00, 50.27, 49.73, 0.55 +0.79, 0.00, 50.27, 49.73, 0.54 +0.66, 0.00, 55.31, 44.69, 10.62 +0.79, 0.00, 45.32, 54.68, -9.36 +0.66, 0.00, 55.30, 44.70, 10.61 +0.66, 0.00, 50.36, 49.64, 0.72 +0.66, 0.00, 50.36, 49.64, 0.71 +0.66, 0.00, 50.35, 49.65, 0.71 +0.66, 0.00, 50.35, 49.65, 0.70 +0.66, 0.00, 50.35, 49.65, 0.70 +0.66, 0.00, 50.35, 49.65, 0.69 +0.66, 0.00, 50.34, 49.66, 0.69 +0.66, 0.00, 50.34, 49.66, 0.68 +0.66, 0.00, 50.34, 49.66, 0.68 +0.66, 0.00, 50.34, 49.66, 0.67 +0.66, 0.00, 50.33, 49.67, 0.67 +0.66, 0.00, 50.33, 49.67, 0.66 +0.66, 0.00, 50.33, 49.67, 0.66 +0.59, 0.00, 52.85, 47.15, 5.70 +0.59, 0.00, 50.37, 49.63, 0.75 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.73 +0.59, 0.00, 50.37, 49.63, 0.73 +0.59, 0.00, 50.36, 49.64, 0.73 +0.53, 0.00, 52.88, 47.12, 5.76 +0.53, 0.00, 50.41, 49.59, 0.82 +0.59, 0.00, 47.88, 52.12, -4.23 +0.53, 0.00, 52.88, 47.12, 5.75 +0.53, 0.00, 50.40, 49.60, 0.80 +0.53, 0.00, 50.40, 49.60, 0.80 +0.53, 0.00, 50.40, 49.60, 0.80 +0.53, 0.00, 50.40, 49.60, 0.79 +0.53, 0.00, 50.39, 49.61, 0.79 +0.53, 0.00, 50.39, 49.61, 0.78 +0.53, 0.00, 50.39, 49.61, 0.78 +0.40, 0.00, 55.43, 44.57, 10.86 +0.40, 0.00, 50.49, 49.51, 0.97 +0.40, 0.00, 50.48, 49.52, 0.97 +0.40, 0.00, 50.48, 49.52, 0.97 +0.40, 0.00, 50.48, 49.52, 0.96 +0.40, 0.00, 50.48, 49.52, 0.96 +0.40, 0.00, 50.48, 49.52, 0.96 +0.40, 0.00, 50.48, 49.52, 0.95 +0.40, 0.00, 50.48, 49.52, 0.95 +0.33, 0.00, 53.00, 47.00, 5.99 +0.33, 0.00, 50.52, 49.48, 1.05 +0.33, 0.00, 50.52, 49.48, 1.04 +0.33, 0.00, 50.52, 49.48, 1.04 +0.33, 0.00, 50.52, 49.48, 1.04 +0.33, 0.00, 50.52, 49.48, 1.04 +0.33, 0.00, 50.52, 49.48, 1.03 +0.33, 0.00, 50.52, 49.48, 1.03 +0.33, 0.00, 50.51, 49.49, 1.03 +0.26, 0.00, 53.03, 46.97, 6.07 +0.26, 0.00, 50.56, 49.44, 1.12 +0.26, 0.00, 50.56, 49.44, 1.12 +0.26, 0.00, 50.56, 49.44, 1.12 +0.13, 0.00, 55.60, 44.40, 11.20 +0.13, 0.00, 50.66, 49.34, 1.31 +0.13, 0.00, 50.66, 49.34, 1.31 +0.13, 0.00, 50.66, 49.34, 1.31 +0.13, 0.00, 50.66, 49.34, 1.31 +0.07, 0.00, 53.18, 46.82, 6.35 +0.13, 0.00, 48.18, 51.82, -3.63 +0.07, 0.00, 53.18, 46.82, 6.35 +0.07, 0.00, 50.70, 49.30, 1.41 +0.07, 0.00, 50.70, 49.30, 1.41 +0.07, 0.00, 50.70, 49.30, 1.41 +0.07, 0.00, 50.70, 49.30, 1.41 +0.00, 0.00, 53.22, 46.78, 6.45 +0.00, 0.00, 50.75, 49.25, 1.51 +0.00, 0.00, 50.75, 49.25, 1.51 +0.00, 0.00, 50.75, 49.25, 1.51 +0.00, 0.00, 50.75, 49.25, 1.51 +0.00, 0.00, 50.75, 49.25, 1.51 +-0.13, 0.00, 55.80, 44.20, 11.59 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.85, 49.15, 1.71 +-0.13, 0.00, 50.86, 49.14, 1.71 +-0.20, 0.00, 53.38, 46.62, 6.75 +-0.20, 0.00, 50.91, 49.09, 1.81 +-0.20, 0.00, 50.91, 49.09, 1.81 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.20, 0.00, 50.91, 49.09, 1.82 +-0.26, 0.00, 53.43, 46.57, 6.87 +-0.26, 0.00, 50.96, 49.04, 1.93 +-0.26, 0.00, 50.96, 49.04, 1.93 +-0.26, 0.00, 50.96, 49.04, 1.93 +-0.40, 0.00, 56.01, 43.99, 12.02 +-0.40, 0.00, 51.07, 48.93, 2.13 +-0.40, 0.00, 51.07, 48.93, 2.14 +-0.40, 0.00, 51.07, 48.93, 2.14 +-0.40, 0.00, 51.07, 48.93, 2.14 +-0.40, 0.00, 51.07, 48.93, 2.14 +-0.40, 0.00, 51.07, 48.93, 2.15 +-0.40, 0.00, 51.08, 48.92, 2.15 +-0.40, 0.00, 51.08, 48.92, 2.15 +-0.40, 0.00, 51.08, 48.92, 2.16 +-0.40, 0.00, 51.08, 48.92, 2.16 +-0.40, 0.00, 51.08, 48.92, 2.16 +-0.40, 0.00, 51.08, 48.92, 2.17 +-0.40, 0.00, 51.08, 48.92, 2.17 +-0.46, 0.00, 53.61, 46.39, 7.21 +-0.46, 0.00, 51.14, 48.86, 2.27 +-0.46, 0.00, 51.14, 48.86, 2.28 +-0.46, 0.00, 51.14, 48.86, 2.28 +-0.46, 0.00, 51.14, 48.86, 2.28 +-0.46, 0.00, 51.14, 48.86, 2.29 +-0.46, 0.00, 51.15, 48.85, 2.29 +-0.46, 0.00, 51.15, 48.85, 2.30 +-0.46, 0.00, 51.15, 48.85, 2.30 +-0.46, 0.00, 51.15, 48.85, 2.30 +-0.46, 0.00, 51.15, 48.85, 2.31 +-0.46, 0.00, 51.15, 48.85, 2.31 +-0.46, 0.00, 51.16, 48.84, 2.31 +-0.46, 0.00, 51.16, 48.84, 2.32 +-0.46, 0.00, 51.16, 48.84, 2.32 +-0.46, 0.00, 51.16, 48.84, 2.32 +-0.46, 0.00, 51.16, 48.84, 2.33 +-0.40, 0.00, 48.64, 51.36, -2.71 +-0.40, 0.00, 51.12, 48.88, 2.23 +-0.46, 0.00, 53.64, 46.36, 7.28 +-0.46, 0.00, 51.17, 48.83, 2.34 +-0.46, 0.00, 51.17, 48.83, 2.34 +-0.46, 0.00, 51.17, 48.83, 2.35 +-0.46, 0.00, 51.17, 48.83, 2.35 +-0.46, 0.00, 51.18, 48.82, 2.35 +-0.40, 0.00, 48.66, 51.34, -2.69 +-0.40, 0.00, 51.13, 48.87, 2.26 +-0.40, 0.00, 51.13, 48.87, 2.26 +-0.40, 0.00, 51.13, 48.87, 2.27 +-0.40, 0.00, 51.13, 48.87, 2.27 +-0.40, 0.00, 51.14, 48.86, 2.27 +-0.40, 0.00, 51.14, 48.86, 2.28 +-0.40, 0.00, 51.14, 48.86, 2.28 +-0.26, 0.00, 46.10, 53.90, -7.81 +-0.26, 0.00, 51.04, 48.96, 2.08 +-0.26, 0.00, 51.04, 48.96, 2.09 +-0.26, 0.00, 51.04, 48.96, 2.09 +-0.26, 0.00, 51.05, 48.95, 2.09 +-0.26, 0.00, 51.05, 48.95, 2.09 +-0.20, 0.00, 48.53, 51.47, -2.95 +-0.26, 0.00, 53.52, 46.48, 7.04 +-0.20, 0.00, 48.53, 51.47, -2.95 +-0.20, 0.00, 51.00, 49.00, 2.00 +-0.20, 0.00, 51.00, 49.00, 2.00 +-0.20, 0.00, 51.00, 49.00, 2.00 +-0.20, 0.00, 51.00, 49.00, 2.00 +-0.20, 0.00, 51.00, 49.00, 2.01 +-0.13, 0.00, 48.48, 51.52, -3.04 +-0.13, 0.00, 50.95, 49.05, 1.91 +-0.13, 0.00, 50.95, 49.05, 1.91 +-0.13, 0.00, 50.96, 49.04, 1.91 +-0.13, 0.00, 50.96, 49.04, 1.91 +0.00, 0.00, 45.91, 54.09, -8.17 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.00, 0.00, 50.86, 49.14, 1.71 +0.07, 0.00, 48.34, 51.66, -3.33 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.81, 49.19, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.07, 0.00, 50.80, 49.20, 1.61 +0.13, 0.00, 48.28, 51.72, -3.44 +0.13, 0.00, 50.75, 49.25, 1.51 +0.13, 0.00, 50.75, 49.25, 1.51 +0.13, 0.00, 50.75, 49.25, 1.50 +0.13, 0.00, 50.75, 49.25, 1.50 +0.13, 0.00, 50.75, 49.25, 1.50 +0.26, 0.00, 45.71, 54.29, -8.58 +0.26, 0.00, 50.65, 49.35, 1.30 +0.26, 0.00, 50.65, 49.35, 1.30 +0.26, 0.00, 50.65, 49.35, 1.30 +0.33, 0.00, 48.13, 51.87, -3.75 +0.33, 0.00, 50.60, 49.40, 1.19 +0.33, 0.00, 50.60, 49.40, 1.19 +0.33, 0.00, 50.59, 49.41, 1.19 +0.33, 0.00, 50.59, 49.41, 1.19 +0.33, 0.00, 50.59, 49.41, 1.18 +0.33, 0.00, 50.59, 49.41, 1.18 +0.33, 0.00, 50.59, 49.41, 1.18 +0.33, 0.00, 50.59, 49.41, 1.18 +0.40, 0.00, 48.07, 51.93, -3.87 +0.40, 0.00, 50.54, 49.46, 1.07 +0.40, 0.00, 50.53, 49.47, 1.07 +0.40, 0.00, 50.53, 49.47, 1.07 +0.40, 0.00, 50.53, 49.47, 1.06 +0.53, 0.00, 45.49, 54.51, -9.03 +0.53, 0.00, 50.43, 49.57, 0.86 +0.53, 0.00, 50.43, 49.57, 0.85 +0.59, 0.00, 47.90, 52.10, -4.19 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.74 +0.59, 0.00, 50.37, 49.63, 0.73 +0.59, 0.00, 50.36, 49.64, 0.73 +0.59, 0.00, 50.36, 49.64, 0.72 +0.59, 0.00, 50.36, 49.64, 0.72 +0.59, 0.00, 50.36, 49.64, 0.71 +0.59, 0.00, 50.35, 49.65, 0.71 +0.59, 0.00, 50.35, 49.65, 0.70 +0.59, 0.00, 50.35, 49.65, 0.70 +0.59, 0.00, 50.35, 49.65, 0.70 +0.59, 0.00, 50.35, 49.65, 0.69 +0.66, 0.00, 47.82, 52.18, -4.36 +0.59, 0.00, 52.81, 47.19, 5.63 +0.66, 0.00, 47.82, 52.18, -4.37 +0.66, 0.00, 50.29, 49.71, 0.57 +0.66, 0.00, 50.28, 49.72, 0.57 +0.66, 0.00, 50.28, 49.72, 0.56 +0.66, 0.00, 50.28, 49.72, 0.56 +0.66, 0.00, 50.28, 49.72, 0.55 +0.66, 0.00, 50.27, 49.73, 0.55 +0.66, 0.00, 50.27, 49.73, 0.54 +0.66, 0.00, 50.27, 49.73, 0.54 +0.66, 0.00, 50.27, 49.73, 0.53 +0.66, 0.00, 50.26, 49.74, 0.53 +0.66, 0.00, 50.26, 49.74, 0.52 +0.66, 0.00, 50.26, 49.74, 0.52 +0.59, 0.00, 52.78, 47.22, 5.56 +0.59, 0.00, 50.30, 49.70, 0.61 +0.59, 0.00, 50.30, 49.70, 0.60 +0.59, 0.00, 50.30, 49.70, 0.60 +0.59, 0.00, 50.30, 49.70, 0.60 +0.59, 0.00, 50.30, 49.70, 0.59 +0.59, 0.00, 50.29, 49.71, 0.59 +0.59, 0.00, 50.29, 49.71, 0.58 +0.59, 0.00, 50.29, 49.71, 0.58 +0.59, 0.00, 50.29, 49.71, 0.57 +0.59, 0.00, 50.28, 49.72, 0.57 +0.59, 0.00, 50.28, 49.72, 0.56 +0.59, 0.00, 50.28, 49.72, 0.56 +0.59, 0.00, 50.28, 49.72, 0.56 +0.59, 0.00, 50.28, 49.72, 0.55 +0.59, 0.00, 50.27, 49.73, 0.55 +0.53, 0.00, 52.79, 47.21, 5.59 +0.53, 0.00, 50.32, 49.68, 0.64 +0.53, 0.00, 50.32, 49.68, 0.63 +0.53, 0.00, 50.31, 49.69, 0.63 +0.53, 0.00, 50.31, 49.69, 0.63 +0.53, 0.00, 50.31, 49.69, 0.62 +0.53, 0.00, 50.31, 49.69, 0.62 +0.53, 0.00, 50.31, 49.69, 0.61 +0.40, 0.00, 55.35, 44.65, 10.70 +0.40, 0.00, 50.40, 49.60, 0.81 +0.40, 0.00, 50.40, 49.60, 0.80 +0.40, 0.00, 50.40, 49.60, 0.80 +0.40, 0.00, 50.40, 49.60, 0.80 +0.40, 0.00, 50.40, 49.60, 0.79 +0.40, 0.00, 50.40, 49.60, 0.79 +0.40, 0.00, 50.39, 49.61, 0.79 +0.40, 0.00, 50.39, 49.61, 0.78 +0.33, 0.00, 52.91, 47.09, 5.83 +0.33, 0.00, 50.44, 49.56, 0.88 +0.33, 0.00, 50.44, 49.56, 0.88 +0.33, 0.00, 50.44, 49.56, 0.87 +0.33, 0.00, 50.44, 49.56, 0.87 +0.33, 0.00, 50.43, 49.57, 0.87 +0.33, 0.00, 50.43, 49.57, 0.87 +0.33, 0.00, 50.43, 49.57, 0.86 +0.26, 0.00, 52.95, 47.05, 5.90 +0.26, 0.00, 50.48, 49.52, 0.96 +0.26, 0.00, 50.48, 49.52, 0.96 +0.26, 0.00, 50.48, 49.52, 0.96 +0.26, 0.00, 50.48, 49.52, 0.95 +0.26, 0.00, 50.48, 49.52, 0.95 +0.26, 0.00, 50.47, 49.53, 0.95 +0.26, 0.00, 50.47, 49.53, 0.95 +0.13, 0.00, 55.52, 44.48, 11.03 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.13, 0.00, 50.57, 49.43, 1.14 +0.07, 0.00, 53.09, 46.91, 6.18 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.00, 0.00, 53.14, 46.86, 6.28 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +0.00, 0.00, 50.67, 49.33, 1.33 +-0.13, 0.00, 55.71, 44.29, 11.42 +-0.13, 0.00, 50.77, 49.23, 1.53 +0.00, 0.00, 45.72, 54.28, -8.55 +-0.13, 0.00, 55.71, 44.29, 11.42 +0.00, 0.00, 45.72, 54.28, -8.55 +0.00, 0.00, 50.67, 49.33, 1.33 +-0.13, 0.00, 55.71, 44.29, 11.42 +0.00, 0.00, 45.72, 54.28, -8.55 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.00, 0.00, 50.67, 49.33, 1.34 +0.07, 0.00, 48.15, 51.85, -3.71 +0.07, 0.00, 50.62, 49.38, 1.24 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.62, 49.38, 1.23 +0.07, 0.00, 50.61, 49.39, 1.23 +0.07, 0.00, 50.61, 49.39, 1.23 +0.07, 0.00, 50.61, 49.39, 1.23 +0.00, 0.00, 53.14, 46.86, 6.27 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +0.00, 0.00, 50.66, 49.34, 1.33 +-0.13, 0.00, 55.71, 44.29, 11.41 +-0.13, 0.00, 50.76, 49.24, 1.53 +-0.13, 0.00, 50.76, 49.24, 1.53 +-0.13, 0.00, 50.76, 49.24, 1.53 +-0.13, 0.00, 50.77, 49.23, 1.53 +-0.20, 0.00, 53.29, 46.71, 6.57 +-0.20, 0.00, 50.82, 49.18, 1.63 +-0.20, 0.00, 50.82, 49.18, 1.63 +-0.20, 0.00, 50.82, 49.18, 1.64 +-0.20, 0.00, 50.82, 49.18, 1.64 +-0.20, 0.00, 50.82, 49.18, 1.64 +-0.20, 0.00, 50.82, 49.18, 1.64 +-0.26, 0.00, 53.34, 46.66, 6.68 +-0.26, 0.00, 50.87, 49.13, 1.74 +-0.26, 0.00, 50.87, 49.13, 1.74 +-0.26, 0.00, 50.87, 49.13, 1.75 +-0.26, 0.00, 50.87, 49.13, 1.75 +-0.40, 0.00, 55.92, 44.08, 11.84 +-0.40, 0.00, 50.98, 49.02, 1.95 +-0.40, 0.00, 50.98, 49.02, 1.96 +-0.40, 0.00, 50.98, 49.02, 1.96 +-0.40, 0.00, 50.98, 49.02, 1.96 +-0.40, 0.00, 50.98, 49.02, 1.96 +-0.46, 0.00, 53.51, 46.49, 7.01 +-0.46, 0.00, 51.03, 48.97, 2.07 +-0.46, 0.00, 51.04, 48.96, 2.07 +-0.46, 0.00, 51.04, 48.96, 2.08 +-0.46, 0.00, 51.04, 48.96, 2.08 +-0.46, 0.00, 51.04, 48.96, 2.08 +-0.53, 0.00, 53.57, 46.43, 7.13 +-0.53, 0.00, 51.10, 48.90, 2.19 +-0.53, 0.00, 51.10, 48.90, 2.19 +-0.53, 0.00, 51.10, 48.90, 2.20 +-0.66, 0.00, 56.14, 43.86, 12.29 +-0.66, 0.00, 51.20, 48.80, 2.41 +-0.66, 0.00, 51.21, 48.79, 2.41 +-0.66, 0.00, 51.21, 48.79, 2.42 +-0.66, 0.00, 51.21, 48.79, 2.42 +-0.66, 0.00, 51.21, 48.79, 2.43 +-0.73, 0.00, 53.74, 46.26, 7.47 +-0.73, 0.00, 51.27, 48.73, 2.54 +-0.73, 0.00, 51.27, 48.73, 2.54 +-0.73, 0.00, 51.27, 48.73, 2.55 +-0.73, 0.00, 51.28, 48.72, 2.55 +-0.73, 0.00, 51.28, 48.72, 2.56 +-0.79, 0.00, 53.80, 46.20, 7.61 +-0.79, 0.00, 51.33, 48.67, 2.67 +-0.79, 0.00, 51.34, 48.66, 2.67 +-0.79, 0.00, 51.34, 48.66, 2.68 +-0.79, 0.00, 51.34, 48.66, 2.69 +-0.79, 0.00, 51.35, 48.65, 2.69 +-0.79, 0.00, 51.35, 48.65, 2.70 +-0.79, 0.00, 51.35, 48.65, 2.70 +-0.79, 0.00, 51.35, 48.65, 2.71 +-0.92, 0.00, 56.40, 43.60, 12.80 +-0.92, 0.00, 51.46, 48.54, 2.92 +-0.92, 0.00, 51.46, 48.54, 2.93 +-0.92, 0.00, 51.47, 48.53, 2.94 +-0.92, 0.00, 51.47, 48.53, 2.94 +-0.92, 0.00, 51.47, 48.53, 2.95 +-0.92, 0.00, 51.48, 48.52, 2.96 +-0.99, 0.00, 54.00, 46.00, 8.01 +-0.99, 0.00, 51.53, 48.47, 3.07 +-0.92, 0.00, 49.02, 50.98, -1.97 +-0.92, 0.00, 51.49, 48.51, 2.98 +-0.99, 0.00, 54.02, 45.98, 8.03 +-0.92, 0.00, 49.03, 50.97, -1.95 +-0.92, 0.00, 51.50, 48.50, 3.01 +-0.99, 0.00, 54.03, 45.97, 8.06 +-0.99, 0.00, 51.56, 48.44, 3.12 +-0.99, 0.00, 51.56, 48.44, 3.13 +-0.99, 0.00, 51.57, 48.43, 3.13 +-0.99, 0.00, 51.57, 48.43, 3.14 +-1.05, 0.00, 54.10, 45.90, 8.19 +-1.05, 0.00, 51.63, 48.37, 3.26 +-1.05, 0.00, 51.63, 48.37, 3.26 +-1.05, 0.00, 51.64, 48.36, 3.27 +-1.05, 0.00, 51.64, 48.36, 3.28 +-1.05, 0.00, 51.64, 48.36, 3.29 +-1.05, 0.00, 51.65, 48.35, 3.30 +-1.05, 0.00, 51.65, 48.35, 3.30 +-1.05, 0.00, 51.66, 48.34, 3.31 +-1.05, 0.00, 51.66, 48.34, 3.32 +-1.05, 0.00, 51.66, 48.34, 3.33 +-1.05, 0.00, 51.67, 48.33, 3.34 +-1.05, 0.00, 51.67, 48.33, 3.34 +-1.05, 0.00, 51.68, 48.32, 3.35 +-1.05, 0.00, 51.68, 48.32, 3.36 +-1.05, 0.00, 51.68, 48.32, 3.37 +-1.05, 0.00, 51.69, 48.31, 3.38 +-1.19, 0.00, 56.73, 43.27, 13.47 +-1.19, 0.00, 51.80, 48.20, 3.59 +-1.19, 0.00, 51.80, 48.20, 3.60 +-1.19, 0.00, 51.80, 48.20, 3.61 +-1.19, 0.00, 51.81, 48.19, 3.62 +-1.19, 0.00, 51.81, 48.19, 3.63 +-1.19, 0.00, 51.82, 48.18, 3.64 +-1.19, 0.00, 51.82, 48.18, 3.64 +-1.19, 0.00, 51.83, 48.17, 3.65 +-1.19, 0.00, 51.83, 48.17, 3.66 +-1.19, 0.00, 51.84, 48.16, 3.67 +-1.19, 0.00, 51.84, 48.16, 3.68 +-1.19, 0.00, 51.84, 48.16, 3.69 +-1.19, 0.00, 51.85, 48.15, 3.70 +-1.19, 0.00, 51.85, 48.15, 3.71 +-1.19, 0.00, 51.86, 48.14, 3.72 +-1.19, 0.00, 51.86, 48.14, 3.72 +-1.19, 0.00, 51.87, 48.13, 3.73 +-1.19, 0.00, 51.87, 48.13, 3.74 +-1.25, 0.00, 54.40, 45.60, 8.79 +-1.25, 0.00, 51.93, 48.07, 3.86 +-1.19, 0.00, 49.41, 50.59, -1.17 +-1.25, 0.00, 54.41, 45.59, 8.82 +-1.19, 0.00, 49.42, 50.58, -1.16 +-1.25, 0.00, 54.42, 45.58, 8.84 +-1.19, 0.00, 49.43, 50.57, -1.14 +-1.19, 0.00, 51.91, 48.09, 3.82 +-1.19, 0.00, 51.91, 48.09, 3.82 +-1.19, 0.00, 51.92, 48.08, 3.83 +-1.19, 0.00, 51.92, 48.08, 3.84 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.05, 35.00, 73.53, 26.47, 47.07 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.05, 35.00, 73.94, 26.06, 47.88 +-1.19, 35.00, 75.00, 25.00, 50.00 +-1.05, 35.00, 74.21, 25.79, 48.42 +-1.05, 35.00, 75.00, 25.00, 50.00 +-1.05, 35.00, 75.00, 25.00, 50.00 +-0.99, 35.00, 75.00, 25.00, 50.00 +-0.92, 35.00, 75.00, 25.00, 50.00 +-0.92, 35.00, 75.00, 25.00, 50.00 +-0.73, 35.00, 72.30, 27.70, 44.60 +-0.66, 35.00, 75.00, 25.00, 50.00 +-0.53, 35.00, 74.89, 25.11, 49.78 +-0.46, 35.00, 75.00, 25.00, 50.00 +-0.26, 35.00, 72.49, 27.51, 44.98 +-0.13, 35.00, 74.99, 25.01, 49.99 +0.00, 35.00, 75.00, 25.00, 50.00 +0.13, 35.00, 75.00, 25.00, 50.00 +0.33, 35.00, 72.57, 27.43, 45.13 +0.53, 35.00, 72.55, 27.45, 45.10 +0.66, 35.00, 75.00, 25.00, 50.00 +0.86, 35.00, 72.56, 27.44, 45.11 +1.12, 35.00, 70.01, 29.99, 40.03 +1.32, 35.00, 72.46, 27.54, 44.93 +1.58, 35.00, 69.92, 30.08, 39.84 +1.85, 35.00, 69.85, 30.15, 39.69 +2.18, 35.00, 67.25, 32.75, 34.50 +2.44, 35.00, 69.65, 30.35, 39.29 +2.70, 35.00, 69.57, 30.43, 39.14 +3.03, 35.00, 66.97, 33.03, 33.94 +3.43, 35.00, 64.32, 35.68, 28.64 +3.76, 35.00, 66.66, 33.34, 33.33 +4.09, 35.00, 66.53, 33.47, 33.06 +4.55, 35.00, 61.36, 38.64, 22.71 +4.88, 35.00, 66.17, 33.83, 32.33 +5.34, 35.00, 60.99, 39.01, 21.97 +5.67, 35.00, 65.79, 34.21, 31.59 +6.13, 35.00, 60.61, 39.39, 21.22 +6.59, 35.00, 60.37, 39.63, 20.74 +6.99, 35.00, 62.65, 37.35, 25.31 +7.45, 35.00, 59.94, 40.06, 19.88 +7.98, 35.00, 57.17, 42.83, 14.34 +8.50, 35.00, 56.88, 43.12, 13.75 +9.03, 35.00, 56.58, 43.42, 13.16 +9.49, 35.00, 58.80, 41.20, 17.60 +10.09, 35.00, 53.50, 46.50, 7.01 +10.61, 35.00, 55.67, 44.33, 11.34 +11.14, 35.00, 55.37, 44.63, 10.73 +11.73, 35.00, 52.54, 47.46, 5.07 +12.26, 35.00, 54.70, 45.30, 9.40 +12.79, 35.00, 54.39, 45.61, 8.77 +13.32, 35.00, 54.07, 45.93, 8.14 +13.84, 35.00, 53.76, 46.24, 7.51 +14.37, 35.00, 53.44, 46.56, 6.87 +14.90, 35.00, 53.12, 46.88, 6.23 +15.42, 35.00, 52.79, 47.21, 5.59 +15.95, 35.00, 52.47, 47.53, 4.94 +16.61, 35.00, 47.10, 52.90, -5.80 +17.14, 35.00, 51.72, 48.28, 3.43 +17.73, 35.00, 48.86, 51.14, -2.27 +18.33, 35.00, 48.48, 51.52, -3.04 +18.98, 35.00, 45.58, 54.42, -8.85 +19.58, 35.00, 47.66, 52.34, -4.68 +20.17, 35.00, 47.27, 52.73, -5.46 +20.83, 35.00, 44.36, 55.64, -11.28 +21.36, 35.00, 48.96, 51.04, -2.08 +21.95, 35.00, 46.09, 53.91, -7.82 +22.48, 35.00, 48.21, 51.79, -3.57 +23.01, 35.00, 47.86, 52.14, -4.27 +23.53, 35.00, 47.51, 52.49, -4.98 +24.13, 35.00, 44.63, 55.37, -10.73 +24.65, 35.00, 46.75, 53.25, -6.50 +25.18, 35.00, 46.39, 53.61, -7.22 +25.71, 35.00, 46.03, 53.97, -7.94 +26.24, 35.00, 45.67, 54.33, -8.67 +26.76, 35.00, 45.30, 54.70, -9.39 +27.29, 35.00, 44.94, 55.06, -10.13 +27.82, 35.00, 44.57, 55.43, -10.86 +28.34, 35.00, 44.20, 55.80, -11.61 +28.81, 35.00, 46.35, 53.65, -7.31 +29.33, 35.00, 43.50, 56.50, -13.00 +29.86, 35.00, 43.12, 56.88, -13.75 +30.32, 35.00, 45.27, 54.73, -9.47 +30.72, 35.00, 47.46, 52.54, -5.08 +31.25, 35.00, 42.13, 57.87, -15.73 +31.71, 35.00, 44.27, 55.73, -11.46 +32.17, 35.00, 43.94, 56.06, -12.13 +32.56, 35.00, 46.12, 53.88, -7.76 +33.02, 35.00, 43.31, 56.69, -13.38 +33.49, 35.00, 42.97, 57.03, -14.06 +33.82, 35.00, 47.67, 52.33, -4.66 +34.28, 35.00, 42.38, 57.62, -15.23 +34.61, 35.00, 47.08, 52.92, -5.84 +34.94, 35.00, 46.83, 53.17, -6.33 +35.33, 35.00, 44.06, 55.94, -11.87 +35.66, 35.00, 46.29, 53.71, -7.43 +35.99, 35.00, 46.04, 53.96, -7.93 +36.39, 35.00, 43.26, 56.74, -13.48 +36.72, 35.00, 45.48, 54.52, -9.04 +36.98, 35.00, 47.75, 52.25, -4.51 +37.31, 35.00, 45.02, 54.98, -9.96 +37.57, 35.00, 47.28, 52.72, -5.43 +37.84, 35.00, 47.08, 52.92, -5.85 +38.10, 35.00, 46.87, 53.13, -6.27 +38.36, 35.00, 46.66, 53.34, -6.69 +38.63, 35.00, 46.44, 53.56, -7.11 +38.89, 35.00, 46.23, 53.77, -7.54 +39.09, 35.00, 48.54, 51.46, -2.92 +39.35, 35.00, 45.85, 54.15, -8.29 +39.55, 35.00, 48.16, 51.84, -3.68 +39.68, 35.00, 50.52, 49.48, 1.03 +39.88, 35.00, 47.88, 52.12, -4.24 +40.14, 35.00, 45.19, 54.81, -9.62 +40.34, 35.00, 47.49, 52.51, -5.02 +40.41, 35.00, 52.37, 47.63, 4.73 +40.61, 35.00, 47.25, 52.75, -5.49 +40.74, 35.00, 49.60, 50.40, -0.79 +40.94, 35.00, 46.96, 53.04, -6.08 +41.00, 35.00, 51.83, 48.17, 3.67 +41.13, 35.00, 49.24, 50.76, -1.52 +41.20, 35.00, 51.64, 48.36, 3.28 +41.20, 35.00, 54.09, 45.91, 8.18 +41.20, 35.00, 54.07, 45.93, 8.13 +41.20, 35.00, 54.04, 45.96, 8.08 +41.20, 35.00, 54.02, 45.98, 8.04 +41.13, 35.00, 56.52, 43.48, 13.03 +41.00, 35.00, 59.07, 40.93, 18.13 +41.00, 35.00, 54.10, 45.90, 8.20 +41.00, 35.00, 54.08, 45.92, 8.15 +41.00, 35.00, 54.05, 45.95, 8.11 +40.94, 35.00, 56.55, 43.45, 13.11 +40.94, 35.00, 54.06, 45.94, 8.12 +40.94, 35.00, 54.04, 45.96, 8.07 +40.87, 35.00, 56.54, 43.46, 13.07 +40.74, 35.00, 59.09, 40.91, 18.17 +40.74, 35.00, 54.12, 45.88, 8.24 +40.67, 35.00, 56.62, 43.38, 13.24 +40.61, 35.00, 56.65, 43.35, 13.30 +40.41, 35.00, 61.72, 38.28, 23.44 +40.21, 35.00, 61.85, 38.15, 23.70 +40.14, 35.00, 56.94, 43.06, 13.87 +39.95, 35.00, 62.01, 37.99, 24.02 +39.81, 35.00, 59.62, 40.38, 19.24 +39.62, 35.00, 62.22, 37.78, 24.44 +39.62, 35.00, 54.79, 45.21, 9.58 +39.42, 35.00, 62.34, 37.66, 24.67 +39.35, 35.00, 57.42, 42.58, 14.85 +39.29, 35.00, 57.46, 42.54, 14.92 +39.29, 35.00, 54.97, 45.03, 9.94 +39.16, 35.00, 60.00, 40.00, 19.99 +39.09, 35.00, 57.56, 42.44, 15.12 +39.09, 35.00, 55.07, 44.93, 10.14 +39.09, 35.00, 55.06, 44.94, 10.11 +39.02, 35.00, 57.56, 42.44, 15.13 +38.89, 35.00, 60.12, 39.88, 20.24 +38.83, 35.00, 57.68, 42.32, 15.36 +38.76, 35.00, 57.72, 42.28, 15.44 +38.63, 35.00, 60.27, 39.73, 20.55 +38.56, 35.00, 57.84, 42.16, 15.68 +38.50, 35.00, 57.88, 42.12, 15.75 +38.36, 35.00, 60.43, 39.57, 20.87 +38.30, 35.00, 58.00, 42.00, 16.00 +38.30, 35.00, 55.51, 44.49, 11.03 +38.23, 35.00, 58.02, 41.98, 16.05 +38.23, 35.00, 55.54, 44.46, 11.08 +38.23, 35.00, 55.53, 44.47, 11.05 +38.10, 35.00, 60.56, 39.44, 21.12 +38.10, 35.00, 55.60, 44.40, 11.21 +38.10, 35.00, 55.59, 44.41, 11.18 +38.10, 35.00, 55.58, 44.42, 11.16 +38.10, 35.00, 55.57, 44.43, 11.14 +38.10, 35.00, 55.56, 44.44, 11.11 +38.10, 35.00, 55.54, 44.46, 11.09 +38.10, 35.00, 55.53, 44.47, 11.07 +38.10, 35.00, 55.52, 44.48, 11.04 +38.10, 35.00, 55.51, 44.49, 11.02 +38.10, 35.00, 55.50, 44.50, 11.00 +38.03, 35.00, 58.01, 41.99, 16.02 +38.03, 35.00, 55.53, 44.47, 11.05 +38.03, 35.00, 55.51, 44.49, 11.03 +38.03, 35.00, 55.50, 44.50, 11.00 +38.10, 35.00, 52.97, 47.03, 5.94 +38.10, 35.00, 55.43, 44.57, 10.86 +38.10, 35.00, 55.42, 44.58, 10.84 +38.10, 35.00, 55.41, 44.59, 10.81 +38.10, 35.00, 55.39, 44.61, 10.79 +38.23, 35.00, 50.34, 49.66, 0.68 +38.30, 35.00, 52.75, 47.25, 5.50 +38.30, 35.00, 55.21, 44.79, 10.42 +38.30, 35.00, 55.20, 44.80, 10.39 +38.36, 35.00, 52.66, 47.34, 5.33 +38.36, 35.00, 55.12, 44.88, 10.25 +38.50, 35.00, 50.07, 49.93, 0.13 +38.50, 35.00, 55.00, 45.00, 9.99 +38.56, 35.00, 52.46, 47.54, 4.93 +38.56, 35.00, 54.92, 45.08, 9.84 +38.56, 35.00, 54.91, 45.09, 9.82 +38.63, 35.00, 52.37, 47.63, 4.75 +38.63, 35.00, 54.83, 45.17, 9.66 +38.76, 35.00, 49.77, 50.23, -0.45 +38.76, 35.00, 54.70, 45.30, 9.41 +38.83, 35.00, 52.17, 47.83, 4.34 +38.89, 35.00, 52.10, 47.90, 4.21 +39.02, 35.00, 49.52, 50.48, -0.96 +39.02, 35.00, 54.45, 45.55, 8.89 +39.09, 35.00, 51.91, 48.09, 3.82 +39.16, 35.00, 51.85, 48.15, 3.69 +39.16, 35.00, 54.30, 45.70, 8.60 +39.29, 35.00, 49.24, 50.76, -1.51 +39.35, 35.00, 51.65, 48.35, 3.30 +39.42, 35.00, 51.58, 48.42, 3.17 +39.55, 35.00, 49.00, 51.00, -2.01 +39.55, 35.00, 53.92, 46.08, 7.84 +39.62, 35.00, 51.38, 48.62, 2.77 +39.68, 35.00, 51.32, 48.68, 2.63 +39.81, 35.00, 48.73, 51.27, -2.54 +39.81, 35.00, 53.65, 46.35, 7.31 +39.88, 35.00, 51.11, 48.89, 2.23 +39.95, 35.00, 51.05, 48.95, 2.09 +40.08, 35.00, 48.46, 51.54, -3.09 +40.08, 35.00, 53.38, 46.62, 6.76 +40.14, 35.00, 50.84, 49.16, 1.68 +40.21, 35.00, 50.77, 49.23, 1.54 +40.21, 35.00, 53.22, 46.78, 6.45 +40.34, 35.00, 48.16, 51.84, -3.68 +40.41, 35.00, 50.56, 49.44, 1.13 +40.41, 35.00, 53.01, 46.99, 6.03 +40.47, 35.00, 50.47, 49.53, 0.95 +40.47, 35.00, 52.92, 47.08, 5.85 +40.47, 35.00, 52.90, 47.10, 5.81 +40.47, 35.00, 52.88, 47.12, 5.77 +40.47, 35.00, 52.86, 47.14, 5.73 +40.61, 35.00, 47.80, 52.20, -4.40 +40.61, 35.00, 52.72, 47.28, 5.44 +40.61, 35.00, 52.70, 47.30, 5.40 +40.61, 35.00, 52.68, 47.32, 5.36 +40.61, 35.00, 52.66, 47.34, 5.32 +40.67, 35.00, 50.12, 49.88, 0.23 +40.67, 35.00, 52.57, 47.43, 5.13 +40.67, 35.00, 52.55, 47.45, 5.09 +40.67, 35.00, 52.52, 47.48, 5.05 +40.67, 35.00, 52.50, 47.50, 5.01 +40.67, 35.00, 52.48, 47.52, 4.96 +40.67, 35.00, 52.46, 47.54, 4.92 +40.67, 35.00, 52.44, 47.56, 4.88 +40.67, 35.00, 52.42, 47.58, 4.84 +40.67, 35.00, 52.40, 47.60, 4.79 +40.67, 35.00, 52.38, 47.62, 4.75 +40.67, 35.00, 52.35, 47.65, 4.71 +40.67, 35.00, 52.33, 47.67, 4.67 +40.61, 35.00, 54.83, 45.17, 9.67 +40.61, 35.00, 52.34, 47.66, 4.68 +40.47, 35.00, 57.36, 42.64, 14.72 +40.47, 35.00, 52.40, 47.60, 4.80 +40.41, 35.00, 54.90, 45.10, 9.80 +40.41, 35.00, 52.41, 47.59, 4.81 +40.41, 35.00, 52.39, 47.61, 4.77 +40.34, 35.00, 54.89, 45.11, 9.78 +40.34, 35.00, 52.40, 47.60, 4.79 +40.21, 35.00, 57.42, 42.58, 14.84 +40.21, 35.00, 52.46, 47.54, 4.91 +40.14, 35.00, 54.96, 45.04, 9.92 +40.14, 35.00, 52.47, 47.53, 4.93 +40.08, 35.00, 54.97, 45.03, 9.94 +40.08, 35.00, 52.48, 47.52, 4.96 +39.95, 35.00, 57.50, 42.50, 15.00 +39.95, 35.00, 52.54, 47.46, 5.08 +39.88, 35.00, 55.04, 44.96, 10.09 +39.88, 35.00, 52.55, 47.45, 5.11 +39.81, 35.00, 55.06, 44.94, 10.11 +39.81, 35.00, 52.57, 47.43, 5.13 +39.68, 35.00, 57.59, 42.41, 15.18 +39.68, 35.00, 52.63, 47.37, 5.26 +39.62, 35.00, 55.13, 44.87, 10.27 +39.62, 35.00, 52.64, 47.36, 5.29 +39.55, 35.00, 55.15, 44.85, 10.30 +39.55, 35.00, 52.66, 47.34, 5.32 +39.42, 35.00, 57.69, 42.31, 15.37 +39.42, 35.00, 52.73, 47.27, 5.45 +39.42, 35.00, 52.71, 47.29, 5.42 +39.35, 35.00, 55.21, 44.79, 10.43 +39.35, 35.00, 52.73, 47.27, 5.45 +39.35, 35.00, 52.71, 47.29, 5.42 +39.35, 35.00, 52.69, 47.31, 5.39 +39.35, 35.00, 52.68, 47.32, 5.35 +39.29, 35.00, 55.18, 44.82, 10.36 +39.29, 35.00, 52.69, 47.31, 5.39 +39.29, 35.00, 52.68, 47.32, 5.36 +39.29, 35.00, 52.66, 47.34, 5.32 +39.16, 35.00, 57.69, 42.31, 15.38 +39.16, 35.00, 52.73, 47.27, 5.46 +39.16, 35.00, 52.71, 47.29, 5.43 +39.16, 35.00, 52.70, 47.30, 5.40 +39.16, 35.00, 52.68, 47.32, 5.37 +39.09, 35.00, 55.19, 44.81, 10.38 +39.09, 35.00, 52.70, 47.30, 5.40 +39.09, 35.00, 52.69, 47.31, 5.37 +39.09, 35.00, 52.67, 47.33, 5.34 +39.09, 35.00, 52.66, 47.34, 5.31 +39.09, 35.00, 52.64, 47.36, 5.28 +39.09, 35.00, 52.62, 47.38, 5.25 +39.09, 35.00, 52.61, 47.39, 5.22 +39.09, 35.00, 52.59, 47.41, 5.19 +39.09, 35.00, 52.58, 47.42, 5.16 +39.09, 35.00, 52.56, 47.44, 5.13 +39.09, 35.00, 52.55, 47.45, 5.10 +39.09, 35.00, 52.53, 47.47, 5.07 +39.09, 35.00, 52.52, 47.48, 5.04 +39.09, 35.00, 52.50, 47.50, 5.00 +39.09, 35.00, 52.49, 47.51, 4.97 +39.09, 35.00, 52.47, 47.53, 4.94 +39.09, 35.00, 52.46, 47.54, 4.91 +39.09, 35.00, 52.44, 47.56, 4.88 +39.16, 35.00, 49.90, 50.10, -0.19 +39.16, 35.00, 52.36, 47.64, 4.72 +39.16, 35.00, 52.34, 47.66, 4.69 +39.16, 35.00, 52.33, 47.67, 4.66 +39.16, 35.00, 52.31, 47.69, 4.63 +39.16, 35.00, 52.30, 47.70, 4.60 +39.16, 35.00, 52.28, 47.72, 4.56 +39.16, 35.00, 52.27, 47.73, 4.53 +39.29, 35.00, 47.21, 52.79, -5.58 +39.16, 35.00, 57.18, 42.82, 14.36 +39.16, 35.00, 52.22, 47.78, 4.44 +39.29, 35.00, 47.16, 52.84, -5.68 +39.29, 35.00, 52.09, 47.91, 4.18 +39.29, 35.00, 52.07, 47.93, 4.14 +39.29, 35.00, 52.06, 47.94, 4.11 +39.29, 35.00, 52.04, 47.96, 4.08 +39.35, 35.00, 49.50, 50.50, -0.99 +39.35, 35.00, 51.96, 48.04, 3.92 +39.35, 35.00, 51.94, 48.06, 3.88 +39.42, 35.00, 49.40, 50.60, -1.19 +39.42, 35.00, 51.86, 48.14, 3.72 +39.42, 35.00, 51.84, 48.16, 3.69 +39.42, 35.00, 51.83, 48.17, 3.65 +39.42, 35.00, 51.81, 48.19, 3.62 +39.42, 35.00, 51.79, 48.21, 3.59 +39.55, 35.00, 46.73, 53.27, -6.53 +39.55, 35.00, 51.66, 48.34, 3.32 +39.55, 35.00, 51.64, 48.36, 3.29 +39.55, 35.00, 51.63, 48.37, 3.25 +39.55, 35.00, 51.61, 48.39, 3.22 +39.55, 35.00, 51.59, 48.41, 3.18 +39.55, 35.00, 51.57, 48.43, 3.15 +39.55, 35.00, 51.56, 48.44, 3.12 +39.55, 35.00, 51.54, 48.46, 3.08 +39.62, 35.00, 49.00, 51.00, -2.00 +39.62, 35.00, 51.46, 48.54, 2.91 +39.62, 35.00, 51.44, 48.56, 2.88 +39.62, 35.00, 51.42, 48.58, 2.84 +39.62, 35.00, 51.40, 48.60, 2.81 +39.62, 35.00, 51.39, 48.61, 2.77 +39.62, 35.00, 51.37, 48.63, 2.74 +39.62, 35.00, 51.35, 48.65, 2.71 +39.62, 35.00, 51.34, 48.66, 2.67 +39.62, 35.00, 51.32, 48.68, 2.64 +39.62, 35.00, 51.30, 48.70, 2.60 +39.62, 35.00, 51.28, 48.72, 2.57 +39.62, 35.00, 51.27, 48.73, 2.53 +39.62, 35.00, 51.25, 48.75, 2.50 +39.55, 35.00, 53.75, 46.25, 7.51 +39.55, 35.00, 51.26, 48.74, 2.53 +39.55, 35.00, 51.25, 48.75, 2.49 +39.55, 35.00, 51.23, 48.77, 2.46 +39.42, 35.00, 56.26, 43.74, 12.51 +39.42, 35.00, 51.30, 48.70, 2.59 +39.42, 35.00, 51.28, 48.72, 2.56 +39.42, 35.00, 51.26, 48.74, 2.53 +39.35, 35.00, 53.77, 46.23, 7.54 +39.35, 35.00, 51.28, 48.72, 2.56 +39.35, 35.00, 51.26, 48.74, 2.53 +39.35, 35.00, 51.25, 48.75, 2.49 +39.35, 35.00, 51.23, 48.77, 2.46 +39.29, 35.00, 53.74, 46.26, 7.47 +39.29, 35.00, 51.25, 48.75, 2.50 +39.29, 35.00, 51.23, 48.77, 2.46 +39.29, 35.00, 51.22, 48.78, 2.43 +39.16, 35.00, 56.24, 43.76, 12.49 +39.16, 35.00, 51.28, 48.72, 2.57 +39.09, 35.00, 53.79, 46.21, 7.58 +39.09, 35.00, 51.30, 48.70, 2.60 +39.09, 35.00, 51.29, 48.71, 2.57 +39.02, 35.00, 53.79, 46.21, 7.59 +39.02, 35.00, 51.31, 48.69, 2.61 +38.89, 35.00, 56.33, 43.67, 12.67 +38.89, 35.00, 51.38, 48.62, 2.75 +38.89, 35.00, 51.36, 48.64, 2.72 +38.83, 35.00, 53.87, 46.13, 7.74 +38.83, 35.00, 51.38, 48.62, 2.76 +38.83, 35.00, 51.37, 48.63, 2.73 +38.76, 35.00, 53.87, 46.13, 7.75 +38.76, 35.00, 51.39, 48.61, 2.78 +38.76, 35.00, 51.37, 48.63, 2.75 +38.63, 35.00, 56.40, 43.60, 12.81 +38.63, 35.00, 51.45, 48.55, 2.89 +38.63, 35.00, 51.43, 48.57, 2.87 +38.56, 35.00, 53.94, 46.06, 7.88 +38.56, 35.00, 51.46, 48.54, 2.91 +38.56, 35.00, 51.44, 48.56, 2.88 +38.50, 35.00, 53.95, 46.05, 7.90 +38.50, 35.00, 51.47, 48.53, 2.93 +38.50, 35.00, 51.45, 48.55, 2.90 +38.36, 35.00, 56.48, 43.52, 12.96 +38.36, 35.00, 51.53, 48.47, 3.05 +38.36, 35.00, 51.51, 48.49, 3.03 +38.36, 35.00, 51.50, 48.50, 3.00 +38.36, 35.00, 51.49, 48.51, 2.98 +38.30, 35.00, 54.00, 46.00, 7.99 +38.30, 35.00, 51.51, 48.49, 3.03 +38.30, 35.00, 51.50, 48.50, 3.00 +38.30, 35.00, 51.49, 48.51, 2.98 +38.30, 35.00, 51.48, 48.52, 2.95 +38.30, 35.00, 51.46, 48.54, 2.93 +38.30, 35.00, 51.45, 48.55, 2.90 +38.30, 35.00, 51.44, 48.56, 2.88 +38.30, 35.00, 51.43, 48.57, 2.85 +38.23, 35.00, 53.94, 46.06, 7.87 +38.23, 35.00, 51.45, 48.55, 2.90 +38.23, 35.00, 51.44, 48.56, 2.88 +38.23, 35.00, 51.43, 48.57, 2.85 +38.23, 35.00, 51.41, 48.59, 2.83 +38.23, 35.00, 51.40, 48.60, 2.81 +38.23, 35.00, 51.39, 48.61, 2.78 +38.23, 35.00, 51.38, 48.62, 2.76 +38.23, 35.00, 51.37, 48.63, 2.73 +38.23, 35.00, 51.35, 48.65, 2.71 +38.23, 35.00, 51.34, 48.66, 2.68 +38.23, 35.00, 51.33, 48.67, 2.66 +38.23, 35.00, 51.32, 48.68, 2.64 +38.23, 35.00, 51.31, 48.69, 2.61 +38.23, 35.00, 51.29, 48.71, 2.59 +38.30, 35.00, 48.76, 51.24, -2.48 +38.23, 35.00, 53.74, 46.26, 7.48 +38.30, 35.00, 48.74, 51.26, -2.53 +38.30, 35.00, 51.19, 48.81, 2.39 +38.30, 35.00, 51.18, 48.82, 2.37 +38.30, 35.00, 51.17, 48.83, 2.34 +38.30, 35.00, 51.16, 48.84, 2.32 +38.30, 35.00, 51.15, 48.85, 2.29 +38.30, 35.00, 51.13, 48.87, 2.27 +38.30, 35.00, 51.12, 48.88, 2.24 +38.30, 35.00, 51.11, 48.89, 2.22 +38.30, 35.00, 51.10, 48.90, 2.19 +38.36, 35.00, 48.56, 51.44, -2.88 +38.36, 35.00, 51.02, 48.98, 2.04 +38.36, 35.00, 51.01, 48.99, 2.02 +38.36, 35.00, 51.00, 49.00, 1.99 +38.36, 35.00, 50.98, 49.02, 1.97 +38.36, 35.00, 50.97, 49.03, 1.94 +38.36, 35.00, 50.96, 49.04, 1.92 +38.36, 35.00, 50.95, 49.05, 1.89 +38.36, 35.00, 50.93, 49.07, 1.87 +38.36, 35.00, 50.92, 49.08, 1.84 +38.36, 35.00, 50.91, 49.09, 1.82 +38.36, 35.00, 50.90, 49.10, 1.79 +38.36, 35.00, 50.88, 49.12, 1.77 +38.36, 35.00, 50.87, 49.13, 1.74 +38.36, 35.00, 50.86, 49.14, 1.71 +38.36, 35.00, 50.84, 49.16, 1.69 +38.36, 35.00, 50.83, 49.17, 1.66 +38.30, 35.00, 53.34, 46.66, 6.68 +38.30, 35.00, 50.86, 49.14, 1.71 +38.30, 35.00, 50.84, 49.16, 1.69 +38.30, 35.00, 50.83, 49.17, 1.66 +38.23, 35.00, 53.34, 46.66, 6.68 +38.23, 35.00, 50.86, 49.14, 1.71 +38.23, 35.00, 50.85, 49.15, 1.69 +38.23, 35.00, 50.83, 49.17, 1.67 +38.23, 35.00, 50.82, 49.18, 1.64 +38.23, 35.00, 50.81, 49.19, 1.62 +38.23, 35.00, 50.80, 49.20, 1.59 +38.23, 35.00, 50.78, 49.22, 1.57 +38.23, 35.00, 50.77, 49.23, 1.54 +38.23, 35.00, 50.76, 49.24, 1.52 +38.23, 35.00, 50.75, 49.25, 1.50 +38.23, 35.00, 50.74, 49.26, 1.47 +38.10, 35.00, 55.77, 44.23, 11.53 +38.10, 35.00, 50.81, 49.19, 1.62 +38.10, 35.00, 50.80, 49.20, 1.60 +38.10, 35.00, 50.79, 49.21, 1.58 +38.03, 35.00, 53.30, 46.70, 6.60 +38.03, 35.00, 50.82, 49.18, 1.63 +38.03, 35.00, 50.80, 49.20, 1.61 +37.97, 35.00, 53.31, 46.69, 6.63 +37.97, 35.00, 50.83, 49.17, 1.66 +37.97, 35.00, 50.82, 49.18, 1.64 +37.97, 35.00, 50.81, 49.19, 1.62 +37.97, 35.00, 50.80, 49.20, 1.59 +37.97, 35.00, 50.79, 49.21, 1.57 +37.97, 35.00, 50.78, 49.22, 1.55 +37.97, 35.00, 50.76, 49.24, 1.53 +37.97, 35.00, 50.75, 49.25, 1.51 +37.97, 35.00, 50.74, 49.26, 1.48 +37.97, 35.00, 50.73, 49.27, 1.46 +37.97, 35.00, 50.72, 49.28, 1.44 +37.97, 35.00, 50.71, 49.29, 1.42 +37.97, 35.00, 50.70, 49.30, 1.39 +37.97, 35.00, 50.69, 49.31, 1.37 +37.84, 35.00, 55.72, 44.28, 11.44 +37.84, 35.00, 50.76, 49.24, 1.53 +37.84, 35.00, 50.75, 49.25, 1.51 +37.84, 35.00, 50.74, 49.26, 1.48 +37.77, 35.00, 53.25, 46.75, 6.51 +37.77, 35.00, 50.77, 49.23, 1.54 +37.77, 35.00, 50.76, 49.24, 1.52 +37.77, 35.00, 50.75, 49.25, 1.50 +37.77, 35.00, 50.74, 49.26, 1.48 +37.77, 35.00, 50.73, 49.27, 1.46 +37.77, 35.00, 50.72, 49.28, 1.44 +37.77, 35.00, 50.71, 49.29, 1.42 +37.77, 35.00, 50.70, 49.30, 1.40 +37.77, 35.00, 50.69, 49.31, 1.38 +37.77, 35.00, 50.68, 49.32, 1.36 +37.77, 35.00, 50.67, 49.33, 1.33 +37.77, 35.00, 50.66, 49.34, 1.31 +37.77, 35.00, 50.65, 49.35, 1.29 +37.71, 35.00, 53.16, 46.84, 6.32 +37.71, 35.00, 50.68, 49.32, 1.35 +37.71, 35.00, 50.67, 49.33, 1.33 +37.57, 35.00, 55.70, 44.30, 11.40 +37.57, 35.00, 50.75, 49.25, 1.49 +37.57, 35.00, 50.74, 49.26, 1.47 +37.51, 35.00, 53.25, 46.75, 6.49 +37.51, 35.00, 50.77, 49.23, 1.53 +37.51, 35.00, 50.76, 49.24, 1.51 +37.51, 35.00, 50.75, 49.25, 1.49 +37.51, 35.00, 50.74, 49.26, 1.48 +37.51, 35.00, 50.73, 49.27, 1.46 +37.57, 35.00, 48.20, 51.80, -3.61 +37.57, 35.00, 50.66, 49.34, 1.32 +37.57, 35.00, 50.65, 49.35, 1.30 +37.57, 35.00, 50.64, 49.36, 1.28 +37.57, 35.00, 50.63, 49.37, 1.26 +37.57, 35.00, 50.62, 49.38, 1.24 +37.57, 35.00, 50.61, 49.39, 1.22 +37.51, 35.00, 53.12, 46.88, 6.25 +37.51, 35.00, 50.64, 49.36, 1.28 +37.51, 35.00, 50.63, 49.37, 1.27 +37.51, 35.00, 50.62, 49.38, 1.25 +37.51, 35.00, 50.61, 49.39, 1.23 +37.51, 35.00, 50.60, 49.40, 1.21 +37.44, 35.00, 53.12, 46.88, 6.23 +37.44, 35.00, 50.64, 49.36, 1.27 +37.51, 35.00, 48.10, 51.90, -3.79 +37.51, 35.00, 50.57, 49.43, 1.13 +37.51, 35.00, 50.56, 49.44, 1.12 +37.51, 35.00, 50.55, 49.45, 1.10 +37.51, 35.00, 50.54, 49.46, 1.08 +37.57, 35.00, 48.01, 51.99, -3.98 +37.57, 35.00, 50.47, 49.53, 0.94 +37.57, 35.00, 50.46, 49.54, 0.92 +37.57, 35.00, 50.45, 49.55, 0.90 +37.57, 35.00, 50.44, 49.56, 0.88 +37.57, 35.00, 50.43, 49.57, 0.86 +37.57, 35.00, 50.42, 49.58, 0.84 +37.51, 35.00, 52.93, 47.07, 5.87 +37.57, 35.00, 47.93, 52.07, -4.14 +37.57, 35.00, 50.39, 49.61, 0.79 +37.57, 35.00, 50.38, 49.62, 0.77 +37.57, 35.00, 50.37, 49.63, 0.75 +37.57, 35.00, 50.36, 49.64, 0.73 +37.57, 35.00, 50.35, 49.65, 0.71 +37.71, 35.00, 45.30, 54.70, -9.40 +37.71, 35.00, 50.24, 49.76, 0.47 +37.71, 35.00, 50.23, 49.77, 0.45 +37.71, 35.00, 50.22, 49.78, 0.43 +37.71, 35.00, 50.21, 49.79, 0.41 +37.77, 35.00, 47.67, 52.33, -4.65 +37.77, 35.00, 50.13, 49.87, 0.27 +37.77, 35.00, 50.12, 49.88, 0.25 +37.77, 35.00, 50.11, 49.89, 0.23 +37.77, 35.00, 50.10, 49.90, 0.21 +37.77, 35.00, 50.09, 49.91, 0.19 +37.77, 35.00, 50.08, 49.92, 0.17 +37.77, 35.00, 50.07, 49.93, 0.15 +37.77, 35.00, 50.06, 49.94, 0.12 +37.77, 35.00, 50.05, 49.95, 0.10 +37.77, 35.00, 50.04, 49.96, 0.08 +37.77, 35.00, 50.03, 49.97, 0.06 +37.77, 35.00, 50.02, 49.98, 0.04 +37.77, 35.00, 50.01, 49.99, 0.02 +37.77, 35.00, 50.00, 50.00, -0.00 +37.77, 35.00, 49.99, 50.01, -0.02 +37.84, 35.00, 47.46, 52.54, -5.08 +37.84, 35.00, 49.92, 50.08, -0.16 +37.77, 35.00, 52.43, 47.57, 4.86 +37.84, 35.00, 47.43, 52.57, -5.15 +37.84, 35.00, 49.89, 50.11, -0.23 +37.77, 35.00, 52.40, 47.60, 4.80 +37.77, 35.00, 49.92, 50.08, -0.17 +37.77, 35.00, 49.91, 50.09, -0.19 +37.77, 35.00, 49.89, 50.11, -0.21 +37.77, 35.00, 49.88, 50.12, -0.23 +37.71, 35.00, 52.40, 47.60, 4.79 +37.71, 35.00, 49.91, 50.09, -0.17 +37.71, 35.00, 49.90, 50.10, -0.19 +37.71, 35.00, 49.89, 50.11, -0.21 +37.71, 35.00, 49.88, 50.12, -0.23 +37.71, 35.00, 49.87, 50.13, -0.25 +37.71, 35.00, 49.86, 50.14, -0.27 +37.71, 35.00, 49.85, 50.15, -0.29 +37.71, 35.00, 49.84, 50.16, -0.31 +37.71, 35.00, 49.83, 50.17, -0.33 +37.71, 35.00, 49.82, 50.18, -0.36 +37.71, 35.00, 49.81, 50.19, -0.38 +37.71, 35.00, 49.80, 50.20, -0.40 +37.71, 35.00, 49.79, 50.21, -0.42 +37.71, 35.00, 49.78, 50.22, -0.44 +37.57, 35.00, 54.81, 45.19, 9.63 +37.57, 35.00, 49.86, 50.14, -0.28 +37.57, 35.00, 49.85, 50.15, -0.30 +37.51, 35.00, 52.36, 47.64, 4.73 +37.51, 35.00, 49.88, 50.12, -0.24 +37.51, 35.00, 49.87, 50.13, -0.25 +37.51, 35.00, 49.86, 50.14, -0.27 +37.51, 35.00, 49.85, 50.15, -0.29 +37.51, 35.00, 49.84, 50.16, -0.31 +37.51, 35.00, 49.84, 50.16, -0.33 +37.51, 35.00, 49.83, 50.17, -0.35 +37.44, 35.00, 52.34, 47.66, 4.68 +37.44, 35.00, 49.86, 50.14, -0.29 +37.44, 35.00, 49.85, 50.15, -0.30 +37.44, 35.00, 49.84, 50.16, -0.32 +37.44, 35.00, 49.83, 50.17, -0.34 +37.44, 35.00, 49.82, 50.18, -0.36 +37.31, 35.00, 54.85, 45.15, 9.71 +37.31, 35.00, 49.90, 50.10, -0.20 +37.31, 35.00, 49.89, 50.11, -0.21 +37.31, 35.00, 49.88, 50.12, -0.23 +37.24, 35.00, 52.40, 47.60, 4.80 +37.24, 35.00, 49.92, 50.08, -0.17 +37.24, 35.00, 49.91, 50.09, -0.18 +37.24, 35.00, 49.90, 50.10, -0.20 +37.24, 35.00, 49.89, 50.11, -0.22 +37.18, 35.00, 52.41, 47.59, 4.81 +37.18, 35.00, 49.93, 50.07, -0.15 +37.18, 35.00, 49.92, 50.08, -0.17 +37.18, 35.00, 49.91, 50.09, -0.18 +37.05, 35.00, 54.94, 45.06, 9.89 +37.05, 35.00, 49.99, 50.01, -0.02 +37.05, 35.00, 49.98, 50.02, -0.03 +36.98, 35.00, 52.50, 47.50, 5.00 +36.98, 35.00, 50.02, 49.98, 0.04 +36.98, 35.00, 50.01, 49.99, 0.02 +36.98, 35.00, 50.00, 50.00, 0.01 +36.91, 35.00, 52.52, 47.48, 5.04 +36.91, 35.00, 50.04, 49.96, 0.08 +36.91, 35.00, 50.03, 49.97, 0.06 +36.78, 35.00, 55.07, 44.93, 10.14 +36.78, 35.00, 50.12, 49.88, 0.24 +36.78, 35.00, 50.11, 49.89, 0.22 +36.72, 35.00, 52.63, 47.37, 5.25 +36.72, 35.00, 50.15, 49.85, 0.30 +36.72, 35.00, 50.14, 49.86, 0.28 +36.72, 35.00, 50.13, 49.87, 0.27 +36.65, 35.00, 52.65, 47.35, 5.30 +36.65, 35.00, 50.17, 49.83, 0.34 +36.65, 35.00, 50.17, 49.83, 0.33 +36.65, 35.00, 50.16, 49.84, 0.32 +36.52, 35.00, 55.20, 44.80, 10.39 +36.52, 35.00, 50.25, 49.75, 0.49 +36.52, 35.00, 50.24, 49.76, 0.48 +36.52, 35.00, 50.24, 49.76, 0.47 +36.45, 35.00, 52.75, 47.25, 5.50 +36.45, 35.00, 50.27, 49.73, 0.55 +36.45, 35.00, 50.27, 49.73, 0.54 +36.45, 35.00, 50.26, 49.74, 0.53 +36.45, 35.00, 50.26, 49.74, 0.52 +36.45, 35.00, 50.25, 49.75, 0.50 +36.45, 35.00, 50.25, 49.75, 0.49 +36.45, 35.00, 50.24, 49.76, 0.48 +36.45, 35.00, 50.24, 49.76, 0.47 +36.45, 35.00, 50.23, 49.77, 0.46 +36.45, 35.00, 50.23, 49.77, 0.45 +36.39, 35.00, 52.74, 47.26, 5.48 +36.39, 35.00, 50.26, 49.74, 0.53 +36.39, 35.00, 50.26, 49.74, 0.52 +36.39, 35.00, 50.25, 49.75, 0.51 +36.39, 35.00, 50.25, 49.75, 0.50 +36.39, 35.00, 50.24, 49.76, 0.49 +36.25, 35.00, 55.28, 44.72, 10.56 +36.25, 35.00, 50.33, 49.67, 0.67 +36.25, 35.00, 50.33, 49.67, 0.66 +36.25, 35.00, 50.32, 49.68, 0.65 +36.25, 35.00, 50.32, 49.68, 0.64 +36.25, 35.00, 50.31, 49.69, 0.63 +36.25, 35.00, 50.31, 49.69, 0.62 +36.25, 35.00, 50.30, 49.70, 0.61 +36.25, 35.00, 50.30, 49.70, 0.60 +36.25, 35.00, 50.30, 49.70, 0.59 +36.25, 35.00, 50.29, 49.71, 0.58 +36.25, 35.00, 50.29, 49.71, 0.57 +36.25, 35.00, 50.28, 49.72, 0.56 +36.25, 35.00, 50.28, 49.72, 0.55 +36.19, 35.00, 52.79, 47.21, 5.59 +36.19, 35.00, 50.32, 49.68, 0.63 +36.19, 35.00, 50.31, 49.69, 0.63 +36.19, 35.00, 50.31, 49.69, 0.62 +36.19, 35.00, 50.30, 49.70, 0.61 +36.19, 35.00, 50.30, 49.70, 0.60 +36.19, 35.00, 50.29, 49.71, 0.59 +36.19, 35.00, 50.29, 49.71, 0.58 +36.19, 35.00, 50.29, 49.71, 0.57 +36.19, 35.00, 50.28, 49.72, 0.56 +36.19, 35.00, 50.28, 49.72, 0.55 +36.19, 35.00, 50.27, 49.73, 0.54 +36.19, 35.00, 50.27, 49.73, 0.54 +36.19, 35.00, 50.26, 49.74, 0.53 +36.19, 35.00, 50.26, 49.74, 0.52 +36.19, 35.00, 50.25, 49.75, 0.51 +36.12, 35.00, 52.77, 47.23, 5.54 +36.12, 35.00, 50.30, 49.70, 0.59 +36.19, 35.00, 47.77, 52.23, -4.46 +36.19, 35.00, 50.24, 49.76, 0.47 +36.19, 35.00, 50.23, 49.77, 0.47 +36.19, 35.00, 50.23, 49.77, 0.46 +36.19, 35.00, 50.22, 49.78, 0.45 +36.19, 35.00, 50.22, 49.78, 0.44 +36.19, 35.00, 50.21, 49.79, 0.43 +36.19, 35.00, 50.21, 49.79, 0.42 +36.19, 35.00, 50.21, 49.79, 0.41 +36.25, 35.00, 47.68, 52.32, -4.64 +36.25, 35.00, 50.15, 49.85, 0.29 +36.25, 35.00, 50.14, 49.86, 0.28 +36.25, 35.00, 50.14, 49.86, 0.28 +36.25, 35.00, 50.13, 49.87, 0.27 +36.25, 35.00, 50.13, 49.87, 0.26 +36.25, 35.00, 50.12, 49.88, 0.25 +36.25, 35.00, 50.12, 49.88, 0.24 +36.25, 35.00, 50.11, 49.89, 0.23 +36.25, 35.00, 50.11, 49.89, 0.22 +36.25, 35.00, 50.10, 49.90, 0.21 +36.25, 35.00, 50.10, 49.90, 0.20 +36.25, 35.00, 50.10, 49.90, 0.19 +36.25, 35.00, 50.09, 49.91, 0.18 +36.25, 35.00, 50.09, 49.91, 0.17 +36.39, 35.00, 45.04, 54.96, -9.92 +36.39, 35.00, 49.98, 50.02, -0.05 +36.39, 35.00, 49.97, 50.03, -0.06 +36.39, 35.00, 49.97, 50.03, -0.07 +36.39, 35.00, 49.96, 50.04, -0.08 +36.39, 35.00, 49.96, 50.04, -0.09 +36.45, 35.00, 47.43, 52.57, -5.14 +36.45, 35.00, 49.90, 50.10, -0.21 +36.45, 35.00, 49.89, 50.11, -0.22 +36.45, 35.00, 49.88, 50.12, -0.23 +36.45, 35.00, 49.88, 50.12, -0.24 +36.39, 35.00, 52.40, 47.60, 4.79 +36.45, 35.00, 47.40, 52.60, -5.21 +36.39, 35.00, 52.38, 47.62, 4.77 +36.39, 35.00, 49.91, 50.09, -0.18 +36.45, 35.00, 47.38, 52.62, -5.24 +36.39, 35.00, 52.37, 47.63, 4.74 +36.45, 35.00, 47.37, 52.63, -5.26 +36.45, 35.00, 49.84, 50.16, -0.33 +36.45, 35.00, 49.83, 50.17, -0.34 +36.45, 35.00, 49.83, 50.17, -0.35 +36.45, 35.00, 49.82, 50.18, -0.36 +36.45, 35.00, 49.81, 50.19, -0.37 +36.45, 35.00, 49.81, 50.19, -0.38 +36.45, 35.00, 49.80, 50.20, -0.39 +36.45, 35.00, 49.80, 50.20, -0.40 +36.52, 35.00, 47.27, 52.73, -5.46 +36.52, 35.00, 49.74, 50.26, -0.52 +36.52, 35.00, 49.73, 50.27, -0.54 +36.52, 35.00, 49.73, 50.27, -0.55 +36.52, 35.00, 49.72, 50.28, -0.56 +36.52, 35.00, 49.71, 50.29, -0.57 +36.52, 35.00, 49.71, 50.29, -0.58 +36.52, 35.00, 49.70, 50.30, -0.59 +36.52, 35.00, 49.70, 50.30, -0.60 +36.52, 35.00, 49.69, 50.31, -0.62 +36.52, 35.00, 49.69, 50.31, -0.63 +36.52, 35.00, 49.68, 50.32, -0.64 +36.52, 35.00, 49.68, 50.32, -0.65 +36.52, 35.00, 49.67, 50.33, -0.66 +36.52, 35.00, 49.66, 50.34, -0.67 +36.52, 35.00, 49.66, 50.34, -0.68 +36.52, 35.00, 49.65, 50.35, -0.70 +36.52, 35.00, 49.65, 50.35, -0.71 +36.52, 35.00, 49.64, 50.36, -0.72 +36.52, 35.00, 49.64, 50.36, -0.73 +36.52, 35.00, 49.63, 50.37, -0.74 +36.52, 35.00, 49.62, 50.38, -0.75 +36.52, 35.00, 49.62, 50.38, -0.76 +36.52, 35.00, 49.61, 50.39, -0.78 +36.52, 35.00, 49.61, 50.39, -0.79 +36.52, 35.00, 49.60, 50.40, -0.80 +36.52, 35.00, 49.60, 50.40, -0.81 +36.52, 35.00, 49.59, 50.41, -0.82 +36.45, 35.00, 52.11, 47.89, 4.21 +36.45, 35.00, 49.63, 50.37, -0.74 +36.45, 35.00, 49.62, 50.38, -0.75 +36.45, 35.00, 49.62, 50.38, -0.77 +36.45, 35.00, 49.61, 50.39, -0.78 +36.39, 35.00, 52.13, 47.87, 4.26 +36.45, 35.00, 47.13, 52.87, -5.74 +36.39, 35.00, 52.12, 47.88, 4.23 +36.39, 35.00, 49.64, 50.36, -0.72 +36.39, 35.00, 49.64, 50.36, -0.73 +36.39, 35.00, 49.63, 50.37, -0.74 +36.39, 35.00, 49.62, 50.38, -0.75 +36.39, 35.00, 49.62, 50.38, -0.76 +36.39, 35.00, 49.61, 50.39, -0.77 +36.39, 35.00, 49.61, 50.39, -0.78 +36.39, 35.00, 49.60, 50.40, -0.79 +36.39, 35.00, 49.60, 50.40, -0.80 +36.39, 35.00, 49.59, 50.41, -0.81 +36.39, 35.00, 49.59, 50.41, -0.82 +36.39, 35.00, 49.58, 50.42, -0.83 +36.25, 35.00, 54.62, 45.38, 9.24 +36.25, 35.00, 49.67, 50.33, -0.66 +36.25, 35.00, 49.67, 50.33, -0.66 +36.25, 35.00, 49.66, 50.34, -0.67 +36.25, 35.00, 49.66, 50.34, -0.68 +36.25, 35.00, 49.65, 50.35, -0.69 +36.25, 35.00, 49.65, 50.35, -0.70 +36.25, 35.00, 49.64, 50.36, -0.71 +36.25, 35.00, 49.64, 50.36, -0.72 +36.25, 35.00, 49.63, 50.37, -0.73 +36.25, 35.00, 49.63, 50.37, -0.74 +36.25, 35.00, 49.63, 50.37, -0.75 +36.25, 35.00, 49.62, 50.38, -0.76 +36.25, 35.00, 49.62, 50.38, -0.77 +36.25, 35.00, 49.61, 50.39, -0.78 +36.19, 35.00, 52.13, 47.87, 4.26 +36.19, 35.00, 49.65, 50.35, -0.70 +36.19, 35.00, 49.65, 50.35, -0.71 +36.19, 35.00, 49.64, 50.36, -0.71 +36.19, 35.00, 49.64, 50.36, -0.72 +36.19, 35.00, 49.63, 50.37, -0.73 +36.19, 35.00, 49.63, 50.37, -0.74 +36.19, 35.00, 49.63, 50.37, -0.75 +36.19, 35.00, 49.62, 50.38, -0.76 +36.19, 35.00, 49.62, 50.38, -0.77 +36.19, 35.00, 49.61, 50.39, -0.78 +36.19, 35.00, 49.61, 50.39, -0.79 +36.19, 35.00, 49.60, 50.40, -0.79 +36.12, 35.00, 52.12, 47.88, 4.24 +36.12, 35.00, 49.64, 50.36, -0.71 +36.12, 35.00, 49.64, 50.36, -0.72 +36.12, 35.00, 49.64, 50.36, -0.73 +36.12, 35.00, 49.63, 50.37, -0.74 +36.12, 35.00, 49.63, 50.37, -0.75 +35.99, 35.00, 54.67, 45.33, 9.33 +35.99, 35.00, 49.72, 50.28, -0.56 +35.99, 35.00, 49.71, 50.29, -0.57 +35.99, 35.00, 49.71, 50.29, -0.58 +35.93, 35.00, 52.23, 47.77, 4.46 +35.93, 35.00, 49.75, 50.25, -0.49 +35.93, 35.00, 49.75, 50.25, -0.50 +35.93, 35.00, 49.75, 50.25, -0.51 +35.93, 35.00, 49.74, 50.26, -0.51 +35.93, 35.00, 49.74, 50.26, -0.52 +35.93, 35.00, 49.74, 50.26, -0.53 +35.93, 35.00, 49.73, 50.27, -0.53 +35.93, 35.00, 49.73, 50.27, -0.54 +35.93, 35.00, 49.73, 50.27, -0.55 +35.93, 35.00, 49.72, 50.28, -0.56 +35.93, 35.00, 49.72, 50.28, -0.56 +35.93, 35.00, 49.72, 50.28, -0.57 +35.86, 35.00, 52.23, 47.77, 4.47 +35.86, 35.00, 49.76, 50.24, -0.48 +35.86, 35.00, 49.76, 50.24, -0.49 +35.86, 35.00, 49.75, 50.25, -0.50 +35.73, 35.00, 54.79, 45.21, 9.58 +35.73, 35.00, 49.85, 50.15, -0.31 +35.73, 35.00, 49.84, 50.16, -0.31 +35.73, 35.00, 49.84, 50.16, -0.32 +35.73, 35.00, 49.84, 50.16, -0.33 +35.73, 35.00, 49.83, 50.17, -0.33 +35.73, 35.00, 49.83, 50.17, -0.34 +35.73, 35.00, 49.83, 50.17, -0.34 +35.73, 35.00, 49.83, 50.17, -0.35 +35.73, 35.00, 49.82, 50.18, -0.35 +35.73, 35.00, 49.82, 50.18, -0.36 +35.73, 35.00, 49.82, 50.18, -0.36 +35.73, 35.00, 49.82, 50.18, -0.37 +35.73, 35.00, 49.81, 50.19, -0.37 +35.73, 35.00, 49.81, 50.19, -0.38 +35.73, 35.00, 49.81, 50.19, -0.39 +35.73, 35.00, 49.80, 50.20, -0.39 +35.73, 35.00, 49.80, 50.20, -0.40 +35.73, 35.00, 49.80, 50.20, -0.40 +35.66, 35.00, 52.32, 47.68, 4.64 +35.73, 35.00, 47.32, 52.68, -5.36 +35.73, 35.00, 49.79, 50.21, -0.42 +35.73, 35.00, 49.79, 50.21, -0.42 +35.73, 35.00, 49.79, 50.21, -0.43 +35.73, 35.00, 49.78, 50.22, -0.43 +35.73, 35.00, 49.78, 50.22, -0.44 +35.73, 35.00, 49.78, 50.22, -0.45 +35.73, 35.00, 49.77, 50.23, -0.45 +35.86, 35.00, 44.73, 55.27, -10.54 +35.86, 35.00, 49.67, 50.33, -0.66 +35.86, 35.00, 49.67, 50.33, -0.67 +35.86, 35.00, 49.66, 50.34, -0.67 +35.86, 35.00, 49.66, 50.34, -0.68 +35.86, 35.00, 49.66, 50.34, -0.69 +35.86, 35.00, 49.65, 50.35, -0.69 +35.86, 35.00, 49.65, 50.35, -0.70 +35.86, 35.00, 49.65, 50.35, -0.71 +35.86, 35.00, 49.64, 50.36, -0.71 +35.86, 35.00, 49.64, 50.36, -0.72 +35.93, 35.00, 47.12, 52.88, -5.77 +35.93, 35.00, 49.58, 50.42, -0.83 +35.93, 35.00, 49.58, 50.42, -0.84 +35.93, 35.00, 49.58, 50.42, -0.85 +35.93, 35.00, 49.57, 50.43, -0.85 +35.99, 35.00, 47.05, 52.95, -5.90 +35.93, 35.00, 52.04, 47.96, 4.08 +35.99, 35.00, 47.04, 52.96, -5.92 +35.99, 35.00, 49.51, 50.49, -0.98 +35.99, 35.00, 49.51, 50.49, -0.99 +35.99, 35.00, 49.50, 50.50, -1.00 +35.99, 35.00, 49.50, 50.50, -1.00 +35.99, 35.00, 49.49, 50.51, -1.01 +35.99, 35.00, 49.49, 50.51, -1.02 +36.12, 35.00, 44.44, 55.56, -11.11 +36.12, 35.00, 49.38, 50.62, -1.23 +36.12, 35.00, 49.38, 50.62, -1.24 +36.12, 35.00, 49.38, 50.62, -1.25 +36.12, 35.00, 49.37, 50.63, -1.26 +36.12, 35.00, 49.37, 50.63, -1.27 +36.12, 35.00, 49.36, 50.64, -1.28 +36.12, 35.00, 49.36, 50.64, -1.28 +35.99, 35.00, 54.40, 45.60, 8.79 +35.99, 35.00, 49.45, 50.55, -1.10 +35.99, 35.00, 49.45, 50.55, -1.11 +35.99, 35.00, 49.44, 50.56, -1.12 +35.99, 35.00, 49.44, 50.56, -1.12 +35.99, 35.00, 49.43, 50.57, -1.13 +35.99, 35.00, 49.43, 50.57, -1.14 +35.99, 35.00, 49.43, 50.57, -1.15 +35.99, 35.00, 49.42, 50.58, -1.15 +35.99, 35.00, 49.42, 50.58, -1.16 +35.99, 35.00, 49.42, 50.58, -1.17 +35.99, 35.00, 49.41, 50.59, -1.17 +35.93, 35.00, 51.93, 48.07, 3.86 +35.93, 35.00, 49.46, 50.54, -1.09 +35.93, 35.00, 49.45, 50.55, -1.10 +35.93, 35.00, 49.45, 50.55, -1.10 +35.93, 35.00, 49.44, 50.56, -1.11 +35.93, 35.00, 49.44, 50.56, -1.12 +35.93, 35.00, 49.44, 50.56, -1.12 +35.93, 35.00, 49.43, 50.57, -1.13 +35.86, 35.00, 51.95, 48.05, 3.90 +35.86, 35.00, 49.48, 50.52, -1.05 +35.86, 35.00, 49.47, 50.53, -1.05 +35.86, 35.00, 49.47, 50.53, -1.06 +35.73, 35.00, 54.51, 45.49, 9.02 +35.73, 35.00, 49.56, 50.44, -0.87 +35.73, 35.00, 49.56, 50.44, -0.88 +35.73, 35.00, 49.56, 50.44, -0.88 +35.66, 35.00, 52.08, 47.92, 4.16 +35.66, 35.00, 49.60, 50.40, -0.79 +35.66, 35.00, 49.60, 50.40, -0.80 +35.66, 35.00, 49.60, 50.40, -0.80 +35.66, 35.00, 49.60, 50.40, -0.81 +35.66, 35.00, 49.59, 50.41, -0.81 +35.66, 35.00, 49.59, 50.41, -0.82 +35.66, 35.00, 49.59, 50.41, -0.82 +35.66, 35.00, 49.59, 50.41, -0.83 +35.66, 35.00, 49.58, 50.42, -0.83 +35.66, 35.00, 49.58, 50.42, -0.84 +35.66, 35.00, 49.58, 50.42, -0.84 +35.66, 35.00, 49.58, 50.42, -0.85 +35.66, 35.00, 49.57, 50.43, -0.85 +35.66, 35.00, 49.57, 50.43, -0.86 +35.66, 35.00, 49.57, 50.43, -0.86 +35.66, 35.00, 49.57, 50.43, -0.87 +35.60, 35.00, 52.09, 47.91, 4.17 +35.60, 35.00, 49.61, 50.39, -0.78 +35.60, 35.00, 49.61, 50.39, -0.78 +35.60, 35.00, 49.61, 50.39, -0.79 +35.60, 35.00, 49.60, 50.40, -0.79 +35.60, 35.00, 49.60, 50.40, -0.80 +35.60, 35.00, 49.60, 50.40, -0.80 +35.60, 35.00, 49.60, 50.40, -0.80 +35.60, 35.00, 49.60, 50.40, -0.81 +35.60, 35.00, 49.59, 50.41, -0.81 +35.60, 35.00, 49.59, 50.41, -0.82 +35.60, 35.00, 49.59, 50.41, -0.82 +35.60, 35.00, 49.59, 50.41, -0.83 +35.60, 35.00, 49.58, 50.42, -0.83 +35.60, 35.00, 49.58, 50.42, -0.84 +35.60, 35.00, 49.58, 50.42, -0.84 +35.46, 35.00, 54.62, 45.38, 9.24 +35.46, 35.00, 49.68, 50.32, -0.65 +35.46, 35.00, 49.67, 50.33, -0.65 +35.46, 35.00, 49.67, 50.33, -0.66 +35.40, 35.00, 52.19, 47.81, 4.38 +35.46, 35.00, 47.20, 52.80, -5.61 +35.40, 35.00, 52.19, 47.81, 4.38 +35.40, 35.00, 49.71, 50.29, -0.57 +35.40, 35.00, 49.71, 50.29, -0.57 +35.40, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 49.71, 50.29, -0.59 +35.40, 35.00, 49.71, 50.29, -0.59 +35.40, 35.00, 49.70, 50.30, -0.59 +35.40, 35.00, 49.70, 50.30, -0.59 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.61 +35.40, 35.00, 49.70, 50.30, -0.61 +35.40, 35.00, 49.69, 50.31, -0.61 +35.33, 35.00, 52.21, 47.79, 4.43 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.53 +35.33, 35.00, 49.74, 50.26, -0.53 +35.33, 35.00, 49.73, 50.27, -0.53 +35.33, 35.00, 49.73, 50.27, -0.53 +35.33, 35.00, 49.73, 50.27, -0.54 +35.33, 35.00, 49.73, 50.27, -0.54 +35.33, 35.00, 49.73, 50.27, -0.54 +35.20, 35.00, 54.77, 45.23, 9.54 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.13, 35.00, 52.34, 47.66, 4.69 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.13, 35.00, 49.87, 50.13, -0.26 +35.07, 35.00, 52.39, 47.61, 4.78 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.17 +34.94, 35.00, 54.96, 45.04, 9.92 +34.94, 35.00, 50.02, 49.98, 0.03 +34.94, 35.00, 50.02, 49.98, 0.03 +34.94, 35.00, 50.02, 49.98, 0.03 +34.94, 35.00, 50.02, 49.98, 0.03 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.87, 35.00, 52.54, 47.46, 5.08 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.15 +34.80, 35.00, 52.59, 47.41, 5.19 +34.87, 35.00, 47.60, 52.40, -4.80 +34.87, 35.00, 50.07, 49.93, 0.15 +34.87, 35.00, 50.08, 49.92, 0.15 +34.87, 35.00, 50.08, 49.92, 0.15 +34.87, 35.00, 50.08, 49.92, 0.15 +34.87, 35.00, 50.08, 49.92, 0.15 +34.94, 35.00, 47.56, 52.44, -4.89 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +34.94, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 44.99, 55.01, -10.02 +35.07, 35.00, 49.93, 50.07, -0.14 +35.07, 35.00, 49.93, 50.07, -0.14 +35.13, 35.00, 47.41, 52.59, -5.18 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.24 +35.13, 35.00, 49.88, 50.12, -0.25 +35.20, 35.00, 47.35, 52.65, -5.29 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.20, 35.00, 49.82, 50.18, -0.35 +35.20, 35.00, 49.82, 50.18, -0.36 +35.20, 35.00, 49.82, 50.18, -0.36 +35.20, 35.00, 49.82, 50.18, -0.36 +35.33, 35.00, 44.78, 55.22, -10.45 +35.20, 35.00, 54.76, 45.24, 9.53 +35.33, 35.00, 44.77, 55.23, -10.45 +35.33, 35.00, 49.72, 50.28, -0.57 +35.33, 35.00, 49.72, 50.28, -0.57 +35.33, 35.00, 49.71, 50.29, -0.57 +35.33, 35.00, 49.71, 50.29, -0.57 +35.33, 35.00, 49.71, 50.29, -0.58 +35.33, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 47.19, 52.81, -5.62 +35.40, 35.00, 49.66, 50.34, -0.68 +35.40, 35.00, 49.66, 50.34, -0.69 +35.40, 35.00, 49.66, 50.34, -0.69 +35.40, 35.00, 49.65, 50.35, -0.69 +35.40, 35.00, 49.65, 50.35, -0.69 +35.40, 35.00, 49.65, 50.35, -0.70 +35.40, 35.00, 49.65, 50.35, -0.70 +35.40, 35.00, 49.65, 50.35, -0.70 +35.46, 35.00, 47.13, 52.87, -5.75 +35.46, 35.00, 49.60, 50.40, -0.81 +35.46, 35.00, 49.59, 50.41, -0.81 +35.46, 35.00, 49.59, 50.41, -0.82 +35.46, 35.00, 49.59, 50.41, -0.82 +35.46, 35.00, 49.59, 50.41, -0.82 +35.46, 35.00, 49.59, 50.41, -0.83 +35.46, 35.00, 49.59, 50.41, -0.83 +35.46, 35.00, 49.58, 50.42, -0.83 +35.46, 35.00, 49.58, 50.42, -0.84 +35.46, 35.00, 49.58, 50.42, -0.84 +35.46, 35.00, 49.58, 50.42, -0.84 +35.46, 35.00, 49.58, 50.42, -0.85 +35.46, 35.00, 49.57, 50.43, -0.85 +35.46, 35.00, 49.57, 50.43, -0.85 +35.46, 35.00, 49.57, 50.43, -0.86 +35.46, 35.00, 49.57, 50.43, -0.86 +35.46, 35.00, 49.57, 50.43, -0.86 +35.46, 35.00, 49.57, 50.43, -0.87 +35.46, 35.00, 49.56, 50.44, -0.87 +35.46, 35.00, 49.56, 50.44, -0.88 +35.40, 35.00, 52.08, 47.92, 4.16 +35.40, 35.00, 49.61, 50.39, -0.78 +35.40, 35.00, 49.61, 50.39, -0.79 +35.40, 35.00, 49.61, 50.39, -0.79 +35.40, 35.00, 49.60, 50.40, -0.79 +35.40, 35.00, 49.60, 50.40, -0.79 +35.40, 35.00, 49.60, 50.40, -0.80 +35.40, 35.00, 49.60, 50.40, -0.80 +35.40, 35.00, 49.60, 50.40, -0.80 +35.40, 35.00, 49.60, 50.40, -0.81 +35.40, 35.00, 49.60, 50.40, -0.81 +35.40, 35.00, 49.59, 50.41, -0.81 +35.33, 35.00, 52.11, 47.89, 4.23 +35.33, 35.00, 49.64, 50.36, -0.72 +35.33, 35.00, 49.64, 50.36, -0.72 +35.33, 35.00, 49.64, 50.36, -0.72 +35.33, 35.00, 49.64, 50.36, -0.73 +35.20, 35.00, 54.68, 45.32, 9.36 +35.20, 35.00, 49.73, 50.27, -0.53 +35.20, 35.00, 49.73, 50.27, -0.53 +35.20, 35.00, 49.73, 50.27, -0.53 +35.20, 35.00, 49.73, 50.27, -0.54 +35.20, 35.00, 49.73, 50.27, -0.54 +35.20, 35.00, 49.73, 50.27, -0.54 +35.13, 35.00, 52.25, 47.75, 4.50 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.45 +35.13, 35.00, 49.78, 50.22, -0.45 +35.07, 35.00, 52.30, 47.70, 4.60 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +34.94, 35.00, 54.87, 45.13, 9.73 +35.07, 35.00, 44.88, 55.12, -10.24 +34.94, 35.00, 54.87, 45.13, 9.73 +34.94, 35.00, 49.92, 50.08, -0.16 +34.94, 35.00, 49.92, 50.08, -0.16 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.87, 35.00, 52.45, 47.55, 4.89 +34.94, 35.00, 47.45, 52.55, -5.09 +34.94, 35.00, 49.93, 50.07, -0.15 +34.87, 35.00, 52.45, 47.55, 4.90 +34.87, 35.00, 49.98, 50.02, -0.05 +34.87, 35.00, 49.98, 50.02, -0.05 +34.87, 35.00, 49.98, 50.02, -0.04 +34.94, 35.00, 47.46, 52.54, -5.09 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 49.93, 50.07, -0.13 +35.07, 35.00, 44.89, 55.11, -10.22 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.07, 35.00, 49.83, 50.17, -0.33 +35.13, 35.00, 47.31, 52.69, -5.38 +35.07, 35.00, 52.30, 47.70, 4.61 +35.13, 35.00, 47.31, 52.69, -5.38 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.13, 35.00, 49.78, 50.22, -0.44 +35.07, 35.00, 52.30, 47.70, 4.60 +35.13, 35.00, 47.31, 52.69, -5.39 +35.13, 35.00, 49.78, 50.22, -0.45 +35.07, 35.00, 52.30, 47.70, 4.60 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.83, 50.17, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +35.07, 35.00, 49.82, 50.18, -0.35 +34.94, 35.00, 54.87, 45.13, 9.74 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.92, 50.08, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.94, 35.00, 49.93, 50.07, -0.15 +34.87, 35.00, 52.45, 47.55, 4.90 +34.94, 35.00, 47.46, 52.54, -5.09 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.94, 35.00, 49.93, 50.07, -0.14 +34.87, 35.00, 52.45, 47.55, 4.90 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.04 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.98, 50.02, -0.03 +34.87, 35.00, 49.99, 50.01, -0.03 +34.87, 35.00, 49.99, 50.01, -0.03 +34.80, 35.00, 52.51, 47.49, 5.02 +34.80, 35.00, 50.04, 49.96, 0.07 +34.80, 35.00, 50.04, 49.96, 0.08 +34.80, 35.00, 50.04, 49.96, 0.08 +34.67, 35.00, 55.08, 44.92, 10.16 +34.67, 35.00, 50.14, 49.86, 0.28 +34.67, 35.00, 50.14, 49.86, 0.28 +34.67, 35.00, 50.14, 49.86, 0.28 +34.67, 35.00, 50.14, 49.86, 0.29 +34.67, 35.00, 50.14, 49.86, 0.29 +34.67, 35.00, 50.15, 49.85, 0.29 +34.67, 35.00, 50.15, 49.85, 0.29 +34.67, 35.00, 50.15, 49.85, 0.30 +34.67, 35.00, 50.15, 49.85, 0.30 +34.67, 35.00, 50.15, 49.85, 0.30 +34.67, 35.00, 50.15, 49.85, 0.30 +34.67, 35.00, 50.15, 49.85, 0.31 +34.67, 35.00, 50.15, 49.85, 0.31 +34.61, 35.00, 52.68, 47.32, 5.35 +34.61, 35.00, 50.21, 49.79, 0.41 +34.61, 35.00, 50.21, 49.79, 0.42 +34.61, 35.00, 50.21, 49.79, 0.42 +34.61, 35.00, 50.21, 49.79, 0.42 +34.54, 35.00, 52.73, 47.27, 5.47 +34.54, 35.00, 50.26, 49.74, 0.53 +34.54, 35.00, 50.27, 49.73, 0.53 +34.54, 35.00, 50.27, 49.73, 0.53 +34.54, 35.00, 50.27, 49.73, 0.54 +34.54, 35.00, 50.27, 49.73, 0.54 +34.54, 35.00, 50.27, 49.73, 0.55 +34.54, 35.00, 50.27, 49.73, 0.55 +34.54, 35.00, 50.28, 49.72, 0.55 +34.54, 35.00, 50.28, 49.72, 0.56 +34.41, 35.00, 55.32, 44.68, 10.65 +34.41, 35.00, 50.38, 49.62, 0.76 +34.41, 35.00, 50.38, 49.62, 0.77 +34.41, 35.00, 50.39, 49.61, 0.77 +34.41, 35.00, 50.39, 49.61, 0.78 +34.34, 35.00, 52.91, 47.09, 5.82 +34.34, 35.00, 50.44, 49.56, 0.88 +34.34, 35.00, 50.44, 49.56, 0.89 +34.34, 35.00, 50.45, 49.55, 0.89 +34.34, 35.00, 50.45, 49.55, 0.90 +34.34, 35.00, 50.45, 49.55, 0.90 +34.34, 35.00, 50.45, 49.55, 0.91 +34.34, 35.00, 50.46, 49.54, 0.91 +34.34, 35.00, 50.46, 49.54, 0.92 +34.34, 35.00, 50.46, 49.54, 0.92 +34.34, 35.00, 50.46, 49.54, 0.93 +34.34, 35.00, 50.47, 49.53, 0.93 +34.34, 35.00, 50.47, 49.53, 0.94 +34.34, 35.00, 50.47, 49.53, 0.94 +34.34, 35.00, 50.47, 49.53, 0.95 +34.34, 35.00, 50.48, 49.52, 0.95 +34.34, 35.00, 50.48, 49.52, 0.96 +34.34, 35.00, 50.48, 49.52, 0.96 +34.34, 35.00, 50.48, 49.52, 0.97 +34.28, 35.00, 53.01, 46.99, 6.02 +34.34, 35.00, 48.02, 51.98, -3.97 +34.34, 35.00, 50.49, 49.51, 0.98 +34.34, 35.00, 50.49, 49.51, 0.99 +34.34, 35.00, 50.50, 49.50, 0.99 +34.34, 35.00, 50.50, 49.50, 1.00 +34.34, 35.00, 50.50, 49.50, 1.00 +34.34, 35.00, 50.50, 49.50, 1.01 +34.34, 35.00, 50.51, 49.49, 1.01 +34.34, 35.00, 50.51, 49.49, 1.02 +34.34, 35.00, 50.51, 49.49, 1.02 +34.34, 35.00, 50.51, 49.49, 1.03 +34.34, 35.00, 50.52, 49.48, 1.03 +34.34, 35.00, 50.52, 49.48, 1.04 +34.34, 35.00, 50.52, 49.48, 1.04 +34.41, 35.00, 48.00, 52.00, -4.00 +34.34, 35.00, 53.00, 47.00, 6.00 +34.41, 35.00, 48.01, 51.99, -3.99 +34.41, 35.00, 50.48, 49.52, 0.96 +34.41, 35.00, 50.48, 49.52, 0.97 +34.41, 35.00, 50.49, 49.51, 0.97 +34.41, 35.00, 50.49, 49.51, 0.97 +34.41, 35.00, 50.49, 49.51, 0.98 +34.54, 35.00, 45.45, 54.55, -9.10 +34.54, 35.00, 50.39, 49.61, 0.79 +34.54, 35.00, 50.40, 49.60, 0.79 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.81 +34.54, 35.00, 50.40, 49.60, 0.81 +34.61, 35.00, 47.88, 52.12, -4.23 +34.61, 35.00, 50.36, 49.64, 0.72 +34.54, 35.00, 52.88, 47.12, 5.76 +34.61, 35.00, 47.89, 52.11, -4.22 +34.61, 35.00, 50.36, 49.64, 0.73 +34.61, 35.00, 50.36, 49.64, 0.73 +34.61, 35.00, 50.37, 49.63, 0.73 +34.61, 35.00, 50.37, 49.63, 0.73 +34.61, 35.00, 50.37, 49.63, 0.74 +34.67, 35.00, 47.85, 52.15, -4.30 +34.67, 35.00, 50.32, 49.68, 0.64 +34.67, 35.00, 50.32, 49.68, 0.65 +34.67, 35.00, 50.32, 49.68, 0.65 +34.80, 35.00, 45.28, 54.72, -9.44 +34.80, 35.00, 50.23, 49.77, 0.45 +34.80, 35.00, 50.23, 49.77, 0.45 +34.87, 35.00, 47.71, 52.29, -4.59 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.87, 35.00, 50.18, 49.82, 0.36 +34.94, 35.00, 47.66, 52.34, -4.68 +34.94, 35.00, 50.13, 49.87, 0.27 +35.07, 35.00, 45.09, 54.91, -9.82 +35.07, 35.00, 50.03, 49.97, 0.07 +35.13, 35.00, 47.51, 52.49, -4.98 +35.13, 35.00, 49.98, 50.02, -0.03 +35.13, 35.00, 49.98, 50.02, -0.03 +35.13, 35.00, 49.98, 50.02, -0.03 +35.20, 35.00, 47.46, 52.54, -5.08 +35.20, 35.00, 49.93, 50.07, -0.14 +35.20, 35.00, 49.93, 50.07, -0.14 +35.20, 35.00, 49.93, 50.07, -0.14 +35.20, 35.00, 49.93, 50.07, -0.14 +35.33, 35.00, 44.89, 55.11, -10.23 +35.33, 35.00, 49.83, 50.17, -0.34 +35.33, 35.00, 49.83, 50.17, -0.35 +35.33, 35.00, 49.83, 50.17, -0.35 +35.33, 35.00, 49.82, 50.18, -0.35 +35.40, 35.00, 47.30, 52.70, -5.40 +35.40, 35.00, 49.77, 50.23, -0.46 +35.40, 35.00, 49.77, 50.23, -0.46 +35.40, 35.00, 49.77, 50.23, -0.46 +35.40, 35.00, 49.77, 50.23, -0.47 +35.46, 35.00, 47.24, 52.76, -5.51 +35.46, 35.00, 49.71, 50.29, -0.57 +35.46, 35.00, 49.71, 50.29, -0.57 +35.46, 35.00, 49.71, 50.29, -0.58 +35.46, 35.00, 49.71, 50.29, -0.58 +35.46, 35.00, 49.71, 50.29, -0.59 +35.46, 35.00, 49.71, 50.29, -0.59 +35.46, 35.00, 49.70, 50.30, -0.59 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.61 +35.46, 35.00, 49.70, 50.30, -0.61 +35.46, 35.00, 49.69, 50.31, -0.61 +35.46, 35.00, 49.69, 50.31, -0.62 +35.46, 35.00, 49.69, 50.31, -0.62 +35.46, 35.00, 49.69, 50.31, -0.62 +35.46, 35.00, 49.69, 50.31, -0.63 +35.46, 35.00, 49.68, 50.32, -0.63 +35.40, 35.00, 52.20, 47.80, 4.41 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.55 +35.40, 35.00, 49.73, 50.27, -0.55 +35.40, 35.00, 49.72, 50.28, -0.55 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.57 +35.40, 35.00, 49.71, 50.29, -0.57 +35.40, 35.00, 49.71, 50.29, -0.57 +35.33, 35.00, 52.23, 47.77, 4.47 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.49 +35.33, 35.00, 49.76, 50.24, -0.49 +35.33, 35.00, 49.75, 50.25, -0.49 +35.33, 35.00, 49.75, 50.25, -0.49 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.51 +35.33, 35.00, 49.75, 50.25, -0.51 +35.20, 35.00, 54.79, 45.21, 9.57 +35.20, 35.00, 49.84, 50.16, -0.31 +35.20, 35.00, 49.84, 50.16, -0.32 +35.13, 35.00, 52.36, 47.64, 4.73 +35.13, 35.00, 49.89, 50.11, -0.22 +35.13, 35.00, 49.89, 50.11, -0.22 +35.13, 35.00, 49.89, 50.11, -0.22 +35.13, 35.00, 49.89, 50.11, -0.22 +35.07, 35.00, 52.41, 47.59, 4.82 +35.07, 35.00, 49.94, 50.06, -0.12 +35.07, 35.00, 49.94, 50.06, -0.12 +35.07, 35.00, 49.94, 50.06, -0.13 +35.07, 35.00, 49.94, 50.06, -0.13 +34.94, 35.00, 54.98, 45.02, 9.96 +34.94, 35.00, 50.04, 49.96, 0.07 +34.94, 35.00, 50.04, 49.96, 0.07 +34.94, 35.00, 50.04, 49.96, 0.07 +34.87, 35.00, 52.56, 47.44, 5.12 +34.87, 35.00, 50.09, 49.91, 0.17 +34.87, 35.00, 50.09, 49.91, 0.18 +34.87, 35.00, 50.09, 49.91, 0.18 +34.80, 35.00, 52.61, 47.39, 5.22 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.28 +34.80, 35.00, 50.14, 49.86, 0.29 +34.80, 35.00, 50.14, 49.86, 0.29 +34.80, 35.00, 50.14, 49.86, 0.29 +34.80, 35.00, 50.15, 49.85, 0.29 +34.80, 35.00, 50.15, 49.85, 0.29 +34.80, 35.00, 50.15, 49.85, 0.29 +34.67, 35.00, 55.19, 44.81, 10.38 +34.67, 35.00, 50.25, 49.75, 0.50 +34.67, 35.00, 50.25, 49.75, 0.50 +34.67, 35.00, 50.25, 49.75, 0.50 +34.67, 35.00, 50.25, 49.75, 0.50 +34.67, 35.00, 50.25, 49.75, 0.51 +34.67, 35.00, 50.25, 49.75, 0.51 +34.67, 35.00, 50.26, 49.74, 0.51 +34.67, 35.00, 50.26, 49.74, 0.51 +34.67, 35.00, 50.26, 49.74, 0.52 +34.67, 35.00, 50.26, 49.74, 0.52 +34.67, 35.00, 50.26, 49.74, 0.52 +34.67, 35.00, 50.26, 49.74, 0.52 +34.67, 35.00, 50.26, 49.74, 0.53 +34.67, 35.00, 50.26, 49.74, 0.53 +34.67, 35.00, 50.27, 49.73, 0.53 +34.67, 35.00, 50.27, 49.73, 0.53 +34.67, 35.00, 50.27, 49.73, 0.53 +34.67, 35.00, 50.27, 49.73, 0.54 +34.67, 35.00, 50.27, 49.73, 0.54 +34.67, 35.00, 50.27, 49.73, 0.54 +34.67, 35.00, 50.27, 49.73, 0.54 +34.67, 35.00, 50.27, 49.73, 0.55 +34.67, 35.00, 50.27, 49.73, 0.55 +34.67, 35.00, 50.28, 49.72, 0.55 +34.67, 35.00, 50.28, 49.72, 0.55 +34.67, 35.00, 50.28, 49.72, 0.56 +34.67, 35.00, 50.28, 49.72, 0.56 +34.80, 35.00, 45.24, 54.76, -9.52 +34.80, 35.00, 50.18, 49.82, 0.36 +34.80, 35.00, 50.18, 49.82, 0.37 +34.80, 35.00, 50.18, 49.82, 0.37 +34.87, 35.00, 47.66, 52.34, -4.67 +34.87, 35.00, 50.14, 49.86, 0.27 +34.87, 35.00, 50.14, 49.86, 0.27 +34.87, 35.00, 50.14, 49.86, 0.27 +34.94, 35.00, 47.62, 52.38, -4.77 +34.94, 35.00, 50.09, 49.91, 0.17 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +34.94, 35.00, 50.09, 49.91, 0.18 +35.07, 35.00, 45.05, 54.95, -9.91 +34.94, 35.00, 55.03, 44.97, 10.07 +35.07, 35.00, 45.05, 54.95, -9.91 +35.07, 35.00, 49.99, 50.01, -0.02 +35.07, 35.00, 49.99, 50.01, -0.02 +35.13, 35.00, 47.47, 52.53, -5.06 +35.13, 35.00, 49.94, 50.06, -0.12 +35.13, 35.00, 49.94, 50.06, -0.12 +35.20, 35.00, 47.42, 52.58, -5.17 +35.20, 35.00, 49.89, 50.11, -0.22 +35.20, 35.00, 49.89, 50.11, -0.23 +35.20, 35.00, 49.89, 50.11, -0.23 +35.20, 35.00, 49.89, 50.11, -0.23 +35.20, 35.00, 49.88, 50.12, -0.23 +35.20, 35.00, 49.88, 50.12, -0.23 +35.20, 35.00, 49.88, 50.12, -0.23 +35.20, 35.00, 49.88, 50.12, -0.24 +35.33, 35.00, 44.84, 55.16, -10.32 +35.33, 35.00, 49.78, 50.22, -0.44 +35.33, 35.00, 49.78, 50.22, -0.44 +35.33, 35.00, 49.78, 50.22, -0.44 +35.40, 35.00, 47.26, 52.74, -5.49 +35.40, 35.00, 49.73, 50.27, -0.55 +35.40, 35.00, 49.72, 50.28, -0.55 +35.40, 35.00, 49.72, 50.28, -0.55 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.56 +35.40, 35.00, 49.72, 50.28, -0.57 +35.40, 35.00, 49.72, 50.28, -0.57 +35.33, 35.00, 52.24, 47.76, 4.47 +35.33, 35.00, 49.76, 50.24, -0.47 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.48 +35.33, 35.00, 49.76, 50.24, -0.49 +35.33, 35.00, 49.76, 50.24, -0.49 +35.33, 35.00, 49.75, 50.25, -0.49 +35.33, 35.00, 49.75, 50.25, -0.49 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.50 +35.33, 35.00, 49.75, 50.25, -0.51 +35.33, 35.00, 49.75, 50.25, -0.51 +35.33, 35.00, 49.74, 50.26, -0.51 +35.33, 35.00, 49.74, 50.26, -0.51 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.33, 35.00, 49.74, 50.26, -0.52 +35.20, 35.00, 54.78, 45.22, 9.56 +35.20, 35.00, 49.84, 50.16, -0.33 +35.20, 35.00, 49.83, 50.17, -0.33 +35.20, 35.00, 49.83, 50.17, -0.33 +35.20, 35.00, 49.83, 50.17, -0.33 +35.13, 35.00, 52.35, 47.65, 4.71 +35.13, 35.00, 49.88, 50.12, -0.24 +35.20, 35.00, 47.36, 52.64, -5.28 +35.13, 35.00, 52.35, 47.65, 4.70 +35.20, 35.00, 47.36, 52.64, -5.28 +35.20, 35.00, 49.83, 50.17, -0.34 +35.20, 35.00, 49.83, 50.17, -0.34 +35.20, 35.00, 49.83, 50.17, -0.34 +35.20, 35.00, 49.83, 50.17, -0.35 +35.20, 35.00, 49.83, 50.17, -0.35 +35.13, 35.00, 52.35, 47.65, 4.69 +35.13, 35.00, 49.87, 50.13, -0.25 +35.13, 35.00, 49.87, 50.13, -0.25 +35.13, 35.00, 49.87, 50.13, -0.25 +35.07, 35.00, 52.39, 47.61, 4.79 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +35.07, 35.00, 49.92, 50.08, -0.16 +34.94, 35.00, 54.96, 45.04, 9.93 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.94, 35.00, 50.02, 49.98, 0.04 +34.87, 35.00, 52.54, 47.46, 5.08 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.14 +34.87, 35.00, 50.07, 49.93, 0.15 +34.87, 35.00, 50.07, 49.93, 0.15 +34.87, 35.00, 50.07, 49.93, 0.15 +34.80, 35.00, 52.60, 47.40, 5.19 +34.80, 35.00, 50.12, 49.88, 0.25 +34.80, 35.00, 50.13, 49.87, 0.25 +34.80, 35.00, 50.13, 49.87, 0.25 +34.67, 35.00, 55.17, 44.83, 10.34 +34.67, 35.00, 50.23, 49.77, 0.45 +34.67, 35.00, 50.23, 49.77, 0.46 +34.67, 35.00, 50.23, 49.77, 0.46 +34.67, 35.00, 50.23, 49.77, 0.46 +34.67, 35.00, 50.23, 49.77, 0.46 +34.67, 35.00, 50.23, 49.77, 0.47 +34.67, 35.00, 50.23, 49.77, 0.47 +34.61, 35.00, 52.76, 47.24, 5.52 +34.67, 35.00, 47.77, 52.23, -4.47 +34.61, 35.00, 52.76, 47.24, 5.52 +34.61, 35.00, 50.29, 49.71, 0.58 +34.61, 35.00, 50.29, 49.71, 0.58 +34.61, 35.00, 50.29, 49.71, 0.59 +34.61, 35.00, 50.29, 49.71, 0.59 +34.61, 35.00, 50.30, 49.70, 0.59 +34.61, 35.00, 50.30, 49.70, 0.59 +34.61, 35.00, 50.30, 49.70, 0.60 +34.61, 35.00, 50.30, 49.70, 0.60 +34.61, 35.00, 50.30, 49.70, 0.60 +34.61, 35.00, 50.30, 49.70, 0.61 +34.61, 35.00, 50.30, 49.70, 0.61 +34.61, 35.00, 50.31, 49.69, 0.61 +34.61, 35.00, 50.31, 49.69, 0.62 +34.61, 35.00, 50.31, 49.69, 0.62 +34.61, 35.00, 50.31, 49.69, 0.62 +34.61, 35.00, 50.31, 49.69, 0.62 +34.61, 35.00, 50.31, 49.69, 0.63 +34.61, 35.00, 50.31, 49.69, 0.63 +34.61, 35.00, 50.32, 49.68, 0.63 +34.61, 35.00, 50.32, 49.68, 0.64 +34.61, 35.00, 50.32, 49.68, 0.64 +34.61, 35.00, 50.32, 49.68, 0.64 +34.61, 35.00, 50.32, 49.68, 0.64 +34.61, 35.00, 50.32, 49.68, 0.65 +34.61, 35.00, 50.33, 49.67, 0.65 +34.61, 35.00, 50.33, 49.67, 0.65 +34.61, 35.00, 50.33, 49.67, 0.66 +34.67, 35.00, 47.81, 52.19, -4.38 +34.67, 35.00, 50.28, 49.72, 0.56 +34.67, 35.00, 50.28, 49.72, 0.56 +34.67, 35.00, 50.28, 49.72, 0.57 +34.67, 35.00, 50.28, 49.72, 0.57 +34.67, 35.00, 50.29, 49.71, 0.57 +34.67, 35.00, 50.29, 49.71, 0.57 +34.67, 35.00, 50.29, 49.71, 0.58 +34.67, 35.00, 50.29, 49.71, 0.58 +34.67, 35.00, 50.29, 49.71, 0.58 +34.80, 35.00, 45.25, 54.75, -9.50 +34.80, 35.00, 50.19, 49.81, 0.39 +34.80, 35.00, 50.19, 49.81, 0.39 +34.80, 35.00, 50.20, 49.80, 0.39 +34.87, 35.00, 47.67, 52.33, -4.65 +34.87, 35.00, 50.15, 49.85, 0.29 +34.87, 35.00, 50.15, 49.85, 0.29 +34.94, 35.00, 47.63, 52.37, -4.75 +34.94, 35.00, 50.10, 49.90, 0.20 +34.94, 35.00, 50.10, 49.90, 0.20 +35.07, 35.00, 45.06, 54.94, -9.89 +35.07, 35.00, 50.00, 50.00, -0.00 +35.07, 35.00, 50.00, 50.00, -0.00 +35.13, 35.00, 47.48, 52.52, -5.05 +35.13, 35.00, 49.95, 50.05, -0.10 +35.13, 35.00, 49.95, 50.05, -0.10 +35.13, 35.00, 49.95, 50.05, -0.11 +35.13, 35.00, 49.95, 50.05, -0.11 +35.20, 35.00, 47.42, 52.58, -5.15 +35.20, 35.00, 49.90, 50.10, -0.21 +35.20, 35.00, 49.90, 50.10, -0.21 +35.20, 35.00, 49.89, 50.11, -0.21 +35.33, 35.00, 44.85, 55.15, -10.30 +35.33, 35.00, 49.79, 50.21, -0.41 +35.33, 35.00, 49.79, 50.21, -0.42 +35.40, 35.00, 47.27, 52.73, -5.46 +35.40, 35.00, 49.74, 50.26, -0.52 +35.40, 35.00, 49.74, 50.26, -0.52 +35.40, 35.00, 49.74, 50.26, -0.53 +35.40, 35.00, 49.73, 50.27, -0.53 +35.40, 35.00, 49.73, 50.27, -0.53 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.54 +35.40, 35.00, 49.73, 50.27, -0.55 +35.46, 35.00, 47.20, 52.80, -5.59 +35.40, 35.00, 52.20, 47.80, 4.39 +35.40, 35.00, 49.72, 50.28, -0.55 +35.40, 35.00, 49.72, 50.28, -0.56 +35.46, 35.00, 47.20, 52.80, -5.60 +35.46, 35.00, 49.67, 50.33, -0.66 +35.46, 35.00, 49.67, 50.33, -0.67 +35.40, 35.00, 52.19, 47.81, 4.37 +35.40, 35.00, 49.71, 50.29, -0.57 +35.46, 35.00, 47.19, 52.81, -5.62 +35.40, 35.00, 52.18, 47.82, 4.36 +35.40, 35.00, 49.71, 50.29, -0.58 +35.40, 35.00, 49.71, 50.29, -0.59 +35.40, 35.00, 49.71, 50.29, -0.59 +35.40, 35.00, 49.70, 50.30, -0.59 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.40, 35.00, 49.70, 50.30, -0.60 +35.33, 35.00, 52.22, 47.78, 4.44 +35.33, 35.00, 49.74, 50.26, -0.51 +35.33, 35.00, 49.74, 50.26, -0.51 +35.33, 35.00, 49.74, 50.26, -0.52 +35.20, 35.00, 54.78, 45.22, 9.57 +35.20, 35.00, 49.84, 50.16, -0.32 +35.20, 35.00, 49.84, 50.16, -0.32 +35.20, 35.00, 49.84, 50.16, -0.32 +35.13, 35.00, 52.36, 47.64, 4.72 +35.13, 35.00, 49.89, 50.11, -0.23 +35.13, 35.00, 49.89, 50.11, -0.23 +35.13, 35.00, 49.89, 50.11, -0.23 +35.07, 35.00, 52.41, 47.59, 4.81 +35.07, 35.00, 49.93, 50.07, -0.13 +35.07, 35.00, 49.93, 50.07, -0.13 +35.07, 35.00, 49.93, 50.07, -0.13 +34.94, 35.00, 54.98, 45.02, 9.95 +34.94, 35.00, 50.03, 49.97, 0.07 +34.94, 35.00, 50.03, 49.97, 0.07 +34.94, 35.00, 50.03, 49.97, 0.07 +34.94, 35.00, 50.03, 49.97, 0.07 +34.87, 35.00, 52.56, 47.44, 5.11 +34.87, 35.00, 50.08, 49.92, 0.17 +34.87, 35.00, 50.08, 49.92, 0.17 +34.87, 35.00, 50.09, 49.91, 0.17 +34.80, 35.00, 52.61, 47.39, 5.22 +34.80, 35.00, 50.14, 49.86, 0.27 +34.80, 35.00, 50.14, 49.86, 0.27 +34.67, 35.00, 55.18, 44.82, 10.36 +34.67, 35.00, 50.24, 49.76, 0.48 +34.67, 35.00, 50.24, 49.76, 0.48 +34.67, 35.00, 50.24, 49.76, 0.48 +34.67, 35.00, 50.24, 49.76, 0.48 +34.61, 35.00, 52.76, 47.24, 5.53 +34.61, 35.00, 50.29, 49.71, 0.59 +34.61, 35.00, 50.30, 49.70, 0.59 +34.61, 35.00, 50.30, 49.70, 0.59 +34.54, 35.00, 52.82, 47.18, 5.64 +34.54, 35.00, 50.35, 49.65, 0.70 +34.54, 35.00, 50.35, 49.65, 0.70 +34.54, 35.00, 50.35, 49.65, 0.71 +34.41, 35.00, 55.40, 44.60, 10.80 +34.54, 35.00, 45.41, 54.59, -9.17 +34.41, 35.00, 55.40, 44.60, 10.81 +34.41, 35.00, 50.46, 49.54, 0.92 +34.41, 35.00, 50.46, 49.54, 0.93 +34.41, 35.00, 50.47, 49.53, 0.93 +34.41, 35.00, 50.47, 49.53, 0.94 +34.41, 35.00, 50.47, 49.53, 0.94 +34.41, 35.00, 50.47, 49.53, 0.94 +34.34, 35.00, 53.00, 47.00, 5.99 +34.34, 35.00, 50.53, 49.47, 1.05 +34.34, 35.00, 50.53, 49.47, 1.06 +34.34, 35.00, 50.53, 49.47, 1.06 +34.34, 35.00, 50.53, 49.47, 1.07 +34.34, 35.00, 50.54, 49.46, 1.07 +34.41, 35.00, 48.02, 51.98, -3.97 +34.41, 35.00, 50.49, 49.51, 0.98 +34.41, 35.00, 50.49, 49.51, 0.99 +34.41, 35.00, 50.50, 49.50, 0.99 +34.54, 35.00, 45.45, 54.55, -9.09 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.80 +34.54, 35.00, 50.40, 49.60, 0.81 +34.54, 35.00, 50.41, 49.59, 0.81 +34.61, 35.00, 47.89, 52.11, -4.23 +34.61, 35.00, 50.36, 49.64, 0.72 +34.61, 35.00, 50.36, 49.64, 0.72 +34.61, 35.00, 50.36, 49.64, 0.72 +34.61, 35.00, 50.36, 49.64, 0.73 +34.61, 35.00, 50.36, 49.64, 0.73 +34.61, 35.00, 50.37, 49.63, 0.73 +34.61, 35.00, 50.37, 49.63, 0.74 +34.67, 35.00, 47.85, 52.15, -4.30 +34.67, 35.00, 50.32, 49.68, 0.64 +34.67, 35.00, 50.32, 49.68, 0.64 +34.67, 35.00, 50.32, 49.68, 0.65 +34.80, 35.00, 45.28, 54.72, -9.44 +34.87, 35.00, 47.70, 52.30, -4.59 +34.87, 35.00, 50.18, 49.82, 0.35 +34.87, 35.00, 50.18, 49.82, 0.35 +34.87, 35.00, 50.18, 49.82, 0.36 +34.94, 35.00, 47.66, 52.34, -4.69 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +35.07, 35.00, 45.09, 54.91, -9.82 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.13, 35.00, 47.51, 52.49, -4.98 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.07, 35.00, 52.50, 47.50, 5.00 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.03, 49.97, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +34.94, 35.00, 55.07, 44.93, 10.13 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +35.07, 35.00, 45.08, 54.92, -9.84 +35.07, 35.00, 50.02, 49.98, 0.05 +35.07, 35.00, 50.02, 49.98, 0.05 +34.94, 35.00, 55.07, 44.93, 10.13 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.94, 35.00, 50.12, 49.88, 0.25 +34.87, 35.00, 52.65, 47.35, 5.29 +34.87, 35.00, 50.17, 49.83, 0.35 +34.94, 35.00, 47.65, 52.35, -4.69 +34.87, 35.00, 52.65, 47.35, 5.29 +34.94, 35.00, 47.65, 52.35, -4.69 +34.94, 35.00, 50.13, 49.87, 0.25 +34.94, 35.00, 50.13, 49.87, 0.25 +34.94, 35.00, 50.13, 49.87, 0.25 +34.94, 35.00, 50.13, 49.87, 0.25 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +34.94, 35.00, 50.13, 49.87, 0.26 +35.07, 35.00, 45.09, 54.91, -9.83 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.07, 35.00, 50.03, 49.97, 0.06 +35.13, 35.00, 47.51, 52.49, -4.98 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.04 +35.13, 35.00, 49.98, 50.02, -0.05 +35.13, 35.00, 49.98, 50.02, -0.05 +35.13, 35.00, 49.98, 50.02, -0.05 +35.20, 35.00, 47.45, 52.55, -5.09 +35.20, 35.00, 49.93, 50.07, -0.15 +35.20, 35.00, 49.92, 50.08, -0.15 +35.33, 35.00, 44.88, 55.12, -10.24 +35.33, 35.00, 49.82, 50.18, -0.35 +35.33, 35.00, 49.82, 50.18, -0.36 +35.33, 35.00, 49.82, 50.18, -0.36 +35.40, 35.00, 47.30, 52.70, -5.40 +35.40, 35.00, 49.77, 50.23, -0.46 +35.40, 35.00, 49.77, 50.23, -0.47 +35.40, 35.00, 49.77, 50.23, -0.47 +35.40, 35.00, 49.76, 50.24, -0.47 +35.40, 35.00, 49.76, 50.24, -0.48 +35.40, 35.00, 49.76, 50.24, -0.48 +35.40, 35.00, 49.76, 50.24, -0.48 +35.40, 35.00, 49.76, 50.24, -0.48 +35.46, 35.00, 47.23, 52.77, -5.53 +35.46, 35.00, 49.70, 50.30, -0.59 +35.46, 35.00, 49.70, 50.30, -0.59 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.60 +35.46, 35.00, 49.70, 50.30, -0.61 +35.60, 35.00, 44.65, 55.35, -10.70 +35.60, 35.00, 49.59, 50.41, -0.81 +35.60, 35.00, 49.59, 50.41, -0.82 +35.60, 35.00, 49.59, 50.41, -0.82 +35.60, 35.00, 49.59, 50.41, -0.83 +35.60, 35.00, 49.58, 50.42, -0.83 +35.60, 35.00, 49.58, 50.42, -0.84 +35.60, 35.00, 49.58, 50.42, -0.84 +35.60, 35.00, 49.58, 50.42, -0.85 +35.60, 35.00, 49.58, 50.42, -0.85 +35.60, 35.00, 49.57, 50.43, -0.85 +35.60, 35.00, 49.57, 50.43, -0.86 +35.60, 35.00, 49.57, 50.43, -0.86 +35.60, 35.00, 49.57, 50.43, -0.87 +35.60, 35.00, 49.56, 50.44, -0.87 +35.60, 35.00, 49.56, 50.44, -0.88 +35.60, 35.00, 49.56, 50.44, -0.88 +35.46, 35.00, 54.60, 45.40, 9.20 +35.46, 35.00, 49.65, 50.35, -0.69 +35.46, 35.00, 49.65, 50.35, -0.69 +35.46, 35.00, 49.65, 50.35, -0.70 +35.46, 35.00, 49.65, 50.35, -0.70 +35.40, 35.00, 52.17, 47.83, 4.34 +35.40, 35.00, 49.70, 50.30, -0.61 +35.40, 35.00, 49.69, 50.31, -0.61 +35.40, 35.00, 49.69, 50.31, -0.61 +35.40, 35.00, 49.69, 50.31, -0.62 +35.40, 0.00, 25.00, 75.00, -50.00 +35.40, 0.00, 25.00, 75.00, -50.00 +35.40, 0.00, 25.00, 75.00, -50.00 +35.33, 0.00, 25.43, 74.57, -49.14 +35.33, 0.00, 25.00, 75.00, -50.00 +35.33, 0.00, 25.00, 75.00, -50.00 +35.20, 0.00, 27.61, 72.39, -44.79 +35.20, 0.00, 25.00, 75.00, -50.00 +35.13, 0.00, 25.00, 75.00, -50.00 +35.13, 0.00, 25.00, 75.00, -50.00 +35.07, 0.00, 25.00, 75.00, -50.00 +34.94, 0.00, 27.15, 72.85, -45.71 +34.87, 0.00, 25.00, 75.00, -50.00 +34.67, 0.00, 29.55, 70.45, -40.89 +34.61, 0.00, 25.00, 75.00, -50.00 +34.54, 0.00, 25.00, 75.00, -50.00 +34.34, 0.00, 29.41, 70.59, -41.17 +34.28, 0.00, 25.00, 75.00, -50.00 +34.08, 0.00, 29.36, 70.64, -41.29 +33.88, 0.00, 29.38, 70.62, -41.25 +33.75, 0.00, 26.88, 73.12, -46.25 +33.55, 0.00, 29.37, 70.63, -41.26 +33.35, 0.00, 29.39, 70.61, -41.21 +33.09, 0.00, 31.94, 68.06, -36.12 +32.83, 0.00, 32.01, 67.99, -35.97 +32.70, 0.00, 27.05, 72.95, -45.91 +32.43, 0.00, 32.07, 67.93, -35.87 +32.17, 0.00, 32.14, 67.86, -35.71 +31.77, 0.00, 37.27, 62.73, -25.47 +31.64, 0.00, 27.36, 72.64, -45.28 +31.25, 0.00, 37.43, 62.57, -25.15 +30.98, 0.00, 32.56, 67.44, -34.87 +30.65, 0.00, 35.17, 64.83, -29.67 +30.32, 0.00, 35.30, 64.70, -29.40 +29.93, 0.00, 37.96, 62.04, -24.09 +29.60, 0.00, 35.62, 64.38, -28.76 +29.27, 0.00, 35.76, 64.24, -28.48 +28.81, 0.00, 40.94, 59.06, -18.12 +28.48, 0.00, 36.14, 63.86, -27.73 +28.02, 0.00, 41.32, 58.68, -17.36 +27.69, 0.00, 36.52, 63.48, -26.96 +27.22, 0.00, 41.71, 58.29, -16.58 +26.76, 0.00, 41.96, 58.04, -16.09 +26.37, 0.00, 39.68, 60.32, -20.64 +25.91, 0.00, 42.40, 57.60, -15.20 +25.38, 0.00, 45.17, 54.83, -9.65 +24.92, 0.00, 42.95, 57.05, -14.09 +24.52, 0.00, 40.69, 59.31, -18.63 +23.99, 0.00, 45.94, 54.06, -8.13 +23.53, 0.00, 43.72, 56.28, -12.55 +23.01, 0.00, 46.50, 53.50, -6.99 +22.48, 0.00, 46.82, 53.18, -6.37 +21.95, 0.00, 47.13, 52.87, -5.74 +21.42, 0.00, 47.44, 52.56, -5.11 +20.90, 0.00, 47.76, 52.24, -4.48 +20.30, 0.00, 50.60, 49.40, 1.20 +19.78, 0.00, 48.45, 51.55, -3.10 +19.12, 0.00, 53.82, 46.18, 7.63 +18.59, 0.00, 49.20, 50.80, -1.60 +18.06, 0.00, 49.53, 50.47, -0.95 +17.47, 0.00, 52.38, 47.62, 4.76 +16.87, 0.00, 52.76, 47.24, 5.52 +16.35, 0.00, 50.62, 49.38, 1.24 +15.69, 0.00, 56.00, 44.00, 12.00 +15.10, 0.00, 53.92, 46.08, 7.84 +14.57, 0.00, 51.79, 48.21, 3.57 +13.97, 0.00, 54.65, 45.35, 9.30 +13.45, 0.00, 52.52, 47.48, 5.05 +12.79, 0.00, 57.92, 42.08, 15.83 +12.19, 0.00, 55.84, 44.16, 11.68 +11.60, 0.00, 56.24, 43.76, 12.49 +10.94, 0.00, 59.17, 40.83, 18.34 +10.35, 0.00, 57.10, 42.90, 14.21 +9.76, 0.00, 57.51, 42.49, 15.02 +9.10, 0.00, 60.44, 39.56, 20.89 +8.50, 0.00, 58.38, 41.62, 16.77 +7.91, 0.00, 58.80, 41.20, 17.60 +7.25, 0.00, 61.74, 38.26, 23.48 +6.66, 0.00, 59.69, 40.31, 19.37 +6.06, 0.00, 60.11, 39.89, 20.22 +5.41, 0.00, 63.06, 36.94, 26.11 +4.88, 0.00, 58.49, 41.51, 16.98 +4.28, 0.00, 61.39, 38.61, 22.78 +3.69, 0.00, 61.82, 38.18, 23.64 +3.16, 0.00, 59.73, 40.27, 19.47 +2.64, 0.00, 60.12, 39.88, 20.24 +1.98, 0.00, 65.55, 34.45, 31.10 +1.58, 0.00, 55.95, 44.05, 11.90 +1.05, 0.00, 61.29, 38.71, 22.57 +0.53, 0.00, 61.68, 38.32, 23.36 +0.00, 0.00, 62.08, 37.92, 24.15 +-0.46, 0.00, 59.95, 40.05, 19.90 +-0.99, 0.00, 62.82, 37.18, 25.65 +-1.52, 0.00, 63.22, 36.78, 26.45 +-1.98, 0.00, 61.11, 38.89, 22.21 +-2.50, 0.00, 63.98, 36.02, 27.97 +-3.03, 0.00, 64.39, 35.61, 28.78 +-3.43, 0.00, 59.76, 40.24, 19.51 +-3.96, 0.00, 65.11, 34.89, 30.22 +-4.42, 0.00, 63.00, 37.00, 26.00 +-4.88, 0.00, 63.36, 36.64, 26.73 +-5.27, 0.00, 61.21, 38.79, 22.42 +-5.73, 0.00, 64.05, 35.95, 28.10 +-6.20, 0.00, 64.42, 35.58, 28.84 +-6.59, 0.00, 62.27, 37.73, 24.54 +-7.05, 0.00, 65.11, 34.89, 30.22 +-7.38, 0.00, 60.44, 39.56, 20.89 +-7.78, 0.00, 63.24, 36.76, 26.48 +-8.11, 0.00, 61.05, 38.95, 22.09 +-8.44, 0.00, 61.33, 38.67, 22.65 +-8.83, 0.00, 64.13, 35.87, 28.25 +-9.16, 0.00, 61.94, 38.06, 23.87 +-9.49, 0.00, 62.22, 37.78, 24.44 +-9.76, 0.00, 59.98, 40.02, 19.96 +-10.15, 0.00, 65.26, 34.74, 30.52 +-10.48, 0.00, 63.07, 36.93, 26.15 +-10.74, 0.00, 60.84, 39.16, 21.68 +-11.01, 0.00, 61.08, 38.92, 22.16 +-11.27, 0.00, 61.32, 38.68, 22.64 +-11.54, 0.00, 61.56, 38.44, 23.12 +-11.80, 0.00, 61.80, 38.20, 23.61 +-12.00, 0.00, 59.52, 40.48, 19.05 +-12.26, 0.00, 62.24, 37.76, 24.48 +-12.39, 0.00, 57.44, 42.56, 14.88 +-12.59, 0.00, 60.11, 39.89, 20.22 +-12.85, 0.00, 62.83, 37.17, 25.65 +-13.05, 0.00, 60.55, 39.45, 21.10 +-13.18, 0.00, 58.23, 41.77, 16.46 +-13.38, 0.00, 60.90, 39.10, 21.80 +-13.58, 0.00, 61.10, 38.90, 22.20 +-13.65, 0.00, 56.26, 43.74, 12.51 +-13.84, 0.00, 61.40, 38.60, 22.80 +-13.91, 0.00, 56.56, 43.44, 13.11 +-14.11, 0.00, 61.70, 38.30, 23.40 +-14.17, 0.00, 56.86, 43.14, 13.72 +-14.24, 0.00, 56.96, 43.04, 13.93 +-14.44, 0.00, 62.11, 37.89, 24.22 +-14.50, 0.00, 57.27, 42.73, 14.54 +-14.63, 0.00, 59.90, 40.10, 19.79 +-14.70, 0.00, 57.53, 42.47, 15.06 +-14.77, 0.00, 57.63, 42.37, 15.27 +-14.90, 0.00, 60.26, 39.74, 20.52 +-14.90, 0.00, 55.37, 44.63, 10.74 +-14.90, 0.00, 55.43, 44.57, 10.86 +-14.96, 0.00, 58.00, 42.00, 16.01 +-15.03, 0.00, 58.11, 41.89, 16.22 +-15.03, 0.00, 55.70, 44.30, 11.39 +-15.03, 0.00, 55.75, 44.25, 11.50 +-15.03, 0.00, 55.81, 44.19, 11.62 +-15.16, 0.00, 60.91, 39.09, 21.82 +-15.16, 0.00, 56.02, 43.98, 12.04 +-15.03, 0.00, 51.03, 48.97, 2.07 +-15.16, 0.00, 61.08, 38.92, 22.16 +-15.16, 0.00, 56.19, 43.81, 12.38 +-15.03, 0.00, 51.20, 48.80, 2.41 +-15.03, 0.00, 56.20, 43.80, 12.41 +-15.03, 0.00, 56.26, 43.74, 12.52 +-14.96, 0.00, 53.80, 46.20, 7.59 +-14.96, 0.00, 56.32, 43.68, 12.65 +-14.96, 0.00, 56.38, 43.62, 12.76 +-14.90, 0.00, 53.91, 46.09, 7.83 +-14.90, 0.00, 56.44, 43.56, 12.88 +-14.77, 0.00, 51.45, 48.55, 2.91 +-14.77, 0.00, 56.45, 43.55, 12.91 +-14.70, 0.00, 53.99, 46.01, 7.98 +-14.63, 0.00, 53.99, 46.01, 7.99 +-14.50, 0.00, 51.48, 48.52, 2.95 +-14.44, 0.00, 53.95, 46.05, 7.91 +-14.37, 0.00, 53.96, 46.04, 7.92 +-14.24, 0.00, 51.44, 48.56, 2.88 +-14.24, 0.00, 56.44, 43.56, 12.88 +-14.17, 0.00, 53.97, 46.03, 7.94 +-13.97, 0.00, 48.93, 51.07, -2.14 +-13.91, 0.00, 53.88, 46.12, 7.75 +-13.84, 0.00, 53.88, 46.12, 7.76 +-13.71, 0.00, 51.36, 48.64, 2.72 +-13.65, 0.00, 53.83, 46.17, 7.67 +-13.58, 0.00, 53.83, 46.17, 7.67 +-13.45, 0.00, 51.31, 48.69, 2.63 +-13.32, 0.00, 51.27, 48.73, 2.53 +-13.18, 0.00, 51.22, 48.78, 2.43 +-13.05, 0.00, 51.17, 48.83, 2.33 +-12.92, 0.00, 51.12, 48.88, 2.23 +-12.79, 0.00, 51.06, 48.94, 2.13 +-12.66, 0.00, 51.01, 48.99, 2.03 +-12.52, 0.00, 50.96, 49.04, 1.92 +-12.39, 0.00, 50.91, 49.09, 1.82 +-12.26, 0.00, 50.86, 49.14, 1.71 +-12.13, 0.00, 50.80, 49.20, 1.60 +-12.06, 0.00, 53.27, 46.73, 6.54 +-11.87, 0.00, 48.22, 51.78, -3.56 +-11.73, 0.00, 50.64, 49.36, 1.28 +-11.60, 0.00, 50.58, 49.42, 1.17 +-11.54, 0.00, 53.05, 46.95, 6.10 +-11.34, 0.00, 48.00, 52.00, -4.00 +-11.27, 0.00, 52.94, 47.06, 5.87 +-11.07, 0.00, 47.89, 52.11, -4.23 +-11.01, 0.00, 52.82, 47.18, 5.64 +-10.81, 0.00, 47.77, 52.23, -4.46 +-10.68, 0.00, 50.18, 49.82, 0.37 +-10.55, 0.00, 50.12, 49.88, 0.25 +-10.42, 0.00, 50.06, 49.94, 0.13 +-10.28, 0.00, 50.00, 50.00, 0.01 +-10.15, 0.00, 49.94, 50.06, -0.11 +-10.02, 0.00, 49.88, 50.12, -0.24 +-9.89, 0.00, 49.82, 50.18, -0.36 +-9.69, 0.00, 47.24, 52.76, -5.53 +-9.62, 0.00, 52.17, 47.83, 4.33 +-9.43, 0.00, 47.11, 52.89, -5.78 +-9.23, 0.00, 47.00, 53.00, -6.01 +-9.16, 0.00, 51.92, 48.08, 3.85 +-8.96, 0.00, 46.87, 53.13, -6.27 +-8.90, 0.00, 51.79, 48.21, 3.59 +-8.70, 0.00, 46.73, 53.27, -6.53 +-8.64, 0.00, 51.66, 48.34, 3.32 +-8.44, 0.00, 46.60, 53.40, -6.80 +-8.31, 0.00, 49.00, 51.00, -1.99 +-8.17, 0.00, 48.94, 51.06, -2.13 +-8.04, 0.00, 48.87, 51.13, -2.26 +-7.91, 0.00, 48.80, 51.20, -2.40 +-7.78, 0.00, 48.73, 51.27, -2.54 +-7.58, 0.00, 46.14, 53.86, -7.73 +-7.51, 0.00, 51.06, 48.94, 2.12 +-7.32, 0.00, 46.00, 54.00, -8.01 +-7.25, 0.00, 50.92, 49.08, 1.83 +-7.05, 0.00, 45.85, 54.15, -8.30 +-6.99, 0.00, 50.77, 49.23, 1.54 +-6.79, 0.00, 45.70, 54.30, -8.59 +-6.72, 0.00, 50.62, 49.38, 1.25 +-6.59, 0.00, 48.08, 51.92, -3.84 +-6.46, 0.00, 48.00, 52.00, -3.99 +-6.33, 0.00, 47.93, 52.07, -4.14 +-6.20, 0.00, 47.85, 52.15, -4.29 +-6.06, 0.00, 47.78, 52.22, -4.45 +-6.00, 0.00, 50.22, 49.78, 0.44 +-5.80, 0.00, 45.15, 54.85, -9.70 +-5.73, 0.00, 50.07, 49.93, 0.13 +-5.54, 0.00, 45.00, 55.00, -10.01 +-5.47, 0.00, 49.91, 50.09, -0.18 +-5.41, 0.00, 49.88, 50.12, -0.24 +-5.27, 0.00, 47.33, 52.67, -5.34 +-5.21, 0.00, 49.77, 50.23, -0.45 +-5.14, 0.00, 49.74, 50.26, -0.51 +-4.94, 0.00, 44.67, 55.33, -10.66 +-4.94, 0.00, 52.10, 47.90, 4.21 +-4.75, 0.00, 44.56, 55.44, -10.89 +-4.68, 0.00, 49.47, 50.53, -1.06 +-4.61, 0.00, 49.44, 50.56, -1.13 +-4.48, 0.00, 46.88, 53.12, -6.23 +-4.42, 0.00, 49.32, 50.68, -1.36 +-4.35, 0.00, 49.29, 50.71, -1.42 +-4.22, 0.00, 46.73, 53.27, -6.53 +-4.15, 0.00, 49.17, 50.83, -1.66 +-4.09, 0.00, 49.14, 50.86, -1.72 +-3.96, 0.00, 46.58, 53.42, -6.84 +-3.89, 0.00, 49.02, 50.98, -1.96 +-3.82, 0.00, 48.98, 51.02, -2.03 +-3.82, 0.00, 51.47, 48.53, 2.94 +-3.69, 0.00, 46.44, 53.56, -7.12 +-3.63, 0.00, 48.88, 51.12, -2.25 +-3.56, 0.00, 48.84, 51.16, -2.32 +-3.43, 0.00, 46.28, 53.72, -7.43 +-3.43, 0.00, 51.24, 48.76, 2.48 +-3.36, 0.00, 48.73, 51.27, -2.54 +-3.30, 0.00, 48.69, 51.31, -2.61 +-3.30, 0.00, 51.18, 48.82, 2.36 +-3.16, 0.00, 46.15, 53.85, -7.71 +-3.16, 0.00, 51.10, 48.90, 2.21 +-3.10, 0.00, 48.59, 51.41, -2.81 +-3.10, 0.00, 51.08, 48.92, 2.15 +-3.03, 0.00, 48.57, 51.43, -2.87 +-3.03, 0.00, 51.05, 48.95, 2.10 +-2.90, 0.00, 46.02, 53.98, -7.96 +-2.90, 0.00, 50.97, 49.03, 1.95 +-2.90, 0.00, 50.98, 49.02, 1.97 +-2.83, 0.00, 48.47, 51.53, -3.05 +-2.83, 0.00, 50.96, 49.04, 1.91 +-2.83, 0.00, 50.97, 49.03, 1.93 +-2.77, 0.00, 48.46, 51.54, -3.09 +-2.77, 0.00, 50.94, 49.06, 1.88 +-2.77, 0.00, 50.95, 49.05, 1.90 +-2.64, 0.00, 45.92, 54.08, -8.17 +-2.64, 0.00, 50.87, 49.13, 1.74 +-2.64, 0.00, 50.88, 49.12, 1.76 +-2.64, 0.00, 50.89, 49.11, 1.78 +-2.57, 0.00, 48.38, 51.62, -3.25 +-2.57, 0.00, 50.86, 49.14, 1.72 +-2.57, 0.00, 50.87, 49.13, 1.74 +-2.57, 0.00, 50.88, 49.12, 1.76 +-2.57, 0.00, 50.89, 49.11, 1.78 +-2.57, 0.00, 50.90, 49.10, 1.79 +-2.57, 0.00, 50.91, 49.09, 1.81 +-2.50, 0.00, 48.39, 51.61, -3.21 +-2.50, 0.00, 50.88, 49.12, 1.75 +-2.57, 0.00, 53.41, 46.59, 6.81 +-2.57, 0.00, 50.94, 49.06, 1.89 +-2.57, 0.00, 50.95, 49.05, 1.91 +-2.57, 0.00, 50.96, 49.04, 1.93 +-2.57, 0.00, 50.97, 49.03, 1.95 +-2.57, 0.00, 50.98, 49.02, 1.97 +-2.57, 0.00, 50.99, 49.01, 1.99 +-2.57, 0.00, 51.00, 49.00, 2.01 +-2.57, 0.00, 51.01, 48.99, 2.02 +-2.57, 0.00, 51.02, 48.98, 2.04 +-2.57, 0.00, 51.03, 48.97, 2.06 +-2.57, 0.00, 51.04, 48.96, 2.08 +-2.64, 0.00, 53.57, 46.43, 7.15 +-2.64, 0.00, 51.11, 48.89, 2.22 +-2.64, 0.00, 51.12, 48.88, 2.24 +-2.64, 0.00, 51.13, 48.87, 2.26 +-2.64, 0.00, 51.14, 48.86, 2.28 +-2.77, 0.00, 56.19, 43.81, 12.39 +-2.77, 0.00, 51.26, 48.74, 2.52 +-2.77, 0.00, 51.27, 48.73, 2.54 +-2.77, 0.00, 51.28, 48.72, 2.56 +-2.83, 0.00, 53.81, 46.19, 7.63 +-2.83, 0.00, 51.35, 48.65, 2.70 +-2.83, 0.00, 51.36, 48.64, 2.72 +-2.83, 0.00, 51.37, 48.63, 2.75 +-2.83, 0.00, 51.38, 48.62, 2.77 +-2.90, 0.00, 53.92, 46.08, 7.83 +-2.90, 0.00, 51.45, 48.55, 2.91 +-2.90, 0.00, 51.47, 48.53, 2.93 +-3.03, 0.00, 56.52, 43.48, 13.04 +-3.03, 0.00, 51.59, 48.41, 3.17 +-3.03, 0.00, 51.60, 48.40, 3.20 +-3.03, 0.00, 51.61, 48.39, 3.22 +-3.10, 0.00, 54.14, 45.86, 8.29 +-3.10, 0.00, 51.68, 48.32, 3.36 +-3.16, 0.00, 54.22, 45.78, 8.43 +-3.16, 0.00, 51.76, 48.24, 3.51 +-3.16, 0.00, 51.77, 48.23, 3.53 +-3.16, 0.00, 51.78, 48.22, 3.56 +-3.16, 0.00, 51.79, 48.21, 3.58 +-3.30, 0.00, 56.85, 43.15, 13.69 +-3.30, 0.00, 51.91, 48.09, 3.83 +-3.30, 0.00, 51.93, 48.07, 3.85 +-3.30, 0.00, 51.94, 48.06, 3.88 +-3.30, 0.00, 51.95, 48.05, 3.90 +-3.36, 0.00, 54.49, 45.51, 8.97 +-3.36, 0.00, 52.03, 47.97, 4.05 +-3.43, 0.00, 54.56, 45.44, 9.12 +-3.43, 0.00, 52.10, 47.90, 4.20 +-3.43, 0.00, 52.11, 47.89, 4.23 +-3.56, 0.00, 57.17, 42.83, 14.34 +-3.56, 0.00, 52.24, 47.76, 4.48 +-3.56, 0.00, 52.25, 47.75, 4.51 +-3.56, 0.00, 52.27, 47.73, 4.53 +-3.63, 0.00, 54.80, 45.20, 9.60 +-3.63, 0.00, 52.34, 47.66, 4.69 +-3.63, 0.00, 52.36, 47.64, 4.71 +-3.63, 0.00, 52.37, 47.63, 4.74 +-3.63, 0.00, 52.38, 47.62, 4.77 +-3.69, 0.00, 54.92, 45.08, 9.84 +-3.69, 0.00, 52.46, 47.54, 4.92 +-3.69, 0.00, 52.48, 47.52, 4.95 +-3.69, 0.00, 52.49, 47.51, 4.98 +-3.69, 0.00, 52.50, 47.50, 5.01 +-3.82, 0.00, 57.56, 42.44, 15.12 +-3.82, 0.00, 52.63, 47.37, 5.26 +-3.82, 0.00, 52.64, 47.36, 5.29 +-3.82, 0.00, 52.66, 47.34, 5.32 +-3.82, 0.00, 52.67, 47.33, 5.35 +-3.82, 0.00, 52.69, 47.31, 5.38 +-3.89, 0.00, 55.22, 44.78, 10.45 +-3.89, 0.00, 52.77, 47.23, 5.53 +-3.89, 0.00, 52.78, 47.22, 5.56 +-3.89, 0.00, 52.80, 47.20, 5.59 +-3.89, 0.00, 52.81, 47.19, 5.62 +-3.89, 0.00, 52.82, 47.18, 5.65 +-3.89, 0.00, 52.84, 47.16, 5.68 +-3.89, 0.00, 52.85, 47.15, 5.71 +-3.89, 0.00, 52.87, 47.13, 5.74 +-3.89, 0.00, 52.88, 47.12, 5.77 +-3.89, 0.00, 52.90, 47.10, 5.79 +-3.89, 0.00, 52.91, 47.09, 5.82 +-3.96, 0.00, 55.45, 44.55, 10.90 +-3.96, 0.00, 52.99, 47.01, 5.98 +-3.96, 0.00, 53.01, 46.99, 6.01 +-3.96, 0.00, 53.02, 46.98, 6.04 +-3.96, 0.00, 53.04, 46.96, 6.07 +-3.96, 0.00, 53.05, 46.95, 6.10 +-3.96, 0.00, 53.07, 46.93, 6.13 +-3.96, 0.00, 53.08, 46.92, 6.16 +-3.96, 0.00, 53.10, 46.90, 6.19 +-3.96, 0.00, 53.11, 46.89, 6.22 +-3.89, 0.00, 50.60, 49.40, 1.21 +-3.89, 0.00, 53.09, 46.91, 6.18 +-3.89, 0.00, 53.10, 46.90, 6.21 +-3.89, 0.00, 53.12, 46.88, 6.24 +-3.89, 0.00, 53.13, 46.87, 6.27 +-3.89, 0.00, 53.15, 46.85, 6.30 +-3.82, 0.00, 50.64, 49.36, 1.28 +-3.82, 0.00, 53.13, 46.87, 6.25 +-3.82, 0.00, 53.14, 46.86, 6.28 +-3.82, 0.00, 53.16, 46.84, 6.31 +-3.82, 0.00, 53.17, 46.83, 6.34 +-3.82, 0.00, 53.18, 46.82, 6.37 +-3.82, 0.00, 53.20, 46.80, 6.40 +-3.82, 0.00, 53.21, 46.79, 6.43 +-3.69, 0.00, 48.18, 51.82, -3.63 +-3.69, 0.00, 53.14, 46.86, 6.28 +-3.69, 0.00, 53.16, 46.84, 6.31 +-3.63, 0.00, 50.65, 49.35, 1.30 +-3.63, 0.00, 53.13, 46.87, 6.27 +-3.63, 0.00, 53.15, 46.85, 6.29 +-3.63, 0.00, 53.16, 46.84, 6.32 +-3.56, 0.00, 50.65, 49.35, 1.31 +-3.56, 0.00, 53.14, 46.86, 6.28 +-3.56, 0.00, 53.15, 46.85, 6.30 +-3.56, 0.00, 53.16, 46.84, 6.33 +-3.43, 0.00, 48.13, 51.87, -3.73 +-3.43, 0.00, 53.09, 46.91, 6.18 +-3.36, 0.00, 50.58, 49.42, 1.17 +-3.36, 0.00, 53.07, 46.93, 6.13 +-3.36, 0.00, 53.08, 46.92, 6.16 +-3.36, 0.00, 53.09, 46.91, 6.19 +-3.36, 0.00, 53.11, 46.89, 6.21 +-3.30, 0.00, 50.60, 49.40, 1.19 +-3.30, 0.00, 53.08, 46.92, 6.16 +-3.30, 0.00, 53.09, 46.91, 6.19 +-3.30, 0.00, 53.11, 46.89, 6.21 +-3.16, 0.00, 48.07, 51.93, -3.85 +-3.16, 0.00, 53.03, 46.97, 6.06 +-3.16, 0.00, 53.04, 46.96, 6.08 +-3.16, 0.00, 53.05, 46.95, 6.11 +-3.16, 0.00, 53.07, 46.93, 6.13 +-3.16, 0.00, 53.08, 46.92, 6.15 +-3.10, 0.00, 50.57, 49.43, 1.14 +-3.10, 0.00, 53.05, 46.95, 6.10 +-3.10, 0.00, 53.06, 46.94, 6.13 +-3.10, 0.00, 53.07, 46.93, 6.15 +-3.03, 0.00, 50.56, 49.44, 1.13 +-3.03, 0.00, 53.05, 46.95, 6.10 +-3.03, 0.00, 53.06, 46.94, 6.12 +-3.03, 0.00, 53.07, 46.93, 6.14 +-3.03, 0.00, 53.08, 46.92, 6.16 +-2.90, 0.00, 48.05, 51.95, -3.90 +-3.03, 0.00, 58.05, 41.95, 16.10 +-2.90, 0.00, 48.07, 51.93, -3.86 +-2.90, 0.00, 53.03, 46.97, 6.05 +-2.90, 0.00, 53.04, 46.96, 6.08 +-2.90, 0.00, 53.05, 46.95, 6.10 +-2.90, 0.00, 53.06, 46.94, 6.12 +-2.90, 0.00, 53.07, 46.93, 6.14 +-2.90, 0.00, 53.08, 46.92, 6.16 +-2.90, 0.00, 53.09, 46.91, 6.18 +-2.83, 0.00, 50.58, 49.42, 1.16 +-2.83, 0.00, 53.06, 46.94, 6.13 +-2.83, 0.00, 53.07, 46.93, 6.15 +-2.90, 0.00, 55.61, 44.39, 11.21 +-2.83, 0.00, 50.62, 49.38, 1.25 +-2.83, 0.00, 53.11, 46.89, 6.21 +-2.83, 0.00, 53.12, 46.88, 6.23 +-2.83, 0.00, 53.13, 46.87, 6.26 +-2.83, 0.00, 53.14, 46.86, 6.28 +-2.83, 0.00, 53.15, 46.85, 6.30 +-2.90, 0.00, 55.68, 44.32, 11.36 +-2.90, 0.00, 53.22, 46.78, 6.44 +-2.90, 0.00, 53.23, 46.77, 6.46 +-2.90, 0.00, 53.24, 46.76, 6.48 +-2.90, 0.00, 53.25, 46.75, 6.51 +-2.90, 0.00, 53.26, 46.74, 6.53 +-2.90, 0.00, 53.27, 46.73, 6.55 +-2.83, 0.00, 50.76, 49.24, 1.53 +-2.90, 0.00, 55.77, 44.23, 11.54 +-2.90, 0.00, 53.31, 46.69, 6.61 +-2.83, 0.00, 50.80, 49.20, 1.59 +-2.83, 0.00, 53.28, 46.72, 6.56 +-2.83, 0.00, 53.29, 46.71, 6.58 +-2.83, 0.00, 53.30, 46.70, 6.60 +-2.83, 0.00, 53.31, 46.69, 6.62 +-2.83, 0.00, 53.32, 46.68, 6.64 +-2.83, 0.00, 53.33, 46.67, 6.66 +-2.83, 0.00, 53.34, 46.66, 6.69 +-2.83, 0.00, 53.35, 46.65, 6.71 +-2.83, 0.00, 53.36, 46.64, 6.73 +-2.83, 0.00, 53.37, 46.63, 6.75 +-2.83, 0.00, 53.39, 46.61, 6.77 +-2.83, 0.00, 53.40, 46.60, 6.79 +-2.83, 0.00, 53.41, 46.59, 6.81 +-2.77, 0.00, 50.90, 49.10, 1.79 +-2.77, 0.00, 53.38, 46.62, 6.76 +-2.77, 0.00, 53.39, 46.61, 6.78 +-2.77, 0.00, 53.40, 46.60, 6.80 +-2.77, 0.00, 53.41, 46.59, 6.82 +-2.77, 0.00, 53.42, 46.58, 6.84 +-2.77, 0.00, 53.43, 46.57, 6.86 +-2.64, 0.00, 48.40, 51.60, -3.21 +-2.64, 0.00, 53.35, 46.65, 6.70 +-2.64, 0.00, 53.36, 46.64, 6.72 +-2.64, 0.00, 53.37, 46.63, 6.74 +-2.64, 0.00, 53.38, 46.62, 6.76 +-2.64, 0.00, 53.39, 46.61, 6.78 +-2.64, 0.00, 53.40, 46.60, 6.80 +-2.64, 0.00, 53.41, 46.59, 6.82 +-2.57, 0.00, 50.90, 49.10, 1.80 +-2.57, 0.00, 53.38, 46.62, 6.76 +-2.57, 0.00, 53.39, 46.61, 6.78 +-2.50, 0.00, 50.88, 49.12, 1.76 +-2.50, 0.00, 53.36, 46.64, 6.72 +-2.50, 0.00, 53.37, 46.63, 6.74 +-2.37, 0.00, 48.33, 51.67, -3.33 +-2.37, 0.00, 53.29, 46.71, 6.57 +-2.37, 0.00, 53.30, 46.70, 6.59 +-2.31, 0.00, 50.78, 49.22, 1.57 +-2.31, 0.00, 53.26, 46.74, 6.53 +-2.31, 0.00, 53.27, 46.73, 6.55 +-2.24, 0.00, 50.76, 49.24, 1.52 +-2.24, 0.00, 53.24, 46.76, 6.48 +-2.24, 0.00, 53.25, 46.75, 6.50 +-2.11, 0.00, 48.21, 51.79, -3.57 +-2.11, 0.00, 53.17, 46.83, 6.33 +-2.11, 0.00, 53.17, 46.83, 6.35 +-2.04, 0.00, 50.66, 49.34, 1.32 +-2.04, 0.00, 53.14, 46.86, 6.28 +-1.98, 0.00, 50.63, 49.37, 1.25 +-1.98, 0.00, 53.10, 46.90, 6.21 +-1.85, 0.00, 48.07, 51.93, -3.86 +-1.85, 0.00, 53.02, 46.98, 6.04 +-1.78, 0.00, 50.50, 49.50, 1.01 +-1.78, 0.00, 52.98, 47.02, 5.97 +-1.71, 0.00, 50.47, 49.53, 0.94 +-1.71, 0.00, 52.95, 47.05, 5.89 +-1.58, 0.00, 47.91, 52.09, -4.18 +-1.58, 0.00, 52.86, 47.14, 5.72 +-1.58, 0.00, 52.87, 47.13, 5.73 +-1.58, 0.00, 52.87, 47.13, 5.74 +-1.52, 0.00, 50.36, 49.64, 0.71 +-1.52, 0.00, 52.83, 47.17, 5.67 +-1.45, 0.00, 50.32, 49.68, 0.64 +-1.45, 0.00, 52.80, 47.20, 5.59 +-1.32, 0.00, 47.76, 52.24, -4.49 +-1.32, 0.00, 52.71, 47.29, 5.41 +-1.25, 0.00, 50.19, 49.81, 0.38 +-1.25, 0.00, 52.67, 47.33, 5.33 +-1.25, 0.00, 52.67, 47.33, 5.34 +-1.19, 0.00, 50.15, 49.85, 0.31 +-1.19, 0.00, 52.63, 47.37, 5.26 +-1.05, 0.00, 47.59, 52.41, -4.82 +-1.05, 0.00, 52.54, 47.46, 5.08 +-1.05, 0.00, 52.54, 47.46, 5.09 +-0.99, 0.00, 50.03, 49.97, 0.05 +-0.99, 0.00, 52.50, 47.50, 5.00 +-0.99, 0.00, 52.50, 47.50, 5.01 +-0.92, 0.00, 49.99, 50.01, -0.03 +-0.92, 0.00, 52.46, 47.54, 4.92 +-0.92, 0.00, 52.47, 47.53, 4.93 +-0.79, 0.00, 47.43, 52.57, -5.15 +-0.79, 0.00, 52.37, 47.63, 4.75 +-0.79, 0.00, 52.38, 47.62, 4.75 +-0.73, 0.00, 49.86, 50.14, -0.29 +-0.73, 0.00, 52.33, 47.67, 4.66 +-0.66, 0.00, 49.81, 50.19, -0.37 +-0.66, 0.00, 52.29, 47.71, 4.57 +-0.66, 0.00, 52.29, 47.71, 4.58 +-0.53, 0.00, 47.25, 52.75, -5.50 +-0.53, 0.00, 52.19, 47.81, 4.39 +-0.46, 0.00, 49.68, 50.32, -0.65 +-0.46, 0.00, 52.15, 47.85, 4.30 +-0.46, 0.00, 52.15, 47.85, 4.30 +-0.46, 0.00, 52.15, 47.85, 4.30 +-0.40, 0.00, 49.63, 50.37, -0.73 +-0.40, 0.00, 52.11, 47.89, 4.21 +-0.40, 0.00, 52.11, 47.89, 4.21 +-0.40, 0.00, 52.11, 47.89, 4.22 +-0.26, 0.00, 47.07, 52.93, -5.87 +-0.26, 0.00, 52.01, 47.99, 4.02 +-0.26, 0.00, 52.01, 47.99, 4.03 +-0.26, 0.00, 52.01, 47.99, 4.03 +-0.20, 0.00, 49.49, 50.51, -1.01 +-0.20, 0.00, 51.97, 48.03, 3.93 +-0.20, 0.00, 51.97, 48.03, 3.93 +-0.20, 0.00, 51.97, 48.03, 3.94 +-0.13, 0.00, 49.45, 50.55, -1.11 +-0.13, 0.00, 51.92, 48.08, 3.84 +-0.13, 0.00, 51.92, 48.08, 3.84 +0.00, 0.00, 46.88, 53.12, -6.25 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.07, 0.00, 49.30, 50.70, -1.40 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.00, 0.00, 54.29, 45.71, 8.58 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.00, 0.00, 51.82, 48.18, 3.64 +0.07, 0.00, 49.30, 50.70, -1.41 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.54 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.77, 48.23, 3.53 +0.07, 0.00, 51.76, 48.24, 3.53 +0.07, 0.00, 51.76, 48.24, 3.53 +0.13, 0.00, 49.24, 50.76, -1.51 +0.13, 0.00, 51.71, 48.29, 3.43 +0.13, 0.00, 51.71, 48.29, 3.43 +0.13, 0.00, 51.71, 48.29, 3.43 +0.13, 0.00, 51.71, 48.29, 3.43 +0.13, 0.00, 51.71, 48.29, 3.42 +0.13, 0.00, 51.71, 48.29, 3.42 +0.26, 0.00, 46.67, 53.33, -6.66 +0.26, 0.00, 51.61, 48.39, 3.22 +0.26, 0.00, 51.61, 48.39, 3.22 +0.26, 0.00, 51.61, 48.39, 3.22 +0.26, 0.00, 51.61, 48.39, 3.22 +0.26, 0.00, 51.61, 48.39, 3.21 +0.26, 0.00, 51.61, 48.39, 3.21 +0.26, 0.00, 51.60, 48.40, 3.21 +0.26, 0.00, 51.60, 48.40, 3.21 +0.26, 0.00, 51.60, 48.40, 3.21 +0.26, 0.00, 51.60, 48.40, 3.20 +0.33, 0.00, 49.08, 50.92, -1.84 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.09 +0.33, 0.00, 51.55, 48.45, 3.09 +0.40, 0.00, 49.02, 50.98, -1.96 +0.33, 0.00, 54.01, 45.99, 8.03 +0.40, 0.00, 49.02, 50.98, -1.96 +0.33, 0.00, 54.01, 45.99, 8.02 +0.40, 0.00, 49.02, 50.98, -1.97 +0.33, 0.00, 54.01, 45.99, 8.02 +0.40, 0.00, 49.01, 50.99, -1.97 +0.33, 0.00, 54.01, 45.99, 8.01 +0.40, 0.00, 49.01, 50.99, -1.98 +0.40, 0.00, 51.48, 48.52, 2.96 +0.40, 0.00, 51.48, 48.52, 2.96 +0.40, 0.00, 51.48, 48.52, 2.96 +0.40, 0.00, 51.48, 48.52, 2.95 +0.40, 0.00, 51.48, 48.52, 2.95 +0.40, 0.00, 51.47, 48.53, 2.95 +0.40, 0.00, 51.47, 48.53, 2.95 +0.53, 0.00, 46.43, 53.57, -7.14 +0.53, 0.00, 51.37, 48.63, 2.74 +0.53, 0.00, 51.37, 48.63, 2.74 +0.53, 0.00, 51.37, 48.63, 2.73 +0.53, 0.00, 51.36, 48.64, 2.73 +0.53, 0.00, 51.36, 48.64, 2.72 +0.53, 0.00, 51.36, 48.64, 2.72 +0.53, 0.00, 51.36, 48.64, 2.72 +0.53, 0.00, 51.36, 48.64, 2.71 +0.53, 0.00, 51.35, 48.65, 2.71 +0.53, 0.00, 51.35, 48.65, 2.70 +0.40, 0.00, 56.39, 43.61, 12.79 +0.40, 0.00, 51.45, 48.55, 2.90 +0.53, 0.00, 46.40, 53.60, -7.19 +0.53, 0.00, 51.35, 48.65, 2.69 +0.53, 0.00, 51.34, 48.66, 2.69 +0.53, 0.00, 51.34, 48.66, 2.68 +0.53, 0.00, 51.34, 48.66, 2.68 +0.53, 0.00, 51.34, 48.66, 2.67 +0.53, 0.00, 51.34, 48.66, 2.67 +0.53, 0.00, 51.33, 48.67, 2.67 +0.53, 0.00, 51.33, 48.67, 2.66 +0.53, 0.00, 51.33, 48.67, 2.66 +0.53, 0.00, 51.33, 48.67, 2.66 +0.53, 0.00, 51.33, 48.67, 2.65 +0.40, 0.00, 56.37, 43.63, 12.73 +0.40, 0.00, 51.42, 48.58, 2.84 +0.40, 0.00, 51.42, 48.58, 2.84 +0.40, 0.00, 51.42, 48.58, 2.84 +0.40, 0.00, 51.42, 48.58, 2.83 +0.33, 0.00, 53.94, 46.06, 7.87 +0.33, 0.00, 51.46, 48.54, 2.93 +0.33, 0.00, 51.46, 48.54, 2.93 +0.33, 0.00, 51.46, 48.54, 2.92 +0.33, 0.00, 51.46, 48.54, 2.92 +0.33, 0.00, 51.46, 48.54, 2.92 +0.33, 0.00, 51.46, 48.54, 2.92 +0.33, 0.00, 51.46, 48.54, 2.91 +0.33, 0.00, 51.46, 48.54, 2.91 +0.33, 0.00, 51.45, 48.55, 2.91 +0.33, 0.00, 51.45, 48.55, 2.91 +0.33, 0.00, 51.45, 48.55, 2.90 +0.33, 0.00, 51.45, 48.55, 2.90 +0.26, 0.00, 53.97, 46.03, 7.94 +0.26, 0.00, 51.50, 48.50, 3.00 +0.26, 0.00, 51.50, 48.50, 2.99 +0.26, 0.00, 51.50, 48.50, 2.99 +0.13, 0.00, 56.54, 43.46, 13.08 +0.13, 0.00, 51.59, 48.41, 3.19 +0.13, 0.00, 51.59, 48.41, 3.19 +0.13, 0.00, 51.59, 48.41, 3.19 +0.13, 0.00, 51.59, 48.41, 3.18 +0.07, 0.00, 54.11, 45.89, 8.23 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.07, 0.00, 51.64, 48.36, 3.28 +0.00, 0.00, 54.16, 45.84, 8.32 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +0.00, 0.00, 51.69, 48.31, 3.38 +-0.13, 0.00, 56.73, 43.27, 13.46 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.13, 0.00, 51.79, 48.21, 3.58 +-0.20, 0.00, 54.31, 45.69, 8.63 +-0.20, 0.00, 51.84, 48.16, 3.69 +-0.20, 0.00, 51.84, 48.16, 3.69 +-0.20, 0.00, 51.84, 48.16, 3.69 +-0.20, 0.00, 51.85, 48.15, 3.69 +-0.20, 0.00, 51.85, 48.15, 3.69 +-0.26, 0.00, 54.37, 45.63, 8.74 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.80 +-0.26, 0.00, 51.90, 48.10, 3.81 +-0.26, 0.00, 51.90, 48.10, 3.81 +-0.26, 0.00, 51.90, 48.10, 3.81 +-0.26, 0.00, 51.91, 48.09, 3.81 +-0.26, 0.00, 51.91, 48.09, 3.81 +-0.26, 0.00, 51.91, 48.09, 3.81 +-0.26, 0.00, 51.91, 48.09, 3.82 +-0.40, 0.00, 56.95, 43.05, 13.91 +-0.26, 0.00, 46.97, 53.03, -6.07 +-0.40, 0.00, 56.96, 43.04, 13.91 +-0.40, 0.00, 52.01, 47.99, 4.03 +-0.40, 0.00, 52.01, 47.99, 4.03 +-0.40, 0.00, 52.02, 47.98, 4.03 +-0.40, 0.00, 52.02, 47.98, 4.03 +-0.40, 0.00, 52.02, 47.98, 4.04 +-0.40, 0.00, 52.02, 47.98, 4.04 +-0.40, 0.00, 52.02, 47.98, 4.04 +-0.40, 0.00, 52.02, 47.98, 4.05 +-0.40, 0.00, 52.02, 47.98, 4.05 +-0.46, 0.00, 54.55, 45.45, 9.10 +-0.46, 0.00, 52.08, 47.92, 4.16 +-0.46, 0.00, 52.08, 47.92, 4.16 +-0.46, 0.00, 52.08, 47.92, 4.16 +-0.46, 0.00, 52.08, 47.92, 4.17 +-0.46, 0.00, 52.08, 47.92, 4.17 +-0.46, 0.00, 52.09, 47.91, 4.17 +-0.46, 0.00, 52.09, 47.91, 4.18 +-0.46, 0.00, 52.09, 47.91, 4.18 +-0.46, 0.00, 52.09, 47.91, 4.18 +-0.46, 0.00, 52.09, 47.91, 4.19 +-0.46, 0.00, 52.09, 47.91, 4.19 +-0.46, 0.00, 52.10, 47.90, 4.19 +-0.46, 0.00, 52.10, 47.90, 4.20 +-0.46, 0.00, 52.10, 47.90, 4.20 +-0.53, 0.00, 54.62, 45.38, 9.25 +-0.53, 0.00, 52.15, 47.85, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.31 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.32 +-0.53, 0.00, 52.16, 47.84, 4.33 +-0.53, 0.00, 52.17, 47.83, 4.33 +-0.53, 0.00, 52.17, 47.83, 4.33 +-0.53, 0.00, 52.17, 47.83, 4.34 +-0.66, 0.00, 57.21, 42.79, 14.43 +-0.66, 0.00, 52.27, 47.73, 4.55 +-0.66, 0.00, 52.28, 47.72, 4.55 +-0.66, 0.00, 52.28, 47.72, 4.56 +-0.66, 0.00, 52.28, 47.72, 4.56 +-0.66, 0.00, 52.28, 47.72, 4.57 +-0.66, 0.00, 52.29, 47.71, 4.57 +-0.66, 0.00, 52.29, 47.71, 4.58 +-0.66, 0.00, 52.29, 47.71, 4.58 +-0.66, 0.00, 52.29, 47.71, 4.59 +-0.66, 0.00, 52.30, 47.70, 4.59 +-0.66, 0.00, 52.30, 47.70, 4.60 +-0.66, 0.00, 52.30, 47.70, 4.60 +-0.66, 0.00, 52.30, 47.70, 4.61 +-0.66, 0.00, 52.31, 47.69, 4.61 +-0.66, 0.00, 52.31, 47.69, 4.62 +-0.66, 0.00, 52.31, 47.69, 4.62 +-0.73, 0.00, 54.83, 45.17, 9.67 +-0.73, 0.00, 52.37, 47.63, 4.73 +-0.73, 0.00, 52.37, 47.63, 4.74 +-0.73, 0.00, 52.37, 47.63, 4.74 +-0.73, 0.00, 52.37, 47.63, 4.75 +-0.73, 0.00, 52.38, 47.62, 4.75 +-0.73, 0.00, 52.38, 47.62, 4.76 +-0.73, 0.00, 52.38, 47.62, 4.76 +-0.73, 0.00, 52.38, 47.62, 4.77 +-0.73, 0.00, 52.39, 47.61, 4.77 +-0.73, 0.00, 52.39, 47.61, 4.78 +-0.73, 0.00, 52.39, 47.61, 4.78 +-0.73, 0.00, 52.39, 47.61, 4.79 +-0.73, 0.00, 52.40, 47.60, 4.80 +-0.73, 0.00, 52.40, 47.60, 4.80 +-0.73, 0.00, 52.40, 47.60, 4.81 +-0.73, 0.00, 52.41, 47.59, 4.81 +-0.73, 0.00, 52.41, 47.59, 4.82 +-0.73, 0.00, 52.41, 47.59, 4.82 +-0.73, 0.00, 52.41, 47.59, 4.83 +-0.73, 0.00, 52.42, 47.58, 4.83 +-0.73, 0.00, 52.42, 47.58, 4.84 +-0.73, 0.00, 52.42, 47.58, 4.84 +-0.66, 0.00, 49.90, 50.10, -0.19 +-0.73, 0.00, 54.90, 45.10, 9.80 +-0.66, 0.00, 49.91, 50.09, -0.18 +-0.66, 0.00, 52.38, 47.62, 4.77 +-0.66, 0.00, 52.39, 47.61, 4.77 +-0.66, 0.00, 52.39, 47.61, 4.78 +-0.66, 0.00, 52.39, 47.61, 4.78 +-0.66, 0.00, 52.39, 47.61, 4.79 +-0.66, 0.00, 52.40, 47.60, 4.79 +-0.66, 0.00, 52.40, 47.60, 4.80 +-0.66, 0.00, 52.40, 47.60, 4.80 +-0.66, 0.00, 52.40, 47.60, 4.81 +-0.53, 0.00, 47.36, 52.64, -5.28 +-0.66, 0.00, 57.35, 42.65, 14.70 +-0.53, 0.00, 47.37, 52.63, -5.27 +-0.53, 0.00, 52.31, 47.69, 4.62 +-0.53, 0.00, 52.31, 47.69, 4.63 +-0.53, 0.00, 52.32, 47.68, 4.63 +-0.53, 0.00, 52.32, 47.68, 4.64 +-0.53, 0.00, 52.32, 47.68, 4.64 +-0.53, 0.00, 52.32, 47.68, 4.64 +-0.46, 0.00, 49.80, 50.20, -0.40 +-0.46, 0.00, 52.28, 47.72, 4.55 +-0.46, 0.00, 52.28, 47.72, 4.56 +-0.46, 0.00, 52.28, 47.72, 4.56 +-0.46, 0.00, 52.28, 47.72, 4.56 +-0.46, 0.00, 52.28, 47.72, 4.57 +-0.40, 0.00, 49.76, 50.24, -0.47 +-0.40, 0.00, 52.24, 47.76, 4.47 +-0.40, 0.00, 52.24, 47.76, 4.48 +-0.40, 0.00, 52.24, 47.76, 4.48 +-0.40, 0.00, 52.24, 47.76, 4.48 +-0.26, 0.00, 47.20, 52.80, -5.60 +-0.26, 0.00, 52.14, 47.86, 4.29 +-0.26, 0.00, 52.15, 47.85, 4.29 +-0.26, 0.00, 52.15, 47.85, 4.29 +-0.26, 0.00, 52.15, 47.85, 4.29 +-0.20, 0.00, 49.63, 50.37, -0.75 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.20, 0.00, 52.10, 47.90, 4.20 +-0.13, 0.00, 49.58, 50.42, -0.84 +-0.13, 0.00, 52.05, 47.95, 4.11 +-0.13, 0.00, 52.05, 47.95, 4.11 +-0.13, 0.00, 52.05, 47.95, 4.11 +0.00, 0.00, 47.01, 52.99, -5.98 +0.00, 0.00, 51.96, 48.04, 3.91 +0.00, 0.00, 51.96, 48.04, 3.91 +0.00, 0.00, 51.96, 48.04, 3.91 +0.00, 0.00, 51.96, 48.04, 3.91 +0.07, 0.00, 49.43, 50.57, -1.13 +0.07, 0.00, 51.91, 48.09, 3.81 +0.07, 0.00, 51.91, 48.09, 3.81 +0.07, 0.00, 51.91, 48.09, 3.81 +0.07, 0.00, 51.91, 48.09, 3.81 +0.07, 0.00, 51.90, 48.10, 3.81 +0.13, 0.00, 49.38, 50.62, -1.23 +0.13, 0.00, 51.85, 48.15, 3.71 +0.13, 0.00, 51.85, 48.15, 3.71 +0.13, 0.00, 51.85, 48.15, 3.71 +0.13, 0.00, 51.85, 48.15, 3.71 +0.13, 0.00, 51.85, 48.15, 3.70 +0.13, 0.00, 51.85, 48.15, 3.70 +0.26, 0.00, 46.81, 53.19, -6.38 +0.26, 0.00, 51.75, 48.25, 3.50 +0.26, 0.00, 51.75, 48.25, 3.50 +0.26, 0.00, 51.75, 48.25, 3.50 +0.33, 0.00, 49.23, 50.77, -1.55 +0.33, 0.00, 51.70, 48.30, 3.39 +0.33, 0.00, 51.70, 48.30, 3.39 +0.33, 0.00, 51.69, 48.31, 3.39 +0.33, 0.00, 51.69, 48.31, 3.39 +0.33, 0.00, 51.69, 48.31, 3.38 +0.33, 0.00, 51.69, 48.31, 3.38 +0.33, 0.00, 51.69, 48.31, 3.38 +0.33, 0.00, 51.69, 48.31, 3.38 +0.33, 0.00, 51.69, 48.31, 3.37 +0.33, 0.00, 51.69, 48.31, 3.37 +0.33, 0.00, 51.68, 48.32, 3.37 +0.40, 0.00, 49.16, 50.84, -1.68 +0.40, 0.00, 51.63, 48.37, 3.26 +0.40, 0.00, 51.63, 48.37, 3.26 +0.40, 0.00, 51.63, 48.37, 3.26 +0.40, 0.00, 51.63, 48.37, 3.26 +0.40, 0.00, 51.63, 48.37, 3.25 +0.53, 0.00, 46.58, 53.42, -6.84 +0.53, 0.00, 51.52, 48.48, 3.05 +0.53, 0.00, 51.52, 48.48, 3.04 +0.53, 0.00, 51.52, 48.48, 3.04 +0.53, 0.00, 51.52, 48.48, 3.04 +0.53, 0.00, 51.52, 48.48, 3.03 +0.53, 0.00, 51.51, 48.49, 3.03 +0.53, 0.00, 51.51, 48.49, 3.02 +0.40, 0.00, 56.55, 43.45, 13.11 +0.40, 0.00, 51.61, 48.39, 3.22 +0.40, 0.00, 51.61, 48.39, 3.21 +0.40, 0.00, 51.60, 48.40, 3.21 +0.40, 0.00, 51.60, 48.40, 3.21 +0.40, 0.00, 51.60, 48.40, 3.20 +0.40, 0.00, 51.60, 48.40, 3.20 +0.40, 0.00, 51.60, 48.40, 3.20 +0.40, 0.00, 51.60, 48.40, 3.19 +0.40, 0.00, 51.60, 48.40, 3.19 +0.53, 0.00, 46.55, 53.45, -6.90 +0.53, 0.00, 51.49, 48.51, 2.99 +0.53, 0.00, 51.49, 48.51, 2.98 +0.53, 0.00, 51.49, 48.51, 2.98 +0.53, 0.00, 51.49, 48.51, 2.97 +0.53, 0.00, 51.49, 48.51, 2.97 +0.53, 0.00, 51.48, 48.52, 2.97 +0.53, 0.00, 51.48, 48.52, 2.96 +0.40, 0.00, 56.52, 43.48, 13.04 +0.40, 0.00, 51.58, 48.42, 3.15 +0.40, 0.00, 51.58, 48.42, 3.15 +0.40, 0.00, 51.57, 48.43, 3.15 +0.40, 0.00, 51.57, 48.43, 3.15 +0.33, 0.00, 54.09, 45.91, 8.19 +0.33, 0.00, 51.62, 48.38, 3.24 +0.33, 0.00, 51.62, 48.38, 3.24 +0.40, 0.00, 49.10, 50.90, -1.81 +0.40, 0.00, 51.57, 48.43, 3.13 +0.40, 0.00, 51.56, 48.44, 3.13 +0.40, 0.00, 51.56, 48.44, 3.13 +0.40, 0.00, 51.56, 48.44, 3.12 +0.40, 0.00, 51.56, 48.44, 3.12 +0.53, 0.00, 46.52, 53.48, -6.97 +0.53, 0.00, 51.46, 48.54, 2.91 +0.53, 0.00, 51.46, 48.54, 2.91 +0.53, 0.00, 51.45, 48.55, 2.91 +0.53, 0.00, 51.45, 48.55, 2.90 +0.53, 0.00, 51.45, 48.55, 2.90 +0.53, 0.00, 51.45, 48.55, 2.89 +0.40, 0.00, 56.49, 43.51, 12.98 +0.40, 0.00, 51.54, 48.46, 3.09 +0.40, 0.00, 51.54, 48.46, 3.08 +0.40, 0.00, 51.54, 48.46, 3.08 +0.33, 0.00, 54.06, 45.94, 8.12 +0.33, 0.00, 51.59, 48.41, 3.17 +0.33, 0.00, 51.59, 48.41, 3.17 +0.33, 0.00, 51.58, 48.42, 3.17 +0.40, 0.00, 49.06, 50.94, -1.88 +0.40, 0.00, 51.53, 48.47, 3.06 +0.40, 0.00, 51.53, 48.47, 3.06 +0.40, 0.00, 51.53, 48.47, 3.06 +0.53, 0.00, 46.48, 53.52, -7.03 +0.53, 0.00, 51.43, 48.57, 2.85 +0.53, 0.00, 51.42, 48.58, 2.85 +0.53, 0.00, 51.42, 48.58, 2.85 +0.53, 0.00, 51.42, 48.58, 2.84 +0.53, 0.00, 51.42, 48.58, 2.84 +0.53, 0.00, 51.42, 48.58, 2.83 +0.40, 0.00, 56.46, 43.54, 12.92 +0.40, 0.00, 51.51, 48.49, 3.02 +0.40, 0.00, 51.51, 48.49, 3.02 +0.33, 0.00, 54.03, 45.97, 8.06 +0.33, 0.00, 51.56, 48.44, 3.12 +0.33, 0.00, 51.56, 48.44, 3.11 +0.33, 0.00, 51.56, 48.44, 3.11 +0.26, 0.00, 54.08, 45.92, 8.15 +0.26, 0.00, 51.60, 48.40, 3.21 +0.26, 0.00, 51.60, 48.40, 3.20 +0.33, 0.00, 49.08, 50.92, -1.84 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 51.55, 48.45, 3.09 +0.33, 0.00, 51.55, 48.45, 3.09 +0.33, 0.00, 51.54, 48.46, 3.09 +0.33, 0.00, 51.54, 48.46, 3.09 +0.33, 0.00, 51.54, 48.46, 3.08 +0.33, 0.00, 51.54, 48.46, 3.08 +0.33, 0.00, 51.54, 48.46, 3.08 +0.33, 0.00, 51.54, 48.46, 3.08 +0.26, 0.00, 54.06, 45.94, 8.12 +0.26, 0.00, 51.59, 48.41, 3.17 +0.13, 0.00, 56.63, 43.37, 13.25 +0.13, 0.00, 51.68, 48.32, 3.37 +0.13, 0.00, 51.68, 48.32, 3.37 +0.07, 0.00, 54.20, 45.80, 8.41 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.13, 0.00, 49.21, 50.79, -1.58 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.36 +0.13, 0.00, 51.68, 48.32, 3.35 +0.13, 0.00, 51.68, 48.32, 3.35 +0.13, 0.00, 51.68, 48.32, 3.35 +0.07, 0.00, 54.20, 45.80, 8.39 +0.07, 0.00, 51.73, 48.27, 3.45 +0.00, 0.00, 54.25, 45.75, 8.49 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +0.00, 0.00, 51.77, 48.23, 3.55 +-0.13, 0.00, 56.82, 43.18, 13.64 +-0.13, 0.00, 51.87, 48.13, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.75 +-0.13, 0.00, 51.88, 48.12, 3.76 +-0.13, 0.00, 51.88, 48.12, 3.76 +-0.13, 0.00, 51.88, 48.12, 3.76 +0.00, 0.00, 46.84, 53.16, -6.33 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.00, 0.00, 51.78, 48.22, 3.56 +0.07, 0.00, 49.26, 50.74, -1.48 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.46 +0.07, 0.00, 51.73, 48.27, 3.45 +0.07, 0.00, 51.73, 48.27, 3.45 +0.07, 0.00, 51.73, 48.27, 3.45 +0.07, 0.00, 51.73, 48.27, 3.45 +0.07, 0.00, 51.73, 48.27, 3.45 +0.13, 0.00, 49.20, 50.80, -1.59 +0.13, 0.00, 51.68, 48.32, 3.35 +0.13, 0.00, 51.68, 48.32, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.35 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.34 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.67, 48.33, 3.33 +0.13, 0.00, 51.66, 48.34, 3.33 +0.13, 0.00, 51.66, 48.34, 3.33 +0.07, 0.00, 54.19, 45.81, 8.37 +0.13, 0.00, 49.19, 50.81, -1.62 +0.07, 0.00, 54.18, 45.82, 8.37 +0.07, 0.00, 51.71, 48.29, 3.43 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.00, 0.00, 54.23, 45.77, 8.46 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.00, 0.00, 51.76, 48.24, 3.52 +0.07, 0.00, 49.24, 50.76, -1.52 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.07, 0.00, 51.71, 48.29, 3.42 +0.13, 0.00, 49.19, 50.81, -1.63 +0.13, 0.00, 51.66, 48.34, 3.32 +0.13, 0.00, 51.66, 48.34, 3.32 +0.13, 0.00, 51.66, 48.34, 3.32 +0.13, 0.00, 51.66, 48.34, 3.31 +0.13, 0.00, 51.66, 48.34, 3.31 +0.07, 0.00, 54.18, 45.82, 8.36 +0.07, 0.00, 51.71, 48.29, 3.41 +0.07, 0.00, 51.71, 48.29, 3.41 +0.07, 0.00, 51.71, 48.29, 3.41 +0.07, 0.00, 51.70, 48.30, 3.41 +0.07, 0.00, 51.70, 48.30, 3.41 +0.07, 0.00, 51.70, 48.30, 3.41 +0.07, 0.00, 51.70, 48.30, 3.41 +0.13, 0.00, 49.18, 50.82, -1.64 +0.13, 0.00, 51.65, 48.35, 3.31 +0.13, 0.00, 51.65, 48.35, 3.31 +0.26, 0.00, 46.61, 53.39, -6.78 +0.26, 0.00, 51.55, 48.45, 3.10 +0.26, 0.00, 51.55, 48.45, 3.10 +0.33, 0.00, 49.03, 50.97, -1.94 +0.33, 0.00, 51.50, 48.50, 3.00 +0.33, 0.00, 51.50, 48.50, 3.00 +0.33, 0.00, 51.50, 48.50, 2.99 +0.33, 0.00, 51.50, 48.50, 2.99 +0.33, 0.00, 51.49, 48.51, 2.99 +0.33, 0.00, 51.49, 48.51, 2.99 +0.33, 0.00, 51.49, 48.51, 2.98 +0.33, 0.00, 51.49, 48.51, 2.98 +0.33, 0.00, 51.49, 48.51, 2.98 +0.33, 0.00, 51.49, 48.51, 2.98 +0.33, 0.00, 51.49, 48.51, 2.97 +0.33, 0.00, 51.49, 48.51, 2.97 +0.40, 0.00, 48.96, 51.04, -2.07 +0.40, 0.00, 51.43, 48.57, 2.87 +0.40, 0.00, 51.43, 48.57, 2.86 +0.53, 0.00, 46.39, 53.61, -7.23 +0.53, 0.00, 51.33, 48.67, 2.66 +0.59, 0.00, 48.81, 51.19, -2.39 +0.59, 0.00, 51.28, 48.72, 2.55 +0.59, 0.00, 51.27, 48.73, 2.55 +0.59, 0.00, 51.27, 48.73, 2.54 +0.59, 0.00, 51.27, 48.73, 2.54 +0.59, 0.00, 51.27, 48.73, 2.53 +0.59, 0.00, 51.26, 48.74, 2.53 +0.66, 0.00, 48.74, 51.26, -2.52 +0.59, 0.00, 53.73, 46.27, 7.46 +0.59, 0.00, 51.26, 48.74, 2.51 +0.66, 0.00, 48.73, 51.27, -2.53 +0.66, 0.00, 51.20, 48.80, 2.41 +0.66, 0.00, 51.20, 48.80, 2.40 +0.66, 0.00, 51.20, 48.80, 2.40 +0.66, 0.00, 51.20, 48.80, 2.39 +0.79, 0.00, 46.15, 53.85, -7.70 +0.79, 0.00, 51.09, 48.91, 2.18 +0.79, 0.00, 51.09, 48.91, 2.18 +0.86, 0.00, 48.56, 51.44, -2.87 +0.86, 0.00, 51.03, 48.97, 2.06 +0.92, 0.00, 48.51, 51.49, -2.99 +0.92, 0.00, 50.98, 49.02, 1.95 +0.92, 0.00, 50.97, 49.03, 1.94 +0.92, 0.00, 50.97, 49.03, 1.94 +0.92, 0.00, 50.96, 49.04, 1.93 +0.92, 0.00, 50.96, 49.04, 1.92 +0.92, 0.00, 50.96, 49.04, 1.92 +0.86, 0.00, 53.48, 46.52, 6.95 +0.86, 0.00, 51.00, 49.00, 2.00 +0.86, 0.00, 51.00, 49.00, 2.00 +0.86, 0.00, 50.99, 49.01, 1.99 +0.86, 0.00, 50.99, 49.01, 1.98 +0.92, 0.00, 48.47, 51.53, -3.07 +0.92, 0.00, 50.94, 49.06, 1.87 +0.92, 0.00, 50.93, 49.07, 1.86 +0.92, 0.00, 50.93, 49.07, 1.86 +1.05, 0.00, 45.88, 54.12, -8.24 +1.05, 0.00, 50.82, 49.18, 1.64 +1.05, 0.00, 50.82, 49.18, 1.63 +1.05, 0.00, 50.81, 49.19, 1.63 +1.05, 0.00, 50.81, 49.19, 1.62 +1.05, 0.00, 50.81, 49.19, 1.61 +1.05, 0.00, 50.80, 49.20, 1.60 +1.05, 0.00, 50.80, 49.20, 1.60 +1.05, 0.00, 50.79, 49.21, 1.59 +1.05, 0.00, 50.79, 49.21, 1.58 +1.05, 0.00, 50.79, 49.21, 1.57 +1.05, 0.00, 50.78, 49.22, 1.56 +1.05, 0.00, 50.78, 49.22, 1.56 +1.05, 0.00, 50.77, 49.23, 1.55 +1.05, 0.00, 50.77, 49.23, 1.54 +1.05, 0.00, 50.77, 49.23, 1.53 +1.05, 0.00, 50.76, 49.24, 1.52 +1.05, 0.00, 50.76, 49.24, 1.52 +1.05, 0.00, 50.75, 49.25, 1.51 +1.05, 0.00, 50.75, 49.25, 1.50 +1.12, 0.00, 48.22, 51.78, -3.55 +1.05, 0.00, 53.21, 46.79, 6.43 +1.05, 0.00, 50.74, 49.26, 1.48 +1.05, 0.00, 50.73, 49.27, 1.47 +1.05, 0.00, 50.73, 49.27, 1.46 +1.05, 0.00, 50.73, 49.27, 1.45 +1.05, 0.00, 50.72, 49.28, 1.44 +1.05, 0.00, 50.72, 49.28, 1.44 +1.05, 0.00, 50.71, 49.29, 1.43 +0.92, 0.00, 55.75, 44.25, 11.51 +0.92, 0.00, 50.81, 49.19, 1.61 +0.92, 0.00, 50.80, 49.20, 1.61 +0.92, 0.00, 50.80, 49.20, 1.60 +0.92, 0.00, 50.80, 49.20, 1.59 +0.92, 0.00, 50.79, 49.21, 1.58 +0.92, 0.00, 50.79, 49.21, 1.58 +0.92, 0.00, 50.79, 49.21, 1.57 +0.92, 0.00, 50.78, 49.22, 1.56 +0.92, 0.00, 50.78, 49.22, 1.56 +1.05, 0.00, 45.73, 54.27, -8.54 +1.05, 0.00, 50.67, 49.33, 1.34 +1.05, 0.00, 50.67, 49.33, 1.34 +1.05, 0.00, 50.66, 49.34, 1.33 +0.92, 0.00, 55.70, 44.30, 11.41 +0.92, 0.00, 50.76, 49.24, 1.51 +0.92, 0.00, 50.75, 49.25, 1.50 +0.92, 0.00, 50.75, 49.25, 1.50 +0.86, 0.00, 53.27, 46.73, 6.53 +0.86, 0.00, 50.79, 49.21, 1.58 +0.86, 0.00, 50.79, 49.21, 1.58 +0.86, 0.00, 50.79, 49.21, 1.57 +0.86, 0.00, 50.78, 49.22, 1.56 +0.86, 0.00, 50.78, 49.22, 1.56 +0.86, 0.00, 50.78, 49.22, 1.55 +0.86, 0.00, 50.77, 49.23, 1.55 +0.86, 0.00, 50.77, 49.23, 1.54 +0.86, 0.00, 50.77, 49.23, 1.53 +0.86, 0.00, 50.76, 49.24, 1.53 +0.86, 0.00, 50.76, 49.24, 1.52 +0.86, 0.00, 50.76, 49.24, 1.51 +0.86, 0.00, 50.75, 49.25, 1.51 +0.86, 0.00, 50.75, 49.25, 1.50 +0.86, 0.00, 50.75, 49.25, 1.49 +0.86, 0.00, 50.74, 49.26, 1.49 +0.86, 0.00, 50.74, 49.26, 1.48 +0.79, 0.00, 53.26, 46.74, 6.52 +0.79, 0.00, 50.78, 49.22, 1.57 +0.79, 0.00, 50.78, 49.22, 1.56 +0.79, 0.00, 50.78, 49.22, 1.56 +0.79, 0.00, 50.78, 49.22, 1.55 +0.79, 0.00, 50.77, 49.23, 1.54 +0.79, 0.00, 50.77, 49.23, 1.54 +0.79, 0.00, 50.77, 49.23, 1.53 +0.79, 0.00, 50.76, 49.24, 1.53 +0.79, 0.00, 50.76, 49.24, 1.52 +0.79, 0.00, 50.76, 49.24, 1.51 +0.86, 0.00, 48.23, 51.77, -3.53 +0.86, 0.00, 50.70, 49.30, 1.40 +0.86, 0.00, 50.70, 49.30, 1.40 +0.86, 0.00, 50.70, 49.30, 1.39 +0.92, 0.00, 48.17, 51.83, -3.66 +0.92, 0.00, 50.64, 49.36, 1.28 +0.86, 0.00, 53.16, 46.84, 6.31 +0.86, 0.00, 50.68, 49.32, 1.36 +0.86, 0.00, 50.68, 49.32, 1.36 +0.86, 0.00, 50.68, 49.32, 1.35 +0.86, 0.00, 50.67, 49.33, 1.34 +0.86, 0.00, 50.67, 49.33, 1.34 +0.86, 0.00, 50.67, 49.33, 1.33 +0.79, 0.00, 53.18, 46.82, 6.37 +0.79, 0.00, 50.71, 49.29, 1.42 +0.79, 0.00, 50.71, 49.29, 1.41 +0.79, 0.00, 50.70, 49.30, 1.41 +0.86, 0.00, 48.18, 51.82, -3.64 +0.86, 0.00, 50.65, 49.35, 1.29 +0.86, 0.00, 50.64, 49.36, 1.29 +0.86, 0.00, 50.64, 49.36, 1.28 +0.86, 0.00, 50.64, 49.36, 1.28 +0.92, 0.00, 48.11, 51.89, -3.77 +0.92, 0.00, 50.58, 49.42, 1.16 +0.92, 0.00, 50.58, 49.42, 1.16 +0.92, 0.00, 50.57, 49.43, 1.15 +0.92, 0.00, 50.57, 49.43, 1.14 +0.92, 0.00, 50.57, 49.43, 1.13 +0.92, 0.00, 50.56, 49.44, 1.13 +0.86, 0.00, 53.08, 46.92, 6.16 +0.86, 0.00, 50.61, 49.39, 1.21 +0.86, 0.00, 50.60, 49.40, 1.21 +0.86, 0.00, 50.60, 49.40, 1.20 +0.86, 0.00, 50.60, 49.40, 1.19 +0.86, 0.00, 50.59, 49.41, 1.19 +0.86, 0.00, 50.59, 49.41, 1.18 +0.86, 0.00, 50.59, 49.41, 1.18 +0.86, 0.00, 50.58, 49.42, 1.17 +0.86, 0.00, 50.58, 49.42, 1.16 +0.86, 0.00, 50.58, 49.42, 1.16 +0.86, 0.00, 50.57, 49.43, 1.15 +0.86, 0.00, 50.57, 49.43, 1.14 +0.92, 0.00, 48.05, 51.95, -3.91 +0.92, 0.00, 50.52, 49.48, 1.03 +0.92, 0.00, 50.51, 49.49, 1.02 +0.92, 0.00, 50.51, 49.49, 1.02 +0.86, 0.00, 53.03, 46.97, 6.05 +0.86, 0.00, 50.55, 49.45, 1.10 +0.86, 0.00, 50.55, 49.45, 1.10 +0.86, 0.00, 50.54, 49.46, 1.09 +0.86, 0.00, 50.54, 49.46, 1.08 +0.79, 0.00, 53.06, 46.94, 6.12 +0.86, 0.00, 48.06, 51.94, -3.87 +0.86, 0.00, 50.53, 49.47, 1.06 +0.79, 0.00, 53.05, 46.95, 6.10 +0.79, 0.00, 50.58, 49.42, 1.15 +0.86, 0.00, 48.05, 51.95, -3.90 +0.86, 0.00, 50.52, 49.48, 1.04 +0.86, 0.00, 50.52, 49.48, 1.03 +0.86, 0.00, 50.51, 49.49, 1.03 +0.86, 0.00, 50.51, 49.49, 1.02 +0.86, 0.00, 50.51, 49.49, 1.01 +0.86, 0.00, 50.50, 49.50, 1.01 +0.86, 0.00, 50.50, 49.50, 1.00 +0.86, 0.00, 50.50, 49.50, 1.00 +0.86, 0.00, 50.49, 49.51, 0.99 +0.86, 0.00, 50.49, 49.51, 0.98 +0.86, 0.00, 50.49, 49.51, 0.98 +0.86, 0.00, 50.48, 49.52, 0.97 +0.79, 0.00, 53.00, 47.00, 6.01 +0.79, 0.00, 50.53, 49.47, 1.06 +0.79, 0.00, 50.53, 49.47, 1.05 +0.79, 0.00, 50.52, 49.48, 1.04 +0.66, 0.00, 55.56, 44.44, 11.12 +0.79, 0.00, 45.57, 54.43, -8.85 +0.79, 0.00, 50.51, 49.49, 1.03 +0.79, 0.00, 50.51, 49.49, 1.02 +0.79, 0.00, 50.51, 49.49, 1.02 +0.79, 0.00, 50.50, 49.50, 1.01 +0.79, 0.00, 50.50, 49.50, 1.00 +0.79, 0.00, 50.50, 49.50, 1.00 +0.79, 0.00, 50.50, 49.50, 0.99 +0.79, 0.00, 50.49, 49.51, 0.99 +0.79, 0.00, 50.49, 49.51, 0.98 +0.79, 0.00, 50.49, 49.51, 0.97 +0.66, 0.00, 55.53, 44.47, 11.05 +0.66, 0.00, 50.58, 49.42, 1.16 +0.66, 0.00, 50.58, 49.42, 1.16 +0.66, 0.00, 50.58, 49.42, 1.15 +0.66, 0.00, 50.57, 49.43, 1.15 +0.66, 0.00, 50.57, 49.43, 1.14 +0.59, 0.00, 53.09, 46.91, 6.18 +0.59, 0.00, 50.62, 49.38, 1.23 +0.59, 0.00, 50.61, 49.39, 1.23 +0.66, 0.00, 48.09, 51.91, -3.82 +0.59, 0.00, 53.08, 46.92, 6.16 +0.66, 0.00, 48.09, 51.91, -3.83 +0.66, 0.00, 50.55, 49.45, 1.11 +0.66, 0.00, 50.55, 49.45, 1.10 +0.66, 0.00, 50.55, 49.45, 1.10 +0.66, 0.00, 50.55, 49.45, 1.09 +0.66, 0.00, 50.54, 49.46, 1.09 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.08 +0.66, 0.00, 50.54, 49.46, 1.07 +0.66, 0.00, 50.53, 49.47, 1.07 +0.66, 0.00, 50.53, 49.47, 1.06 +0.66, 0.00, 50.53, 49.47, 1.06 +0.59, 0.00, 53.05, 46.95, 6.09 +0.59, 0.00, 50.57, 49.43, 1.15 +0.59, 0.00, 50.57, 49.43, 1.14 +0.59, 0.00, 50.57, 49.43, 1.14 +0.59, 0.00, 50.57, 49.43, 1.13 +0.59, 0.00, 50.56, 49.44, 1.13 +0.59, 0.00, 50.56, 49.44, 1.12 +0.59, 0.00, 50.56, 49.44, 1.12 +0.59, 0.00, 50.56, 49.44, 1.11 +0.66, 0.00, 48.03, 51.97, -3.93 +0.59, 0.00, 53.02, 46.98, 6.05 +0.66, 0.00, 48.03, 51.97, -3.94 +0.59, 0.00, 53.02, 46.98, 6.04 +0.59, 0.00, 50.55, 49.45, 1.09 +0.59, 0.00, 50.54, 49.46, 1.09 +0.59, 0.00, 50.54, 49.46, 1.08 +0.59, 0.00, 50.54, 49.46, 1.08 +0.59, 0.00, 50.54, 49.46, 1.07 +0.59, 0.00, 50.53, 49.47, 1.07 +0.59, 0.00, 50.53, 49.47, 1.06 +0.59, 0.00, 50.53, 49.47, 1.06 +0.59, 0.00, 50.53, 49.47, 1.06 +0.59, 0.00, 50.53, 49.47, 1.05 +0.59, 0.00, 50.52, 49.48, 1.05 +0.59, 0.00, 50.52, 49.48, 1.04 +0.53, 0.00, 53.04, 46.96, 6.08 +0.53, 0.00, 50.57, 49.43, 1.13 +0.53, 0.00, 50.56, 49.44, 1.13 +0.53, 0.00, 50.56, 49.44, 1.13 +0.53, 0.00, 50.56, 49.44, 1.12 +0.53, 0.00, 50.56, 49.44, 1.12 +0.40, 0.00, 55.60, 44.40, 11.20 +0.40, 0.00, 50.65, 49.35, 1.31 +0.40, 0.00, 50.65, 49.35, 1.31 +0.40, 0.00, 50.65, 49.35, 1.30 +0.40, 0.00, 50.65, 49.35, 1.30 +0.33, 0.00, 53.17, 46.83, 6.34 +0.33, 0.00, 50.70, 49.30, 1.39 +0.33, 0.00, 50.70, 49.30, 1.39 +0.33, 0.00, 50.69, 49.31, 1.39 +0.26, 0.00, 53.21, 46.79, 6.43 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.48 +0.26, 0.00, 50.74, 49.26, 1.47 +0.13, 0.00, 55.78, 44.22, 11.56 +0.13, 0.00, 50.83, 49.17, 1.67 +0.13, 0.00, 50.83, 49.17, 1.67 +0.13, 0.00, 50.83, 49.17, 1.67 +0.13, 0.00, 50.83, 49.17, 1.67 +0.07, 0.00, 53.35, 46.65, 6.71 +0.07, 0.00, 50.88, 49.12, 1.76 +0.07, 0.00, 50.88, 49.12, 1.76 +0.07, 0.00, 50.88, 49.12, 1.76 +0.00, 0.00, 53.40, 46.60, 6.81 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +0.00, 0.00, 50.93, 49.07, 1.86 +-0.13, 0.00, 55.97, 44.03, 11.95 +-0.13, 0.00, 51.03, 48.97, 2.06 +-0.13, 0.00, 51.03, 48.97, 2.06 +-0.13, 0.00, 51.03, 48.97, 2.06 +-0.13, 0.00, 51.03, 48.97, 2.07 +-0.20, 0.00, 53.55, 46.45, 7.11 +-0.20, 0.00, 51.08, 48.92, 2.17 +-0.20, 0.00, 51.08, 48.92, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.17 +-0.20, 0.00, 51.09, 48.91, 2.18 +-0.20, 0.00, 51.09, 48.91, 2.18 +-0.26, 0.00, 53.61, 46.39, 7.22 +-0.26, 0.00, 51.14, 48.86, 2.28 +-0.26, 0.00, 51.14, 48.86, 2.28 +-0.26, 0.00, 51.14, 48.86, 2.28 +-0.26, 0.00, 51.14, 48.86, 2.29 +-0.26, 0.00, 51.14, 48.86, 2.29 +-0.26, 0.00, 51.15, 48.85, 2.29 +-0.40, 0.00, 56.19, 43.81, 12.38 +-0.40, 0.00, 51.25, 48.75, 2.49 +-0.40, 0.00, 51.25, 48.75, 2.50 +-0.40, 0.00, 51.25, 48.75, 2.50 +-0.40, 0.00, 51.25, 48.75, 2.50 +-0.40, 0.00, 51.25, 48.75, 2.51 +-0.40, 0.00, 51.25, 48.75, 2.51 +-0.46, 0.00, 53.78, 46.22, 7.56 +-0.40, 0.00, 48.79, 51.21, -2.43 +-0.40, 0.00, 51.26, 48.74, 2.52 +-0.40, 0.00, 51.26, 48.74, 2.52 +-0.46, 0.00, 53.78, 46.22, 7.57 +-0.46, 0.00, 51.31, 48.69, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.63 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.65 +-0.46, 0.00, 51.33, 48.67, 2.65 +-0.53, 0.00, 53.85, 46.15, 7.70 +-0.53, 0.00, 51.38, 48.62, 2.76 +-0.53, 0.00, 51.38, 48.62, 2.76 +-0.53, 0.00, 51.38, 48.62, 2.77 +-0.53, 0.00, 51.38, 48.62, 2.77 +-0.53, 0.00, 51.39, 48.61, 2.77 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.79 +-0.53, 0.00, 51.39, 48.61, 2.79 +-0.53, 0.00, 51.40, 48.60, 2.79 +-0.53, 0.00, 51.40, 48.60, 2.80 +-0.53, 0.00, 51.40, 48.60, 2.80 +-0.53, 0.00, 51.40, 48.60, 2.81 +-0.53, 0.00, 51.40, 48.60, 2.81 +-0.53, 0.00, 51.41, 48.59, 2.81 +-0.53, 0.00, 51.41, 48.59, 2.82 +-0.53, 0.00, 51.41, 48.59, 2.82 +-0.53, 0.00, 51.41, 48.59, 2.83 +-0.53, 0.00, 51.41, 48.59, 2.83 +-0.53, 0.00, 51.42, 48.58, 2.83 +-0.53, 0.00, 51.42, 48.58, 2.84 +-0.53, 0.00, 51.42, 48.58, 2.84 +-0.53, 0.00, 51.42, 48.58, 2.85 +-0.53, 0.00, 51.42, 48.58, 2.85 +-0.53, 0.00, 51.43, 48.57, 2.85 +-0.46, 0.00, 48.91, 51.09, -2.19 +-0.46, 0.00, 51.38, 48.62, 2.76 +-0.46, 0.00, 51.38, 48.62, 2.76 +-0.46, 0.00, 51.38, 48.62, 2.77 +-0.46, 0.00, 51.39, 48.61, 2.77 +-0.40, 0.00, 48.87, 51.13, -2.27 +-0.40, 0.00, 51.34, 48.66, 2.68 +-0.40, 0.00, 51.34, 48.66, 2.68 +-0.40, 0.00, 51.34, 48.66, 2.68 +-0.40, 0.00, 51.34, 48.66, 2.69 +-0.40, 0.00, 51.35, 48.65, 2.69 +-0.40, 0.00, 51.35, 48.65, 2.69 +-0.40, 0.00, 51.35, 48.65, 2.70 +-0.40, 0.00, 51.35, 48.65, 2.70 +-0.40, 0.00, 51.35, 48.65, 2.70 +-0.26, 0.00, 46.31, 53.69, -7.38 +-0.26, 0.00, 51.25, 48.75, 2.51 +-0.26, 0.00, 51.26, 48.74, 2.51 +-0.26, 0.00, 51.26, 48.74, 2.51 +-0.26, 0.00, 51.26, 48.74, 2.51 +-0.20, 0.00, 48.74, 51.26, -2.53 +-0.20, 0.00, 51.21, 48.79, 2.42 +-0.20, 0.00, 51.21, 48.79, 2.42 +-0.20, 0.00, 51.21, 48.79, 2.42 +-0.13, 0.00, 48.69, 51.31, -2.62 +-0.13, 0.00, 51.16, 48.84, 2.32 +-0.13, 0.00, 51.16, 48.84, 2.33 +-0.13, 0.00, 51.16, 48.84, 2.33 +-0.13, 0.00, 51.16, 48.84, 2.33 +-0.13, 0.00, 51.16, 48.84, 2.33 +-0.13, 0.00, 51.16, 48.84, 2.33 +0.00, 0.00, 46.12, 53.88, -7.76 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.00, 0.00, 51.07, 48.93, 2.13 +0.07, 0.00, 48.54, 51.46, -2.91 +0.07, 0.00, 51.02, 48.98, 2.03 +0.07, 0.00, 51.02, 48.98, 2.03 +0.07, 0.00, 51.02, 48.98, 2.03 +0.13, 0.00, 48.49, 51.51, -3.01 +0.13, 0.00, 50.96, 49.04, 1.93 +0.13, 0.00, 50.96, 49.04, 1.93 +0.13, 0.00, 50.96, 49.04, 1.93 +0.26, 0.00, 45.92, 54.08, -8.16 +0.26, 0.00, 50.86, 49.14, 1.73 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.72 +0.26, 0.00, 50.86, 49.14, 1.71 +0.33, 0.00, 48.33, 51.67, -3.33 +0.33, 0.00, 50.81, 49.19, 1.61 +0.33, 0.00, 50.80, 49.20, 1.61 +0.33, 0.00, 50.80, 49.20, 1.61 +0.33, 0.00, 50.80, 49.20, 1.60 +0.33, 0.00, 50.80, 49.20, 1.60 +0.33, 0.00, 50.80, 49.20, 1.60 +0.33, 0.00, 50.80, 49.20, 1.60 +0.33, 0.00, 50.80, 49.20, 1.59 +0.40, 0.00, 48.27, 51.73, -3.45 +0.40, 0.00, 50.74, 49.26, 1.49 +0.40, 0.00, 50.74, 49.26, 1.49 +0.40, 0.00, 50.74, 49.26, 1.48 +0.40, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 53.26, 46.74, 6.52 +0.40, 0.00, 48.27, 51.73, -3.47 +0.40, 0.00, 50.74, 49.26, 1.47 +0.33, 0.00, 53.26, 46.74, 6.51 +0.33, 0.00, 50.78, 49.22, 1.57 +0.33, 0.00, 50.78, 49.22, 1.56 +0.33, 0.00, 50.78, 49.22, 1.56 +0.33, 0.00, 50.78, 49.22, 1.56 +0.33, 0.00, 50.78, 49.22, 1.56 +0.40, 0.00, 48.25, 51.75, -3.49 +0.33, 0.00, 53.25, 46.75, 6.49 +0.40, 0.00, 48.25, 51.75, -3.50 +0.40, 0.00, 50.72, 49.28, 1.44 +0.33, 0.00, 53.24, 46.76, 6.49 +0.40, 0.00, 48.25, 51.75, -3.50 +0.33, 0.00, 53.24, 46.76, 6.48 +0.33, 0.00, 50.77, 49.23, 1.53 +0.33, 0.00, 50.77, 49.23, 1.53 +0.33, 0.00, 50.76, 49.24, 1.53 +0.33, 0.00, 50.76, 49.24, 1.53 +0.33, 0.00, 50.76, 49.24, 1.52 +0.33, 0.00, 50.76, 49.24, 1.52 +0.33, 0.00, 50.76, 49.24, 1.52 +0.33, 0.00, 50.76, 49.24, 1.52 +0.33, 0.00, 50.76, 49.24, 1.51 +0.33, 0.00, 50.76, 49.24, 1.51 +0.33, 0.00, 50.75, 49.25, 1.51 +0.33, 0.00, 50.75, 49.25, 1.51 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.50 +0.33, 0.00, 50.75, 49.25, 1.49 +0.33, 0.00, 50.75, 49.25, 1.49 +0.33, 0.00, 50.74, 49.26, 1.49 +0.33, 0.00, 50.74, 49.26, 1.49 +0.33, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 50.74, 49.26, 1.48 +0.33, 0.00, 50.74, 49.26, 1.47 +0.33, 0.00, 50.74, 49.26, 1.47 +0.33, 0.00, 50.73, 49.27, 1.47 +0.33, 0.00, 50.73, 49.27, 1.47 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.46 +0.33, 0.00, 50.73, 49.27, 1.45 +0.40, 0.00, 48.20, 51.80, -3.59 +0.40, 0.00, 50.67, 49.33, 1.35 +0.40, 0.00, 50.67, 49.33, 1.35 +0.40, 0.00, 50.67, 49.33, 1.34 +0.40, 0.00, 50.67, 49.33, 1.34 +0.33, 0.00, 53.19, 46.81, 6.38 +0.33, 0.00, 50.72, 49.28, 1.43 +0.33, 0.00, 50.72, 49.28, 1.43 +0.33, 0.00, 50.71, 49.29, 1.43 +0.33, 0.00, 50.71, 49.29, 1.43 +0.33, 0.00, 50.71, 49.29, 1.42 +0.26, 0.00, 53.23, 46.77, 6.47 +0.26, 0.00, 50.76, 49.24, 1.52 +0.26, 0.00, 50.76, 49.24, 1.52 +0.26, 0.00, 50.76, 49.24, 1.52 +0.26, 0.00, 50.76, 49.24, 1.51 +0.26, 0.00, 50.76, 49.24, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.51 +0.26, 0.00, 50.75, 49.25, 1.50 +0.13, 0.00, 55.79, 44.21, 11.59 +0.13, 0.00, 50.85, 49.15, 1.70 +0.13, 0.00, 50.85, 49.15, 1.70 +0.13, 0.00, 50.85, 49.15, 1.70 +0.07, 0.00, 53.37, 46.63, 6.74 +0.07, 0.00, 50.90, 49.10, 1.80 +0.07, 0.00, 50.90, 49.10, 1.79 +0.00, 0.00, 53.42, 46.58, 6.84 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +0.00, 0.00, 50.95, 49.05, 1.89 +-0.13, 0.00, 55.99, 44.01, 11.98 +-0.13, 0.00, 51.05, 48.95, 2.09 +-0.13, 0.00, 51.05, 48.95, 2.09 +-0.20, 0.00, 53.57, 46.43, 7.14 +-0.20, 0.00, 51.10, 48.90, 2.20 +-0.20, 0.00, 51.10, 48.90, 2.20 +-0.20, 0.00, 51.10, 48.90, 2.20 +-0.26, 0.00, 53.62, 46.38, 7.24 +-0.26, 0.00, 51.15, 48.85, 2.30 +-0.26, 0.00, 51.15, 48.85, 2.30 +-0.26, 0.00, 51.15, 48.85, 2.31 +-0.26, 0.00, 51.15, 48.85, 2.31 +-0.26, 0.00, 51.16, 48.84, 2.31 +-0.26, 0.00, 51.16, 48.84, 2.31 +-0.26, 0.00, 51.16, 48.84, 2.31 +-0.26, 0.00, 51.16, 48.84, 2.32 +-0.26, 0.00, 51.16, 48.84, 2.32 +-0.26, 0.00, 51.16, 48.84, 2.32 +-0.40, 0.00, 56.20, 43.80, 12.41 +-0.40, 0.00, 51.26, 48.74, 2.52 +-0.40, 0.00, 51.26, 48.74, 2.53 +-0.40, 0.00, 51.26, 48.74, 2.53 +-0.46, 0.00, 53.79, 46.21, 7.58 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.46, 0.00, 51.32, 48.68, 2.64 +-0.53, 0.00, 53.84, 46.16, 7.69 +-0.53, 0.00, 51.37, 48.63, 2.75 +-0.53, 0.00, 51.37, 48.63, 2.75 +-0.53, 0.00, 51.38, 48.62, 2.75 +-0.53, 0.00, 51.38, 48.62, 2.76 +-0.53, 0.00, 51.38, 48.62, 2.76 +-0.53, 0.00, 51.38, 48.62, 2.77 +-0.53, 0.00, 51.38, 48.62, 2.77 +-0.53, 0.00, 51.39, 48.61, 2.77 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.78 +-0.53, 0.00, 51.39, 48.61, 2.79 +-0.53, 0.00, 51.39, 48.61, 2.79 +-0.66, 0.00, 56.44, 43.56, 12.88 +-0.66, 0.00, 51.50, 48.50, 3.00 +-0.66, 0.00, 51.50, 48.50, 3.00 +-0.66, 0.00, 51.50, 48.50, 3.01 +-0.66, 0.00, 51.51, 48.49, 3.01 +-0.73, 0.00, 54.03, 45.97, 8.06 +-0.73, 0.00, 51.56, 48.44, 3.12 +-0.73, 0.00, 51.56, 48.44, 3.13 +-0.73, 0.00, 51.57, 48.43, 3.13 +-0.73, 0.00, 51.57, 48.43, 3.14 +-0.73, 0.00, 51.57, 48.43, 3.14 +-0.73, 0.00, 51.57, 48.43, 3.15 +-0.73, 0.00, 51.58, 48.42, 3.15 +-0.73, 0.00, 51.58, 48.42, 3.16 +-0.73, 0.00, 51.58, 48.42, 3.16 +-0.73, 0.00, 51.59, 48.41, 3.17 +-0.73, 0.00, 51.59, 48.41, 3.18 +-0.73, 0.00, 51.59, 48.41, 3.18 +-0.73, 0.00, 51.59, 48.41, 3.19 +-0.79, 0.00, 54.12, 45.88, 8.24 +-0.79, 0.00, 51.65, 48.35, 3.30 +-0.79, 0.00, 51.65, 48.35, 3.30 +-0.79, 0.00, 51.65, 48.35, 3.31 +-0.79, 0.00, 51.66, 48.34, 3.32 +-0.79, 0.00, 51.66, 48.34, 3.32 +-0.79, 0.00, 51.66, 48.34, 3.33 +-0.92, 0.00, 56.71, 43.29, 13.42 +-0.92, 0.00, 51.77, 48.23, 3.54 +-0.92, 0.00, 51.77, 48.23, 3.55 +-0.92, 0.00, 51.78, 48.22, 3.55 +-0.92, 0.00, 51.78, 48.22, 3.56 +-0.79, 0.00, 46.74, 53.26, -6.52 +-0.79, 0.00, 51.69, 48.31, 3.37 +-0.79, 0.00, 51.69, 48.31, 3.38 +-0.79, 0.00, 51.69, 48.31, 3.39 +-0.79, 0.00, 51.70, 48.30, 3.39 +-0.92, 0.00, 56.74, 43.26, 13.48 +-0.92, 0.00, 51.80, 48.20, 3.60 +-0.92, 0.00, 51.80, 48.20, 3.61 +-0.92, 0.00, 51.81, 48.19, 3.62 +-0.92, 0.00, 51.81, 48.19, 3.62 +-0.92, 0.00, 51.82, 48.18, 3.63 +-0.92, 0.00, 51.82, 48.18, 3.64 +-0.92, 0.00, 51.82, 48.18, 3.64 +-0.92, 0.00, 51.83, 48.17, 3.65 +-0.92, 0.00, 51.83, 48.17, 3.66 +-0.92, 0.00, 51.83, 48.17, 3.67 +-0.92, 0.00, 51.84, 48.16, 3.67 +-0.92, 0.00, 51.84, 48.16, 3.68 +-0.92, 0.00, 51.84, 48.16, 3.69 +-0.92, 0.00, 51.85, 48.15, 3.69 +-0.92, 0.00, 51.85, 48.15, 3.70 +-0.79, 0.00, 46.81, 53.19, -6.38 +-0.79, 0.00, 51.76, 48.24, 3.51 +-0.79, 0.00, 51.76, 48.24, 3.52 +-0.79, 0.00, 51.76, 48.24, 3.53 +-0.79, 0.00, 51.77, 48.23, 3.53 +-0.79, 0.00, 51.77, 48.23, 3.54 +-0.79, 0.00, 51.77, 48.23, 3.54 +-0.79, 0.00, 51.77, 48.23, 3.55 +-0.79, 0.00, 51.78, 48.22, 3.56 +-0.79, 0.00, 51.78, 48.22, 3.56 +-0.79, 0.00, 51.78, 48.22, 3.57 +-0.79, 0.00, 51.79, 48.21, 3.57 +-0.79, 0.00, 51.79, 48.21, 3.58 +-0.79, 0.00, 51.79, 48.21, 3.59 +-0.79, 0.00, 51.80, 48.20, 3.59 +-0.73, 0.00, 49.28, 50.72, -1.45 +-0.73, 0.00, 51.75, 48.25, 3.50 +-0.73, 0.00, 51.75, 48.25, 3.51 +-0.73, 0.00, 51.76, 48.24, 3.51 +-0.73, 0.00, 51.76, 48.24, 3.52 +-0.73, 0.00, 51.76, 48.24, 3.52 +-0.73, 0.00, 51.77, 48.23, 3.53 +-0.73, 0.00, 51.77, 48.23, 3.54 +-0.73, 0.00, 51.77, 48.23, 3.54 +-0.73, 0.00, 51.77, 48.23, 3.55 +-0.73, 0.00, 51.78, 48.22, 3.55 +-0.66, 0.00, 49.26, 50.74, -1.49 +-0.66, 0.00, 51.73, 48.27, 3.46 +-0.66, 0.00, 51.73, 48.27, 3.47 +-0.66, 0.00, 51.74, 48.26, 3.47 +-0.66, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 51.74, 48.26, 3.49 +-0.66, 0.00, 51.75, 48.25, 3.49 +-0.66, 0.00, 51.75, 48.25, 3.50 +-0.66, 0.00, 51.75, 48.25, 3.50 +-0.66, 0.00, 51.75, 48.25, 3.51 +-0.66, 0.00, 51.76, 48.24, 3.51 +-0.66, 0.00, 51.76, 48.24, 3.52 +-0.53, 0.00, 46.72, 53.28, -6.56 +-0.53, 0.00, 51.66, 48.34, 3.33 +-0.53, 0.00, 51.67, 48.33, 3.33 +-0.53, 0.00, 51.67, 48.33, 3.34 +-0.53, 0.00, 51.67, 48.33, 3.34 +-0.53, 0.00, 51.67, 48.33, 3.34 +-0.53, 0.00, 51.67, 48.33, 3.35 +-0.53, 0.00, 51.68, 48.32, 3.35 +-0.53, 0.00, 51.68, 48.32, 3.36 +-0.53, 0.00, 51.68, 48.32, 3.36 +-0.53, 0.00, 51.68, 48.32, 3.36 +-0.53, 0.00, 51.68, 48.32, 3.37 +-0.53, 0.00, 51.69, 48.31, 3.37 +-0.53, 0.00, 51.69, 48.31, 3.37 +-0.53, 0.00, 51.69, 48.31, 3.38 +-0.53, 0.00, 51.69, 48.31, 3.38 +-0.53, 0.00, 51.69, 48.31, 3.39 +-0.53, 0.00, 51.70, 48.30, 3.39 +-0.53, 0.00, 51.70, 48.30, 3.39 +-0.53, 0.00, 51.70, 48.30, 3.40 +-0.53, 0.00, 51.70, 48.30, 3.40 +-0.46, 0.00, 49.18, 50.82, -1.64 +-0.46, 0.00, 51.66, 48.34, 3.31 +-0.53, 0.00, 54.18, 45.82, 8.36 +-0.53, 0.00, 51.71, 48.29, 3.42 +-0.53, 0.00, 51.71, 48.29, 3.42 +-0.53, 0.00, 51.71, 48.29, 3.43 +-0.53, 0.00, 51.71, 48.29, 3.43 +-0.53, 0.00, 51.72, 48.28, 3.43 +-0.53, 0.00, 51.72, 48.28, 3.44 +-0.53, 0.00, 51.72, 48.28, 3.44 +-0.53, 0.00, 51.72, 48.28, 3.45 +-0.53, 0.00, 51.72, 48.28, 3.45 +-0.53, 0.00, 51.73, 48.27, 3.45 +-0.53, 0.00, 51.73, 48.27, 3.46 +-0.53, 0.00, 51.73, 48.27, 3.46 +-0.53, 0.00, 51.73, 48.27, 3.46 +-0.53, 0.00, 51.73, 48.27, 3.47 +-0.53, 0.00, 51.74, 48.26, 3.47 +-0.53, 0.00, 51.74, 48.26, 3.48 +-0.53, 0.00, 51.74, 48.26, 3.48 +-0.66, 0.00, 56.79, 43.21, 13.57 +-0.66, 0.00, 51.84, 48.16, 3.69 +-0.66, 0.00, 51.85, 48.15, 3.69 +-0.66, 0.00, 51.85, 48.15, 3.70 +-0.66, 0.00, 51.85, 48.15, 3.70 +-0.73, 0.00, 54.38, 45.62, 8.75 +-0.73, 0.00, 51.91, 48.09, 3.81 +-0.73, 0.00, 51.91, 48.09, 3.82 +-0.73, 0.00, 51.91, 48.09, 3.82 +-0.73, 0.00, 51.91, 48.09, 3.83 +-0.73, 0.00, 51.92, 48.08, 3.83 +-0.73, 0.00, 51.92, 48.08, 3.84 +-0.73, 0.00, 51.92, 48.08, 3.85 +-0.79, 0.00, 54.45, 45.55, 8.89 +-0.79, 0.00, 51.98, 48.02, 3.96 +-0.79, 0.00, 51.98, 48.02, 3.96 +-0.79, 0.00, 51.98, 48.02, 3.97 +-0.79, 0.00, 51.99, 48.01, 3.97 +-0.92, 0.00, 57.03, 42.97, 14.07 +-0.92, 0.00, 52.09, 47.91, 4.19 +-0.92, 0.00, 52.10, 47.90, 4.19 +-0.92, 0.00, 52.10, 47.90, 4.20 +-0.99, 0.00, 54.62, 45.38, 9.25 +-0.99, 0.00, 52.16, 47.84, 4.31 +-0.99, 0.00, 52.16, 47.84, 4.32 +-0.99, 0.00, 52.16, 47.84, 4.33 +-0.99, 0.00, 52.17, 47.83, 4.34 +-0.99, 0.00, 52.17, 47.83, 4.34 +-0.99, 0.00, 52.18, 47.82, 4.35 +-0.99, 0.00, 52.18, 47.82, 4.36 +-0.99, 0.00, 52.18, 47.82, 4.37 +-0.99, 0.00, 52.19, 47.81, 4.37 +-0.99, 0.00, 52.19, 47.81, 4.38 +-0.99, 0.00, 52.19, 47.81, 4.39 +-1.05, 0.00, 54.72, 45.28, 9.44 +-1.05, 0.00, 52.25, 47.75, 4.50 +-1.05, 0.00, 52.26, 47.74, 4.51 +-1.05, 0.00, 52.26, 47.74, 4.52 +-1.05, 0.00, 52.26, 47.74, 4.53 +-1.19, 0.00, 57.31, 42.69, 14.62 +-1.19, 0.00, 52.37, 47.63, 4.74 +-1.19, 0.00, 52.38, 47.62, 4.75 +-1.19, 0.00, 52.38, 47.62, 4.76 +-1.19, 0.00, 52.38, 47.62, 4.77 +-1.19, 0.00, 52.39, 47.61, 4.78 +-1.19, 0.00, 52.39, 47.61, 4.79 +-1.19, 0.00, 52.40, 47.60, 4.79 +-1.19, 0.00, 52.40, 47.60, 4.80 +-1.19, 0.00, 52.41, 47.59, 4.81 +-1.19, 0.00, 52.41, 47.59, 4.82 +-1.19, 0.00, 52.42, 47.58, 4.83 +-1.19, 0.00, 52.42, 47.58, 4.84 +-1.19, 0.00, 52.42, 47.58, 4.85 +-1.19, 0.00, 52.43, 47.57, 4.86 +-1.19, 0.00, 52.43, 47.57, 4.87 +-1.19, 0.00, 52.44, 47.56, 4.87 +-1.19, 0.00, 52.44, 47.56, 4.88 +-1.19, 0.00, 52.45, 47.55, 4.89 +-1.19, 0.00, 52.45, 47.55, 4.90 +-1.19, 0.00, 52.46, 47.54, 4.91 +-1.25, 0.00, 54.98, 45.02, 9.96 +-1.25, 0.00, 52.51, 47.49, 5.03 +-1.25, 0.00, 52.52, 47.48, 5.04 +-1.25, 0.00, 52.52, 47.48, 5.05 +-1.19, 0.00, 50.01, 49.99, 0.01 +-1.19, 0.00, 52.48, 47.52, 4.97 +-1.19, 0.00, 52.49, 47.51, 4.97 +-1.19, 0.00, 52.49, 47.51, 4.98 +-1.19, 0.00, 52.50, 47.50, 4.99 +-1.05, 0.00, 47.46, 52.54, -5.08 +-1.05, 0.00, 52.41, 47.59, 4.81 +-1.05, 0.00, 52.41, 47.59, 4.82 +-1.05, 0.00, 52.41, 47.59, 4.83 +-1.05, 0.00, 52.42, 47.58, 4.83 +-1.05, 0.00, 52.42, 47.58, 4.84 +-1.05, 0.00, 52.43, 47.57, 4.85 +-1.05, 0.00, 52.43, 47.57, 4.86 +-1.05, 0.00, 52.43, 47.57, 4.87 +-1.05, 0.00, 52.44, 47.56, 4.87 +-1.05, 0.00, 52.44, 47.56, 4.88 +-1.05, 0.00, 52.44, 47.56, 4.89 +-1.05, 0.00, 52.45, 47.55, 4.90 +-1.05, 0.00, 52.45, 47.55, 4.91 +-0.99, 0.00, 49.94, 50.06, -0.13 +-0.99, 0.00, 52.41, 47.59, 4.82 +-0.99, 0.00, 52.41, 47.59, 4.83 +-0.99, 0.00, 52.42, 47.58, 4.84 +-0.99, 0.00, 52.42, 47.58, 4.84 +-0.92, 0.00, 49.90, 50.10, -0.19 +-0.92, 0.00, 52.38, 47.62, 4.76 +-0.92, 0.00, 52.38, 47.62, 4.77 +-0.92, 0.00, 52.39, 47.61, 4.77 +-0.92, 0.00, 52.39, 47.61, 4.78 +-0.79, 0.00, 47.35, 52.65, -5.30 +-0.79, 0.00, 52.30, 47.70, 4.59 diff --git a/simulink/BicopLibrary.slx b/simulink/BicopLibrary.slx new file mode 100644 index 00000000..6ce12028 Binary files /dev/null and b/simulink/BicopLibrary.slx differ diff --git a/simulink/BicopLibrary.slx.r2021a b/simulink/BicopLibrary.slx.r2021a new file mode 100644 index 00000000..890e0a42 Binary files /dev/null and b/simulink/BicopLibrary.slx.r2021a differ diff --git a/simulink/assets/BiCop.svg b/simulink/assets/BiCop.svg new file mode 100644 index 00000000..2427cd8b --- /dev/null +++ b/simulink/assets/BiCop.svg @@ -0,0 +1,137 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + y(k) + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/simulink/assets/Fan_u1.svg b/simulink/assets/Fan_u1.svg new file mode 100644 index 00000000..361a88aa --- /dev/null +++ b/simulink/assets/Fan_u1.svg @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/simulink/assets/Fan_u2.svg b/simulink/assets/Fan_u2.svg new file mode 100644 index 00000000..317143bd --- /dev/null +++ b/simulink/assets/Fan_u2.svg @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/simulink/examples/BicopShield/BicopShield_EMPC.slx b/simulink/examples/BicopShield/BicopShield_EMPC.slx new file mode 100644 index 00000000..ad3a8224 Binary files /dev/null and b/simulink/examples/BicopShield/BicopShield_EMPC.slx differ diff --git a/simulink/examples/BicopShield/BicopShield_EMPC/ectrl.c b/simulink/examples/BicopShield/BicopShield_EMPC/ectrl.c new file mode 100644 index 00000000..af819ad5 --- /dev/null +++ b/simulink/examples/BicopShield/BicopShield_EMPC/ectrl.c @@ -0,0 +1,1223 @@ +/* The function for evaluation of a piecewise affine control law associated + to a given state X using sequential search. + + Usage: + unsigned long region = ectrl( double *X, double *U) + + + where X is a vector of dimension MPT_DOMAIN and U is a vector of dimension + MPT_RANGE for PWA functions ( 1 for PWQ functions). The output variable "region" + indicates index of a region where the point X is located. If "region" index is + smaller than 1 (region < 1), there is no control law associated to + a given state. + + Please note that all code in this file is provided under the terms of the + GNU General Public License, which implies that if you include it directly + into your commercial application, you will need to comply with the license. + If you feel this is not a good solution for you or your company, feel free + to contact the author: + michal.kvasnica@stuba.sk + to re-license this specific piece of code to you free of charge. +*/ + +/* Copyright (C) 2005 by Michal Kvasnica (michal.kvasnica@stuba.sk) + Revised in 2012-2013 by Martin Herceg (herceg@control.ee.ethz.ch) +*/ + + +/* This program is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 2 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program; if not, write to the Free Software + Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. +*/ + +/* Generated on 15-May-2024 09:17:31 by MPT @version@ */ + +#include + +#define MPT_NR 83 +#define MPT_DOMAIN 3 +#define MPT_RANGE 6 +#define MPT_ABSTOL 1.000000e-08 + +static double MPT_A[] = { +1.39011071953583e-02, -9.52786860645844e-01, -3.03321541271604e-01, 1.36845953591262e-02, -9.51615985474686e-01, +-3.06984931289630e-01, 1.34620629720490e-02, -9.50368014508472e-01, -3.10836628890099e-01, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.34620629720490e-02, 9.50368014508472e-01, 3.10836628890099e-01, -1.36845953591262e-02, 9.51615985474686e-01, +3.06984931289630e-01, -1.39011071953583e-02, 9.52786860645844e-01, 3.03321541271604e-01, 1.36914789662114e-02, +-9.51653411698841e-01, -3.06868583282279e-01, 1.34762006584533e-02, -9.50446756726095e-01, -3.10595161978836e-01, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, -1.34762006584533e-02, 9.50446756726095e-01, 3.10595161978836e-01, 1.39011071953583e-02, +-9.52786860645844e-01, -3.03321541271603e-01, -1.39011071953583e-02, 9.52786860645844e-01, 3.03321541271603e-01, +1.38947430621097e-02, -9.52752629870511e-01, -3.03429336732728e-01, 1.34687765654363e-02, -9.50405874969839e-01, +-3.10720557544308e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.36845953591262e-02, +9.51615985474686e-01, 3.06984931289630e-01, 1.38890444880915e-02, -9.52721135578969e-01, -3.03528470269804e-01, +1.36783995462763e-02, -9.51581433870825e-01, -3.07092292476052e-01, -1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.34620629720490e-02, +-9.50368014508472e-01, -3.10836628890099e-01, -1.38890444880915e-02, 9.52721135578969e-01, 3.03528470269804e-01, +-1.34620629720490e-02, 9.50368014508472e-01, 3.10836628890099e-01, 1.34620629720490e-02, -9.50368014508472e-01, +-3.10836628890099e-01, -1.34620629720490e-02, 9.50368014508472e-01, 3.10836628890099e-01, 1.38890444880915e-02, +-9.52721135578969e-01, -3.03528470269804e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.36783995462763e-02, 9.51581433870825e-01, +3.07092292476053e-01, -1.38890444880915e-02, 9.52721135578969e-01, 3.03528470269804e-01, 1.36845953591262e-02, +-9.51615985474686e-01, -3.06984931289630e-01, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.34687765654363e-02, 9.50405874969839e-01, 3.10720557544308e-01, -1.38947430621097e-02, 9.52752629870511e-01, +3.03429336732728e-01, 1.39011071953583e-02, -9.52786860645844e-01, -3.03321541271604e-01, -1.39011071953583e-02, +9.52786860645844e-01, 3.03321541271603e-01, 1.34762006584533e-02, -9.50446756726095e-01, -3.10595161978837e-01, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, -1.34762006584533e-02, 9.50446756726095e-01, 3.10595161978837e-01, -1.36914789662114e-02, +9.51653411698841e-01, 3.06868583282279e-01, 1.34829029666019e-02, -9.50484526769832e-01, -3.10479267743793e-01, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.38947430621097e-02, -9.52752629870511e-01, -3.03429336732728e-01, -1.38947430621097e-02, +9.52752629870511e-01, 3.03429336732728e-01, -1.36914789662114e-02, 9.51653411698841e-01, 3.06868583282279e-01, +1.36852883663621e-02, -9.51618900926333e-01, -3.06975862702734e-01, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, -1.38890444880915e-02, 9.52721135578969e-01, 3.03528470269804e-01, -1.34762006584533e-02, +9.50446756726095e-01, 3.10595161978836e-01, 1.34762006584533e-02, -9.50446756726095e-01, -3.10595161978837e-01, +-1.34762006584533e-02, 9.50446756726095e-01, 3.10595161978836e-01, -1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.38890444880915e-02, +-9.52721135578969e-01, -3.03528470269804e-01, -1.38890444880915e-02, 9.52721135578969e-01, 3.03528470269804e-01, +-1.39011071953583e-02, 9.52786860645844e-01, 3.03321541271603e-01, 1.36959864362163e-02, -9.51677911725442e-01, +-3.06792392815469e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.34854517484242e-02, 9.50498251563104e-01, 3.10437137544180e-01, +1.38826707101136e-02, -9.52686830934095e-01, -3.03636416819038e-01, -1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.34687765654363e-02, +-9.50405874969839e-01, -3.10720557544308e-01, -1.36783995462763e-02, 9.51581433870825e-01, 3.07092292476052e-01, +-1.34687765654363e-02, 9.50405874969839e-01, 3.10720557544308e-01, -1.34620629720490e-02, 9.50368014508472e-01, +3.10836628890099e-01, 1.36743370888768e-02, -9.51558773087091e-01, -3.07162683062527e-01, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.38811302798941e-02, 9.52677991564369e-01, 3.03664220169307e-01, 1.38890444880915e-02, -9.52721135578969e-01, +-3.03528470269804e-01, -1.38890444880915e-02, 9.52721135578969e-01, 3.03528470269804e-01, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.34762006584533e-02, -9.50446756726095e-01, -3.10595161978836e-01, -1.34762006584533e-02, 9.50446756726095e-01, +3.10595161978837e-01, 1.38811302798941e-02, -9.52677991564369e-01, -3.03664220169307e-01, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.36743370888768e-02, 9.51558773087091e-01, 3.07162683062527e-01, 1.34620629720490e-02, -9.50368014508472e-01, +-3.10836628890099e-01, 1.34687765654363e-02, -9.50405874969839e-01, -3.10720557544308e-01, 1.36783995462763e-02, +-9.51581433870825e-01, -3.07092292476053e-01, -1.34687765654363e-02, 9.50405874969839e-01, 3.10720557544308e-01, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, -1.38826707101136e-02, 9.52686830934095e-01, 3.03636416819039e-01, 1.34762006584533e-02, +-9.50446756726095e-01, -3.10595161978837e-01, 1.38890444880915e-02, -9.52721135578969e-01, -3.03528470269804e-01, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.36852883663621e-02, 9.51618900926333e-01, +3.06975862702734e-01, 1.36914789662114e-02, -9.51653411698841e-01, -3.06868583282279e-01, 1.38947430621097e-02, +-9.52752629870511e-01, -3.03429336732728e-01, -1.38947430621097e-02, 9.52752629870511e-01, 3.03429336732728e-01, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, -1.34829029666019e-02, 9.50484526769832e-01, 3.10479267743793e-01, 1.34854517484242e-02, +-9.50498251563104e-01, -3.10437137544180e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.36959864362163e-02, 9.51677911725442e-01, +3.06792392815469e-01, 1.39011071953583e-02, -9.52786860645844e-01, -3.03321541271603e-01, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.34829029666019e-02, -9.50484526769832e-01, -3.10479267743793e-01, 1.36852883663621e-02, -9.51618900926333e-01, +-3.06975862702734e-01, 1.38826707101136e-02, -9.52686830934095e-01, -3.03636416819038e-01, -1.38826707101136e-02, +9.52686830934095e-01, 3.03636416819039e-01, -1.36852883663621e-02, 9.51618900926333e-01, 3.06975862702734e-01, +-1.34829029666019e-02, 9.50484526769832e-01, 3.10479267743793e-01, -1.38947430621097e-02, 9.52752629870511e-01, +3.03429336732728e-01, 1.34921466764067e-02, -9.50535962512441e-01, -3.10321359156294e-01, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.34921466764067e-02, 9.50535962512441e-01, 3.10321359156294e-01, 1.36959864362163e-02, -9.51677911725442e-01, +-3.06792392815469e-01, -1.36959864362163e-02, 9.51677911725442e-01, 3.06792392815469e-01, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.36812293279368e-02, 9.51596266929507e-01, 3.07046199666927e-01, 1.38811302798941e-02, -9.52677991564369e-01, +-3.03664220169306e-01, 1.34762006584533e-02, -9.50446756726095e-01, -3.10595161978837e-01, -1.38811302798941e-02, +9.52677991564369e-01, 3.03664220169307e-01, 1.34854517484242e-02, -9.50498251563104e-01, -3.10437137544180e-01, +-1.38890444880915e-02, 9.52721135578969e-01, 3.03528470269804e-01, -1.34854517484242e-02, 9.50498251563104e-01, +3.10437137544180e-01, 1.36897992488730e-02, -9.51643427673875e-01, -3.06899618705603e-01, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.34687765654363e-02, 9.50405874969839e-01, 3.10720557544308e-01, 1.38747501706511e-02, -9.52643638401686e-01, +-3.03772265884328e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.36743370888768e-02, -9.51558773087091e-01, -3.07162683062527e-01, +-1.38747501706511e-02, 9.52643638401686e-01, 3.03772265884328e-01, -1.36743370888768e-02, 9.51558773087090e-01, +3.07162683062527e-01, -1.34762006584533e-02, 9.50446756726095e-01, 3.10595161978837e-01, 1.38811302798941e-02, +-9.52677991564369e-01, -3.03664220169307e-01, -1.38811302798941e-02, 9.52677991564369e-01, 3.03664220169307e-01, +1.36812293279368e-02, -9.51596266929507e-01, -3.07046199666927e-01, -1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.34854517484242e-02, -9.50498251563104e-01, -3.10437137544180e-01, -1.36897992488730e-02, 9.51643427673875e-01, +3.06899618705603e-01, 1.38890444880915e-02, -9.52721135578969e-01, -3.03528470269804e-01, -1.34854517484242e-02, +9.50498251563104e-01, 3.10437137544180e-01, 1.36743370888768e-02, -9.51558773087090e-01, -3.07162683062527e-01, +-1.36743370888768e-02, 9.51558773087091e-01, 3.07162683062527e-01, 1.38747501706511e-02, -9.52643638401686e-01, +-3.03772265884328e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.38747501706511e-02, 9.52643638401686e-01, 3.03772265884328e-01, +1.34687765654363e-02, -9.50405874969839e-01, -3.10720557544308e-01, 1.34829029666019e-02, -9.50484526769832e-01, +-3.10479267743793e-01, 1.36852883663621e-02, -9.51618900926333e-01, -3.06975862702734e-01, 1.38826707101136e-02, +-9.52686830934095e-01, -3.03636416819039e-01, -1.38826707101136e-02, 9.52686830934095e-01, 3.03636416819038e-01, +-1.36852883663621e-02, 9.51618900926333e-01, 3.06975862702734e-01, -1.34829029666019e-02, 9.50484526769832e-01, +3.10479267743793e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.36959864362163e-02, -9.51677911725442e-01, -3.06792392815469e-01, +-1.36959864362163e-02, 9.51677911725442e-01, 3.06792392815469e-01, 1.34921466764067e-02, -9.50535962512441e-01, +-3.10321359156294e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.34921466764067e-02, 9.50535962512441e-01, 3.10321359156294e-01, +1.38947430621097e-02, -9.52752629870511e-01, -3.03429336732728e-01, -1.34829029666019e-02, 9.50484526769832e-01, +3.10479267743793e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.36812293279368e-02, -9.51596266929507e-01, -3.07046199666927e-01, +1.38747501706511e-02, -9.52643638401686e-01, -3.03772265884328e-01, -1.38747501706511e-02, 9.52643638401686e-01, +3.03772265884328e-01, -1.36852883663621e-02, 9.51618900926333e-01, 3.06975862702734e-01, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.34872916702401e-02, -9.50509251715091e-01, -3.10403375251331e-01, +1.38784916071139e-02, -9.52664332231616e-01, -3.03707190504934e-01, -1.38826707101136e-02, 9.52686830934095e-01, +3.03636416819038e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.34921466764067e-02, -9.50535962512441e-01, -3.10321359156294e-01, +1.36897992488730e-02, -9.51643427673875e-01, -3.06899618705603e-01, -1.34921466764067e-02, 9.50535962512441e-01, +3.10321359156294e-01, 1.34921466764067e-02, -9.50535962512441e-01, -3.10321359156294e-01, -1.34921466764067e-02, +9.50535962512441e-01, 3.10321359156294e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.36897992488730e-02, -9.51643427673875e-01, +-3.06899618705603e-01, -1.36897992488730e-02, 9.51643427673875e-01, 3.06899618705603e-01, -1.36959864362163e-02, +9.51677911725442e-01, 3.06792392815469e-01, 1.34965305488427e-02, -9.50560648784693e-01, -3.10245542506524e-01, +7.07106781186548e-01, -7.07106781186548e-01, 0.00000000000000e+00, 4.47211344158600e-01, -8.94417189382936e-01, +-4.46150111368878e-03, 3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, -1.34965305488427e-02, 9.50560648784693e-01, +3.10245542506524e-01, 1.36812293279368e-02, -9.51596266929507e-01, -3.07046199666927e-01, -1.36812293279368e-02, +9.51596266929507e-01, 3.07046199666927e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.38747501706511e-02, -9.52643638401686e-01, +-3.03772265884328e-01, -1.38747501706511e-02, 9.52643638401686e-01, 3.03772265884328e-01, -1.38811302798941e-02, +9.52677991564369e-01, 3.03664220169307e-01, 1.36857424485574e-02, -9.51620811206989e-01, -3.06969920564513e-01, +7.07106781186547e-01, -7.07106781186547e-01, 0.00000000000000e+00, 4.47211344158600e-01, -8.94417189382936e-01, +-4.46150111368879e-03, 3.16299652174141e-01, -9.48613138917365e-01, -9.36176841528263e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, -1.36857424485574e-02, 9.51620811206989e-01, +3.06969920564513e-01, 1.34854517484242e-02, -9.50498251563103e-01, -3.10437137544180e-01, -1.36743370888768e-02, +9.51558773087090e-01, 3.07162683062527e-01, 1.38705669152212e-02, -9.52621107869393e-01, -3.03843104603578e-01, +-7.07106781186547e-01, 7.07106781186547e-01, 0.00000000000000e+00, -4.47370016461584e-01, 8.94338466826250e-01, +4.33302735207592e-03, -3.16551250726381e-01, 9.48531836741517e-01, 9.09177382741911e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.38705669152212e-02, 9.52621107869393e-01, +3.03843104603578e-01, 1.38747501706511e-02, -9.52643638401686e-01, -3.03772265884328e-01, -1.38747501706511e-02, +9.52643638401686e-01, 3.03772265884328e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.36812293279368e-02, -9.51596266929507e-01, +-3.07046199666927e-01, -1.36812293279368e-02, 9.51596266929507e-01, 3.07046199666927e-01, -1.34854517484242e-02, +9.50498251563103e-01, 3.10437137544180e-01, 1.36857424485574e-02, -9.51620811206989e-01, -3.06969920564513e-01, +-7.07106781186548e-01, 7.07106781186548e-01, 0.00000000000000e+00, -4.47211344158600e-01, 8.94417189382936e-01, +4.46150111368878e-03, -3.16299652174141e-01, 9.48613138917365e-01, 9.36176841528262e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.36857424485574e-02, 9.51620811206989e-01, +3.06969920564513e-01, 1.38811302798941e-02, -9.52677991564369e-01, -3.03664220169307e-01, 1.36897992488730e-02, +-9.51643427673875e-01, -3.06899618705603e-01, -1.36897992488730e-02, 9.51643427673875e-01, 3.06899618705603e-01, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.34921466764067e-02, -9.50535962512441e-01, -3.10321359156294e-01, -1.34921466764067e-02, +9.50535962512441e-01, 3.10321359156294e-01, 1.38705669152212e-02, -9.52621107869393e-01, -3.03843104603578e-01, +7.07106781186547e-01, -7.07106781186547e-01, 0.00000000000000e+00, 4.47370016461584e-01, -8.94338466826250e-01, +-4.33302735207592e-03, 3.16551250726381e-01, -9.48531836741517e-01, -9.09177382741911e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, -1.38705669152212e-02, 9.52621107869393e-01, +3.03843104603578e-01, 1.36743370888768e-02, -9.51558773087091e-01, -3.07162683062527e-01, 1.38747501706511e-02, +-9.52643638401686e-01, -3.03772265884328e-01, -1.38747501706511e-02, 9.52643638401686e-01, 3.03772265884328e-01, +-1.36812293279368e-02, 9.51596266929507e-01, 3.07046199666927e-01, -1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.34829029666019e-02, +-9.50484526769832e-01, -3.10479267743793e-01, 1.34921466764067e-02, -9.50535962512441e-01, -3.10321359156294e-01, +-1.36897992488730e-02, 9.51643427673875e-01, 3.06899618705603e-01, -1.34921466764067e-02, 9.50535962512441e-01, +3.10321359156294e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.38826707101136e-02, -9.52686830934095e-01, -3.03636416819038e-01, +-1.38784916071139e-02, 9.52664332231616e-01, 3.03707190504934e-01, -1.34872916702401e-02, 9.50509251715091e-01, +3.10403375251332e-01, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.36852883663621e-02, +-9.51618900926333e-01, -3.06975862702734e-01, 1.34965305488428e-02, -9.50560648784693e-01, -3.10245542506524e-01, +-7.07106781186548e-01, 7.07106781186548e-01, 0.00000000000000e+00, -4.47211344158600e-01, 8.94417189382936e-01, +4.46150111368878e-03, -3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.34965305488428e-02, 9.50560648784693e-01, +3.10245542506524e-01, 1.36959864362163e-02, -9.51677911725442e-01, -3.06792392815469e-01, -1.34872916702401e-02, +9.50509251715091e-01, 3.10403375251331e-01, -1.36812293279368e-02, 9.51596266929507e-01, 3.07046199666927e-01, +-7.07106781186548e-01, 7.07106781186548e-01, 0.00000000000000e+00, -4.47276405074511e-01, 8.94384916983822e-01, +4.40882472583738e-03, -3.16355458438552e-01, 9.48595111193299e-01, 9.30263061214179e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.38705669152212e-02, -9.52621107869393e-01, +-3.03843104603578e-01, -1.38705669152212e-02, 9.52621107869393e-01, 3.03843104603578e-01, -1.34921466764067e-02, +9.50535962512441e-01, 3.10321359156294e-01, -1.38747501706511e-02, 9.52643638401686e-01, 3.03772265884328e-01, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.36857424485574e-02, -9.51620811206989e-01, +-3.06969920564513e-01, -1.36897992488730e-02, 9.51643427673875e-01, 3.06899618705603e-01, -1.38784916071139e-02, +9.52664332231616e-01, 3.03707190504934e-01, 7.07106781186547e-01, -7.07106781186547e-01, 0.00000000000000e+00, +4.47211344158600e-01, -8.94417189382936e-01, -4.46150111368878e-03, 3.16219473520630e-01, -9.48639003953550e-01, +-9.44906050104055e-03, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +1.34965305488428e-02, -9.50560648784693e-01, -3.10245542506524e-01, -1.34965305488428e-02, 9.50560648784693e-01, +3.10245542506524e-01, 7.07106781186547e-01, -7.07106781186547e-01, 0.00000000000000e+00, 4.47211344158600e-01, +-8.94417189382936e-01, -4.46150111368879e-03, 3.16252292715041e-01, -9.48628418595272e-01, -9.41333022436286e-03, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 1.36857424485574e-02, +-9.51620811206989e-01, -3.06969920564513e-01, 1.34921466764067e-02, -9.50535962512441e-01, -3.10321359156294e-01, +-1.36857424485574e-02, 9.51620811206989e-01, 3.06969920564513e-01, 1.34965305488428e-02, -9.50560648784693e-01, +-3.10245542506524e-01, -1.36897992488730e-02, 9.51643427673875e-01, 3.06899618705603e-01, -1.34965305488428e-02, +9.50560648784693e-01, 3.10245542506524e-01, 7.07106781186548e-01, -7.07106781186548e-01, 0.00000000000000e+00, +4.47211344158600e-01, -8.94417189382936e-01, -4.46150111368878e-03, 3.16219473520630e-01, -9.48639003953550e-01, +-9.44906050104055e-03, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +7.07106781186548e-01, -7.07106781186548e-01, 0.00000000000000e+00, 4.47276405074511e-01, -8.94384916983823e-01, +-4.40882472583738e-03, 3.16355458438552e-01, -9.48595111193299e-01, -9.30263061214179e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 1.38705669152212e-02, -9.52621107869393e-01, +-3.03843104603578e-01, 1.36812293279368e-02, -9.51596266929507e-01, -3.07046199666927e-01, -1.38705669152212e-02, +9.52621107869393e-01, 3.03843104603578e-01, 1.36857424485574e-02, -9.51620811206989e-01, -3.06969920564513e-01, +-1.38747501706511e-02, 9.52643638401686e-01, 3.03772265884328e-01, -1.36857424485574e-02, 9.51620811206989e-01, +3.06969920564513e-01, 7.07106781186547e-01, -7.07106781186547e-01, 0.00000000000000e+00, 4.47211344158600e-01, +-8.94417189382936e-01, -4.46150111368879e-03, 3.16252292715041e-01, -9.48628418595273e-01, -9.41333022436287e-03, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 3.16219473520630e-01, +-9.48639003953550e-01, -9.44906050104055e-03, 4.47211344158600e-01, -8.94417189382936e-01, -4.46150111368878e-03, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, -3.16219473520630e-01, 9.48639003953550e-01, +9.44906050104055e-03, -3.16299652174141e-01, 9.48613138917365e-01, 9.36176841528263e-03, 4.47211344158600e-01, +-8.94417189382936e-01, -4.46150111368879e-03, -7.07106781186548e-01, 7.07106781186548e-01, 0.00000000000000e+00, +5.14654323573967e-01, -8.57396054959857e-01, -1.71235682536255e-03, 0.00000000000000e+00, 0.00000000000000e+00, +-1.00000000000000e+00, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368879e-03, 4.47370016461584e-01, +-8.94338466826250e-01, -4.33302735207592e-03, 3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, +-5.14654323573967e-01, 8.57396054959857e-01, 1.71235682536255e-03, 0.00000000000000e+00, 0.00000000000000e+00, +-1.00000000000000e+00, -3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, 3.16551250726381e-01, +-9.48531836741517e-01, -9.09177382741911e-03, -1.36812293279368e-02, 9.51596266929507e-01, 3.07046199666927e-01, +1.38705669152212e-02, -9.52621107869393e-01, -3.03843104603578e-01, -1.38705669152212e-02, 9.52621107869393e-01, +3.03843104603578e-01, -7.07106781186548e-01, 7.07106781186548e-01, 0.00000000000000e+00, -4.47276405074511e-01, +8.94384916983823e-01, 4.40882472583738e-03, -3.16355458438552e-01, 9.48595111193299e-01, 9.30263061214179e-03, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -7.07106781186548e-01, +7.07106781186548e-01, 0.00000000000000e+00, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, +-3.16252292715041e-01, 9.48628418595272e-01, 9.41333022436287e-03, -1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.36857424485574e-02, -9.51620811206989e-01, -3.06969920564513e-01, +1.38747501706511e-02, -9.52643638401686e-01, -3.03772265884328e-01, -1.36857424485574e-02, 9.51620811206989e-01, +3.06969920564513e-01, 3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, -4.47211344158600e-01, +8.94417189382936e-01, 4.46150111368878e-03, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, +-3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, 3.16299652174141e-01, -9.48613138917365e-01, +-9.36176841528263e-03, -1.34921466764067e-02, 9.50535962512441e-01, 3.10321359156294e-01, 1.36857424485574e-02, +-9.51620811206989e-01, -3.06969920564513e-01, -1.36857424485574e-02, 9.51620811206989e-01, 3.06969920564513e-01, +-7.07106781186548e-01, 7.07106781186548e-01, 0.00000000000000e+00, -4.47211344158600e-01, 8.94417189382936e-01, +4.46150111368878e-03, -3.16252292715041e-01, 9.48628418595272e-01, 9.41333022436287e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, +1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -7.07106781186548e-01, 7.07106781186548e-01, +0.00000000000000e+00, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, -3.16219473520630e-01, +9.48639003953550e-01, 9.44906050104055e-03, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.34965305488428e-02, -9.50560648784693e-01, -3.10245542506524e-01, 1.36897992488730e-02, +-9.51643427673875e-01, -3.06899618705603e-01, -1.34965305488428e-02, 9.50560648784693e-01, 3.10245542506524e-01, +4.47211344158600e-01, -8.94417189382936e-01, -4.46150111368879e-03, 7.07106781186548e-01, -7.07106781186548e-01, +0.00000000000000e+00, -5.14654323573967e-01, 8.57396054959856e-01, 1.71235682536255e-03, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, +-4.47370016461584e-01, 8.94338466826250e-01, 4.33302735207592e-03, 3.16219473520630e-01, -9.48639003953550e-01, +-9.44906050104055e-03, 5.14654323573967e-01, -8.57396054959856e-01, -1.71235682536255e-03, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, -3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, +-3.16551250726381e-01, 9.48531836741517e-01, 9.09177382741911e-03, 1.38705669152212e-02, -9.52621107869393e-01, +-3.03843104603578e-01, -1.38705669152212e-02, 9.52621107869393e-01, 3.03843104603578e-01, 7.07106781186548e-01, +-7.07106781186548e-01, 0.00000000000000e+00, 4.47276405074511e-01, -8.94384916983822e-01, -4.40882472583738e-03, +3.16355458438552e-01, -9.48595111193299e-01, -9.30263061214179e-03, -1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, 1.36812293279368e-02, -9.51596266929507e-01, -3.07046199666927e-01, +1.34872916702401e-02, -9.50509251715091e-01, -3.10403375251331e-01, -1.36857424485574e-02, 9.51620811206989e-01, +3.06969920564513e-01, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.38747501706511e-02, +-9.52643638401686e-01, -3.03772265884328e-01, 1.34921466764067e-02, -9.50535962512441e-01, -3.10321359156294e-01, +1.34965305488428e-02, -9.50560648784693e-01, -3.10245542506524e-01, -1.34965305488428e-02, 9.50560648784693e-01, +3.10245542506524e-01, -7.07106781186547e-01, 7.07106781186547e-01, 0.00000000000000e+00, -4.47211344158600e-01, +8.94417189382936e-01, 4.46150111368879e-03, -3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.38784916071139e-02, +-9.52664332231616e-01, -3.03707190504934e-01, 1.36897992488730e-02, -9.51643427673875e-01, -3.06899618705603e-01, +-7.07106781186547e-01, 7.07106781186547e-01, 0.00000000000000e+00, 5.14654323573967e-01, -8.57396054959857e-01, +-1.71235682536255e-03, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, 4.47211344158600e-01, +-8.94417189382936e-01, -4.46150111368878e-03, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368879e-03, +4.47276405074511e-01, -8.94384916983822e-01, -4.40882472583738e-03, -5.14654323573967e-01, 8.57396054959857e-01, +1.71235682536255e-03, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, 3.16219473520630e-01, +-9.48639003953550e-01, -9.44906050104055e-03, -3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, +3.16355458438552e-01, -9.48595111193299e-01, -9.30263061214179e-03, -1.34965305488428e-02, 9.50560648784693e-01, +3.10245542506524e-01, -1.36857424485574e-02, 9.51620811206989e-01, 3.06969920564513e-01, -1.38705669152212e-02, +9.52621107869393e-01, 3.03843104603578e-01, -7.07106781186548e-01, 7.07106781186548e-01, 0.00000000000000e+00, +-4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, -3.16219473520630e-01, 9.48639003953550e-01, +9.44906050104055e-03, 7.07106781186548e-01, -7.07106781186548e-01, 0.00000000000000e+00, 4.47211344158600e-01, +-8.94417189382936e-01, -4.46150111368878e-03, 3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, 4.47211344158600e-01, -8.94417189382936e-01, -4.46150111368878e-03, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 3.16219473520630e-01, -9.48639003953550e-01, +-9.44906050104055e-03, -3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, -3.16252292715041e-01, +9.48628418595272e-01, 9.41333022436287e-03, -1.36857424485574e-02, 9.51620811206989e-01, 3.06969920564513e-01, +7.07106781186548e-01, -7.07106781186548e-01, 0.00000000000000e+00, 4.47211344158600e-01, -8.94417189382936e-01, +-4.46150111368878e-03, 3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, -1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, 1.34965305488428e-02, -9.50560648784693e-01, +-3.10245542506524e-01, 7.07106781186548e-01, -7.07106781186548e-01, 0.00000000000000e+00, -5.14654323573967e-01, +8.57396054959857e-01, 1.71235682536255e-03, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +4.47211344158600e-01, -8.94417189382936e-01, -4.46150111368878e-03, -4.47211344158600e-01, 8.94417189382936e-01, +4.46150111368879e-03, -4.47276405074511e-01, 8.94384916983823e-01, 4.40882472583738e-03, 5.14654323573967e-01, +-8.57396054959856e-01, -1.71235682536255e-03, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, -3.16219473520630e-01, 9.48639003953550e-01, +9.44906050104055e-03, -3.16355458438552e-01, 9.48595111193299e-01, 9.30263061214179e-03, -1.38705669152212e-02, +9.52621107869393e-01, 3.03843104603578e-01, 7.07106781186548e-01, -7.07106781186548e-01, 0.00000000000000e+00, +4.47211344158600e-01, -8.94417189382936e-01, -4.46150111368878e-03, 3.16219473520630e-01, -9.48639003953550e-01, +-9.44906050104055e-03, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +1.36857424485574e-02, -9.51620811206989e-01, -3.06969920564513e-01, 3.16219473520630e-01, -9.48639003953550e-01, +-9.44906050104055e-03, -3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, 4.47211344158600e-01, +-8.94417189382936e-01, -4.46150111368878e-03, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, +-3.16252292715041e-01, 9.48628418595272e-01, 9.41333022436287e-03, 4.47211344158600e-01, -8.94417189382936e-01, +-4.46150111368879e-03, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, -7.07106781186548e-01, +7.07106781186548e-01, 0.00000000000000e+00, 5.14654323573967e-01, -8.57396054959857e-01, -1.71235682536255e-03, +0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, 4.47276405074511e-01, -8.94384916983822e-01, +-4.40882472583738e-03, 3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, -3.16219473520630e-01, +9.48639003953550e-01, 9.44906050104055e-03, -5.14654323573967e-01, 8.57396054959857e-01, 1.71235682536255e-03, +0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, 3.16355458438552e-01, -9.48595111193299e-01, +-9.30263061214179e-03, -1.36857424485574e-02, 9.51620811206989e-01, 3.06969920564513e-01, -7.07106781186548e-01, +7.07106781186548e-01, 0.00000000000000e+00, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, +-3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, -1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, 1.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.38705669152212e-02, -9.52621107869393e-01, -3.03843104603578e-01, +-4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, 0.00000000000000e+00, 0.00000000000000e+00, +-1.00000000000000e+00, 3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, -3.16219473520630e-01, +9.48639003953550e-01, 9.44906050104055e-03, 3.16252292715041e-01, -9.48628418595272e-01, -9.41333022436287e-03, +3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, -3.16219473520630e-01, 9.48639003953550e-01, +9.44906050104055e-03, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, 0.00000000000000e+00, +0.00000000000000e+00, -1.00000000000000e+00, 3.16252292715041e-01, -9.48628418595272e-01, -9.41333022436287e-03, +-1.34965305488428e-02, 9.50560648784693e-01, 3.10245542506524e-01, -7.07106781186548e-01, 7.07106781186548e-01, +0.00000000000000e+00, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, -3.16219473520630e-01, +9.48639003953550e-01, 9.44906050104055e-03, -1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.36857424485574e-02, -9.51620811206989e-01, -3.06969920564513e-01, 4.47211344158600e-01, +-8.94417189382936e-01, -4.46150111368879e-03, -4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, +7.07106781186547e-01, -7.07106781186547e-01, 0.00000000000000e+00, -5.14654323573967e-01, 8.57396054959857e-01, +1.71235682536255e-03, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, -4.47276405074511e-01, +8.94384916983822e-01, 4.40882472583738e-03, 3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, +-3.16219473520630e-01, 9.48639003953550e-01, 9.44906050104055e-03, 5.14654323573967e-01, -8.57396054959857e-01, +-1.71235682536255e-03, 0.00000000000000e+00, 0.00000000000000e+00, 1.00000000000000e+00, -3.16355458438552e-01, +9.48595111193299e-01, 9.30263061214179e-03, -7.07106781186548e-01, 7.07106781186548e-01, 0.00000000000000e+00, +-4.47211344158600e-01, 8.94417189382936e-01, 4.46150111368878e-03, -3.16219473520630e-01, 9.48639003953550e-01, +9.44906050104055e-03, 7.07106781186548e-01, -7.07106781186548e-01, 0.00000000000000e+00, 4.47211344158600e-01, +-8.94417189382936e-01, -4.46150111368878e-03, 3.16219473520630e-01, -9.48639003953550e-01, -9.44906050104055e-03, +-1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-1.00000000000000e+00, 1.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 1.00000000000000e+00, 1.38705669152212e-02, -9.52621107869393e-01, -3.03843104603578e-01, +1.36857424485574e-02, -9.51620811206989e-01, -3.06969920564513e-01, 1.34965305488428e-02, -9.50560648784693e-01, +-3.10245542506524e-01 }; + +static double MPT_B[] = { +5.51053795091707e-01, 5.73058648838128e-01, 5.96464393563851e-01, 1.00000000000000e+04, 1.00000000000000e+04, +5.96464393563851e-01, 5.73058648838128e-01, 5.51053795091707e-01, 5.72359492129188e-01, 5.95004060257397e-01, +1.00000000000000e+04, 1.00000000000000e+04, 5.59547926552810e-01, 6.76683044029523e-01, -5.51053795091707e-01, +5.51701020044155e-01, 5.95758748044284e-01, 1.00000000000000e+04, -5.73058648838128e-01, 5.52303110681947e-01, +5.73710766561065e-01, 1.00000000000000e+04, 1.00000000000000e+04, 7.32892313228285e-01, 5.19495902946219e-01, +-5.96464393563851e-01, -5.96464393563851e-01, 7.32892313228285e-01, 5.19495902946219e-01, 1.00000000000000e+04, +1.00000000000000e+04, 5.73710766561065e-01, 5.52303110681947e-01, -5.73058648838128e-01, 1.00000000000000e+04, +5.95758748044284e-01, 5.51701020044155e-01, -5.51053795091706e-01, 6.76683044029523e-01, 5.59547926552810e-01, +1.00000000000000e+04, 1.00000000000000e+04, 5.95004060257397e-01, 5.72359492129188e-01, 5.94299528719722e-01, +1.00000000000000e+04, 1.00000000000000e+04, 6.73514592062113e-01, -5.51701020044155e-01, -5.72359492129188e-01, +5.73011098026456e-01, 1.00000000000000e+04, -5.52303110681947e-01, -5.95004060257397e-01, -5.59547926552810e-01, +6.91462809518060e-01, 1.00000000000000e+04, 1.00000000000000e+04, 6.41555431628426e-01, -5.19495902946219e-01, +-6.76683044029523e-01, 5.74601766027617e-01, 1.00000000000000e+04, 1.00000000000000e+04, 5.32657411734330e-01, +5.52951276820564e-01, 1.00000000000000e+04, 1.00000000000000e+04, 7.27954901562669e-01, -5.73710766561065e-01, +-5.95758748044284e-01, -7.32892313228285e-01, 5.76701467005299e-01, 1.00000000000000e+04, 1.00000000000000e+04, +4.96260926328146e-01, -5.19495902946219e-01, 6.41555431628426e-01, 1.00000000000000e+04, 1.00000000000000e+04, +6.91462809518059e-01, -5.59547926552810e-01, 4.96260926328146e-01, 1.00000000000000e+04, 1.00000000000000e+04, +5.76701467005298e-01, -7.32892313228285e-01, -5.95758748044284e-01, -5.73710766561065e-01, 7.27954901562669e-01, +1.00000000000000e+04, 1.00000000000000e+04, 5.52951276820564e-01, -5.95004060257397e-01, -5.52303110681947e-01, +1.00000000000000e+04, 5.73011098026456e-01, -5.72359492129188e-01, -5.51701020044155e-01, 6.73514592062113e-01, +1.00000000000000e+04, 1.00000000000000e+04, 5.94299528719722e-01, 5.32657411734330e-01, 1.00000000000000e+04, +1.00000000000000e+04, 5.74601766027617e-01, -6.76683044029523e-01, 1.00000000000000e+04, 1.00000000000000e+04, +7.21987822722998e-01, 6.95833692233899e-01, 6.71190978854678e-01, -5.52951276820564e-01, -5.73011098026456e-01, +-5.94299528719722e-01, -6.73514592062113e-01, 5.96076297407560e-01, 1.00000000000000e+04, 1.00000000000000e+04, +4.97463149951699e-01, 6.98377265724429e-01, -5.74601766027617e-01, 1.00000000000000e+04, 1.00000000000000e+04, +5.40956142651829e-01, 6.15978503659878e-01, -6.91462809518060e-01, -4.96260926328146e-01, -5.32657411734330e-01, +-6.41555431628426e-01, 6.61619003551662e-01, 5.42046656870749e-01, 1.00000000000000e+04, 1.00000000000000e+04, +-7.27954901562668e-01, 5.56303608685010e-01, 1.00000000000000e+04, 1.00000000000000e+04, 7.01344306307657e-01, +4.63142758763710e-01, -5.76701467005298e-01, -6.91462809518060e-01, -4.96260926328146e-01, 6.15978503659878e-01, +5.40956142651829e-01, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, +6.61619003551662e-01, 5.42046656870749e-01, -6.41555431628426e-01, -5.32657411734330e-01, -5.76701467005298e-01, +7.01344306307657e-01, 4.63142758763710e-01, 1.00000000000000e+04, 1.00000000000000e+04, 5.56303608685010e-01, +-7.27954901562669e-01, -5.94299528719722e-01, -5.73011098026456e-01, -5.52951276820564e-01, 6.71190978854678e-01, +6.95833692233899e-01, 7.21987822722998e-01, 1.00000000000000e+04, 1.00000000000000e+04, -5.74601766027617e-01, +6.98377265724429e-01, 4.97463149951699e-01, 1.00000000000000e+04, 1.00000000000000e+04, 5.96076297407560e-01, +-6.73514592062113e-01, -7.21987822722998e-01, 1.00000000000000e+04, 1.00000000000000e+04, 6.96358568604549e-01, +6.72198635997386e-01, -5.56303608685010e-01, -6.95833692233899e-01, 1.00000000000000e+04, 7.21421028871059e-01, +6.71713037227340e-01, -6.71190978854678e-01, 1.00000000000000e+04, 1.00000000000000e+04, 7.20814686947770e-01, +6.95270850265615e-01, -5.96076297407560e-01, -4.97463149951699e-01, 6.22201539491909e-01, 1.00000000000000e+04, +1.00000000000000e+04, 6.62063510673645e-01, -5.42046656870749e-01, -6.98377265724428e-01, 5.98275533271613e-01, +7.07106781186548e+03, 4.47211367513621e+03, 3.16219555986665e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, 4.71756410945701e-01, -5.40956142651829e-01, 6.61314314665243e-01, 1.00000000000000e+04, +1.00000000000000e+04, 5.79037786076085e-01, -4.63142758763710e-01, -6.15978503659878e-01, 5.18140123101607e-01, +7.07106781186548e+03, 4.47211367513621e+03, 3.16303722016459e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, 5.14847399617721e-01, -6.61619003551662e-01, -7.01344306307657e-01, 5.59332444390728e-01, +7.07106781186548e+03, 4.47375958891505e+03, 3.16568027247532e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, 4.38825810877665e-01, -4.63142758763710e-01, 5.79037786076086e-01, 1.00000000000000e+04, +1.00000000000000e+04, 6.61314314665243e-01, -5.40956142651829e-01, -6.61619003551662e-01, 5.14847399617720e-01, +7.07106781186548e+03, 4.47211367513621e+03, 3.16303722016459e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, 5.18140123101607e-01, -6.15978503659878e-01, -5.42046656870749e-01, 6.62063510673645e-01, +1.00000000000000e+04, 1.00000000000000e+04, 6.22201539491909e-01, -4.97463149951699e-01, 4.38825810877665e-01, +7.07106781186548e+03, 4.47375958891505e+03, 3.16568027247532e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, 5.59332444390728e-01, -7.01344306307658e-01, -5.56303608685010e-01, 6.72198635997386e-01, +6.96358568604549e-01, 1.00000000000000e+04, 1.00000000000000e+04, -7.21987822722998e-01, -5.96076297407560e-01, +6.95270850265615e-01, 7.20814686947770e-01, 1.00000000000000e+04, 1.00000000000000e+04, -6.71190978854678e-01, +6.71713037227340e-01, 7.21421028871060e-01, 1.00000000000000e+04, -6.95833692233899e-01, 4.71756410945702e-01, +7.07106781186548e+03, 4.47211367513621e+03, 3.16219555986665e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, 5.98275533271613e-01, -6.98377265724429e-01, -7.21421028871059e-01, -6.96358568604549e-01, +7.07106781186548e+03, 4.47278828966577e+03, 3.16362288767996e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, 6.72721192187865e-01, -5.59332444390728e-01, -7.20814686947770e-01, -6.72198635997386e-01, +1.00000000000000e+04, 6.95795456626559e-01, -6.95270850265615e-01, -6.71713037227340e-01, 7.07106781186548e+03, +4.47211367513621e+03, 3.16219555986665e+03, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, +7.20248479188010e-01, -5.98275533271613e-01, 7.07106781186548e+03, 4.47211367513621e+03, 3.16254006457817e+03, +1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, 6.35692573494055e-01, -6.22201539491909e-01, +-5.18140123101607e-01, -4.71756410945701e-01, -6.62063510673645e-01, 5.93729356862099e-01, 7.07106781186548e+03, +4.47211367513621e+03, 3.16219555986665e+03, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, +7.07106781186548e+03, 4.47278854175854e+03, 3.16362359977505e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, 5.52214558674803e-01, -6.61314314665243e-01, -4.38825810877665e-01, -5.14847399617721e-01, +-5.79037786076086e-01, 6.32399850010169e-01, 7.07106781186548e+03, 4.47211367513621e+03, 3.16253988611452e+03, +1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, 3.16219554579117e+03, 4.47211367513621e+03, +1.00000000000000e+04, -3.16219524365925e+03, -3.16303722016459e+03, -4.47211322794194e+03, 7.07106781186548e+03, +-5.14654332551985e+03, 1.00000000000000e+04, 4.47211365523006e+03, -4.47375958891506e+03, -3.16219396675864e+03, +5.14654332551985e+03, 1.00000000000000e+04, 3.16219517337107e+03, -3.16568027247532e+03, -6.61314314665243e-01, +-4.38825810877666e-01, 5.52214558674803e-01, 7.07106781186548e+03, 4.47278854175854e+03, 3.16362359977505e+03, +1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, 7.07106781186548e+03, 4.47211367513621e+03, +3.16253988611452e+03, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, 6.32399850010169e-01, +-5.79037786076086e-01, -5.14847399617721e-01, -3.16219524365925e+03, 4.47211367513621e+03, 1.00000000000000e+04, +3.16219554579117e+03, -3.16303722016459e+03, -6.22201539491909e-01, -5.18140123101607e-01, 6.35692573494055e-01, +7.07106781186548e+03, 4.47211367513621e+03, 3.16254006457817e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, 7.07106781186548e+03, 4.47211367513621e+03, 3.16219555986665e+03, 1.00000000000000e+04, +1.00000000000000e+04, 1.00000000000000e+04, 5.93729356862099e-01, -6.62063510673645e-01, -4.71756410945701e-01, +4.47211365523005e+03, 7.07106781186548e+03, -5.14654332551985e+03, 1.00000000000000e+04, -4.47211322794194e+03, +-4.47375958891505e+03, 3.16219517337107e+03, 5.14654332551985e+03, 1.00000000000000e+04, -3.16219396675864e+03, +-3.16568027247532e+03, -5.59332444390728e-01, 6.72721192187865e-01, 7.07106781186548e+03, 4.47278828966577e+03, +3.16362288767996e+03, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, -6.96358568604549e-01, +-7.21421028871059e-01, 6.95795456626559e-01, 1.00000000000000e+04, -6.72198635997386e-01, -7.20814686947770e-01, +-5.98275533271613e-01, 7.20248479188010e-01, 7.07106781186548e+03, 4.47211367513621e+03, 3.16219555986665e+03, +1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, -6.71713037227340e-01, -6.95270850265615e-01, +7.07106781186548e+03, -5.14654332551985e+03, 1.00000000000000e+04, -4.47211320803578e+03, 4.47211322794194e+03, +-4.47278828966577e+03, 5.14654332551985e+03, 1.00000000000000e+04, -3.16219391054595e+03, 3.16219396675864e+03, +-3.16362288767996e+03, -7.20248479188010e-01, -6.95795456626559e-01, -6.72721192187865e-01, 7.07106781186548e+03, +4.47211320803578e+03, 3.16219391054595e+03, 7.07106781186548e+03, 4.47211367513621e+03, 3.16219555986665e+03, +1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, 4.47211367513621e+03, +1.00000000000000e+04, 3.16219555986665e+03, -3.16219554579117e+03, -3.16254006457817e+03, -6.35692573494055e-01, +7.07106781186548e+03, 4.47211367513621e+03, 3.16219555986665e+03, 1.00000000000000e+04, 1.00000000000000e+04, +1.00000000000000e+04, -5.93729356862099e-01, 7.07106781186548e+03, -5.14654332551985e+03, 1.00000000000000e+04, +4.47211367513621e+03, -4.47211365523005e+03, -4.47278854175854e+03, 5.14654332551985e+03, 1.00000000000000e+04, +3.16219522958377e+03, -3.16219517337107e+03, -3.16362359977505e+03, -5.52214558674803e-01, 7.07106781186548e+03, +4.47211367513621e+03, 3.16219522958377e+03, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, +-6.32399850010169e-01, 3.16219524365925e+03, -3.16219522958377e+03, 4.47211367513621e+03, 1.00000000000000e+04, +-3.16253988611453e+03, -4.47211365523006e+03, 4.47211367513621e+03, 7.07106781186548e+03, -5.14654332551985e+03, +1.00000000000000e+04, -4.47278854175854e+03, -3.16219517337107e+03, 3.16219522958377e+03, 5.14654332551985e+03, +1.00000000000000e+04, -3.16362359977505e+03, -6.32399850010169e-01, 7.07106781186548e+03, 4.47211367513621e+03, +3.16219522958377e+03, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, -5.52214558674803e-01, +4.47211367513621e+03, 1.00000000000000e+04, -3.16219522958377e+03, 3.16219524365925e+03, -3.16253988611452e+03, +-3.16219554579117e+03, 3.16219555986665e+03, 4.47211367513621e+03, 1.00000000000000e+04, -3.16254006457817e+03, +-5.93729356862099e-01, 7.07106781186548e+03, 4.47211367513621e+03, 3.16219555986665e+03, 1.00000000000000e+04, +1.00000000000000e+04, 1.00000000000000e+04, -6.35692573494055e-01, 4.47211322794194e+03, -4.47211320803578e+03, +7.07106781186548e+03, -5.14654332551985e+03, 1.00000000000000e+04, -4.47278828966577e+03, 3.16219396675864e+03, +-3.16219391054595e+03, 5.14654332551985e+03, 1.00000000000000e+04, -3.16362288767996e+03, 7.07106781186548e+03, +4.47211367513621e+03, 3.16219555986665e+03, 7.07106781186548e+03, 4.47211320803578e+03, 3.16219391054595e+03, +1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, 1.00000000000000e+04, -6.72721192187865e-01, +-6.95795456626559e-01, -7.20248479188010e-01 }; + +static int MPT_NC[] = { +8, 7, 4, 7, 7, +4, 7, 6, 4, 6, +5, 6, 5, 6, 5, +6, 4, 6, 5, 8, +7, 6, 6, 7, 6, +6, 7, 8, 7, 6, +4, 6, 6, 9, 6, +10, 9, 6, 10, 6, +9, 6, 6, 4, 9, +10, 4, 10, 9, 9, +9, 9, 5, 6, 5, +9, 9, 5, 9, 9, +6, 5, 10, 4, 10, +6, 5, 13, 5, 8, +6, 5, 8, 5, 6, +5, 8, 5, 5, 8, +6, 5, 13 }; + + +static double MPT_F[] = { +6.12602719453146e-01, -4.19880095655810e+01, -1.33669641159051e+01, -7.56792203547651e-01, 5.18708083928873e+01, +1.65131722514201e+01, 5.79904414164707e-01, -4.03260963210318e+01, -1.30089280731406e+01, -7.16397635052098e-01, +4.98177274213074e+01, 1.60708645744396e+01, 5.48088412307963e-01, -3.86928583874347e+01, -1.26552635186198e+01, +-6.77093039449364e-01, 4.78000711239473e+01, 1.56339573113256e+01, 6.32465473561184e-01, -4.33494098385533e+01, +-1.38003685278904e+01, 1.07462358978833e-16, 0.00000000000000e+00, 0.00000000000000e+00, 5.99239069954525e-01, +-4.16513005463326e+01, -1.34308094032897e+01, -7.40283126081380e-01, 5.14548475220985e+01, 1.65920449272859e+01, +5.66901358088546e-01, -3.99823044220475e+01, -1.30657611595509e+01, -7.00334024577898e-01, 4.93930165597127e+01, +1.61410745740578e+01, 6.30874586656981e-01, -4.32586208229349e+01, -1.37768547813504e+01, -7.79364755390816e-01, +5.34404858735288e+01, 1.70195396736753e+01, 5.97700071288893e-01, -4.15635923044339e+01, -1.34081359734223e+01, +1.20268673736372e-16, -4.93405367282421e-15, -6.62628056179353e-15, 5.65411315783067e-01, -3.98974794543448e+01, +-1.30438661914416e+01, -6.98493268139941e-01, 4.92882261756920e+01, 1.61140261450583e+01, 6.29379419348833e-01, +-4.31723777417641e+01, -1.37543351191684e+01, -7.77517667668424e-01, 5.33339435919368e+01, 1.69917195151537e+01, +5.96250882295624e-01, -4.14800918486164e+01, -1.33863651018206e+01, -7.36591602927497e-01, 5.12433411028536e+01, +1.65371396848247e+01, 5.64009675468841e-01, -3.98168361381024e+01, -1.30228826405088e+01, 0.00000000000000e+00, +0.00000000000000e+00, -3.43879548732267e-15, 6.29379419348833e-01, -4.31723777417641e+01, -1.37543351191684e+01, +-7.77517667668424e-01, 5.33339435919368e+01, 1.69917195151537e+01, 5.96250882295624e-01, -4.14800918486164e+01, +-1.33863651018206e+01, -7.36591602927497e-01, 5.12433411028536e+01, 1.65371396848248e+01, 5.64009675468841e-01, +-3.98168361381024e+01, -1.30228826405088e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.30874586656981e-01, -4.32586208229350e+01, -1.37768547813504e+01, -7.79364755390816e-01, 5.34404858735289e+01, +1.70195396736753e+01, 5.97700071288893e-01, -4.15635923044339e+01, -1.34081359734223e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 5.65411315783067e-01, -3.98974794543448e+01, -1.30438661914416e+01, +-6.98493268139941e-01, 4.92882261756920e+01, 1.61140261450583e+01, 6.32465473561184e-01, -4.33494098385533e+01, +-1.38003685278904e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 5.99239069954525e-01, +-4.16513005463326e+01, -1.34308094032897e+01, -7.40283126081380e-01, 5.14548475220985e+01, 1.65920449272859e+01, +5.66901358088546e-01, -3.99823044220475e+01, -1.30657611595509e+01, -7.00334024577898e-01, 4.93930165597127e+01, +1.61410745740578e+01, 6.51978140827589e-01, -4.47056764932547e+01, -1.42377080275074e+01, -6.15235897506191e-18, +6.84590016624433e-16, 4.20015056343382e-15, 6.18242867167010e-01, -4.29721971782543e+01, -1.38567435439308e+01, +-3.88650061902680e-17, 8.79578827389216e-15, 8.74428176242894e-16, 5.85400057564814e-01, -4.12680932336161e+01, +-1.34803744905765e+01, -7.23186798643131e-01, 5.09814439647895e+01, 1.66532762448032e+01, 6.50397515637332e-01, +-4.46141172783360e+01, -1.42136604975197e+01, 1.03073011558427e-16, -9.86462414796752e-16, -1.35183855742238e-15, +6.16710721048622e-01, -4.28835376239706e+01, -1.38334904288356e+01, -7.61867113405042e-01, 5.29771186183013e+01, +1.70895057627875e+01, 5.83918003555545e-01, -4.11824509547664e+01, -1.34579553609518e+01, -6.63016855418838e-17, +4.62795596394347e-15, 3.90416388537754e-15, 6.50397515637332e-01, -4.46141172783360e+01, -1.42136604975197e+01, +1.07356917567867e-16, 0.00000000000000e+00, 0.00000000000000e+00, 6.16710721048622e-01, -4.28835376239706e+01, +-1.38334904288356e+01, -7.61867113405042e-01, 5.29771186183013e+01, 1.70895057627875e+01, 5.83918003555545e-01, +-4.11824509547664e+01, -1.34579553609518e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 6.12602719453134e-01, -4.25672498641541e+01, -1.37224036415015e+01, -7.56792203547635e-01, +5.25863855981796e+01, 1.69522722639767e+01, 5.79904414164695e-01, -4.08735385376820e+01, -1.33494872653086e+01, +-7.16397635052084e-01, 5.04940221687802e+01, 1.64915818407771e+01, 6.48728768164466e-01, -4.45184768250783e+01, +-1.41887452901543e+01, -8.01421310049357e-01, 5.49968766137885e+01, 1.75283776462789e+01, 6.15096167219023e-01, +-4.27911241216862e+01, -1.38094585880075e+01, 8.43971676644078e-17, -4.99921084857836e-17, 4.71998417415472e-16, +5.82354617031382e-01, -4.10930604315440e+01, -1.34347429711506e+01, -5.09247286172691e-17, 8.11940306699086e-15, +2.94359236415170e-15, 6.40911112657100e-01, -4.39864693483814e+01, -1.40205998574019e+01, -7.91763597881058e-01, +5.43396495107932e+01, 1.73206554985831e+01, 6.07486849937125e-01, -4.22733064012972e+01, -1.36458015872429e+01, +-7.50472201952575e-01, 5.22232560953062e+01, 1.68576402364036e+01, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, -1.21363559856628e-16, 9.01676928861211e-15, -3.50823928680452e-15, 6.50397515637332e-01, +-4.46141172783360e+01, -1.42136604975197e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.16710721048622e-01, -4.28835376239706e+01, -1.38334904288356e+01, -7.61867113405042e-01, 5.29771186183013e+01, +1.70895057627875e+01, 5.83918003555545e-01, -4.11824509547664e+01, -1.34579553609518e+01, -6.91833630340409e-17, +1.55891165797845e-14, -1.52268524305355e-15, 6.40911112657100e-01, -4.39864693483814e+01, -1.40205998574019e+01, +-7.91763597881058e-01, 5.43396495107932e+01, 1.73206554985831e+01, 6.07486849937125e-01, -4.22733064012972e+01, +-1.36458015872429e+01, -7.50472201952575e-01, 5.22232560953062e+01, 1.68576402364036e+01, 4.00124090684067e-17, +-2.52767642055407e-15, -1.71592194537186e-15, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.48728768164466e-01, -4.45184768250783e+01, -1.41887452901543e+01, -8.01421310049357e-01, 5.49968766137885e+01, +1.75283776462789e+01, 6.15096167219023e-01, -4.27911241216862e+01, -1.38094585880075e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 5.82354617031382e-01, -4.10930604315440e+01, -1.34347429711506e+01, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.50397515637332e-01, -4.46141172783360e+01, +-1.42136604975197e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.16710721048622e-01, +-4.28835376239706e+01, -1.38334904288356e+01, -7.61867113405042e-01, 5.29771186183013e+01, 1.70895057627875e+01, +5.83918003555545e-01, -4.11824509547664e+01, -1.34579553609517e+01, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 6.51978140827589e-01, -4.47056764932547e+01, -1.42377080275074e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 6.18242867167010e-01, -4.29721971782543e+01, -1.38567435439308e+01, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 5.85400057564814e-01, -4.12680932336161e+01, +-1.34803744905765e+01, -7.23186798643131e-01, 5.09814439647895e+01, 1.66532762448032e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.12602719453134e-01, -4.25672498641541e+01, -1.37224036415015e+01, -7.56792203547635e-01, 5.25863855981796e+01, +1.69522722639767e+01, 5.79904414164695e-01, -4.08735385376820e+01, -1.33494872653086e+01, -7.16397635052084e-01, +5.04940221687802e+01, 1.64915818407771e+01, 6.71101005089044e-01, -4.60537531376581e+01, -1.46780622233188e+01, +1.43197787537647e-16, 2.96584339851349e-15, 1.62870283276820e-15, 6.36874529018666e-01, -4.42856462434796e+01, +-1.42857865136000e+01, 0.00000000000000e+00, 6.87759097464534e-15, -3.43879548732267e-15, 6.03546197072756e-01, +-4.25473151389899e+01, -1.38982370325497e+01, -1.78922457651668e-17, -7.40866439907795e-15, -3.61172888350273e-15, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 6.32465473561171e-01, -4.39474311631562e+01, -1.41673326642550e+01, -3.54275993414415e-19, +-3.92335909801320e-15, -4.19349193674982e-15, 5.99239069954512e-01, -4.22170244509951e+01, -1.37825867971785e+01, +-7.40283126081365e-01, 5.21537269537655e+01, 1.70266208451287e+01, 6.62742930738706e-01, -4.54848122198051e+01, +-1.44981936756972e+01, 8.04275508088366e-17, -1.01027304340937e-14, 7.56961527007868e-16, 6.28739177392136e-01, +-4.37318781622174e+01, -1.41107184429514e+01, -7.76726730727032e-01, 5.40251347059081e+01, 1.74319854694972e+01, +0.00000000000000e+00, -6.95446965012208e-15, -1.73861741253052e-15, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 6.30874586656968e-01, -4.38551101564181e+01, -1.41430247862851e+01, +-7.79364755390800e-01, 5.41773720523600e+01, 1.74718958191963e+01, 5.97700071288881e-01, -4.21278340034554e+01, +-1.37591459820806e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.61019559915794e-01, +-4.53857598059593e+01, -1.44722900981834e+01, -8.16605009170275e-01, 5.60682936633019e+01, 1.78786609428735e+01, +6.27071613546468e-01, -4.36361551822057e+01, -1.40857284735184e+01, -2.35286903388823e-17, 2.76853593478299e-16, +-2.25292268104172e-15, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.07462358978833e-16, +6.87759097464534e-15, -3.43879548732267e-15, 6.62742930738706e-01, -4.54848122198051e+01, -1.44981936756972e+01, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.28739177392136e-01, -4.37318781622174e+01, +-1.41107184429514e+01, -7.76726730727033e-01, 5.40251347059081e+01, 1.74319854694972e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.63776114160422e-17, -7.24242420161168e-15, -4.28184296969575e-15, +-1.08663588283157e-16, -6.95446965012207e-15, 1.73861741253052e-15, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 6.30874586656968e-01, -4.38551101564181e+01, -1.41430247862851e+01, -7.79364755390800e-01, +5.41773720523600e+01, 1.74718958191963e+01, 5.97700071288881e-01, -4.21278340034554e+01, -1.37591459820806e+01, +0.00000000000000e+00, 0.00000000000000e+00, -3.43879548732267e-15, 6.61019559915794e-01, -4.53857598059593e+01, +-1.44722900981834e+01, -8.16605009170275e-01, 5.60682936633019e+01, 1.78786609428735e+01, 6.27071613546468e-01, +-4.36361551822056e+01, -1.40857284735184e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-3.53459924389524e-17, -1.24378984395004e-15, 4.99782084703261e-16, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 6.71101005089044e-01, -4.60537531376581e+01, -1.46780622233188e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 6.36874529018666e-01, -4.42856462434796e+01, -1.42857865136000e+01, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.03546197072756e-01, -4.25473151389899e+01, +-1.38982370325497e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.32465473561171e-01, -4.39474311631562e+01, -1.41673326642550e+01, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 5.99239069954512e-01, -4.22170244509951e+01, -1.37825867971785e+01, -7.40283126081365e-01, +5.21537269537655e+01, 1.70266208451287e+01, 6.84287431258151e-01, -4.69833373724608e+01, -1.49817143337940e+01, +3.76381079674651e-17, -5.26897472298892e-15, 2.58709380014594e-15, 6.49722240012977e-01, -4.51913525690945e+01, +-1.45816388171861e+01, 1.07390046646914e-16, -1.37459259708051e-14, -3.43648149270126e-15, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.10998079853801e-16, 7.33016324664116e-15, 1.13143067998955e-16, +6.85417140724884e-01, -4.70492385738858e+01, -1.49991886745658e+01, 3.58871131313703e-17, -3.24959844123820e-15, +-5.68969396887530e-15, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.59862496313247e-16, +6.91479268382375e-15, 5.13928603716753e-15, 6.17118782570206e-01, -4.34910971440193e+01, -1.42026848476522e+01, +-1.33021289254738e-16, 1.78445565104169e-14, 2.51230646434691e-15, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.51978140827576e-01, +-4.53221191506275e+01, -1.46161268830033e+01, -7.20255678312934e-18, -1.74714846962370e-15, 4.37044840646868e-17, +6.18242867166997e-01, -4.35558620065005e+01, -1.42196769297977e+01, 1.01398930463811e-16, -1.30779770247547e-15, +-1.07410885805308e-15, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.87084272434350e-15, 3.43542136217175e-15, 6.51978140827576e-01, -4.53221191506275e+01, -1.46161268830033e+01, +-1.88694837708730e-17, 6.97633915499147e-15, 2.42831176148539e-15, 6.18242867166997e-01, -4.35558620065005e+01, +-1.42196769297977e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.07390046646914e-16, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 3.53572087496739e-18, -6.87759097464534e-15, +-3.43879548732267e-15, 6.12602719453121e-01, -4.31456096322885e+01, -1.40819347868628e+01, -7.56792203547620e-01, +5.33008750208849e+01, 1.73964269487369e+01, 6.84287431258151e-01, -4.69833373724608e+01, -1.49817143337941e+01, +9.54832644384518e-17, 8.70525348666655e-15, -1.53881474176064e-15, 6.49722240012977e-01, -4.51913525690945e+01, +-1.45816388171861e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 2.33167707514524e-17, +4.99229181139943e-15, 2.19408186466123e-16, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.07356917567867e-16, 0.00000000000000e+00, +0.00000000000000e+00, 6.43467784186022e-01, -4.47427194450245e+01, -1.44329220968372e+01, -7.94922038120839e-01, +5.52738996518676e+01, 1.78300268190899e+01, 1.05151968253927e-16, -6.34581131557227e-15, -8.67615186968878e-17, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.74913834272993e-01, -4.63526233968113e+01, +-1.47843931685572e+01, -8.33769605691928e-01, 5.72627298030958e+01, 1.82642243151240e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.09244802688800e-16, -5.16678641859226e-15, -9.20909748767123e-16, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 5.99307283102648e-17, -7.41423883065490e-16, +-4.38432284865208e-15, 6.84287431258151e-01, -4.69833373724608e+01, -1.49817143337940e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 6.49722240012977e-01, -4.51913525690945e+01, -1.45816388171861e+01, +7.14533731079566e-17, -4.23971337594477e-15, 1.82863158796576e-15, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, -8.45024339470655e-17, -2.85615030631423e-15, 1.27490008810169e-15, 0.00000000000000e+00, +6.95153654085368e-15, -1.73788413521342e-15, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.43467784186022e-01, -4.47427194450245e+01, -1.44329220968372e+01, -7.94922038120839e-01, 5.52738996518676e+01, +1.78300268190899e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 5.48411877678268e-17, +-7.68441291220574e-15, -5.30974281747984e-15, 1.08588824922658e-16, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.51978140827576e-01, -4.53221191506275e+01, +-1.46161268830033e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.18242867166997e-01, +-4.35558620065005e+01, -1.42196769297977e+01, 7.45333407191021e-17, 6.26524759143536e-16, -4.36959043794983e-16, +6.74913834272993e-01, -4.63526233968113e+01, -1.47843931685572e+01, -8.33769605691928e-01, 5.72627298030958e+01, +1.82642243151239e+01, -1.36160523931363e-16, 6.14978260702732e-15, 2.82945072080199e-15, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 2.61189080328743e-17, -2.94577292722334e-15, -7.69871555950032e-16, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.84287431258151e-01, -4.69833373724608e+01, +-1.49817143337941e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.49722240012977e-01, +-4.51913525690945e+01, -1.45816388171861e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.74613534914851e-17, 4.83729014763018e-15, 1.79503021657191e-15, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 6.51978140827576e-01, -4.53221191506275e+01, -1.46161268830033e+01, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.18242867166997e-01, -4.35558620065005e+01, +-1.42196769297977e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.85417140724884e-01, +-4.70492385738858e+01, -1.49991886745658e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.73742119876253e-15, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 6.17118782570206e-01, -4.34910971440193e+01, -1.42026848476522e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -6.95446965012207e-15, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.12602719453121e-01, +-4.31456096322885e+01, -1.40819347868628e+01, -7.56792203547620e-01, 5.33008750208849e+01, 1.73964269487369e+01, +6.99201652365551e-01, -4.80206942349018e+01, -1.53164324210546e+01, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.65449142298277e-01, +-4.62711654110978e+01, -1.49259618993165e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.32465473561158e-01, -4.45445434073990e+01, +-1.45385210852171e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.65449142298277e-01, -4.62711654110978e+01, -1.49259618993165e+01, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.32465473561158e-01, +-4.45445434073990e+01, -1.45385210852171e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.99201652365551e-01, -4.80206942349018e+01, -1.53164324210546e+01, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.65449142298277e-01, +-4.62711654110978e+01, -1.49259618993165e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.39697605246655e-11, +3.79336671939226e-11, 2.94081184472739e-13, 5.08329737073997e+04, -1.52495799859836e+05, -1.51895719343700e+03, +-6.27976288111223e+04, 1.88389030513459e+05, 1.87647707888386e+03, -5.88521994141581e-13, 4.10313709357202e-13, +1.21703218877136e-14, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 5.08329737073997e+04, +-1.01665322369875e+05, -5.07123470300984e+02, -6.27976288111224e+04, 1.25594485459290e+05, 6.26486100000355e+02, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -5.51547422067617e-13, 4.01936320052028e-13, +-3.59910572395089e-15, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, -1.22969177379479e-12, +2.40715684112587e-12, 0.00000000000000e+00, 1.27284152880247e+04, -3.81844643098842e+04, -3.80342060531159e+02, +-1.57243269538417e+04, 4.71720153514175e+04, 4.69863905188304e+02, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 9.77154722758984e-13, -1.68098842712660e-12, 4.63190035026860e-15, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -3.49360129040188e-13, 6.46493551616662e-13, 3.43879548732267e-15, +6.99201652365551e-01, -4.80206942349018e+01, -1.53164324210546e+01, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.65449142298277e-01, +-4.62711654110978e+01, -1.49259618993165e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 5.08329737073998e+04, -1.52495799859836e+05, -1.51895719343701e+03, +-6.27976288111225e+04, 1.88389030513459e+05, 1.87647707888386e+03, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 5.30971515714416e-13, 6.46493551616662e-13, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.65449142298277e-01, -4.62711654110978e+01, -1.49259618993165e+01, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.32465473561158e-01, +-4.45445434073990e+01, -1.45385210852171e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +5.08329737073998e+04, -1.01665322369875e+05, -5.07123470300984e+02, -6.27976288111224e+04, 1.25594485459291e+05, +6.26486100000355e+02, -1.33358643415427e-13, 2.72002247480589e-14, 4.80289455505103e-15, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, -1.43435936533768e-13, 4.10313709357202e-13, 3.47723482506104e-15, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 1.27284152880247e+04, -3.81844643098842e+04, +-3.80342060531159e+02, -1.57243269538417e+04, 4.71720153514175e+04, 4.69863905188304e+02, -3.46592259969640e-14, +6.22110368850020e-13, 1.12038775486718e-14, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +-3.21644221318146e-14, 4.10313709357202e-13, 5.21585223759156e-15, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 6.99201652365551e-01, -4.80206942349018e+01, -1.53164324210546e+01, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +6.65449142298277e-01, -4.62711654110978e+01, -1.49259618993165e+01, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 6.32465473561158e-01, +-4.45445434073990e+01, -1.45385210852171e+01, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.28411401579808e+05, -2.56821224206252e+05, -1.28106681246322e+03, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 3.21538074170776e+04, -9.64594479329585e+04, +-9.60798739685939e+02, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.28411401579808e+05, -3.85226319981842e+05, -3.83710430303988e+03, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.28411401579808e+05, -2.56821224206252e+05, -1.28106681246322e+03, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 3.21538074170776e+04, -9.64594479329585e+04, +-9.60798739685939e+02, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.28411401579808e+05, -3.85226319981842e+05, -3.83710430303988e+03, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.28411401579808e+05, -2.56821224206252e+05, -1.28106681246322e+03, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +3.21538074170776e+04, -9.64594479329585e+04, -9.60798739685939e+02, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 1.28411401579808e+05, -3.85226319981842e+05, -3.83710430303988e+03, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.28411401579808e+05, -3.85226319981842e+05, -3.83710430303988e+03, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +1.28411401579808e+05, -2.56821224206252e+05, -1.28106681246322e+03, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 3.21538074170776e+04, -9.64594479329585e+04, +-9.60798739685939e+02, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, +0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00, 0.00000000000000e+00 }; + + +static double MPT_G[] = { +7.10542735760100e-15, 7.10542735760100e-15, 0.00000000000000e+00, 3.55271367880050e-15, 3.55271367880050e-15, +3.55271367880050e-15, -7.87379442398830e-01, -3.00000000000000e+01, -7.66445096785425e-01, 9.46844758071467e-01, +-7.45763990130666e-01, 9.21295899439190e-01, -7.65156093899122e-01, 9.45252360088698e-01, -7.45214232437768e-01, +-3.00000000000000e+01, -7.25417113102697e-01, 8.96159938705853e-01, -7.43326201196659e-01, 9.18284323420075e-01, +-7.24263897803954e-01, 8.94735288897113e-01, -7.05424316892650e-01, -3.00000000000000e+01, 7.43326201196659e-01, +-9.18284323420075e-01, 7.24263897803961e-01, -8.94735288897113e-01, 7.05424316892650e-01, 3.00000000000000e+01, +7.65156093899133e-01, -9.45252360088688e-01, 7.45214232437768e-01, 3.00000000000000e+01, 7.25417113102708e-01, +-8.96159938705846e-01, 7.87379442398837e-01, 3.00000000000000e+01, 7.66445096785432e-01, -9.46844758071464e-01, +7.45763990130673e-01, -9.21295899439183e-01, -1.60308827518798e+00, -3.00000000000000e+01, -1.56088109218862e+00, +-3.00000000000000e+01, -1.51908484636661e+00, 1.87663477772982e+00, -1.57911875486757e+00, -3.00000000000000e+01, +-1.53785712929085e+00, 1.89982552910705e+00, -1.49708651800309e+00, -3.00000000000000e+01, -4.28196649906312e-02, +-3.00000000000000e+01, -4.10013021337114e-02, 5.06518577289334e-02, -3.92125718738399e-02, 3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, -1.41696558374937e+00, 1.75047950723125e+00, -1.37873138212612e+00, +1.70324604779906e+00, -1.55489262049287e+00, 1.92087069674327e+00, -1.51468845170640e+00, -3.00000000000000e+01, +-1.47486305501083e+00, -3.00000000000000e+01, -1.37112666548528e+00, 1.69385139432917e+00, -1.33596467005821e+00, +1.65041325219335e+00, 3.00000000000000e+01, -3.00000000000000e+01, 4.28196649906312e-02, 3.00000000000000e+01, +4.10013021337150e-02, -5.06518577289263e-02, 3.92125718738541e-02, -3.00000000000000e+01, 1.37112666548528e+00, +-1.69385139432917e+00, 1.33596467005821e+00, -1.65041325219336e+00, -3.00000000000000e+01, 3.00000000000000e+01, +1.55489262049288e+00, -1.92087069674326e+00, 1.51468845170640e+00, 3.00000000000000e+01, 1.47486305501083e+00, +3.00000000000000e+01, 1.57911875486756e+00, 3.00000000000000e+01, 1.53785712929086e+00, -1.89982552910705e+00, +1.49708651800310e+00, 3.00000000000000e+01, 1.60308827518798e+00, 3.00000000000000e+01, 1.56088109218863e+00, +3.00000000000000e+01, 1.51908484636662e+00, -1.87663477772982e+00, -3.00000000000000e+01, 3.00000000000000e+01, +1.41696558374937e+00, -1.75047950723125e+00, 1.37873138212614e+00, -1.70324604779906e+00, -2.44598607297715e+00, +-3.00000000000000e+01, -2.38212766535853e+00, -3.00000000000000e+01, -2.31893056092570e+00, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, -2.25028807875934e+00, -3.00000000000000e+01, -2.18989802675623e+00, +2.70533855072163e+00, 5.90622625385759e-01, -3.00000000000000e+01, 5.76177858984984e-01, -7.11793953389332e-01, +-3.00000000000000e+01, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -6.95251126279679e-01, +8.58893725359032e-01, -6.75826589560469e-01, 3.00000000000000e+01, -2.21918028285008e+00, 2.74151302793238e+00, +-2.16193245416729e+00, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -5.90622625385759e-01, +3.00000000000000e+01, -5.76177858984984e-01, 7.11793953389336e-01, 3.00000000000000e+01, -3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, 6.95251126279686e-01, -8.58893725359032e-01, 6.75826589560483e-01, +-3.00000000000000e+01, 2.21918028285007e+00, -2.74151302793238e+00, 2.16193245416728e+00, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, 2.44598607297716e+00, 3.00000000000000e+01, 2.38212766535854e+00, +3.00000000000000e+01, 2.31893056092571e+00, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +2.25028807875934e+00, 3.00000000000000e+01, 2.18989802675624e+00, -2.70533855072163e+00, -3.15209803884336e+00, +-3.00000000000000e+01, -3.07010197702822e+00, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +-3.17389543457258e+00, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -3.00903383292283e+00, +-3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -3.11234796705295e+00, -3.00000000000000e+01, +-3.02947629037758e+00, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -1.53084489783995e+00, +-3.00000000000000e+01, -1.48921717521336e+00, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, -2.87132897299747e+00, 3.54715921360054e+00, 1.44249270350518e+00, +-3.00000000000000e+01, 1.40584866884514e+00, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, -7.74076193556006e-02, 9.56272000813136e-02, -3.00000000000000e+01, +3.00000000000000e+01, -2.93180497151778e+00, 3.62186956458101e+00, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, -1.44249270350518e+00, 3.00000000000000e+01, -1.40584866884515e+00, +-3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +7.74076193556006e-02, -9.56272000813172e-02, 3.00000000000000e+01, -3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, 1.53084489783995e+00, 3.00000000000000e+01, 1.48921717521337e+00, -3.00000000000000e+01, +2.93180497151779e+00, -3.62186956458101e+00, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, 3.15209803884338e+00, 3.00000000000000e+01, 3.07010197702822e+00, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 3.11234796705295e+00, +3.00000000000000e+01, 3.02947629037759e+00, 3.00000000000000e+01, 3.17389543457258e+00, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, 3.00903383292284e+00, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 2.87132897299748e+00, -3.54715921360053e+00, +-3.91121444667917e+00, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -3.83203297647820e+00, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, -3.75180709018644e+00, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +-9.09618487055003e-01, -3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -2.17704820538881e+00, 3.00000000000000e+01, +2.16340656833357e+00, -3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 7.49514639827598e-01, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, 3.00000000000000e+01, -2.99999997100380e+01, -5.08329843093108e+08, +6.27976419084257e+08, -2.99999999992569e+01, 3.00000000000000e+01, 5.08329737073997e+08, -6.27976288111225e+08, +3.00000000000000e+01, -2.99999999914193e+01, 3.00000000000000e+01, -3.00000000023856e+01, 1.27284146233000e+08, +-1.57243261326595e+08, 3.00000000000000e+01, -2.99999999901575e+01, 3.00000000000000e+01, -3.00000000023856e+01, +-2.16340656833358e+00, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -7.49514639827598e-01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, -3.00000000274959e+01, 3.00000000000000e+01, 5.08329843093109e+08, +-6.27976419084258e+08, 3.00000000000000e+01, -2.99999999951739e+01, -3.00000000000000e+01, 3.00000000000000e+01, +9.09618487055003e-01, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 2.17704820538881e+00, -3.00000000000000e+01, +-5.08329737073997e+08, 6.27976288111224e+08, -2.99999999978308e+01, 3.00000000000000e+01, -2.99999999992569e+01, +3.00000000000000e+01, -1.27284146233000e+08, 1.57243261326595e+08, -3.00000000003853e+01, 3.00000000000000e+01, +-2.99999999992569e+01, 3.00000000000000e+01, 3.91121444667917e+00, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +3.83203297647820e+00, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 3.75180709018645e+00, 3.00000000000000e+01, +1.28411397873692e+09, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, 3.21538020317717e+08, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +-1.28411432067875e+09, -3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +-1.28411405285923e+09, -3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.21538094440033e+08, -3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +-1.28411424655644e+09, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 1.28411405285923e+09, +3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.21538094440033e+08, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 1.28411424655644e+09, +-3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +1.28411432067875e+09, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +-1.28411397873692e+09, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.21538020317717e+08, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, +-3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01, -3.00000000000000e+01, +3.00000000000000e+01, -3.00000000000000e+01, 3.00000000000000e+01 }; + + +static double MPT_HTB[] = { +6.95606681734144e+01, -2.37906948588652e+03, -4.03317676421839e+02, -2.37906948588652e+03, 1.22588280472113e+05, +2.74528689138917e+04, -4.03317676421839e+02, 2.74528689138917e+04, 8.68463769270146e+03, 7.01519726957515e+01, +-2.41959770940179e+03, -4.16219914823111e+02, -2.41959770940179e+03, 1.25366099411857e+05, 2.83371929500200e+04, +-4.16219914823111e+02, 2.83371929500200e+04, 8.96616396127337e+03, 7.00896432134124e+01, -2.41585399363183e+03, +-4.15184111785557e+02, -2.41585399363183e+03, 1.25146246175126e+05, 2.82780514849777e+04, -4.15184111785557e+02, +2.82780514849777e+04, 8.95083605291488e+03, 7.00324406848857e+01, -2.41237474570870e+03, -4.14210819424752e+02, +-2.41237474570870e+03, 1.24939499131216e+05, 2.82218814128623e+04, -4.14210819424752e+02, 2.82218814128623e+04, +8.93615841846789e+03, 7.00324406848857e+01, -2.41237474570870e+03, -4.14210819424752e+02, -2.41237474570870e+03, +1.24939499131216e+05, 2.82218814128623e+04, -4.14210819424752e+02, 2.82218814128623e+04, 8.93615841846789e+03, +7.00896432134124e+01, -2.41585399363183e+03, -4.15184111785557e+02, -2.41585399363183e+03, 1.25146246175126e+05, +2.82780514849777e+04, -4.15184111785557e+02, 2.82780514849777e+04, 8.95083605291488e+03, 7.01519726957515e+01, +-2.41959770940179e+03, -4.16219914823111e+02, -2.41959770940179e+03, 1.25366099411857e+05, 2.83371929500200e+04, +-4.16219914823111e+02, 2.83371929500200e+04, 8.96616396127337e+03, 7.07173712500411e+01, -2.45889685776167e+03, +-4.28892253127312e+02, -2.45889685776167e+03, 1.28097664694601e+05, 2.92180089678627e+04, -4.28892253127312e+02, +2.92180089678627e+04, 9.25019043583326e+03, 7.06571627838605e+01, -2.45522765384553e+03, -4.27863374372513e+02, +-2.45522765384553e+03, 1.27879000933373e+05, 2.91583805121731e+04, -4.27863374372513e+02, 2.91583805121731e+04, +9.23451869243212e+03, 7.06571627838605e+01, -2.45522765384553e+03, -4.27863374372513e+02, -2.45522765384553e+03, +1.27879000933373e+05, 2.91583805121731e+04, -4.27863374372513e+02, 2.91583805121731e+04, 9.23451869243212e+03, +7.05606681734137e+01, -2.44760984366200e+03, -4.25137631984276e+02, -2.44760984366200e+03, 1.27286061116108e+05, +2.89484164747873e+04, -4.25137631984276e+02, 2.89484164747873e+04, 9.16074815344851e+03, 7.05921564163533e+01, +-2.45131315341554e+03, -4.26776937743622e+02, -2.45131315341554e+03, 1.27648373492793e+05, 2.90960834602295e+04, +-4.26776937743622e+02, 2.90960834602295e+04, 9.21827900348309e+03, 7.03567199500204e+01, -2.43526756993573e+03, +-4.21698369720921e+02, -2.43526756993573e+03, 1.26555641319252e+05, 2.87504726342284e+04, -4.21698369720921e+02, +2.87504726342284e+04, 9.10904461707940e+03, 7.06571627838605e+01, -2.45522765384553e+03, -4.27863374372513e+02, +-2.45522765384553e+03, 1.27879000933373e+05, 2.91583805121731e+04, -4.27863374372513e+02, 2.91583805121731e+04, +9.23451869243212e+03, 7.03567199500204e+01, -2.43526756993573e+03, -4.21698369720921e+02, -2.43526756993573e+03, +1.26555641319252e+05, 2.87504726342284e+04, -4.21698369720921e+02, 2.87504726342284e+04, 9.10904461707939e+03, +7.05921564163533e+01, -2.45131315341554e+03, -4.26776937743622e+02, -2.45131315341554e+03, 1.27648373492793e+05, +2.90960834602295e+04, -4.26776937743622e+02, 2.90960834602295e+04, 9.21827900348309e+03, 7.06571627838605e+01, +-2.45522765384553e+03, -4.27863374372513e+02, -2.45522765384553e+03, 1.27879000933373e+05, 2.91583805121731e+04, +-4.27863374372513e+02, 2.91583805121731e+04, 9.23451869243212e+03, 7.07173712500411e+01, -2.45889685776167e+03, +-4.28892253127312e+02, -2.45889685776167e+03, 1.28097664694601e+05, 2.92180089678627e+04, -4.28892253127312e+02, +2.92180089678627e+04, 9.25019043583326e+03, 7.05606681734137e+01, -2.44760984366200e+03, -4.25137631984276e+02, +-2.44760984366200e+03, 1.27286061116108e+05, 2.89484164747873e+04, -4.25137631984276e+02, 2.89484164747873e+04, +9.16074815344851e+03, 7.12565822415667e+01, -2.49690882783805e+03, -4.41309003008474e+02, -2.49690882783805e+03, +1.30777339055467e+05, 3.00933344570433e+04, -4.41309003008474e+02, 3.00933344570433e+04, 9.53611872741932e+03, +7.11519726957508e+01, -2.48869716918121e+03, -4.38382952438938e+02, -2.48869716918121e+03, 1.30141050811856e+05, +2.98687794562440e+04, -4.38382952438938e+02, 2.98687794562440e+04, 9.45744555270616e+03, 7.10049637379472e+01, +-2.47975728925064e+03, -4.35879379506955e+02, -2.47975728925064e+03, 1.29609022102198e+05, 2.97237317023953e+04, +-4.35879379506955e+02, 2.97237317023953e+04, 9.41926901459309e+03, 7.10896432134117e+01, -2.48489371520137e+03, +-4.37314717358406e+02, -2.48489371520137e+03, 1.29913948959302e+05, 2.98066968329961e+04, -4.37314717358406e+02, +2.98066968329961e+04, 9.44106649929983e+03, 7.09380857510052e+01, -2.47572318578784e+03, -4.34757421732778e+02, +-2.47572318578784e+03, 1.29370834182681e+05, 2.96592154441589e+04, -4.34757421732778e+02, 2.96592154441589e+04, +9.40238632923288e+03, 7.10049637379472e+01, -2.47975728925064e+03, -4.35879379506955e+02, -2.47975728925064e+03, +1.29609022102198e+05, 2.97237317023953e+04, -4.35879379506955e+02, 2.97237317023953e+04, 9.41926901459309e+03, +7.10896432134117e+01, -2.48489371520137e+03, -4.37314717358406e+02, -2.48489371520137e+03, 1.29913948959302e+05, +2.98066968329961e+04, -4.37314717358406e+02, 2.98066968329961e+04, 9.44106649929983e+03, 7.09380857510052e+01, +-2.47572318578784e+03, -4.34757421732778e+02, -2.47572318578784e+03, 1.29370834182681e+05, 2.96592154441589e+04, +-4.34757421732778e+02, 2.96592154441589e+04, 9.40238632923288e+03, 7.12565822415667e+01, -2.49690882783805e+03, +-4.41309003008474e+02, -2.49690882783805e+03, 1.30777339055467e+05, 3.00933344570433e+04, -4.41309003008474e+02, +3.00933344570433e+04, 9.53611872741932e+03, 7.11519726957508e+01, -2.48869716918121e+03, -4.38382952438938e+02, +-2.48869716918121e+03, 1.30141050811856e+05, 2.98687794562440e+04, -4.38382952438938e+02, 2.98687794562440e+04, +9.45744555270616e+03, 7.16284023743726e+01, -2.52312048892090e+03, -4.49871138540557e+02, -2.52312048892090e+03, +1.32625144260466e+05, 3.06969268258018e+04, -4.49871138540557e+02, 3.06969268258018e+04, 9.73328439544417e+03, +7.16710713198111e+01, -2.52573070067885e+03, -4.50606442636248e+02, -2.52573070067885e+03, 1.32781494044471e+05, +3.07398403283963e+04, -4.50606442636248e+02, 3.07398403283963e+04, 9.74467038334772e+03, 7.17173712500403e+01, +-2.52853009361454e+03, -4.51387202395614e+02, -2.52853009361454e+03, 1.32947322346995e+05, 3.07849425803032e+04, +-4.51387202395614e+02, 3.07849425803032e+04, 9.75654521550635e+03, 7.17173712500403e+01, -2.52853009361454e+03, +-4.51387202395614e+02, -2.52853009361454e+03, 1.32947322346995e+05, 3.07849425803032e+04, -4.51387202395614e+02, +3.07849425803032e+04, 9.75654521550635e+03, 7.15606681734130e+01, -2.51709574131215e+03, -4.47537799671650e+02, +-2.51709574131215e+03, 1.32114351088358e+05, 3.05049122340595e+04, -4.47537799671650e+02, 3.05049122340595e+04, +9.66251566587135e+03, 7.16284023743726e+01, -2.52312048892090e+03, -4.49871138540557e+02, -2.52312048892090e+03, +1.32625144260466e+05, 3.06969268258018e+04, -4.49871138540557e+02, 3.06969268258018e+04, 9.73328439544417e+03, +7.14542193726142e+01, -2.51059022195162e+03, -4.45707315648109e+02, -2.51059022195162e+03, 1.31725121858293e+05, +3.03982343023557e+04, -4.45707315648109e+02, 3.03982343023557e+04, 9.63426538045099e+03, 7.13397903598623e+01, +-2.50367668307718e+03, -4.43780796295885e+02, -2.50367668307718e+03, 1.31316039673174e+05, 3.02871267770863e+04, +-4.43780796295885e+02, 3.02871267770863e+04, 9.60507578489480e+03, 7.16284023743726e+01, -2.52312048892090e+03, +-4.49871138540557e+02, -2.52312048892090e+03, 1.32625144260466e+05, 3.06969268258018e+04, -4.49871138540557e+02, +3.06969268258018e+04, 9.73328439544417e+03, 7.14542193726142e+01, -2.51059022195162e+03, -4.45707315648109e+02, +-2.51059022195162e+03, 1.31725121858293e+05, 3.03982343023557e+04, -4.45707315648109e+02, 3.03982343023557e+04, +9.63426538045099e+03, 7.17173712500403e+01, -2.52853009361454e+03, -4.51387202395614e+02, -2.52853009361454e+03, +1.32947322346995e+05, 3.07849425803032e+04, -4.51387202395614e+02, 3.07849425803032e+04, 9.75654521550635e+03, +7.13397903598623e+01, -2.50367668307718e+03, -4.43780796295885e+02, -2.50367668307718e+03, 1.31316039673174e+05, +3.02871267770863e+04, -4.43780796295885e+02, 3.02871267770863e+04, 9.60507578489480e+03, 7.16284023743726e+01, +-2.52312048892090e+03, -4.49871138540557e+02, -2.52312048892090e+03, 1.32625144260466e+05, 3.06969268258018e+04, +-4.49871138540557e+02, 3.06969268258018e+04, 9.73328439544417e+03, 7.17173712500403e+01, -2.52853009361454e+03, +-4.51387202395614e+02, -2.52853009361454e+03, 1.32947322346995e+05, 3.07849425803032e+04, -4.51387202395614e+02, +3.07849425803032e+04, 9.75654521550635e+03, 7.16710713198111e+01, -2.52573070067885e+03, -4.50606442636248e+02, +-2.52573070067885e+03, 1.32781494044471e+05, 3.07398403283963e+04, -4.50606442636248e+02, 3.07398403283963e+04, +9.74467038334772e+03, 7.15606681734130e+01, -2.51709574131215e+03, -4.47537799671650e+02, -2.51709574131215e+03, +1.32114351088358e+05, 3.05049122340595e+04, -4.47537799671650e+02, 3.05049122340595e+04, 9.66251566587135e+03, +7.20599789459506e+01, -2.55313874565528e+03, -4.59556960113458e+02, -2.55313874565528e+03, 1.34713060511518e+05, +3.13706229849691e+04, -4.59556960113458e+02, 3.13706229849691e+04, 9.95066213492394e+03, 7.21077066487011e+01, +-2.55602963410779e+03, -4.60364974009307e+02, -2.55602963410779e+03, 1.34884693976456e+05, 3.14174360586732e+04, +-4.60364974009307e+02, 3.14174360586732e+04, 9.96303528385313e+03, 7.21519726957500e+01, -2.55874131891803e+03, +-4.61130151547202e+02, -2.55874131891803e+03, 1.35047449126020e+05, 3.14622215789001e+04, -4.61130151547202e+02, +3.14622215789001e+04, 9.97496385885763e+03, 7.21077066487011e+01, -2.55602963410779e+03, -4.60364974009307e+02, +-2.55602963410779e+03, 1.34884693976456e+05, 3.14174360586732e+04, -4.60364974009307e+02, 3.14174360586732e+04, +9.96303528385313e+03, 7.21519726957500e+01, -2.55874131891803e+03, -4.61130151547202e+02, -2.55874131891803e+03, +1.35047449126020e+05, 3.14622215789001e+04, -4.61130151547202e+02, 3.14622215789001e+04, 9.97496385885763e+03, +7.20599789459506e+01, -2.55313874565528e+03, -4.59556960113458e+02, -2.55313874565528e+03, 1.34713060511518e+05, +3.13706229849691e+04, -4.59556960113458e+02, 3.13706229849691e+04, 9.95066213492394e+03, 7.21077066487011e+01, +-2.55602963410779e+03, -4.60364974009307e+02, -2.55602963410779e+03, 1.34884693976456e+05, 3.14174360586732e+04, +-4.60364974009307e+02, 3.14174360586732e+04, 9.96303528385313e+03, 6.90490563878541e+09, -2.07084797382156e+10, +-2.04370341173281e+08, -2.07084797382156e+10, 6.21068506230647e+10, 6.12955410024854e+08, -2.04370341173281e+08, +6.12955410024854e+08, 6.05853004903601e+06, 6.92556238877561e+09, -1.38449106490062e+10, -6.70783655139184e+07, +-1.38449106490062e+10, 2.76775202076297e+10, 1.34125920435370e+08, -6.70783655139184e+07, 1.34125920435370e+08, +6.59292043831812e+05, 4.34188411442884e+08, -1.30102868122202e+09, -1.24709116044474e+07, -1.30102868122202e+09, +3.89859877432360e+09, 3.73974929825461e+07, -1.24709116044474e+07, 3.73974929825461e+07, 3.67773532597424e+05, +7.20599789459506e+01, -2.55313874565528e+03, -4.59556960113458e+02, -2.55313874565528e+03, 1.34713060511518e+05, +3.13706229849691e+04, -4.59556960113458e+02, 3.13706229849691e+04, 9.95066213492394e+03, 7.21077066487011e+01, +-2.55602963410779e+03, -4.60364974009307e+02, -2.55602963410779e+03, 1.34884693976456e+05, 3.14174360586732e+04, +-4.60364974009307e+02, 3.14174360586732e+04, 9.96303528385313e+03, 6.90490563878544e+09, -2.07084797382157e+10, +-2.04370341173281e+08, -2.07084797382157e+10, 6.21068506230649e+10, 6.12955410024856e+08, -2.04370341173281e+08, +6.12955410024856e+08, 6.05853004903603e+06, 7.21077066487011e+01, -2.55602963410779e+03, -4.60364974009307e+02, +-2.55602963410779e+03, 1.34884693976456e+05, 3.14174360586732e+04, -4.60364974009307e+02, 3.14174360586732e+04, +9.96303528385313e+03, 7.21519726957500e+01, -2.55874131891803e+03, -4.61130151547202e+02, -2.55874131891803e+03, +1.35047449126020e+05, 3.14622215789001e+04, -4.61130151547202e+02, 3.14622215789001e+04, 9.97496385885763e+03, +6.92556238877562e+09, -1.38449106490062e+10, -6.70783655139185e+07, -1.38449106490062e+10, 2.76775202076297e+10, +1.34125920435370e+08, -6.70783655139185e+07, 1.34125920435370e+08, 6.59292043831812e+05, 4.34188411442884e+08, +-1.30102868122202e+09, -1.24709116044475e+07, -1.30102868122202e+09, 3.89859877432360e+09, 3.73974929825461e+07, +-1.24709116044475e+07, 3.73974929825461e+07, 3.67773532597424e+05, 7.20599789459506e+01, -2.55313874565528e+03, +-4.59556960113458e+02, -2.55313874565528e+03, 1.34713060511518e+05, 3.13706229849691e+04, -4.59556960113458e+02, +3.13706229849691e+04, 9.95066213492394e+03, 7.21077066487011e+01, -2.55602963410779e+03, -4.60364974009307e+02, +-2.55602963410779e+03, 1.34884693976456e+05, 3.14174360586732e+04, -4.60364974009307e+02, 3.14174360586732e+04, +9.96303528385313e+03, 7.21519726957500e+01, -2.55874131891803e+03, -4.61130151547202e+02, -2.55874131891803e+03, +1.35047449126020e+05, 3.14622215789001e+04, -4.61130151547202e+02, 3.14622215789001e+04, 9.97496385885763e+03, +1.68875170442295e+10, -3.37686974671944e+10, -1.66461514824332e+08, -3.37686974671944e+10, 6.75248488600730e+10, +3.32890997035753e+08, -1.66461514824332e+08, 3.32890997035753e+08, 1.65076517420272e+06, 1.05878872896167e+09, +-3.17479128187170e+09, -3.11348038799466e+07, -3.17479128187170e+09, 9.51977152290754e+09, 9.33880238028146e+07, +-3.11348038799466e+07, 9.33880238028146e+07, 9.25475578371622e+05, 7.25606681734122e+01, -2.58752574147730e+03, +-4.70524858559379e+02, -2.58752574147730e+03, 1.37074736011625e+05, 3.21238907953198e+04, -4.70524858559379e+02, +3.21238907953198e+04, 1.01909205421797e+04, 1.68668602942393e+10, -5.05937320174801e+10, -5.02046860585566e+08, +-5.05937320174801e+10, 1.51760772437126e+11, 1.50596669023372e+09, -5.02046860585566e+08, 1.50596669023372e+09, +1.49535022983727e+07, 7.25606681734122e+01, -2.58752574147730e+03, -4.70524858559379e+02, -2.58752574147730e+03, +1.37074736011625e+05, 3.21238907953198e+04, -4.70524858559379e+02, 3.21238907953198e+04, 1.01909205421797e+04, +1.68875170442295e+10, -3.37686974671944e+10, -1.66461514824332e+08, -3.37686974671944e+10, 6.75248488600730e+10, +3.32890997035753e+08, -1.66461514824332e+08, 3.32890997035753e+08, 1.65076517420272e+06, 1.05878872896167e+09, +-3.17479128187170e+09, -3.11348038799466e+07, -3.17479128187170e+09, 9.51977152290754e+09, 9.33880238028146e+07, +-3.11348038799466e+07, 9.33880238028146e+07, 9.25475578371622e+05, 7.25606681734122e+01, -2.58752574147730e+03, +-4.70524858559379e+02, -2.58752574147730e+03, 1.37074736011625e+05, 3.21238907953198e+04, -4.70524858559379e+02, +3.21238907953198e+04, 1.01909205421797e+04, 1.68668602942393e+10, -5.05937320174801e+10, -5.02046860585566e+08, +-5.05937320174801e+10, 1.51760772437126e+11, 1.50596669023372e+09, -5.02046860585566e+08, 1.50596669023372e+09, +1.49535022983727e+07, 1.68875170442295e+10, -3.37686974671944e+10, -1.66461514824332e+08, -3.37686974671944e+10, +6.75248488600730e+10, 3.32890997035753e+08, -1.66461514824332e+08, 3.32890997035753e+08, 1.65076517420272e+06, +1.05878872896167e+09, -3.17479128187170e+09, -3.11348038799466e+07, -3.17479128187170e+09, 9.51977152290754e+09, +9.33880238028146e+07, -3.11348038799466e+07, 9.33880238028146e+07, 9.25475578371622e+05, 7.25606681734122e+01, +-2.58752574147730e+03, -4.70524858559379e+02, -2.58752574147730e+03, 1.37074736011625e+05, 3.21238907953198e+04, +-4.70524858559379e+02, 3.21238907953198e+04, 1.01909205421797e+04, 1.68668602942393e+10, -5.05937320174801e+10, +-5.02046860585566e+08, -5.05937320174801e+10, 1.51760772437126e+11, 1.50596669023372e+09, -5.02046860585566e+08, +1.50596669023372e+09, 1.49535022983727e+07, 1.68668602942393e+10, -5.05937320174801e+10, -5.02046860585566e+08, +-5.05937320174801e+10, 1.51760772437126e+11, 1.50596669023372e+09, -5.02046860585566e+08, 1.50596669023372e+09, +1.49535022983727e+07, 7.25606681734122e+01, -2.58752574147730e+03, -4.70524858559379e+02, -2.58752574147730e+03, +1.37074736011625e+05, 3.21238907953198e+04, -4.70524858559379e+02, 3.21238907953198e+04, 1.01909205421797e+04, +1.68875170442295e+10, -3.37686974671944e+10, -1.66461514824332e+08, -3.37686974671944e+10, 6.75248488600730e+10, +3.32890997035753e+08, -1.66461514824332e+08, 3.32890997035753e+08, 1.65076517420272e+06, 1.05878872896167e+09, +-3.17479128187170e+09, -3.11348038799466e+07, -3.17479128187170e+09, 9.51977152290754e+09, 9.33880238028146e+07, +-3.11348038799466e+07, 9.33880238028146e+07, 9.25475578371622e+05, 7.25606681734122e+01, -2.58752574147730e+03, +-4.70524858559379e+02, -2.58752574147730e+03, 1.37074736011625e+05, 3.21238907953198e+04, -4.70524858559379e+02, +3.21238907953198e+04, 1.01909205421797e+04 }; + + +static double MPT_FTB[] = { +-8.05605458077565e-15, 5.59131837304573e-13, 1.80056114992191e-13, -4.68798055449167e+01, 3.21315864449584e+03, +1.02291527376649e+03, -4.43029134198193e+01, 3.08078971332427e+03, 9.93842088508934e+02, -4.18057032624295e+01, +2.95131610119027e+03, 9.65286219315282e+02, 4.18057032624295e+01, -2.95131610119026e+03, -9.65286219315281e+02, +4.43029134198192e+01, -3.08078971332427e+03, -9.93842088508933e+02, 4.68798055449166e+01, -3.21315864449584e+03, +-1.02291527376649e+03, -9.41517226522473e+01, 6.49888703832065e+03, 2.08242581076276e+03, -9.14903246734103e+01, +6.35944032255528e+03, 2.05108424852741e+03, -4.92761538676091e+00, 2.54363054852858e+02, 5.60146147616943e+01, +-8.66690534111496e+01, 5.94032792886667e+03, 1.89111489407109e+03, -8.87578251492275e+01, 6.21769001556242e+03, +2.01940331086910e+03, -7.71140778035309e+01, 5.44394667926879e+03, 1.78055027926898e+03, 4.92761538676092e+00, +-2.54363054852860e+02, -5.60146147616945e+01, 7.71140778035309e+01, -5.44394667926879e+03, -1.78055027926898e+03, +8.87578251492275e+01, -6.21769001556242e+03, -2.01940331086910e+03, 9.14903246734103e+01, -6.35944032255527e+03, +-2.05108424852741e+03, 9.41517226522473e+01, -6.49888703832064e+03, -2.08242581076276e+03, 8.66690534111496e+01, +-5.94032792886667e+03, -1.89111489407109e+03, -1.41686417359751e+02, 9.84987101529704e+03, 3.17703705596482e+03, +-1.36284263586377e+02, 9.38788534499566e+03, 3.00250392184130e+03, 3.07636645163685e+01, -2.26286432154820e+03, +-7.66586587439221e+02, -4.48814320642742e+01, 2.99500123398400e+03, 9.29157534561802e+02, -1.26151118226851e+02, +8.85629681498341e+03, 2.88205514988715e+03, -3.07636645163686e+01, 2.26286432154820e+03, 7.66586587439223e+02, +4.48814320642743e+01, -2.99500123398400e+03, -9.29157534561802e+02, 1.26151118226851e+02, -8.85629681498341e+03, +-2.88205514988715e+03, 1.41686417359751e+02, -9.84987101529704e+03, -3.17703705596482e+03, 1.36284263586377e+02, +-9.38788534499566e+03, -3.00250392184130e+03, -1.81507160532652e+02, 1.26570558125230e+04, 4.09401429832584e+03, +-1.83836127031099e+02, 1.27807891894732e+04, 4.12250076433908e+03, -1.86242314722871e+02, 1.29074827345876e+04, +4.15154645015788e+03, -9.45911286774820e+01, 6.45056002002798e+03, 2.04355568308254e+03, -1.77964157405335e+02, +1.22840501809709e+04, 3.93614053257858e+03, 8.00652224183517e+01, -5.69202827522423e+03, -1.87305557707539e+03, +-9.10798973988604e+00, 4.73573326632084e+02, 1.05647485179692e+02, -1.67357245940145e+02, 1.17237156942816e+04, +3.80765649090779e+03, -8.00652224183517e+01, 5.69202827522423e+03, 1.87305557707539e+03, 9.10798973988597e+00, +-4.73573326632080e+02, -1.05647485179690e+02, 9.45911286774820e+01, -6.45056002002798e+03, -2.04355568308254e+03, +1.67357245940145e+02, -1.17237156942816e+04, -3.80765649090779e+03, 1.81507160532652e+02, -1.26570558125230e+04, +-4.09401429832584e+03, 1.86242314722871e+02, -1.29074827345876e+04, -4.15154645015788e+03, 1.83836127031099e+02, +-1.27807891894732e+04, -4.12250076433908e+03, 1.77964157405335e+02, -1.22840501809709e+04, -3.93614053257858e+03, +-2.25440645809987e+02, 1.57128441178726e+04, 5.08000827366132e+03, -2.27949464065132e+02, 1.58457953911659e+04, +5.11081702294652e+03, -2.30386967422598e+02, 1.59761886991473e+04, 5.14118675350658e+03, -5.85898470742200e+01, +3.91423176321482e+03, 1.21552090800639e+03, -1.36627356332769e+02, 9.37269927460101e+03, 2.98592905209242e+03, +1.21787754482915e+02, -8.59403399472578e+03, -2.80942939289517e+03, 4.00594158343802e+01, -2.94522010407859e+03, +-9.97172814137473e+02, -1.38099888261447e+14, 4.14174873691750e+14, 4.08745050216372e+12, 1.38513086197767e+14, +-2.76901840941826e+14, -1.34157625081743e+12, 8.68422702246574e+12, -2.60219025697909e+13, -2.49422570813564e+11, +-1.21787754482915e+02, 8.59403399472578e+03, 2.80942939289517e+03, -4.00594158343802e+01, 2.94522010407859e+03, +9.97172814137474e+02, 1.38099888261447e+14, -4.14174873691752e+14, -4.08745050216373e+12, 5.85898470742200e+01, +-3.91423176321481e+03, -1.21552090800639e+03, 1.36627356332768e+02, -9.37269927460100e+03, -2.98592905209242e+03, +-1.38513086197767e+14, 2.76901840941826e+14, 1.34157625081743e+12, -8.68422702246575e+12, 2.60219025697909e+13, +2.49422570813564e+11, 2.25440645809987e+02, -1.57128441178726e+04, -5.08000827366132e+03, 2.27949464065132e+02, +-1.58457953911659e+04, -5.11081702294652e+03, 2.30386967422598e+02, -1.59761886991473e+04, -5.14118675350658e+03, +3.37752169788694e+14, -6.75377558269406e+14, -3.32923914207006e+12, 2.11762303371482e+13, -6.34971454758913e+13, +-6.22700325612978e+11, -2.74007406789879e+02, 1.90483762509912e+04, 6.14389236195167e+03, -3.37339032442710e+14, +1.01188007249046e+15, 1.00409824165146e+13, -1.00669299967588e+02, 6.84017335886086e+03, 2.15935909293708e+03, +-3.37752188824995e+14, 6.75377596341774e+14, 3.32923933198134e+12, -2.11762351037775e+13, 6.34971597754866e+13, +6.22700468046233e+11, 8.19209080207830e+01, -5.85600607732762e+03, -1.93612216083708e+03, -3.37339013406409e+14, +1.01188001538273e+15, 1.00409818476845e+13, 3.37752188824995e+14, -6.75377596341774e+14, -3.32923933198134e+12, +2.11762351037775e+13, -6.34971597754866e+13, -6.22700468046233e+11, -8.19209080207830e+01, 5.85600607732762e+03, +1.93612216083708e+03, 3.37339013406409e+14, -1.01188001538273e+15, -1.00409818476845e+13, 3.37339032442710e+14, +-1.01188007249046e+15, -1.00409824165146e+13, 1.00669299967588e+02, -6.84017335886085e+03, -2.15935909293708e+03, +-3.37752169788694e+14, 6.75377558269406e+14, 3.32923914207006e+12, -2.11762303371482e+13, 6.34971454758913e+13, +6.22700325612978e+11, 2.74007406789879e+02, -1.90483762509912e+04, -6.14389236195167e+03 }; + + +static double MPT_GTB[] = { +1.38839534395118e-28, 9.29181193830142e+02, 9.27618502326520e+02, 9.26143841984272e+02, 9.26143841984272e+02, +9.27618502326520e+02, 9.29181193830141e+02, 1.91726036826763e+03, 1.91400772930451e+03, 1.80013368304751e+03, +1.89761877895855e+03, 1.91079624039577e+03, 1.88726088427886e+03, 1.80013368304751e+03, 1.88726088427886e+03, +1.91079624039577e+03, 1.91400772930451e+03, 1.91726036826763e+03, 1.89761877895855e+03, 2.96487773718597e+03, +2.93839767872187e+03, 2.71579208345996e+03, 2.72289651693873e+03, 2.92130491017648e+03, 2.71579208345996e+03, +2.72289651693873e+03, 2.92130491017648e+03, 2.96487773718597e+03, 2.93839767872187e+03, 4.03104619266734e+03, +4.03643674719890e+03, 4.04195854495571e+03, 3.70702252103140e+03, 4.00105535644843e+03, 3.69048448682912e+03, +3.60044921987433e+03, 3.97801730759914e+03, 3.69048448682912e+03, 3.60044921987433e+03, 3.70702252103140e+03, +3.97801730759914e+03, 4.03104619266734e+03, 4.04195854495571e+03, 4.03643674719890e+03, 4.00105535644843e+03, +5.14912769646405e+03, 5.15605574970951e+03, 5.16295709501648e+03, 4.53713700816493e+03, 4.72349661064329e+03, +4.69886271940627e+03, 4.52526974024475e+03, 6.90508325995579e+17, 6.92574630357956e+17, 4.34234363379789e+16, +4.69886271940627e+03, 4.52526974024475e+03, 6.90508325995581e+17, 4.53713700816493e+03, 4.72349661064329e+03, +6.92574630357955e+17, 4.34234363379790e+16, 5.14912769646405e+03, 5.15605574970951e+03, 5.16295709501648e+03, +1.68877000072184e+18, 1.05883437732929e+17, 6.32686936869674e+03, 1.68670430226289e+18, 5.51441667719108e+03, +1.68877019108485e+18, 1.05883485399220e+17, 5.49245151643963e+03, 1.68670411189984e+18, 1.68877019108485e+18, +1.05883485399220e+17, 5.49245151643963e+03, 1.68670411189984e+18, 1.68670430226289e+18, 5.51441667719108e+03, +1.68877000072184e+18, 1.05883437732929e+17, 6.32686936869674e+03 }; + + + +/* main evaluation function using sequential search */ +static unsigned long ectrl( double *X, double *U) + +{ + int ix, jx, ic, nc, isinside; + unsigned long ireg, abspos, iregmin, region; + double hx, sx, obj, objmin; + + abspos = 0; + region = 0; + iregmin = 0; + + /* initialize values of the tie-break function */ + obj = 0; + objmin = DBL_MAX; + + + for (ireg=0; ireg MPT_ABSTOL) { + /* constraint is violated, continue with next region */ + isinside = 0; + break; + } + } + if (isinside==1) { + /* state belongs to this region, evaluate the tie-breaking function */ + obj = 0; + for (ix=0; ix +#include "mex.h" +#include "ectrl.c" + +#ifndef MPT_RANGE +#define MPT_RANGE 1 +#endif + + +void mexFunction( int nlhs, mxArray *plhs[], + int nrhs, const mxArray*prhs[] ) + +{ + int j; + double *xin, *uout; + char msg[70]; + unsigned long region; + + mwSize M,N,D; + + /* Check for proper number of arguments */ + + if (nrhs != 1) { + mexErrMsgTxt("One input arguments required."); + } else if (nlhs > 1) { + mexErrMsgTxt("Too many output arguments."); + } + if (mxIsEmpty(prhs[0])) + mexErrMsgTxt("The argument must not be empty."); + if ( !mxIsDouble(prhs[0]) || mxIsComplex(prhs[0]) ) + mexErrMsgTxt("The argument must be real and of type DOUBLE."); + if ( mxGetNumberOfDimensions(prhs[0])!=2 ) + mexErrMsgTxt("The argument must be a vector"); + + M = mxGetM(prhs[0]); + N = mxGetN(prhs[0]); + if ( (M!=1) && (N!=1) ) + mexErrMsgTxt("The argument must be a vector."); + + /* dimension */ + D = mxGetNumberOfElements(prhs[0]); + if (D!=MPT_DOMAIN) { + sprintf(msg, "The size of the input argument must be %d x 1.",MPT_DOMAIN); + mexErrMsgTxt(msg); + } + + /* get and verify input data */ + xin = mxGetPr(prhs[0]); + for (j=0; j PWM duty 8-bit + analogWrite(BICOP_UPIN2, sq(AutomationShield.constrainFloat(voltageValueM2, 0.0, 3.7)) * 255.0 / sq(3.7)); + } + + float BicopClass::sensorRead(void) { // Read relative angle in percentage. Maximum angle defined by the argument. Default maximum 90 degrees. + if (wasCalibrated) return as5600.readAngleDeg(); //AutomationShield.mapFloat(as5600.readAngleDeg(), -maximumDegrees, maximumDegrees, -100.0, 100.0); // Relative angle degrees to percentage conversion. + else { + AutomationShield.serialPrint("The device was *not calibrated*, please run the calibration() method."); + return -1; + } + } + + float BicopClass::sensorReadDegree() { + if (wasCalibrated) return as5600.readAngleDeg(); // Read relative angle in degrees + else { + AutomationShield.serialPrint("The device was *not calibrated*, please run the calibration() method."); + return -1; + } + } + + uint16_t BicopClass::sensorReadDegreeAbsolute() { + return as5600.readAngleReg(); // Read absolute angle in degrees + // if(wasCalibrated) + // else{ + // AutomationShield.serialPrint("The device was *not calibrated*, please run the calibration() method."); + // return -1; + // } + } + + float BicopClass::sensorReadRadian() { + if (wasCalibrated) return as5600.readAngleRad(); // Read relative angle in radians + else { + AutomationShield.serialPrint("The device was *not calibrated*, please run the calibration() method."); + return -1; + } + } + + + + word BicopClass::getRawAngle() // Function for getting raw pendulum angle data 0-4096 + { + return as5600.readAngleReg(); + } + + //BoB commands + void BicopClass::TOFinitialize() { + sens.begin(); +# if ECHO_TO_SERIAL + Serial.println("Adafruit VL6180x test!"); + if (!sens.begin()) { + Serial.println("Failed to find sensor"); + while (1); + } + Serial.println("Sensor found!"); +# endif + } + + //values from sensor in % - for possible future use + float BicopClass::TOFsensorReadPerc() { + range = sens.readRange(); + + if (range < minCalibrated) { range = minimum; } + else if (range > maxCalibrated) { range = maximum; } + + + posperc = map(range, minimum, maximum, 0, 100); + return posperc; //returns the ball distance in 0 - 100 % + } + + // returns the corrected value of sensor + float BicopClass::TOFsensorRead() { + if (calibrated == 1) { // if calibration function was already processed (calibrated flag ==1) + pos = sens.readRange(); + ballPos = pos - minCalibrated; //set actual position to position - calibrated minimum + } + else if (calibrated == 0) { // if calibration function was not processed (calibrated flag ==0) + pos = sens.readRange(); + ballPos = pos - MIN_CALIBRATED_DEFAULT; //set actual position to position - predefined value + } +# if ECHO_TO_SERIAL + Serial.print("pos :"); Serial.print(pos); Serial.print(" "); + Serial.print("ballPos :"); Serial.print(ballPos); Serial.print(" "); +# endif + return ballPos; + } + + float BicopClass::deg2rad(float u) { + u = u * (3.14 / 180.0); + return u; + } + + float BicopClass::rad2deg(float u) { + u = u * (180.0 / 3.14); + return u; + } + + + // check minimal and maximal value of sensor for BoB + void BicopClass::TOFcalibration() + { + short calmeasure; // Temporary measurement value +# if ECHO_TO_SERIAL + Serial.println("Calibration is running..."); +# endif + + + analogWrite(BICOP_UPIN2, 0); + analogWrite(BICOP_UPIN1, 150); + delay(1000); + + + for (int i = 1; i <= 100; i++) { // Perform 100 measurements + calmeasure = sens.readRange(); // Measure + if (calmeasure < minCalibrated) { // If lower than already + minCalibrated = calmeasure; // Save new minimum + } + + delay(10); // Measure for one second + } + + analogWrite(BICOP_UPIN2, 150); + analogWrite(BICOP_UPIN1, 0); + delay(1000); + + for (int i = 1; i <= 100; i++) { // Perform 100 measurements + calmeasure = sens.readRange(); // Measure + if (calmeasure > maxCalibrated) { // If lower than already + maxCalibrated = calmeasure; // Save new maximum + } + + delay(10); // Measure for one second + } + delay(500); + +# if ECHO_TO_SERIAL //if user sets ECHO_TO_SERIAL flag than print + Serial.print("Measured maximum is: "); + Serial.print(maxCalibrated); + Serial.println(" mm"); + Serial.print("Measured minimum is: "); + Serial.print(minCalibrated); + Serial.println(" mm"); +# endif + calibrated = 1; + } + + + //end BoB Commands + + BicopClass BicopShield; + \ No newline at end of file diff --git a/src/BicopShield.h b/src/BicopShield.h new file mode 100644 index 00000000..21ffc4b7 --- /dev/null +++ b/src/BicopShield.h @@ -0,0 +1,99 @@ +/* + API for the BiCopShield hardware. + + The file is a part of the application programming interface for + the BiCopShield didactic tool for control engineering and + mechatronics education. The BiCopShield implements an air-based, + pendulum angle positioning experiment on an Arduino microcontroller. + + This code is part of the AutomationShield hardware and software + ecosystem. Visit http://www.automationshield.com for more + details. This code is licensed under a Creative Commons + Attribution-NonCommercial 4.0 International License. + + Created by Martin Nemcek, Jan Boldocky + Last update: 20.5.2024 +*/ + +// Defining c++ library used by the BiCopShield + +#ifndef BICOPSHIELD_H // Include guard +#define BICOPSHIELD_H + +// Defining libraries used by the BiCopShield +#include "AutomationShield.h" // Include the main library +#include // Include I2C protocol library +#include // Required Arduino API in libraries +#include "lib/BasicLinearAlgebra/BasicLinearAlgebra.h" // Basic Linear Algebra library +#include "AS5600_AS.h" // Include Hall sensor library +#include "lib/Adafruit_VL6180X/Adafruit_VL6180X.h" // Include TOF sensor library + + +#ifndef SHIELDRELEASE + #define SHIELDRELEASE 1 // Use number only: e.g. for R3 is 3 +#endif + +// Defining pins used by the BiCopShield +#define BICOP_RPIN A3 // Input from potentiometer +#define BICOP_VOLTAGE_SENSOR_PIN A2 // Input pin for measuring Volt +#define BICOP_UPIN1 5 // Motor (Actuator) +#define BICOP_UPIN2 6 // Motor 2 (Actuator) +#define MIN_CALIBRATED_DEFAULT 7 // Minimum ball distance +#define ZERO_COMPENSATION 0 +class BicopClass{ // Class for the BiCopShield device + + public: + #include "getGainLQ.inl" + #include "getKalmanEstimate.inl" + float begin(void); // Board initialisation - initialisation of pin modes and variables + void actuatorWrite(float inputPercentageM1, float inputPercentageM2); // Write actuator - function takes input 0.0-100.0% and sets motor speed accordingly + void actuatorWriteVolt(float inputVoltageM1, float inputVoltageM2); + bool calibrate(void); // sensor calibration + float referenceRead(void); // Read value of potentiometer and converts it to percentual value + + uint16_t sensorReadDegreeAbsolute(); + float sensorRead(void); + float sensorReadDegree(void); // Measure pendulum angle in degrees + float sensorReadRadian(void); // Measure pendulum angle in radians + word getRawAngle(); // AS5600 angle value + // BoB + Adafruit_VL6180X sens = Adafruit_VL6180X(); //symbolic name for sensor library + void TOFinitialize(); // sets up the TOF sensor - required to run in setup! + void TOFcalibration(); + float TOFsensorReadPerc(); + float TOFsensorRead(); + float deg2rad(float u); + float rad2deg(float u); + + private: + //int startAngle = -1; // Variable for storing zero angle position + bool wasCalibrated = false; + + int _ams5600_Address = 0x36; // AS5600 address + int _stat = 0x0b; // AS5600 communication variable + int _raw_ang_hi = 0x0c; // AS5600 communication variable + int _raw_ang_lo = 0x0d; // AS5600 communication variable + + float _min_angle = 10; // minimal measured angle in negative direction (relative to zero position) + float _max_angle = 280; // maximal measured angle in positive direction (relative to zero position) + + //BoB private + float _referenceRead; + float _referenceValue; + uint8_t range; + float _servoValue, pos, posCal, position, ballPos; + int posperc; + float maxRange, minRange; + byte calibrated = 0; + float minCalibrated = 0; // Actual minimum value + float maxCalibrated = 100; // Actual maximum value + float minimum; + float maximum; + float deg; + //BoB end + + AS5600 as5600; +}; +extern BicopClass BicopShield; + +#endif \ No newline at end of file