From 417a8f8ef4c704e9029835387a45de71090f9d79 Mon Sep 17 00:00:00 2001 From: NemcekMartin <127301773+NemcekMartin@users.noreply.github.com> Date: Tue, 28 May 2024 15:58:43 +0200 Subject: [PATCH] BicopShield First upload --- .../BicopShield_EMPC/BicopShield_EMPC.ino | 152 + examples/BicopShield/BicopShield_EMPC/ectrl.h | 1368 + .../BicopShield_LQ/BicopShield_LQ.ino | 125 + .../BicopShield_PID/BicopShield_PID.ino | 78 + .../BicopShield_TOF_PID.ino | 97 + .../BicopShield_EMPC_Export.m | 51 + .../BicopShield_EMPC_Simulation.m | 175 + .../BicopShield/BicopShield_EMPC/ectrl.h | 1368 + .../BicopShield_GreyboxModel_LinearSS.mat | Bin 0 -> 5152 bytes .../BicopShield_Ident/BicopShield_Ident.m | 85 + .../BicopShield/BicopShield_Ident/pid1.csv | 23999 ++++++++++++++++ .../BicopShield_LQI/BicopShield_LQI.m | 84 + .../BicopShield_PID/BicopShield_PID.m | 78 + .../BicopShield/BicopShield_PID/pid1.csv | 23999 ++++++++++++++++ simulink/BicopLibrary.slx | Bin 0 -> 131800 bytes simulink/BicopLibrary.slx.r2021a | Bin 0 -> 91314 bytes simulink/assets/BiCop.svg | 137 + simulink/assets/Fan_u1.svg | 45 + simulink/assets/Fan_u2.svg | 45 + .../examples/BicopShield/BicopShield_EMPC.slx | Bin 0 -> 56190 bytes .../BicopShield/BicopShield_EMPC/ectrl.c | 1223 + .../BicopShield/BicopShield_EMPC/ectrl_mex.c | 105 + .../BicopShield_EMPC/ectrl_sfunc.c | 134 + .../BicopShield_EMPC/ectrl_sfunc.mexw64 | Bin 0 -> 64000 bytes .../examples/BicopShield/BicopShield_LQI.slx | Bin 0 -> 48568 bytes .../BicopShield/BicopShield_LQI_Kalman.slx | Bin 0 -> 42293 bytes .../BicopShield/BicopShield_OpenLoop.slx | Bin 0 -> 30756 bytes .../examples/BicopShield/BicopShield_PID.slx | Bin 0 -> 41472 bytes src/BicopShield.cpp | 223 + src/BicopShield.h | 99 + 30 files changed, 53670 insertions(+) create mode 100644 examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC.ino create mode 100644 examples/BicopShield/BicopShield_EMPC/ectrl.h create mode 100644 examples/BicopShield/BicopShield_LQ/BicopShield_LQ.ino create mode 100644 examples/BicopShield/BicopShield_PID/BicopShield_PID.ino create mode 100644 examples/BicopShield/BicopShield_TOF_PID/BicopShield_TOF_PID.ino create mode 100644 matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC_Export.m create mode 100644 matlab/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC_Simulation.m create mode 100644 matlab/examples/BicopShield/BicopShield_EMPC/ectrl.h create mode 100644 matlab/examples/BicopShield/BicopShield_Ident/BicopShield_GreyboxModel_LinearSS.mat create mode 100644 matlab/examples/BicopShield/BicopShield_Ident/BicopShield_Ident.m create mode 100644 matlab/examples/BicopShield/BicopShield_Ident/pid1.csv create mode 100644 matlab/examples/BicopShield/BicopShield_LQI/BicopShield_LQI.m create mode 100644 matlab/examples/BicopShield/BicopShield_PID/BicopShield_PID.m create mode 100644 matlab/examples/BicopShield/BicopShield_PID/pid1.csv create mode 100644 simulink/BicopLibrary.slx create mode 100644 simulink/BicopLibrary.slx.r2021a create mode 100644 simulink/assets/BiCop.svg create mode 100644 simulink/assets/Fan_u1.svg create mode 100644 simulink/assets/Fan_u2.svg create mode 100644 simulink/examples/BicopShield/BicopShield_EMPC.slx create mode 100644 simulink/examples/BicopShield/BicopShield_EMPC/ectrl.c create mode 100644 simulink/examples/BicopShield/BicopShield_EMPC/ectrl_mex.c create mode 100644 simulink/examples/BicopShield/BicopShield_EMPC/ectrl_sfunc.c create mode 100644 simulink/examples/BicopShield/BicopShield_EMPC/ectrl_sfunc.mexw64 create mode 100644 simulink/examples/BicopShield/BicopShield_LQI.slx create mode 100644 simulink/examples/BicopShield/BicopShield_LQI_Kalman.slx create mode 100644 simulink/examples/BicopShield/BicopShield_OpenLoop.slx create mode 100644 simulink/examples/BicopShield/BicopShield_PID.slx create mode 100644 src/BicopShield.cpp create mode 100644 src/BicopShield.h diff --git a/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC.ino b/examples/BicopShield/BicopShield_EMPC/BicopShield_EMPC.ino new file mode 100644 index 00000000..7d1736e8 --- /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 3). + + 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..cf025668 --- /dev/null +++ b/examples/BicopShield/BicopShield_EMPC/ectrl.h @@ -0,0 +1,1368 @@ +/* + 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 129 +#define MPT_DOMAIN 3 +#define MPT_RANGE 6 +#define MPT_ABSTOL 1.000000e-08 + +const float MPT_A[] PROGMEM = { +-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[] PROGMEM = { +-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[] PROGMEM = { +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[] PROGMEM = { +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 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[] PROGMEM = { +-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..2cae3d9f --- /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,'AVR'); % 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/ectrl.h b/matlab/examples/BicopShield/BicopShield_EMPC/ectrl.h new file mode 100644 index 00000000..cf025668 --- /dev/null +++ b/matlab/examples/BicopShield/BicopShield_EMPC/ectrl.h @@ -0,0 +1,1368 @@ +/* + 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 129 +#define MPT_DOMAIN 3 +#define MPT_RANGE 6 +#define MPT_ABSTOL 1.000000e-08 + +const float MPT_A[] PROGMEM = { +-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[] PROGMEM = { +-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[] PROGMEM = { +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[] PROGMEM = { +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, +0.0000000e+00, 0.0000000e+00, 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[] PROGMEM = { +-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 0000000000000000000000000000000000000000..6e330b2611eeb66429dad382eb82651118be283a GIT binary patch literal 5152 zcmV+*6yNJjK~zjZLLfCRFd$7qR4ry{Y-KDUP;6mzW^ZzBIv`L(S4mDbG%O%Pa%Ew3 zWn>_4ZaN@TXmub>VR;}jGaxZHIy5jkG&vwLFfueCARr(hARr(hARr(hARr(hARr(h zARr(hARr(hARr(hARr(hARr*r00000000000ZB~{0000?0001Zoa19)U}ykhHX!Bz zVnGH7U<6`TAkNKCNzDQCSr~ks{ewYtW=e4}A5hE#Ngpp%A1jp41~r2bDh}dHK$v%# zkmNv^8;AjA00%`60000)6952soa|Uxa~#zbJ~NhN%eG{B0pm5sHjo%_3^w2dh$W8} zkF71zcp(9g+cQ_1wr9HAy$q5`!V-wd#=bq}2ZSmfQ+b0b9>`lrRUYy{Qv3wH!J9d! z@41>YS0me?DX3I&t4`hT+`fIjv-Rzs=>>qk3P2amYf!pDk51MzD4);jnMRg%$mGXJ z??vgKZQP%2alaA0-jQC*@Sd^U#I&*V&I#UkJT zcX5A%PwRiN{Gk0uH!UCcnoZ67v%J=U^Bm<2H-3upG8*_4Z(iur*UdQNgsyY3s)}$r zcB^hY52qs)4mz;|c`r!fai@mY9B&??ICQ;Py?WYn<04EX@!}4R^?H6{+P#Wv1-GX3 z3fU{dxkEX>UV!O1OiFPQDj0w<*K=!0tq5bzoCd?8!ds_H4*8_*oN=lNPC8#+Ze)#axm_@kxH4pl0qx73a6b~fL>rwW_bz4w9kWsX#L1p<<3@O1SkB^y^7usB(a}IFA9}VMHRnVhCw$9s?I#+iV_1u zVd#gA%cHKRoN(H&)>Vie7tyg=&GE`lFpc1a@>+E4Zn#91| zQk-UHRAJGhSho;n?qb?R4X1)|8l5Ut##CJK%f&@q2cOnGk4|y<2Fi6JEH47NIl>hB z8Xb(%br|s`U9XOHMh`r64b$a1)e+Ar_*FDYzK@QfS7Ds?P^zeaNRMMROWG=G!-Ehk*MiWmtC~ViGB~BmNqRqeh-;B9LBoeBHJem1 znO9TO*mNq28^IX2v7{zTI@S2N;qig=MHrfkL&v0HN(Fuxk}S`dFs>3o5L+p7u`G3!TJ5Ce=9N<-&ZRL<_UIK}Bs@h%mA; zog8V4q4y)9o0hyjT=LR>OCM{wkWw4!@#af4R*vRjTK-LNB}p9JQ#VP)KpRa69h z4&kliepsVyrXHpaFEhFX-iC6A(08Nk68haJcM1JLlm~=<3gx7wpBDNPDCdM;v2?Om zv;2!%_-x)sG_SIBdtPnn-Io5Sr9WorZ&~`=mi~^Vzia95wea7JbuHrB3yt>}fPAMm zuV=+9*H?*Iu6Kxet;I_=c8WdH)<$7d+UgQMn9<2%@3+4<%vjB0?_a|{+WWg%?ESQN zeT)6;SnU0@x3|Uq9u}FmPM$Yd>*l%XYhj;kZ*F0qY-|!X%^(|FK*ucy<$f#Z9LYg8 zZinV)7nt)lXnY@;LAH0auuprpx3EvPx3#cOzR>v~^I-1XWvv^o-PXGC?FZJn>B&9T zx_L(K6lh%)geg=^Mi9SqQ&^;xT>|#b^8)O2GJa zlq-ziKnWSY$#zVC(cH`Uag+m$hf(fjJc4o`;}aqU>W#Xa0W1Kjqx^u}(2-A;JHKaY!f`&1=!(D z37&f_p1Uoc9|@iVg6CerbD!Y3U+^3hJclfvA6q;R3ZBD)=ZN5WNbo!?cpecvKe2d@ zT0B1!JjVo2zu*}VJjVr3PVfv_JcFR0@q?`AIYz=KMf|7O-VxTvI4;8D92emUj*IXl z$3gh#BE~7ueNLEu0Gn@y0yMrC=sV|e#%DNw!e=>t!sj@C!cTDggnz;D6aFQ~PxwiW zm+(^}7w18r6NKsa^a$gN%tyEc`V2h5`UTDvVF#K=kI2o8$jz*Xufn{9UFIcxiER^p zfo&81E&D_GMfQjAOQ6pz!oLH3W)Z%|+=O3dZoUdfBS{1(5L>)a*M_<%25OusF z>KKYRBT>g#)G-lttcyB6E$TQY>NqdzcvaN#8Bxbyi8}sT)bTk{$LFm&{zlaCS@?e3 z%IFm{oe$<4zN1{vU#y`)`kS`E9-#zpcE_W8UZ6n0ND?`~Q}A z^BXz+UmBKwPGoPNV z;h)LNPG~($E|%tD;h33;e^T;qTFT!X&r*J)XH&^SCZpq$cJ2ITVQHQAEQw&@db7U& zqjsII-Ps%alcgsm1DTcZ_21yWuhXY1$>ZdK|19jd_RkNsws7pTf9*c_xAXt|(2mRe zpR-&a_aPd9_C3$t?038D(cV?iuD-L!!u9X_?#6!Gd3@{Sh0i|t;^SjR|K$4nm;U|N ze|)39I}YvZlXcMEzN0hU^xb#)y?9G~wL-rB8{GHp^wq**KQ#~i9{aj|m4o*6K@YUI zujv23mGsqD00030|Lj<8Y!pQpp8M#>LE1YTP!TjGifNRROEKCI<4rkQ+Vm<1rKCS< z+P%B2-Eg;i+1*w+u|b2zf7(CwBUT9-FeH2^8X8Pw)fkD<82mws0;&8Yejrh!h#xz5 zGu-TSd$+f@<^J?dCNuBsKJUEq%scPBxAg#kpx&zWR*QQiRahtD!o3go^$gDEHsaj4 z5u6)%O>w2H2Mgd_%z6kH$eV+tM|PqG?67_#JB^^Yu>10w_(vMZ`sMX{$=?UX%a$78ZDyYaCYSGO*%x`A_Xa2s$ot`K)5u4umeCj0VI_UbTS z`Exf4nO{h|PVB!1uV3kVbt`bN0M6RIx*95Ghvt^H<85l#ylUvj(D~1+FOUEC?P)9b zi1sI-YrBHZo%?d&>^)ir%T*TKzS219j`k7^!%-E*4s7qmZ~e*Q!_%loU8 zU6+Yn+D|L|dJOz}Kt>uV3peD-xcu%`<`PB5L zm)_BaCR}~JD^J4a%=c>t4j$4bj}7hcT|1y1UVq~3@Ba7UgM-Z{MR^yz-t>$5SodA9 z>5cBst_W+jL;Ke(ndxoN;I$*#Z=J2$i^pI1xOTh`j!#ZKmHZBBv9X_K&QCRJGnX!H zk%P@J^T=%Njgda>)Sk`{R@~SMkDjah2EMsfLp;9>j69Qllk;ME4p2N0u2_C(4oM^Y zG~PU=tD*UN@EG4rpU;S1?PBF)8j zu1gEzSX>&jW@jm5XDM+;5mIUFTrs|g&~~iu!_VOS*?mZ9#FMg4d`J-zmd?v-u;T^X zs4CgbbBe+%s)c=9tv@RL|CWtQw?1;2;1+Vda&a0c?cR}dK^XmFWr&?}^R-R9m(&+d z#BoV}Ych1I?pT4JIb{#c)nI$ICFa#y%0`4s#S$C<+wk+prIa9Y$x5C#uzTJaUY4BV z_YVBNQ}?`-yl;2C5emoFLoDA`@;hxOfOS2)3wlk%XaA3uSQnAsOY}dXLr|l<9M`KK z5Rnw6BQB!1dV1T*20NlRhizS9Y8b~uF+aUA|AO7`6AyH+l&&}T!Lc)+?7#b!ZrgSB zpR2$4`BA?=WEcO$GesYh^am*bmP*t?O+Cu( zvpej}CW42tcDr__pu4K+u3oaE=*5ET1d6-a1U90MPMzp$UbLzc{fs^l_HE@zAHuE@P zG`LEy2gHu#ym5q_c|(rmalna-IDQiRtbvz&5C{os9oLS)&m{0OFk-_!xVa) z2;4$>?>tKyuB`5|>W4BC;GE-T#XZn)<$dO><7UN*;{B1B0ARG=x=lTsauy(|{~UOs z;zzfh#I7o!>%9UfUh>b6Z+|Ik&t6o|ijsF(v=d6+d@0@j z#{E)m3%Q#%0$5kiSD8yFa;CZ8kafRD*k?uQ_XYL-G~$vz|NYkeTw>j0zM|eYh0|a`Vs3pX{=B3jk_N9iHm6pIaNcBY&{{vvYCqrwQR&uF1xSp*0bX8 zeI@CBzGy8~CEW*Z<}3{Cg?wH};8o_kT4xIdyy<#A+rbm7RP%?!_52DX?Naiq82MJs zVOz*qv_wcJZs@*h)uHdwT7TAVqHSM$c{8=39(hsM3nzy7wC86VNFVP^b4!2Wpo zi;r#`n(Ry^FYH$sy=0$sfVh#drjdUrqo~DFURYlLDb(RBixr7Lry4fyyiOz4L0dE z>*riw9S+V9N-)XoBpsI5O*5}avoBf4%jyp=iPq)vs3~0`y4#?H$9ve1#b>n2_woMomOe8{K`I1bEA+jEL^#kVd_Y9U)1@=Qg1o z*k2kVIv9_zjvevB4mN5ba=>+Lhmja<%v}2X?EB31gDXpy|NQ;+OPTlc@B4rK z)ZXmmv4Q8F+hZnwC`EB%RPW!kX ztq)SxKjT>Lz~jImvVk_{LuU6AUym_GwV!0sKIr(^CXus_U%Z3KV8{s_EE7k(*q8Nx zz9FN~rh_$EQ~A%Q;%e4$5Bo3sF8}}l|NqTYy-ve05OzXS2vVyqNK6ozn5vG5sVEZA zA??tDx}h{NYNRHP9H&xw0v?IyU}E82@HLL&xS>+23|Kmyzl*>7i_aQDND~4}=R4SU zxeU0pxts_M%MdtUInNYY<(Yb!r=h>&_4IR= z>al=C7NHiSZj`(c8oFTVTVuj3oUkASUSI9A8duG;C*^x6Pp(t#i~4`MqRxGN>7a5P zz%~gNL4{{Gj1Ls&SEZ@>sKfg{s+a$n zz+YTOQJk`|8)9ipGUIa;upQ$gC21^KCn?+IXGVpe85KUiyEu`9Y>i4b+x3EJ!moST z9@F(024NMvZ-+q|S?J3XD*Dn<`qEbV0{A@J{^-)T3!$6xcPaV1MfLuhI!8_9V>Mjg z)jzB6TFU3p_f4)tolCV2v*hn?sPe1cI|G&D0uH5j?nC0675urx*9At}$f@dMo%ap2 OV^5~JA6UOoLh*{dTXfj~ literal 0 HcmV?d00001 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_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 0000000000000000000000000000000000000000..6ce120284d8173b520ecf446c934cc233df1a2e9 GIT binary patch literal 131800 zcmV*AKySZLO9KQg000080000X078fR;hLfV0Nk|z02Tlg0BvP-VPs)+VJ~!Ob!}p9 zVQFkGaBgP-01yBG0000000000000000002&yk%Qe(b_h=K#`E{M(OSr0g;fBPU#kq zZb|7D0SQ4sLJ1Khq`Ra+NOy4LHz#cI(IDMsMS2BU`j3<+TVxIjo0+ z;wB2Sq42+(cuLs0@UIqH+Bo*j2tqR1|M%tp`||(aU*=bC;1Du$1xho(@AdU{#*km9 zfeHqR1F_lJ)KgPa`IVKtzg}l&XTK^}Jeb4fkfi4*AW5I7b24CNVd)$n*F2%_=EtcZ zO8Ibc5g7Pq$v0CbM7p-NHo|=H>G=84cJwXZpPEvlOsA)(hAn;q`frVkpZXO=+}Bm~ z@eytE-i~r@|EoWtcQeuE?Dyut(9qrB;I{pb2I}f~a8H~{s;4hrTz7JEa{kg{guF|B z;@}>3?i*YZ5)!o+qIjQ5)OEb{sC%c&4cxb;I1G)AtxkWf^NWb+d8Je5wztc~#mA>) zWMJm6u9g-T7cU#@jnB^ZX9`$nt4l>iMy?E`F!2irbiTJ8vaq!+-ry8z%Dv_Lq<@Wr z8+pvhtGn}c*HtrkF}nFR4Gj9ju3+wOOfY4>c)``=m>6eCNlHP%BqPJHwY4=qH6`!w z-}tH=Bi~=-9fO3&RU!M)tI^$I5XIx&h3JzLzqz?N_W%CazMoWNFB6NGTs9?ra&$VE z0nUrxDypg}xw(mBGXH41qX{xL8_9W1u&k}Ev*>kZ<{~PKi!n@1O^d0#W=x2iWN&n= z_Qu~N#6ro6qudr7+)s9D#%uz385kIfLw?zlG%>EG5KC%NjjW>^YimDw_KY}X_9{Bs zvuDpV_4Qd(J>?Y?!p44B&(}W0QQkN>I1u;RAbggZYU$`0m%^lEb#ZcF6&^pw_PeD; zYGY%gqoYIiA#s2w+)vZcko_0r+wWi%V>C~OFVz!@;3gXzrkR-;Tq-s;77GWb>(gru zOBMjo*hn(;oTob!?aK1bPJ-{=7t5Inqq$~ZzRQb44Y&$Nk(s=px3~9j zmJlW;J}qG%Q*?JHL&!xKq-pRQEjBi`o0nJG$7)DU!QISTzPu);rYozfPbw<7xs7YF zntk{BWd2Mof;D?EGxzbqa;jJ57h>YSV;hN?|75;Q1^r{L?FouxoSLo;j(Y}`Mx zAA8xkv_$vi%NOy-$K2wyN$5_>W%KoqXc7_=t3&<;Q_|2_Z_m6HRQ(=DN=|+aGE!mM zOim-}OxSjLy!)V`xp{4fuf3OjA3t{f`5HnHWqE@TOa78M zu6x~MqW;kXh{-)05vG9En{njC#82kt409yCRaVb~&VF}7n^b%Lxc__aYkP{5Qud3? zOv=R;e-bS%E#h~{OHJP05!fVE@P-5`Aw@J1Qnn8fW}2FzP&W{cLI~L}NxafR7;L`! z3(-so&k{E>Cfca=uo_S@~4-uoIt<7GW#EXlI-@K`{mA(d_^YEHBMLc|v z^9eMGVj0!Lq`0^^LIwtNCn*nc+TR-!cOOC<1_<^1IE2D4CMF}pK)Lz&RMu4pn##sH z2JA1RodgD_#w)38j1ayU_m`q)@p?u2r7h^Xy1F_b*^Keb=qUc!%iB&7#wp*ob{9UN zLhBzb%oyuutyUYc{{AtRxAwxdt#hv08c9yE(RpL_{%IhT-6V;m7WL=Pp8*Hc9qS`w zW3fFvJg5uwiy8+VP6f23prEj^x4(iK&Ak;J z5pi{A;e$q}2vgB1{FGumIZqMikeO`yX+fCqBkx3|D9inWH6@AJGM^C_%Pi>m>!}jk z&}rS}6) zbaZ&GuCAGxnajyCmxK>qXAn*{KsQcNXx8tUQ1Rx=i-=77Is0JKp^R%C!jw~4JG;8j z*ZL9*y@#>2_<1w9j-&~8NQg2PxcSVBh=iy8bOZ6QZjQW!;NV=pUd;JGTN_>Wmmj5^ zO+jfN0@X2HMuvtrgoJd;-e+ZHjZaQKX=`iCaZ<=GZ|Y-00VNF8sAv~N+{e-q_w@9% zv9Y-~J)HIOCBCYv>J}%Hhqa4K5)fpmV&&`Cue$*f=jZ1WHEXi9of`W{`cP16ypgA3C2U5pOA1us1WwXnbqa{?}HZo=e|C& zS~|_4#M4u+6t259F0xYm_g(f54p{2yBdoq?EM>7n>s`ac6(9e1S$A<-Lqo%<05l#> zPPsdG!X`~*W4E5M(o;pM5^d+MSG@nB=;l>fg+ohyeR2S)r)gE644zb}`jw6fNp%xJ5aNX>H5Tw2Ppv$Hea?CXj^ z#+7ThPd7a>>g($f>KYszEL)0~6c8YS7gVZi$Wq?^+55^QEKFKZP!JOrC+FcI_`aq_ zVNmU*l+lSVu<+dH&jkkW%r?HZ%Ur{!#p2@P%9`$QFi5CLP7x_w)~ZkTdze*P6O4ZoOJbX%KrZC#y~ ziAe%rR?+L%Oe`!I%F41O+7MF4Vm|viux~r}G-9QROL`HTF3}DgI(^CpqT@4Hhny9u`f@I5@n=?pCN-iJx z4UCN`+1asbYimEv$w@f>vxlI`o%{Fkkukcj$|L%!udffUjD{xs zadSi#-Ue6{1)$VDHAR}rs^0Z;sd?qwH{G@D4X71Ggk(BNtM zp%f1mT-#SZ*VvzIzRm;bVX}vJAB6Du2Um0Fg?cbImO*%$ASJAK>8NRM`%Z*SdbC2bm%(D~oz56Osha*3i%} z^;pB5HzOXxV+~s8p0aXh65TDgZv#ZgyP+MPIVOjeL3vD+sK0Pr)4D-;LqI^Q6yTrb zcYiX2HN>&1y1Mgddv;}S@7)F`5u@0@%X2;ms{3jW_Rg19nq>OhT~IeRU;b5;mc}-E z{$P}lpt`)goNEiZ)#S4q_xR7x=}mE3d`ur7pDr|iJr*{$a7)VKrcmNd1$p^=&mW_R z;tIYzwP$8!wE_V)os{v04^ds20#`Khq&exECw^0_IPcRJM+h9xj z?7UgdCSqg&Scd}Sq?hsw1<7wY@bqS)87AED>a}ZKpFWYmeMGvtyQ^KlN^fj$&z>0p zddbVn-wWJ>lBue#t?zNJbV3z60Px zwk&uUNPP`#67djJyJ4v!X==8uy?r-4nCq98J8EhPa?kv20jm_%)Nnz5E&u$PM8F_D zb(V$v9E|avsw&Cjy@R#>s+yW|-}ZJXb`ABS{MWCMCbU?nf5gtsop$C41AY1OrFh^8 zKj@hFi9)6BuU{G9i40o{D^0`e>gryVU(J6dA;`^* z%fiBPvKr6l*c$tDq7V~xLt5Hwrxk>#_^n$*#V_US{iNvolIX5OP9h>A@`KKg<0^?! z`KHZ2SlHNMVPR+x-SE}bRqCOdgOmN0yVZZv1n6Jr%DH}i&!S&x61zT>Q3yW-al7K- z>ACHNm`KD4xVyU}VqQ>4Xa$T$XE^2>)Dk-fM~coac1kj^Tmpj(J-Ek{?RV|@@b3m^ zEWfB|U$JV&)2B~S3=DbH=Tk7Ig2KXZOal6t7DW3N6*2$b`KtHLo!KiL|)8a>mw*{TAE_a6eogec^|GV%Uej!ExsBTzog#nGmww6u8_!zgl zqrV>$0RSM1;w=i@t28t;h#!Em>h=8^WbjA=q?p&<7t2CZo&dWO0M{ zHaV|(TZQn8=eo9*mSIB~d`zI2K?9amSEQz<8cMOUvc76)Fx*_N{>b8mnyaxVP*YR0 zu(OM5Xb_M6OEbyI#nqiiBj$E_;h*;Wc~@sATA^a%vrXbB5d%Y6LiTRIzA2kDxE0JF zjkI5$IXO5v#Ru`2x3zTs2)Q_^?y=634l=HA{_}H*2)ZaQ_ze4l>(|QT%xAp$)z#JG z6BAlxM7{EhP|ie@lrc5-WBSeF<8fqM%zX*T$r|Bf{{VqDwzlHv9{;=iYh`=Odn=;- z-z5!zT`y#BCnhG+U^1h z?=Sg&wcHpl@cVlv0`!(_fg{{PryZS~I1ox2GpxDVbi=z+f|0LfzQN zhzh7$;PJ7uUqFEVgUXf`6RTl>tTMCf#CkrzH?#m(IyOJZ z&B@u{`7D$YmMtJ40N%);>1PCM);L-Rw0Bfg)LeUr3^}h!4BC}z%ZrVkBEcoKwWOV$ zos=*pT3XtDAS(nG!3^{vGa+_%GxzG)$~FLGPQImTK#|`FI$N_Azc2`s#itT=yzGo1Foppk#~@#hwtl_`^3E1mMovzZqH}&OE>+6pNqlxuF)<|@8|JpZ z$KaYlG+O^XJ36^M-=mpw{qoeW#dq(eTXjYgsIc(%b{SFUxzMR8-ReK(_)|8NQN&Fx zi2!KucpZH07f&#*ljm1d;No`QxN!q@e0+Rz`Xg^;cQ+BB%mSd`zjJ8{(8N~oc!2Uf zY{j#rY6B$h<|{<%csyZ5CR1fxK} zZ-;N|>z2K7WC%P2UmPeQVB+wp1W&)h@a80UnFDUO#b}NM=;zMYdBHd+hlP5ci;Ii# zas$57qykW7t&jh#LIcb-xLYUMf_Vfjmkg*_-s$bCW*&He@toHbM?*scxoliz65-=D z2OFCRXu+XxnZOBG^2RbU_kaER3@Nh)z$avKIc;|Ch`=OuI#X&!Vw{#z9#mEEe zM~@Q0NX>2@0#jt(ek_VlFU4NX@O64xFH`F0V&fG$Iy!Ml$(hENzl1?Pot&LnEq8<+ zZ3R4i4dHTl_|S5?OixhaOUUIR1FGX)`z7bGnX)oAXc=E*-X=Rc+gsXa-H#OOsyMiZ z++;0n?I$3`(BEXTon&F9|(8h(l4|X>D>=__*S>|MlM` zGEH{^?dr(W?!B!~D-+yu-&>FQ_+Kg1HwmknW_A%h6;&)!*kCDuMN&Qrz%wJH4+1A% zB=Mzm5H)%j3I<&{TMekpGpS~tXE(aMY_abrh3fdd`DxqRTEJ<9Ckz-ch9 zn|yo(054FQ5d{U7xnnn7IWqw4J33GZwO3hoFMt2en#0&#N$Cp>SyWtX30fDlVpLt7 z2&=}+1TKThsrgzSr+4PlQN0C@vwfvf3LDk!x%W>tDOc%Zm@x9@X6ZxOMcV#^d81 zBK#sfxC_2$nv&G>jEuEEUqdMT|H6;Bd3u)r(KQFjl5+beSn>nF9Z9;o{$O|zd1_lBIXO2JH zBW0JDXCD5&z6QiI;+k-2L~#)l)z#Ityt?{?L#G7m^*!(aPsV;&e;Y_4PSz6nn30}t z*&T%k#Z3QwkdQHV*=Q+YosAer|iI z**ChrUKFq=9N39#9b;-@f(ZWi&R3fN1aopS0jOf5M_CH-Qs2v}3`5$YDW2!R7V!>17PCNe*a`zm??#pu#n%^Lr{Pa$a7wZci0lTzH$j zHW`oH324Pbk?#VRQSw`a_6Rz^!pFmV>*J_0^qdEoqE6vpRli+2TR-tc3S=lIY8))D zWYAB@DKbX|@^9tGk7x)+eENzf^k|MmiGi7=L_Zh0@+%aPB8J@8KK z&&i=hrW-&>7&f?B*6B>0{ocGnpUjri)qB}Ky-uy4JE*Z)T3QOwowDWWtjZkSog$83 z$~)(mHuY_+uP`z)a?)8;N3Z7I25S8612K7d`5Tgw)SxH9CR};->J=gQ5-9VFA2R>$ z07=^hoB3!iKq=-|R^qFxtFK%r_!OW&ERhhvy&@wc19o=#;`9()W#vImQ&ZFO;i=Wg zL3*9b5;bU25~`<@X{k-Z3pWR;7u3u$O7Fn!DQ^b|o3#c+8r9f!e*M}$|9;2))2B~p zy28E>3=M$_^3m!lHS3b~vh7C4$2Bc=b|7a8O)gu7kaN(O#J*BCFYbeDrSVGYyTMVa zx-iJ3dKB9a!ZYyl^as)cZ6~YOLASNezcx`mcvD==lDhO4T8&$4d-Y6 zo$xZ#OGD%D-@o(o^S=?G=i%W=cieq8n5`hEp|0K=g-3(TB&@Dl)jCe&0DOVSVNy(> z)OttMG--udryQ_quVkwt^ehM%2l*bd-ZkxFyrUEF$Qliq8K|B7 zWeB;@+SaampQMBzeFXq1_F$ksfPLZj$3b1m0wLURx?4V21~KPbRUmHto?aIkVqEakJwQqdW)G???xa%w z9cA@auyh?PqH-VQ$9>Li^aNx=*wDHav}m2rZdJdnf$q@IQ0k^v*5F7^9S;WNJ4VQU z6!oUTl2*VfLT$^!!Xgy(<8?q*Msv_TsEnbvhdEXXR;f*|rda61;*Rj=E-#U=NiLNO ztX0<+TMP{jMubZo{r+u3&UWqEH9*xSLn-jCw4i`NTR!{f|LsmOi6p?tyLWugo;|Ay zIC8u=UT}q?!t~jl$1pcH-6L#W!91vhN_VV_?@NiG2fVI3R z&eMn>^Z8C65FX^GW=cx0m4&_0$*%O0Mz*5#KUCkfUHIUtWMOeboEHBoI@(NykFjB@PWs%;s^`VTEtSsz&s|gOHM`_w-X84fu zYCl>LN79qPHZ?ohkMSyOUiz=^=k5bBtsHI7B5sk_qydG@q_hT*y%2Nl^ZgoxEa4A& z<2MzVr-5g_BAe(L`gsg|+vgg4YtRER$;tiSKBksGqF+Be9T*&Z0v+!5R7qV{;+m3X{{qrFu zHMNQ}e#JX-9^)7(_o-Uaii#IvMyIEz8w(%!z+A|;Md8!oRD^@-bQ9=AkN)`gE;>#4mIAscrkE`-rLJd{_?M*F^>MrgN<+Bn8}l!ugl(@d6DtK zE@j*Zw0$POB|4bFf?d!t$Z`fLIr-r4oE^HiMGF5O|K31@@G!Hm z=ru3d=5#Znn6*I3;!^1?9%ya5N33PNp!#C;e;6w3LHMbNatkk|wQE z{f&&MP*akLS`!Bj&@w=|-9R7he~)QUVC@Z@Fa2$wtqQQQDQzW27ime*mp{M}y>;tB zL$lpN{iE{S1091vX$A=i3F0*YK|x|v1Q#=BpbV^)^YTN=SCCaA5)U<+~9Vv(}nlguC!oYt_t`1Zkvo@YV+{t~?AZ3&4qVhDU$z2)$Z?bmsIANx-n zR`u)%xYcluM9n-Vu8&<(YisL%AbObWmjAEGjoEj30}kHG2f#(jE9yOn`)au+?`_r= z7z+qQy(Sfh=%ogdwVU9wx+v!W~Ne40TY~dKkd%Er3sC@6O*oV0CWHhYdM@LV3p^8 zaU$UC?7Y0Pa?|}2jhL92gM-7px@QLK6V;G!&{&aeZPKGJZ*v{IN`LVp9vm(BZ=Ba0 zGr}76ZNefV3g1(|w)pGVs41)mm6Y>-`m6~8QPaR6IyX0W?r};=3ZGIf*^%m;$GdJMSwN%u-jtC|1&0(2!2G4Yc^rDXkc(%!WL zWF;j9jaU74R?Qlb<0R<5m60*v(}{QHGHO|Z829hrN9Hzy&o{Z4nsL(it?5$?I56m}j-UL5NvQTqFM1;)sYg=!N|6zV%A=6^=ozJ=% z!^K7tZ^5N>U9JN6bO5O6l&IZ#XV!{r&8aYHBra4;Bz`W&&)-2Ha}kPI=g;qL5r6*t z`SStFD`0V9=!{HEg`*lHpseQVoG4HhNXgBR=sP=etEj3Td}PaunJQIEruRth9~5iR z$de{x)%ErD&BFhJ2i`6`JbbRU{o*1}D&RNPrxNvWu-lV;)-|dd)z#I=;wU^KxZ`MK zMz}Yg0+}@7cUcriCV6_}$izLqVU=j)C7Fl()%$t)Lgsu&2x$}5=iCp+8wZDms=YR~ zbHv@zLAg}aFGdqEM2zUo&(Di{Z|SDq`_88Evcgx;9=?f-?BxM22X~4%Yf>_@6@-kS zP7%FsXl#r_f(w$OsVN}w?;$eN6&hzcUZxENUR-Qj7q5j(D?zB9Bqia47GV1IZ;W^8 zR`7-2iW9U?Uhr9|+peRLySqD)zlyZ?R@(kvdWJyy`X|C}{)T{~vL5e_&o8JnG&C9- z8rat{es@J)Kf3?D0(6hnU>XOq?dCzb?R7Xl-LuBxgE$N^wzvD^{X zCBEv>NSxtoyH@?{-%VAJ?v%;TvP;2{#vq$Y1_rRo_1_Xd49Fl&MtvhrK0ZF~VyOs= z%ZvQG^wdBK{f#I+7&U?@O9VU`nwz<7rO;8760z~|)+m18pNlE897WHwvOa>&&UN?j zuu4cw%<@0{E&#oqAbaD@fhTZ40^|xHjkct=R`=%-B$Qpq^@~(g|Jw9vjlaKtLVLRm z2{pB`btAO45LiN7l%lF?yhPv$e`-dC!B_zI9S2bs2?+_Ap#Mup zp#)-$x5?<~M^P55Yiqq<9yEHee5$rqin64%8_5o?2aZ7%HT7% zqnGmQKxSuWJcpjt)YR<%5D^w8ZJvR4h&O5tsMGCVJ@8Wt43s)t?Y&;o(qd9JCaJ7JcBLDk^!Ygf#ytT^_p!c%!6 zmoR=@WK!Dd$kW?9vaqnwZ9(5COZeflfi6{KUI^4lNaaB-76j4-B$p(Kmf!JkMeMF=8j9y;_Fu!hGk|_t_<2k!1{qX98EJLr<=T;BBG+? z3=Akh26&i%du2QHT$^ou5T2TI`dO8%g8Aps+*^@MCNJWkz*fGGyzsj?aSwmiD0Omr zdgs9d8ZLuMXEzGK0ennhV+{JuIfq^)a2ykR5{J^ zBGbPsU6BZ;SG;{I;QQ00^it>d(a`~5zSXyZ6vQzwGBQ#Z%={{Z)J`=U=qcU3dj%?? z!aE?FvG&mdISi@`nKq@Sp3k@b3%1Yi-{tLkmnBY7!-P7&11n@dL_@V|kS=`!DIFb; z$=3ADOnsjbiFcjHx{BBKjQVQK>5s8IfDqK^=qPB~ZineIGAnCqTc2PfO&uL%(QN{R znc^*bGc$U{BwB1CAt72RzpD97WM%;|U9SoYBMYYDp?>agok{P6g>NPw#Uynp}xX?8Yef|9AJsn^d%qs>(! z2UhId;_~u%Dj~ZYQc|?YG&B$m(k5S8AFJkkGRn%%rbb6cuL4X9JllNDSQr|+bp}x* zBqR*o-*-b+4AIcgx|j{7p+nu)`tXqbv3GtzYBJ44-gT^rYIOZOSS*$N_RAhv&5o0;CP2)`na-;n~#s+ZWQhv6BAk_ zlMg?!R+zW9&A({ExK6$dCB#@RJA-*E(HFRE`uW88cn7j`=w#n=u{{I^Q9e90qzX4n z>@U@ME$SEVq_3uii)^KZhEr_`vjaM_QW>O99^ou7_`bXx3NJH(lxb^g6A!)+M+(Je zfN&*7Q5oDpyv)A~5^!!kXGhy)@4G1;N+Db65B&Cj|Ly^b?p!-4GbK~i&>#rEhUe(E z`U%DYF>|~<+Tgy%Z_$AQ?VxMtjx1VLTldGcnt4-e1*K z))xXQ3z?xYRmhNAv~#T0goTYtNBw4I}jpz zGS&M0{2ZBd5c&D^&vNIL>SEi+$2+kg5pOUt-QB{A)=f-LCj<9RYMMxmarJ6G00I^k zRtM-MTMso?SJ$1TW`mPfAi?2!{-ydyG|&`ICX~^MpaAD?KR%WRyP~bFo#seVZkId0 zwz^ss@-LVcH~>@$avcawu}YF@vyXy}4Rc>24Ppz{zmj#b1cmti^C`RhWQYDl|DcdBDl}pRKcV#oS;J~E+yai(*k05rqRD$x~ zM2@3`SXmWIE1O4n3n<9RSEovKki8BsrTm{f{8WOV{L#E~*Ww~AvehU#nP72o(QRYA zfSST9C0)d61}jxUv)a9HzRu~zRHd%G52AT%YlQ<(*E1UY4@(A~(8~4>$2Q?Ef+VG= z#O8fFKk9yY;g9f{xYx$hx!&sc6&2hqLFf8Af2!4Ah&oKX!mzTkVlUuogi2p+|M!=# z?QDw+gl=2~H>PYuRbs6;?fu-f>Uz(`ChzN?UTaXe6qwS{Cr1N`Sb*?md`Ck=gUryz z#Kxw~vE;Lluom?9^;tnwk+uZw#ScOd86V?N$qcf%lSF?TCnO{U7ktZBsWo0_rJ7zA z;~xvwxDSrgoG>zS(9d!X4sUu!SV$w6CS2G060JO!%AX0Nu-`Pi(UA%GgfIf~Mr7^| zKz;&5j)H;m2Gj;((Vz2~^SV=;*(TH9M$a3|IO%wuaPVd_e3de)6Qn#oZ$`XXYd`^z z7YL%5m>6W0ohE142=w{(%-e7vMR)h=#rEL8M+ViBQ^JhdZ=|750Bo##Vu;+lz4hW| zsG}_Zvv!N@;d`YJU$mv8e(zprK|#R)idi4bY4N;50z0zArj{p7M^8_WME+Izm3%85 z3h+Bf`K;Qh>aj30%Yryx#d|NOJF5VFRic*l1oZXV{z^C0 zca3i0ztq%JOM82^>WbFZ+ep_1bLnY^b+6pu=O=`&Mi#unjcV))-n_YY)0=~rHwwxR z!BS{H%dwZYwfn6>Q?T5(ulewy|NPIMQ_j!DIbF$uE1{rHk?odK$kt;i&Yc^)znHS0^EVc#F zAm=wgOS^-fO?hkNl$w^NyL+P$#86>HMM6_XcILabGaSU<8X8hUe-M(9O~3h(9276poUvE-AA6 zYIXIAfOX$M(B{NxMWDn!VpigE~+X161_~0bmk}@JX8mYGZ{r%9=QV#mt0TKE6`I7GvJJt^N&yJi@ z9+_~})YeA8D78&xV}FAvLpI>{^!6gM5Q$!~$;v5EZY-J@c;C#96!5lY<Wx{pFvK z&B1Pe&%7(lTB+$Iy=0-$EuEbcA|kFLyB9`v5)3&wI4mej=GhqWqpyI6L3X`1dAhlE zAp4ZT%YkD@&Lh>=*BjQ@;kkTiiS6p@lB9bFYV(83(v!TryaDMg5QoU7TlwdNmGOXY z;KQfI$4ox2R)1D|z*N+@4G~5T7J=JZ1*{eK{EjQ?vWNv@UR+$fV`hdtSJL|lct;R6 z1#jObf|(;FB?Zd50uOXoTbmd{dX+chx|o<4_k(&|@bQsqqU@Hl`fqm8&)|C3^5WTF z78WuAey3z-$1N{gT*bs>x^V-Al3$$wY(6_X8=sg!OYXl5eFi!WSwmrFV`I8`6Ae8K zS=2_B*;&;xZ`2n%2i>Dd2HAusol&7F$5xc}aJG_8|E+PPUb#N9DFPhz9WO88XQ`>~ z+cP{i_V!F{Y?utvfk;z9UM(CQaX?`p`@kTtVddpqUf$le#_x)Xm@~7oI(vGG<^^+a z`Bu7rHk|xz_}~Gu4FcIBjC1`u5fxSJn>XypxIim@{``4hWCWQ!9Ud7$&bpEF7$boq zVO8sR&hr2<`&oP;xoK%v0h3~N*p1+-eV2dFZxUirx7f9DBV(r$5*F?OIO)|lzfM4) z1QB>|@za+t^i)(-aHqGPdF)!j0RaJ&Qhxl`2zSQp68byDA;%{P zUy&jwteU*HsfVgwv?1=eSoRQWhJF4Ndm+<;ySk>KI4T zg%92o6okRUva3sJBPUl(fS{56#M>BYL+em^au1=My}_!e)UniqO8nmuk}h}!T{aat zoT6)J81w4YtN%Nkl97^v7D_Csg|9Ax91oNuO?o*VEBLVNfc;N|3tW6phfpqC{5W=C zYN~eT{h$|eh9yzy;qkd=s zNQeYIET70xzedr?BN?czH=aVv*qAdgaqPz$=x=s*_6~qOe%nFPw6ru3Nto00{qytG z;GNyv+@3my2gt?zO7)Q!&~!%|`S_8j@i`%*>W*N|B=--;hYzu(^O6Y|q=n^199jQF zjDAu6v-t^=g@vVSWcM^s8eI94U%xyOCz& zKQLIwy(y|Fv~K?8!&CTuRH@_W$caxU838P?GG1_3WkOf(o@d{W!(vAl%p2UZPn}RV zMgEf#>EDARtLeV>j?-o7Zd6M7j9KQb0c6?P*&6_Hb^T5bf@1>%vU^`zBY6~T9e zIj!W#GBGg$nif=4;37K+-oHnW?!E(vBrGg!)5gGiv&fwvmnq|Y#FUawqEaL4?>eVh z^fwKjr59JtL>_(sB?0c<>fIHx7Xn^;U+5wuBge)*=yIX4UCOtlK)Q4Wd02-G57g% zEVJivZ0=trWTI41P>|o_+r3!j*2jN-0)5?ecNYL(*2#|>7Z-=@nXV30H?DV%O{5VM zy})Erd2KuNyzcqw$pI5|`_sHU0#LT%5)#?m&^qx%u!LF>YV;C6BIwrp^EyXr4Fo5Rl7#zfznVI=jA^q@)m9;gRZjTDIXQgQ~ zYakyN*L4a$GkHKb0k>sYub+!lKYt<{b+TTSsb0$XlsU@D$-T7&!khcnqz@(cG$jSu zyMJBj?vL-^S1(Qvk+n$Rj|4>ifqT8DtgPks2%9GP;NYO{xgJ2OQ|fu4Qu5QxOe~;t zWG6`7^LJ7jt&&in8w(%aY2(T|42shxseD;!fBXkuRv`pHH^VIzS<1am!JBVC_7d4J z`+RI{Ec*HL=RMYXW&<$;2GFy}Q4vsdzke<@&wJo@FRye*BWFFRt9|h79UNjN3YFH5 zwr7_;8riwHNLUX+Vqp)Fk&@n{rNz~h5@m%JH8e81DJn|-pQE}vfGh$avlYvXM!r2C z|16yk)*ag*nknuN2(FIFN#g&iim;NBlBq+U7f%Ld;$vfD-4dd}GXVo&2nh+ToM&Za zA;;{bq@>Djo86@lWSrE}(YXtH7OBO+zelsv&sFc=SM>3zzenuMiHnPiZ1q8rY3v|t z5BH?LfBSZWk?~a@4Ru_9U+0P&qFq7C&l)12JC-M7knNZDKyLQar*3fG$ZlAugA|!q zt2d>kmdhPs(7}oP1x{ej)Z`%bN|03rv!UVPh^8hKJ|ywknbX?EItG(ip!53v2AD{u+54gZ1)64N_@17g)i$Hj)xNv)dMA>-g{uiv zLf7KSdE{JNTE1Xv#>d2jHa1Ftz{&@F zd;eY#MTj5xacC$U;@idd61?|aH#dH6Ztg0t%}G|7Ukm;Hm@*gpS3nT1?C$a$ODFet zgRw_u@mNV}(lK}6D=$n;XxZfL!nI5q-0oDI(m5C(P}0*Ut@S5&4-8fH`T%MTg%l$oP!M*A7i~$k?&54Vj(3CnlI@Q)y*Qo%Ca3MxrkqM!3cG~pG z2CpL%zS)8;?TSx;JRvh`O3C!f7g^ajz#qf8w<}4Ob-@I z#XY@($%lwbG|P8$5?Q5Ww1o!cx9W*urAr3XkN)sMOq>=U)K-=6o*6SUv+!ov(ER*7 zGKn?w&OG@}__f%@3nAQajO*lx_V)ZSs%OEY@R6sW9H0Y}raEMHdb;>_0@=O)esl%^ z??4d0azeSJgjHBXL=T*jpAX%qADRY+NDNe|l)JVilK(Nz#hB*(?SP6KUhZ7mlY z+$lw!Gu1}5K234>8@C7F2GohVc{j=eQt0O6)7R{~SM_K?6oJhjqq*VW(dD-E8Jy+X zy*7!FEr63U$mKcunY#IrH3zrf(s^SD`AMJe2qnXwQze+1yvKjCgIBouueBoVnvOFV%VNXpb6* zfBBN$WvMALoy)*#wI`OHm-iY9eCZ8t?uw5`xivz*4JMU_g6|eDE)Uj}1Hs_xpBuYGqmq;B|WVLpQQp4=J2^E$X4ZQTMj$ZVY#EQ4!WTE7xA2u0M));bL^%lx;&VC=iD!n+aG&ziB%j4YkQJ*uty@r#O!3xF=weX==e zqIc4S@S~XoQAv-2e|R(^ll90Z3?e4Q7}Hzn67rQ1(T1wHl+0Q_(1x_TLe;m`!|M%hmoz~1Rzc3>YOrE zm=6b$bFBq;F%=97?|6869{iiTb=Z(y^DnvG<@{AIwH)VzV;gLv_@}w@)~ePY1&@iW zDDAifgek9mY}1S4u+E67z42gXk}*x?Jb3T?k5ap|`G?2l50;t?Mh_1f2&D6B0>9)f zoG#A($T^hWyF!YSlblSjHB}l81AGPODTnW7Y;25dJY{5JQr*G&==pfD(UT3bxcu`c zK4>cB?1YHiaJ!PW++)$2 ze@_Jex<r4 z-URpwoY|rI!iz~D8swu_00zl-Q`qY00~8gb?qR6|%^KG^7Cih^LYDpG^rdddL-l8DzAeKe1io54&k zw6?&^$cPR)ChYlhazKlMSFaewbb`R)y7~Gly}qBT`T9Pcu+vP!IbFhkPsS6Ikffxi zv-o_u*lyU9q9-UTE0g=9C=W`_Hdxt1-ob(0+1c4;nsb1^~iVc_`VNkg+sF9{V!^4A$ysHQH>5AqC_p_%@J4WuL>0V=}Jsuk!je_(bGvJk`w_JkkK@o!6 z&MzoH1EMP6li=XM9vmEeqgPH&FC7>Isy;I-D;7_N3MjLvh`H8f$=JrMNO(a-4q~%$ z4yGWyu#gF11fP%nhd;(ro<0rLe`_4;9rtl~xCbN!Bp3tSS@nHd&@oCNjuSm!ancXp zGcuyu+S(FK&hLFA8FyTuZ(#5vK>iowM#b&mkb$P#`a|i+LR)GoQ*942*_tV6i!(Vn z2`NkZ-|;M&%M&K#gd@0SROHGZHFb3&Qc_(W>SJ? zFe{{I&?(9O`jwTI-jtEa!w@R#B*joVJ2UsE^041M zIKMlytF`sSY^oarXV#*xzuy`X3Wg#)HI)Q)gO?W{^mSBjE*)|P=*^oq%L6G)nF7|= z=Ifj=;fB9=K9i`w5Jf)FYN9>lpWqPk0tz`x&Y@ERqVWnc?Eo?^9_rEk?jI;1WOht3 zi8dBs&7*Y#x_u3J)y>Tfh>sD-C)#^^W@WNi6%~q2!utPF_ul_p@Bjb!Gc<&ZkP%8q zGRll(K8+$FBPpv$X12^yva+%w%FHT~>{THvBO`^#US*H0`rdBm_5S=3-*Y)XoH{(# z{eHiW`~5cLOi?m2u}KXe~LptCnp2I>yhv# zQm~6yP}0-WFZ|u{oSL2<{_tS$o8n^S<%!k;v-3@@` z^4yc?QrF)syJ$8nt*xWrL!I;4e%exTyNd^=EqEyY6e*9DDS42jL?S&as~Q1}^Q95t zyu3WJdn2QxWzJv~X27aw#;>e6YwPHwA5#gVp^Xd;rE;0>RN`%KjyaiqcX@(HT=}zj zgG5e0--w}kba+@ECVE_B@yOWZWXMi6Jp;q-j%0aoSdxPFV54^>gUj3BgYPRWD$2!~ z8qOj6Bs23kIT?xI4y+fldm4#nO%6lGsF!2&mtqJg1 zp19~d`;`i?6=%D+-9X^;bDsODem@EbP&`5t_<6Y6_g{70#-8&n@ahz;wgCYFASx9t z!B}-1gR$%#aDb2Q-zg?4dWO0ao_yE6#j^Km;9z+%SzJT(SVfVdN6G zzi{+Bbq5u3P6e3xr|k!&BOQ&;K0a~sWJnbcA?4y;z8lZZ=;-L2IUWxaP#)m&nDS$} zDvwpHAa(RC2I>{d0MWg9bLz^KD_Am$Nz##vMy?^6M-P{>#|pTNabexgUAFQjJe_1c&@S z;;3S&6O7oE3ReN1iwRs`&e5-0amf1cj~U3AyeCkyOP78u4!ZGYVHg(Edkkd(os|j~ zA6Nwe?e7!;+Sv(yZf(W$2Y#bUCTezR0xhy0#!9B9rR^fD&h#i=y~+YwXcxV5YJ!+GBjJuG zPkVwG#aY*1_g=i<0E>u0e3-RAu%>(bg^ahtl`Bsh=gh<+!M+@mkue(cA`;1fmWayw zz-Y9LjE^wuc-8ywcD!eH6e9o+?i<0#2i=8v{|Lqx7Mt2?-#E8~L`k#J6%k=!+yYNe zPv^@vevYLLI5|0qZ4C_#$N2dlhv@$kLo&K{E%DoCPU>|=0X0DZIXxX6dbs7nc*~(| zqY7!SjiudK@c^DEcY>rdAymjQn1Yg${+W#LUoTkfdDo6|reZ}xm<*CCr$9$+j)u#Y zZr3M`aGe;PnYrNM;lbHESm7o#Ju~yf&yQr$T^bgAI!q#mX>oD!o40Nq*Rg=9o}QoI z&gT1P;r{0OeEW4nef>CTX=$$F*JqS89G;2W(mewcsYI{@{sEu?++;a(=ZJm{Xe-Gx zXEZf54$#tab8%^cuL^1yjReu%lYKd0U|^teU?A}@8(UByuY^P#V5zFS{Cz;)tn*Pk zV^dSSy&4X&v9VNt!0I;|dF!%&mU9O8qXf$C;fNg)gw6t{L6=rUmPekqofvf_z zQVwNNN|JKnbK3ydPD}7u9P!ur-B)lU;M<{w=8>^6A~+s}Np@*>Ie3}wVq3$j)m~+q zeIxZDP4C|)*KLBdPzX4{HWKFI>}(0>7W38tWNmtO_Ibk8-<>VaY20A}q>D4`$S^ge z1$utxJgrTl$?Yddv#;^nx2O03e0+QgxmH|C3G0SL-J*3^oiv1_izj$_lYuZU!{q_K z>=ZVHu9eCWc!hgx9J3E;_Zv2Fjyj*d6lvm~pl ztEOgV+9MVs3vwnd<;08ixHWAzR4w3`)M;}vTiwS;X0XPWno~hjlje|tFnA)ECm$C_8}QgV zXfCr7BQ`MU+Qmib_0^&~a7(&nAns8BQH6ExIUjD@INVS4{U>8LSlRSLMAOl8@BU17 ztZ>m^Vjof$*526oezN^VB&g%guOUnT2=3DCBqSuIPGD|SFI{Q?_Fnw?fi#6GVtWVU z;nbK|Sb|^wn{|x`q5w?~;N#@m&IvLID+EMD&;;H1O3fitIq>^!`eZSG{{@e)vR;4g z4GdhX^jHmkwj}Af#&6M@P+!k=T3FZ*yeeF_g`vGhJ$=LDy@@KteK|aLc;~)o#>r{b zUo3F(xwHY-P=;C@JWM!P!EB$MO&xH5<#&cjcJJOD863QS*AWH=21i#{9!^fMG*Wkd z-qU0|=dqFuiO|gdi=b>DgI)^PQy@A?`tY zgWpdAEx~-J=jCZov5JqqG_|p{4GO$qGk-|%S~AF%sFyE!5dB3(MIV}Jm6n%l!xF~G zezJQ&*!6=>lWj@2=LX6K7J-x-KYsLcbaYfzRD2M|A={P#GtR*^Bp2q0q*>iQyZvB3 zV}yl;0|PN2IQ`{IWe|puP4SrlTgTj>a!vA_0B_+b6p~CF0Yq}?N6NRrMt_yq=n?`!<}HTGRm(KN_bq7H8Gd(?`yj<#d@P`i{$nJT0 zc|BYL!{J}<`n$R6Fa!C;$a#&$ErHzYj78>dZf=4CV+!JcX#O_h(O-8>Nvsc7hovH!YW*5KeY-_vx+~)%4wW@Hihu2 zD`0|SulO#y8hBl)uxzZJGFo0*vYhxF-wjTHR*OGXwd2N(8%-S@nwH;oVCL!6_;_#r zSxk#aR$CfiEV=kZI3Xb+JtIR2)>6i7Z+=KppSrqwI{akUpT*Jo!ArYM{n{cf{rdH* z)QCnaW&R#ab{ze)lM@rlR#sLD)ORmj*#G-SMI5NDYe(gM*M2cyukpFgyR$Og1?FsI zBv4fctN3YP{tI8!)2FIHg=3()i2i=oKtU7U`Bw`3Lat8z{(TV@O86o;<5G@$fb$fq zFY9`Y6Otzm_oZ2TBBy?EGPebQVmB97#Xf^Ae9EPNGo_eYsU7ek(=g$X$ z)H$jX9v)7;D;eODwx8?7Wv;1PZHXrqD_-rF9|D;NTuo7RrP#VR>=6~~C$=~SgC|+r zenxs+s+?N#|28IHWXnI;!}(X*!ouR_jT?%@ku>YzQLxkL$;ooSGAlr8+M1d_|GI+d z!|zGAkIZ>-L`hpuZ^9#KWJXA>gF9%>ATfWpcYQF!O$&=p8Lf$uQHUEaWPKUwoXAv8sHkk9|C={&63NNQxhHZ7J%y4K546~;y*B({jiq4;U6ES{ z+>BII_5zqn0JiM`w*+GbY%OQ0e-@lb-e=&`7VqC+Owcv}Wj26+T^OmSuxrvdf4bDT z#)pcPl{Ll5W%jEQTFTS~(2Q?C&l(ySm;!P%0#(8HH8D4@uV(%Yi+|o@$UVc}c zkg+l-x&#S(Ba53&!J05M4tOinC5w}%L2&fRrn);{bXfV_e+V!DPxPKdMQH(X&CQ$I z+J^d592x;%xUjyil5bS?&_IFu(f^ADaE*>i|C=8vT7K)i`qNXp42x~#Z{Fle5VsA6 z#XY>evCO%_%Ae9^2cHuv)L9e%#w^%)!$#$*mvdtDiDimZDv+gh--ua5;YUhmvFg^mz&&SPTI|8fRbKghnE znR@Ak4CgdT+d};OCYVsRf4^TziG*@E`}I_+`kEK1hXV3zUIa&SI9XcqKBDFbV-&dh^P@k-z}LY}{YEHz;-J(4l~D-@ZA{-^_gZ@{v)M2UfxO^5sjS#3{|v zAvsLKupg4?&e09&@6*?=F0L>rw7|{Pw}plNoO`iw{O5R)YxB9H38J_CK%{(ZX`wJO zGWu3{D_r$Cytsmr((e2B?=zh;A-GjfZSigTR2KuhGBYzj87%IGw+sNwhl!s{4_-Wd zx)1mOWBWfhJ~^qMM}J$|2SMbB0ioR7+lc)&Yd@nQ}?;>7@U`PU;FcO zwU{~_Z2?oWH(Kz~yO|vHA-4CiL|5-n@HP z7j*FW1#itvkB`+@wczXoqDk1|= zx*T!p>uXk!EChNxCLPgjJ1eW;G?j2padF1;=g(hxV{*UaZKTKQ%u!+CCuiNZ)@*U7 ziBQUI#lpgZWqZM4L_T@qx3N4q3ImG8Na53B#h2->%rv_nA{bqwv*1H=C4=E?8Sy9yxP{NyxbRA@HU}`}0uTI03JVyIaoAqF|zjM@Nr2%ztQW zI{;*=2vcMa6${r|0@eWf`r6Q8x|18j7)3?t+uGVtje|WpX7()IJSQr(G58>lI?dLN zUsF?o;5=*l`zv5@?k(()JSl4FYogI(z2K5ebPyVPRpa>grgBJuxW>%m3J& zoL$04mz9;RtE<~rWl7@yd+CMm-}~^BjXLKIEG;d6_T=ij|5pIKS|`=B@B4RLj4*?^ ztI1T6i(hlLOVOInbZ2X7Yhy}-!^V<%qO9-pEqdd;D<{$=kF}fV#KPB$DlRT=)O)8S z?fW;85CM=$OS_wlECS5lqPsK@Q?lOct6Jb_Xc_j@U_!MfG5_8@f>n1G?XDy2;VNru zYof4F+BUG(Uw4+)G2ks80RaK4?{B%2;C9h5F_O0uva)!sz|L!uRlu-C#l|w0=+uM! zh52%(qF(73e^7Gr5fZr&Mgh9>%d4vltdf_m?bIiQ!>yG-u(62Ss1p4nNs|&2k&@{d z7|00*SFUK{K2WjuZ+aD-(oQ*WK)jAd4npg%UhyZ$cuRqaaBR8vDU3}mC@6@#PfstN zGqbeQFH5!SL>{l>4LP}c-&XwmNZ_$f!?kF%zDIJ041w0xexe#N(zgYe+4%nbJwgQh z49a_r7c#BiwX}gG0KegziMz}V7;p)2bNhpJAaYIy<<_`YtSl}b)z#Ha$qF!6TIX-; z)o@UHcf0G+)e^f_wnJ{g$N09&7|hLB?qUDgm)7J!%5bB7xUy9BH>$nC~7J6g&V|IRz_`Tv>P9r^PCchzBKb5v(u9z2_0%;9$seYEHj`0*81* zsTM!*i(}*CG`uYL)@5^V9_{F&V?tE_OP~0?K*mlFO&Eyml<);$r@YWO& zCdxezv`9_<_jk%v_sFGibCXGoz%xaO+r`}kV8;Jn{ZK|u&KUs#s=Wse6JE6MrFHnX zpUf|(oa@1dKVd%?-8D5eDGzn!khrM> zVMRnmJ^1`teIFSKhMI#p7bL3!V#D(=ar;4j>&r|%L@<_-&z^;>tT-=hcoBZ~-E`43 z_cL-9!EX{XHZg%Qulx6-iBw{sk`iX3i-e25dnZcpH_OY(xoX>Mf#0qAHn>O-CooUq zSmommon`9TON$5D)6>%cSAN04`z5YkXVZy~JA2R>uG~XI+pE~#+NuP$ePCa9<+l%6 zM!{s~KzQH1d$%XYU%dm17Kgaa4>t8t?isB(%FVsI#O{Xz%-FJX??XI@OT1H$=fhLi zp2o(0Dr%bP{>aDb_>b{>5Obi1Cby_>+P{N&3 za&m&>MQ$~BKLWgmPxO9pkX_DHl;6|S6O%%E^Nj;yVq(;PZy8}D7Gz$~VkW~M{ojgb zD!;we&JLH=9`ma5SUqL)?G*Esx~!mq8ea}95bfn9y|TLM04~RQru+O?3te*cj&VvM zAtChy(eq>5V@*-R!^0oQsuI5R_BMcqHn&v{y}A8o@k+IqB#yOr?rv|Gk zUbSxJkyBBD+7Efv8nGWY_~H8hos$L}VDo$S?AhbjIV?|;TbN;Rt`u5?Hg3Q*n!Q%; zeTd)z5UeY>(GUT18iP7aYaeA9mgK!^-JEM`ZvF_Km6nZ7!1{8|Ls%FF&os?X$;XLc z6CAJxk;`CMdsve1eaI5j(bdIcb%SRg{`iuS>;jQn0D_y}uvq=;giZpyvSXKpG&?ov z-UHDEO1gUwI!mUfpXmmx@pE~jr`U-aFv3Uc^5qA4d2sJ6Q3^(WfDjcqIRd|cK)uH8 zuk`r%83Gqamp5#tSpaXMNx`tyhaAG6mp?Z3W?r{p*L57p)Tcb}7yVaGNDU(!@e z&CUH;CG1qY^6Z0w9SvyVjJd&Ue45b9c*a!A95#u^vg?2dw>On;69CQZFyf(pGQTJ z+S}V>jcYtZe`8vE%3*|eTzk%pxW>HrLGJ;T2G}66*xC zj&Wj6uYh53^o;juJX)O4%y!X?jg5uZpglQ5#UdIJ8!G%D@Xp+TB<5A3lmyw`Qsn%& zVf4edZ%m&)eZrG>B9RP_1PNCvTwi~q$%nZEw2BE%lvGr^w(b8W?v63VmpHF;^=L4$ zDy!rw*9<727;%kQufN;OuCA`Cs;c+m;tnZ?9X6PD`3aZ(R_1gZH0|POxa`P4nUmQv zm~ZmmwQO{Bejt~1XZn!hvc9Wkv>eyyt{E3NZd~Qz-xPIxwAa|zKPoD!o3tFe6@cyY zuc?v6O35Qc+*k!Lcy_khWtI_R=X6>BqsPLC1Z@TmAAsx_y`G*6>gtpj0E1_#K0BKO z8{l(?(XkYXHzZ(R}5~m3_7; z9+PcsSU0S*w94uhICz?UWN*dO2I!S$!NUBIC=+tVv<=%nQCN&7r*desUC)Jtc(_Ew z#y*1iX!7~#Y4{DSps%j3o}8I^{E5Wr)3oTcuqskHRuKI86KkKTseZoy(P*nzZTaon zx1hxhENoW6qP}lv2sk^}SCp%{*&K7y^wzDtpwY3t1|c~&mjZ|tX8Qg1NyUp7sidT& zGJI(rn=#8#=7o^82p`+jmyUMrF>`U6X6jNkM4_!F*dF1mNXoeflZ z9s(U3%UhF^!{_?z+b$Iq6|%j16%7pH)mq?nz?HRlnIN!W-TC+TNimQs+s|jF`vg%* z=|fKs!|d1B2TxAPnT8L1`m_gZ7*>WR(67Cztf~SLK?>Ikn!EHIrcCY1bQdzhtuLuc z-~?lem>=^U;pJ7e?90!&yEwAjsM1|apm#G?WpRu=d%uT;1&{J$rd_hKHI8vE4h|m{ zhHFjj?AnsHX7g)0z_4J)DVzA!+1?v-17#V4lOEfDPFGe|{u~>7_$idN_Txtq;zQqm zJBLO;g^n(5Y;Jz+>${p-QU`7fL+48!$M@sTYH>;X$f@Z(3zyC4vgUhlv}D?i!R`(EmB4A0#So@w2PNJ!RK{=DmF$&im? z?IS9GvYn0;#i@a^!YlIapFcmWsqxJY9iHjQ#Xb|5x&n{rH2M0~t24Fg5Tt4kSGOWr7MATB`l@FkXd4z8~*X^*k2*A=*S7vzKI5VKe z;*R!h`9sGiz)}jYQVtg0qQ?F(m6g(12sKq0*mnG?Rd2x!6-;U(K74IhvOiNe45kx8UsTj1@Sej$axH;P8<%F-g|+(9wxjZLcV{@}YoZxlrYJ`ngFxCOpsLg*| zxqjY%_jS;O;FrznD>);3a3|}W=h}Z!(k?FbSz2iiC&ETYM=^UgZ!$kSI|y(y=tr^3 z(pVEP9>zTv++DW7Jy9X!>aosz+GW4~_i!peUn8gFL6_A82yC_jw1#I@)i`fng*`S_>)mq;Q+z>K6AIwyjrme&2Ms&jhzMxhv> zrlPVJD;dlWR;lrKv4XkW>#S{4WF+KBL^u~MA0&{-rsYQz0_F)K? zt`D1wi;Mf+yQZK8Fru7C{VCzU@FYh5D@Tg4O%lu9U!8yph?~4zJUt2 zOH*F31Zik!j)?tFp)CKg@R;fe1*eUDU7kK=dSzV0US!?-=)r>r9i4BNFz*TU3U+S9 zL=%k{GS^4G=7w{~GVWKjwzA?I+tvP`|95zr94B9B(TcMjB=cbzFD8%~4}*fpJ=T6< zrkHEk? zzV-Eu00?Toj?+4g-UzKsg~}Zmi1Zm--{& z!3zKW?qDH7xD4gtGc=c;OUs9|pSx*BJ-Rgka|v@98Y7QIg19O2(0_f^e|fUKQ1^@@ z3AnZgdrnmH&{i%&CLyKd^Z*isjl`Z z>ib|qkCnMlxbCB(s*gT#`3TKEzU!F*0eg#WzLQW;P+(=2{d&TD6mXkk;9WymB^V`* zOYE)}&nA#z%g2$t~!gS4 z#p<)0)(AT)`}oL!R3x@7yGxg?492Q}dYNc{5#G_EiDelP2E?ox0arp`;qjGO+_`f~ z{o+N3u|`?~nj>s<>kJD0LSDlk4ggJ64UO0$W=HDqhT0+Df1!VOwr=zn+kUI@_4S{* zyR{~OjhSHPU#oO4xYkc>VU@5Stb>FHt38i0fja9PrKmmY@vYtNE- z^5hA!QZXHo1XEEkheluj5Vj>;`xQ?d$L3f*+wOS0>ASOf=+&!NIo~>SkhbjX?Cv-@ zJph)D6*3Nki5_Rr*3m(ORs!rG);4`&w6c}>{COBmlb>KWwM(i*acy0=aDkVXm*$zC zrsn$zvy+X<@(-~28b<9B-rQ(7url?9wEcx_zNYtNTheH3!wKM7kgf~M%LgmE*wbeI zY~KB|y&>}J*RO@O--gUrS8O{{l_<8C+hu`KP>$1ba2Q+paDLq0SS~v{V^COJfStwsRoD4JfyG8_U1-so;O{W{3C~bZiHg<%;`|&L zAyHDQ=c^`Fc5s(|u6g9;r57@$9m(=NgCd)Zpf#ys-q5nKg=(cKJ7@{jBU+-h!u`?zs7BR$<@`_F%6X~(JJ2s~4c zpTH3f&(8}v4h{`*01*qn$+CbSUjVJ_c)(gxQW6iuh*i-l;p`s(j&YBfu)R=Ajp4BE z&(G!7uCU0vx{8CoE2U|6n)ponY##g}<|z|hSeTi~docMJZ0fzBax$cdn(ZYDKR-W2 z?SjibGBPr_sVU_$^APlI^LWTC)~|7!yN20_xQ7h>XDI-o3r_Z{oc3H zdV=Sq=+PRO{svSDcm4pA>9o^?IxOQzHP%xmgh1>d$ytnT7{9(UxaJKUg1zn-wQl+S zWdIuibic5)q~POIt#0#F+?M44n-rJmueQl$?2~s!QnIP;Wr8Y5Z6v-|SBv&bvs3@u zS?7>)o;tG9!FZHr-vX#J?0|(a=$Ju=JEXEcm36ImnMMps?AYKZ380MX>WIM3S8QZX zo;->5#72(rii?XYC?-2NIH-4XkHs1Lpo|3Thlk}U@31=}HlOb5dJrBSJ|N}M*WW)1 zbcEduXL|F)0sl#Oy(Fj0c>Z53z;_WbG5;4YI1V2^91$D4$Jp2yz&Q1@uHu8e)Ss}3 z^2YKltbz)+y_Qg2ErWGpz&aP0!i346cp6MIm1tw*Z-U-c@SJM_A`GbZu`b- z!!f8u#_NwJpV}=JahpKg`-7(gjYLK`EakipNGe~)>u z@7uQztERAsSv_1FZNTcm*Z{Oq83d7~wYAem2=PaIJGFpe@vEOnY60N$0OQEm&bspV zcG$VRA6+a>SqBtK1G|N46FY3u9#fV(LW3<%lrYG^mhaxjjqO|Q&*hDcIb3GCcWIu{ zogNwS1DnTr^r*b*tD!2-0Fb1Z?1oQ9ckp2So_Ri>P;6KQ6XuSa+o9Qt^xWJK0CP@p zalKz|B6ohuO-)Uiv?hpwN=wWdDs>>m8nt63N7%nA{tNb4ox!?2ps+9l1}*a9t+B?) zZ`IxvI=`4C><(k)$H-90_A!70Td!H4j%K{QjTsi|#)3)T)|T78WU z1>f7%)s=7$d<*t7@%_7TyySCe!{~?l`rU4G0~>R70}Ty(U%q^aYPs0%N3fXnR}+9F zOpXF-i@S9B^1;h5)jz=JDs!rE{rwT9DWC^-e*sq*$o4igJUk#HgL|;@ZtW@wym_e8 zWLr$j*X+xgBki*P#=^!^GXDZVU@E|mau+Q1dxeA9AnoPLM=-By8yf>z-?EEY(VN}4 z;jl8Lh4mP}@{sV-_rZt76A|o31)x{<4mc1aYq7$Bvhtp|f6Xx`-xL+?Cd^gze))1@ zRjRG64SO;H^{Y7(zxMPf85yx--B`18uqN;rA@_A=o5z%Kfy=BO!W+(h&`{3R5+K>Co0~6w@M`$P&7?S{uT>uIp>@R6M z=d*ogbM5!Z8z;GspE{*!C2#w&wpQuzOH4`F{^Rg8KHe0JJ7NFso%JE#2CzI>br73! z0l1cWZ3y4{`1}dnQ*{SRRiXO^^0s3jA&A-!Rw}U10!BUpD}kMSe)^`)0g$h4>bB-x zub^RJ*`M4&edFUpa;8%za%HpGR`$~{iBQc=eJ?zYO=4i?|F<}0eY|3f4iUcQT|fDy zQHe+-11KWUSCiR+kOXb9SMy9KZbtJPS09G8gvnreVEfBmWdtCX6MIaauP=pCJ4_KI7x#!@2w?#-DssANO(qUli=@u(^Hx zoX6Vh$hf!$F*66Eib{)lxI82HgQp1zsX%wCmo81l(f~f|*m>|ic@i6|CvdicA-qxo zSmak<5ruxUUa0XP}{j{DJdz{NpK4ZQLnA7VJ8-Nn^RWZym=B)adCUa#ESNR zk4Z@2bAFYVXEa>Sr?$A-4AuzSk!oJo-Fepi@**ql^I(>ESlEH}w|YIlz7?b?j1SiM z3OP%gH`8zb-I~YZm%w=o^ELk*{iwI|A7~|n)4ym}0fXkVv)ZejHq8*qb)N1(vHKYV zF)^{AxTcuBJX6M}?=Ia0#kPxgg-@vclpA=c&!0aN6EE;x(9k%*F6~Yb5D<6=2Iu2! zdrwb~sl9!;ZGUmlO6)~Yx4krM=`h3HW3O9$Pu_nG}TTjHX*etBLbnQ660nm-azhSVXuL+gz+r4`?Zql68&m$Tc zJ@244gEdUly9280XJ>{QrXpd%iCedB*?_ntENpK$IZt(@46HF;q@c%QU(Y1$n{AvD zQzu^qf+YGlI9NTf3X=IJEZ$Dhiw`lQ57fYbg(eySkTAK@f9rwLk4L_*y1TpwjPg(7 zJGD4Lg=wr01po{~Oa?CDT8&Q<>rs;ZDkJw4UPL@WlL2T0@&~mlD4d{H{dZAmFb%TB zJ>A_+#+zdX3V_z^1}hE3(v)u)#1$vB6at zSQn3gr#8*`x>|H}be4Y>hRN;`G-1X}13Plj>}&k-BS}ls;Z{8wlI(Nxr>Sc2Qp$#>T4?~CiK5<{&QcyLmf5ZtCJvvusi7eNE@D|9%rG!S zOMt(im1K4J&7EwJkIg8`JqdMDIjrrIy!~EzP_6_HtHNQUNqKtf`XOstb z@67b%cE2%IoV#yW?ws97JqOb<%X5A1+H;_xxIYms2|08tZ-Gt+{=q9{1CS`lIx8KP zbbJVSsc+%EK0kCEG+ByA{bEsad(v5bySl_FUq3;C9PJLUYgtBB9_eXmio?UhL}GMO z(#0x|RZapf0KPIiC9*1hGLl`l*1_8OcLKqmS5#CaP6Y*GNnGcA_%g={H?6Ht7PBQh zdv+N_gTK*24dcqj@}z#|(}T39h1~99E2^iWx1V%uTEMbDbLNc6P_?)4yH^(2B^ibs zQ$zl&OdniXS;0+qoBra9b*3+sLKsosgoIGg)6-+9CO%O2_4sNDFv+k=&=oU_SYZ9> zBqkzviqNPx77H;FvC%*xFtB0BmZw)tyIl%(4$n?23T z$A_niVERrjR*WsW-??*#_i`3kjw6dp@3Ge>eC2_H$Vl3QPUI(edEY-IKZwD^cnI)d z4;9^oeB&A!L8Hn*%nk*h$Ch!A`2{dYsqW{82lbCyiVF*C!R%suL{fjL!?D19Si0HF zj1vzDz-F5@MjRa|%O^ebqssHp;^Ly&&a07;k%xUZu!w;Wqk``0&i4q<`ctP*rwj~S zi(DqTe-Gg3VIjK*-uyO-jsvrdli&+)+S|8NWfWQU1S=>i z<~GhO9nC%JW?*{rCYR`|+a@M*w6wHu#X|zed>gMHp@{%i-j$5SeYz_p>;{f-b8`!e zi@yYWtk(J{hsp6cX98FpHc3aK%~i0U01hFP4RHahv%QxA;go#NViA;Xc2-eKIqa&j z;L=P!o6^Dxg3PS<#*({qF^31Ys)oj+*RKUE+7g3az2e7WxB#V3Wqp0hMyaM|W=86Q z4qlt;?aeo?9T+%lSZuSwBfV)&XPiG^*_n=QH7;AwpHe=GG7%O{851D`D?y=!g*QRF zO;jtoSr046VSVm;%F{i@X(=i9L0MuFdSa%>U4YzAuzrRoCU}sL)yVnTgZW+t{ZYjRo|1fTB* zVsus8B>QB7SmgKL={gD^-p>Kzb3NXz6#ee+R)Q*zS0~z?wNW=g2vl}PhoirO$9r9S zStP~9rD|%EDxE*mN3k8{I4_%_yB+k+In39iH=gE+D2FyBDu$Z(H=V>cdgWRom&?{Q zPh6~)Dq3J>s7UPXauh11Y6kQlAcm&WWO z^imd;$uIZEFO7`zy6ODX?4EPTiR|e(7D-a3922GzTNN#3KAcNxum4hfQPsn>OarRTHcI{O2JI~^C8vk9h#IZi%9qR8&Jty2egx{Y-Q9dR zV`X`HSBF-zvoD#wmWUwX$5%dX+4ew~iC)xWm^&Eg$G|`ZXB-~)B~Qtz@AFkyO-)dK zy8G*EJuH`+!my{P0PT0mb%Dtf2p-o?rZU*g@4MlzEe!(!4IE_N&onn29E71YN|K)x zeQjr_tJNl-HLCzHqtLG9q|^rdl;k$j7)-wQR+q%@zCe?6j$i#qD>r3yT^3i^d;77 z;a|l(bUKu1Mwy$<8Aa?(Jacz7?N?StVNpp-3?LAINf$dr2Tz=nQ^&?XniNk{4JQEP z8EEQ)lAkBlVblT&sFfNNHxKg=j*Y$7A+)unWsV~*jLus1Yip7`JH)i2cjdqr1-YHz zMOnVaMDivP#14r;@0784+?ahfB5G4-5~xA3ayAaZjv9tUR6&wE6;P88D;E#V#k|j4 z_iVRCRBVVe_tbhA82H%)ANi{xWn>7Lvqo-pbm+K|Aq&YcU60RIFhPD@!yNod(45Li|BsF+JA zC9a>t52(g{!nLLC%T)cla~*>5I%Wpt%If`6R%%@v@Vsm%V{2^8?gy8Q2EWB`@)*9W z6;cK0s`Bw;ZPl`QPW2;8FD^Ugi8`14ib$|CK4~f@X?#8!bKv4nC{NNaKzcY&gIm7c zF9rqJ`#Bh(FH~)Ay3>h07j1+j``<&cpFwx4s6GSv;cReuN&GvhUypYi-J$&kq#H5t z&Phr4#;iPy0JrWV%`qO1WCrrTr41L-^;5?WkBqSQvi|Wgfi`|LuQBr7U5~lRg@%`# zT8IRpW>_huR@Tp~x33NUz0{}%bNUEG{(Ptwksb=&x&QHz%uu-}E+VTYNk(Z z=9|3$;88qyN{Py|d0!S23a(MQ+l#oVy$q@Pdu-mAste?VszY6#9obWCJK&GD!myLiimp#Ph@X5kdk628Ym%+Tm z!NCDJXH6ahHHr6s^L`k;#-^nN4fxJlh#k0+V_;#ePWKR7(>&Yaz#LtmFq|0e*E=Xm zcQ@H@*X%H^ZW7eOkt(2XbbGlO`fTbo5;HKIyLpgV?*@QCI8fK9GJh{pXK^3ctvH52~-I zzN@O7!t(e+|JAjfSzE7I2q-tne+ zc}tum*6#6UaGp4)7i7f-W*SNQ&-BZdJD__f$Hxt=v$eMYF+{&sN?LKE>jjoQitz-I zp_9j)GAM6{pv+*WbUukQAB6*w-K+^~AEbSUTH!Hw^Jg3S@*2PiIK za?;#pwlt9B5>++)VMp^KrQdIxu5dK`aVrf z4MJjlu~Xol<6ShtWoJBLratgNPe;5Si7NBlI(IAeYq)}17y1n^pGz>x3St3*f?zTQ zwcFhT0JCliXBronLH&fIwOopb&u0~Sy@h6D{H*N3uS?9Mf{*mm@##AlE2{y1KQd|l z<@v?U&z*tp64DVwB4|+3*$irDBg%_!>qnYhz1s&$lpC&L-SNnBX zG}1$_LxW=ZNAP(a>bLSj)PB03?(tmu?cRiHH=YjtG2o4h8Tc=6rbQv+8sBmX3j20S zB7@yO1APXm-iiuJ28NltsozE&;4~47b;M!Vf9R&yRcN+iqrIN5RO2x45q`Y_v4Bbm z=m`dZn*Dmh0?^0ZVlI#8)Pvv#_(K%s-m7|99v&V*PWyas4dKmxWcDh7q9Ag}FzJ=7 zy<%rHI}Y;+Vmd(;K?lXu&j zz{}CqbY$xh*thX6#WdA!DX?k0>oNsnWsO-j)s3llbCw#Iv9&a5$ZMNm0acbuZpgnJ zE%?^7-WxUOO<^e6YuN3ma<5+4=NRpM{}TahCiU8avhe?eK;R|UwB&0|o~aA-s8IdJ z9O4yr=mW2M-_+54G-Du^gVykvI~9j4>Jw*(+Ijy+N+R`yYIrKYF+4UqIppiS)8qG7 zhh9GFBfwZe%M)BLuC?TCTVI|5s<@-0q>h5rh8Emlc$Bm?IyL!_~d98B%5t zMCWizLu12ME94>%-`9o@$wcgLhT=F{J5RX@s`h8b`9G`k9=UD%F>u)wn6LHWlOZq| zGIEUlz4qB;>pWy}$1oC-^*V`qBxI9U7Z<2)^qGcfP#Pnx*EhhZ7elEsgf-*3eh~Dr zY!Vu|vZ+)to_C;C2AMb;Jw8U?U!Su{mvVA)TArThyb1SwEEg9Lg_#}P+S2w0)t4CK zVFWTX7-9syd2;foNIR5@Fau|Dz8qjDvAP<}5;3-Jmun%W zZGpl<7M2!?CGFb!YeDNNAFo>IEDe5qH42FtVVf$u&`Z@pFXOe?JldQ*`ecUQ;#<_ zk!MYnTm443_LJHSo;Eznh}z;QO^-iZ>bZ_yz7t8>cYE#Pm8-DDv#UJe?=LAHu0Au> z8=Qqfov01RsRgL8r<>*NXZrW63GB2wylN_Fpg%xO0gNvx);>!rP~g3~5hmX)~5|$I~n!hUQmXC3M;K2gk>VI%3!FvIEbYf=4+fo7ow~oSgQwx8t&b`Ka z*H1hk52butT%DY)0lmN1yyi1zoU6Y*PjhrNPGM|>1FrcACaA#&%A5|N+2-eS;^@%; zgUI%EBXf@q>_?Quw`LeR2*vH^9|k9!)6IFLtlYo^*4COZwYBdA21$Fo8ey}s8ifcw zz3ZfD$BA-d6O|c5_FLJ1iv~;g>8Y66cX7xkWgET9tEw<^jX!I`d_W&1{E$2gf6}eo zFMFWddcFi+H4FKpB16T}9U3}lj}|%Pt(CiipjcbeoJ8Y}FIIh{4t@;b151W*i24Xu z2y7tM4+QYG?{^`o0Re*fK}kuC*}^W)(RpKr&WCJjKxTX%IUGMyOqkGo$>7!IBhYVW zvF%%Ri48UWQOApPBSlYxVy|)5Xd~_AZ|$y;2l6i(+?K|Qw^uRu;Cgl1&MmR7R#U5WbkHR_r}JCr+B@s@*07+`E-NP0JRMT4H1!`iXxV-%}!lj3t|$qsxQEqgOxYu z;>=o1;O+F(QfwXsbf+?8Xb2btjhqdN5uJ+O{u+3kKKny`+cZc28p~h2ax0U&)BIk1 z>S8^-G|O!ClclNYd49fKsK>9Hz350pTAF%hGVQJ6;Hm)(92IcG(mSN;Bk3xxvSHV! zYntKZua!*dB6;fRTT6tNGcNNCb;0=q6ga$l9N!I%3WLY{dtdT#CRQ-WUkT zsCMTXmfe3n>l1J>)Ru!MIFcCs!*tD)pSt?IBRtX^wbU_IK=Wl| zu3LMt1q$m3Q*=%WwIAQ?jGaW8w)5cik**{ze@*4*D>o&c|2zaQdWI7D(Js51#w;7W zug~i=@RT2mqiUT72Brg!4*_A_I(7<%Yw-T^@BnAiduQ(KOp?`_ktJX-GpqrK$c%}y zLSB_E3>~%W?V0^rw|EW_m4;5-)%N=y4MKDONPc|o4l6SsO(`4kaG&VuVd6lmjWxu) z$nAxuxv&<@+fkb^loV(3S4Rf^f~XdMUR@@IQa!f$JvqTq->u&{flm4_WPKjxnnYM$ z->vTJXB)TG*5xUu8B*HfhxnRxcL@T53-?F=*ngGr{tVFRvg2SYa77j(zI%1|;|0V& zcP_YjySln^8nk!^jiY+Hy}kX}_I%QpLy-54^mKye}7>Q-7&m54R$W;O=@CAEbOV=SB6j zyIG8ZlB8SA6qDVAS739dBcwafhLwkD(C`i25%sF9m;~55@D(||6X-7!7uT9e*pgJhC5s1 zS=o;t`e&8wh*Y>BbF`ijrA|vGG4@o-l%|$lYPwgAlBMRd9u*E2{^{LFQblQPb7M|u z{IAhrJi?BIX-b(TC{00evCEkzb=}nZ-DU5!WCf!xo=R4mdB4-CMv%*n>Q*hupZGxLgdSklf_nvdz zbIobz?P;y^_C}s+3}m{JuzlaLArAK>qqvtROP&7H6&yxewi(*s6ZB1GZY8DLKl92S zuN>WguAS1$_7^)h+2^Y=7Zi3;wdj43ho^JS!Cy2H}>%M()exJ8^wM1Pdqh<++^A{8au(?=wMK!hgb?qhVxPKh+6o11!a-$RTv;!Uy8caj0D92(L{&d(V}lS zTwX~|PzMn9O3T-hB>sft`l1rsI|A3IO;0!h55sGJr!%c%Y)A`SFL;BeC<->cx3khe z*ik#@ktEU%^;Iq5_dMCOTkmNagbuz33h=t(_|r_*3sMLq*K6vBdli$k&~Se>ST0WJ z`JPjyl%n*61Vsf021-SGZ&d;ivFE@A@?fF_i4zS<5dxQBECmtaEz@x1-p{8jKMWCS z-!{nj)>3W|+q9$OV*+e~=NsLKl*M)k@3YlLbG9DGQ5~EU5tZkcnS$^s!QT5A`z;Zm zyx*>_awnJ<$LaMugZ_vT$UW}RYk9tL z4;yG0@OOKTJ2a%iqerKgB`u!&i3v_=f2ex;{;bn zIg~>hEWJco*RO(@Fi)I!Xd_qXIZ+h(&q%%`E&;c z^ut4jS}apc)c*?v=HW^!sRr_el$=g_bKkXw*Td1v?dT^*?%Vk4iqiW6qGLdVBJlwK8++Cv` zv{&CL8VW?Pt6{wAnk!g;f7q`d`p9P}98E^fPoMQXkH=$<>niL?dOE2paxpskpwH{O znhYr=p0J*U-}mc0AT*#75%fxtR6P+D-VFn-5Z?zcZpQ{RPoS`O=`=~=MM5xuAa_w^ zix4B0Eox2Xyx+ZS_SDwqy1%DW^hW&$ZgBL*A4<_>B03$D)j}XZshx}=pA2_k@b@p%?&GtOGL)ZIz zvDBh%)0m;FR<%QVg?9AD5-o7{L4^ymt$UMiOF5afb-|Pk<<5ud>)k~k*1J!vf|HXI zKt3U1z5U*0jEsyNC?sUm(9rNv>M2LO<<2-UUM1k?$Wrh*db;_8>)cDu%uzMj^1*z( zV6WXr^V@8lPRuVTcL>C`vEQ_$)hkh)L!W-E6(w4* zpR{_mZ)OI`Ha6H=th7vZH;Vn{uC4tQeL|-*ql2L|e6lpam=5MGlk?kj1`3-8n=)8f zcGkhi86h79y{fuK&RI+QY|5Lz$9g)q$f8!t(9KynQA+8xwY^=pqr=s=!$p8$!~h>e z#3$E??H5<==L!ov#Jw3k!_zw%qf$)6R?1yDBy^KIk|)<_nTmm_UG=Kz_7V(%6pvhj z#F!M+2yX39;0!uqypFb4+w&@CWM}EboS?1`kO^Tl7=;q$d zd|R)l4UnT{7x^s?Mw{PH^7RR$l4#tevSwySVCiknv|K^rlEtWU5?4v1!6=~`YV`PA zR`A0GmaZ?;BtobB6%qUWEAEh3{miC$=N+B4L{ymzNLs(UJYCP`Xc4oAjN)=Qi16_7 z>B_aOF!1nrnYcP&PMeJP1IVF`J*$LP$RPULcnMcZ@Y-C{B}AHo4bCPfRlM6}ec*0J zK;K|XbDVNr{|){yJ(34ztPaki1YcG|rvGOt=oi zvaMDL4%K+foO4Enzs6NAvnazkB{#DI9?HN2i8DoTd zc&mFt|NNZsmEU~Xw-~l0beNLz_D=;Jd>|*>V_2}3_@$VxN9WaUy488T#a4Ex&ocAA z`kwwH9WRvoqJM#vJ*xoLyoGZDKYzs)PiqV0?QdbBTI^=lQGXc+z*x-|+uLyxGa6!) ziK@+JKN9Qn6BgG){b<`jcfAcScSaU{XPhICm4)?B?8fGm;~nip*5WFE^wf?i>*n<- zy?lLUPqwd(o{O1n^wC0djCE@C2(X>9nkwz3A~B*IZ%e*cL%LQ1{U^CC-P162W=&K& zb~XM)b|vgr%Xwb_GlLSWuxg*8Qj)>mA~B{z0ppo^;{j1@6G}p}ck93UsW({Uf%m#nn9aL@ZQ$2J{ud)of6xw%uv z-CQxOVnu#9asJ5yCeBx^Z`uw^T%aAes!Ri-)V z7y!(IF}{}86b24I*oR?(6Dc7w1bEDG@cFmy0u>jdn3)ax`jTevt*%y8d?A+vTF^q| zc+X%#GLi9KJ$!IY;)__XY{Zg74W(@N;_iu3YG`X4-yP6h&Ny@rXf~uJnaTyNhe{YV z#*Y})cfHFrUaqPayQj;&HA`=`q^2TGvOHFI@gP}nNRfeVOarz}zq8&wuMv^~yTISq zU+eQ$lQL&Gfc1lgI(VO+n7GMR2feuRtSh|ISiPqdAX7smobfH*hH=zXR96@4w$jrP z5dkH|Vzl;@A~jw#2mAfXU}ZjD1fc&bkZV{dTK=Z7nv|M~0JGpX=IjfG<6)tF623IW zu?B&F|G}6$(3eyZ4YF*-yxsRFV53zP)YCY=PX0l=Blq)ZCcL>W8lz;>WdEeRoaiQg zLAzCs>{%UL+PzmtMXI;wAb}sk2bNyjiHwt$cEMG1bUq1*i#%EkkC2a&MTr3zFDb`* zBc{o>w6v`I(l+1(Fz-yC>4`?UlSczi>*L#Ai^c;j!kuDPx7RiExwQa6GrigAHlori zezr+Ph4Xa1P0%z$5I$$3_j$NfY{fK(@Xg$w@;z_ zk+C%uLTlzg0)QJgsjO378@I42MEnRwl1iFB_xZk;;y2A|KU}DMcftTPmvwtaN6iqP_admSMX1Pt;md5?{`{_bu>0`@Pf110hj5Jv>lLz1q{Qov)5)#9%8vheY` zj57>$xIiAnU-UO>zLRVo+4u-iDWmtDKljg2qWRbu7Eo3m4z@eH$i%CtM2u+}ai%9z z7Mzv+7HByANejdIW$=#eDun1>7LSPPM*iyMZIAYYQc_~IH8kHTCg&O;8>VHzRLtK3&oe2pMb*GbR{^{#ZBXKnS?D%J+;M&VIdoa~=DrxPxOV-ndx0 z#og(0dp?dev40oHI)&=>7%nYIzBSf@9%;o4+2K7-d+hSBib~P!U(yQ_-$~R|*R4kz zVzNmg;8N_VCDPMkf7eT{8m#E2#R~CHgh)TSz(n*Zvy3%rcD#jS$b?ogAuUuXVii(o#9Vx9@1QG6ff$&X@A-*6#jfY;uxgiW?w? z^>|Yb(#s!UObLaV1CH>@OZ~wJ$DoVxHH-|tWmOaje>MZXY>%dphFW2NF?NW?ZWk#v zg>+O`!=`jtGNP`GYuflAZ`8-~#308X+AFaHKLD5Nq2<^Mh=EZ+-)LNd1$K3Li@8=( zUe_wnC0P7!KN_ZQ-0t13u3>wl44?xob^BT`Ltpfjm6!1xwp_yJ;X9L1TXjLtU15A? z+ax5TwdDrzc<}TPaxc2?=b15oGYtFn@c1E%^9kzGu<4oTpVLw;QW4JuN_Y>_pOxk3 z6P|u307v-*BIPSri2JRMebO&~e3O3n9{6<)YM#uzKWUJ}V&2)p8DG%&Mz&lQ0D<$3 z$k2q#BXDoOuq#M|fYJg00LY(11b}Jb!ngne0Ais502%-)z}eFFw~eKpHNB0ck&~g5 zhme!Ko3p7Cy|azXe_YVH+u8sD5P!b$pU-0Iw*5LG;>b6e$)%$-Y%GqwlZCo$5}B=+ z1lJ|w-zQc4<(6?x8V_Y^|4Te)3OiGz!tuY!DnCBoMk zutghP&o0=4arU-R6=8q!0NyB3Z=qd#lcyqMJQ$oyE_sx#hf4}V=}AyPn(Ob!K6bMC zloseN=^(h)Ng8wN>+Cj?yPJjBZ=14wR+JCk8J^vF&Za&`7VOehu|F3!fZs~9V`fD$ zPuvzqg}$3mGWyU^1NH-g!BF@0C^9vm$;KR@iz3VG11kWY%0LSAfRMwXhP@gYW}~K(x&FP9nL7)Cd5B} zmy=0Y!ql@*1{!%pAk9$$e-eWHdW(#D87@>?j}L^`%<9HWZ;h$;){fPtltKJ|0Z7nB z>Ue64KKzm1cLVRs>;s*PSFYWg*|gd9QHISPJ>6RNHPh&RU-Q>#zi$WT$y={$!a5%p zzerPAlBDiy_31;?svaN5dGn2oo+4&CAJ4Ab)}PH`xK|1WiH?T=&{^w^L*t)cll$}Y zKQMY{j0smapR+&BWgH#!9v@$3-5$TUg_gCrQ{*w^^K=mCm)P0Oqb6M&wP0J{H=h>I zY;N}_5AW6YT{!PL;+w}e*KuexyR~gw)Ya#Svs*oVUyp1Y-@jG9o&I4Px^>%J-^sHRz<Z?~gF z@q2vZ4@#J}acT1mc(+m1_a5`;tbEypAv{Yz**$vqZqlmL>lw^saQM6(JiMJIRV_xX zm&sF%5J(unL1zbZ4w=%Ck0T1$d*9@oypVhd#^TEVRfywLnp@wTbc;Lqxc=^}!PoTg zu}a^3x;#3=@9fgMR_}yLTb;y?YYh2TIleNkz4;!6BtEallHt-6OA3t&PB`>OBttL_ z@-_kSYj{xjeE5e{nTHSPmH76U`!2$`JCm7SychU7m;WgH%2M{5*85oIulw#`BgY~} zRSAVTHV=Z`hMNz%!LXcZo^~=E>6O=g8EJk0#PFzV%-j8Y#mB9o%%g7vZ|yWxC8%fL zK>s+Xtt>qzPBu0foRkb(O*{|}hb$92oD=-dFoG->)LKaVGu*>mYb5?ld?CcrbiV+2 z*s>&LUee+eQ=ALbcq9Vb>Z@+e)-QtF{keIwzf)KwM$GRd{0%IXW=f^`pdG$Zaxt~Q zp_7)pBAuzcos(;Nh-LYW=6Dr8=bt1OY^l*9!{yDqByNs8Du?o#&qzQS0)pB0&Eh3a zkM6rvxeExrE~{wM#$#_X$HnZ>uF3wFWbXA`M(*;+lt}$|ThztFy~$5}URh32kM;2O z02a5;Z{xD>?Tss3VB|?yW+yxds8LL)cAoTzF?DvuSF(MiRVLvCm5Kq#E&8!Za!szG z+j)qnke%L^!k}+5v`d}B>q6{N3abRC6BaAcv_x2Pe7JVl`hQr*YcBygmv!@;n4GkV z^G;qIBWIjB{=V^M++6$!=4(ZmTBXtFV#+vA<}N3n0dews`ey4Mh>zn--@`4lSqeHO zyjJfgW?-~?Rv}`u;9+KpWhL^{L6*&=s3}%IEm{N#ZAuTfl>llD&rN7YLi_gH1uY-bM`lj(tcZgRMAp^hvwu>ovxnZGJN zzXDQzawdvO>Mhk@%f>eEArNb5gD6N&{k^Pn0IEn|NwwFQMJ87yN>CU_|4C#u8_q&< zJhqKnrzfWWymL{cq-2mU`kUaO0?w80FdnMQE2?vF&qbj*@9Mr}h}R ziSu%9rv~OIbKCZ_?kX%6*pCcn&CoFFh*oc zSknXSt*dk(yHE@p2xo-AP=zPIBGLR;;zfzTVPy&CYb3A!=3By!~_F!CC2l(b`1wEQht zMD7{YfYCjP-ocQzL=ps>{yr>XADlwbSNY-jn_QH?#}a~&h|JBz01bs^7OqHP_z#fS za2}Y&C_S2vV+J=1(YZj3pa$YXf4e9m6O)!N4fG)eV2El|W>A?5a6L@7>fx@D2Q)I8Htm!%SG2ZrfSDNcdg(z~aC4&vWt-WVq;P!4!(+52&ry zR6ZK0plX{)6lpeNJ?NxA-7D-ZvMs2N3+TzJ5F0vW^w~<+bwQ6*%+y#|c_5$E5CUS+ z0X$?v6xQD{*unYq)$O>0DJ{%>y=l`C4Id5`2tXjJKUL-qI%c&95*d@c(UcP7d^mHa zmvpTtMjNj6Nh#gVP}A@;D!hNzseuweVx^jhx!dk`O$7iS83#iU|DvyQZ(b1tb8elU$NgGLH2 z(N=I=^-lG{j#aavxB?`4Ud}Yz70KNsRf}xM+-M*MyO$hQ%!J1AI1F(18Ai=ZSpG0< zqwFa_n9e%WPKo}fo0Z9#du`KlI=>xHBB5(oDp_3VM7!Hcbf6R4&j##O?hvvalZc96 z>MRGr+!Zhw$jJ{ENPbD9fiok^$>Q1l9d8$~o>;I0tUBpEYLU<~7yGvt&#yKg*i%!! z`Xg*O(Am+JsvdVzn|&x)BXzypoMMl}@*mk?4&VYTxV+fIOca%SHA%=hu+9pyY%Zfd zn-Crn6p9;o(rdM-IksKJ&OTz9g;wydH_O`cGw0(!CQf}qO)WWrS}_5X;CVofW{`gJ zjvRml=aQITcH-9^EYQ+^=kj~Q&Vk4;N{^s8VJBirG zx;Fef$dY77PI0)Kgz6&S;G`L5Uku-iQZn1<#n>@KZ6P#L!V3m_8Y(?vWtaX^VCRvW zVQ>lv@%$a|jv)bX3$#*v*)LH~liN$*+xrsjSiNKBv~oYt%YFob1rEY7JcYioI_MGB1@W{NP(M*B_B>uod4rQ`qYyd^xqpQvQV^PLR%@(BPVkdAFYg*h|2kaGTeRS5E z9@?-LM+$hv++IgM?S41wc5i-uJhQjf`eJ{*wvMmwc4jU5-rw{0=+ikKTy~z9^?oh( z0{&Bwik)jZ)?xwxl_CHD_x~eE1&v*P8@kv#{kI-fcd~T(A7LtM|8v9m-&g;aJU#Rp zO+1%yy8OyGB`Cj;ZDmXnfE56h`YnwBFc1920mN-Y$N@|OF86)YbM&VD2psy8?l_V$Z9)vlMXA?dnQ@#Ba-ExHYc=;NUX@#h@V zC*}Db>|@@*FI7Y23J`da)Jjld*`xC1*=G~RLA-Y#e&E|+YTkSn7tm~dKGJjE_kKP{ zzD1>feRW&R;k`AF?MNl*p`3#3b{qFZq zo(;hI(|%4KE;T?BKi+S8#e;^kHs4ZH9;JzhJrxru!6fcI~0uyM8VS@jC!X(F6qrnUR089sBuxb zXWb11*AH&zMgAi9+h6UMU(Dh^zYPY(V1v(ue6(mjLil{8fD-Y8qX+JzI41Z@uK{9F z{H1;rC(%UyeE9r92Jf3>=y&%g^<=caJlH+sub=Vc`awLeNh48yD)+CMDcmYw@c|$J zoq$^C@*CStULqz;K)gGhFdCp8m_wFxQbm8J3;I(*;I$#Hf55WDAmUz1O0jPSMBxB# zFj8qIeSU+>J@96*8`-BsYARwDy39}ys!K_$X_C^VOoE7;yuEK&*MAzyDJ>+4GcK^y zyJr6($4xKdIXsGym(-BO*CNzOQLz9nW44Of&th-^b8{oKmnv_aChQ~4}9(4z50`QSK$j7`E@RRztJsmf*d{K$`V*Hjs;jD|n z2pis>#Xy3kM%=id4tCf=OQmz#J{q+_k9pKi8;NV;UUtw4$B2A9B&wRM9pKJ>xxs^J zZAKkpSx>i0mw~S9q$vU4L{a}n((0>tboioKgL-LV<|We3Op@K1zOKOsuI27Bl`VP{ zh;aCqVrV8EPI_p@>5a}SLBZ)5*?GhtjDSwIhGf5JxF-+JcTx}OlkquHK!m`^BbTrk zGLSfGI1dGuZ2}qE10e-Eub6=4uu0`WDrAvKi!QJ|xe*Cwkbvj@Bsed^ytz{$4|$vU zNE3Cc-}`ZLpHCgTP0m_3*_Jy?Fbkc-}O~v_Zgn{!FnS4>zW|>8=iTfm;n!7 zQ?5}$fHVZmSF$ENebSnzg}EEUJiy4YxX%VqFBQi`)yr=Dkb_qQNo~d>H4VFZJ!$z6;k!UYKmkstiqd#*f>iowp(JMt>9PRt}U>H({m#j$p#gn=poZ^yrK9G7aPI-w+F5 zpZ9V*s-6TgVALeBJUdWHz^izt)Zy*r5mY_>!L^A{wW9Cqb&Gzw7nWV(02$=xh#oQB zp(Ee?bwcBcEm+*po6D)WNCs3C9sGHspicX>P+3;>kNU*<4{Mg2s%oPv4W~82`Q@mm zx0y>T^_A7YDP)+>!E02bd7MJf+o3Y_!jy%JMAN8=%6ay3%*t|D<+uzresze@pm!_h`YlOd zsLBk_K`Y$!QEc*b;CBXFR#)kHx-83_i(tulnG3cqIFZw(I@dcRd%EScpa^qe2(z(* zE%sn-vl2DGs@2P{8cyU&GiRu|3@m)1xs<|1qxx+<`kb{nj;EFio3v4bg64N4vbepq zRpkbO6{t}x@FRxJf&}F7N#$=YaW=>GKc6+f%pOXyPEfhI1v@pXTyfrX{cNddeY_gv zAJkG1y47sCF;nVO!Kt4+a;lu#tJKZYOgJt%H*bv~waz}QU<%hxsw%+d98r+|EF;Fr zHeUtb_Sj!Lif_K}A}2f%>Tqd;xMHler_vg9YT?=70g_7wy`_8<-@!Ti<%M4n}=i0Wc!nw%o z9%$2()(k#=6O(&s*Xpn2*NzeLXG3Jw+ydpnBA}G%4;mkfg5+_l))nV zJW~U#+rQbfzTrZLQ%Bya%FW9TvCL&*hrYD7W|pH0ZJ*n;H8=i+TA}Oa##5~(Qr*gW zOW4_BB2s`%CpI6&`g_t-gx(D5__3qhA{b3bQ44qaxG9Kf#=+ExpXe00EUutXmJd zVL=(&f_58&O~|)ZMU6%6MuEche^apBaASL2p(5`Ftacss+eFo|L9W93c5$nx4w_@3 zCkxS%^qSefbVRFO&OpYq(!9=HeQM2+L*7Uh*)$Lq)#jpc=4?5~j>b{rurXNjAky9l zwG;-hOC0K)LuK0{*bKP1MD^@#MKJ23H85sZ<}RJNRqCSXj!b8%l+8i~OR1i!IqikV zJRQOyE!*tUC;L$q3zzC$ncTvll(N>#uYb|%c=Y8W3cS?|Ete|RcpP8CKSXrc*`nXK zD-$3bjSg+?w1?(%*1hGd!THO%D*KrIOO$*tNh(>M{6LNUE2ev{8xn33sH)FGT-IUK7Sv$se-m= z(@4!kAm<6+j#-&7Ovs}PyaA`#eZ#QQ6o}tl2xW3fUYJ-eTgKhW9l9CdTRSVvhUz|HK}^s7Phpah%u2?X!{B3c{eE{em^5r$+#s# z*b{rnujFMCUq~u?n?tv)j~zTS;QybLT$|kp2?5KYgF6WaDFNV1LL}m!K!kJ z_dWyMC~d8R7GOXt^F0`dTFI(l@9clGho5ryCzodNQcS^Kd@YQ-U;|^nzY8}nCm46F zQMOuQ&#+l|VApal=gGvbQ%{~lZPIQe@pLQwU8-y=#db6c_xP#DtKAjVecV5et#byN z{_FRe>WA4cWYbZFF-wm*7u(Dy+fOxnl!DUV`9<{P_g7MGktj6EX-9}IZ7jB)- z(Wf>no9g2I2~FHRuI*YGEp2#jYV1jq1%>P&n4BY5B%AxIhbp!2Ifsb*3#+>J-KlUf zbO}{Ye6p3Jn$UJNWhK(A7Wq@IoebtiKYoazf<6QL{ zQ9f+oa?$1yJi+EnTDDvRo9(eTZH?CIK8Z4=e9>(c96L+GLmE#v}mXp;3D{F|th5lTw3QHHJ z!d=jn=bmB3>-lR`C5G`2a?LX1J7>XW9$D>ZTvWta+G(WOq8H`lBLO_xl{wNb9XhpJ7Ale`;||2`Q>1?RAF&cx9)UPEUtzaH*S6NkUaKf7lE$ah&sPMAy zX<6C170kg-&`c;y=Rq-}cgeHcmrhkDbHQ|JPIvl9bIe$BCEP07o5t{77`D!jytOdT z4~KF#uIJK0GQ);NI$2j+9YW$O(YGsndfz8H*DgY;|B3Rhv8En{lGM$SV6NgNs7-Aa zOR`&$VrJX(`Hj7CgY6|!!=5GQjeW7>9zPQ^`;V!uo&{mcEHbO+HniGxcgAT0RxeP| zwFkMiRohmjasr-mGBL|;TKyE0>0Xo>S_BWpy1www?*tfUiDcK zbv7=-20VC`vU9S3=v;mG?%;WGT66HTS#_giT`Ya;(W`eVg1R|Y*%oYjtQltj8;4p| zSOi@$$g8JvPHL#wx?^R;=YC~GU?Zw4hG8f3ocLVDR=R7Ba$9)!C`U(&k%tQp>#7QY zF8gGEU|{|@`T)pcNLVjVn1=}S-&dJrbr=^+0o=xg*O^cgyxHAdTf&FEXI=M{UUcPiiE{z^L6bRtb+w0L?9^qe|D5dJOAIZJ6Z{XCB$-H8 ztN)y935U;>An6ALt!wFnpjS_arJhU1AgXbzMGiQcW7bXfWqe-e*f=8D?~Y1^UBWpW zC0WcRh4kUUe=c=o{jOVPt;G>U1}9f_X&x>2$!Q(?FV4;>xRa>e*RgHewr$(CG0DVs zCbn(cwv&HsO>EnHzJ0Ft#XeQ%RQ1KW=&tHowW_PvdfxZ96l7 zjSq^qba(8Js?@~T)>fsuj`c=owZ!Hx*#L^^2-GG`qnk>5wlm=cPlIgmBxH32$0xyJ zI5y3uMYOqkp}&sHsa-0~)^TQsk30*O#4K8z>Gk!z>`pMpE$UF4_@hWE7G{`KdhDY9 zF5F_&e6QGgGjHR~Aknc>x*j#Gc4v0dgv4Cc^7LOl)FX~N{pDa)xgzbpai!Qyxoqte zm8{5HL;10g%o-_dh;d9UX;##oa(0_XKn!uNK@MqjIh`&Jl)JhDa7-4|IpUfxvSMr| zG@+A_Z#BDeJ>fVzw$mvh+Bs3iNscO6TiV@p3P&{O$S2ub!Ptp5pljUwWSXyAka2z` z@f&UCRHMq)`i-zV(gRrKW? z1M@h`Tl9Uq*_-wZRt;rV_w^3?xP9LLS=09Oe56e#`tzv%q$J+$Wu$$!CQ;s_-$eSk zi9CiG6sQykB?#nz-rKq(P1K3i{%NF3aq+uQ4f&ffa6?2K+Kr-@z-(cyQXnN!2c}j| z)d(T>uN*r?GeZL{g3}0{TBwet7O8s9Qb#47ii8e34sMuxJj8!Q1DU+=lSQ-;ok}DF z+I2SG7@Ve1#l%{B;4!7IRz!{AE=rMwypE;fj}}QaFm1omv4}GC0tzk#O5h_6Ejr0W z`!FNB$r*pmLz;|T@~pF-u$(3zJQO*(crB1JSau#1vdL2h4$#OaJw-}{ii(zK0CSoY zSTt~-oha22ifM+l6(37(@S*#t7|9PyuvE4LI`RPT%+1byEir0`)QSE!>*MF-zgX@+ z=-Bmeq0kdI&B$5_uMOpcNQE%L$=1-s|0ICu(iBYo$`p4HCgKAqekR|)i%vlzm_kp| zn8{21K&8q-ia!TSqKT7$Xwj#eg|UwVl7Uh)$cXv^Nu~lyoWw=Q+OR8)4DzbLo$QJG zfgrHdxb)zD0U`M+va)Jm`Mi?`w~+>DQehE=v63IIgBDMpie+$8i3P}M!kBn$k%OV& z;yB)70poJ-%k;z{3B>|yR))~VpMk~0BxG!ZLLZ_N?PH8!v8;f8XeEXj`I>!WW7!lvrZV`d5s^?0}VoSo90V?Tan~F zZZpofVTu7A?mG=3u_Xx>0Xmje>c!>wt!p8W&54$w%I|Hd6Q2Q|5>AW<#K0VY!%E<)5-G$nss%Q$}X!2;? zu`D3IqX;Tb;X$eo@hri~y$dopTvx!$qjVa{m*@ZnT6!5 ziyf0C>f6#w6r5ig9_e=i7idCgm*Iqw0;7zKKo89{vnPb^Uj6Ir@Sq6+I*>{GL)UP~ z?WPdA2vL*$cWLfSDP4>>^xaz!I8%gf?Q~AkEMds8V+mP=H&33?8r;KFblK9&z&Brv z|2O^XuCb)r=O;1$j{)KRCb1qNp|pz6oT5OIXXvh(vfAgu>R8{0{r&^2FNX}r_|Hh) zO`_fN?|=h79XV?}WUOpYI>U ziD#YnxSuvD8UO7!>(`r~=e9P^Q5J4+!LP-iH^u+SM)H+7DOGTQfJ`NUfH?oZ*a*x2 z%0+zE6EE7GuRdaK1;@Vwz&*9v{ z@aoIk2wfj`nl6tO_+80B%w*0ra%9rUexIukZb`iF%H3O`y9UWYpNS7c>j2%bfwr{0 z{LfLt@24`t1Jih3`ksHN3w$p~CcSmL_YmWoMT<;{9FxkTvYdzEE2)9k-#g*AbF3}* zsG&2HD3-ssHrd2Cq%=>CLMST3WucHrBb_YMW6uQQ$qb9$kB+GLA{%wr`~6~^utV>b zU2jiF*PQ>vh;*~=$F9NFj7zH@+U|8H4WssE8`ZWD>d$F7@2odR(B0>{%g+_LK=I=E zk6Pab{Qw?=%et8=fMe=w(~kzCXXZmWeA|ylmmf_3s zSHAG*t!}ak?x%6rKX_u8j{6@PL7n7|vVGZ&KB0U2)&>0Yn43%br(PCv`U^nr)rLGS z#;M#c#^nme`M)by7m-qE4Z;-$2m;0p8d95fxV-#&p#%8^{=Tr|-uye4ZgUdUri$V4 z|B~f+-Tn3!{SpWG`9;Vy%ZmPojWD1JdaYQN%%BJag!i$v-~X1$Hx&JQ1p(~yhuse( z5N&Cdvn4->+l+Wp1TE$E$J4Ls@!r;G931ecuo9a>Ny#kI06i3w3u6Z^A#)1eh_LNi zcIrgZv>WeZ1kFeWVnTffv!Hr|x_76n1>+YA!P0yMbOx#Q-!hka9gO|%-E7HXiHp7Q@)JBL9&B#O6W^MVqTCMH{x??jZt&i!6-P5mHyS5=LghWJ&*~h@$u$0%uqd2#_4#u$M|? zUvR(#;s>874Az@-U_ov)3a4UHZs**u)0>h2(MDyN#G$Us-hH<~>6N`K?LrD2T+t7l z1$SE&|Fe$8nGw~aF#gieBw-@qth=a+8b2|_qE{a2xRNhI!KvLbVPVnu0{iGje35VQ z#Q71)eG{CtDRxM)=&lbn4HNnSPM3V5n1RvEYo%3^5_GEdHWyx=#?M*>)<}_<8+8cZ5Kx#;LYa zF4I7tGB*iCESz@dA`Cfb_lZxAlDSZGp(&bXOY9GGn%blj*Q=E{ke75f!uW{!qiEB0 zoY$G6rU7D>-O)V}?5kF`zx7_aIuyIEedx{89f#A*bM|-z@)l$lMI*h0kbTDn$Un?C z=;+w~e~z>R8+4J9iE;cHfb76vaJ&&yGS`X;Suh*Ds?;5;!83M(Ix^u&cai*~GsG$H z>G-m?Q{L5HbDbo=aHf|9$&NP`^Vkx^w?X6Ad~O6N-3q#BcZRc~cFfel@Ef2-%O}7X zx<5IBj6jBg=|MUERSq5l7q&-=jU(v~Bm9n{S^pGbHa3FaCVSwZU;~mDt4AeGkP8uR zLSxx9ZCaz?IPf0tig--rv2bqPwu~|UK>J$8jcLS=|5Hb$s)TH;S&i;{GdI{5X7TC& zBm8!gk8R9(4mHk#O#-aR4)sYxKMwZHj=VW=-DVkhf0Y383rMtRj9p>3E6|4!fea$e zIC`rI6un}`zFLkgZ*i;EjE2voCNkg`y1n%>2Y5r%z%DZ4~SCJ zKRCj2u$~h+>F6C8Z=L!dIKqUy;>d!^NuiCCHSwDCX*DDu1ys?#YFsWv$P!JtfSBKZ zWiHl=7$h~!F~Eu(We>7zpqZa#2b04#5B5xgq&|-ftGv|{VWxxb`Ra?H#rQ)exbo3F z^g_C_%7;klzkjk9!jGbU$HtS?hs$I5u$3_<$jo#4&7w?}i^Wff8wq>(oPH2&MY9g?`gdkjOU90ewlq$#-xgzMep+JRpPNyf@}+`iqB0*$ zubA#QA52HiX3gG|9m>#dJfF?)L*mw00cIn&Q(~nKQHn(#-Q$IU+{`uy(yFWQ-k>8+ zJ-W4sX~C%DGo{_su9EyHtqmuNin)tJ=+`H45rv#yJ-&8u;XNt`&DCPP>-dh42SjV) z($Y3su=u#0TUJXltlp^LcWS#jQ{ol8YNcI^g$-L7O%4;);IT!J9|m*VX{8GPd}#dg zHtv~S9dT;%<_dD$CoZFRC598IGZTvZ(;PTareU?xb2_Q1I~6=`FD(szQZe@xYYln} zD^-g}5-D0ra!;W1Mfrq`(sJ$lmy#`$7CY|uU&YfL3-uduIXs#mOB!oKlTL7udM_1_*)rKFYC2?TDRE_lMUfv2}#{au{FJw>qz^~ z7(aAo^ayiE`!LRW)oE*Zd-#|WjhMTtDS7^-_wB#pxl7Wwai_bbWD0a}C01*0c$v^n z`8CE@>YvI>MB#1oJYX#X3_YYb4H*#(slRX{e@GHyY z?3dq&TO-~OnVl$jxTib;zkzT zAVg?-jrZ=KDo zAJ-ewrR&w=-sb}FmN!CmxUOOV&sHmpH4Zswzzu5xiK( zj4O%SysHl&ZMk7ts-j&qI&Y2SqvdSWaU!~} z=NRsAw0Wmuj?^_SXYLS3o!&NwqMY`1gQCzkW{mR`J@!w3Ff0VQ5oI5K@4|@Ka^~E1 z_u0WU=cnkU*jn>ygY~?<;ZdwPWlJa`+K*Ms(fnf#e)UL1KiT4xfByuKrl*9yzb_6kw{+C3Ep6F0DntzO z8p*ChJah8TRh4yATYM0i#zM^EPcN5t*%$aDVx3!)DBax-!n0`b*%rO%2A_|j0GcpZn6^QIMogT?$8<7w%Vp0D{S>C`XwvZa(ly- zo{YU5y1&a-==d{6*udJ-c@xznXZr5{^e9$h=2fhS5@poCs4EXf)zk2B&XQdH7?y9R zRa<#ivRpOGrj}P)mrLOU@Y?j;T3u)(l5af_q*z1T_IjHt!Rh@5M8Uqo8!;}_+qfH4 z!6ls;pZOgc6LcCf(M3g5v~qK*dbvgaR`Kd(t-1QF%Us+wvoxfwu2f=`6m4+W$#3AL ziIn-N^K0Yk)yn+y)F_x%&)(ZsM6LjG3Ad@zIdv|c_vY|(bWpeX?GpHZJyE|dIOq$| z(0g4Si2552b+T(+C7-hV8gwZU3rk^;Yn-o??7b(&p*!cvnMF7zGhn>D6Jq{MxMa3m zFJ_%>wh?na@3s4Daxo{-$|A7pC9a)tX}v2b5?@vGW+qWn2@glHo zUShKCsGM~|l9JQnPp4S+C78h$BIez4q#Zak_t-Mc-vV)4`Q&@OJ zlYK5DJiNZ@$XJ!URk-C3i;az6OJh=njrALuU^M_Qw;BIIrZUPQQMQcvOkOcYm|~x`Z064?QY{H$Bn>v8ZzOo0+7vZpuz5qR&6bG_-tTJlwEp#j?b8*#?Ck^JDH zLGKy&fq^)pt3ywh9a39fA_~9}5p^dGU&}fxb?l`y5cA}{s4|uGnFOBMDb|+cVWU>LRINs?wi^Y^EZsrl8kYn+xQsb>4O43EDb2~P)0o=lBgJjwj4{BsF;RjF+r3odMqs#h+$>GeB(rC>qmLr{C2<$gm}(sZSgTHUPkz|bWSx8JqJK3rnrY!J(RY}JS#>^a?d?=@uJ~}Y)RWoD zbiQ)=?Af)^{N(3pXzTSh>2W+lzreYX1VyhaEX{)X@x7*g?07&rHcoy*+@oEbY!y}6Pp8%<6_d=NMjwT(YjY~ zp_N50+h`Iczt*y?9SIO-Q@tl4HC8!%PV z(D5j-aYRx7CJ7uUjOIML8mu|@XzF;^u*cF@XmwwoY3Z-&m|0-%FPd*};40*k-~WBE z6_zcwIUUZ*C|^eIB~@YG9_f|qJ>-PmHJ{lZ0J+srWW4Y0vGmI#$EP?sz9}=4!j*SI zik`HM>t?!evgOd_D}zz;)P~iSG-V6Gc0Q(Sfp;$8R`{5Cu0C^BlU1{n<8gINC&xI` z}|G+=duMgP>rumL2vaF?(4t=4`&? z61T^89~Qh_f-%3drxjY`=dP{Jt6B>tFBQi74tM1qz31Fv;~LE@?^f%hRnu|6j^PP- zf6&60J9Ut*_5*#&4AyWgRwT;lmb#+2$#%P2P_FaZ)p>4x4_nQ=n3t2WwilN;D`2mb z+!1%+9otyy!lKtVSO#TuB=Me{N-ee-S){9LnsR8b!&r342q^77NKxXF?2U66Z_ z-e}ssaC6Wet)N8K;jQ#dd6u1OR8DZ4_$Mlkls%W&RI*dcb-BtY(-2X!TZ4v%jBx9$!(Cw)kmGRIB*Cbdy9FHsH`65^uW%-?F0rys^v7Aa3l?kr^Kqu-#V*kFTLKfJlj1@^K#CKq_@=dX}+avixN9>6* zGq=v0iC;ZE185g(>hr#5u)#($~v7R^6Z} z0h5eG)dVtz*2hxPZ;s8w)Y8wi@ULCls`3;Fz9YzxnwqKb&Qg0>2p#*VS`r+CREgp{ zvWBQi?!!EE5>`qAExA)uNlhrT`Y2zHeb8{^f@a!U0neu}yGKPMK4LN-RFCKnOi6pB z2SRFuxwvnMPGCjy;c$UOVQ-rJoeH$ZTekuXmL2&d%mH25d=SZ0B$lECmZ&#V@L+^T z)CBdSGmeWI6f({P3>*={CKDiZG$bf&rD(rH%E>~`;xP?f4xNQz9BbR$=~+WAM(9YF zJL}xQ*h10|2$%x190VPQiW<<&tfn+#stk{`k0S)5F^I)u)t;{s)`)3dc}j%IR+vb6 zEJ!J?s*H`r#~WP{^hPf}0xmv-pr;Zf1X_p=r4 zl+ci#Fk~`L3n4)iYa{{D87Wvs)F0=4HWcJw4$&QSMvy}d@y+~+hff3^9U6MG2ucQL z%5M08R=2NfP^j!S_m|qX9hkFwOuXQm6vAhqJH$L0gUQX4zwyX2}uwf z9^~kI*uVu3+Y5@JS^pZPKqiV=xrGL#DDtRa_e(cF4hwhUuiEVT01TR(ov)TSDliL< zDnW9v@JOKBw^l=h5p;G1Vla`Dgr?H910xyW10*mPLOgQretW;Z6hys+l4SNCv_WzN ze@^lTaw`rx*T=)^mS|dZ0J4Ap)`JP)ReLKTtr`tQ{35MgZ1s2cQ`$NtIjFM09YC56 zv-Na_1{KIVd3weccmI({fbQPr4R`x%Y79=X&$s;c*JXI5d*4s={EHX4m|zbINKzkg zff3_3*+4IZkLS;H?PsfC=y&2`k>F+uG*)h)tc#kFJN`?eo#2RfLFv*qiXXH+5sbsB-l!k&+rf+H+8aoesMSy zuza==I!c5`#Hg2N@!qn|o z5e`Ez07zMc&Efxy>_*iq3tz{#^rBPu81*A&skhEs?kCxhGV3l&O-k|l+gZn9Nfl%&YN?;jasH{{$>m)}3{36|w z5a|ED{z}4Nv`P^bMxabQCXF=RNzCZx_2WW3^T5%Fq(a9bY*cm44xvjO2OGJQxQ76RmDO9lFK{AM%%k_TUt{ccRqzA4F5&vfN>j`=NnRRpw zBz&J|yX)Cvn9fNpXyYB}_<_~sCUIog2flTTU~18$V7kkUY8okZE{b}ViLRhQS-T`QZsT`j?&KmykSg@8zc{eK8C9lu=MUcyJ*9^ODBaS3y`W;}Sc z?JV*HT{hMgKZkx^$954<)>Z4%@lNstwWu6S0{L%-7Ps`LkH=;SnIcJLu+efb9pX0( z1pJwDqbbS8QPbcj892gc36IB$e%i!Hpn^P%M%zBLL2$zo;_buLzumMMIjS7h#YFyu zbiVHq`seY>V_rO+AZA^Se%-ooUANJ`JcQ40VAqj6t5VUu=b!s+qx`&jn>@$$DQ=zpd*SeerGlu?OHix_&%8_0)GL3HPwcx0ne%T* z(bYMVrFb&eDaK}(jk=$&UA2dwyUodWPSLLic9xGTYt}airk(xM>zkuUUB*K~>u5t- zd|zvfS6wQf1*UO9rcq3x`1Yr}B=ojo0XQOfq5`Gw7agj(G^#nNH}`$i6{=IgM_%Rp zpCGEaHc4T=8>OlotCkBvGLZv?{?Ho{kT`~@v6CUNCNp8?77cSp`XS zr;6ZPn20D#cWMSZ#d$6UUU9{^u3vcKSHRYSUJIJZXfIvY_uB@rPKzF>!}153x%vLW zO#_am9IupaXdAGb$U_IiJ`mi4B(ZrUC-9G;kEb|BAMMJ&=~xhrthNegjU?9+i6rcG zHiWLf&TMtkPe;SE>mYmHIOcw8ub%pX#$Ky7W;cg#N}qmrB7{ic`J*)=z{#&2xcdg3`OzS(gvy>HkIgkoF0{=#(y`f%X+146g^~#BwUI24PEwWP(etNBJ2K zwUJ%`v8tvih|9k4MmG;bTWkb{21yeIHejJk2A5h6E9Ith7Yetpl9?l&H|>-qu|}~D z3ob8RfdJ36!m-}apz+qre-G*$P&v}+o3mWwn#V_$Uks-cd#1^_4T2tg;FUKoaULdG z2WHX&c??p{PbL)VGdiVJC~jNV&A6n@k%9m>w`B~2V^<_gMxhhUJeM@4Ip6@Z(qHce zMimXJjh+Wec9NQ(`$HzZWUjxgW?>Z4T5~DNK_4T&nRo8mO|70ye#1qp zP5N*xxG7qAO^3oYo9irymWv6zpsvA5>(y=>62>YBr-)fw5LI=d>aqyQ)DO$V)@lP? zpdwGnv%P$ZzO{FYK342B6$^Wt&Y}%tzJh>1i!)?F;UvKxAONWJ^We|pS;?m9Y}k>@ zxA3;9v4(~5*{HrzI$K^Zixe0z)&0xV_ClS5e&-g(e8DCsN`%ozs_xsX4i2Ttj?P?4 zQd`7m$JYukX;KCY_pH?oh%KQ+g3)fV8+r%si(a3jRi#Z05SREsU+!yW25U5uU+>BXGsd=qz)DzzGlif@>2M!J&kr4um#T<<^ zT<<`-=WvtweieNnY+xO1z5=p{OzjQO6?ylI8iglGa`&z@H%AG(041kQ-8p)8 zz#$zzBON(0)fiLu0gpC_yPZmM<<0pXiL&RnD%!pp{9*3~ai}S<{xh{cy$LpONC_WA zFZ=FZ;16HF6nl$3)4oxsrN;;7FZ))SZE{|Ra ze>^1&P)1qH-GH%>N)e*zeG0hvuaZg&!gp%bCP76Ao*^T=KUw@B21OMb;?=f!{t5Q` z0^KGAPk*zN9NArYGQ4^5cz<$!lQjOetxmrQL&ZVxWgRLItZRCW`bJai6X1I*>i=OU znDc4NXQV%!G4Xsa`vG~CzuhG~@$k<+a4kjgZt}(WSoGKYdRFuD&p)8_$PeyWzfSnd z?i%YmCdI$J*fsc}TKjo~WbK3g_z=Z+d{lxwaI~=gob{_c$Vz?I{D{cyStkhm8a(;( zXRq3G#6Wn+W5x6HZ$3cuZVv8Sx90u{Rh;_i59fW&%8_~4O%Xh#ggia*?GEnKMjC%( zM7W)O2?+P_3<)sz2|SEl2?{>DtqTQGYQN7%dIR{d3hv<+er}GNK;y^8i>C_He=65j zs7a~&uKR)6-1Cq$#6D(0T+dHmCLW{F>+~H6VcOK+^h4b3s1<^Odlkc%g_=_s)I=I!2RPlNPlaqSTwgOzWAqmhff5; z3pLqHu#ZK~3m?W31*MKRA^whIFZA+6a}>&A7N1lV1Y&~NI=h!Z&JmS!+|SQEJ>IK# zh;0vZ@}70t0I{?U8vnl^4~VXaFYw}U3dQ!~Pv4>NiU0bXWE!v=oSeO*@&lTl)(nR3 zQT`0rIh=l%46-8CQ?<*-ia@pCHN&0j2^3G=i3Wdkn@Z?fw z(@+mBzV=dzUgfpQxdrao62tUP;(kF0dEE!#wY}eTIL!wabG9)@az%bd-RVjwJ@(UJGZ7DYHbuVC~;vUq!X6YfBb41%J%wuZz z<=4DTYe?mcY?x;xG`%oYtzfb1pT(&22%$OhB#rkwgZfx6*a9tC4UZv3Jq^!{Z6Tdw?Q(fxv5gTqG{O8;HngEnK*nJMkJh*Qf0A&G;A-@BZ$66xC+t-HtmN9TfQ|ag6K@f{^WC6y%sdm^79cfh7`H=(is_0Crb7keq+)8ty z=OcwW17Rce0XPuma_CSUcWK}lr-udfxX+#AYA;mclQgBt3H)quHxL&NB5DNSFdW>J zGmeeKW*XVh+!pF2S)+;?*(?RfB1GJ1{f6{y!wA<6_0nk55Lz+SBGV_6@j2q)jr7_? zj?D0OR&YlI`hfFxI}uZ}Kq*Bg5$ITu&=3sDWZwd*V69zRSh^$>8Yc>wF(YIZvwr;6 z?}e=+Un8oG!h%c=I{P}VOXN^~iEesd43UNXYx1ychJ19Y{)IKOz!EwU3?LP(YvP4j znHwVe-A1NF^~bdVr~w{Qf{`KxlH9T!&Vqz^tBcbnH)~A7KC}ELvvRho}_BWP}6Rui|<}2CPRFc@`;Z#m1xKW~2FOh+phISA+jF8#{ z{&f{>3Xnc&QGfbP=6Yu(8DbSFhfo69swiydbi^M(^GjM4QTk;t`}O&V489Z-wQRY) z7N1-RFnkR%Vt8C~pwzZ)jI?n+DiG+9GZ}2W#FWYo%pvCY-QC;@yG6r8U+eETLLiddOkhK33XQyS}E$YIT1di;l#= z-i4ARjBv{nbsz8`4MJ&LZ*8<(&^d#F-G(tSXS6eQ- ze9H-#CtSUXXr1OtQ$>KN;15*-KpEWUxo21jnUF0;gg0LPf}5N<1*0I@O#A_gc2Qk~ zCJrGbK3Zc*NDiHM5=G8MG(EhkCA+<}pyv;adO>1no-ML}pb|F?Fj{nbq!7;BV1BTvjY5WWF@Jpw=7iwjXEWx9FK+QsIY(qf^>b+jD za>V2B$+F}dazmIx<7vqw->s zGHeY9yqcJQ>$o#E#_IH6+Xp%%sYhs1IXh-Gfp8!J@ya~sz7sx|^4ibD3^Z9DaR}{5 zRXPDQ)URY+H3{l}3kPnV0WQe5yZ~dO9vE2yt^k-8W3((t7MW&f?z}NykRA4h0*s_W zA3QP~Vs_s~F>uIUitUm~ghtTgs!<5m28t_MjVLF&nNN$9*aDK^b6E0^yHT7;uu497 zL~rbqSs)Tz2uzxT)GVo{-WR_`JQA$2by@$Dxhf<`P=6!-9TyB^5eTb8MfrKHTOlRp z{``(yoT0oZZS=Vi4tsF56(OED&LaXeEPYBPe4vu4nN8~{yi&245J7WEGa1-?Sfz2X zQ7q4r%C?{JuR8Z)lb*eV$s3+j-b)3*&e!O`);NFHh5tSn0w0YCl=qftWKKpH`=+DvAIc=*6aly|P>OaP+y312( zT(8?gWEvYCqArjddNRFL*3p$dWA2~&wl}fc1?leZmIP@yxZn~SW$%K9{tVT^kSFLf zsP>&Qr1fRr>t2>8D3@LIz`1NRxI6v*G0xqd?4#$R+G1gp?A&Cp@~vv`dYl1}Q#nJp z9algI$k6Sw0RnduR6l*9oiMYhPqnLC8^_>{;?SE)VY!ei+S~%@U2<9RRT^CCeLF)n zrpZ+0=s^{6u%JY&0d~z}b5LZ>Rl^h5%e{wo*k&!cte)Jv8rG8$vRoazCV#Cvr9M=o zbJtu9VzugcI6Rj%?YCy$e?`-xWUSCRM&qnSA^RDqg)b)b9AI+t%X8=CGw11VZP#v! zS0_%Zy}*0rpV&{%%qmzka7Wtr1WTa zvSrV@xs0ox9KNp&u@8V2ZAfcux;0|RzGNS`xGTV|)7L-5?6(TuLu?kSKYB$WSL7yf zbGnOR$~2y8kXbi*U!zTGIO7+0jdM4hnYj$|Wz@!~8q`yhOZJ#~E4A1)rBw4$ViY4< zOX7jI;6SxhdiS|oReLVroJdfmmjJ4#O`fuQ>cB=!;Bi&Hhl$YV%r@{k&@C-WpRbZr z0M*>Q20SIyM(*{uXo{+fHID4gkcpLmhY>P(ydmhsh(i|U!x%Jd@?obDW%~{qiidE0 z9X5w>@CjX6LC34FL8lY^+A9f5GsDi5`Mczb*~FHwB^{S@$eT=pLiIww$~51Dr5pH( zXxE$-NWnh+?Ho@Zm8EHZ?MLyt6q=jdpz%Ma64o12fS%0>KE zO7TFrx*q%2oq4Q-VC61=<)z2{c?6cOW7oHHi=lhkkPfu{dgtVb7Ea@$wq0egMw<>k zV=;r?FlR%4l0bF0^t8fz$(GxqZd+E2YYh4O)07FReZ)qUQL^Kf#@NN-pM{LZ&1aj< zEM8pAq_N2DMz<@sj?ruHMn)mZL_qgPo{9eRz;{g8FwgzsW! zy}#Sm$>&FwIrpa?(u&y`PSuC4_`kKYd53<7CdakR&;;XNn~BsrhZ1$nVC};?OnXX0?DjO>=a=Re2e-z?@>U%%DIa zbc$q@Lcv&%oZd zy9FnCgH7FbHx4{Ik-FY5@NH97*AH!e*}0yV*x7OpHoI*TjMiM0>z`}9@XkJDjhMUo zY^g)w*V$(CrfKzTpS36yeXo$LbS&$&tnBQycf^c3r0H+0IydRjBY0n+;#xX(O*KoZ zmV0+WxOKGWfvKOn<10JH#4Q=t!`o=;owr>X;a+Zx$Q?+)6*cKSo30n2W{o|IZms3H zeOg`jGg#JY4-nDsHT9v&)-SzRaYuE8P@e>`01H7lm4-y;`2OTy^SWtNZ1T zl{{RK&8^8ZI+2UHvA$g^Y*HaI-8-}9rrcF%Q=+b4M$_BJic+TD)mxOxTdwH6a!JJx zd3L>+7HPe>;)5i+BHh3u{a3hl>vCphvVs)_z08B8ZQ=GDPxEcvUPWf?yyBmhEhc!~ zYpvcyI>{Ts(9wNLziy2hKDO-al`Uhbj&`NBiE_w2D~0qzH$#tIgY^P**IrL-p4Snx zgx01YU%5ijYfAfzgKwtFFAlOs+x=!Ivn*+M)^p0&ZP@3+s!)`YRlCNatfdXhv77Wf zInk6)A+W{-h_oVBI)*=slaY z{ig8WF-A8oj+}{2S+9$1TEBcaK~&VlpZe4|o#=()Xa4M_bT`8ANBV<|{%haz-;On> z;3Uqk;jIjTA9)PPYcePBjlionJol#H#QXGr4!?gy6fdHhfq(JIne|urP4}w)5gLxj zLq6Yl5zk$T>z#jjkjTAd%~y*nF+eLZl+4|Fw!3@t!?AcX zN#p&qLCl+(!8u*yUznj*+JQf#E5FHgWgm@0+0<%3gLx3)Ul3~jy(7+vKsN}D~uWhs<%Y)8(?=E1f(ukpl$y*Ad?^QN;2 zndyQ(eF_gGrNL1azIC=<-;u&SU8-IjP7P5WpzeM3*t733Y1AT%Zu`Cb{NxS11$V~0 z=DHbY!uPCR_XO9PM-VM3Mb)-BS*oKVZhF90iEy%dZzCOR=RzP)=goP#w6Wu{IR@&op0Gya38?v0Gaso_T}(@I)}PFx zzvgPrF<7nNymr|zXs}K#^r#P9b>UtJ67{de9tE?Ge z+9u%&cvbt+78(M>%T_%N=VKG=#)!)sQm4a7sU{yw=e)7v;xJxp`4cepV`cr_?& zz6}@T;LZc{=*7rhLL6m9- z>Ri(^_TlKkRbf}pNSLhDb{vJs$IMdjyQ}Y!f*1%SbRko9+UeY%qFa!M}ja1 zP1+C^f32LZ8NShSu1Z0u3UWBnkYTIEj_uR`mZMZ%V1(C!U?i{EqFF~9+hA&8Je+}O zv#l6Nv5$Uw(=fR9K8A4&nwQBA%evGsJ3d-$X6NPzNr&aRAMtCiNO|bd;yf~V&Y-Ey z9qaMh(_=j0-$yT7A8uEdJ9O$zglSxrb>>X2RL~o(0)5WBXyLYbB@=ARbm2rhksW(v zSq05Zm0w}dD+}G2+-Uw-e^8s_-nb4vDv9)vxhBmVwvtQAT3_oJx%J?cKdzQ7)#pw0 zbWGT0DOwvxOlnXwKU;B9nQrnipsS@2uKHVtGsKF`cAs)LlAfpHyaMh7R{OEo}v_{v|zRd=o#ZfG=&lQUr)z-7ydY}6ktih9zB@Qo1;nigB-L|6^Tw7RsgSg?FAGO{+_dm! z{KxSz%PeJtxj=ifxA2(k1onJlSHOt5$ED?Q5na)5Q5(!bS?zykMLE$7~YN+qP}nwz12$ZCktSu5)ihNB_6uobDC5a>dG* ze8@4!H|O|rj**r%A2|7TSo1EzvW7II++cZj>HWl$JDdp#?zD>YnN)5 z{BG#C_DO1XZJdN73z?>9fzM4=@F~*YTr1RzsaNT!l8FhP46h9BwCMKIHl4DO)%Fk- zLpeJ!hlcQpL}A$XxWo z(jWLzgG%e!;6LzNi2pog-SgEDEy+;}4lOj>WSFwex{LH3kC*?#;;e>YYgi=X+NZ6q zasI-Nq0;odY#OF!z-G;C-DDz&VB4s)T6wiBRZ2&7aY$ipsTb~(9b==;7D(^aK-seD zpf4QDzFJOf{HU;wgP}oVI4W|qUV|l9T&GB3tz2LpVXS=nqh*e9F;3ms({cUx5S~?# z!>BY{&{g%><@(3{$akF=SH6cbW2JA`gf(O+pfjh1YDWh>bYX*mCW3_#U%lNx|qq>$BXW~3V;~(vlRHulh9I(K z4Kv=vJHhrfibbu`n|1@Moz?t!a*X?>aq(&7k$yePr2E84{C0@><#yTu^Ml1ICe;;% z-zGW+SK?s5p*8{(Z)jHs;>a%cY?fz9T-($zZb&0$3HFW~l|DkV6k}O% zBH$k1BAwTX8H}xV=SdB3hHKP}qg^yCJes6dj&0E8NLQY!I9kF^1-y2ZxVB5IS#+?R zX@zrB>z)!`ZYx>O{uo?6f!gqCy~Jwfu&_ePZlYhOQMqm=cusy7l9M6+G{0X*^tn;1 zU4u;t*T=M2>f9py-7YS--jV)z#FVw-%_=Vm#-*GM_cXl3zddL<9AmJizWiFFmLm(> z-Z{aFbsgtV}dLId67HTB*on2E<} z?ddkmxG?^74qMBXTSZanQ0RrE+E8vP|C+INq>^;}^cb=E7Gp6cZ@_3UwPx3ubClqw zCcUykw5bNapyM}ApK4Syde|so!(~D8{zN#3>9L|Tl^vV;6r5mu!9l;_b2r=Z(!T8; z{b^LIfT_*ZepU0R-sq>ob^?pEQpH?RjTK~Xg9{ak)}a-sOyW`#J*L;3y21IfLHoCg zxf7)eN}j6{!(~mnP`#uL!^yo?A&xZHESKV)f-`Pm&jV(-T1qY*EjuXn@h#hjd_;u2 z@%WhP!0v9A=He(u+mNZksI4Xvrwqsni#p+q@^*(vs96eX(Q>CRjY1f zIN>p5EL=X8{la}{3~4QCmCE3LyY7J4IzZydg+5Cv%9`1gOhrU_wU`<`GNH9H+hD}< z&1v-!y7Eu_FZc@7c^8^sWz?07z?3Ps(ls2I_E?cuahBVwA!pYq4+B>%G}6b%d9CSe zE0^H+)&T6;s!em44oM!G_^W&*%VPM(;hF@_W680@LyIx)@5weCH7eyUkfGp(Y=?GC zy!C=EvK)nXNx5DdlN1{nc;g1%S&@qN%XFFx&_4fz<7$U$k2UFUsrTyO#zMuULF644 z1+#4`u(Dk0yrY(G&Nj3PmCgm}x`{M{Rr{092@8Vf$lwhM%a)ja^yjX0;!97Vc&*y6T}Q>;3{I$uKx*Qz(p&dUfS+A_A=bSzyYb)Zv~>Vs$xB&T-` z^b3UzyU|*mi!;f=ftKErzs@(s1~~%ex3^v9)+n?bv@yA3CO~bojEE*>UE(NH8(X0S zKa#SJDvms+x2dUfo}tT+3@A$zeQ{2X&J$)*{!;QXX61<2>uwcKU@nj;l=@y9jlZUu zGWDI{x#)O1a7#A?D_(X;ki;=kNrR;;l_x*OZavZ+ldx(^$T!Yv8fR{8-r*x^Ek!0u zSSOytz`KmKB{6u~(z%*l5F>?bPM5YOUJo+*Fu4`b=FSM$4Fsk^<`Bg~Ecm5C-u***I4lDMjjYUBRNFzbIOIsc>< zJ2LApJiQ%8XW7#RXh$Es-Ouvbf{kn&Blo;zg3~+;3wDbv z?`rjzHpA3GhTHjRmiIG0oP(l5Ly`o0IQ^O+r6NHkIcLW3I$4C4ED5Vozx|4U#Q76N z*vaBlsl}@wlLjzNeB0KcZvja~0vHQjam2{~76%I+xYwLgtFGvsL20uG9zCEBQK1%e zQ{{1tD*{TJC=e^fn?>V3eG^+DsYX?`<6VHoSftagFunlM9n>lib{*^&k~iR4xFmT_%GFKlY!39L0O96%E{R$xh^dwV7R;57WJEN0(?_O$6&AcgW<3_%+YkQUEJB@?$#-WS1%xRXo%cK*Q}mt(jXbPJ{b}1}(ePt|mvqz{j+_oBWBsLsF2$QWYqz%{je) zy8o}>gPvPZUpInYoQOBjshBgV^4@1Fo1xG z)(hvkj{5gWT|i1!h8$p>)zbSP!eZ!m}5V}R}mKR2iL{}7Eu&^geGK$zy$z+tfd zOFL71NR0kQ1$7*OPiu~LQsSSacpR67tgvnufPaNRJQNrl1OXkBhT#=~s)7kK0gFSP z9_NRI^qqbVGj=Eh6-baD%VB_27f_L;JuhQT^{Yc`L$8lT`LD*=L^G5nz`N zNtwkOIFE)NHV7=1=i&H0&Vh6hcte%JJ%)`-gIG2byvMo~0}f7!fStveXD}Jy)zm<&#$bE$G2qz-`S!|9Pm74B(aqD7Ye?*jo`hCT4>kpE58~Eq=Xk941 z&z~8?jZkcQwHdlNV9X-7q{!OOmNkbpCAcu1CV zn{2fJ?lE=Zu24`(I%Ei>`SJBxjvu$NxWtt6<3n8F0E{%FUI76?OhLcuKsyI+R{XdC zE8pG$6_EL^ftm|;ye;?%;9(0QV}A#I_qdoBaZ{OrTWqKVeQ07oWd zyk$&~HM8Ow|2MQr`Q(We0OP>-xPAU(ZYR^DErD_@i_Ew&Wt-dnVX86238>Bl!Fo{Q z)kq=#&pf(8M)73B1ndbr;<#+ZV*Dr(D07}UMjep_AoHm)1jvS4C}ZWg+<2Zo772f- z^vdcHHhcz#P{|oh4|bU?ngHly9@i$4nzINC0IDC@Ale z1#4OApUxvz6w7f)zy!)c6Zq@K<|*eZ;EliLKUi_It#VgzdkiWvyBByWC-tp%nL`l5 zD0Z5is;~R|RRzQw)r|_^{1S(YEE=T4!YEQ%AqWqG;hzM!02KmA8h|R+RA>QKCy6gU z_%#|AhELnA!6_A$lofz~-xqoi=JrxNMOe|@p)Jh3zs(V1Crm3{VGEI2j-&}`Qo&R% ztGg@jpUoINd0uBS`T~)k%0wKIS{Pm7-6x>ciyBGhStnq69zB`v7qqXxJ($}Q)2Yd?amgl-lb=CdO^iLe8%Zo@^+XkwY2f=|0lT2pWWi+t@ zFrYTJD+%J6B%AkX9N(Xy8w%3fyo5(S{C%RJYp*apCr=2wMUNog#rBpMF$Qb)_|5gI z@wvLDxwQroQo)5zX{1%BaWhDWNiH2qp!odRNQj^_qf&&w4sW1S7_$}Qj0#IHHDW?fuO+&# zpL=+=k1O7NpnalnI=H%66yWqd-~Q$ppF1yv0w1Ock^R2kR|}=-o%YYubJ<+htg?Lu zjB8+_rQhV*l%%;Z7l}=Jf!|X`zKP3=9M@Z8%iLGr_rC9;OOI#YU$iH;4>y+2ZLc%m z_jtKHW28Tu8F;@gd|!S4xj&;=PwtHs1^}Qy0sw&gKkU!ow=uQ)uc#G=|BwNArL|$B zIfCjsvXg?`61X-GUF}5TV;90jy|rC z(MAd^m>(F%_@0%%*0{2sin-wNb`{FHGWCA+WYVmjD_g{zXwvRe->y|%JN?`Da{|xQ z{qI#{DeFyb#>Udo_0sEL2g{4n_Mdd7+LX#lRnD-YWDI2C8`X&oUMrp~St-K|t&FJG zy8gFgufGmIov-v!!<6{lu6&Nt=_M(YN>W;S28Ci_DCjMz3lIvyd3VI zUC}p=e!cFnP^KMl!n7}w=>GWfPH*ej&39aP!)3Oj)2ej(o_cigysuA%pzB3%JsEi4 zJ2ZMb^0+(JZ`AO3Q7Z<1Kb)|tMO8ATo+O@}vPNokXT4SlH>P(IfjqWy==eYMrICNDV5T}jrkb28P`Uq0__pYqOyKF?y3i*5bY?a~; z{e0)umeg2v{cm)Lj+IWj zCcq6F!A1x(OcpYM6FH1QPK@4Bw6M}IBIC5}Cp-k7gwF%L?^>PnT$wZPdz`Qy7Yn>y z+iyl;hSo1GeBa_tO$M+PUy#zTd2cU5=VC87*B;N-4R0jpp%0kr<4^#)YBg*rd7Rn1 zY0cg_fm&ibf5H$dG);{iDlHd0*FWNyi!0Yo=a#Pif!f`=Hmu+9b}BJoS;?XhS&!Y) z+$zlnj+$^_p`5rlxyiuYa%>f?t7(v-@ZBu%AtG$JSbK;CbFYH1s$GsRz#gI;xVUGC z`|^w;C%+WnE^$UAU!Ukpyxs-?LVy{}Eu^gu@^9@%CJwLZO&s{o?G#U>E-dPxLLcE> z|0rGK8dCfQks%0M;%x{Z0v|YV8{6a_Hj??S!zysdorH|x#K0YqJhqWK4qSrw-ux<} zSaP!WomTl!c9nellmMc7?~A^;*g_S0goJa2SK1rsNjPeN%1$3dG5!RSm2R2LtQdgeWT_t3`{u;SB*S#4%@i*=^_BGV^+YRFm>`%P*&dR^1~BjNRgspUrbwz$*O3?xW{R2~1tTU#+Z7miz{A z|5jmz7_XJ=$bi1rpA0sx;f$9R$)wJm-*@3VSmg6m#1lFb96p6XvLh)xpG@b2x)fYt zmxVR@*rZA2uGSQ12ep?d8D7H?6YgKxc}-s<#D97bl8gYRGR;KCv=EBCDGG%YG6RKB zg$}4e37N7|TL!b}!OToEmG^H;{d>iBG0KieqJdP)On)ti|D_`Zq4PYR6;p4M0qHWC zKClY@>OW>VMTln^>dmwi%ToJwpo}_c+u#_-XT7%sO@;3zdgmoo~ny-ZY#s zsVdjD{P`013v|n;jzQGOE69Q+U%CxaH~Kga3{93KW!eOZp72qTkOT^eim8QuaBh0l zq(EW^NX3@xj74AzSR7z&7+ExeIM960hNERZcva^D?M^j?I8iiH8R zB@~Ta!@w934xrd#>!F?`hHR!H^Dm`$lP*|~mKiXs3DD0NlX3CS4^N!4Tx#6IDdBLD zC!F`FSri+JBMFKjRt%9y;`3Y~Kp@iqX%qoRm=h9S2$_a8U<8}o-nkB*J;7v>7n2ay zn}e>?tN;%1hk>HF#GfV9CzqYHaI-Y9p#(=tvOJz!xhwx$7rrV*mj>_YaJ%FOz8|dH zE#&bV5{LzE$B+K50%avnAk|`P5lhV;MQvs1fPeqoLE0}Hn#eDZnXyb2lQ|od3BfQA zqtI4h^H3e2f@yS9WWXLKOaQ|EbJ?_hv8^40q`XxG3tT)vnqCr=MdO%mgLqEP&l!O} zT2_r+b$&XpIaVI4tU!nNeiF5~Pis4+XdPZ9NsN+yH1jay^o^iE5d$zzDa4{^>F$0TS3H+&T3I{1I6IRj+yU*VM?Sr_LJ_GXR~~u6-RwBu*X3qO$0M z`f{`THBR@ibuNv%vuz>=gg2U7l4#1Ga)iIKTAip%aojYlgH@}ny6AV&$dj^nV zHe(`YN0~D-KNy(ox$;Z&4vi!eN?J_Oi;!;GS5vK)MpOdNJLGN6VjJz5$P}n?;Bd5! zMoLLBr76^pgRqvl7DBWej=s2ivYO$`Gk3_gwlorVYofYexjZvA&0tXr5)FNosl`Uu zK-hWnA^#%4!-D!X+hFlfyo1aI9D!!IPFZ`Ppg}7_k~Ap6uTDTSHSq2@br$tFKcVJv z&Apv{%jlrI6t>dB+D>|m$Uxf7@ae9>DAH|9xSJ{Ppr9q`X{dCD(079l;z=xi_g^(N z65=YIz4VSXhkeM`VP7WCpaUG)gOrBW*(?iG;!_0?z38UpT{qxaj!C_EOhD7%;`_Xt z09OPM5uB30Oe7&9NXe;6av0DJ&t2lg(;Qb5)? zWzPYIV+Wn&8-a8Ik(B**XZhZXF8SZ|;ATHpdGgJ&1E^P&(8OihFryL{2|W6^7%AsK zLsShkB|&BSt9R)n0xSGDv90hrlRC)C8$UmHHzaeQ1Fv;Bv|s|RVHaylhE)#R`ZLsD zxN(+>N~|Ch9%V4dmjG}r){x4W3TZDVGSXdE2Eyr*(dO{g+G#MNiVF9{+i5n@-Onld z3wtRz&&s-l4j9U)%0Lp7X{9`3;(FicWz!{?H=vQ2EJUag1wk6sb?OQ(8ys3cyH(Do z=6*8`Rup)rP0%yc(E-~zxu}4ZRr2AF1T2)6U63r1S@=t9#&5duiwl6tXP`Oj$ussk zAa&sL^~>jJ=|jfevO!fXB{avBCn!{kG55e{$UBto27p&Ya75nvjZSG)_tc5jHDfUvkpMx%#`ycbO3Z`cg?Kx{UR7x)ak)ae zl}#j@`SksqcusV#e}AcO$m;g>U3l@IvTu!LT^q@`GL&+rFJw=i$s9ZVcI-&}cb7-A zCrv-#;+#$*Yon;K^ma+_Y>-K$c5UU`Hx|)(&U8pW8@^56Pd*ef!FyW%~vF&lSlC!qZU;2mpWpDgXff z|G6S@ba!+zwsxfb?_XU9TU)1pmur8ec4520g7BTw6M&FnfQ@vq$L4~jDV#Bam8TuR zX6+9v*e7Nh3L#uUoILn>;aNm1Dziy?XJI(>B)of|!?k_mR{Axu5tV2ummyAn+pn^V zh!8H7jsgFtKZ?b3d%~@nH_HrI{f~&)chUzxBZix;kpQfN`<-s)9@yHYO&r}hD7I1O z##iS}?leN~pHwu$SBHDppHCb zFnHEyAs{Sj`xMVR$`;yt)=L3-=DTOUu{{#toHxaTpO!BCkrJ1ndKpM}V%@Xxq1#=p ze&vF5LKb!%PZ(q@%HDKv`Ca7`?qmwRiZ1_Xryc~Q)ehS20cKNTEGl-+%jGeFJmHHD?v#N#iPa+B)G<`|k*!QnruUq_NsfM0jB<$n| zSFR+He`1<}XTvq!WRq1J)n~}lkHBb2#*rEqc! z_Tn$I^GUF20k`VVr}BwNnF}&R0uYMYlp4L(VJtu$ zfl3Gn6RWib4B)HTPO%5^I!2VkpHM%4cDj`}Ah8F|^)A?a%oQx=*WYv^e1nh1QtXOu zT?zZ)IR`+!T)Et`-4>bx`7ZAY&wdF(emjSWRtC8>34~el^_24B4^!i#_qAa-;zOBf z0C%or0$Zu4mEv=rJ5w69wr=bQxRgGVHCzpF1|Kbs{|@+hS)g)+u^#%yP8OcapFoKH z-AedNQ|~Lop*thg%Y$1@hZgjVaEUlxUE~U2tAX{>3LH>C+YE%Arfs!OY$Sk-+ATg= zquhh$>or7#2j!3x3&T?qNZsp=0MM(K_lX{$(k)(t#kCTu#nR!x~wR?YE zK{{1u`6?9p7z`N@%C2H;KbEklX?{WBM|53a?yNKN9&2a#Qz3Jxwf%X6{_<>T@-OIH zR?1lRZ+4$m5ujwoOvJ65x>f2LeZmZF9}yPLjS1 z=~GbnG?NPHA^Ob@{EbrJmRF91G@`SslahMBhTh`tUIJyr ze?%GMjpX8o1lh?br^k=y7~fqm@aEmKbjrR1RepPSiDm?)H3zF#^lnycTNTwTkCn8u)O~)xvRaH_~%K%JmAr@A=kE7<)_$Gzfnsx3S2;1Htg3|^vY}gpL zOOYzx>6V7}9*A$Y*d!Q^vW_#9SH+9VTbNN>))efR)0asaPF*m!T*W4ngD0yU4O}u{ zAF_b!u#|6G2Ubo5u}r#!ZH~1ek>4CwhQJ|oI@yZA`rw6xs!C!&I<@M)Bj;;{^XTjl zDtK^e#|&T;%Xw=)=VZ2WEragpw??&5svTK1newJgp+LP!C;q2RMRfLB#<) z?OtB?WFmt4>8j0g5XGxJG=2-4(W-x83F%95b=i$e7sy=guoOI*XN1%M?g=nb7|way znaAX$)dfEG2tSp)tHZcOQ$@4VHsQqlgTnZ8j$9j4v*10)=Wv(nOx zbCjCrAO>a@^{_Z55iW59F%L}lFP_%`O?SNEcegL#KPxYVi}MoE58~?nABbaMW%>U_ z9MbTP#G`??Qzs@V z3_QXWOLNj_>vjJ$&Q$gz3t+9*tN=oxUdr&vz`kXTo@OUq-1|hHwy#PQpAoo1Qvl_! zfsyrbC|YzLaDJG@Z=NEKN3965!%Z8h+r+93O>@F6;aqe^0E%LHjHE{;2(gyeMnz^Q zG~346*T&Tkn}~yjt0fv-u&b`EUg@pT)`7(~8YQLA7D)y9rg1cM0&3&Iy}9af0&>cK*BLo~~&W#UI$*NkaUBuFqJvdd2wM!R>9 zYMn;i_D?UiQJu}w+_;8K|4I)oGQ6lLQsHddr5sxPD)!(pyYycJqc)D&rUWknRJ5NC zmUXyZ!2#5MD2G2-VK{qTXC9TuL7ibG2u*?aL6*w`AT-Txz zJp%RMD1Gs!uI~(-e;pfOOOBK4dJ}ywd`~RzO{MPi4)+w&ReT*)$yu;X4rYhQe4L0q zNBb}@Bh?v1J= zL6_So{l!J@vmFvIUAWo=8hpBzl{u5N3axBThwU2S)UKkK6D*VV>FE7-8t(ki6A-BJ zA5nDj89%&_xZaqOZ5p%{ju58Em83Q>I{l99l;d#MQ70&w@v6;+FaRPJfu$i&5xN@_ zZ5dPh7xL(K+}S3I%>A)cZps>saajxmcB!N|SNEW0XM?f@iV0XSAF8^~VKyJEku6 z23QAtTYc23cjJz;*-iR^(r*q<&lFEj^3S2)uR_E+ZTM9V5Ia0as%^ko=WVjQNK|Pm z^NnWh?X3_)wtiu%i9is83B$Z$L$Z%Ump*7aA~=Cawj&+oOPXk~Alb)Viu@$y7117lbg>=|@~m9rjri-CjDM6jiaL1wWG3awHE19EiDxrFJARs(<$IO%L0(K&~z=(a-4 z#+5Uc-*A_Vpprx#dIa$&3&4|vcC1jwZQ5BC*XRK-++`Bl6Pp-Fdjqek#^ds~e1*aa z6sVjRbr6!kFrabe%c77z#9L$r#1qT$cNP*kazg#8w0Bu1w$#7BzaKBwcXVs;DIC^m z4#qs|cx06OKhxsrSciW>ihq<1JBgCk_jZOP{jYw-d~T84g<(>8C8$62d(Nq{ZH&9Uoqk*>K=zGzGkp&Cf7)GUN?h09SAkHhHYpTg1J&r%avM0!JA zDJzedhS5?TcbfNAN#{vRSEjOZQBR>uS024ZtM|QuHw18veKp+%u6{GnZZc+>G^VZe zdOR)a1&Nk`-SB2(R@nEnmSXpPCc}(IHAr6&_E1zXlFggA@q|v?%g_}JU&R0U@ewF> z91^a-^9VwrZ{<%h#TnCb{e6_QIy6TDm?i`^i=TPght!Aypc-5(<_crum{d1AN5z>j zPvTZ!1n^sM^7eAK+rBBvoo%bG=SyjS-Qql#dyTg+<(N>f%g`(|H5W8F6 zYJTQLW4K9n|6%H>L)vk!xBdR;3&?^0KD66Wadz&p z{`P87RSN5B;k8Ad>G=lxXED>L@XQAKkuK7Z004;o!<7A}nCa59G5ouNwxuR-yU&K; zv!jbxtgs|u9F7bmF4yG#KB}q6s{+?(48UEy_ zdZ^K32#7`}@$6%p4_&>~IU9F|fv(YN`Z;GS>yqVbX!QsR9$>#E*dm{1ONjPSZoJc& z%KYLTb7v?-8U@Xb*X~|m`DNx-of+d8jw6{Gc(l=XlTutSwmy{TwHQRg1a6w)S8lw4 zp0O6MnxdUYd4PQ%2hftD&Sz;_wn%2Ho&|x^V?cF12R9j`0}mz6=2rsT(=rDDp`*y` zGaxU~`xM)o!Krt}t(T2MB`{@n<2&Thc_PNb)pmp)aX@V9QzZm0j}C!4br1Y z4H-Qiu#8PH&_F=G=-+>3bnjnPvZz&P;U!FI>pX*=7Rmo7Ol-*+CG^n!Pf9-W*2FcR zs{-P>x|sbS+Q~RS6aH>&MT{HPgFdIY znKQmTf}KzfPxL`hA(tir9z8Jp%W(WQ!2D~3(H&@Iv&l;BT_O=*iJPTHGHgsEE6V0Z z+ZKue0}d%Q`D)>66i-yb4U7cX;&3o)n47~7Qx$hHJPwn(-A9T0Yj~&=$ukPLaa1H* z16)B228iBP=;4deajydz%6C}C*~It`*Q~MQmZ|QZGyNzYt*yZd4S|SK&loIdTE@>r zA3|XIqv8pNsJ<=4GbUmIjf#Iv#*&w|K5}wbVtU;DF?VKN1krQ#*@x=K-No3ehA)^*OybKhUX=hN@nKO_o_@RV(;f_Ec9K2&=E*wVi6e z14E|}R#LL^*zLJsF`IuvXH5QGr5$Ir=_#Tx#Tglkh`>_g)lL(!E27K(Zl;M<%Ki?F z&{G$yX`?)wvO0fkSW74M!dW|qEtOZbS#qPi$X0|I%v?Vc&@yi%nLJDoj(}r{AYr#- z&$>#u|H|(B6)pZtXXwH`&-0bw0>lL<6)IPs5Gr>YGMct^GU*PN9`5WNKdNYwLdi8?x{EUZ`_;a0NzeaSmkkZ^(WCs(N-o0xn^qX;{;e9Y zq_*?lw9?ZrQM`~XB$;(f; z{*Uemo$aI{L2|P;^YN;{*UQ_u1J})b{YHw8@~R63Qp?cnwZG+vb6-!PXtfPo0fZr; zAQS@51|>${fl@@8#E@A+*Jif}CPh3@5k34F6j{Sx%wX@w1+2+YXhJVU`3I?jq-!o5 z0Weu3eiT^mmR({As0%1cJ&3PXh)m!zNphT!J;2~!l?adM@eaxOVCk+@ zAoAz886)i1ZdYIqnlix7^|)8a)`xA{EHS`+pTCiSH50&~3S@`~zXP>47P{cRCxa6I)F;i!p0@=UJZYp@4rnJB6aQyK^axjrg# zrVDSjWE0KQm78=*=kE!L5;C~Uv`2&{n`C{-DWZ@`p84{y_NCSS%2T*>dY$gC$~+n< zSpNw>aoN(&;9N4d`GlYUAZ_&k3HA2W#6_r*HnX)v#T<4KCO_?XYh$ysc4xUgZK|xT zwpn94*!!g{yR3%-NigA(Tc*_S&A4Y+a~d!X>6azCKZF(bV~2g|^Om;t?LO*C9Fxz_ zcb^2F$rdrUPsIA;a5do8LB^qdO5$NnOQzW4?3{=GoN!AVpo>m{ zmy9k`uEp?}EH7?!I|zg{Wky)QBGiP-?ice%?tv?DBb+u-jj2tqRh79K+lq(V`cy%b&&X;SmmeyuJWxnpf z`U3xR{$hXPajy0w0G)yVe-I5l{lA;PBqz_={K$?WH}5DZp3uM>LB=o&<%Uaft9(%N zMbZmNV4=d&m!tM7ZtrW5aOV3Zm!#HN2aes}ydx$)u2RUisS#YqR)BMz^dL#WUU-cI zKxhnD9kF=dl^NXE;dflKq0ZBBw8KM44oq5m5h715fZNR(x*n_pdn{8p&=HpK?iF%2Oy?QAkM9$4>fZ} zz>K*7%%Z^b3cmUAV8n>tMno>l{k9P>{p8g*rW=aP?U~5(ynwCo11t%LKEu(aj`5d$ z1bU&%zhgY&b|{sk76Z*Z9@l}R#h*7y;?xNoPqj%#@pw?Es4TISyVcJqF5J4H;b!lP z&kd7qP3^|O&^-QG%FT;sLWGt z6(!O?#-Az3V+(8^OwqVVAG$|B2`NvO4^kSw1V>fe%{PzJ<>g(9vgNO~p>pI23^P3-dZn4pa%BK$g1S@W#TyLlb8}_M>M0F#@QhlQ5Cn)Rcw^k%F zO0K4iEE&mU17i4stdno>s~tDQ$K-9KP0@_( zSh1Sr<+#1y*SmJ9G?`_FKr6S^e!gRRV0as0J}yGg6I2m4d)Zv1sI&>I&iMrsI6b$9Bv>=>Gtqn@yH zlx@J#p?)Y6+!t@oXxI?!D|F)gjM7!{v(izErQZR8Phxnp`tmq>#FL-fhy& z3d82hCdv({Z7Rn2jsx zZ6O-TUT+}c`nyx@Da-W~>=|B#m;Ow7BzU$-IF8Y@^}Ut#@l|~(5zJf=Zd}P9E->WL zNnSj#C#qAvJ&5N|uxq5=2&*pF2AYg`xm>MX^?}k@dn9K)*FHB}AK#^~M`kcWz_OGh zzE0RUwNQ=2e{)Q4d_LT7I*zt>tQ$Xa-Z>^VF1lU3rXJusyK3HT?tBOL9c_m-_Iiy$ z4ri3_nA6pNQA>{TmE0O-YgVf<(U#mJvc|y;L9j+8nd%@UoPx5dfwkBSnP7G_AJITJ zvJuK$5HxQvV7Ocn8;369I<7>O`wTp|(hygvO=s9RWb6IdL=~Fkt~z`Ww+w&kE|fFIkAEI4Z8EKID;few*YtwGU?V&5{yp4{OkZt z*oXw#j_6Y|K<8>}767;S!P#u|T={%=KjEr}FkgP3tg+%q(%?IIy%(})aB(kO<>IL! z#p~Ze#h-w{<^|*1PUX>($LjX!>t4BHbrC}%YC!pucn{i*x9at~NC@O*!{%eZz{kKx z10#n*vmZx{;n(B+;O8l@=SRLNiaCol)0O_BoF^))R=>%yu&IEWl!tk1>7* z)wc(P{T?H+kyrtW{FIc(5BuPJM?$eDF>siLLqx+C#*{rn14U2#Tf zYM+-U3@;w9B_y)KsVO7>qOcXHk`_lNPk}^Vt8XgpSHq)3)(E9B%L%(lYp}r3v8#Y! z3$KJ1!fR>jGIw3M0+?A2<)2-D{wltU1O7`r;!h?~Ud;}V)sUeeQiF(fEHQ|H$~#g0C5nrMFWXK<@ToZ-6E<5x*c|M%A@KB# z_qUte$V{2{p+qIO}tdgqJBb%HT%0|(KDunr__HpKxh-GeILQ^!ct zHPOH)?VjVE2o%*VHQQJ1+Yz*s>n8{OEgZMYzTkLMjxfJe7o;?Cu(2za9XDIJ!7qIM zVJMUeLSeXO!Pso=??kV3JJy|Zp6OB^e`~hlHT#C7Fu0{@qCmjeD%HG?tP%V|Ec3R} z$8gm7;P;K&#T3vKV<_9pw8qPTTPoX)MY}xjKVQ%95-$Apyk65mbjetT%==8U4ZCC$ z-g-1pQMHU9O8ZjGayN0!rg8(dII!VEm?oh|qPjZb0{zPX4KLVaDN0bE-$ipp z%UFNj1-&<@=G#q5^ndmgq1FiQx&q^M50Zh%JlRj;^rf=7S}B8{v78~LV@g%WP9-S*=zbG&C-CM zYgRQ&Q4)w>1fpEfE~hTVdpz^$DNzMHls^k)*dZ)AX0(ajr4Kkw+t5x%eMde%%;Z|* zWi(03E>Y)CBmXK<5e;&JCp|17mJ&x0*?*goJ^;gUji?Yw!ic-z-kksqT99W1M=FS} z7!JqArgvS7mPB#?XdV8|Shrv{o}nEn@Oz@%Z_;mbp(?IYpp4|5=04Y9_dR#cU9o%F z#5_<)vPJV(aNw<&%Ed|_(-4YEaHBNKv~Q&9*tLdHXN_r4xJvox_S}?G1-4o9n{vlq ze9iV9jHE@(kP`8dB;5ws>Kr=yf=4X92Pib=XNb3&TL~tC+NEp;JI4CI=8tPPClL{Lim2ov;i=alRh2y z0p-`v29^`V%B}N*ZS;Rumq*QbedC`;SMk#hCjLLw%>RCd2LFq(cMh`b>#{}DS?R2_ zQI)psN~6-YZQHhO`=o8#wr%@mzuWgl|Gw8>zZ-FO#EJ9AiP&R~J@=Yxjx~pcwZ6H5 zsjjh|uH}C`+5a}C9SNG|z5h`Te4r9OnU`7g!If|Gkw{|nX-X{OtxbC*5UoCJ(K=au z06M0_wGP`y?s#xajKi&aW`5S|ibJ@ZzhL;nD)t-TY)@UBT7|{dC(r-2 z8{v1CIz~(OGWg>Nr2&yH8chYH&;j#D7Bj@qtWZ*yIEvuLM+A{a`bv6y#U68jPKo?r z2AJT2yNqZl1kEI!Vp#a#vKaRMge6Cw!qHDg!_=s6nLeV>Z+lY za;%xBV9lYV-%N>r6q@oRQ$FLazo%J!qoQsA98qjRVUb7*6u#ic+B-BX3k!8iJ3U#p z@!lV5tQsq0z~~hx)-qSy9TOe=bqxeC}>JKG!D(f%)L z+gnKfF-}_~G6Ax`5|9O=fPh~{@fygKQMel|)GtrXnyWtu zYjP}(IA1!Xug)zV7O@ zUu;6vxDjC}l8CH3@bLn3$^x}y_aOkfwf4)D_)*It{EC@odM=*mVwG}1A zLwSGM)+j8xCA50s>417UBA19uIP(4=5AFf+uKOFiJ1om8v}na#J_)bUuzhE)I)b}A zUfG>yerKZYJcJO9cjyEypDc2SH6r z{;9^HW911J`jaEuU0o%Tl01JqpZ}#N;^lP?T@d{_A~rtbL0HIZ?gA5Kkg#nk6P+tpIKqZK zX%hDBCz$o(>n2-sG;K&eIAGN^zZi7R6V!AUh77tnDlX38<}uGCFIbPksdnYqoJxnFVxb4~8sN?B(^(}PYX zNB$$vGv3zSk%~Q$W9u>Y2q)54Uh>rmD+4+?rOaf|`WYH2a9o;`thi(}ERs&)zOd*0 zIe-5w@Xi{AB#eZxfae*=^Df9{0;Tc`}9JFEiuU<2H< zdhNV1$bO-0*lmcJ=1X|0`GQg|<5zxfNIupikPsDer&$|KCewEHKpNZ9V_2L)`1WCt zq8s^JH=UJ=#OU=IG+``nPx{$lmfcZWH53GyOG4%>RJ~@h5A!m(YveP zk24Z;Ryi4+rX7afT0_92b_2uE#`CWf0=k?%y{}f$c8u=E53afvF%};Czr;=MZ!zyE zzHth@i=GHngsGpX0s0__b-=|vgj-3<7NM;y1c zKOJI_vsa*_JDnhr3Mz?uVU;Y0GMYvYi1+Xj%fZ%?Trxq~U(~&hV)sqs=EGYOdb!bmXC1%#BRSJO4#C?RkPoPH1;=kmWB?x2D%QqwEEU|hB9{6HimW%riS+a zk(d6v6{}~Qtn~NlCUENoRbs2jNuPj828o$VOb;dhrqTi3M5C>+viq}RW0?eLSAXim z&F%6cllm_O0=!NI)jiI@Pkvw%Sp&JN!(+=1SW+@T)LFz)U=Vv*cb-lU1f#5+EQSk< z5Y(U;z}I;;Da@_q;;J751Gb8PfF>2>cS;Fq}%uM zPXDRG-N8~BB)3$D9e9g$4q9Cr7Z_8`j)YL%jf|(Bgt3w?e5T`!l7_>?Wkzw=nWckHL2eI>Q)#t3Comp(h@2J?%X}8HJ?NN<-P~ zJrFX+z%U&_5Xr;EnYd>E$)ovZdbRcA7I_$@5`3y~%NZnjjK-rcP5wIm|aqOoc?9Kbve%jeqm*;wnxzY17lLlSK z*7GBx_QK>9TAP+sPH*3zsWPL|7n-+6e||o8I=vQta*}4d_Xl3bpFw4pAG+)^rwc%8 zuPS477K>6mN=kD=Wnzzfa{-3;OT0WFDO2E8zXSSPqbxJ;s0E;L#L9;P19mQy?QH%(EgJhO*J&HE#G%f`^^rr{|Ny(LkmM)d&B>|6#nm?amT;x z2;Wud<_oIyW21~{OhH0(a|>d0EP(<64l^}|cc(&BbF=4@JC&C+b$h^U!};&Efhf4V zDMQ&OLj&zek@_Zms~TJZn@o9`Cxp^g3py78o6(?C62*MNT=+s~Q9()uYM|WGmX;Gc zVrEY(V1Upzp%eGH&gru*B3ML4>qv=f_|&%r_qt2qbW2(G;m^ro+PBsff@fVS-&dVc z`ChWYQOa0Ww{y0_9iDrSXtxN9yn*5GGX?*Iq@@Z}!RH%}f$vO*{tbz}simWZsg*gc zo`Hd(k*=eK!@tdPmU3fOdvvhvPn2LA&KsL$=4Iy#DS$bv`QJ# z5^QgN4j6E@Ff-el-_zk^{Cg$A1|vw;9?6#tQ%5&P3n>fod7ko&=)<@J_pKt;)^ZKc zK%dB`-PHg(ir%&t-em=1CFE=MK;p}f7?nY!(yOlS>K7=LKV$A{kzeATC-$cec&@h9 zwo-XvoiGJ*9d4jnB7KfVJ~8ND*mQZ7Y;|3wA4zUh5Pzv-0r7(K6tt()!Jm0=QdPKcu7smV1>gz8ICAs*JT`$jKUq?|?g zrHsqzypt~{>wTzQuXD%SP!Wm&jA+@~03ZNSDIlw6QBilasuoH+7ObN?O!9X|G6b)- zdaW4ZbswW_2c zq3gX37zTj%TkKQYQe?;J;YvG^++|hb%B0g~0y*TFtP-sg=-A={;%Ye>X(!XV=<@P+ zhsjlT3sI>|3krof1t;UKVY#oXiLp%FH{+`7;RA5qm+F+fRGDA5s>!n_Ox4ue^OeGf zFwn(F4PcrEYONk|&1mPpKE}7d<}Ag@#Iv$8G43$^)0X>O*js6cxuY`JzV2he{ER%4 zEM6q9w2<$^6XyVeB`o+uYgnZ@R3ftZhyOMyKm97QrZ?59Y9}tDn(P)|xCY|8n{x z(N8CE5eEo}Kl)#u)&Enw)BU@QJ)!Aty(Sv><;@#N02aI<6c?JAssX{8A4s(l>O`!L zc(6|w95_Rwjx#fE6=25e2s7^-Ew(+w?8?Brb|IHioeWy5fSm}midte)(V^i8Wy6YBj>{+UloNNun zF0PWbRh#g&j<8!VxqE(M8F~I2rTZ=`4`YbkUDAaqSufrEeCk6q;kxg0+xzo#&iPIs zZ0ZlDHOz6{SLWx2jCkXfE_Rp^(QM_gixOY_*aw=|ZK~nV`ep1P@~L~KulIbs30;O$ z?|Az0qAS)qKBDgCnG&m0;&^*0z{A_&K36&{G)XwIWCyRy(_?0+um$Q!V64$|3a!vA zKA;v60{U4Bu{J=t;MW;RduX;R3W|rhxn77W5GSdDfs8lttZfE}bWU+*m` zH}#@ujm=x@z+n>bWU!vW$Ud7}ib<~Jl@v)hx_i~SkSc7qpWGE~Iy zg;4@Nv0t4F_3;+!XwHVf-fDDotAGTgMld})n8MY{=cmtYn0R`4SYuWuhChU#qXIV= zbryr+ks&!<0;^9wDK}gQ#=mx1%5?e~J>cU;4x*MS%^H9+=tLQl^@xPBmO|b#q`}WQ zWB}lRC4vHGtCWhsh;XS@{PnO1A&YPrOSNcb?*uCNVgUj!LT(TbblKHK1@0HsBubyyz1>T2d{NLsg6X=DBqTGuZT@5x_)G)n3lY zL^|F52^)?ShSW{eY^xN;@NNFBP3fqY`s@6I&2WTvhiHQV5U!QecJpBAU#muzQm)85 z50Q%|-0W*_mu!B4lIU|=Vb@4vuJbIh{;ro>J*`0!FVfV!O1j$FB zqq)F=HP3-TPQ#cK0}+%Iw$w2@y(*QF8yO^(k8;NN(XBhUs zq@-#xn<{ms05~==8WfIgT_(MAfiH921~&+;Re-h59%z= zvB_2RMu{q9sDz+}GtIC!d$h7L!x_(D;wNO6NZzHyv<3ZHGDU4M+Nz$e;}LonM|{J} zb}oISQ9c>yG0MN8dL&t&2$|c@Q=A<-+iP{8oelxm79y`}b!XOs`E8;LQ0=&g(9~~& zZ0!{-cH@${oQOBAYWek7hdAOsctE*d*2*XWYamn3#UEVTmspXv&lSTX9l}@j!jVxW za+nQ=87Mz%eoiecovlVJVlynvcHxuCrd?yONcCi}=EN<*8rZZ@c#YDTieI=rv~J-H z?|o)JWNq2=%JkeOcJ>+HKx~!ditQIKgC_+U{tXd*(EdEEoPsd*I-Si{Re&hl*sZP? zDtdVe>CbEU5u9fBch8<-iUm6#0yMr7>^1{6Ae=9tP*~IuWat zL-X5Gec1A4v3s^Ux|;}=r`GgvuBsl{5LLQC3W$UY_kn|liGVC|`^1H|rTlUq{WPnU zY%%otl;iB#jN=NIrqo>{K2JE~>b;}a91=sWO?&bg=4k-@^yZiY)X{!cBw*fLVKvlA zL~m!t5zXu^#Aubghm;UI^tJ*1G8#8yIArW1OG-z0c z63cf-JRyE+X@#!&ewb-S=5ry*oDuL}^gv%sUmL5XuDwT_oyG1;Uit}$Ha7m~S8P$! z^?_L(JS6R|Hf5BrgVx9FcZA@Ab#(yOorWW$cGqCm+kqhCA>NJ6ZQPCnU1kvzI%Rga zPp@^XF}3=o&xLnkvfSNAF*EZ$41)4nW5kh}^{vxl6<*>C70xMYrd^>|!Ef#pz$DN) zphHHKvdd;Lf-6{r*mQ?C=1xwNLQb3`Z@>lDd>h9LD*VLvIwWxPxDJ!e7P9(%Lo_C`kM+@Glmzup& zwZ8oh#f$NG+Fd@X*rJivAYn#&XaLwKi7KNh$z? z{eUxzZ$0FT(IkPyHE}Qy(TCUoV?9MS75x`6Jv}sz`~JwcPo&F!S~*7|5Oco|#@vn) zbsr<_ZJfXRqgZW;0TerVxuA#rd5ZqjQ!}kI%9FqKXdG`63j3$IKr@W;4@d_4mB|m2zCVshiTu(Kfj)htQt@vw zl-_o6l~$^ULfWE|+`|koiOowGV<-xwFiDjy()chjkCdGtnRlp8_}K^MTYDsV_*LCe z9XO#K*}xXKNW1S*ImCRn*D}rlCv^ z;t)p*mREaX22DHI4jU>VsR2?U{rmQQLW=hVUxP?_!xmCTltVEKo!U0@6ab+YFzGa2 zbimYbrs?0_EDfz|4I)QmV;t96I?Ayd;zi?2E330V)=U9bdgC1M`Pw~;IW@#?cU~N& zCNtZ|YoXhw)S~xsZ(IbMLlv z_LGfy1M@$i{{o!tOL`TK8vh1}lVu2u*A?}GthZrIDuNtjabQ>x#w!1Kx_~jjlSf)o zh0k5xSzeMC8OKlwG|tdX1-K*n76D?Asg<8`2Zdf5+lwRtHEAer5d;rLhPc(3A{zQyBgBm#Fi&zQ|mw>u6$X+b7T@PKKl&D)(qjJtLv6?42ta^_^|2=J76eIL{{4`h zJQ}t}ZB#CcOSHHK_QXt5>In&Me;vGOERCrG?10D8O@(lkyMP{+%5zk~$qDL3+5M|8 zZxB4u+(TFF1Zmj`RGi|PmG&fyg4Y`S6o`v!_`Mc2Chz1QQ)Kx6~>hq znHtvw_lCMiswBm(2YK=~-wm~xIB8qTAcPMNl0I=A@<6{cIEP)R;ou@+(xy4&xgd?R zAAwb%OaZMCJZ$W8qrV$AtZyN=O(X&0kerII2l0gYZ=#%H5C{-Ke-~^`SS@e2A(qjM zpS7yRHXXcVvYi11#ls_%h6UuBL` zemJSWSj9TzDT|;#$B3{_0}P5#^`$kqE7ZaWfM>m6n6N740Att}W1PfIs;PpESfbk# zoW_L#SdejD$15Lx`v}$^Piy-}1e2`{G+OSIH^di0KE7O%z(MwDpItRe!XJo7yhk+C zSuqymWoVi}1V~rtAe@$Lfae`mYt&GC(9dfF$96k-(TNLP+k}Q2{;A{Vr1C(e-m8pC zcwo@DpIu;3Euvf?Th%{AoBSX3iu@c4{4^2q;)=6yb;MW}OM{*iYUPAr8{>Or>C~=a zKk-`L_;%Yws5*=1l$~Ko4MK>KqaB6PYX8Jjg;*BjvAJo4hyaQ*PfqhOD(pybv!D(x z%uRiJHpVZz`eB8gnr1uOF92baW^8oIm@b66p`9hYL2l(M+zI-p{;XG$_@0>S7FC*M=H%Q)if3vLquRu7wQn*Oq{2eC3YF6X z`}O4^FHoWj@AN`~V{;c9KY*)}NQLeFKaGPVr|YlKTsG@b%B-d(J>b%l3=4i2*~Abw@U;BZKONi;iJ5PrR>9(41pe9g;cC z$Qn55s2Z~)Ad+0Il$lAMIJpdxjXI&3Tk&rJY@}aV>9T124OVuk1D}wwP;?Z*oMEWE z9ch6-eFYU~#Ae+}s?^Qxrmu#+&LLOydJDEEZWxh3CZ^d-uM(2^fABUh z@j%?hqeRkPBTtc(R^b9~K`oBCePJ#PNTtd)GATdNclNjNbT@49=AjN+9D)prLjOs= z_|kD}7hKt3piCpMM-TIgE0brXTcoN3O(4g zc~bPHp_;@|Bq1S#p|grVzgF|>Y%*_Wkf$|kfG7Yhf~B3#%H<%RvbKgjciXYaM}V6L z7G99^wm~LUQPOWcck8Ag91V62%v^7w)xq6Xp$`#9E=TKCW3aReMK+h=OGNlP@YL>> z={HHRH{IM-hVk>ynJnu<@r!4h)R|Z2*3@$Bv1XbUq0GHQu&>h^PBa>z0wpb z$G*v~ob~TTB~_AkkFseqJFisp^H9aJZl|fi4OE+Gp*`&wgL5kml>P>c z(LKT*b30Oo*Ny7wP(ZI{1YRKr4h47{$BW+w5J+3z&bXtOkp=Fd_(8fM^7w#4Q%*o-JHzv%Qu1=$e5%OnxhTZ3b7<&H$}-5{;8NHh*s0tnH!x7E+&`O}_xm}LIO~(uHccVHRNGX==mN-L2 zwSC%+doB<2t+m^{$>gJPr}$$YAL>Ss$Z)^GPck+2*pC5P-fkP0>B7U(!^5(%m;w{< zDzmPLsd*-mP70*e;kST)oxhc`R`Mo?kax08N5-Ex%AJORa2y-FgWE_sURt$25)SVK&Ckk7>qm_sguMjpA;KUdNz$MVf+$L#IVZ?{EgtsMWXu78p zXUyq5wYUOvu^0Z%&oz>5Tg3XOxIXM-f0jla5hRHb{O!T^4Cq zp~L^Ofv7<7DkaY}G&3%MxZ1+nbYN$UJV@-zQ*?`(V^C~L@l6!hdIjy1%PeT85=uQZ zP)-+DlApz-QW?VE>SP4uit#3>=&GiL@oPP!eHwDsINIg8+)Oeq3HPixt&KK0!jH2a zIlbJJ6kfJtZ@4X1HM$iAdu=6>)UwpM2bqH;gv)UC*e0THh0B~}Sn*G=%ftfT*V1eGjB5a--!&>Xzs=vGgI(pC-wP4{n zZ^OJ~9Q9u9xcGu=e{-J%cZz3`IMW(Aw|{N}a(I3kgMn`! z(V{1DPz@kY%}cOv9)o|uSz9`G#;(SS7U6TmjZkBKQKaZ&oVx1QIq(KDVF(J?%B2R% zTUP{f1W+=&9^(9wIk&AR#rHFrNwci&h}Qpeo&v;XA8+#QtKdiKs!LMQSPODwLJ~DW6jh*R`*wiw{mx#nM<`*yKEx4 z+_XIhD9k+m@b1EXg>2jn|N35^YXni7J&DBddPawliE&AOEURF8@~2PnR6!QL&d>Lj z(s7tvPaBb-fr{huWy5??j?5xstb0}!hrHSa@r7ak_O_*k?y^cz)7@; za(hYmShUUP-JxWaD4h$SV44iy2?;yK!);&oqMXV1w1=iDv24w9_x=NhOxsrq>^W(B z2Tk8K5?tnc7_Rj{dJ@;lY3~2XGjd4ZU#z~kl-B9rTc0_ry$?xUg7ExR zQM}(Cn-J*g4y?w}wTa!%JgE~AY^Xb;+H6nYS~;V1HKym+j?byNjj|S4*6kBf7H z8OYe|Wj79=HO#XXPzpT%jJpJW_YNO$WL8O$+8g==3SY$!Q@rInx0`c12xN z+$ojg;r;;M+Is5r(g(>{Hk-$47*~=;D3SzvH6iBM_1n6m`N;16?-odXNMC8}-8f{! zMf{ky<(5#TWK1S#j$*eZPy)^J4G7`NMk4|9K3r)h!kSCiGR(@wIvb?RJ0ENsG;K^+ z{Cx1nF;)emE2&UR<-6T$?ZBtaN*^9XCWqFfiEoPUDBx;DXZbwGyS2AXU@r-ii3man&MACM$he;YwDs$4xAVI=BSgA zCGjzC~Dow(zJUl$V4bJeVA#i3;&XwFeNRj2*EEK{Y6gLRr=`-|vt^|!8{ z1>%t<(Zt!o8PGQhR>{pj6*l=)qX=D~UfUSZt7)~nygxq9nyk0f(pt1xcEBp}BnqA7 zYWR>@R?jF$R^mBQTsyd4wlmr$aHr@rMbz%sA=H%#MRf3I&!xf;uGP?Z#}XT5+{UiG zOkqHTCD?6Dh_6?G9d+)_Zbo-`K}8GCCc$!Nc!Icm=DPpN4u#?<0!u&>Y=e6liw8Px z;v45GNrTcJv}I#kDB_csbzL0F4L(l-e@oFWKCNax+W(@Xx-rf&nNH}rv`o94$!UE$I;wM5k{oUj@$KJI1_)7Cz8U<6l{7%)^8 z{R8AyDx`{cB_~Q7a@|aUU{qcWefwCg{K3V-*z*Vf{lqxOLxfLh;ndj5yi+2g=rwIO zt(e&FrN9VW)W-U*PWL9YmCc4_#bVvlhO^9v-|hYVpr(7s*ACm3i3ohB)gu|c9QTEw z%4!{b(nE`m6(bqWAooCu6n=}FgWytVecN|ngLeeSkXs$UY=vu;g)I&SOb`xzTz*{0 zl^)t8PozHd)sSU#4D8ogny(tK#%(k)%8K7Nu~!?+y#hm)YM;2bXmi5h9rR54D@5T5BN?v8?E zviq;Z1_h`$=+D@KtkP?eA~|OdsncbfY>wp$9|lL<{-!B(BroubOpF_bB?xd2!UYvP zT{=E!UtJZGy=wfCh{c6~|D5*}XCPfNrvAG7B+NQl)+sP@3F-e5K)HmZ2 zV@-Qxf6ze>=mLwX>fu+je|VER9L3`<>mb5l!QV?%pd0n(^bKI_~GGuJ z4hbhbQ*gC3+Bv@NKcc+p>S(hwcs+ca&l9t~KV3iV zGqSU|zlhk5cxoQ=M~bbZqyKufR^?uGc=xWBmh!ynIfUm@1>KBn4s4Pl7|DlAYhP+x zTv=*c@Ol8gF0HGxKewatJJ`5iAIrONF9Y|MrZ!u&@v=QUAJ2!ZwJp3KR(9&9@H2Ti zURJL@VhqMUi)s&I;QXwJE}hqvpt{gW+oA~+Ae6{q>s;5#`f-T z+n;W&kEXnaJsR(7yVhQI!tX>xc=1>2`ig0{@OafddA*E2@Y_DF@DfRtHs4O4kBlLB z-CiEjGil#A+n<>3?=qi{kJIx-XtO%zzpmE@?+zXjtf%lhTn?P1J9&AY;Vrj1S3h>^ z`Z{Q{?Z=lq?ODCjojd03W%tev7PDtKS|jI}@aT6ShuJs+Pgt~=bZ;Jv+G`xavx zy67_0KF}{qC(L;{&Ys@t&F$CTuB@9n>x{L(ZcPqW>R8)oKL~B!kM|kXlM`EMJFlg^ zUEa*D%Cn<7U2m3_w%$MR8-=&JHa~CHw0+Jtso4(5z`ak4GE8w{_w zMx{zAmymT#&N7j=bG&pDOR4ueR{KKb|VXi)p_HqVWvX^(9Md@q|iyx$b`d z)7(tYVqY+VQDYT)Famyp-r9xD*YV5FKp$jHFk~I8$Q!S>)9d37D62hVdDc$pMb=T> zUAXhm8v=eims?wleYa&Gnwqy7;br*T++Hw(Q*^YJWws_) zie`pob_RY%R!2R2Bkg3=<|pBJW_U+nocZxYa`Vo)_nGvc$h$cEGvxNM0V-_v5Zl%rjp6aji_eOpRr)bqiZOR=JF( z6(jPyR_H~#D@uRwNSX-#2y%QJTzqd1PIm5hr5HB zfzOqj*pC;7!;Ne_54*nR)m4B;$sHF&9rP2+lrkimSHABB{@Q6qbrj{Z!S6LsPGQ6C zwqOLGBFMVBCY`haA7`M`1^$779ItfW{Rdw}+AlYv6Zqe*UWL`LqqW5AoopGZHzP$) zrg$u^o?ma5POKa4md~!s_jgv_Yb42bn=-O2>m+6C>uXzP-g7Mg>Qw~2hY#1=6 z=Ga>Yuv7hKkH#Q)b}fO9o*RvoZ5i8F#_xKoS25E&kwCm!!tMm_H3bqVS>mE{tzM;e zN-QD%2m-E(T)CQterneuJZo-;fo|$eo<*WU+6hcOG}8#*uER$(2xKj>L5gRC2)EAjx%C&jC* zKAo!-4{v7uHYP-N8T>_<4q~U(*#17OAy0pXEL+PLKw2%OV=F8zZ!U{E(&6{oy`y_7 zc9wz_!R`#)&fq#mV%{dDhdr^c$@nC_(2IhVIl{VT`0ImK9Z(xs5Hn*fo8n^zaOe8* zfIXU0xuvIqAj8oYkFvefb*m$3S5|dhu=QQA=dM|lf{Y{IYhPZsN38?oE2=(UyhZHp zgj1>lF)}M9rI-iZM=rGN+LG5ViJSiUHDBCH*ruU1L6ZS2I3rH5sbOd^%8&ld!cRkt zrby{5sHVyF+tH0H+ud;ix{juI0vxw#4nfpniZyQ$3Hid66Fl~2X~X~VGi z*|Ipkrv|dC=3vs*75^gj@&I*A15b&`AKYPRlCT8F)U*8G61A*@hO21Zra$l8uNA$~ zJqCz7N0GFp_Igb|T7NvaZ&OCtu7ou(=M9-G?I(WL3^x4Y^z9~Oiv;J)f3~Yzzuy^} z7;PGM`#czW$K`RNPA0qq@3bc<-RzJ37&0D74oa-TU1A=;V%eRCMDE1^dvN=8^t#Xz z4(~a)G&_+!=KQ=)#8!Ys#scI%bUe~cIteSccZtF{aPoRn||F}_((PSQFWuVQFu$WgN7tQz*7=N zgST^~)mJ~_^CbdrYI~6P*E^JUaRn4rWk`B5@yJKr#ob5U8Q2I^=s+q1W;+<*5R>u3D#}_c1&>JM=8_mOpcPE_t8)w6gwOP&Xm6Hj)cc0g? z*tdZe0lvkT{n7J7>V2612W^vfb~e6cwujM_#i#pM!`I<3qJK)180RdINwS61fB zT`u)ZwvqC{S;xm+cs}xDtLy8lUQLes+EMVDvGLj!%~Rh|F(l;CTjR9V4T_|p^IPK2 z@sqRo4vA>(jPHc**(pwKdUHQ-f(pw#w zc*^{^aQHp&{v}Ajg)jQO-)}Usw>71_?G0t+m&E~1d@uV`I9(0sNU365J(E~oz^zsw zj1jp)gAs5K-&~lQE#i=Hw1KTrA(lF%r&Eb)Q`G}a4T)0rfXp`%09T)%ZWFFl0tb-L zMLXijpHhLd;MrCu5gVUvfByDFn>Subo7Br*NAx9^!&o%pD5m&}|^sMH}V1F7KEWz?-rLRpa$S zYn`B&f*u??Rm+E4RT?~8s~u{WWA@O|gMu;8Dbc7=xaQgiv0(qxS-CvUQqZmQ#gfhl zGfAQcgCz?j$2)J*K5G zaq3U^ZqczS5YqfGiOH}SdBjm;lyGkVTzvj-D&Vsf?#ppsKqDmCa%X6?*hSv4@?s^e}#co#RI$PWMAzK z0~=3XA3#?dky*aa3Q6SiIhY7del7p)Hd z9vtm>V##mN^YJ6WX$@nas6)NHtt@vrU-#vHuelHZdX|{ zGNxJE?qYzNZ9V-Zm~j={7<8`RwR~0G-~_hOqT*j4{`CnJSUN)(Z*zdZA(mHU@V#q) ziW^hOa&u&~4>u5@U?aV?{`CS0L(fOVVtabQdGu8qcII;8~)+O}Y=x+o;^TO_dCPR9*{K4k-hDRL- zRDV|0AH)_=NN9ev78yDG$}(k*kQRk*^_v%5gd$*C7E7v41g`q!cp?J3;+TPM@4((? z0X4Bb=N0yd0wHY3)(C@xm+h~06UO1@q+svX93qx&>ba}O0CQ02LEzsna2d9~1}QIY zL+8*L7*yXAyMWf9B5;ous^raTj60)22e9#-P;im1*NOu_CVX7sQG{{&3D%Sv^*MZ! zhHK4q^C2d6`oZG{^&<4~YzUvAoSy3x_%9ktG_jF_m(aikET!uVj^Wsj{L{f}$AQq$ zZXj=^a;gy573|TM!NA`HE#-wYm~M$u6%_K;1NNk<2L}Lr(HuL%k(GtH#wf3OnAgWO zTQ!;k#KmDyYiwv0F~4UF-PJ5Es{s9)$pIP+5%gr(ASDyF3M;V_*BJCKO?(whIcRwB zY`;Oc%{8>9qy zbi2+<)9j)U)OY^|c8AwkG}>do`GFBJYibHovSfqm2kmOX)U61KzQ}H4j@5NX(v~}K z`x@8G=|is{VIF2K=*S9c1^8bS!$ ziA7~V^hqwSqv_U0xeg#9(JkE`QGM|Zvc~pL$^GT3=Wh!azOD(7ud*Ij0NPL zM@T0`bdQ~y97W(TOyc3a0dvIQQU~G9r^YCgny$qdfQup()E3C$#j!#6E3ul@3jk$d zN7+&CyBViw6L8jm=+a0n=0FpN!pAbpqV?yom{4#8NP8=rG({rwZ?+9pbjYmeYwNn4Bj!PFnP%$XPS=+U%0Gir|R<#(qMf=J)zjCuV zyGtY*j&}*MCM!o8xR{&>jSPcz6m1!ZOdUxdmnd^ZY>b2)^e!Xz41Q+aCh4aF61ph- zs6~J$@IsYf0eu7Hi83#sq;EopO6F4SU&IgP=Ok?;N*%&AkyP!H=@}B_CysIj8-$v& zg)mqYK9Z)%g*^y@$R)D(A^5a7iH9k>FkZuqq*%3|?DT7OpI`vXInEJOuZ$45jU4>+ zHHhkuWPnQ__d5AafVgVu2pj*ddKR1vcgU+scuB?|3+G_U!XLK?6GJzkX=)@>;ZR4J zGruIP4bYld z!N@oGm}LsyhxY0Hwic+1L{B4$iJZf)@WHo6!3{)DF6B;?9Cuk;+Xf~MIl2Wqk&`w^ zA6DVt?N@=u+nol3+qUt^4Tscf)Vc_~$(whkr|{aT4dG!XYx53Q_B`JkhT%Oqshzn@5YNZo5ycX!rT)j3SnQ7m( z!9@aH4!|Cb!ZYUnL?nA8ehY4$~^q5mxdYia6 zgkLuoC2c*-g>R@FSfEALb-R8#)^r&BHn)atnb@U5Zlhi-oWtbwKDMmUlI@ZeG@QDK z`x-^yT*U$Zwux9RnCrp^5XFbaF#MzRhODQPDQm`-g@o0?jM+@aFX90^SvWdW&S4Zs zB!})G4~60~Re>nmU2m8)je`MwT^8m}?`cM!(K5$y?RFJT)#aB^K)36kMg}F((7uPZ z-VyUE0uGhZtd7{_c4dU*Q3F!Y1k-+yb@YAcuBVnDCbnQ8m#?rNnWYnw=6nXn`vRI>uiE zQNvHy$L_93Y>{QuWQ^iM6v^0W0r5>eHA$+CMq2t~^mj{CtF$KbhAQ>t3K~IK5Wm8$ z#NG#Hh#4*QRJVwLs>QBnliRe%6%DC_?^<8*#l6g?aE>y5rdZIOCWV$wEQUPAVOv#3 zD3WX2oXCh0oG2588h#`Ywiw~48@HQo-{gUmUWQq9b;RM9(BMO@;GgVxS_6)w0$(;c z`gKaO7hP3Cs-Nr$(`)rvw(=4tmix6%dcK*l-h_qOCx z{0$ST6i1;IhYZd%wIlHVuy#&Of<;l9P209@+qP}nwr$(CZQHK2ZL2b;y8ET4BRb|~ zBKA+X=bjULeGn=mbj=}yXeb_m9`>J7YQt`C*=}PgU(g|!cD}L!hnD%g0k{;cyBGF# z`VD+=#iPyDGQZmXmp4zkI4*dyyq`dUIj933O)M&we+xxUr}KiWH=Q689QRtWysh5J zfVKDFm;p6-n3Y4T2_s+S^_*lkZGaL`Djt+{xX>j&T5DKA7TW8zRPM7AX9Av%%fp7kmdHTqzM|Cia%ZUhKv=vsmjA$R=r$2bFoyOEXqcA z)=QI4uD(T$E%&+CiFe;G@)_r3vU@2u)ubE%n0?gZ+bn=FTB_>Y1lWlOI*gZ#R^|8b zrJVi7tg<-35HTjHwNaA<;G=s;aY;dg;d^X$FyY@T@2e2)265bsR-TY0(he>HB`ET( z=4Klmk+y-4A!>{~kEwwW!|0pEQG->S8$?{BEAfwTS(2DIGa(}^b#pO3ywq?m zPmgp$m00XEuN`ez$;1x$E@2`}8D1LIB5c2!{^uQJ^AJr0Fz){Tdtu7Ecu%`C z$-aE#WdW)bqAv>9NYyovo{xePUC_A#akuIzfj3rJyo_wlB2Y;V1v=@qpQfBFc))>2 z!c7U36Dz`<8#~7&C#WJneF)gv3IQWW)e5SivZ6)u02H=h(&v(DLiWbA&w$48V$EW5 z=mJd&mtrU~oqV9Wfx!@1Tsu!LWj`*#W2MXK8Rfp?$~#5lX7z|L_Rln^I_?cnst<;0 z*rCqEIJ(yJN(@^pPI-`aWe4JZ1kDvT48j8G^kh7f`6Km1thL)x>ir2;iL(Fo;r73T zq#Hfc%CHdsC$*7R-VI7@pf6ev`Y-kw*c)1Xk4zxp}Xi&aA)LMX+62=J9rbSo) zfCvx>T#fjLCNKZW^1VCo+%WtQJmWQYGH`kW(f}@nA^{mOGGXtcJDYDid_TXTRzcYv z)os{b>~Jp}d&~CnvN(5eECFX4B~DcAd2MjTBoeNV0`1AT8pt37)@x|hNrfWBW6?fZ zeN3io=xS6vXgFn-V?hfALtwP}Mb%WGN~i^DcCvamOnoVGC*=?V5xj(Apz~s)Pf^iE z2bmzCxr2Jq3Wf(jv3nw@y%yp6IhZj=Q+fTe)T*;E>!t*VdgkB#wQ%*(#Tw{vV76=; zvTeOcKrUTuCb>Lg>JY9Hje#kEfJvxsjg-9e`Uh8xPyqA1Nl9@HZjQNw<$zcIVj>SiwzAGf!j%D}d zg&sihEY7mKu~6Qu(nxSGP1Nth?nU`Zs$yLY+x86l)^dsLX^4FNnRVq~VYcxK%1wSh zN*fx3TXz1Ha7%||Uqe87V`Iat1rkHLeMoQ`8RQI*QP3U?{<-N?^+T!Zj?csvCc29R zXb;Z19Cdw4>e{JGaWyi3;u?<=YpvbcdYG#;5`UimSQLeU%k&_c9nlCA8 z{g4~0MRh4^W*s`VN&`+|tlg!i2AdQ02m-f<1=OddfNYI(6%8VdEXm9qifPhFQ&Y*K zsq=$EEd)Scbw^E&HmS$a&(eF|{nSBvjbLaa0_srH(aQ~CZ9ypwOm5&KHDmLk+=Cfo zRGif9us&wS)-fShqja9%TnEwmdhF{pXktMpsNMpHK2)%F`m}H~B#{Fr$u67m&IAW9 z?Ie+OLVN2>J2bRI;*hKW$0_5X-8>~?rcP{^ zN+l$aaiGUgC|@dU1VQk($`(G;^(Z_>TtBq52oMXt$rww>EZ#ehJ~YVMvFHtd5N2X# zBXO!H;|z+e6c8mHrNFIXE(QRJ61OFCff0w9zk-n@O=U3{g_yE4{+%Ueo`8xusGIqh z%(gnAI7*-6^a^GF2JPV@qT27cBAdx;cWEAj*!-SAe7I2M_q;sYQk zGa+g!-#7R1fFTMWJN$hxT!kSM%&>uD; z0V^J*PX@U;KL;nm>^{mg=(pGr-2G(KvrPQcaTq9BH4GVzP<)0J^B`~K)8a!;N)tFz zcvWmdy#N@l-Ejfy_*_Xku}a-33hxF+6aZf=Lshkba#WadAE6#2RoI-`ht{FR+2}cG zT;?crdKh+Ar>UT$S;)KHm}ZTE{;Xu1Is=rcc{W8tA!9Ev8JmQC@BkxtZdB&BMsch0@Vr3;Yquz@uvUg(%F+t0GLKq!z_$A-16^WcLxn$7Un7L#1)fSuZtf)_|d;teh#7F@ui7_k44GXllN+Fx$nje62 z%d?OROv;)!(K4olku^F>O+|zXBAv6HW?_pdi!|(-3Q6YQ4ZSsx`S>IeX?98c6hDf# zg;J6^S%e6Pcwy+`StMK#@br@RI?E7rXNs?xMC5bmbRCHgE?WKK7#oG;2SG(0AE-W| zg2gq2Ylx0ISNeR*M~Z5g79|z@ixemU#rV(_A(4q8*J$(j9jdrrscfqF&pR+NGm87+ zLF|X|hI>zwh;7Cq?G)jCu z=(kJ8P{%VD6{}jvNT?MGsu>yX%2}99RB0%upqkT%=mMLhj>P9$HRphQyb>BINNUja|;X4rzLIT3SMp)5za>%@f`3JMFavi?_7_yO0jHU>^b zPLp0)R_RkB|A``nTblD0hC{3%?H0*m=7M%+(cLMK&>bU3?*g_f7x)i*B4k+~wRYWP zWhDw{lpE_d>>SUZf29XdnkTlXT~uVuoSB9zftN}O8V)5EBQ;E?&ZMMO3&jbhv=d$M zh0d85D)GAFddsAmQL{^SXsVoG7iS0MN=6Rl#Z?yb%=qh9U}17V)^eSvnqp46E(>CT z4f0o^EKGjgSG&I=o0}{P_AAiQ;x%cZYiqOZ&aa@K8I0pxgZ?$Bjtvu0xpep z?TS*FnfqzDrOXpgNh@nRFC%_c_I9Q`$ltKCpBN-(nHA5I-!vr(n!j!}J~v20LP3j-DFW?-R)8dK1&vd6XVbO z>Z*K-45*h(T__OV2V7FjMVuqfT~N5V+5BcK_p6dij3pf@6z+UdB#^-B2YBH+ECbQe z83BaS5Op|}!doMW)K(O=Gic0-h+@Q)i8#-yVd&Dn2hC- zrCt^XaljVk%dTV4;F&|62T_OG4n`*`QORTg+&~5vK2T$F<<@D3q+;u`5J65UjNN$U zCRXRAKT=j8V{tm!Fwr;nuvP?s9HSFGARQn#54i||s2#dN7!we47oA7VkK_!=xP=CI zj0asUS$H&CVBq!6NaJNpf^aZNVP2;j)tb0RD7Z#7E$Wu#l{cAe@@-BW!kDE|%7SO< zQOr+G&@d?Z3$kxd!*JlDS|MX9jCH6<^>pZzHYN^WE_r&wq9|A1Tpvuc0L+wf9vm;_ zighrUmyxhKpkQ>Kb;*P0=ez^pY%f(Kh``B#Ypa+Zi8I+2bx4F!}z#tuZ3{Ga4G5@BvW)?=J8BFtaYY^n*bSm8?fnORu=l| zSPmz5HXw-mkuw54XsjPUI8io@4v8kE#7TobKfUaq1#X~L+dqTGaLc-&FLYRdyT=$J z5=9E!dFYBUt*KqwO-fc*R7-ZOOeF)&5XoBimNhcKmgiPm2peCq# z{H5VmXA8aExHQy31sFo+V|C0_GH8T13R6_P<{>trJ~S0bU8I_@8SOj)ed+$l3y)YbB%n~$PeMKfq5rSgx@p<<0;+B=Sr}5;ur3@MD8UBS)G-neSf?^D zN&2kj$~gNL{yZuC>)xDE@832QN>#E0CIu9_Q0q1lK$k&?&ES|_WOyj^LQkQ7LZb?0 zQkm$Dc!yC@6E0Cu+_r0nfYJl=nf7N&O|)!s0VS;dOT>bG0hHBGLp>!r^Gd=k9IU<@ z7DF<;z$=ZxfI`qyN(1&AXt~KX*C=XA3z~RCliBQ(N>dL;6w$p&kwlk5Oi}={fuU1O z)OA>=WFV5xJ3c2)&)t6NEFN2oGE)-u$~Cj8dYW-s;?F}g3&!{c%qBt#K(S6m$vGXS zVM=qBYwbFNB|_cQLfK2zoNKw$Ek3^8RF6uI$Kk)oJGJvMZ2sj5Juw%an?xwtrO{fM zXCpF1QxWxY(H7v{Ycqx}GO-$qAOILRS(>L3Dyrf&IZw%v7pOPsIA$ zwrVBKuJ2D3B@g^2rX_B9lKWJqquz^PE2g9VBj4%D7BMhaJDc?wG?K@Z+y0aKY_f4{uT0uWEF&({_Kfzhm|WUng(7 z`|tXDU&Fu2-e`y3Y>_d!;l?JsE3skU?=j=F@nh^!JMGu~DirC~tK-xA8=kGc&X0|r zo^9ayd5P^w8=QE&JAGf5|LH&THwLHZDIcp&5*&lE*&MumUIx)v$lGb=3!W+?CZ=mK zgK|{D#Qilxa7=b~G)_s!eP8;=RsL?)SA;4cs#Du$P`66VjHj+yVyQ!Evn)E{*?o%x zXV{tMk;Ob7Rl~Pc+?1UFOJ&+!c4NZv#8MvxHlcWF{!P=6^ZYhsT_+?Av81`HkIjI9 zgP<-2%_tIcCp7o+Y3faFy_1KbX%_h~OJG@NSrfb?NaMYg@8;B0Fy zxV}~c4~AKGvU$M#aLxPd^e<&B=1*99mB3yP!Mi$7sNe5<7N4D0oJWK7MvV>XX1`4+ z&G59ZZo8*+myF|jdywzT6gn^_1QFThW=mpv%MZ)h%T2<>cU`6%F{)0ub&a6l+YYn$9kkGgB{5~a;+-C7u>J@*t@P9XjTvJ>>aP&lBNuBo?TuP z7$_E)>HAUMfz0qecTydp(`&nr#*cg>pA7$*lejkSpnlGty7(tqsR>ZQ$>a5a_CA&JUBC{c@t>Ayz z31;Bo4o6VScQ8#cZytb#m2`g^I%JjiwYT?*m5yF<{GsSl2Q*gNoD(XKOS-z-yO-UM z1bgDQ{=d&R?h%{)$j7AwaT^wh-OuhUMu+3Izmv3+PRZ6$>MT`5qHAfNGrF$Re*Qz&V5l1R;#KYkUj zrcZOPR~O>%=4Lq6@ds5=Xch>Uy`nmel-OP`wfEH!$BZH?i2X#uNu1+#g& zG2YkN6h-zfr`1JAlIEwW6B&n}1c0_Sg^HdB1d2HbS52|8WLqoy(8!8fhmZLwR7~Q>Xd0j!R{K3UoS;HkHwi~ogVB-_~k9zOpbn4 znyRNFl-+}JVJ$xPWu?v?mdfjC2{EXKPLLzLNUF&1$2CLy5c=g(D3_Kh&h*uFITqI7 zm=-zGYgtmAIMNp0R7eUl?6VGzc&KvU1(d;CGu%Vi?yP*8Gj=OGK+-n)DcoljeSn&h zD}!I*va4vXa_tx&RIGvfO7x9gZO_C7JBHJtda0F<+I>G(MGN+Nw#bj;eQ%-$ z1=;G20ckUq{)$oK8ym;%UOIG8PLJ2$PUd9w%}9ccW>+AFi7uv}mVmdM?V`N%i4H`M zxToa@*gs@PYW$MECAzih3N2T8PVa~e(uCQC%`!s8W?9R9uY*M&04M0Q*VzW{63wiO4Fu{4c(^vbHL6>AoIMM zoE8b^hGrFEA_kEii0`e~2PS=2sdE82Jb%*_KUB2$J#}wz=ycIL?Wc@75!%l;9Se?# zL`UP_3IIHSibA*RrH>2elghhsT@;i5G0Sel59a!ooq4ZdkBBWy`pcb#Yavd`W&{pZ|UQpM@IyKJ?R% z7ytkU`~U!W|K0iW-%KN7hIaa{jQ^W!q*wcoleT!0Z{A1L)^)lY2;gepgqgdBn{<(I zN?1~DC_NlP2!sT|0D(Z{^ZGnzW@u>i4Td!DE#{$_>P}TnjgFj|uJ2oYb+hH0rAuSR zjJY>=o4s4tq74Us=8W8%8(sRHx9OSw@Auu^&)Su%yjb(%r~zlc$42ibhZfxU-tWBM zS&Xx<^(WnP?bX=y$;aVAFnI8jq(7nYXR_z|m0{Ru`SOkHwOn|rd2}ysU$8o#|IhaC z_19DMGWZ>*2v43r-G9 z8gOs!;;VeRz23&t&FA^c;rVdzHI2^y8^rA8%jxm;$Uf!u{+x34 zf!aUs|NX;!{;`;SVRQeCaECL3zWtj#-dx-co{YY1x|^SygU{>BIsSFJKYrJ^=E3FR z%yjk%-tQZ8r;lA{2)+S*?EmuJe(*AAUw&(0G!8BgSC{|S$0GmNqrvCxG?zaE!+Sq3 zK0m)V8XW(1I2!+#*VDhFy?yyWC;g~5*TBH;Xz|#kXM5|R_0}bytav{DRNb4qj2X9! zyKTrzu6y*+i)(X>Gh62+uDtk<b#OZ>vypJSY8N4~NBow~u_+qN-{FE-A*oa!;}WH)cN^1j$X z&wQk?4U~Ss=--!}4<9dBZ5-F+{GaQ3pQmzW(ufKNMuKNgtVo_Fs=z38hmUuXLL zY4u%i{u{Nolw5p`?pC6^Y@B|f{cZLg2KuA&?Qesd3LBW*BDUwcqp-{1yXR+}P3U`B z>W5+cDvwA#pwmz`XoV<`*6%u@Pu#LcY92PV(hltl=V9ip;h@!r7)q(jcjJTz4Th$( zHKo#b#`j{xKUo#gbWjPk-@e5pPt=DU!~~h6(zMyko2q!h2{B}-i}49Gn@4R3$X!ws z@{rdM2Z*>Ox!uknHTZb4P=6GgL-8%pSvWtfvBAhaR0l;jU8$fXCqH^ubqg{%^PL=4q7g-~oKYdW24T8(@W*ZG%Fu78|1;6raq1U?(XPNl&Xy%^~v;K+hYU36US zu#hZ5NDGyZYYj-9jncS#YYrGM+X~$iuE;3`&;R5*>z-H4xKuaisamhpOx2~H&B44{ zRrXKfX&Wr!y!jk@M9dn8y>|ZADDvJ`m=+~2-^1g23 z*G5Dp+)E3E-9}0U>s;F1>%ASum!Ge!+3m!7mo1>QNmmnseSky#jZ}wvoNS!H$7U^- zz3g$n5^kN8An(a$kVZqKgBi~MLPQ{o3{%+mAUnWCcu5gO7 zX&MW4*&qqVFmm!JQ!b!h#@+a8@cm!W{FT)A3-5vc?Ye=pkBwqH#2tnRIZm{=G92LR zgOcxcDSi;T=h!@Jel3XeeZ}^5{s)k8y(V%g$dMYH{&KhuUXi+j3Nv-ftI%U>+l7!b z2juGH+>svm#nRvo`nZu1=6md=)ic+~VW&}NDZ=On0?ELNHt2@(K0|ZFLo&zjN$)nl zOUf^u(FXLONE^WsnDIVh8&Ep!N$y+hLyEPyhkn>96i->|BBO=^3u`W|P7n+!jNgIb zY3xwgw1*}XIHtCC!!+19Jzdo#!UOTaHiQZZnJSjTojI-!Jd4Ibd}&V{Y2T*v5VwSr zEqLYzfvOuBUmS*BVL^#-hXYXnEO;nG8YJ`kP#`LF?r>WUa&Fm!#lV+?kn19_gVS{i z@-bI91k#SUz-Do{Z>T=$RTJyOnNyS*3!VWOGr;^mmUg$pGvjYATz;0 z3s+1eAfrY;0bS8i_qig)luLMo;u1Ah@l|kngMv|VAh-rX8ocI73f&YXM+c-?a3D$s zdTYwc5}rs1>IjCMd7iewxr$Vtn3K*8I%^XO+9^#;ETW}4+C&pIIW5nP!q5)};Tbe5 zL{TOb7!t{!AiC3#*dvsV^7kU0#sVWB!%9FXP(&hQdw^6$;OD?b_bO;SUpbbVh)^I< z)Ikgv()r3UIz(4B9Qp;y)K{nsaUwb6*(tsZIl1?$mhoN=1X7AS^_$|;57gQJJnAklWiZJsEax}<}W@&J6 zMCDON+8Fx`!djE%Mn%V#u_`A6gK262p+U}48oWzFf1XU|F{vbNgQLMg<%Nv_oh$7N z#<%N;6AK;p$%o_^V)Qnq8Dzj_hv=YvNWnm0!Z|@bf<>$gr3m*)OPIopii0V)UC@vc z{zSs~q%^k(4bVp2S7$YN*mAzmlM(qy&M|d{uZ;4aPfiUG91usbpDONySKtW}Mqa20 zPY>q7%A>)xfsIK)-vn?}A@g5~y2TMfbHtg)zQ#1mWnLN`2$Ynq0j4j(n|{mYhJzX6 zfI!*?p4DUMlI(U*ga<4Kp^xh$b-K(Yqa*BFUvch`Rw>1Wq`na!(ngF_;))YPfneZt z70l@IRKO^=%RmU?Ut2&zZpLpQij*_r5`v&GBSwncHVfb{U~tSS14mt>RoyY1vz09ac_R7d=#Pz+;f%tUw)5F$rrt3{B2>@ZVyiMC&UDiNX4Cu4)8 ztBigOG^%lGiNC=_6nMwcQ8z?56(EK2hN=|+HUNm9pN+Z%P7)o17Gj|4ndp>p%ZPeW zi5^w5Pe#R$NI?v#%1|EqI6xpChR;Jj=V1gOhh#134sU@dYC@Wet*|rD5R`qth)bm> zrhCvc3vql}@t{#Jrh_Y^LJr)RYS2OOYV!bQFxYd8EY1S0eO0j3Z)M-5P7YX-8(d-ke--< zggbDg1dlR2AT}64)KoQ^&VYX`)e1Ms>LZvJS%4n+7m#TV$$OlfgIG`oxqtw~AawbO z!3nFr!Ri8;1|AR;axx}q0^$oXkPU-#+&~BEKcVvp?-hmzoB{d94j74QlTZ;Bsp}OQ zbMy`{n1qIyQV<-+KoS`qQ%YgkB=w1rAV69;1Aiz;)B8mWmxw^zkp#{}yHrq)EvY|{ zgYMYCQcaOyMF0p-Oa!FAw6K123dV^lP!PUXBfvaPBtf}DA#o-m zx5yU>iT5bx?|Uo-MN3^Bv26_yk)2>YO+xz_ZaW+XDQN}9#{f_1v{+dfpT{JPCcq@c zdw7QNkUXjqx;%#e zhtG|GD4#?q$Em_EEd3=|eIqiW7moProaBR+LElmw20_RYK(HloUQ}NGmZU)l)=_ho z1}br23uKps>NYTs6l8WmP{ZR9ktV*oDVi7(|NG5Mh?zo2X(Q-S1O-ZnagLj4YMW4| z^wHb|Q>tA_01?CkQ4KMA9pk(hCgG(hkE=|F}jtnPHa`Y0+_PO{Z@yi#w5YG=0H{)tyjCUaN?=Q_i~DdHXzJI-dEmLzOq5UI5n zzzkw^PtzR`a)YdL+41CAie7~ctp?P~;gzM2mSCFn zNgnw%yUa9LlO+)44TLT6E9)Fi%g5SJ<~Grxn98;)d2TQ(e@>Lx5X+`wK*Y3caf{G$ ztR++*5Tk%3hMEe2TQpYK2CB(bBi`Hts5EOSIzGD<#iLf7TNM5>CAU2DVnP0H#j0iG z|0gC*LYuw2C5m**qIkinSNdkBr)P?!z2c=S=;L~J5c>m@*0e?(yOxbL(!xX4e%cCL z5)u3&jar-%6AQA}np2ywSbb8`F-2Xs^di{Hi&RK~AtySl35QjLVXs&WYM8~YFlSLC zulE(|-~N)!(qGBUvth+%5I_KD=Ve$5p6mFOC)5%%BS!A zGxd96J8I4%%MrJ}G>R0ZPl*x!N$DY9slRjT()wDoar$ePUAu0Q($^Mqz+_mVb9qub4NsjYV#y zDQjQbcMe}#rP|8kiU79g63xd{SK2s%X;R`c`44A z;Io+=ftd&=H6`c4jMNl$)=9&^o9w}09;%Pw19*8BW z8zr03cCi^YxnyN)8U}mzEV+nI_DDkYh*?>cXeS>fxizcOLqg6Vxauz3g(OY~r<7H= zthIpO3DZ?rQC*-q(1G}U!xosVwWS&nATZC(stQD_fvKsX1;1Mqlwjdv<1f`CQxP-; z%WrFigfjCgVPk90=|qS$UOHK*5GKg!2Y*--lEQ)fT# z?`fp6*0d#S!-5?5FE@_o`dU02>yY-uMrvP}l0^mSYn_|_QjJmp@(QJ?-b{gY>LfTS zZhKknC*j&LkF_$^@Ya3ZlqNth(9>(Q$$3yHNuz?i83>`DU?R$u@MXcR0b_NWOsp@`zp41#pJ%v;54QXF8C zffGl$?8KT(Vkkv^mbqcEinEDTQv|u;Xv`GMB|9l?GJImy(Yx zcH!wn>LfMth_fS=v|uEC<`k_vi{>V$ce5R>0zN_s`G$DS$&D}XsMX?sRQPdw6OzuB z+ox^K*5qYQV(G(UVM-;4q_Ja>1aC*1#j>MDkvob7C(b&J62ARJSZUU^L8f|iW|a^X z9)x#{Cmy#WAn}qW(_yuI2m(@&YY1LF>e**VJkG6AM-9#W%WLs6ND_i%ibz`Je&`25 zgy43z0Kf#aV_&6G> z6gG!rS5x>RXU7Qg?=R31_9E7onJ7j3z&TRV-YQ2I_M)X!IVat*z*D3=b9PR^MLwwR z6uy}`J1qCrV`YE#X!IH1|63|w*>_-Wa0Nf`Gc^8n2i|<}GGAQn&A+GbOR*L`1Ec;6 z$g-}R0let^CC`u5{S=t*ckbHl`DFO@VZfyQdWue7936gxO*v(C<_JOB<9?Tm)iM7`9=3?iuG0v1`p z)%q5vk)-sQYb4Hp-8;I4tj@c57=D+=_3GZT-3(AgpUUaTj6#&Wg*Wz`u5 zD~Y&ifWuzzI30kl!$TimW=WMC>ErL5x49`*N=+f430;GW_w%Z9*)_(Ty#h zFp;>^-<;fA`<)KjTJBhOJ#qqJi!FvkJDR+Yc!Xlq<(_bT0N=xHZDdpglJN zLAs{DVx&m=x~L7D?uVp#*4?4)N1}o$@+dkzgGPtwMC_e&M*ebq94uQv>doG-;kse_ zjW*2H-Tvka6s1t9CfzUF-cEM6ANI8s25H%W3boEw=q# zZmDlHT_+~$+jTmRcU7~CcfZr@e{ufaP5oZtL!R?DcRXKqttL7j^eXrdHT~ z1-vYUb5zsKb1VAqTAkE9F)h0J6>pv>@Ws6$t$xH$p6G&o>VTjC{2vtNYalA3NLi=tA}lWW2M`imhT69f`O1CTEC`_Ek9@kk6y*Ob`)AhesG&OJXr zAGyr0{`}2fH($P8K6m2d%)hzW==*aa)_m}BVe;x{e`fVir|$Oi5&!%1rSH{yJ88kz zg+nt(kMBm$ABQ&l0RP*($9bf)m(>UDd)4(|dtp31dGhA?EwD|kE8q)VxPPM97R$-0s95mwf1HJT$7y7^ zdC|y$O9STBO^lsizt`8c{0o1M{9n=&51;FD^%1r)oY_2G{9eyHgU6?Z&-c-fkN@io z+Ahw1s`( z-g{%;jN^x$zs_LV&F3BJw0Y+Bv)SwG>*MhKbbS0ChF72W|3Ec=zO=eO9lc9=xxetP zJ4^rO`??69FPM+lmp2bC7xy@0;5+-t=gGtE=gi^Br+fUlem;D^h<5I=hx7jgw2mzg zUN1k>`MrOOf7qcOX1xaR4*agq|I63I`Te(-J8$FRAbB`DSU>K%IUf$)Ucdh(9N8Ft zr}^Pu@YBQnu%E}zazEK!-0Q0wSI(7DPdhTqj4e-A4?g{?n@=tGPWj~dQ}NSPFYa4;C>E;;*4IMc;zqHT3Y@FjpIq{4h?bi2uU$u;DeX?`hXH^foB|CYumG;IC zyX7H-Y@>GrhyOAx4}H9V|AV3|_vW&PgMab=J$MC|^5pA~!a*28a~cH8S5S@hzGOHh7zF6-VM&pUA66mMJ2^xut) zKR$J(_;*aFeTc@zlyl~Nlj+TXIk5HE>K;9TX#z6bJ149=W<$fU_>a0}-%*wJ!xBC7 z5fdkS&PaVh$#3qbQ7be!2L_C{0(h@Au)giujX%{^VZ6)q-EDVXZTb(|UQQ{0hvHhS zy{?&jqxWL=7{>FXen;07{~&NkT0iTq!=At{zumOAVJ?;HU4}E7{h~Ai&45~C)u26? zJZOi1vkHCbI+<0-_;RnG1(>&mbC#cAD`qU6EYqPk8W_yA*2DPyMQ1ry+`g%-{)UUwp)H3&~hVcbDpVIVZ-j`%_sqtNKX z{pHe|jvRtd!T#)t3B_$DzOLGD%7G$1c~<$Zi{dLFoT$Guhgeo7=$16A>Q;4|!rk7o z+-*|sSBcE|k~2~Lw1eUd)MW>=UdCIew1CnejwAeMFwFycjgxB-Y2yPN=2^YCrPcm7 zxf1R(H}H<1ymo*yZ<}OZ8zT<2LAKo(sTANi;>(>>Tx}@utb!;@RriaHNF7a*m|Ht; zc=sDB-4o6Tsm0Il)Mx7mOpf3J9Zyu-TX(icU@rCcb{Pxm0X(h?LAYVMa9?UEZe%; z2IA)uLa*0NZ^-$1uTFlcg)qhy6D&%y#4k!M{C8}iyQrP*^+_c|NsUC=DWI*3b`N5N~62q24ze#}Fy@+f5I1B0t!mMczfQ?xN6QEMjSf zsG@3j7-_eO@bun`QqMFt8odtwzYkjtzVZD5&BWf_vAsK_-rd;Oh6%dx{qs7XVoWC& zm-%n*hL}wiALmZkRLwy{`;dk5_fMst7EP@0N7f1{pmhye<^26~WFZXd8Mh~+1{_{| zU#@(ci5z~HV0H*#r|s76Svw7n>@nZmKWU2$kL$TGIvDTnqqecjM1^5RdUCTto6zgM~Xv}!}#xHIFy)6;{qH=ZSb zzjwMnAcR<})wHG^90G$m`m=I(t-$v4cWn1~G8?RT!z;+3X)M%bfhHKi%E_TjyMTHd zcjBkR`M*c=S5Q4Hz6biZ>ITd{G>G#Mw;3ShI@93Da)Ph+Nqp3$_(SNPVezc_H~$fl zMfP?62as_+Ci1CBk(wO-ayX9Okvakjv-OKhP-E-c1(4JG=mv5=!!txfGAAENpEm!?%Fk`lhIAmvYr&BiaXw-j z&^qnO?i=ibiZwXLepsp$&spiBLk0p1>n<%$5R55|p8?@%?9f;=M<$fGCbo9NG*~#j z9n~bl{c*uI1d0ins+K~XIWCU8b4Ee@X-^#KpDuHdw*(Wdc;!PrIQ}qh+F;}>R(vCPl=JB{Ms6J`c z^9Vpq5G;ofw72eeeM?NKsT*o(cfpN;Nm2Q$fIUS4^ZJBSt=f9Z}JDxuQiB z%lHIh617%wRq*+J0#WiHI0nL+JZ8xXU6iGVdn8$KAW8=Mt4hie9>@slhz6Ybp0>a_ ziqxK%V@?e^Ym*9EDNW3*BBeT7L=!bRt%*-88j>6?+^?8~R|&gank*2s#YCmm&;2 zUBu4{wX}kU1z!F0EXM|y)aT_GSiKyIFmnp>v`7wSX>jmFWzj}j7>5i(+7o3)#m5%0 zDyMw|Y3cx>K~B;dJj=rCkFGPA)RMNr(cqx+!p4Bk74`*VyY}cgnJ|YKXvm3c5iq_fO)bKGG|_ieS&g2y zoKJOR#6A-9%x&SzL;PnGQ-g$i#8K=gihE#{_=1EHm#V@OgZVIWXmD*{5FitpRzgOU2 zL4vzG41*Kg-6nRP~E#LJ?OV~YxmN&?>u0Zd)s@8 zvqvEPS&!e#6!;+s$(|ps)#4^Vq zTPcK-aYi3;AyVZIQQ^*z3g)pvR~f){NksFl<$3quosVL?Atsxtv~WyJ=sOiwX~&zB63Oin$m*msO=e&tb+heU)rw+Mvbi| zIQ#zU5okazj$!hA8j*zTy-%qo9dbtWi1RG@c=ndA}#OU1K39v`)2 zr||z8jgt89Xq43dJB{N1_Zr3af1*Yy`qvtT_n$P%(*JIa0`$ACQDlGDC<lAHHsiiqi99LG|Jdt8l_fgORuHrJsp3+$WM*3)n@gZMv?uMMq&N0(J1%- zqf!1pH44YZe>BSfc#V?uFEt9;C5=-0r$#yaOQW!d{H0O6D>?4KG)m;38m0M9jRLu* zQAB>%C?{Kuvt=j!RexxdrT=J@e_x{*{dZ^-|9?}X9R8tE)*Vh>wVW5iG|GaRK`~6D zyn|^JV zat`)6*bu!Pb-ts>?}8+YD5R(5vPPNw?22PWMkM^%T=|RNm}EkEy(LSb`E)l`dHVuP z&h+p?F&0N8l)+Hyh()BCs--#aVVo>uCyuUuLaiO1ihw0Ju2zy2=1f|@4nZZ%i3f$x ziT$ad?)`}ONvFV67b`QhG0%ISli4akb2Jo);#|CCjG#ZXDmj{HO=?8n!L3VL2|WW= zr6u%yoeQmY^z##H7VZL(;V??WJSX~Nl| zb<_qi$sCde1TQ{ib3UYOhzd52H^wEqEuJ<8+*bk+>Q0TK#5s+GN}ty|!X|GHdiF%; zIJUPUi|(_7xhl2Ws(vY7F>K!ljNDQIA#c2QYiJZ*E<>CX62T}`FH>xs8OY7!GF;bGHsQ496 zkb744VGAd!m>%Lq?Gkv>f~Cqb8CNt}9rk9lguKVGm`j(tCwU-!1+~jwS&kb&tYl_P zEK`qct&J@>b@;qy7wdXWH!9da;)g%%L@@m7l{Dw-_;~BHeQxP_2TmceWoIvUX)514 zmvWnfk%Z!@s@32)J%`s$Jw63|T|Pg6vtJ#*wy<3E`Osxvy#F$~^8EtD)5(<^BtmSk zO;UvJ_K2-N5Af(gETZehMR2z!;{iO2zn}rAT}x+MqhzClYBhVeIF=?7EV|@YO}1ba z0N0j^nZqI%(SaORM2X2L&GyP(mvad>f=T5|$3u-I>l!EmL$5c2MSKA8XeK4Pr<>vJvjIp+Mb}P=BiaT(Bo1IEYa)ZdmS??A zC$WZEUZt)%vvW_V28i04n=e`qm`f#e31M4&Fr&KDjEN; zvK+mFgT*J~Z^0GxHedL%=fO)0Sovd?SwU9F8e!fOPRb9;nd2r#pX>&`p>1xfnOrFe zoK_|NN^NsQp#T{RtYdWI-E6Y%OH)z*)?C-`vQ(!2gCx_eJHH@&!7Nk)=dL{w`ml1w z+C+hT-n)7N!djupOhLFKgc6QkUBOyUwVsXdjS!2$*SyCB z{~oK3S8;hhVrdH8p43k`dQQ(!*{dH{)+X|rkCV9a6V2?QZ4H^Vm9|iHX=IycDe3Y> zKnU#UU7g$|oOduf4;}!hNB;HXF7k%f*1sI46Zt^TYLXMr3z~H?uj*lrUd?_?TRB}1 z3DQ6#jmJE>t1D+OO(xW>XawAB*-=#eXreNV=wDjw@j>M7qh}~C{WZQwNwo#Nft;zh zbC8FaGRcf4WwH3ZYuicj|OedouEq^X(H>S*MIwXJ2Dn~teQuvRe3+94~fy#J_Yf5|ElQpOLP+CwAqcrv;V>02a##i-F@_YQQhO7n<{?8%_P_p<8Q5Jin-ZO@(Ate+5h za867!H{5pHnS1^D(>976@!3cLO9HRr%WU(7KFU(OwOxgWqiPug;rAayaRWFi348?J z4ta`z>>?ySGxu=kO}3jGpyW$nG#{dx$Y?Jhi?`e&(m=I8rS=069&0{9kmEK8IezTi zZa4aEOY~zUyZ*u(*}W00%88wY=0R=;o(I6GxwF=tLA}k~ebFsSwjIjSmP+Fm(QsAZ z1;G~eN@J6fhx3l6o9>%299N2wa?-Q5HMFKjNX?Is4COK{CQ#6(c;Uh@X9Wr@nxm-h zaIrcw?Vfa}d?+oM)}{izje=M9z@io1teR1kHJT%7Q5`q-u)Co0eyuR0(WE+>B7{T< zbin#@5i*e`+p?2Vy=t_-t>yH}EcOY3jVkQ{5frmMYe%TnR$42XMNp-i=K+}K(R#QtT=!1CV|Ckj@HS8gq%4o>;)j#HxVScC7!}?5!XE$) zBB*ofT(;u{4Zv^5Yx9*ofg51TDZ!ehu$}MA=NoN%RGWt6LSnw*xp}*XIxnK_5L|>> z!R<@6`@P@NSw7%SOq~Bzl8)gEy8yN)_hMdr7;z&i8?$PRDy*#LG>Qn)Y*OmsS6n}q z3l;9Gs)#hQl+bLZuGre#)4+NNE-A-E{sOmzEiHA|H)38X(_V)jjmGJ?M0!{E;XyL5 zl1NXjX8Y;agGBk6PmmzqTKvcgR*BC9u=k$WM8Yxhag?NVqPW-CZ$elSdTWQikm2(> z#`>5}iM_U|h*8y~A6iUHzu4||eN?A5?Us{NIK=Th5xubPxF;bY&;7f16;_vCeQb*~ zh2h1F*liu>3{#s=1Q6UUfVc3}?6few#*uU;7!trOUWI5$TidRZGF1P9j>q2_|0Pcl z9{pMl2Qvn2e%)x|NFn{21L-u=^bo9XTEd-di(`%4@2r{wyl4*U&jWpjOO{_RPRkv-aJf#}r= z%F}!~p;UwF@m*~9W`fdJa_gCZ0+t*=&EuQOj|FR?(N_+Zx+;=emg5R zJePQ#VfOJboNiWO*~h4Lqdc{+GTfg{(QIis9-%#?ohiq41=)9jBAr}Z&Nau#!BB0* zY+=y2CT;h2&KbhhhMRV5S9=*Yt(YJj06=!75ZjtStfeiCVTBiJ=-|fTYGZxVq+BX7 zeU|N<*fQUa(Lf$r-n|-?>3W&rk`}2?Vr9YBMiZUSCYN_M-qGU)`yp_L^p)NgD`V6* zJ(?Ey6eA77=AJ8fJ+Irowjlq_&fIyV4|ML602u1*&BH3k1@2p0?s~oSQzp$={xCKO z8_on;uH;pfRSiD!NCS$#9RisdJ9`+~TBPN#AJmO0WKH0JoAtdoqXIW-QuqN?Z0Tjx zuZk+BOg^nQ=QZFzL+epWp$Dge7YkhNlS)!nsGmcNggFj79pxx zZp`BtTK6RLgKGKQR} zqe)(?=4GCX7?NyjDm**Rz5bGa76FLe#e|Wc*8NQofWYXau`9fUyYIxmEZTp!$gvIt z*PZS_3mt_MpY|)=YG)=K)Q9q6Wr*D3tkG+GmGjg;NaYAoO<@k(QWxKuca9ZpYWE3Y z=Tn7-iAP$`e7TBK<$^Lf2z+D>Vzd>Ia= z#AL~22XhiucfjO3F^Q=ve8LXC>D+BO3I}Yh&!DXP5Am{gDpyp#W*P-J>d_u4=VGZdBDXiN>Hf7s1C=w=>7Kmg=m0xfu03Kt#Pw@UQ^@ z@}(AHL2#fU$_TMS6$(b2cMRyUsmUQSygr!C@$!ky8mYoLbMqB?6e?Cw3!A%?>h3xE zbgzSDLG<;xxx_C5G^ClRkJk_$aU#X1LqBeew;doO4WD~8R?X(qlrw!J&mY=i(5pn* z7XO&wF0zZTYRd9eB{&<1B%Xkr_c6NR)|AUiFssFkrXOw^V2MP0g|P<8TaV=wG& zj8-5tj#TpO^sf$ag{b>#-b|C1ELcMOi|c5~WbNr`NR3am&&yL3tiF`Rs${{b6PK2{ zQa*EB{g~n=us$hgQ?B!Q-P~)!f;V8Ks$-Kx3dq?}647o{It_n6Yr9goy~aWKdvG^z z2Qac9T6*^Iq)bNvURpb+Ta_K{12*l)U0tL?N%jN?>b++rHJ=XOcdE7K!W(q8N_&6F zngeS-K+5;(E8G9DeJJG|8E`1pOgXHh3l+$VgQqw;h;*JJxj5va8oyn23Irmr36aka zm@3s@6mMCofD$GoNe;55N!xuXhutJLm6~Y!#N&^9)X(L-XgXCV^~hi^rIKR&HfnYU z^-K}rF>w#=vKdn)C{O=@{(eLuR9PFNI@hjRLTDPZ{QZL7NGTg+fV2f)9}-0CLI@6L z(-M4~y%rm?F#3b@cDRIcHUhp%aqjM&#A)kSg)VvcKbn`BAP ziSA|z5V~s<1Ru)l6ukM-kg?8E0%+r3rDO9#b}kN3cjpTK_3aRmMaX8 zOu1@hRiB3Cs5Pton~(%dy`_pgw6!$;jUSj-8ykaoTS1BP z7E*;914-aUJ{H2~ZtWi2wySH!pj~FYa-CG;x(OP2*3aNcmaewqLmV}08T5hX`}xfk z_yC*wg4%@4KC*8D`I7q>15L4lN9#7(QqEIRW=R?jsxsed`SRkN(WKrwK2o4euF^qF zWkL>j?D21mZ?UDKO>>M2s!FDW2 zCFbQCasu*?Q(nHOn=#mm%Y1M5yNx_%uV!^y5FjLi0RS`^0{}#qPirm~P!n4h$G@8| zb4gFfWwIW}dsaVdAw+ajn`fJlzlWlGUq-~)xXZpyL59SblgN_{LsY!GSifZk!&3k4P(3B4zU`2&^~hU8{`JF;fy5!)h($GSp*}asXeOL~f;>N(>NDCVJ6YS<$qHdO&&5FPZu#i&P}>3b@U4U~ zVkD|uU;q3@YBhLK!d-Cy>&%|=@Wiwje4MKB?SzNq8@J7dH#E9#hAbp0?l8!E;~T?^ zm4?%HR5Kl0I;|JSOq=>%8F>9(gOti|hZLc&MZYQdjJK>^P#h)R_YqQ_^k%HI_SWC@ zX(pG>vHN6R?i8dsi{D4@>0u4DVbE0^~uN=PxEMYCeu}We?$`=4`RK{MB{@L4pV$S6m1l_-4YlejM}B~+GXY( zw=P8qUjA|DS$UkD0CBnK>-(e$!sT42O{QT!VcDqx&V<&@G=9k1&zwHGNzOce9M#@K z@-0g%vzBMnt__t?QEQi07kLyrA9L9MR-Rj#!^*TB(VO-R@@$J{R{1mn{&$Lrx`h*E zAQ}H-%zBdK2PVWV8*}-5K{`;e<#zU0-3xX?EgKO#U8Dh##0OpNk%*s7@66)arum{d z#A1A{;*&t`0H3y(KKB&Q!Ci}p?F?nlpya8l{Ad{CF zPqHhBai%;S=1Zbd078BP*BbAuGeiOiObnpZrK{CjkVd3Q=L<8L-k^cu4d=#I@v%+UDA4vm0&@<;60P+!t5K5zN|4 zm=h-uB5n13uvZ(%%}VFZtA59cSH0TO(N_bk73hcLBOijS0S4fl3M-IJ^VFw(5~(F) zuvz?wHoDuKMv@1_bBufaSj?gMXbaKwIH15|Yh}WGTl%}l7minLZsN3>)W@<T`nBSmvVdv^YJ)b^07qVQ*o91_?F)D_qFOZu%a1cMvc|s&O66j zO~Ay_4=a%AURjIZ3-#Stm_lSruSa>$mw(`c{k(9+j~LY+Fpe3|PLk#{V8GpRdSPs$mds2y13 z+fql+pQ17ykh3wzD%-QvR?Z2;PvaRr>&`PL6}c^apRR)|6j#cu4bASDDK&Op(@_Q#76BG!h5@a7o7_F z@*%3Jc#$vXoA*T~aC<%0I=&&PZCDKOWZUwF%M${J;@UFF9$UOliB8s{O~}z2&}{=IRf(he9tip#Hsob z6W3X*CaR^u*KA~rB^=z!u>Box9!ZOk>SOV|2d#OK6mz4(!G}iDY;bqL=EyDvG(bo) zCPoK~cvUYVOFL1k$Q#cA1jCWs*@iCofqTk(C5B{+*lk%-j!(J+Nb3o#2&N0!gFCQ0 zQBu&+xaeE6-hXxg9djlb(_pV*qfKReqygx6#hcEdhthN+SdY-n6&`7CFo*IH*s&U( z(_(N8TUheXyw7yXtf>(Y)*>p!lgig!5H&%%$7PI|-4NlzstKpOj;8}hMupRPzb|wM zY>Bk{6`(6q==x$yOAWh70_aaVsQ6|3E(8DU#(NAM?KBA#MDo(Y#CSzn9+V5Pkzb`I z5_Tmsajq`)cgd&YC74WEy_zZ*_`6*Q_P~S$AOFzofzf2KJ)X*xO+jOd&4w%x8b;+C zs_t^$q}E(yeuzVH1Kp?tU74XQ@*Yn>D=|ZwZej{CK^)fL%a6!tx>31v!NSgdRhIi- zgk8RVCx|ll&q+8e*;!Uz2e;KHDUv*r!FWH&MQURmDrnF~@+A_)z*!HGMWWCV(vq>T zUEULFUlD&ch$_*ad#iU7`$IQ#B-%N+aO+tdSF}M#%6GYiy*|o!oS^5Htg3V6yy`7; z4BP5cTkO2=iXL*B_94CtT3q13C(3hjP6{*e_AO!(Qx$=KVJ03go|I1@CL3F=Pk2X& z_T`?oDXk*)v08XR*vGk#w1_OxOfRsXn$qA+iD<20fB4K}c5j(+56KE}Ujbo=2P)x5 zh(-4xZreMt66#1sjC)Il3D?gasHD3!hkYhGLE-Dq8{efNlWe`*W|AcLaXId^vDId# z5Eb_XJs5E z96pDno>zhZac-f05pOYTDZ~pH8r};N$iFZwd%OZh`G}nr5#@3YAQ*;227=UlbdQEV z46!P5gzKqh(8s$yE(b&1>56)ot0@D@-4tM7Cfo!y4w|6qhKj}5w&jFjG+c?}rQLheVL96oOEPiZ1K;l!z*N{h~L{@Qk67O}4W>m6iZkITof%=4fD(~)W zE{0PJPp5j!kmY+|zQKwH9!+qFdQdw_TM4|u974kHJe2DBoFjuy5qw4-(=56(oV`Ns z{5?ECZFzO8i+oQ~U%2SZ6Mj@5ca>^OdGB+L>yteXWsmO-dwpw8SYo`YUElXpCt)2A zi-p;3yG>DL(pTHN@4Zs^khfRgrz?L04UE;N>E!CGn=a&dtdQtW&4*g4kzUw^jBUqR zVNA~lZ3xOeOY0|B4u7T+ITl{r89Vu+5z8zRVa&QA(F)t;lf#P-nU4pz7x0#F$0C=| zn|wk}$kfhyJJ#@cLFOUfdOWOs7JA8j&&?u3g&OV1L$(M9DPB&UBh{@C^aXfr>v2mq zqipZe_BMApJC_YY?cYdQi^Ze7PS4C(+4Fk;V$~(Y*?-LH)4??UD0jy|3vhC6qegIe zm>2BKy^W?HZFK5orzO#lDUGnvGq7huWZ_F>ikYk7hq#2OOJ|j^%bAk_<`;C z`SzyhcwD^{!YrfqJ4K^ext>!LPhJkhrU^44j!vb8q;wRWms>NIojah59ro{@WUo3p zriZm_zA3@a$V?h1V;rJ*b(z14Hp`sVn6f=fCLfrZ7d`3%i1|D{oi*^;ocA)H?I{tH z-xp?E_{hF4=auq^n@vTd)68XYkYUiQG&dTHY~7B~7@$o#7Sy=)YWKWZ$UFP;OcHS0u+zn@4*ze{2GkkE!^Jw0aJU7mddcX~OgiT@GH#_94~(tcilt#N$A zknYBh`&At7dU`v%b%oV@?`+B4E%K}f5P|RBeD3+dPj-Q#t^^0WC5#8Vqjn3nQUfGI zPUlmy0f4Dm0Du6t<>~^vEo^9F=wt|VGJj%Y1U0m<=CFgBU1y-z-6hfE0RU`& z0AL?s%NH2g(Zc45wFT4)Xl((z)#uWUFfj9sit(C8A_<8wwoqYG(TrU@lx=sxM zuwNmw<^7rrhL}PeAW&n7I2Wfl7-DGhbL7xou3g58{lLt2LSM2+0jJz|I3bk8wYj$*BF#_ zZ^(fFfQBUifbq&s;un6s6G;nWTf2Ma77*(jQsCNX=FR0GO{pdGO(Wd0Zu+ zX4b!@#o-s3@4`M>s)IQRNqhi+>I$}#`V!XB&Cv;B;|ToyufBt=tn31Fhd2li27G~i9XQVS_dqVr8*^vB z;=Zm4%iS8vb)baMzW{GluYn+*8)2^0GSp%)7%uF9Ts;_j z;=hJ*3Gm(&8Hw;$=P$4pt`XLT-nn`(q~HKLQnt{aR!#rDn;pba?AhF1L!+ItQ~VSvvuc2ku!=)^1@9Xp)f&DPRJs6Dq3TQ{;63E8oU!%OwtA7;15Hqlq;R*^JM*l0O>nIsl zSe0~yxx$;mdsWGC(g0%tVc{`dVPf9@8zvZH4KZ|t{8<;S*VTqHg!{fQVh1dHgjc9k z4=x=RBNG#dso@iAryDc3ITD)q90sX?9b4inkhO=GA=j$<^;i=84T46=004>T>#@Ao zyoC9yeskWGCVijwIX74gS+Et>q4{lrg$7$Tp405z3Zfot3cO>!qQ>`4Z>S zD|96-q-^bO>RerY|L$+G{LvmR72J&a$J=0E&EAaq=Z8A3Gp}0p%S>6=dF`(ryUjm4_UojpuK6;_ec=-6AI0McC;$Ke5CC4T4a!!Y?;h9!aya z+n`4n?UPJyLuM#ZY?0w#9-x#l#HGx6LBc#uRDa9!2AkylrsY?{h!TblO5^2o>pR66 zlig^W(-d*KBd<9hR+C_g?T5&cOmaKOlY5Pca|jN|N~W^PN2UWjJZs(b)#U6CPlRIe|r90iiEIoWycy+YXDKQx5mMbl2!a zmeRS%nK(SVWC~dYn_{S%*qf!Ga3>(l%6g*1j)@5w4$`!!kB8%n*9YfsQkPQq8uaK* z6Kx3cNysuZ_(nla_AD*VAmdc=BAsGL`4WI1n?l)HuBykwn*Cc1kHoqS*8vZ&t%O=i zc$W-5E4g34NNQ);_tF%Di^snl^*d3s@?a0FGHH>+9S9VAH)H%_Pp2hu>!Nf`=XuDO z5l3*fuSZgy$Sf!JX*TpZoYY)?H0;#(b#M(dz!%s=9`ror`C|(v#Igp7b1iN*tvZKB}8%n!Z~|6VMW@=B{Zg?;n)tP-7lc`u%!;87;QT1!QVVq_pxaM zV@*4fvv2v1{WXGiH~`ikwIHTgv1{Yvk zEM|8S(P*fdyW5;~*#T{#*eTU^>(=_=aP|Wz|6h5fGxEpX6%YUb5DWkS`d?n@Iht5I z(b4|rS+cZk8%U1=ey2v*lLo}}8F?0?buf}>;skFm3O_HdwYXAY*VhP-N+G*ViZlEB zB`C+4SuKLE~nw(iJ3`nNTBB?f!f~LP+L~9Pa4g^&!fuf_-lP9o|F%Vs1tV=u61)`gv z57)_`g%p5>p`QQJhPKjZ|11;p3p{VjT!6RaRnj<;EL0$Hr5ze&GIAW~o3if4;XLGJ z4yRn3teZ}+6lmL(L>>#LUgO~xP?|o}*fz?Ou#*pis zi@swl^OJ9jOJ}pabtv~g>GA(p_CEw8ciR8x>HJsv*#GFUF>y99HgGneGqQ6uk$1GS zH*s{fFmd`%`G+X#$OX}(d{Y(Q%1?$m!PX1UVtq39+zhS7%5tvjnbOLLcE_qLR~`t}M0aHeI;1 z_6^i?dzJfE(jn|paNr;EP7ml-v{4Lq8&SsIccRD2QmXAY%rMfLC;S-hrnbFZq>%*T zgV6Rn2Q!ddS?Vh_{zlu^d(PRnuT^e@8Q-`iVOj*GOlRf#Z1DnIm*I-|L2_z#9R8U> z>oiVD^bZXV-PdTH$hWK8BkyF93P-Q~=w(`5I7A|gTS=_X&C54%YT@BPQb~lA;$9za z=labAkloL`k2~ZbcSD0b^LU-Vk^#m^kIwiM${W8Ivy^0y_4HT6yu7O;Yz1N;C$0ZA_3L=$l97O@yL2dGB zsuvQr#|HTL1Amu>kLb-?N>?I{?!{@R&BD!j{RkaCz-?}x5|Q^lBLM>zv_D&K`Kzv7 zGk&@4cK#cGpt|C9@ju*a|8BDX8-5Y@f1fBP3p?BY^VG)dpN}z` zz;9`Nic}MG6NPP$5kgW8kG_O%V~&co+@wl<`5R_6kxG#7!oZ*1arFPjDM{S7)b|e` z>pz~!|8F=IO{`4}oJ=HaP3``J)FrkH?qA~!b;~^%*Ci)_lAv&Ka3U-$vd9P8&qRxk zv!hCDUps&Lq&tm&+h)Bx5LER+&xj3?+0$7$RZ$Z*_2en)kFF4Kg&44L6>_76=BqOs->qkDp*ZBVP_F}x{s zVrf|ITXCdiQh@zH$b{p-=6DeYN{L-7W z4*`NKI59gq^>s5x1K%&DMJl^zUm!}DY`o+N%WY8jN3p8MqIv|IKI`>5ixHcjq6R-WF)ZD#LauJ z;4;3yey*-JNua02i+Woe#*~9M4Pbw-JsiVXLmSCk+tfj}w7w@>e=&Cc_m7-&<+NW# zGZyP-rtj*7`&mP*k^pzYXt=-t@6<#kfhQYEI~Dqp#TghY>olvEQ$WU|q@jtgv5 zct5^Tb4@9OrM+FAtEG!L#9P;*8!R$*S5euiNX-Y}OBg&py@|2$4^4358X8|+D+kY- zyt1OFu8xk)ATAnStjm*Es@B5U{L|MizAP>60}(~AgckjVuoQpM#J;&MGwSZ5qS{kZ z5%0~%S+^Ld!}&Q~O=#2I)1w{li6k7ypn$sC<&-t*#`5ZFk*=@|CHBis6eVYEKnyoj z6LUhIjzS?+)cc*A9e0%k%+A7%pqIJ03w3Apeb3a?RQv+C`LqH1Qvo07qB7CeN+{ZI zE!;50={6dgZ$j1-C%V10@Hn}|D~nLOb6Sr{bkg~}Cqal>+rT#&FCgIS>Nyy^ZDv=i zfp^X6QOL#!VJBs?S=r*u=!KDpXTeaS8Ko?dcD<;GXUf{+&u8UCnB19T^PI|{@jR5h z?M`>a=7Anx<3$V8GAY@}NQmAg`)0zRmB0Al`UVb7x7A~=L@cT9VEuFY5nS+}Qin82gkV^mb9W`^jO!UvPn@94i)I% zG9~S}Vm1?I7M7~dWhRllYTQ4h3jLWg%$^C+X&BpfPg@2=agMwjE69kb*XdbCC`;|b>#b3SKeI)o0MDxhHcN2Ym_}58iUi*)U>3ao0F53s|Rq}I|DCAEEQ2f zR&Q@_Selv!$=x6AP2h*a89I3mf)3(Di;Lxc8>(%)1`%W1SX4JSeptrFOl^y47W+)b-lKXeVvanz_eHHz{g&m|V{v2en@Y>B#!E}}m7}0A z(b3TbQM;ZWpDC-|S68jpR+-Yb@3{BE2n&{Tej?`GHwJ+U{iK8n_6`mevwc+PczC^S zeR^lH8F*W(M~K zB6P(AW_dnXx*zf`?^qNTSp@|JH#gc%xrvIqLz=v%C#TD;MRZ0MA$lW>k|xV&%PUYu z=GCpUET1ZYo5@;m#dnYQ_a!8M+z4kpNJtp%$f(?iXJ9RHX_^`vBX9Z$Qt^8vFnQKd zWsaF>zN`@>CdS>LdG_F?8XZ@g2G}w?3his~U$OJzV!b&HB5qkSaB!3ZfaAqNOyn2- z`q|uVo$v0fXLPf3ksWw(|CRvuvF(ov8R=zOmk7T&5@{0N0qz&M;)rTLfE=3c@=<6N zg;Zp2eSWG*O-)(EK~bxt>S_=;7g2cpx!7KbKVh&(rTM^{`4lpg;c`td_tERql$Dho zP4>H4@=knNJpD*XFE79R!36|_KNN(O)p2thfB~dBXi5=&X8RYHYX`nIWADdh#u%UH zykcmM?&v6Dp53|L4@RY1Rk)L6ODi}nkkuLM`7=*yiQUF`6g_osd^ zLK?cbZO5P2{j^-XN4f-KqMJ(x;;<$e-c?psR^b{;HX)RCPJVAhCvcryb(7g4i9I)BgTigTR9>4I&Y-G!txcE4hVw4-2R?`AmuH_} z`e(F1baoA1Vzmx5N-f8)@RBd|yCMQ=X+cd*8AyO-;2v7q+}vn0y0!qP z1jle@U0p^o_U~A+P;Ow+nV=$O&?D|Mu0&F2$#mm~JMx<*5tBzCy`{IHS< z?!eWu5N+r)8p=60NHVn2OVB#9v^F$MH0{gJA))M}qRNa7j;`b$k?Tmf#;L(1#g$;z zOnF)me68cag-eOQk!JfxQfOpkFnT)p@F+6wF@ujvE-jAF(~EV*b2QBLlq`cXLtl($ z*xafAj9bYIot>S%iH--5NpQ%?3|4y^?hD8TKMQAA<_+45X(Ejg53-AA_3cpkQcorz>4UT7SE28x1e;yyk`>-L%DmdWVqOzIe^LDEtm znW}kVzdx3t8MY*V9D5FFAnp5NEC*o`Y4gF)OC1vIsp(4Tv<9$;hwAqEZUYy*LQPvs znYeYP(h(98($c~qQpN2bAE!u2nr>wKHwhRQmxn{MA}7T2^PWzowdhR>WAZE_?VVm< z*AN;?#XRq$UUW7B%Rw{8^_XUTTShz||5%9IS(cY0Sf*idwdZ;N{^;!HhT~&j0^g6U zf2l;gNC-sg3h1OT{YAv8I_z+Kmo`4^5_dSX-#A$5e5Yz?wuhL`LPEUQ0H*b+b_-g=8GOay8;l zC+4dtDk>_g!YLTQhv?^J=8^aS+akSSfAWdQ0ab^IFu+rXnHJC>sujH>g~jTT z1ZXwQKAJQrnhdJ@7Wjv}F~M)~KvP4*&`Z>II+=D4CnEC zZgX`UWRj$vog>I(w*`=!I8i+C2?o{-O_!j4gT&r1I@&yy6lp;71rBD*&AFSjTC=)G zMEqXHNSPNxp)x*(BszJ{hc<7jPooK!a83x4gAz8|x%t)p(WTF!`RG98)nfkQ!qUU8 zuJF_lTvgJuvsWg+k$DRzn$zX4ii1g@qj*AIE6!dMV43=2`Vv{4|x>nRUL*3381N9~E2Z z4Z;H4BdohET3QbC+1y&9Uxq=?d4!qj|4E4NlaU#rSc&Cjw-*zqqS*i5-mNq1l~nB| z{90wAuQxes6G+=c+}nwFZ}FvG3w9dKySDk9e=ijT&s4WA2V}BM6n6sXXo*u!PHr68 zu*EUdkTt7E-vh_``1lUy#%X-Q49!WwHL=bBqO;4k<3POE7ubhdj!|{C?dL%C}0Ihif(2u z9IodDfr&of;ju(8Dos~=H7}6un1OfACs$_cbh%7D7z%sU(S9SHYXz;W7Ms_ii#5kJ zyT}FC&1RI6G&RAwg_m-fom~W`;Oy!QB_SirtPedq8=o-X{mjJsA=caW_A1nFo6W#X z#5^Xo#=$v3fE7nHD=jH0=_#@(JNENSg)Q6G*2!@@B{?ewIzJoX9x5z?^dIX}QRl^( zMkz|X<1xRKI(l=ezgH*KLVDI%;p0mXs0jB5hsMW;yx?A5Is&{nKRe5A8+BLMH}l>= z6mv0!g^caCk`nN}-Z&Tp5)=>slxP2-rWK+TZ)_Ej+8T#DVe+^FgM))>zawgY!B&8$ zB_~j59*pJSEEy$adAxku#U%0G{P?(wj)_54Q9jZa;1{qya^IuzYyAU?^Zfi&US^pi zo}HcD>+A+xr5jb!fvu?LcUxo$#u{JT{>!HrzBc=q^!?Um2kA7cgFyevw+0&#l#DwNfAcPAGd#?#Ix7!`4AgYp<3fnL$J_Ri~X9kc%ls+7*S;7nY;E6BAchLu-~ z^!SeXU*4ao?F*tfIy$xjQnnlMl||nOMtY^evY0?{xlB*bQ=BFYjlb}#ivYnL`jp|t z%#9Q5{ks-ugu*?(Q-hQPP0$^)Bd)v!617xCp=QhqH)110LO=;~`VP;}BQlc$$KFlm zdKVEG!&iOm{NN2G`>euj^!58kXKi0-#K=1QN?F1k+K#W#+9N}2Z-iwhf}U%(TJBGW zp9-PPx@vg#7JVvx0{}reWJO^E&50RPkmeE)K+T@8Y}t;cKLLFDe%t z>{jUDw%BdEP@2ZU`@mlnp~AtgpzU3qE4DbVBr0-pf?q}H&x^)t zpPlK!E|r!;pq0P&8_PTK>oWx>`2{F1YY1by$b&q=sIL4TLAvaR)~7DFild_+IcP8% z!Q-Ht_a1Mp%!i*5ySUm5pJ8E~1!b@;9@hC>hUwx{5(KO|xLbh3BuFB!HW|9KTCCh@ z=39PfYUa=*nT0Gi!{#TmMi@eqnhlj-MBXoBB1;|dP`#@h==nJy_Ns3G>3vl2b9;Y6 z;8RsqtF^V?kbK4TifMo2yQj#tbE}&dZ5~e0Q=8o8kBa+A2_R&oyTOF?AFjsR#G9MT z8X#CS1ZABV=u^b~S}THL@G~_vHB&{^)z#&dxeC&^Td@xt@+t?7^!4LWWu>I${2)65 zB7&HBUH-h;aW(m-uwbF8T(EQD0#R9e*wlzw`x0e{$j1|H{?hHdkBt25dX;?*^$imu zjephIIkB9|jW#sGeDOz+M#z8%Vs>A4m;{;uKShJ6{W?XcDlNs0N{!9nrMhvlGdSvU z3tu~GDPk&S@U8txDetT!lOVstY+B6C&WJ5gHN&W?%}!1Vq@+w^gQT+3(fYvt_NzvY zvJ2f0Ef6Lr0L>{^mdVDR2C0VxH@`k`X3CCPSxqHMMc28@pr^efkQ$C;vj#J@hhF;Qh0r0MEETj zAASOEtxPAXoY(+7mR6)!IVt+tg_J~uFjzcY1Hcd^*sZ0dIV}HP7{JeaFYT4Z19{QM zH~$R4Hw+ICN5WiAj7jCaRL324RzD>!FE6*m#FQ{YeFfR}{P5fo`m{8}hH+Ayk8nDc zpwh-gXL4R_vc(i9qb!{aX4IIvZY=}1aaQgC3x7U&t_tEiAd z^rvOiaYkCmhKGid(e0}%s)#HsE;1gv*4XhAP^vTBB32u&D^ma>DzrQ5f>XzQigj6j zKmM&*%+Oiu3sCOG(^ooiA88K`j&EhPNNMI$|0h_8Xv#J=p2^J27#9~0)IZ;78425O z`T2QbEFd6I6VXbg|C28`xdfZ3j}*L01kgeLX->jI8c41tp`)WP63Uv~WscFAWfP_mIF|yZL_(C}Y~43`0hCjQN$mr-?baTM%w4=371=y~Ozp0WM2@Gcd!=8(6|(CBJv zLk5_e61@w5|8{-pC6!Zeb$cWBxgL7Cv9V$IHq$^TXvZ}Z0US6(4be1A zW@b7%I+CENuHFm_gV5a8mbSbke1<+HM2hL@Mc3vSmBc;i@ta1u8G~I))pO5}y;!g4 z^;fpWJi8{WPaja&`=`-IS%S%lg+Q(w-6x1U5+x$~>*YG@;YWDBcJ=i6F$FbhdL7$; z$zBp5LDY&P>H6B7Bswwh7lo3FQczOrJ=V2UPgv)W|1_C$fSBaVf*zcXoonYBFeg1T z>+~nQoztr4Li@^F;f9_DMKdek#GD8NPzJG*s1oKQuewxJR0K7e;z5A5yTgVut1UfT z6U3i3=>>s$=~{w*cYdhmUfcZMZn)c4pcdu2P5Jz>HQUy4Q*L#bRaDN^%}8i7gMko; z-6J7y&Y_v>mor1_w8t_u-rL4RDl?LK?>KL&X?wP|7F-o}Vq*0-={e5r)PWi3KE!s* zJ>CuiI3hN-m#u$w0}NL8LwM1ygKOo`O{#xfQtv>#=C9JdzY-Mt9~-(C}o#rh;;qT%KoyyX~J&gh?EJ zeh&%)V(aDy{8inEI|Baxd2m)c#|jmM-V1QvyISQPiqa@n3cb-?H&gAB8R!0;36hFU zb53#kuKNcP3&=C-YeSxF1q@P|J?~rZ`uqFscBcmz4Xy z8dI&{b$33Knbq8od(bVRoDFk@<2E+or?WYcKg0qwu8r+1mYR#U#R5ftZjEY>j^aX! zT3LF-TKnP@%H%(kDM^_gsT$*HX(=KCbGRkhgvJYG{qx{AfhI>?eO(DIZc1PAo3N@3 zLiMJm;-cbO^2CKEicwuoiyPtFi3#X4h>^OROG{gKGb(q$@Ul6=WNH!W zu^eqv9(JHq$lcS?$O&Gq+LD}w6NqJGhcUNrp(LzrHwzA=_`horcz&sJygt#&GoJbqJ zh4?>aHc=5ZS2jR}au4cOc5R&+U!25k7(Sd~;g@abVc!6rw^KJ4Xh1IpYnn=db$6e> zSQ*$gD3R; zbQ~j~6eG!Vz6E%K|Gh;55cI^aPAa+MAq^FUN|y%4Bzc>OYCp5EnyP_ek@jc~ zL;w)s^!!MOt850>IwaB1(2%K$!{@^T1SODXLu(rL!Bg-tsey4hrbu^qB-)Ni>L9-RRVsjKp6T4cL9A zC)YIEk@{-7Ts8r)v{gX(j%RbATMa+$K*IJoiJM*Ua>HMw&$iu%6%_i2-!9vW1v=wP zaC4kpQ2eSePvNZ5UeM;|kxH!LJ*&$H2mZ%1HAA zk15(?0AE{O3Jhmmp9tGV9d-kF3-Y8HyZ;{+5kjNNuljCyLgTv0yy&* zLihdkeP+HhZt3Lhumb%?Y$_%JR^ObCYilh}gfgXuEhI{Ib`4_F0A3^WIy*mSh>H6C zgVX1S5F;VQ!VhIz`Jfss&7;-m?u@#T6;fit1rp(VukhRh{sL+4^ZiY@5dsecO!{x} zmX?-bNfW7Xcg`pV|9EzG$+2Scg%X(vX{UCJdr{%Wo+XM@<4$i($B*`iJ; z_AV-K$AE?p`%R&h({}*h$O4^A;hQm3+kpW2puDgHO!Xqu1RCb&rzGilfd;r;L3&!o#*?$FBg4j)XM{ zj{qEl01m1+&YJ43jUb$J3I}^3rrQS#id#zFf7tVT%`gNo@`o%G2n)#!f=h&dDwy%0 zk!5t#ncb8ibF(Nv|Bkq+g0nFcGH1_kEArj$)tw;4&u7LR5a9Fn=qP7wCB5*UW|yE# z3RTkjXOaPr+uc7I3I$wVgl>LNYzb61eDHXUiyc66pI) zxx;M^WgY|_y{(2TwN*D%H|nx;H5Ff-o&r~AdM{s6M<@uBApO}I_yP^ZJbx$ljPu%I zZ{)n|-~VgE>O+)u@uDMJXy{jdqUufT#}h2n2+Om}OS|G8`B|xa(!x_~nVVojrh>5E z#Kc4*$(D+d=VJF#+4Bd`3wUzjhTl~;_#gN@_B78-jXqHXW!Ff5KS}tdBS~W!!5`rN zb}#%1L+mU0XWt-#001EQ=U#BKuyL`ru(hK5e|>I-)^+P<0eRG*Rqx9P7uBf10>H-35T4qgg4bb7l_4RWabHoESWlAv# zn1BF`Q${cG(5v`6yW(SyNYQ?DTRZhhjfMdgXrY-=wNK6jRdI2Wu|}5I(s@;Lv8v z=F;5g7jfilXQa_=N%Y|k?_{d1Jc*sC4N(RS4Qy+?2_o|-IL;jjS7u08k1}If^c{R1 z0`6LFU)A$4>rFE2CIaWYBlg8*`ZznV%6ZIk8d>^KKg?8jzp^fga^@gOOY>MB3Rku_ zS0dqY_SpAIm)*htJG&)3>1aiv002~I0RYhdSJ;Ne#wMl)F4oTf!x?z3X=As^j`Y*p zCpaG_a{IDTJc4WQmgT-b?0~I}gPnj4+@(%!Zei^tl)$OznE3t7CL|e&o8+i%9R;-N zZU4kb6888o4ej#qSBSQd#e67*J7%|+BbGS6VzOO3cT}ar{d?}MY{%`7nP7<<@N8=4 zF|c~QWOC`N4oVJ5TxoEP*qc3)P7{voAtV)l91FNcBNBSJSK!2S@!Q*x`2le*`A~#o zF=Mz_HKmHb{f9b%fC)%4=^4O+*n|}FYrC|XzN7{|>Y*dz_ut>(%ndn*c2ZL7rVQeL-Yx5c!^T#Ed^@RE;w_GZ#gpn8)yfItm^ zXva5=ZTS+dS-~Zg-hm&3rVq~;0EMeMD(u43kZ`UN^E%*LD1kh(`vq57P6L0toXCc8 zMiAHblF+u7+`;=AUJAlgegM|PJo$Vx5Jh4Xbpxd$%yrHCcWsCtvz8`M(-4MZf}S4h z_|$m*h|OtmVKV&flt}hhCvbiQHFFAh+|xbuywFrwFsVF}-&C0=y}oYO|E)RO`H3sa zlGHVf7TPRpV~e+N^}}MC7$&}%fNS855h_l63kK-+NaWDP$$(8^M@bl518`M#64I8# zXb9kppk0wxc4cm0t}&kB+0h0rMTFE^&5Ed|Oi2280sB{)2MxVF^~6kUOQY?kxfP0r zlh9sHOOe5lE!<)nR-{`@-kQ5{(2UScJX0%QY)~ac`@FHa{(mSICKpqP)6JtzOn^Vi z7>J~CY)EL!?kjOI#8?OOMuAYLnHi(;MDPOl73gWNc^L2H^=p-GQwcoBL7|3gP8kC< z%U5e6%_Pm3X0~>SqugVe4o@tG9h!;bl8R(5JtHfwiRQA0d!w)FjJ~sJ4^^9KpjPq+ zY_`_!)?~26J#@!nWRjf%2-^uNtBpZU=T5sskT)gsTMGeA{iNRfJtMm&eOB{P-hPSMVOM)Vq}m4R)FBwl$_DcXTlehpmIt;3M}MVHgUZ`d5O?tN~=LkyI7gJt>&><)^J3XGloM|2d+7C?ealjZ=oT8X7pc)<_|2I z7}pU)cPvz8tzYYPHwc&#=PT};&FjibsB2g_FEkVzJ4JX7w4e>9TJI0*ufn`k0Mmm$ ztl{$X0(DTUMN~RRI(2qW=aIAw6S}(>zNw?+)AZZC8n_0bMY1))Hhtr8;|CPn#JF8V zfv2?_9RV5daU!r%gt^EHiHOVt&`+ovVe#x?32h<(Sn*Z&rd81wJGLfI>i2}2%%rXf zW^d{LG=#z~KB5-8r9JS76Fl}y@XiF&Kaz6t0^V zMLTa%y$E;6Q4KtAvTRtR)rSWu5^46I*L~}^A$I@Xt^>|`>6)axnaOxj$WZ~C zQa3KQS;OmJEj@Q{voocNPo1l~XZwjte3#7YmzSg)I2%4e2>c zaSJT~6&VQ`jFTlSC!=SIoWnO)%=SLA`~nvDjrL$R=vPXq9J0$+j#~smmDd8>z7Tc{!sq@I-*KX@nErrd#G_dp1|1NNOb>=_QOVkrfIG63NR`T^vGc z=>YcrJ2^=ntTg7myO*pYmLfjGS$T1tNC$|?7rGQ4QBZRHi#)Up4b^|0D=jZsEv;r2 z$C^saFgbJwv-Kt5uqMD7Z8XYH0aj9LD~%Dxhqxiyt8cmLYd{U_LP+mJ0DNW(Z!O=P zwnHg0p;bE-2}#05PMrkm>ojL~b6(aNU%Dv2IbKp>LybdVt-z?eR1$`)w`~TEP8l2B z$TwM29)&;q(`pKbIka!n{s)a$Qu>Ny5ec0xUl#kK*7d+Nt6tCASWf`FmQa>}m^jvdkUz8=|zN6Awh=#;t`m%lxI8`9^?(6*zu9vIG z7`@m)+wzu=#9jsdnLB7km!VTW0{s$YnHLb{ttkKL*3zuF4a=qllwvAA`$`I@&O%2s zOZ8+#FI}+RJj!ca`2wBFtP(gJpp;Ig*UWkJ zd-1{y#nm5JTRC{WZq|=CnlP_TIK4->b=HN9NSK+46?(uzVD$ukjRW_`M1^mlAhh&~ z#$Gp_<8ebtke!7yopeTK6B)0SyTp*~0k1HV46cv)P+8-GOJ*X>RtU7$+Obvifd0Ab z3G=h~@t(RkKb_&wFu|aZ`dCDtr?i&O!XZO`72`7|g_GXPN7ySRs~}H;O)J-CHr5S> zXMj~(82F0)`yN#lKunPVQ>3L(JFHtYs|BSlMA&-XA9%B0Q?N%Sw-a2Fj^w^g{u~mW z5^%#OBZ67vjrAb)$wT_pl9RogGDqE3GU-5eawj=TIg;Y=v}z2EtnU+wH2{&0pSvKv zTEY6kr7;zAcyn5rlMNBRd~z?bAZ;I@YD?mN!>|{g_xJv-} z#39n6IDeZPog}Yb5=-81?;nk~Ux5D}J^XW} z=`5`TsHk5H7JhaduzS4_i0~oN5u)aY*Yd+X=FFT%or%J} z>1JOnR^9O!csbH{&o0dNTPj^H@YnS|68(Lh-JzR%jxK)iX?%D$-&XB}Z3C2N%w~FU zS^_3`V$J%Gr z-PdP@Z}EEAM>c~HrBvgPILZ5I<2XX2P~TSfwg|w@{#BC4V4TQ`MuXuME0!c^OVW|S z!s$ExMTmc_rB(Z{6vNEWcYIE&rpOgezLT5avqY1SkjD#>J%&AS9VJNE&bh!hVOy0U z*Y$$>D&iKX$~v)F073*ZknxsH#KMJTJWf((<`srRg7IL<(Ygx|z`9tk@sKbww#|f9 zfYI}xq~&YHd}raU>L0l01Rztfm@GjbR+J#Uh!c@&8!#A6G167$l zP6Edx7haJ`E0$L1N)ZHDs5TrT;lP0x%DN)hov(dwST$yaa{S5sI24g z6WdJ!&{=c?alrDxLK<$A-0zbpSQU6#U>E|$|2554BNW4#Xd|5t{anhlp$>tuq#MCQ z-4zxY)qyLSl|($qHO2=mrGB|A`lD!(IxgYHaP#s~2ft`EC2ZC%^jc4vah7L3z&G=W zxA4O$7dMg(ly289Cyh`vI9dYK9nU=Jwvm3<%zX+z&*_Q7KjYnS^b5dZysjH0eNuw_ z2$1P^ZBdz|oHZn-PRAt`3qK52LE<6AyMa+P@GEv(J~$bY3kqFo;2ug5UnAI3KX-rD zj74SYM<{&GfeSATSFOSse6s~w>$ z+3mRJn>qv7(EK{z6W7pCWZucr{mROW8SWPA0T)|B=@KmxjJBL@L-dvj(ynmARBl(g zd9PFMp?RM}7+24v;pNPLmnVMLQhDEuwD83li!K#^@?w1ZZK}o|c=DIMFH*Udfz+_5 zLdB5Mp;sUt(#0e>v-8(c#9DRT`o`Ut@*baOD(7qfj*DJ34ZN2GNMqS&qB#RC9U!tCzc2+;+$qC-UO-d+@yJ8)sG!eqjCW z)JLsa$NTcj_%>9QFs^#fxi_*0-?LM;8K&o<{?w~#ehUE4AO<=0h@JY7_bHH_Dv{08 zTg&hn4mJLm8;CK+;U(_QoMxD1wUzgoK)#>$J+S-pb3XHh5p-G*-3B_n?pO57nw)s; z#U2`n8R1ODn2Sn(usO`Li{r7Fv-+2!}nXP=Cl_5F=q_Zb^duxjR1*Y%Ul`e zIeVgwZT;QT!7)b|6gXiBsdWplPfUi3g6ce^+DEEP;m3Af>I(^x{lKO#2yx-v#IknT9>_7$Z)!$=+YW0Y62wbFU}LG26KZ zd3|tjokzFh^To7#GK$)qfOuRJ5UC~?Vyu-w&u!RqhujxYc3vB?&-d?@D>=V^;+s&z*PIzy{B>w zP^g6Ao;2-^DuF;gH8ep=z`kX-K_eO?Evto}JuxF%0}WoL0DBUPUpzHj znV>Z)!v`>W2idwL^@wN8u!)ETSAs-r5Nz8f$;ko*mGDm`~jw!e&tO+*oEKycyWPw z;&F*#oE>(q!5WxKv${IUjX2%xq7$)a=;7>wpmGqlcefBs}d|~Ef9`arPMDZ z*+m*)?9&iuuHH@yepPT#FPq7aGPX(E%$jpAIV(<6(5$VW*%}HQKzT)l*?bg%5vPm> z<3t-N{o+1UIuGlK!PYb@#9mxJ`2j%pE>f!W8jFrvg^=JNAR3rWU>+lY=vDex6lI*~i?|Rg z3TP3KptvCVSsoTMHh2~|Q(2685v}+(PvOlBznI5F(tAGk@LVVCkRxiHNIOB^lYFk~ zO~SQF9IDvabGO1~c}0%gQc!Alg~{q%-5Rzw8VvK;AC{mM2C(`K+%-)c2*R% zhr^=`nv*E|lnYe$J=&wCI_CopXPzl_fPbN4LZxri1B2aB&8pIP-ulQywp_2k<+wt_ zl1G0Dh!xD*UKq0dNIbaFzGEzpkTL(AY#ppw z#X(~f(tX9#j*L3}o)fX!KfFD27EQULpam~10r>6!nKlhO6*PbOYEot4h&ITcqHgV) z-`AyfR0WTr+$ACZWiQy({Eew*+U7@$)N`04X)_-ov4#f5L8Dd`gC?+*0a(X`KPg@; z?f>EHoq~H|qBz0Wwr$(CZ9BQKZQFM4jcwbuZ9DnL*l%WQwq~bl_o1u0x*xjxrR$vY z!=dx-h9Ey4XRCJvMJhmj=vVsaI1aScZ3Y48z1f_`pRQ2LFi@P2aZv1ckEpN;v63YpI|% zSnVLn58vwX`o6r2%iVz#^{-y?98iIQR%0Z;o4C~LdBANl=w=o7Sdor>Z(Ua^4x1;G zzlBta#M-&&U=T}Y!!VMvOb&pR1hP-L(Nmt?Q5r%*rDZGD*;Usl)geG9-DV0sS0)IQ zbrF~}nw;rsS$EJ)Ma5i`PC{(5`bs>O4f?0`V%fTcQM@^w{MR2c2Crco!)_Id6(W8I z-sId3yOlXkv(QlcRB9N6dvFX0%{-tGUf6+Ld=r$WM!x7mSh%QKKbj>bvsnt)v&QPS zKOmLiFn2fE78P`jH%A7gg!+48kS|ud=Fc6l@hz9)-E8J#sNEbl6vD^%r8^21-*F$Q$ zfzpRBgO}!WfwOCzP$nAemz{VcjFt>Ezhh=TAkJl43;bSodMh6S>sQ0luOT-?J$4}P zNChTDV2q8c8i(%8zxkkuX48x*MVNU1QF`fEV1H6D*Q^RR-D?07MHRYnT4dywJ>DGF zIvIRwb=xu?-0_p#FlhE2VsXs!eX|Wi^nM6^z2VIC@Y<57m4-X?HE#lLUw%w=n97ch z8x>jAU{7d8orD>jdGdSVQVWhPg^?jo9qD|#!C4w=s(5{KAZ~QY+iBWH7g5J32Ptym z3@oN{U-~zWTr6xOds-u&xLn`BafL=n{0B@iTM(Vd@_3ew(|8V)(UT$BJCgM>sCjzQ z**DJ3X+z#le@9&O9AcF2km&>679K}8m~(1LS~_>1o-DWFD@n31^eD526&Q!rmCh2x z=#dUi-6eM_HGZlA_{QPEDoe3ZD4bxpT4wvm=ycl-Jf;G{EZ69+R4GgqojnhWM%Xdh zWS3oiN7+l&5G}TfsXXtM@yAY$Of?{%$kiEV2G)arJ`0mEYb`9NXR0(f-~)l5U}*k{ zA#qa|KiQ*bV+be$S13g|F6;+-3kQ({Q;OnO`Sq%(Zr?F!g;)_bp{Jl)%XEFwN4p*% z1Tgqa_rnxE)dQP&c_P+yB+j_*H0EE!J>vpnU?Z?Ils6sH%F194wL&WC1qFD`J})17 zk}5$OF%z{-Ij(#K17DxwPMhdjbODDhM$lqBMpNqW%y%B*%H=4P9RyS6o=Db^GuSDy z9uTYaVz5BDI**tnk+&0LD}+@d2QzmdPDc15niiMeb@yyw-=Z=LR2?7$LDGqx^gGhc zd%Cw#LC~lG)m7dR9N@3F)C0|k6>3V6PC8-p00SWfV3|0W1O%S(PX7hpYg`x7;ll1; z5HBt{mZ~uJkLroQuzV~WRqMFS*$g&iJm=c3#Tn-=iHXdf!!Poq08nutTN!EQOZ%i! zXlg+$0-7nB!_3w^u$gGzMI6aAd8bKqO+@`Ce`fD?jfIr(X09>b zc8JXNABDFQzZsLYC5RMFO4zfWJRjBQAM4BCaF69Kl`x!Elp`uEdQS*J$y;uuw-;dD z%?jHqgr88j29LucdwErNt7Pzo8ol7Eu@Fxn*6pk_0hnDH#^r-WrNO>a46SXz^{vgc zk$D>}KG=Gtp4#z&klqP46tv{Cx*ON>UkeYr_##B({)N9g;_-<2;_-}f5{?pI9=l@j zu#pT$CbK7z*5u)v@4$5HO6^V$1K?Z(t^2RxB3r<=H1ian1Jqiks3P#P6(j}1W7#~n z#1oh!*%i2GDeba#%&<}9N|4uRveRD7!-FQ}=tcp7WhYVpDujQT|H;j7-ePF+>cFfl zSwi%JaGPL9-LNshFm*q}vJP?*ld21}*|Dz=SD7H!abhVZuIB(K?NpyaJD-i!h@d`B zwlePymD*H@uv0XD8yJ4BE{-BJ3H{H%A9QoY4}E?PA_TJ@8???}6H_S)MK!VuHU9ho z**rPHT4Z3Bw~Cl%6V_K*3avRAwKSsV7AS<=Xb>%+<;T~`X5mcN<3G$D>h{JEd{OV0 ze2fbBH19<$al|q4&R8ko#vK(_xG@Xc_ks<_9pt^Xg)!lLZDqdYW7;IaeWNp^^ug=g zzvKkBt1v(PqVd~TE>FkvL4S+a`p0_dE=rjjDg(rSe&3a~i~T9X$UoiZu^|6e znpg3e*Fz=sY15#QN2Ku1Ox*t%3-`=y#c3P`>A}_xNo(aBN>rcUu5QQ{gIu`%09nPN z=21F5-Kx^djjm*NPWx-Vs&fS5Z*ws}47=mT*S!F-mtL*Ww>VDr(ANdpd$p z+O*&#&{%~D(~2I)B@>2y%l*PDc9_kz$d{iDs2*_=2@-i&hq6bt&XC^#1kXiyRSMQV zi575%Ua3=fQaQAJ(QScbs^duREq52FF3HMn=Z0>GTq6@Tvm$+s5lx#N3OYO+h2x6Ojc|)(xnQU+aI06N*X=c;Qx3n6fU>WykNk4 zzacs1P4NE7&=2BY(@oNqKD_;e!B33_abxyUg)vccbu7jCudi^-k z#^0sqv7rH?xj>)x)|or+M#c9vEsF5AAh*I4b*n2PfPlLgG;CE_?&a zLv_-)PujY2BTOMe5}p7;sL1}HCf_V5MVO+gY@rc!L~YTRVeamYIeDCE)Ka-^Jy4OC zF!G4oP5@tbLaA6MPRyb4dadz@SZm;H=i1i~g>sf}1{-g^akW~`Kx(3DF#aH%@zjvd zn==TTY-w7XALEtwAh)e4$F_GRiZTljb6y7Yy$`Ig`)m` zN@CtkB}a*NvwMB#TKZV?7(syb|Hw;$hPimy7KmGViO6* zp12lIY;-X1qZAWy0JI4UyoQ5~Ct23zVSd{)!VX52W_p2IR1##cp5PBibv1WTqgNud z#nyh$cwSiy&t<@N2$;`md6<0*4ztY-jH zYN5;tfqX3FWfFAT#^6MAFYP5=;zkI6%{(=f2)Jo!jYY&1%P$IOJRIkzbV<*J(WT*B z<_ui{*Jp3NLhGgL^<1c79weedH)OE;AU~0!o`Yg8s^kXf+@Zx*&3abbgZj3&CqAlb z?N3HfUyDoi40qQzk9uS@%8E;Q-S1xZj*MGE$RxXXEusD&fkxwLxxneKw5eEC%+B7X z?F+VJg-aVu2Yyv`G!VPC8dvqRL0?skI{|{Y z<-FFvyq%jx>IswcdtHrmtHkMijIGZi6`Uju$P&75<6yQ!0TSNJ8S~8Ef~XD*$$o)z zRF@Usn0R`oh;(?j+D(-*BW{^_Vd~7IE*5IW;PtRjOMm6QpsOwy=Y)#4%IEs43^23B z9FeHfDDRH7l^kwVmVlyp>Cy!Udq!XT^W*T`%|O4E z)W7fF-vW73@hgM{ucwZkoIh=y%eDdz>n-R~@wL4KkGn{2rQALb3`!J#;r;=AypM&2 z{g!whXL+xU;Q9;%3{{EbF}k`J8(n0?v)RIq_E8>V!2`OTv^vp*ao|95xGJUxD>zpN zdBh0WJx}#Sm9CvyC>=i9jAl4C1jZVO-EDz#JEYl4G?4~Ux|u*V2;~cNtNf-Z%KeSP zJ$gWPMgC5^qo}e#_i=;#7IZdL@)8cwp^5``;6M4wC|1IpZV(kf@djDVMM=gae7_Ze7AubidOoJ=rBX%t ztk_zGKSCIc6qYr~v51HK+Xa$Rjl7o0q0=)Pmf`N<6gXc0tezGL@1LWVpZM{D1=-WQ zh;0eGNry}{p4G2qve7M>gbBJj@uB%hyY03~BUagMLAN|qU#WLKibkS=Hd2rS!vQ=^omsm)zQac#Q_y9+_TdCN9AEOo~KLP z5D`+a4nPk_HaL=2H$V}!YC$uy&aATopf0w;>Z{p1<+bt!J00F)CoFkRA6ghoh|;d? z!>>4x)ti7p2`=MLp$BvbnMU0l8q z*>a5J$G}@CRI&OZP5v%p@S*e8k|QeK%E^8BZfJX|gQ;#2UTP{OAXyRL>HYlbx>oU~ z4BFxdK104K4EZ(4+*b7Z8W!&<3Un<7!Iukn@Ko-(_Ro;}c>?z*(X8$SI+iC;1vacP zmKo#T-!yV|T{PCnu_ugJ_6wnb^bj53~;awA8bWS@pNMdkz zpB%!>Ur;Q05Ld01=g>hz})9{XEywp<=4Gv@%&kj&(wN z!gbIXRn5_h0959AKWrB{JoG%mN!tTgZhit--o|YAP5BWV5x+0&b|v1A#`d<8pz@OC z=acq-AyJ<6;FYk+jzWFX-_$|7mG&>}&L0g|2a=$f$2_x#@sgiig)KgZ&_1pkqjAp1 za_deCd{CB|OOLo;=>qGPZ>c2G!5@JqsSc&9y@W7d4~DAHF1_*nqxJLWPeVczNFJ^l?;>l5nX7&LeFH; zz|f;;r?hJqK9|2cu>BhI|@~$E^1XINxEDa4vU^gcv$JfefJO&Jk z0z{_-E@P~6fk_zr9{sC3-N@?^Y(8m+pw;O^bIv97sksgcLtqA{Zhb;A1e^r0f=f;~Xe5XreqICi}aXk}ad=Je^D2<&@rj5>B z5CkZbvV&!ZZkAX7n8FFQbw$-A_u z-F?4B{Cj7ySfRUFn$$~Ysk#-$05m`tXppQzR6F~N&o0p12k+gbvta-RSROz>xqNGp$i{5 zgRVX^m}lJWCUTdk$CTKfq_FYv?QciC(W`iI%$dmoux5@I@E9MGwz6NNMwz|hb04F8 zmkd;GG!v{2QtZQf1*#KHhIsl$C1C5{YnJxzK|BXjg2BUV&3hsApJ$9w*9i#SaCv{3 zCBkUH`^|xowK8OCV_n#Ld^Ib4&aAeITW3{~j%=&^0-z$i)O!EqR-YB4tx&r2>|14a z$RVqgkNFQ!Jn!~a|Ezs}Qe*Ux?k!43gavs28wFe8d>i`xKP)B<1BUj!{-aeC{Woy_ zcY4MD0}%c%Dsxjq-S~_$l`K8Y?DSldI?FPvl8V%f?5yI%v}~I?4ZZYIi&A6TQKQrB zoa~ewq5}QHwCq&dk&2Q~Bo!DLM%o+sY3U}-1*YX``l;Ee`4#1m8T@k~1{F0IMTS{A zuzD(5S}Dzj@N+r_c{-3?%R&S$c(WAY48{M(2l*d}CN}DPa}fd%P~(3#fz1E=g>CX*&OLHUA$I1{e4L90a%Q@y3wD??8|7DXwy` z*0BNaM3K&k^3LMG9gYNn7@8=i(P~mMjezI(pX@CCT6!|azgS6yI~V!+w>)0}&6VnW zzo((CtAnAR+n>vqQ`;lTHtZKpMhC_^dxHYIpO+iM(bo6V_oh$8x`+hL3`B=n4q^rF zmH##@Je&HwzfXgxIn%V7N(J<81b-f0BAViGx92~Uwk-BTb3U79av~x;6bty?-yV*h znHAbR>I%TlwozLR()qp*J}yr`=jfk%UMbx@p1wA&4pvqGfQ{4B7mGgZTf$rWzP$pw z-mYHH_ir9NOzrQ{)p(D)I_<{a`o4~yZazAbzVE3R56hg-fbPEbt%B*_?-v*s-!alP z_v5LnDvzTsSUaAAPp$AR4@|~70{`YG4KD&&PJ;i8awEE8ay~WNJRIgY92g01YyIDP z_IQ3a&(`otRl}#6W?)B$ysoA!?S?vZ1$OQ)p0fSc`+VDba9`^ToEo4Wj^CRo>k0(B zw);8*e&oEr)FJhpf*~FrqTFyl9R*q)-w524*BAu^H~gyjb*9z$$KWf6%G01o=-u;Jq|CPZFw{Me2%#K1lz55l~&nBqvbrD0TJ~v!}kUc;X z#gN0t;2Yrkd7QarG{_*62j7e^7s0UaET?ZgvzM@@WAH^*cS(M>1v|d8dV-0&WmO?I z2Ez&0G&n9o|7BKDT9gw&+?7Zn!X?4ELJYtw8y$b0KWn@;g9nJhvOo43;PE5dszmpHgYshZ^_1nsaCcyZwq zou!k7adnmZJ#wtEgb`yN@D zeik3qmFVppz>LjlHC=!=bVg$KQh42D^n^DZq7HeFRDLi(=_DhKOREbGC2%Utl8`yG zNF8W1UE39vVqqaQDlF;nfnz!Ja=m@glDrRhQUNyjhZM|%Ol56M8=i{MWWP$3K)xp5 zOy`;Xn`~ctJKe?}7{rXu-89LnrwP<8D;$2-L6QbXpfVVhHju=}qmhq6!2;mv8ay9tY0HAVzU z{CtI{q7P;_1#k#RMi3a>{kii67s)yeb`$hVCpuX^<~)t41J&?Ey(Dtkc;>?DsYVmL z{*qG%Qsg6cFNsu?uk0YarMi8m)hxq*kAufy|2KR%EDBd*#(*(s8fQPAW+c?PSV?cI zP%IJ&rI;&dx*W;wQBOid(J;vHisCBf+-hkVQmZUnW;BpOf>emH>Wa#nt_NQe_UT3C zIkkOvnpvxWfHEC@8GRXZkUw+3Cq$N`>sLtuWH8ZCOoMuyF>f(^3eEipFGgjEMGgGFcWJg#U1~ zE;ygeu})k`Q(;J34v}ai?~T^qq zA(w>7ia;4tP+)8R3mlYnE`Ur-ToqQgO^TKxN+KpJI@>0jQWp2Ljx@k$Se1~JSB#dk zu2=l*+WIXXhx^f_V+r}~qh`t2RBpk!&e6HmO|veZvRKYZ6^T#_L7}bY#Pr&b*FdA@ z4}o*Cd!F=vvznD<$AS@UGRy29NC#qbr^RsGpnij^qSL6C|B@mMTDFiNXB zoU|1OPE-w^C4nnz?p9YP$?fcrX;!|}9~Nt&Q{!KKUcwxb=e@b6!jpt~IN+la#jBN3 zZma1UqwV^fa$NF9-=3~N0GUs$g%O5<@_sG5kqyj# z-J&A%(bxgvD?cXciLxK8WVvMv0)F|&Q*52H-wQX=GC>^^i-w4PxhfV0QJ7hA{ElaI zk@iXHtR7?;WLe5Vc=JWYQ}7q@oeTI?p(ORg3OcG35_#=de+>+v?Losw`8PPqWxQhX zY<&tO&j&&H?+OMAB0O1sRZ>(z4ikXtc3Gw&VmTz*rbr&7yN0afvO)%*W*E99WRSxe z^I0__O(@Aw>|g$54gQ?+Xz>JBtOpbAun!ihpDP#JL#ed7iVpYtgs1kUs5_oVI?G9W80(z#9-7&vHxo;H9xG}`i%wGbF z)N>^aCiFFMTCs~=L|6p1dih@WPVg^9VKPCZ;l*;bQi-WT%Y97E`yH_s5?mHxQ|Zobis)0r_wwc<`<#x9-2V_~+-7XBPE!a5ermdBj)BDhM=aa=7HH zr!@MQSo9X781Tqki2IbHj2{+Wn(>%yQSb=SO&Rg1yj%!11dJ1*HLP4u=t>D9CFA<) zU9b-%zsEfwF}Exg4+bJYzY{t`$Tg{;k4Ln=i%AvTG?Z|^{vaBTF1~Eh+ zR(euKxXd$*q-w&QNVH&2O&{Zh>R7yzYg%Op90!CxubzFEf%y~gO@t-Eql zCjNSbMjN;#(cp^ZLM|v6*Tks}sz4yH!Gi=|$l0Mo;P9yAcBTu|mGPtOuE1hzK%NNG zO^f9$w9xP+FNIeAgO*UAc1*Jke1{!fpQf zZIe;##W8y3g#nt77^p~z+;^(({HMYeph*%qybcA0k~k)QhT%A9eO;+ z^ClyBOAzaa5h8M6YQ^6+%N?FSKmOusk|?jkXfDXp&fnaiEp%N+FP|%{U}>@pUh3+B z%BFO$L_bTMx=OCsqQt>Ns$rb$P-mkWkB;U#1BULZegM?pnEHEdWL&N9^!Q5W@^&4xL%~Re`Twe+Sw2VeM&4+zxgGlE zIZ0j#bn;bi;ro)xQmGvCWr2yzUA2=LF6piSbO^nMeOAidu{tm<9t|!p;PIkHA1P)Ii|Md6!79GpOH=6Q+o77gbO?=JJLv9d zEFk4GC3d2(hLDzUj%N{By~`?}dw8eI|K(Ki?4Rc-_oQuQL#4xQ>m}ZiNqIzr_Bz!{ zhmX)1wr@8SXZr{BU{5Yq=b8^#P_Y8^uQ*ye5d}27`4q0%M2}uPrSk_yzyQ!N-cxAq zvF3^YD5cO{{0;$)O4s);ANrOCZ>5iHgsO+{P8QltPm|@zeY!!102tBk;_A}m=@hme zxQP_$KmM4{r?TNymEHRZ`#hapR{ouAdz0a>hS;!zyx4B}aK0{B1DOiLA5s?@u9#_q+_wcv|1u}R|$)sxeV zD$d>^(cRFKw>2U+H}pEyY_cWVyTxVPdU)MvbgO76F)dx9v!1u&+(-!eu@*SAi<{_Q zT-bG5*fXpIh4(VN?-G|Td?2fM07Gt1Wf^Wi=3V&)o56<9x5Q4z zeP0zieRc}(0dFoXKi~FvhIbAx9+-%qQwJ{=Z=P;0UY`&CZy`k35*d=_A#WuHFCL z1L6M>mj9pmuDP>=s?{HJTeJU>`*{rii26J?;xaE)e~Jq`;uH83NFaaK z{{Tf|sniPvLI|mJ8Q!_DRCQSjagk;3z|e82MW&?fsHde-I;bx#`M#eS?&`Y{zP5Q} zaIRU>Zsn-A_4)g`IC*`)*a8d#KBr2nf4(kHcE;Lv%BEsI3uZMIUUt=AZ+9v`{{+0h zlzld(HTB3-rvM(De=qhN{JC|rW?fsuYmJ2Doc#Xl6LazN^Zm+b;QR4h@q7H4v(?6! z%X|txYTxGjJGF8Gm`m8PvZ-M_zPwzSYTL<~s;X*Q0n7mWS9W&xcE7p>b-z8`em>5M zI{pl9rfqk1d^?8ez7W2yabjW~$zwVEetdmzT;2u<K|~GH9}#TvbiI z=DeQash#ns9-Mx^Url}XP5FlKMJ(El;ugkzZarOfadNiZ&1&4u-Z?M^y#Le3{h|!` zg-&rwzdf`CfNt&}$lwXU2*`hKx&C_k+7Z6i-8tBEesVepu`wHTd%qvvRApd(a(dJm zIFkpQpk-u+zz1+y8bHSOHJk*lC*lZ#l$}Nn2@$y+lhXUO_k0|AuzVHx>uc{}zdv!a zv~d#FG7&jn1Xn6K03`z=g#P1|rrzKt;}v0VrOOKbXkirCA<+ z^{9%6pb0fUN$Y))Q7#I=q6P?ETgDiK0g#o1j@96hjfcKm%cOXP=8$K!OO^~uzi+^| zn8HeuP`y5+0om&jIN8+M$NzoZ*{Khtl%vSsKBHEL+h-{{s-tt~(4+LnJ9GYotqK%nj)U-P!vr?ZTRfZ zt)|C?=>gXc4nKzDVdP1$bBGlPT(CX^K};L8YpoRWTRs$cWJk8bXLDNvVsE(7c6@t@I_bPD5NLf?4?n zf}d>kzjYg8$gg(q<*p3)Wv|^^w3ho_@@d1#t9I|`+KKcHH zYEsJ7`e&Ui@6q!Oi_U*McfXR-P* zO~~igh-V^nDB$IMq8R@%BSXc*UbT2>@RKhoRJ`T%KPc5P^#qb{|N=v~mI^b3v*evl`w92XrK-0r_` zfXLeTz@mUK`^QnNcx2>pCU-#30H&`PIg+xl8j`i~Z=bYslg@2W985hs0xOemO)Y2E zRwRKBE~?ln$%ME;mRa6=lqE)nIgr%}0tl3&zWtfX5(vp_)wpPIg8X5>(qrU`e!+{t z9WcS0HWDmE$mQSAxsR87)o-;ZOs-`d0e#R|IZC4gI;N2khAJbEAImb338s8DVf4co zT~2@Av+|Q&?e-7@%MC@TSqo9Yl!2X8bgV66AOs~_+OBO$e;xNyg4pU z)urK3{fHS&O`!ko=9XNJNGTSUmSwn=EiNQ3F5$8c-%S`mZ%<5j$ z2Uc-<)bp&vn@ZWD@UVzL&QA0%)GDqgjgZSmqx?A4A3Pl0m>umDO$Lfg zI=4CX4xybjp`ESXVz}}`Qq>|KDdl8R4TJ+ArRe1yB;Cc(M~R(fw=R)y^!1Fhqe89B zs7zh`yj5`68N65n+I;vkrptA8xTMV|by9TEbaGcVmIkF9+v469Sgc@-f#q``Q8wv$ z*M<(^%hEvZw=GNJXUJo=uwojJuArb56+A4gSYe?s0=nYyOd2Fscn5u&o=u@}#~lvv zn}QXDuFw&&kcWB-M8mjtqmYxK?9oVMF*>|nVDm!_UB3vNol19Q5TO{rq5(kx)_KqAbuX%}l zo(;G>6EtuR?o*~UbJ`-HCnA&VL}nM|e>*~#iODxa(VpKFOq$CGrr?@QQi9eC6xLC~ zyJmajg2%vHF(Yws5ke3#xLa`K2=Qi08d9a;E=cQ_^5 z)^yJLM&W1N6se*TlPYYncvT(QaD+`vF!G`n>Y8S?=9pZz3$B{YupmiXY;54`^dUaW zt?P^Shj1HnAa_S_+)g@mHEw#A`J-;ljCCCyB*|LVb1mKw$RYak+&Twbru8P0f6EnA z_MNfd*^Q)mwzX5R0fFKcdW>joJ41;$#izoZDWO`~$WE92c+q-9X^?ag;ge&hC2ddSNS1gHJ*rZUC{$3_s(5R~aL<8$qjQ{vvInM%+F!vudD00f!qA@_Wa)5S-i z&fN~YB4*mVsU+pm7h0=`+_0n#9LE*yZ#47+(FR6UCFKAqz`@ADHnC}LnNx6Pwat)4 zC3%cawM7j;;sqO#FDOI-Z&*GmXe%k@y$csh087WPVLi$BPv)|f5tGWtWICQUVs51N z7!ECWXh~XT%R&o_#=ZU8l>a|)hhmO2=VeSnV5`{Dk5Oh{`wmNvf^z8x@)j1q{nSAd zk_ojS1wHE&T5C6rW;xP`gBiCKDe9@TdsqbO_ztCo*pm0C6>0b-b@`&dG!P|G$}N?< zaj{n3^d}SwXhUX%V!n(;`I+jp*f^v1SpU|;eB>w~c#{HHJm7*U0m&_lM%~|?dwECC>lHd33*YKE$hn8c@aeH20eqE znxr_U#=NCa=z?6SS{RRp)6{0(LSnNZlV3M7bCWNpvU!VFkQ9c=fC0AHu<2A2;=P3~ zX@#NRFtq`fm-Pxu6cZiONEQSV#uH+45k;;2ODnpim**vc0I(gb9J^`%z{vaH4*qrCba z#cHA{nw7k~s)lxr+d{RSh(w}g%1ZKLD-JrZV+7PTvutbjF_Nv-O-iQ#cUG)rUJ#_( z;;**CJ5f@?#Ak%j;8+}1gg6K~(4Q{j3_HBYr&SVuLDi;)?j-dYx{gvi-fopbmzIT6 zVkn_qJsGQP8;B0krDbgZ#|El*-X`d;isix+%Z)#pi(sk{!CW?!xnw+j!F2lnv3!MK+IuR`DJu|=n}6^$Hak%z2osQg z3IFvI+3GfGIrNmAKyqgJmh%COI~)t08xn4L!iCEt`!g)iMG2^;g6SVPZ<8TSCW%^~ zEkdh_+=Q~Tiu?)N<`L5mxd}Ar&%ZAGpRs}qXvjW~YqDK*d?|0bF-}k6BAg$^hK0{P zBjY=s<4+~&McI4gIj1F&lQd|Q;^I5DRGTPhwjyb(Z?#9D=mqkQdj)W1kB;crlEf$m zb?kX~Ed2~q{yb^#O|r~_H~u&$VZZE;9E0FM!Nd$Ya4$WrcBA*~iF6on`EreZ++!CLjyu zaK_QhPWB?B7>%dW?7GaU*pwK|+GmP`P_>V1zOR(Pb;D?Y^gp13Ol*&!9L{9vQ zW|Qm1rf|-@ZZ?+0VtSMRwMb_iIT@jYQ@i+Gn=}kRzY@Cl*6F-PN{Jg!s;z)k2Ho`( zD<8)1==DDa?fum<^?h$NxWH-h_iWPT2>3B^@7~CwB#e?9Pgt1I2I9|ZjVc*ZJkIbf z6K=9RwI$v$kAKt`aoxOaEYNm;AR9^q(RK?x3&&A%w`t0LSJ|Dfl%Y}xog%tb(XzlO zteN3i$uLRoYFhE^&)$g+#Z;(>A;a+4E%*$oW%C8sC_R6^00)!_3cawq0DAvvi1FmJ z9(Dmyq3+(SiKg0PS)AP5o(E(T(c<$v$>*2)1FuVB2N$ZH1F0wO_2d%WnK|^iaw+KC z1;jUU5f>>3L|phO9uex0>F{FyA5I01jy22Tc35e|bGjVLj+4Mt-d-r9Pu|}p%DxlA zJFn+2|F1L4%*BuPb3x&u-(R;Tudcq`z5Km9#?G9p+oco0$V^$+?OuJFi@oV#xF8zz zp5$u}^NxD}d{SNK@0X*`lmFiL*!y1Hn?t5sK$maZo-Nbie`SKYpL@n%*#EakxkSbl zK(7G=1RV?nMF0N>>Dyb{{!bX++1%Ldf5G|J-D{0kI_~6ew4AjDl^~O$9+z_J{fYOx zNAUTfqoJq05uC@zJZIl5Hn1?H5a3JA;SUzAB1~Fzc=OSfN$*IFWwKy z%E}wzYzQv3tQ}uo;A*yS|=EkEhLk>f;17 zg%rWEcn`P7g1dqMNq8)7QOzxTBA=J;N=IZ&3t^IqiqtTEnMrJN{pHw}7`#@cyo?4W>e%WY=-4)`oH zJoElE6{7i(Eco|(R^9)jDg0)B)rUAl zI1%sz`XKqpnFr=GJ~ul@?RZ~+4tlva0>p(4id^>FT136?eeHnj_!uztyS(@Ps|cto z=wtZU>pT;r4rmA%{Sp58xk;n&KVf_*$nB$gxXX=D2^eNZVoU|n1%afFB?%C7`XJ0D zjxw|i)co~c3gCKp_4#Szi%0oYR1w%~yAk9+x)4+Wn`r!{^6baNlK2}Cb&z1H1vB)E zG5MOvzOrYWKRn=FR-#jNQr_+cLhRgh^ZlNa7mycA;skWw=X`=`_B&-$aVhv~V4?fM z*as0>*6=R)Xj?;dSg=Rz&_VfEdL{x?uoSbKKp6Dpwm_5~qaDoloh8rs@hleUNd^sf zKQ%f~wC?zr#;*Zv-JxCb*HI(`tEQ`Z(V<}U4VbtZ`?K7rzSUSsW{HjR4nkOwsvD_t zw+srSBz3%sD|f)zhxYe42Gf_;!>G>QDq1KJS9jyC9~(VPmCZB^UG5qG<(+1zv++-A zY$C6zB%6pVNA*jNfRc69A&RLi6g+LSJ`rKtpY~#W^^5N3KL6jkfR>P)zOC>cwsTzm(Am$*Jhzaxt( z@6E=z4L_URcmEPjkoG9XXLPplu6&OrcT^!Qt6~wxGj$it*h7{h!v<|J4Ts||dpflgGZ z28uu1D1Q@s5#LpSWmGEdrI)F=AS@{T=Ln(~6U{QCokl9}RsOh57LNI%XGrUSoV?>3 zU78Z>nwFOt(Oz)1#6GHEdQ5h>;VlioXZcTDc_1s(*(O;=CHBYl?yLgB2!C72>9~S1 zS$+mHPqH8g?I>Jd-Ym?ICMVMO>*4!){fe$z?OGvLR2dnXABDtRYuI2s?-*xtCZ~mX zf9+t`m)3Jg=w2R$ri$JJLk-8Op8F;X#&nBqb>~;Z?DAYwk(=iD7|9m>B^T z=Bqc-;`Gjp$!C^VTvw7s2;QrH#t)0w-lX^>vHEBc(_6q8SrAYdy1c;psi2lPz$(6a z&h^M{AmJ4jDv!(dNIuPhezaf?)?W3N&!E6-B#8CuSFv-Q0!<}~a7IJCPrpn2W@*~& ztB*ebBP-utA=$v60Vm;68@+^hAGcpQ?xcSRY^`%l(P^#{gPHQ<$^e(0Yv=zLvd6_i zgomreKHh&$kCIz>w*tA^xibX^sf1;RRz_Ldp$g*3Jtp8hLuqV_DQY` zsAa!$C;tF_U`uZhd>?7C`*u7-iPp8BC0v`M8JO6!UP@)1VQIaFU zQHeZJ4!XG_w6=E>@j|4}8e;jAHNDn)A+q3$RlUzK>lkyE;yeabPKkBbjO#xK;97Lj zDA3a{qx&{=AfS*A4$Ak6yMot}mHln#ZQRNlv-`<}9c`B%^ZYR*3WT+vSpLt1zUrr& z!n#w+S)c-8>p*FLK1Gdw!oIe(J8F%frGPiRD+u%&+;=@8;Qoa%8Dsm+uu@=0aDq-;n$XH6lEyT)l00`d zEmv%09$v?Z9q~M##{EW5!;Wg2skm8afewV-H1Ml9t^$-DsQ2bv?%@?_n)00YfZO9# zGaWp&>*b*IFE#UjJh+fEWKE6QT&C=1d$YOljPrXmo7%T5L7TQrUg3b({7yWl(cf3+qu&I;y&=bM-`c6^1R=>- zq2Z8-$y3J~S;1Sx_)v~F*N&aO%sRPsYy?(Yt6;O7PTN8Ms-xUa$GX z!f39cBX(+C>IGjr;dT>Y9uW%0=#+GhS8qWjyqR?I%7ZoMG05wgK|A}~*7zn$4UK8C95twY>0*V*+bdBN5)et`XAeKF`O`zxp-+fIyXvzMo z8UFtTOF*>0bIluva(umpo8W378FM+YeFyo9;weK9`>J0{dJQPF#}WOgM1RH0&yRNa zi6zQ!mBVQPLcX%99E-#{>KLK4^--#NVg{1)tc3h@Ep0(rLfUYN;60DYa~2;6%njX1 z>)fB*s`5w^h7<1N#?Aa84Yvrm96KhMJ4gCy$Q-4W4cujSk{7F`DsAfNvyUg~^alC) z`s)~+&Xts(VFC1H*~YA#KJ9hus_`>b+G77saz68tIG)F9bq-G%6``tKKR*OEL$+@Q z^yU*;pSyC~Z#7#4c(fJy#ppY(BGee_jbQOW7gs($p6iq`G(*Vs)>8ZRlb;-?Fc@1F zJl!M=zp)j8!#TH{66`tIcjzJMQWkxrYbe(9ZMb1oEjYP(urD}SyE%FqN@`LkW^*d> zFi(l$dD7siB{8}wiV>!3P(z2H$WjiAJXEW11@=XqH67I)Xo)trU46{}oiIy)X9ok6 za2D}6Iz^gjhNm9~_8R(;j|Nk?#t(cxBKD|mr4sr{65+iNFW?u}DfOq_fFi)(9}Ou+ zP&2Vq@X8Sx!p=uTXFAyNquPaY-z^xLbgu3u6;r-B#!_ZKJ>qLXfPaSL1-ry^c|U1E zM$E_@%!V|&%ujyshfN)wkZR6OwVVwz-(;pFk1*P_SAOw?#f1oQS^aRg(N2&#nh~Ob zkM-pOen-56P_%NcDPwWHP#;B=3#b%Vww$+?kP7{AJyvZz?RIwx>{gQ#5faRKXAj#< z$ZcsDz9Pk8hRCngO))LjK35hF2Ly>p5hC24Cxjy(s!hYhZx)*KiAQYaq{AA8#0eG$ zQ(Vcfix4$Scq%pjrW*btsIGS#E#?sBL0)mT`_C3N_nVcY zd6E?4O?MmkW>v;k&|!?+-gjZ$@hYJ{Cq}s=9NA*wP6YOpYxQgKQ<`u)DQ5_t*#LqV zN16hUfuCS(fJ{*;n0s7J=4&807~l!cJYl17jfDHYrxHUeOk@mLTu=dC$14~|<9)9= zrSeQWSH4FO);F*66IG>qjUh23vB%^s-?b@Y^5A7~A)oaTPX2sGGd}Km3?e8@6uwB2 zLYIj;D*Rw;%$}2$-r(M)uM_W7u||Et4t9L(RFMe1C6dbd z#Mpg3t@|8AwCNGk-;D&hZ>8%^gA-RTT>{yFgX0ZvJ}20npG)%TLan;uK2nE_6^SPY z@o4Jx&55~FtBf6Y*>FA~^#fL)?t7~IB*Ok`AzjTesEX#f<8xNAF^nSVbF7q8}?Oj4e{a!Iho7AN#{g7*}ZjqPpswM|pGE|=za*0<+>+qdN`4kO~ zHk9rPa1`%Un~?o@55F-6U%6_Pc~QCfS@v2Rn$sql$_!;T2i;GiD;=gH1vc)8ro)(C z%Pl~IaySN^&0wlrtFzRMoF1leP9Yt%d36n5nUyb2L*LQdoi;yqGe34i%&XF`NW=<6 zhge1%O%MIB7Ivs&S5K@E4ytxDecY*ce`9jBQT`w~YUO7nf06x+rSMQKuPX&&*EXa+U^-okuFUQTu@4rNr@tt%RI_AM zyk)dKX7asEKYaSi1DAM+*U*!av~Gy$$K?-K6hT{StH(1Hd))fOEQhv<{avH(MN|3Z zY#m(ehspS<5^uGt({;$kZAW?gP&sp?a zPQIteDFR>PtpNd?TZf~dyj}*=I>9xOg^;hh01pIcW*^b8w`3}pi$7EvZuuScqIriC z5%$6y^5|)B`mEM36&>G!n8mTgzw}3~0y6dvB~Mx?npB!;*Z^0vDdhTG0UfxOQX9}x zG9iD}QICt$*=eT~ za|f$tt%2+q@gfLe?9k|b_e^=(KU96v2`{Ww4fY9WW2_-f2cpfQ! zeMT;0#(N)+S6ycQXhC*oj`B`Vccv+!*%+(>EDK@yEi|$ z>_;{pW*0D5%+<9&C8#7uLI?Lj$R3QWRVUoxpv`zpt6m=+qRK;wM=M6yC_a(}umy0eP?BNoIa(;4m5!KAwqkWO8ASAx0mSXS9%JkFn~OM@ z?_aB})NiFH868#SmP~2oK7<4CUC4`7yK*UVQdu6#$%bcuE#5P)msw@lEZIU#=zxw8 zbk2l@x@qS8nS^*-18K=a8)%Eq&}+oLmV?rxQBoV1+7sZ^oFoDEj`;q(v55jTY*!&a zDQ0MWZLVPi+q0hp<%b&X7a)<A4wevK@&7}sV zsu2_L88B_`Kl7!E?^~QaI~BTBgZhT*-DMRN27&*=)il`?eJ;Jul?Z|sciAU(!Yy)Z?F-mjaj_$n7K!AArHJ2xA8Zd_%i#D z=Z&Bm7@-2)lr0WZoV<{3H?&KbnJXFKN+d=yg1r zka*-xtn0RimY6o>LEzb3JUbvM?0%*KSh)tA#r`&9ATdeKjvt%pq;lp3tJ$viTTTWLYxL_RB`3V*twiezd zVg&1W4{AvzIJWi7gYVolgU1~PmOL#Jf)N7}u2i=^&lmYrd&g8nDr^mn=S5%WH4 z!T9;yYj_KH1GI0C9$YBmj)pW^l#FP~ivWOlp<6yUl7RNgx+DSl_ulL&#SeXM#Ap!e zH9G{JU|hWtYf#npQ_db1ulC5E_}4p4Ud4bA?U8Nee8|xQ(6Wje8VbcE?2OmRW|z~H zgKyF~PpWM_pW9V$g~p(@^C5fd`@76;9gDNZ>O|>jRIb`^vB6lXg>8-cc#gtx*h&(! zbUu5gi6~NjF|X+BMeYoM{mI{I#g(K!Viy0*rbNDiNec_UNTzoeOu<7mF>I8*C$`8Z zyBi&6uZkD1KWY!QyZw9s z$1#rG6NwY6`1JaEfWk|UAs>+b1(Sy=)V9*T*f75bhZi8&xoB^yh+#=}xLt2yXp_M# zV3Cwf#)RT6;S2FT)e6@zao!)F;(hgC4JxwI#EbM}-TkUm&qPm_gdS(7)Cf@Mca%{t z?*fhgzGO3r`a-P|1jq`iLU|Wu?&X%W;Tr`Z>FuFlY)|t0IBT4DE-&0?;aKqwaBhz3 zV@zau803eH3>q6l;Vo*B-{_?~B&Ur$2dP1;Ny=uV<7%aO8eX<+irS;~kS`G37nP4m zqfu(#5%NFV zff%+&?DD9ao@^RU>OsGY|0aN9RYMooc_B zVpNOcW}GjEe$b>OBdw4%u(N-b9Mdsr zpH@yMg=S0HOok2Mb(5C3YuZ}Q*EBbVO2EG5(UXsfAKSdJOSN&Ky06v5qIod zKgnvBS#y#{`mHw$^Wwe`|D+nmpM<2 zkkix=>iM|bvH7MI{9JsE>q^%O%NHykfd=|_qe9N`g!4nBfvDyT?^1nA3VX8hO7-yh z&9^>>1d0Oi856qBj-vtaeO2siUZ-shQaC8$5RP#5!DUI%Q0ZDf+I`oqIOlPww?@5~ z@C-CI01%q&{V0fM?SLYlWA7@($YyZTp7Y)fideE%&y^O1bQzNds6153_8@lLWk)+4%45!@1om_%%fb6B&-U6B&;l%s4NN63 zT*nRAi<1&dd<3wuG3GAklmh$OHW5C5p6%*-^9`@^saM_z@DioDEW?j4)=NpvzJ7S( zvsmzaZZxf6+E?n}$u=jb!S1R8Izs9I&c7)Gdo6>GaOu1DVkwNTwPaaR&%Uf40r{vv zo8?I#==&Ody_&_7J<#_{`*H_h)?yGZsD7=g9EBs6V;M?SS7UTzglwrdcn;*;>ur;D z^ua;;a$V@n+J3?Sx3OL)_lEy@#}I2;sFGj&asj{*U!X^bm-_H>m1N9r9n{JNy|bWqr_V|{91 zyBa9E>UC`#@#cKJWnI>hK#w(J_a1oTZlo+JVr>2ILj%bt-hog z4lZ5Ci1irC;yg~h)>9opQrrbP+gpF2R=Z$aErmcK_ewqN37ZG*XHiB|KBBiYyUaNpITZN7w3 z(MvaU01@w~lb8?k2-1Y(1dj6pmk+hf@zQzkGuNpd8wKmGv3jAMac)imNh+@HK_F|>H|7@=(&LPgnqth3oF$#Kg591+ z1N6&oXdcB!n4;Oo*?DqK41GVp_5IFMK?89;{VA2ZeJ|80loH^ z{ICV?{rOH4$Yk|ANVOYCl#fk3XsHC$4Kp7h`}Us~Q6skT-Y`4MOs}?GUK%UL!@RkT zg>5Y(wBjKZ2T-aa2B~i^#UJCoJ9o#?k}oqJKwz;fr+Lnj1?xK0RNK?7O&#^OYdSnT z(rn&~#XpZ}PqHayw2B*9I~_*M?%>?=7Hvk}_d{wVP$us1B0)wxMO8KECz;fsH9xB& z{>IorN{BMy*sITd)3}50s2%Du5UQVfQd!&Fm+AFDq+w54schI(s}lL^U0-|yw5#Yb z42jSWG_xf(uI$~M1ey04pqS^bR|PJg4t(~|7%pChn%GO(4$hP2FV9%s1S6ASUWIWJ zGo$Z@nu%bghd_=IJXODJxT;`RA0BUJ1XNvBhxxs%^;LsBIq(D{G>9k_iCJ$?#I5yu z>D9LxO%Ja5gDUW$e`(RU+nmgF>X~~hBMZ#wqN^JGCnc1}^I1AIY?o8z zGW$okIO*qWT(iVxjhxd&_>%IVuS~Nb_9SefM#y`&9ST(~=0dV*um$*{JvLqza?~-7 z*`BzcXAiB&ftViZem-x>hD^#9pqW86nHS8wSJLa{cQO??oI(o`1Fq2DIq{u7S`xIo z`%brsM)K<0KRe=iUTDAB;U?M>Oly~@HoQAD+qpIK;(aJ|g4ucHk!7J^ET2t}+&+tt z#ZnE8vpbo90z$Fm^||1!0}mO&0H}ONlijd3sT^pj*#$PE8mo;-m&<-K@2syr6%(lo z``eo$>k&V0OW~r>0=)Hrd;y@S+UGlmZ!H-;^+V!{U73ti195n}{f5`cgAf&}zZAp~ z(y5#+24Y`Q@uBGPShgxI8Y*x4($7O-y~@;z=9olOSeU0O>oQGuY1vB^fO&mtvJd9U zRdf=X8FQY~_K7oxz4VNJa*xzg5zGlcQw?%6-bgNNH(h|I;{4$&YKqv8BN@+PTN=a6 zU^d@BtqRiSas2clo5>I(=xwum&Mri}8@lp1DN96?v{d3LPN$YAl|ZJPHcfhZ0A*uTZ@OasZ96gR89+a=av8i0gNyr5xRBDvR8x zmBn&!k3V#(_*&ldspWTc-*D-oACi4@AlsXYX>os`Rz2SQ-tn4cH-oNfA z@k-=$q8x#HXb9OCY`(|UCWZ6~Cw5nfeOib>8wfpVeq%bm89P@Oren@Zm5@BF9PWs{ zf(aC<5Vx=IP)3A56|GmT^u9Lr9KDC-X;e)P$~rBW^oceRk52A(j=X?8#Ir4u$5N65 zefCMb^d@I|dSXUixIF!{5*mhU!|GPX&-2E4|FI9HUV9ucs(Rg2+Dr}rGNAw9JWBHW zGOjM(y-06qE{3lIjbZ26Cn;!&P;wEl6Y|6KRZl%Bc3E}Fb?EgMNAE1F-&^e)fls=o zNfmGWvjN?q5FFkq!xek2UC6V5J}CBeI~b+Z;}lG){=oPMd8Mmeba+6#q|0*$ee*ro z^uw}+i(KJD4Di9Pkalt3QxFV@+g-OOupX#~-jg+MddptPqxRZQ8^+h!hnP2<*a74& z1NTupkRm+Ok~C1S1LpLpkYY-`WqsxxeyX>yM^7IyDba+Ur$Y9uQMKr-P(PljhRhxt zOT;J0$ipwI!}quaN+0nN+_CJ==(Q9^@ezif*T_vTmzkB)ld~)C=nGG(lxjgvb#Axa zVptdY&-bmcag8fZ9@CG8aG>e9-}>}4qbBWFtn)KRzREJusF#i9k4dJ`9^`=d)@mpU zJ2MiTTBYL-aGkqy7*-Jd80$VDhv!5fUIg`Yw+Y{jO{8EPRiv%EroL1})SlM0a!4vH z`xWV=WGlfzPPxsnLRAlu`>GOlUN^6X@5T%hb{=8cE(R7lV^l)EetM~jStcGIJSf)( zLZGCMNBXhQZ{F{S<5?6>gCiT4`8?=>cXl}lFuEMVT7F4UQ{4?%FWw1nSliUDg15

6B#reE#JTfl0pMZZmJEN#V7ed zND||*A|pFHyGGEZ;ZLI(Z*y^}j7jIHy#S1O-?=2ga0ldaR~%=CdM}5|`WRY{S|})N zr2d(dl3U9xM>(LTAxSeljy4OtYCzCo%u==Q z23W$&%L_$lJ-Cz2>oOF->Hrf+yWi(B>lM_|@g!fjir5d6AW*v?FfT8!XS)d1m!rz` zAvTuJEk8II3ztq*cWd4H;FR`?Gx_!Snu9MX-qohI@4)8=!q6bE+Q7=c>x^YLo~pDz z`W5H0In@MU0kYW_QedtlihD5dY_ppw{Qd3pJarIX!G_WmkI^Z6qHq?Zb-Y0oq?0x7x8cm(}ui2j4n71CF zDwJH`bv`*j0QGBW=~1Q%8cI5nHsaM_)^(R=*-T>W0Cbr0&?kqo&!0b!W7uO7(E3M4 z5};PDx~GVG^?gyID=?MKR55o~04Ga;&+3?RkDZ-7w@XA=xU_k{>UVNW!^Hu+n!37C zYcNsVL+kkM^|LVc`bNiIkJeOyQZ8s>RqS%dbF9@rX*2hn$d9We;1_ z9?f{5Zk-vF=%y*hWqQId%Uy%mh~q2d&3zq zAU1#j#)fTMIHk4j3yA(*jjFKLzk9#umzOcBbl(C0z>YRGH9d;!c+3*hJU&kO`0-=G zNi%cvjG`h!6fXW*po4=0Qt8Of=ctvh)`2qGL8gAdx~*qKw%+!et!P@PoJ)Xy8iY1cSe3b?(N&R$13d^^u7O@wzjt$cf7w{ zR8%AmY>fyYw_OwD&;^8(owM_eLrQAuFi-?jd69m!sM$<3)7sZOpEkcXinBY$zSZ{g zWuwPqa^O@G7e_HF#QWn>KNJVW4$g##h^P`&CZbf%PmfwgN67&f{Qz;m4;NWaJ_O~U zTjzcwIXT&N_Xm^xpMksl0s^oG9B?h|N3%WzAa&I=G_ccV?MemGKZdfScE{QVO=$8d zR*r-)1aEV45*hfM^Hw|kc?+PB{vXttQm)L@38|>4%x!Ms zQ&UqrZOz=gxVQjz8kjJL`9#IWVxsIE9sRTmq_wmtASb(b$U;^`qobmH!4_$0X{AC! zEVK1^`T8nCMVE|h#j~6SiUkD*HUqVSnDm#T?{~*Lb_^Y!sq?TrZ@BPYSXh|Yuj}*s z)7C~#G*A~*6=pwMrLK%W8zR@Ohg&CldFE&}RY|0;uMZXe@zG?Ws23HmDeo%(!-o$k zMBJU^LdP~a`ku<1zaKd&G5aN8oO>AIg)43n?pr6Z(=?#jr5AqMlX&C7TD*nD)2B}b zJ0YT}%FKpP8r$9%dnuQ5nVG5Yw=B4YUa!9ayV#p7f`$U8 zE4aw5rlvO67D2szcqko&e{-T#81`MO!Mlzl`h^ann|vGnPJhE|c`qY{$Gylp>zTt`DgleS)*pYKmME|bA^8YuQSvI(c;#sC+EI8X-%F88BN zJlK-4@$q?pYUHeWW3r+jVE=Pg7QLt_EeWH%xS1K_+qZ9(b#-yU`NQ5jHr%AY>A2k0 ze^Lj+-#iISwbAxm6F=zl1k96|`{!>``Gdv`qN zM__1b8UP~#_0n^5lK|#HCV|)F_w@3L0t*iO4@|~Pid}oQ+qvvbEmc4t^~C>A=w!Sa zi}gWxu)=k0>}KG{X|q$zH$_Dpt!-^ob$TF~Ul<#wY2?k%&7tV%QZy7;OrP+&JNo*F zy-1DLhf0852+Yj93&`pRYL0=G6*n_8^NFHj+gy_$5hg>=HqxZaOc;rUxr{XK(f5t z=^G^Af|a}Od?zpSrsFU~y{WE=fqJ^(P(`C8ymJ)>?g#fa&s(OASEk*KVQ0bx7G6+~ z9_HR}UsB~=jH#}3U{{uj<{?!B(mZ4WI~m`TBq34@`TTUlWae-W3M z$ck$`RbgvDBlH?qU%xG)JY6Nn?r{BiM)^~Dc_}lqtp4F)06+jYUJGht*u?emk}t!N z=%w+S*iE@}J&*_&|CFHl$x$3`|wo zuzKZgi?mt{dB$LoSi5j`b~XwzI+AR$iwobwU^-1CO2WRtg~mhK&noTa(J=^U!@(S- zm6np89&SilTR$LU)k03dUH~CgIxJxm6B8G??!3sDk%NFRDkX<2Bs`?7jfjmUPxd}} z1%yFe+YLp_34YekOvx%|ch{j~$swFhtX}sG_% zyQwMNd5S=un!%mc|J4idnncHse+~`H$-~2=ZkiYy2j`idUO`zG2x1!>8^N{mr5koS z)pRN6F`xxcw4qwSc!z^;es=W))N;|w{&bBE1_%OZBL$2TP_o4^Zy;X7fzMB+F+nnM z)*mn6)b9SgukAwz;NJ4_fsVFU6D|r6U&1+0B}eMzOJ;zmq-iqnVTtMT?IbD}6-*Hh1)wH*8cGpi_CJ?nczgl{!u+c|l(n zcAe7l4^Z~9va%)WhNFcB?cYp00r!y$#_5cKGJOq=k0V=nG8vWyVdU)eEG)U*)Y^dN zMiZs4RwgTK6KKCY;5qB6u$d0!oAo3C#j3p~0_F;gEuxsEBdAQjE$TdfeqH1aF$u{t zRn?3V#mkFxPWuD2I^!zLYuD01jz9q-HVV8gCm_nu$Ot{a0fE?A(RLRZDoY_D@EQ); zEe;Ms$sqj4va;AL_wUayF8YDaPB;@{#)#*zrI-^C5Qqq@zOB9c9Gt`x^YH*2a&6tf z)A1|RD@S?ui*2{>-pw30ABJy&LhI=1sh7FS9RYA?c`j--#?h51K+-F6l=$?}KwCT1 zJlRd!Qfs1|kevKWg>8vwVcj7Wusz6SmMJ5irPbj)e$QhLa4QkCQZ0lC5!g&s`hr3S zZ-8&-Lw1lQ7QzU}UF38p^H0`1|=YHE0|(L!s;GMjV_Aq7QnV`HP)D7Aa8BKd!E}MTrsYl{Bu`s zdofb1d3KhrJ(7-ZRSSr{87e+rmkD&)tmhscJp)6rVH3LW`TpQojSIW1oE&l_kfib3 zp-OjcHvg{8Ozn8?#=*}1{?PNR>#spr0FhvV)_C&tsc%8SgWSBlG-c+w`FUUPes>rd z7y4!BzC%GOXtQ0)i{Qvy(kKM)uFLL02yxl^; zY5J3t`{VA#=RE~`2Z!eL$6@bdVy=Nq&Bzsl%!#Ove<-DMAVcaAW~HMu`TB^~<6t$Q zK&Rs2$w{(^hrhrSnqhZ5Zybja`i$3+-r2?J)=_%!Q6dN&b@dyp4<6uQOLt4%c<{>Y z?07K}*fjr#^X~3$U#1*6t4=vC5aoAJ=x@Q_fn;s@`4gL*O}DXyK#Vot*4Q{>aJXM< z`8fHf30GRp;E!k~=gsD@(9pgN8G`6oYY*w3?a$x7 z5d$((@Y|&ptvC8!F=OrbdjwG9)($m=S1=lRQz$Tq)*TBaMZH2r9MYQVT?yG?yOZy% zl2bY^RR6rhY(B|lhG?X-tIIzx@BY-(6d?(T-xW;!#>q))NOB24WL;fdDHrnVXKqnO zs~kzZmSjDN0)7xcLvUzdGr;R3ibC{pwU3#f!qC^_p<>X$D}zZ?W;Zr-HUI~vMS?da-i{rohV zN>9dd&vCBNmvNL^rVg9_jN6g~Ocee5i{!uVrP~3C0!ESK0DwU3ZCe`#a&!Z> zzz%laX>CLyJ5WJR&QBt(5jk}QBzYRmh}?L=vI7835nBf=mhN+T(QM38rTbO22VA6a zfBIvjQ2}H)n)sJf6Gx;OLKq|^YPGuH9w~Ox;@SS75+Z6j-FAOz@Fn8l;2@S$qfj4D zNlEGW_;{{0ghYZmVtKO%iupabyuQ9Z>AbkDGB6}9ZEezV)(W$;_O7n{K!MH^`H8}A z#K6WavzHexb#-@hb90peiL5AL_lm)F7ldg*VArQ>MpHT2)mUx-m6U0(Uvb9c0y$7* zH!txaHdc}`dj4=@Qkj`_r7!IYaEXzzu^)I;adn-r+=1#X#VQeHEv(O_TM@>XnTLLDLN{rfG!L=3nmth}OU+me2xHyG-CLJ$do zoNvRxpw4JS+(|9Uw2uvw{=L2-fMUX>;(0P=1N9I=+tJ@oq^_=B>AFL|u($|j35T4V z98yD)C59e|%GcLd;y^`Q{0)b=l)gT#H>lc-nYfsk8&+0UrMY=jhY3TvQbVJ5H@mON z$;*e&u)mhue3NZIUE?yk8VEw$@YSp9IyyQ9hcs=TbUY8vt*x!gF7Pf-XD_i&|G@e| zeqj?35FpzGxHd4+4h{|zUI1&DmYRwJp5%90A+(vUz6R4m{9`30_tk#wZOA8PtW7|pyOZBO7RbTz$JN~ z?Z_OToFM)Vl(*FL=akDmNjT=_zcpfWc&Rju*G?zPD=LCOj{EufjqJ9zO3{dVQh-2m zm*H1siOJ5*<*H;oKRIXt6@px@f_|VBexnXrnoYMd)$tJpHFenD?_Oiz@s+76ZUE(e z;21EE3ln9QE5muQcHFAZ^+V6bs<(RXYBo-+^$KZ#co>_Qz~+5|*S^{3a$!{|&s{F# z<|cqd9CRjfm1y3R`0DVyK&v?YaiksO*)t7|k#w{Vn=bB`13*>5uui9qiL!n?JzZV9 zi!(RKL*$Iba`%=+85Ix*(pFMZ;ujQziO8^pg||@*GRWbyor_D5E*m+-x5>v^`mu>%ysrok5a{-LNpJJ? zwBFk6K-`vJNeMS{5d^SK$H~dr?0~qyl|HoTYUh?5)i3Yk<3m?hEwYC#lE?F6F&81HTU3=q0$>B@(QD>Ybq;z{fWMHw1C+S! zjoRqw=xx5qv1vC@r}_E$hSt^*|NKK-NA49Nf}OVo(oPyY&y%-pY4o) zN(!Bds%k$3aH`gg1n2_efU4SHBW@cvO#E4q& zOU?wB@vBW&q_uIUoi3xgnu^Z*`1V7aDdv2~y=4VJcr2!4q$kL>{%=-KQc*+%9^!ZP zYF_gS{S#aDDzMTztSRf~&!5}N3AX7jTQlI)gSG_jbPKvel`nw`hc23EAuRi9rZjSXj(K zsX<=Wo^IA4$KDB^;XHP8;&+&skee5v-?qLq$zq>NZ{&pX5`+z>$D!5wOdU1Iv7nfk znCz@))?9TU^?@~lltlkt1+}ub+%1Xt+tW=UR)cz)PoF+*A06=>8^%ZL0at;)IjA2= zteA1f@x#EAFg3jk0SPA8cSXY_pl$WPP7*)$wWvs$iQ-#HN!jKEEHuAF&x1}taXr~} z;rjkce@1tp`>^L0&t)N&#IRRpGgOye^Ah3LB)(jgZDX@@Tu4R19}FO zt3J{I@!FAw2L*#u7m$edYa+S8`@$;v| zvu8w57Dh%!x5JCvz@9m+k3EYc)|TJLa92>k!@nu$4`6fIem-TlI+KYDtkZES2ZdNmjR?PIt`N0)MH^P%kYIgI`BflijAOu8D2 z{Yu~M&skXyJ^Eia3<%p6Pfq+9`~pN=SP^CB2nLXxM(A}{w)N&rU6{ZBRsVp1 z+u&4w{P=-f9IzSGVy7`eGg9zTAZou4oD;srg_``fo~4Q*`+KFJ6E{3#oaSyNXhQvY{3fsy)yfRK=J z=f?+6o;>0BQ>>F$wP)<Am{4lc3pKOD>E}KJsn+NUmwVs>)5l_^RI)^b}|uz z^vmH~FWBNZetUYT+3i*mrP45*yQ%}!E0D2I6coNAR!H=p6Dm$v{>+}x*sH;;`Kc;L zECPZcs6jUUT4vmXCr9kvdv)-eR}U`#d`UqrGUZc5Z-VRLQ~fhB0xAc&@`O#HD80y1 zNGNjMSs*L>bG&A7X|d0dwbgJbih)mq1@U=uhZs20XsXg4IgCJ{)DM#&Jv$o|w7fiSmSPe%9UUFYIa=c7RAjWl`}udYA{GN;!k}fO9zTA?`_2+aKtMo{ zoGHR>ubVGoq5_b2M3G4e3{*|TTLCZ+(3Tg#*HURN;2NwqJac-?;L;k%ty)4J_0FD>-LMNc7H$) zIg8|*^+Y-??x|)OLcl1*yoHe-2G9$B6W62u*h|nX@=h>sg7nsomP7hzN5AT6MK67_>AGrpyv1WXBkZ~RgDFnP%D#6+Jzgl4Rk0D)1Rb>f;DanZ-QZ-sjB*c)!N^fBxi|{b;a!~F;_|yaKr$^LLunH z{HA(`(EE5Eb7*L&G@*WP*{tJle`lxMTG^@d>Yvk?8F82+qMl20naZsv10{p-c_&^} z3bY+cUUnK>(8~)WLJgPtA?{6~*HW;C8G%k}RTUL_c@y^NAEn7c4|$vF%%(v!t|T4B zZi*Nf7*-ogl=HasyVI@%BL9!iLJd{tMK+w{q4L>nSShV_1uVh8kW zC*U3Y8N^KSI;519lhff{NanP%wl20B=R!~)92~Ms;DV6r(2Qo?95rMM1S4z*2L|jG z8ye=?e0(0owr3d*7+mC+4eo1nbaWt>IKT%;e>y1sG^&b=YaLK+JAkh(ot-$~Q<27Q zfP$&%>8OAHNmo5J#Ojt}x6UazDg*^v;P^G)$J;9V;@W#%Hqe4HAg&W)qp7Ytg-D^x z$jB7TKe$Ol1NP|lKJV4luLHO_4t(Ww?&|6{KCKN)7R?LdY-&aauusU1-rH+9w_;>>z~kWPjU^@}J=4|>t*sR< z=$``({YHk)ixg0&13*?;nGm9cOp=#R+>xH1o{)&hXyE8`FKCxC>Gm4U&nowj+kFrf z|31^;@GH3gltSn=E3MC&ebN$g?)xRh>z&P_zC@w<%v;j|{dwN*qhGsAofKRqSit=L zj!!i-$iOk9qoco1Obkc9TTxMwLe!HVTqio%B~Yt0V%{`>DblZBKLq}WurRfK_39oE z<3lwtMNmGa6O=qme0-y+8nXq61^^LVenO+&Kqppq(@#iGDM|1~!{vn#D8>NO@87>; z;OUJ2E}Q z9bo;whmqfo{-F%f%Fk!5tgK8eDk3Z{F7D{+8luAc`t2Jrr~{}_YH<5Rl$6&4Bzzki z#hq4%e#`|5A$^S7+uMEBld+vk52}N^dU^uo8M$-GI)|u6+&#~B+WFo0v$y&2vOUW6 zeAa{8K;o>14`B?cM>m`;Ds))a-9j_e+bR(P$@p0%hokG&`Qpn!i{UP>nJ-FoAgcLQq-2CU%xl{UU{aY z69%3Ovfv7+s!I0*7F|6(t7Y8II>6M7sK@J5x((t}KcR`HCTH<>!rfHHvq8uBq za&vRvfBIxQu$R5uJVY9qo$V&*n+!(md5IaXP@<*R@7@%?S7}rZE-tpaawW*+CnhG+ z@pfPHYb&U`zG7n;pev*U1E5BHw%+TRippE0nE~{@l&NVZ$E!!m%I`UTAUDSE!4kZA zgF?Q%_B_bDFe(`K0E+}aurUepiRk^n_T6mX`Bj$RqQ$tJ3Fg)sq zNMl=0PEMu$A_n9eK47t{tE=HkUmDUL2bSN2ixR>P^G@gXH~Zhc33KO1vq71ecQNp& zuFA>DA*vOGbWlM-!4J`vz|~RrJ9qCk4Ga+9*T^TVj%OjoMz|&|Ee)eP$(lJt>Mc;w zRGo(=1$zT12a7Uob3$T+e{jl=UYDWbgYO|M4EWPf2Jb-;+rWBqhca6ZuG>q zaIQuka)2ugxnKEuBYwnf2)+wBbxwWc=P#oMruX{w>#%~6Nk3n0MW#OUo4I3{O8hJ!yWP$7JR{Z?@NOJ^oJ)J2RJ2y9n0`U3# z`A(Wfs!>Z_YpWE}N47GMi33(W}i;*8O0 zP%}uchGHT=^1K;BEsO$L$b%119)_l-&PvsTGqw(nj`rJgkHCOt_0LGe@2$k#*R(r7 zaZY1g^&=1^419X9v(qmadAK%;JYa+v01Jy;2y;^t8rLWJHKJii?^HFG`GtjMaX!u@ z@vYg027#ab7LLnZO(5d!=9{mfoS7z&laCN5BmbcBfp8LfxvjUZ;nj&OV#S!tai{Yqv~IO#!_}b@U-=+G#!Hk3~2*2$z)Icgwk1GNjJ zpFX{goc?ZX;89akhg0#&jv2K4FvfkRr#Ee~<_VdhrK7Xh8bVS81R?Dt?7T{fJkG`X z{9EgaF_i>M4Cr>;ot+&R(9YS}dVkXsL-xqau+4Djn#>=`(R>= zJpb-K6lz1_3!cXF;_q+w-=wGu;mEeOw&wPBnYj3hVj~r#%L1$zzktA_G-a&FFFe2d z)6?mN_xmKZBSF>V`yX_a-m$n6Hl7W?Jz0-(;BYj!@urqFNh1|f?zBdThN10;iXPtLT5`cV~W}$v?WMoiK5GKMy zTU!J%vH?RwYLK!<*{v%pFGFNJNThL__7n~*(K9~ec=gBD9%;u?z{{DW644NFZ(6?{V0kSewzbKL#G`~Ti zaIYb~07$!0h0Qb}DXGcok<8I`At9l(n^!^xhx0U}K7JfAJJrlVbBj3i37sex_*i?3 zdU(k>vc!UPmvOWpCs)e!8JilfY_`P*!AYJ&?xsXxpA#6oKUb?Y&R^qqbU%4)=qh$r`p5YAYG9+RnV&@fjZviNyV`|> z?Og(iM;aJ51`6Vr4T_S|4m95eR5*@pOS*TH(QhUg1WoYy$%GF23n-5g*BeA9k(K58Ls&|JE?<5>?A=l^jw~n~*926%~9v$s!1a109lsEFh)Tv#1^d!UTzWi;b-(yEh^G zHijV4A4K&aeTHf6p|=r6R#zYXRh0Ik*m+H(V3s!$kN5I&vu2CKenCo0OY0Ury~J9S z>G>azzbjGlAu!`1+4x%{XAKuagD9%Hz2yuUuDjlT!T+~szqvYAhx3XZe=DLI<=E>? zmInx*Ny5t(8g6a^3kwU#106`eUBW|a3Fop;g1#hC`pAQ7-9LMKWz^J2t*opFK{%rX zRV&b)A51@ZaFC+$?c2BQWO368jd497dwVvR0vqoTio0vV9`;iD&2QLDM+Zw%B*?hu!#CEi+(0a z6{e@7tE;QqIXaSj{ITQ!&gs)WKXOH^BzAt)($Z2&O6nFLANgd3ZIBwvckn6x-~o^W zcUG8_4yp@Y!|?VhbZ8@L2BO2U{8dE+G12WN>SQuVOkGIe8H9F{<(X zZOL1)qY6sTH8e16ZEa1=&5e;8MqRC4_S)>515wm5XW!Ey#U#N1q!EOL1zSKs z0B}@BSCOC*3yc5`g2facz75&E!i(OvF)PsIrD|jR~Y34XWzqhA})KD zA&uPa78Msidi?m>z`%h2`-A;`f5=-9$MO#OeSONF`~5P_TX=b0YfAO~NQ3mfpx@mI zOtqqJyT8o7FxXgvg5z;dcpOGn_ULJFhcYtkSG}5a5GoQ{qK9L~W(ij_F65TF6tM<{NTgll zb7m&eR^#})=dpwY`rEf}?M@G^fypx@gYW?s-bP20{1YABpCLnldQ(>?@~x!A$ksLz zR2tHn3h7f~)@?DkOC0qOL$Lpnl$5k_dU`tBdUtns^Qrn?we#A<83m#*p)mX>CbSdz z?a^URgTuq6V7j`xx**B|y1L{c(HgtE@t717#bKjBO(~R900Pfl6$C=^*8_ z#nJc2H#ROV7&%>k`t<2#L*1!M&bP}&{)-W-;83dc!0g-PF)u?TZ(Zvr95R!9<|E;V zhxfo&O7a#FQN&xhs}CML^0-TJ{{B|_fW(vHkMS%*v-8r$HI>7=GPALf?O8!LBZ-~v1|GIZ+miiZ|;8m`V}ZjSFg&!^!e{g>(Ngj%0)_Q>N7Jl zsUq5xVwtOJYVyEVA%BfqUF@HL$;e$zk!eKllmMD43g(u^2gH3CdMl zM<)sIirDr%YbzBk?N_j;?tgbpp$5LXyStmc5Uq1t1H~ssv$xb4Tm5=Ndt48g)%Eqnzo@u?B^DHVC4ngTrp* z?3Zz?5g2@Rd%oq;O&a2GNJUMZ@b{!8h+uep{5fcl$J_H_<{}=4R{ECi zP{VqacJp7hDk>^QVJ5$YFZO=-mO-46%QbcN=_LvYL0f5t=HGr zum1Uy1EGNI*6=!vePeX3(UxUw+qP}nwr$%sZk!uCH@0otw(T1yo$BhYQSbG8HTuUn zXMEqkGuK*k&$Tf(ck>P6?fv~ax8@-t>JtBYM%RaPMz8rhDvwB-q zk2v@pT5Go}Oxj$N zkDItdgYK*l|Shl5E-$&1l*f)|oj{mi+es1e* z6=R2@fKgJtxr%-Gg*L#hnzHOc@yMtogR;JqN#Q~xxTq>bj&raq_` z$FP&Pz5hLf{dEHSo!hmSW~ZK)fyFF2ga^tmk54V-o5JAp?hmN&4{i?zWBg2$umAu= zq5uE{KW-1smbR`omUh+TyfqQ{wHVkhM4$1t_hAxm-jL7x;`Xt0cSt$4YV?s(fTK@&vjxhH z*%{5l9;_OCHx-XVC48YkxTpq?x-id&A6Ko_`#>NkHeIi9lpMhWLj;H{KS0c{h>qNZa6VCa}$1eu?Thcg5drd^~>`U z#rcvs6`;XJfzJQRTal;jL6ZTOBH+RVU;?}q;~79ou8?O^X$V|$E)eMmQ^JO!96*Xj z{bw776Qd%I@Vi2tY;v@2WHDvHgvoe-r>^Vd)7s4^rFV+?91zJBs#AnngKMk%m+d~8 zJU%opP&08sm9T69&mG3^UW3VW+Lc(WEO%Pr^rg<6aLePM!|BaQ+OQ0*jxU!!H00y1 zG2t7Y#|G=!VFMq$?YhC4WKAU6WKkAV!7kO6{TsaW-{v+KO%ltNgO-!?*=o7r215DR zmyIvuvIYnUHl6GUnRN^uQmer;es6Rx_P}hmFVF$M)J*+&_A^j6+=f04+5o@hs0PT6 z^ET{Y8?~>;LHHmPNyDr;rmx-J=U|=En5|}h-?O{j9y@yXE6StCeb5>p zHzoxxuM> zlcA}W3A+^W!l`Lw^okKK2{h&bYyZ9+-_MtGQ{+DonHf#;t3_-e6ZwFm*XArJ^o>{OG`g*s4mRNgarZ~il@$+B(e z?z9J9xv6{<`qWEX+UT7XgE~CuTKV-sBF+rL`JJxg&MB2djH-fGFTBpE=GHP|u(T4Q zPIWZabms+O8d~A$R+(vKW+|evW>09WVNG!fXsoe$TL8q7z|Ut)bQ0~ZNmrqQR+g*p zEJkpt9>OOIj7f*0*7ruV!JIh%AiVQI>z|!dv zVSjt-2p_oVyE2I&wM$w!marT+*5ie}QD@vWd|7~PL;36Q7I zi5VSy3TZuGkcLb|N42-&$u(xo^KlN4*?HIh;F1_vtn-CZUv%l2TI(e0p{Vnma`c;M zGGmLjn5OgInT`iQMG-B+Wk0UBwIF#2c+S6$u~fJHAq8cB_g{>y7Z09zsX z+d&V`Tyi=G-!8boLbRnQ}_3$?Y{g<@pGZa3spqk zSeE{lV4T+Uv;g(eV}*EXj+kI_vNL-*P!B)5S&eV)3)*0UW#-~MEGmzxGleP}Mj3;X z%%&%`iwGe=bw-swnv_dh7DfPEg3?spFS!U)AsIH*d!!Y$9oUU9Pgt>tGOgxn#HoU? zYk+DfaY>|r)ul=)9Oa>erB8$OB@r21fC5?qaEgG?B_Bx$1{DOd{XEt@-|9~y=ykvM z7IVSBPWvDhB?sM`-p0T4^x^ei8$;yYGO_eZ^q$Bd? zLtV0>EBb)@ao7ZY6B4tSHf#@%xC5hnfctGMBYNUg!aKk7NAygS zXreOLx1D}NAOG=G!ilW5SIntsQBz2n-`GdgScj>Kvk(qYOvj zdUZa0TkpfhK5L-XJ`XxojWfT1pvrI8Wh->=D)3UTL>rTSIz81S;+;BbF%qf)An3(hnO!4fHJ(A@dJ;Cltn?55I$y2^jig#+KzdMcBjK6Sz~V zz}eH?YKEtoIbaJ^qy`GY&WBx6Y9rqXM3K=6wm9>U z+fYK)`$tD^6_LP|^ef-dpR*YS9Hh1YZAMvsqD@By=7{9>ml?aGH>-%7``f^_(9GQ9% zlyp@MIk4reh*0GY?;_yU8B853vVwhehOc{^dJ_x*aXUP^8FrEJiFoojF;T!d84q89 zBV^M!7Vi(jgeLndiuS>+sE&pQ(ZgQwlfHfUI?GO2I^FAEkzo+S;dd~w#CRlxy?BjL z`8lG)^Ii(~YykkbOybg=3MMuGj!%4m|7DB3e=)e;+U`SHL;-IkLD(G+`3j(oJ^`x% zf;fvc(x?2g!}Op`FD}wJC*_-wd!n3*20bP4txINRE(eoJFj!jz zAK0e_WnWvXY}VA6-YLf1DW!k8;2LUydMXX=Xm=j!6Z@mv{4>gHW6-gOgTRQzHi4>% z#rkFj+Azq$U28v25Q`|9MbowhZ95R@LxF z)U9-+g;1lgL{Cc5$HR_%@ms3Z>?p2AtCt^m@@#u5$v_L2;bs=7i?*D&wL-S6%#~2I zh2ymOR9$f?VHqEZs-r(ERY#87zi~W-I2`<$S4YohMDFZ(nUnR9RdD!x45c;dtC|jd zAJzAX^3jWW$vZ)18$Vp0CXcc^w* z1Nym+{mnS7S8VU&xYaP>s}skT%3j5-3#EFl5UYhdn7A{_2_$V(L2TH-Un6ubVNvc) z5uzdeP0+r{kJHyDs!hoG`fx5>@g(?nE_``5e7z7}5J_(i{PW-xxQ2;KB>yakxLnlx&}I- zkE-H!7mJ&MYhESwmOb_18rrGrZX!)Gh(np@;9fqO}YCL1lx2=s#b(bu6kDv_SsOo z`*++NX9?9!Ck8emLQ6B}3ZXe|yZy)!^5&#)FBol@r5f?1Aao7ww`8u|Ahe^4wMEr3 zIed-C%L5aZ*7a`x6xtDZL=$)|RT8Jz)j$}y5)zDc;19;JKb={vj4m0uvkUcdV>MQ_ofEn+?q-IYqWFGEuYyqxITolXjUoeyfi(67E=>$ ztS2{lwT!z$ZbUDH@0yqEpYDyTAswPpdly*aKHTw&%REbfq7_q%%_F#;$WHl~a1 zknCg)3}<+#Tcr+?@*MZaY9(|$E-#o*9&u3;_YhQXfJ2w2kFXwa=|pF=rqiq*NQF8$ zU`5GL;DSDYv&Nzj_%)-O8OWl540*%%a+h`QnYoS#XxMm>KXa+R(iGIV#6NYmeDcmu z4e!P%D`6S%f?(Tbn7uEWn~qI2l6gMEX|QWbc1g+A)rNV$h*U zP*ZdSM4LBmBNP3POjpcfv0#OduZ4s*WcS+_Aqhl_gkw`nYgVj0tJl^E2=@-mTIg80 zT2nyXOK03x*&x$TwhaL*xKV=I)q8fBGi#rrB`%woFPq}KOz9x6KEq(!ditV3iSB(k~Y^zG?&oUmE` z2G8DLo2*!b`FY?yynFRW6^U`yuFK1ZX<7ahzo?*VMos;d@H_dC#3I~+bG^VD4zNL zJ?edgCh>K3;~1%`pHTOixA)Z<_01CBs`!g^c^85+ zcKJh#6&L@lkHUsAA?w3_2;)sDV@-UC$x|_?WtUhoUPIEDM==aH9C_j$4Joi!i;WBn z+KebEG@Z@jK{C1AF+AfZk@Kl;cj3ljkGuR{Zo#uMQ*JUnmRH1A#qyk+y!P2ws#U|% z$NrRSo>Y=M7tQE*Mu7*cfvAmS`ULQ*#_kN+YD~8m?-741t^&W6ew=&bHDWBtN`Y^U zSIr!__hbp}`TfYqFLZa+E|Pryx16xM&=@yo7#x1m z(1CaDIO1stpWOb>M!Pqg**kWl#|Fh7qI2`N3Vd0joad~G_pcYgw_N!H2zsB6CF3a> z(y1P{7u8^T44<*x`%T_hJ$=!~5uFVF=+_y3$T#NW`p?)t{Y) zf4o1kuWCLHthmw^HgQ%aiMiMu@m^)r4tNTl*>e2TUOh29rdZC>Eq#<}}7|EhBudmyxxK-|x+-uc(OYr35;=6T<8^e`nj0d7+|K|wYFa6pX%#EWxd|9aiZRv)h#Toi$yqT9 zYwD%jdnK4lfi8lC4IU;=)~h@he9Qwy2q;?ROPe_g3Me}1L23|ClK-4%&&*APQcQqT zx`asyg$5}`>mTX`qWk(1>`SLK2-L|t#(@U|kr*G7pB6(K1?OZXW#wopB4MWQ!XScx zf(Hf@@u9AG*BKDPZa$#msxfKig-aIt4iOU5b+rCS z&P)y9i2Dk#mjwrOs=KYO~jM_y-G{~*p{&00k+BKlivUNI|THZe5a=6

%ZHq!RfDpv(Au*R!iU znG_?xH1@!GyHDG+C|?@pA@r8yq`{q`DhW!dTpaxE%nss02L6oIG~v?*xH@E^~7 zdP`LT59QB78Mli{kC|*@cNqds)7Q6A(B4sw53{&e`x`~D@Vd{a2Qy->2$hn)(>>%m?Y`&Ec`A1=n^^{nNH=Tah6dkCs9mh|u?(T8 zg*M2tP5Vcyk6mk-bX1#%M5>jIZqH4rlw(^oy{WeEB~)+U!AM*E8d4!yl4jTdTb)Bk zU(hRmO1Uu^!ENFrW?|;D-~e>Wwg|2nzHvGLal=3Tf`KVW;&)411&ZPd$YFz1b#2oj z=FT=Xc7eY813XtFT$Mapn@~!;7V;nFLNtTPv+gw)4958oO3NEX-BHpCQP^WVbPB-o)sbeL z%2X{N?9Uxlg75|7X!dM;j_L3Q!*PeO7>#KZJyM!Qw)Oij6OzvCI>E@YMxxGXrg(rL zSVtGTGUqx}r2qD+E=nJ|-!^T?VzpYeOy(vGb{%2B{;cHKC}$%`|IU^so!t@&sN8u^ zd3x5U5mF~Qzbvd1QQyU>u>nE|$wp0X-%dD~po}RC6_6 z=g!v+@1+fKK#b&2e#x}Z3vFo?z#VN{^>BApK)x~0)}8`i%4}|1>R2^|QP1AfxVa@< z>Z*r5u7qXy+t22YTbvSd&zG|wzQbZB(PRMY_M_nm>^~MPB&rAb&<~B5{6wDg|Bbq_ zy`7n*xw5H?q@9`l{}}eF_&%!v2AHrLPpHE8eUoHHv8-*V4!bL03~^T(qcx4~ffo zxG&s_G+f&|jhhCw+eCflFN)veuhc1_+P@2q5%`w{qEVhZZ0o*;1HT6HzlZX_{lf+A zySdre{}CI?2b22tA8ZJIu%Z6%*!hR(JL>VWGQZpRa|U>`{Xc=+r}vE*R+nLc!ujCnV!(Q; z@jKW-DA{1#A_HNoX&_FjxpY11M5US9Nb-^iz)FHIcem-~e66x6DwRM^`?X&75e8q&o|p6gBP=1X)M!>ekjw%B0AT;X@?SRv7~4CUDmd9Ym^!&wnmYfx znE~HKefa?bl%btxN~~?|yo+NJ?cb$qNzyUX7CypWE39Z10M92I(jCpqrgsU>{y5WJ zo3Hm269(|ZXj-%gu@F!KklCnI`gto;R9X4GT-8i^R-n)>K+!>_Tp7_(khZ&Hr%*A} zyzwM0F;%O9hivyD_d``|iQN7yoYk!_`<%OJ@sz2%9>cgJO@;98-aIq{@e=fMp61AaI3@()bkb&PMkd>J+fS<38l zkVs09V{;jYFnK*Nj-Wql&paq*vP7QImX+yQI;U*5H+>)30Su-Ur*{{_x8UeIoU073Mb57bEipthV!#%-;seEtyt8DnUa zfgp_R>FPpCckt}5^>${B{oftRC~7shbg{MzaLRa{zkxq?vpl#tImNqRhlFPRigcq& zm$v5fQ%6xZtmu`r1ktJ@JmY0e_XQ{&kjM_Xd9p1!=GVG%z~m_$U(7TchdgskFI9>7 z2K$Q_X9BMnAymcCB@N39Bw%5+Z0lO`gTr4tKzwnCQ{4LeKH->&!1+8d2BIRdK|^Oh zs4}N8Iw9Eta4i$g!k(`?#6CYdhfIRO71u>uLRCuDCUVw=#9FD%h|VQeL!}i`XtgXx3-^uPydr06#o+fN~SiZhR&w{cRcu4s?Jr86aEK-?N?O! zzs(8~@kPn4t!)T#2?QzxIIOf7{@p6ST3daey=na1X*)yan=XkrhJL{o%$O=Zo0{lP zi#N6y+tuL;IbAdt2$_{N_Wn#}VIu(mVE#bzUwdSfjV(+~Ty0E+fB5d- z<-wH3hTMS!g6|1+L8trX^8^&nJe+ruS_82`j<_!=S|sk;G~MNjJ?C&=V8}(lU(o&P z^YU}$l3(1MUoKrbGGD)3l~s<$k|%FnkfilP3p#ny{W@My&(2CdPFpn_D{g)_=}wJI zn{a7r`kT@pw6t5u{ds8C{Y*BE%^fMurnTk%E-A0cNUup4Z@!Gg zSo#)a9ty`ylFXWQ`op-U`P5CZYc?dk8=}Y;eE*!8bkX&Xp@{c+BH@tcQ|#+-9R`_6 zSQCY?O)?jpLqJpj-zOLbR^9!Att0db z$kxAPI<6?U`=%IkY}UopX|H_MR1Iu%=9*@M_H|s-b*-UM7bQkAgsBt2*w4`{qKzJ< z5OirIGOUD4mFDl%!B1Ag@IK87oo38WNSY%a4}sKh1|7wx`R(h`76w&aI7dNchsYj7 zoQ=XGCYL7hvj+w~b%GyH7oLUy!=pD#Ad4ibkpx8%J@I#+M%h}R)3;VjTq64AjY2KJ zJXjWqlpxq3Bl@U9Is#*|6JC>J2tM75;#;?TAENkhib{m!9>5+!g7hY#eQEQ!1)V8} z&TS!xpI%=@d+B*W7borcsrKyA$Me3^muZ(v-PZzJ?PtDt4|7;S)%nA6v*V7Ye;YG= zxM@~~9JHbom!NxrAX${0nK2M9J5s}(Vf69GpT~!Gs%U@X(G4%$xCZa&;G6MO$2$>9 z{T4o9UY>w2rW-{TwBSo?-~|c64AezTRL9jfOEv*^uA3_*SPK2sV=Mh>JKxL^a4b!y zh`tKYj2K`hNdY{n;>Bf49Px~E|4VD?4X|G;6{365Z1Qe%0I3@%efgIjE?7yr^m#W& zX{x}GP9l)%I?Q8FxU9`~Q|nLkufB&jFv4ealJ+o&5>ntQw|zv=!O;#ygTU7qkKWLd z@KS3HHJkvGRh|+CNvMJ(!O6~fAX=m*91!$%S<28atqgLru<8xy501oLWb+JZYC)u< z>>$ng;oh+rVm_SSs>8@-K_Hv8263QffU@8pNYaprr^__;N2)DcbQ5laW{hwhQNeY?n- zxLo>!{_O&j*wn7KyuT1aZq9M6zYYEokB=pPS?>tt(!f}BUmh@5#*~;VyWL}Z7W?fg zOhyUlCd@N`w06 z6GPokKpy=qhyDH%PAmY|18MB5<5Y z21(=uCb=TFsZL`8_%^i02S_g)8DebFU|L8rLq9S;CovJH7%i$EUTN(IWB_hbq&8Nh zq88$q0wJ4dEEHrIbd~^18Tf5@_%T5wqaW(%dIpY3UI-Mn!eT$tgewt&i-Z)^c=ma? zPyFyokWBF5wv%8of`)0Ivr&~vh&0{<2&ahPJ0U*Fy<_vFP-P@MGEbU@!k;w#Mno055tIf*?{69HjDJ=UEgNL55f?raoy`MS3ctny6C? zBJ+;TZL7o7JC9w@#9{5lTX6Oj3UU)x_s~~DP9dt46BpC>>Y#n+anze_8Xm+aD4WF#QUctFiwBuL zhD|!iF&FbCX2{a3%-ayXn$_Mg=Vyd>X~Z>|La9;`A?Mi~fuhB(5I96}{J zkiZ*6sIZVvQ_20@xRrkfL3v^h9SeLoPPLybQdp`&(&r`F%T3FQfPasN?U*U(>~J-eJ25De`nmd)mHYjXQm-uM=$cKDIAdV~CqF_?&1@m24~Bc>FhG%pCc>6t6*0Ve;F(lW$7!ajm|v^UM>4 zf4o6AWq-tD#b3E|rSBV}PkzX6aVKh7tayhS7l3aXj&}cWX#S@1D}nL#pSZZK8dxRZ zN2L$_wBP9eU6vY|n3$Rwy4tw>+t%AwX~OP+0jBer8f43TYuhVA+a?nX+h762&CT1) zmJ_i*zMAA@u7=)}Q!M&wEDbRn500~q|4I=z<{_1Gg`K~qiAlxL)-vgWj)mXu>2qu8 z5U_1smevO6vgA)7TyRf^l2tuGPX|Id%PNh?hK7e|lC>QcZbgxum2b3z+C!8jne0CG z86KUs#|6=Kj}|KK)L0m1$BS0ldLQG8K){K65(y|c1Q8*bq1t7CXj#&4mA~ri9tm!N zzMvK^Y^{;i>Ik+V2a5}UwHHfs^X-LwT><9AYsn56VT#U3fgG3yhIx8OIp8mg)E6Y5 z=3Th&mFbSQ8+azhBmteCCQ!c^9sA)t*1*;xzSobWzk^6onZ&F78X9hhfN6r6^Vk0b zr5yNTe>s5W>)Y+BRTMXfQ6V?rhH9lS=IIoY0?WZ&I1deMN%(JJuDXxqJV zG*AQoC9V_QbmzDvH^~A)T{y#*QPe_4@-_CdSY}X>w?XRR zVz0>&e*3Ku;s%C2-O)zPa6aptY(ifTF&#|TH8=PB%#9`Tgc`S1DSp0?E zXNkbFU-(y(94hW?ZZ3VJeGBP!g#Vo>n|ii+og^3duDS~H3x)g7`pY9=K@ODpq<{re z=q)JnNVv6&epDK%y2>m_GW@VXiI;1$W!4Z(!NiC49Mj$QjkELiM9ilA+w!6y=TYahx-F{a(@&ZicSM@px;2D<=Oe(Sfu&S} z6o!5cw-nY5r8o@^#7Or&P`#181b=e0NKLD=e7LyKB!NJ(N2tSGa8NH=1SpcrHs48}k{vm<;I|Du$#AKM%;#|yKN8NC> zV1TP--l#AXW4s)g0m`-pK2tfcIQS}%A}A}@CpLT5N}~+jFlr59sK6~=@0CYEzAxUU`t{_!9s6B2He&f2U!RU{Y44Q zfv?m)_(qxIoZ(-Y`%9P9`z<|VH7b}HB+`h?y%}u~8fv#Hv*j_QMsF24OmeP`h8;gG zJtn8jmljlIWmD}m7dGkw{m!{tc$2h(VtY-IylUUQTlH)9H+%{|==Qe$KT1-l1d14U zG5~fydxw>mt$IDX>KD*yZj(8n97{9Bx z_{bID(d zV~Qn90|I(h;T}A}u)v-I(6@=*uR`oC#YS?^^DBF$d5)nuo=T1XazyIjxz3=t__-Zl zM2uX_y1Tjr$QoZ4MY_-U;|+40$GkVjY~SU2lb84(Z)k7^GcjEi7-5UYNe(vW&)h~F z4e~Ds>lJ5elJCTFDd>hJn zT+|s%Cb^#W8%P%QfC>*EtYU`Ktq87JHyD~^m9xzRvY_a z_Gbg%W%O=Saj=YByjL*XCqDi0c0&c5G}Y!YT{5hEu^r?&VS;HfVs1B=-7p26aKNip z;{&ftDyq|h&|sWDw{Phl(WS1fvOJiZGUz~ZL~sbAkvk78F}&QX|C10N?VH#lGv&$v z53Ru`Wk$325CMAfm2Jml)9}O@CEZEsklh7<@rafD=i_Hv2vRIqdM@;JtL8(%Ks}c> z2PXV` z>uc-=P%nZ*^*#c0+QmS{LKna&!a!Wcuy4-J8^9u^l+3=qLo7OtLQ-!5AY8f zmaDzXjL&9-yI!r&M&LJ!dy(dvFN=zshXnSGevzc#0oBbWe0B$>yRvu&eU!8-UKpP_ zARc-c>|%g{bQ|8hQTI2Cmxz31lGNPhDxp4;gY_SpApd^K><88k@QX%oHu*7#a&h1b zztb&m54>JZ^CtE5SjJtk#O&~c9wk$BM z#8h_#iVXvnH=c|dO#@)@bNaB=qziybXOzorB%HvlztPUB)AQ2|y(*y80^E`YnjHDw zDC>cp5nNk@>6yqU8pzy`#Le>zgP!d=1;y;-aPJ`V%h$HANXyKvk(Enw0H}Uf+PB)gzwV~ItTWr z!Dgh7rp89Wb~rZ3pFW0mpb<-FqAX@miZHW7T4g^iK&`KHGzo03dC_Ci;iA>fz)W)) z1N&=vLkk7%teLtH-&BgN45A}~v8$3bPv1i!DGHoTCVDXgq84#!#zW0YyMz7s z6HpegLC?gt_4^>zVF;rJ3KPXOL9D56VYDjYXnO;@AYIK4FXD zq!L|GK^^5lI;BdH80}5aPPl5-h&@isDsh-FR*>|l>x;VW$ksJA4if8~Ad8z1>r9E~UPKy$gs$!5-V5oDewh)r@3w#j!J zU!#5QDbAVLvZ)%+0|1Q|yk`Iy-Yr(Ey#=s!@;6WLjmC)5u9r^rdzp0*Edmt(g9f!Q zPRO#cnJWV<^T9^S{mpLYFmt>Bp+n9v=7AClg&CcoOfT0f#fojXeXEs!qcYBv0gWRKVf@B7Dq|K^h@wMx)`F#Aw$0>%<3AXz%CF4*U`7g;UzsT=yxfps#iNbK~1Tah|y&+@pG7FEsP)6aDb-1WE zQUUo4$q-VN+){B+BFRZt;!oDmug{jr5mE>-s#*ic0a;^utD)73G>u${pPoU@X|rSx zje(wHXkzw>9{buc&i2GpX+flyp% zxf-I0kyr+h=rZgt$?GCdnojmkH{2hZN(PMjuqvOqG5ahKYUh$bw3l%V>gCoxq)bh?X2a+<4`@E#7Z3tA*6)Xy&$3bk@EfuwjgaI^w)!zvalOAczy zAl?Oc4KxdA!C7h803#DVuQ6)IWSI=V4D?9_;tLagPMZAw)%VdDX*dA_qQ0x2!_1R1 zs~buI%#eY9apRzt6R>^p1|~Kq+mKaI;;@~_$#W2y2(vi-0#%5mlEQYtXYNS)x>FiX zTuTZxC;$l#r}}78(sGCFF^P?$J&bmSQ4)=@1JaiL;D9JbG#k<=;BaP(4bK*w<&e8y1qSdnqiJnzNjb;;c z)xj)iWUx46r+CJK5$i5r0VDV=MTLyvDF(D?0?;Z|^Fu1xH;@m3VXg}KT73YGZb6k6 zEFY>8YC@^yDQjZ)*qt^FSY-9UU`>%~3#iib5w8ZF{d5?1K(&7whIhrTyW}y!cw*vp z73Ld*6-RX%U$ig3?f&{gDMsun=X9|Z5W+CcK0CBXBx?0>h){W;ka3T)=Z!i(`~Fpt zfjikwn`5!LrmrAh2}rzg<1Y)bk*OU?Ryf+v1ASnxR^tj_yNl3t36UYW4!ZiiO0ps7 z#i)8mFVsit;Fh2~09f0N8vTV+RQrJ8Qq~d3n|24_=axAluscSJ#-z;Gh=|7$5zGqH z;^`STE39VV-ChJTjR(Jv)@W&4*}flaI&2bbDrESSrETDZesF=07o0AeI-j~innaP( zZ|EEv1W(LSfL}0A&|~EVT@2OLaExs%&j0pcieh((9~{QJ6I=JFrcStZ`cUH8N;**v z*T!jox5i+9mn}*+dveq$`m`oT>Px714bys~zH@~V0e~4YiiAvHR(Oqx;Lx)J^V)Ty zF#UYt9YPuNkrVdi>O{zq?o6M4Zy}JRY_jBT@HgWlXZwUqfSLiQ17@!LB~M~AWe=pX zo{uoRI3fjdE`KxIEYSqT*r~}=6hkT}6F@Erg1H#B_BV~z9mkn5(0l?>r*~M1X#}zR zffOzgFbwom=sPA^?XlrAOwyUvE+PaFTKwkE)rKH6;BTQ=dt@;>392i%zq|gXj!kM; z%~cWB6{mhTN{k`yR|P2nsMTmcSLWKZeqX~^9NK^4GpnLturV;UVu<#JRVacKPvq~< z5aoS&sSrM)7eQ<}h(_hf{w{*Z)JI0{zb{A&xUP=EYrirr>$B>l11f=S8CRTqQ3X)H zCf0(Je(JytRBlaO5zK*KG`zen_S5d$*a<2I{Gv$ZSkq&EPGziyWf*r~WJ~XcVPe(! znxhBO()M9m-*j3*C0scTDvX?D{Y$>=F7?odK+McEE&L)Fw2*W#Ke}^eNsW9$A4Vp} z$@hd^GlQ_~<~hC(QMc(J8Fqs}eM*FgAR32W?NO_wqoD{6StJ&>0Zoq4(S23f7R}v& z6v!;QM`gNh^(S!zlr`*ug1!^5Wu9I+zn?C9PcKf)v0RdX7-2!-IjSwEzm>n|GWS3k zSVcHTZBezL{ERGGa%7(IGDopg%k#C_1{550xGSDX4WNkY6w$@5tTOKav>;5C`77R@ zGoq*WZr5+APQx=*#S|+nvebj$fBZX-GLY6j9{uqXH8orY=gvW0zbuQsAwD`PQnL7_ zpb`c}GDPZdZ36-fnbjP)tG@NugLfit0PO%aOUNgJ%esn+7z;$=opX?37yH)L@d;?}D+@(d22kG$EeHVj+20l~hWa zEjCt;h{ZJQ{=b6%i?4f%j;(9gMjhLBGGjZLv2EM7ZQHhO+vbdI&e-P8`+n=+ZT)Mv zwGT!eR2_|{`lwc|^{d}E2G?gK_Ld>Q4)lE*q0fPTbNmvS9%sM1Iet+=TbmegMBB)I z@-RGIin!iZAt8r;RM;QA7-D)OnlCbCGRS<_1p*4f@=%1EWf7w*KJ`YvSOTTB8wx$W z*4S6Dom>e{LaQM3qHOW;CXEPqjH39-mHL`v8kd4#>VAp8bOuR%>u{*rOAg z#jT8ndQWYzF*K=-MOn>A}B>8EAE$<@Hvz-{<^7 zP+ffSX5~y5g20oRj5+e*K!B$VoZDl#&rbX@LYNHE;L`K7?}+ADRS5!qMdqig^+0zi z{})$~2x}+ws5yVW^*|mHMm`?o@s0+0%eBY z=q{6JLV;^YrNi>`?{$y66&|S=S|wtgJdE=jz*gR0$oCMgcSxE zqknGgGCz-G7-wutXRj~(ASdMg=wt4KCc^=2v!Wg7(LI^9B+xM^K)KtNj`R)yar-9Q z9G5rIKKL6590n{<)r;oKCn(QBQldR0`#eplM?_|_Uo9T~k>kr-4un#eis|%CeDU>l zYt)7$7w-3Ko7;n@qL73-M|4}KjNg)UxmXZyg6&;W9c_|>(Fd3f}o;_srQ zzYrUWyGC{$q-nZ4D>wceir{2n&oIPsIv4SCwcwaRyUUS(x3I|N0m^$7t-Wvob#AVk zbi(2ntPkx?uUK)b!33g;0mrD}Sc2@VSOET}dShEA*z$LriJZy42liqE=x9yB=4A-L zir9y+LtyWk(5;%g8`ne%C5UyEroTpXPr5Av?nujXQkllXCYIYOR*K=>xW*YHYG|v> zmZ8vMsy&~J)KPq3+B&DK&z4UEDj%&aA1!tiWiVCG08)2W#udC*+XAZu_BHl!<@r(h z$}fzKBGF_NWgC^|Srw9@9D$W#v__v;`y~1@=5ZK?*p^SFr~%MY)6ssY=#y%sz6Q>X zIHhgBCb)pIlaQA#hLXQtaYgrf`XRHQlTk4dh5_H{#-{%fX+_e){32E2w&7DcsQ83m*eQ~h@$eZVAUU2+Sj^m`hl z9vel4SF^kj!PDX0sM#_ANQDlxK3Yb+e2Rn6@x@?#fui^%eT+OzsLbiyMiKTc97c=6 zjpVbGy^`lId}-rCj#b5whz62z2)L|+R3c@~V?r<90mfk^W!T%PZO_acX2t!9J>DJ#0z7QNmPHxrl5vI zvaAc8nH{7mHximHusMrRG)+^iWr9EMSyrglJd(S1vOi}4Ipq6EF3SNMYbH>BBFd=) zCVYUpYM4wR!-4F2M85#Rx^{c9{fpP;syN#4LG%-x3zmKvNkyT~^u3MQ!a|^rwvlwy%0Qw!E=^gX7wGr}NtrFXY`FtLuHkVyM6dNS2G zz0T*$BLv(`g$8g>mOLL1U`P^!GA*(OJ`%-k%HNGxuuM9B!zl{MJ9L`0#%ETqezS@h z9_yKwrI@;8yYav>(~DqQ;|+`7PZOD^fZ_za+5mCj0_tV%>f89>ZQt@egvdj`P7xE- zM-Y_}2=jsXfH^cS);bm?-EediK~0UL^*JjEH%GIt5q8DYocPNu%QWU8^)1Z$Hq_f% z^1GXZHlbuQhouit1wfG^!^)~Pr1UPqgkk|;Lqk9h+a(BqnKEz_q39Q+V%CU{PJ}q6 zK=+yD3!}`a;>)0Rd5RdXbZKB~@((5dnsse-6n>j(NYO#*? zWrU4)8EQM%T*@CL_0a}o#%@9Ohhb#-xbwa^Y`z+PPqcg$&Cwi*Nn8z`8dFh9+A-CC z89cAHj?{jvQVBVHx|jYjF)FP%j_y z`)%WOhLIpciHJe4u8}_6ZDWwU=g8!5r6HC?eGO1IK0uO1R_X^Vx#syTT;vcY(6b9M zc}d{1UcR@IOSPuQ6vi~jb~;dZi~pJ=Ag@dET@$HwH)oRDf@AlH6uwpI0TrK!~40_h?D`~xT#>*rp&<3Nbw|_9x7o;#KIxg_{TRwg23L36M_~3EE*1s%+ zfEd9x{^Dd^eFAsI&I8N-TbzfEu@2#ow2uH?XLrd-raF)`=QuW`F8OTG1SKu1DZ*-e z#v{@gdE2qPC!QpF_ta4gsl#1F{cfxz*1(8+_7Mm?s1FM)+!%hf(ysB@KlSdFDWTag zoz%h)jnvNOTq|hK&CIl0PkmdN;eBzNv0s5K-#hlMlJFOH5KS_P_{d<&c>YCm@Mo0N z(Y}*}BI*(cDTdpcAsT9avxfc)yyC2Fqr1;E3@Qrh0hIlwp7mdKQ>iXYS{BvpBPH=f z4De=I#`bJsiY%C0_i~rCRDB4OSDae^y1wA;lfY<#OwQ-+oUYHCr-O~cLL%7ob9cmS zxyBf=MHoorF}vyQ9MP<;@RQ?>*KJe04D;=K09@UKd~3)QiDd9RJl6hBSeLbV93KQ| z^*9MpjY|yJ96T?odk%^-b|i_^?88eY&|sba>lCiXnKrw-c=T7{6;6IUxud# zhJ^F5$Jt=coK5fbC#0$F2e4oc z3g1R8a1j}GVHel-MD*+8IfZU4a-ng*DSzSY37>$331K&mx*t}DxVuZ&E^QXII(*0@ zSN=(v5${c}HkraV_P;f3up5{j0Riq^&vTMH=|-q~*Q>>wC$BYvf12z#D*>z^(U3^i zU1+QfN(lD3W6evq+~A(H`02yMlHPt88u7VpaPoK%gHsC(%;-)=Y1i4`jn`3`YaAAT zf-D(frrNpYA&h$0^OdG3{BOla3slus)oZrtnA_fXqPM7P8q}8Qu8tND zY4y0O1~h;3KX>I<$f{*iWT68wRQTAnO6L+2)dWt{4U8FL1)w`GtT7`kJs6T=*%5k< zp^^qkbR&H5Xza=!Lm`oROo@XHtyd!wUIOtAmk;^WU-r2xZC~E;`F1|6mmz2_Kv-5$ zee+6L0xCACw2h7sGtqb4Xh|lVS)r|AEWQOU(g^b-jIX-?loh1&&JuV;h+;jo8VvU` z3rdjQy@O?`d6Cti#)MWcXcj*3w2H7>hsN_58k{njq_pI&SHHw)oa37D*1KSUEP6!E z;A_$qAr?QuM!W?6NiFOkjy%bYe*adRmFr+ksz<*-sG+TRG7 zeRW(Y9GA}01c&&-Xs4OY}ixZPNd84 zGV{~Pywcw$3hpyYogFu(y%h|cnQRafj3sFL02`yCc<|p=qzU&vP2l#`sG80aH=Yt8|_mw~- zN%&3R1;AcYZo^3r2rxE598iVVqSFnnh-Bm7jVbeX@JD98*Ac*B!hw1ea@>K8FRnW61|05ys75S~Tw`RHLEgQu+MS~YO`VJ3cok3f_EoFkCHt{nG+oCbNbo8;qhupA($rvV@f&@v zuvo9#cgQMc|2DaOBTlTE6rkbWNxMRoK9W@WlVsUgZo|jO;remioq10LY~wX(>_{rR zI&7vEn?Io1)8odMHP@(25cikNBV{Q7_W=(-K0YoLUIHNfv3qwk`Er|S2Y3XV_QzNr zxwl-G1Yw@t1_+aj)~g#V??~y_7uFToWh*MZs6*?h#e_EO;wpGIRv~c{HRYI43N_5l zT#_4VvPhuIP#O5LhQ<7QZT(&HLNt%v0^Dxh0K_Y$*KM-1hs69MpMXnEva}7QH?hU~ zd0Nv4Mi_jkK01w;s#hPMnlo`G@XQ;Hs2P^AZEThKjx&Q)tatvY5-9E7g zM?uQ?9@++p+CuM=jn1XtDqtR?$~B!Y`>T=6FH4@rQKUyva*DD7ru|qJ#Ef;pboi3x zhgKKT9H-bDsXO?Y>$`s658#cE+Z~Z{tlSXNeO=!-S@wGD>w))Yt~%@+=w%_V6VPDUA>XBzLT1-oj9M>Ick$b zijPi>Ks~Axrzx7M$*w3EmB?VYzs8d~70ASY_J6~?*-yQBRIaVVC!XtWHcJG^A~(|I zBgzp)d&7;*wLQA37@j64;6IOcK8_% zUp!ZW2vMD`7!Z5367vYFY5)E@vL1y`-_ZBp2%mqu3h*Q@rpoaS=V!iS(Ei3_LBtWl zDv%@f%r=#|3I2`Q&e6)8;|{TelQY-1mRwKTd)4+L?y}2q!ASGE@2n;}w2p>B2EMJ) z)_I#VNhN4|)GwSIKP`+zYmh@dK!9CX;la}dH~PTu5=>=v-THy}21yF2V-7tmMqq8% zF0Uff+BPHd*?cwDm<4^H40SddsVOHLiFLgnSs#Lw?@BrkT z6OY^?qMRFRqVnxv@1cy(uz3BEf4t0jxG4k2*_tT$=W~Y&YyHF$vH~ ziBk;c^=>P@iYe9`OfSI#yHDn)39OEO=`ca74w8bli!s4_SK~tg8$%Iulebi_LoVk# zKIE&J1v1Q=YG8A#a@^~k1{MRfMHiZ*7?CH#2TvNUOCa}(LxD$TaI1FRx*Y%YdRts@LZv0F6}-#WA~9?Stpwp;XUbrz|8 zj=}N_w`7Luf&5ccY{JP}3rm%p2hhw@1R1=((aF+=UKDb@{H~Df23D>j*Cun$;H0NVGfkK0iS7Ig^iX)?inpN~ zjH>c8(kvgYGhAPuGw(OM#rK!tC=F?l`-kKw4Ca-}VEA{{^kyaXDKbS%ATcR}(R**J zJokKhnVZI05!0mL$&&4!cV7d_my`Fb8+`SiCo4e8{g~0^I0=qQB+B(P5#`(B=ae(~ z`nqE`z_uB~J=|aQO&khjxr_2nH1*s1Vc{e(c$KXOYm%E}j{zh-erdZQ+y3qOHY>U9 z%4DI3A@HHZPq%SHJh(Bk=P!F}nZA5HpLSvf`0(Nvic|)4N?yD1+alet@nmeYsHeh`QvEic4px+>#6}cPc_f)(08y@RqCLk9N<9j*^)OqX?qa z+SW(LZw3jfrlXfmS-NiI$(Y+N$Dp&X`WO$-FH;<0Ovk=3CT6zHP3) z?U6jXtH$S{Al1~YbEXaQeyTWGI3jqLZbdF6z$Q1a=M7&)xBMscyPcwQF?zip+__QmdrXWmBZ>xj)Aap+@ zD&-e4&T%$GbFZtwcXKZ9cZ4jU?gQ3OA=JlWu-M42_ujE+a(OCldhWrkK|Wj4&p_*1s1{vvYbbKZ>7Q7C1|CWjwRLw?@H$$qb5J^gBVlyy?s~aK3K; zX96>^0Nk_1k6#m8`rrH-!~gErtZg?Y>TjOksX%^_uM^r6bB^1u2_x_f@&{#@PN2-g>Yc`?K--5Jdlu z7g>Pavd7y>4hrM z7ZX;W!@7xNBM`hx&CZM%x2dx;74-*CFNa`)%G7`xoTaUdlAr1ovTIe^4`0iUU6Lc(iPk=b{FkpWL*nAK(EaeW`oHIK zqUU{%PCtB&$cC)`z0dbl^oOr`HbvR|o!MHr=e@Ts%Hl^%cag7;9xP=u+UPTM8*$n8t;-eKEv&DNGCfm#>v=QLX%5{j+Jn_`}!Me)yVc#N(SA^hh{*rz6@{ppyK( z@XUR{D2&sgZK7Mk&<$B0b?Ss+V5?+^g`PjGRlq?~~r754O0CRSc@#cE+_oIU`sNn>5j#wOAg~1-jR1xZ@PbWC@)$ z;t7jYwr+XQx{CC$WGv%t!L(4Jfdi6_6|`ZwVF}UFT4Hsyt!8%_N$j)5BHDRj%&1NM z{dG^*?fE!F)3WA)6HKy=+%{DM|M7~e^bcQCx{De~(}g;2({{`qtkBS8!$6Pewqa8u z{^`c%OI_s$8XIb<$psN-zBBAW3J_`}vOC{`z4xgX&7=X2HVb0Lgt2vqJ7w?JXioUm z8IG96w4Ol+u@;PeQN9fGzEFkODvt zl2yqj8q5d&I3$?sPVD8c@X?Y?UZ&m7V`19HBv8UL2XEoT&IerdVajsR+-YyPIb*)N zf7a9$7ph3Lb?(ProJtu$S4M_aCLyVxa(RsReB~{L3`c-OjUC5yPh`STY^9(l83&CW(IL zlPvUIy>r>=hM+5!Z_|85s*YFfWIq_q3V&|qXB1ll4Jy)lBL~C}jeEmhEZF?ufksEo zig3|`S9=B|Ss3>4?TU1yzQ;hTfr)Yh*YLUkobeuoLqBYli@f z2DKi6!%;~Kh{$pi;_X%Lc1Io@G4ZPMR$3mshFNs*+DjG0_QcuKcOdl5vt^!x;KzF+ zU5=ke8)zT#JMkXI&;4?1d%vtVeG^Duqbs{4>FTacH^r^Yd&p^*j1kw$ZWc9*2oA-;nYI}R8$KKs1wZn^v% zZTup+>HzGK6Wab@y+ehNNB_QC=`+7I-uKWO8*eVJ(;K3q(_?tiJGH|y6W7@0&$IHM zJGr&%G3f!tDeuKFknMTb%PQ1!P2B~*Xw}WCbVyN&04$+Y16&senjC=S&YOKY5?(xo z8{f=gGi9#dCorOd71Sb~BzYqhFG{|>v21$hCZw`sPQ-Yt3uSes?GNgP;u5Xod7sh& z?o*{}GsGLCf!nT|cD6*x6JZif{#(26`~^qBP4U;?1XeT6qfB|l?WGBHMzzj)dj7CE z%44n=d(ho8#zvh2=BFG?jogg_(9@DZwScPwF*k@nSlh0MY*)!|a#)kv!uqC5X*(;* z@+P`_tNbsWPi`cyx5AJ|3BmLU@sRadFqN9)y8+0+aldn4nt8olvX$HuCh{2UhBBMP zdm+Y+br|>HH^ldLug)}j-ie#Rp?}~WoI8d@w%*jiZ|LRP8^K>RLk!RFowe}6jSd@T7E*N zUeX$fcl{kr0*$2=J-UP&7j3Zc>pD5d-acY}Z-@|uwBHgA63|KNG9n$+~V);n+hQX)?fbSpPml0!9C(`UviT4aQ$H&A%0td1{ zV-25T38sVr&Qqj0-KX)}z*Ts@M1Kk1?V3+jd)tq5&4WI&eG*3m!qx|`Q<%DLzGt+- zxz0CJ1_Gh*f{hOXU>K%q^bdG9jdynoKd~5*+lb&+3fg7&5g+JdkQ-5p$ZU~=F&VGuI%*n$dSQs$n=%ZG4iGQ`qO)#~ z>2A~SK=8oLB|{_cpuwc?nWYebr8D>rOOK=ha_ZcXKm=>H;d|j!O9eiI>}Up9xbu+4 zYy;FIypeT@qP+psa^$QIpZ9fzgkd=uG+Cq=Mj=thL4iZ%DIQ11uKJv)bY-RbEpBS zT^nGCylTIXrRgvC{z1}eIr%64bItDa?DonmI-s2g$a zObjq+0(u=;U$T{pNHpoUU;8n}zdtcWAqb#uq?mWc5e8Fa7b1F`c;5eI5|;5Ae=n%6x&V2_0OhF{VAn>> zf+jsmDOzt4?`0Es4+{rpFvJ;kDJ~*s_z3`u6coUXsI?m7T-or+b5H-s0yH?erx3WP zYX|jQc**Tj2pf6ne3@|pkcwJZA=R9ag6e?5E^HD3q_MLr5}1(rf>8~ciL7XBiDsaH z(|FUdbWr0D2-6``XSPKeO1ucfrP%ay6pqEv`*}+@vHL)c38^i5z@HpPdYW`9z)uP^ zu88T&a=*Zna(r>k6%mb=nHjSzWpv&83TOrtwPQ{=BFHi$`LFsonrZp{Ej?qZFo$R& zhqD?0nK1Y>fynnm$R;lc03AWSA<~yTp;DWUE?SrbK5ZwdTP=fy6$gb{Ap4o?_cl1L zU&tvr3c~r0!X`;xQ9_*|w(CnyPnT=HYHU5<38Agj3pB?DeG5eq*;MUJJ9YEo0 z{1;s55#&jCjjcY)7IP$p2h?Ah^l8N$@-e>4C|mjpeqnQ_D|@u$gzsh#HW1ALQJ5sV zUAbURs`f~iT?Sh@D@@HI!z@|@FVw@QKZD8$5q!w=K>fw7)>^AD4ge zdJs-wlEq>Pgqcu&FR6HFMa^_KX&yaH2b#x}E)c93c1Db*cn+K8I!@uBrdW}7bkRcV zCo0tWCNyQ=WRo}!Lj0KP(|;AnbHqi2N5|PO7W>E*#vOx0;-)N*@>w)p9=Bu(_2>KI zVeskEg36r#!n=K#OLAa2sxd4Z05zBQe59sjh+!N&_r6tzc}9bv;uI`h_Ak083=J(8Ht! zqWK1X?#%Rv{(?gEnrK)NVGiO4d&9dz6Q7Ugg^Pp23m%8NgC%#^^p3r}8{eD4X37W| z?lyisw2*7qx*9Hyi-vqkL#oiiY0~>zUy=ZyCB$QhjEM^$!max>h&199qbsTS6ee#2 zed2MjU;{{LHJHndMtQ;uq;+0tePg;B+{u1pKyY&ib)HIsuMP%>H86x7)K=LhdYBz+ z)zVe~GK~ed2VZYuRMEccS1@cCVa%`d7@?tWue^Q6r~Us3Hi7>Lw$6V98%%fWvE`3o z^SC$0u&ToU%;4UMt#?xW4Y+kOxy7}bV5}UhmD~Dal-Bw(A^?7JZ?InQVOE;dgK+Kg zws}8M>*65f2P04v4vEmH{|*GfwqpbS(cet*_x*@_;84UzR`A>MAHgR1JLj%W_8-Ca zthf9l*se-B`r>UtTyXQ0?MuWqQU4>@0{<0k{+rnz{}F6H|0UQC5SWTt>Q<<=Zpp9o zf#y>PyS)AXBiKZK1X~nh1~fdAl-_jU6DaAzQlB6K$P`(-$w{Z6yHhmS_`B%9$%C5Sc4Y@4GsWTxfl7>YFvFtuJ&6*h`_>zES(*rsmL#jh}p1 zVaoV}aa{TF9lS5~wL2l2o5XuR3JD7nE$~ZZP$}7HaDA`( zf{4f;*$@#K27w>JHjD7&Vn4BuP`_&@UUCg!c_M&_B%F&*+up07r7jN%Srj6>LA8O; znPXhr9{3~J@|mPhDUa4EOA>^^SW52csk#A2=cyF(=V@^Vl?vsHEcPcchL~r&4Qfj0 zucm7~Q(smAP~$66U5eW*8pI3d8g$Jf^dhkj-?(jqK?#vHyEd0rC`~7) zj0*`36i&OzErErx@=-ipeh2gmEvf6)()Nh1af|Erq3NFskF}dq`BPOHe^^VxW&N_w zL?u2P=3J_A1AB&zyczIlqZR??tOCutw>x+{F{|7)*_Un>yft!q%&3C

y23mUsT145`DafH_YJ|;2Pgm)8F-E_Td)N zwRkr{C1g_`uM$*!W2Z2Nb=6OU?>hMN?x^x>sJ%v;mB~ufP*&ftZ(z_f4zV+Ag@$7w zhUvX1pHtz~Yf1;*72xDZQOAzIq3}^GG9Y4neZ%X=kA;vsRs_^oPWw$g9bf=PL|*Nn zZ94NwS)&_{DLS-l!`CD1Wac3T0tNv+Y(^f*QXOU|A*mQRW-qv&S=%?m4m@~`uO;kM z2()d$+rrS?xL+aa+h1%8ru{()iOPg0-SMMP_oLOri~7*UqvF%__OVnnucZeluSYLd_keLy$udz1r%jzRv zNMF(9MMJ!|6UQz3*zJ73H?jfG81Rz!!xc&@=Lz<9Y7zQ8jc3SV4%;3tR9S0EzsxtL z0zs|{>(QU~p>|KyL<^Aw2@>Tl(ez*0qi7zjDx5lHBiQ*5p`sn9D{OSK#df5`33(4@ z-Ma7YFvP>`_>T8rbhTl@N-w!-qvElx?w2T_gD%*fx{q`x&HFMhCq8u7y)vuoY_(L4 z*9@&;NcF{X8UAE>ZkaWGpOC|R*{4%XB%#$D+yuvTH#ecZlwy2D*2;K%%7sH`_5Jkv z8r(8_UiSDtx);-@9k4laB2Cqlcn{K{u0)mF6RdLAh@Idfl?X|1aHf@}8q3D^tH!&D z_Bw03QHpyUQi1N zWyp)K8{o*^wJ9!!KYv3K_fuGH$^EV-`Am*rV5pbuj5QagLDoS8gg_*D!0`1_fo!&T zk*m3dl-PluCZ*zTQdm0(`3%&vzMpOuo9G+fQMJ&EHmxdFjQlqwlEc>gd>QhYtKyvV z47cRB#LmKp8WCc|NnG8sscybiqP>vx1AkF@mWRISQI34~sbTf;Wz^TE;4~oe4~A%l z_(||_@54Y_8|naBLxj(Z2n)y=vOD{%fXyCy)FIHK8uKDaJ?Lbda@f5ZiYx=Ea|xtT z=FFv|;~;tKVN%G{wht+bxRy2eS(E`@GQ7>FR=+7gKy=N9+UoGqelWZH00^)?vY}M2 z_4)REUYD+sX7N>_`faM8aN~|#Zg_rROnOie+`|>Vlh}83&}7uf^I9)=A2Jl}T?NNa zFPTGS#BJXSISK4)mpsx;#U}a|3UF-d1qk(q87op{g!_l*=+1I)Z1L0YGRkl7*T_-G zi%*L|V}#7Jk0-hw_BTy^d{GNzClhfZ74`kGC!ecB&etqZ!72K^<0b`24*0G+8YLOT zi*osimC)1y+3qAzpOjZW3ex4!rQ9Ou>`hfN!XOM8@$SqQDS5u#J-s?L(7lp0CPkn>as*+@`vXc$a~&RY4%N|So!04JmAyL6Y1!F;gL z6&aAXEF8>@X-5HAf~{VCt?vf@z==0)i)w;J3wOUcV=1er9gwrn5u@oE{pPCrRs2vK zO$u8jlA5gYCu%G|&qtVlVHp|_>uH8!@SWtK2~Xo23(Om(ux#ANyf2@nqVfWAaV znNgl-(YRf&MV1`s31hjam>Tt(FoV`=KKZ#8z~A5%>A$n)joET%lWspAQ9P0cJl!t# zo<`{V4Eq$H@cl-E1GG+Pq3VgD*> z-=9!6(H41x7#|gYcCByuRCwD~e0>A>CQ5eWPS#C6p zs?*w#tQ$#JEL&Vb&{gd^Gn|ZE!mf!PN_140@t71Yop=Nh-%@E2pRtP8`I=XYy3xug zaVmZUJH~Mzmb!khZn(OGme_IBT(jmfqT^kM9c;MvQKKA&i-Mx@IRqC9gbyYciY`ZZ!yd5tUo=5f0|6=l%9> z<)xhF`5U*;6iyB%GGEQwjZKy8g-6~cDi?H(z3$HlB|LY4ys9cp;z>7GRo_vRM( zGz>4#kpb06E8(jiQB>qloit*_t*?lr%rZ^OF}v~e0ST~Y9Kme0hp3IQux@$m#3rlQ zb|7$l6;2`#yG99{W6V7ZQK!#|M|M`q)$0m$m&Au4U%W-r)jjZ6l;d zHr1P?>776EFiJ`b*b!Rdk@HCb&z>=Xf|58w4C#uem>SU?Yfz*I5cEknp6yW z02CojDU^fEaV~#qke`P}h6Nk_kz8jtBannzXK02{t~b0>xjZy2-Qj>bfV+~Hr8NL6 zaw`BP6f(4=4W{nHqVlc*B0xVLyNp{bZ5dCHV~JHYC#^rB;my)M@^qHQ1))FaFD z`_}dxobXW3sO(M#TyWTDUir~ySuQ;u-m{|lp~me6-nqH1=An0FB#?HCLQ-nvkk~KH zjcRUiA(ChE`+Oes(b?G$U2E_oY_2V%u+J&RS2`s({1juQxASQ3s|_o)I>#cMt4Rg4 z$MolKM$Ka>+B^7SI5Ta}NmR)gokmhYJttG_Q{SiD9?$l3lZ4$xYV95IGGjh(u`5g( zwScQ4N}2$ocH%@npx*(N{NVuiFB|d1k={g*+ne?} z>B?fZCi{5V!_9In&TY$H>Vgvc&$aikd6ae*#OS);fd1o;I@Q*bqa2hMs@`Ysl6_)3p8$GH-@7-#t6sygyCJ7Oo8oO_CbcZyY2V^dzAH7}XREMC z-drBYkp72561ex`heWI@8+Xv+;pOPj$Zl)BQo^Ep#lOq3YT$-7a~n&Jl**jXoDLu% zO<&GuEVNLx^x?jtgK$!L_=>6RP%;{iRDGXR5gto8s#fmnRpsWo6K#FrN-bMIi znuuWdZb_tZc%%8G7Q4 zWSk6DzLlKFv78p|-uqmg9)@(te!*N4MZ|K$Y`LwINDz08cBl}GDwcK@ZzAd_G=oQ?z`2ll;y^KH$mCz1Xx}B(o$R$#KhuY4gZsa|QFpFKNd*mWn|S+v)IrU>+PryRyc(>exPDS3=pU6W8!+ z>tjC;fhCeQ(2$>_$TZHgYC|h2fQm*xy~!^?R!tSmScm#BsBVL3YW~2ea0#O!V?p^T z!^&C@3jhi_XB8i+C;lao4~XqYWYO4TD$O~MBMj?^hu`!h%WnDnl45`mt-&IaVSPdi z=zFpRO+3^5rQBsN<`JzMUJ~a)Ex4rW3KX+PA?8`7y@v-cSBI)taQbE(mC!RM*ds~`o384=XpLURJDpCC68=2{{eE^C$}K^ zY7K5bWK3B4ZfT(I%YJ`stel%3$C7xg<yKQkO7gvLG&DFG*s9!Aaz;U-mz5R^wr zxRvrM5M*mxH8cp^jIGJ~zOze-9|&a2;ROYg(Y?h9+tOCjzY4<`oK-$p0dHiokablZ zzx#J2M47Y6;BYEZv{H*{4B`>7-OgrLkUr6`X&+W8FW+#!*to+HcHbmEf2?-r$P+>O ztUVi@S`|ju%(RL{i;h4J4y`nDA4c+le4MHu54&f{)zEw?XbTPy&6t#qh`&0`wU1B4 zz}tqxRzqckz#Q)&j{*uicA^!&ZxnrEnw?f_Cwr8`6iHOlOa=*(c(5zLyhRGS7`iI& z*-I3uUpy@>EX43NSF_rY`~HuXlxgXVp$RQd754g6wI)@5Mn_WM*WRiWa>}s=^X)aedkkIB8QnK~BbUC`zN(tN$8;OWW;$>Ne4~pqvgcP9 zbzC4%UyCE8nt^ePk|OGppXS$2+ZFa&A}PZ|%%i~*AKuQDp_$T-5zgU8G%+3lBo2wEsa3zP8H@T$9Zgy$(+|J1O`9C0*2DEY@ z1~1O+Y7%TmGbCd-b5NW0Jq`bSK13Zy<;s7*7Sj0n;;IoA7Pg@vpo@QET9mG@{NbTm zC_E>5sloOfsBMn7%oo{aY%-uBS>H6~7}{=xe59;dY-^0PBr&@aTPsn~T;wo+=*55O zfn$(QmwiIbkR>;#RqmU{8Vakk05j0%J~st{U&69UyFilq`So=y8?>oKU-Ol~A3%rR zRQakpDgG$C3VQi<9=nY=Qr*}HPOo8$*8TmU#q=3<=eV=ES63N4D+KYVyA}_LlDfRq zJ7M+tSVi{n8qc1%Y98J3+RLVAj@77Aq8S5$iRNl{NK#GKPGb7;6Q?FSx`V7Tjm313 z|M;KneMhgfO0?bFlK;cCr|62D-oP@UyMZP)nHiZT=k)7c{oRS*#Fi~va(G8-sZRq% z)edW~1qDUK_x1S@DYe2Z?2pah%rSE^%ZsgoPd|wxY#Zb51-slJ6@Bsfr;Rd98S6I* z6IL7=4C(Z>vWd5&2Oj;{BUKN&s=&SQtRJ?D_i`jZnYxTrp3!KHbx-EqzskygK^~8c z=q5w`1T%LkTB=kgyCN(dzrI+*eIbJHsEUC!LV0dsANj4qRI_`^4{=ljifo&};*F#sY+rMcyjIj^5jW-t3%F6qlN9{S=F1LL%2@#iwB8u6kT?hQ5 z(Yj)*x$rXMcbP9hR$$)fH zWJ8;%U#FIR=s}iT-j8^YGYnjhnmF6z`7wZ{c5T4H&(sXw?-CyU6M4M-&C0N zzV+~ZjJ263CMigQ{(C7YW<)8cmO9hDZ$W))n_3V)hsxhqHO3adtY*?lNk`67rj1^VfM!`sz$&O_ZF*#_COGKFdP0WFo=8{>fs}6fs6Jn|#rwP?1{#BT$JlJ1JKHYW%Eojt zC3Oy}un_>Cl?T0iAa1*k>_kd3d;hM}%85L=_;}%jsU<4LvIVN~Rcx;37^qMCp3Rjue@A-J;4!p4CJhrc( zVeKm%<#;t;NV#J4X9~IBE2#oe29yyFn1Q~-*H-WuzaMQJ1?lAVk00mZFy}S0j-iM zS!!aL3bLarZdb?7GQJ`uciY*|u8@X}Xy@;}Ump~!a*gc3E zSlxy_w_+SsBKFl6PhRP!hSzreGKD@YfYgW1(d|$NdYa{7)?bG9;#Zluys!!#}3A*Cu#Wx?R&%VG0pZqQTfRRvN2o?XGm z#%HAQ{doDM1c6Xe7T~6c5l*Y(ZyPE(fa4`y+&^_yFON*lF%d_^XxdRGb%I04)M(C$ z>9pQg+H2T5pNklZyurwWkwifQ1C^JJyVo$MV=~lqq;I z-`sLcV3Wem1VnH^(3|hv!V<$ScTgs#ijeazWKb@sY3U)w_OY{LO1t&@H^-T?+GjhwD#caO*9F?)D&BoryiO)>jbp38SX&UDJH$4F;e*IdzU{t?38+r!QWH& zPolBXMVX6rll3BV8p5TU$UghLH5HO*)ia<;cr4HT=XZnmohMlY4gZX@E4nKlu}HXft7 zNXzAAU%1@W&5GX0W`o26Dx_RjpJNoMG?oF!*LGb`&Rgritzu17q$0oIP8qNz-cmT& zIdsWdp!0Dm4?!oR{*iDT_gZ-6^LV^6&FNhu<}CQd#B^i9mY%=7Gc4ZVRjL zy&f$pJ$7S4mUmLG%H3wgco*hK=MEZKy{(St6@nAb%E$;vqXa1ivWU0bW+t%_E!L6l z9=AyP_LYc?P3c}VL__l+kbX@F5N?T7)b(h#Nlf}cqVNe+an$;(X3iD{)ZQb~hzpd& zV>gJb?n>`ZK?=x{^_$)%60h_M%v&TqppC0PjUPAQ`nL_2Uoz+Shb@e#DRD@Ym_P%5 z-)slEAD9!U;+R-djtIzlmS96RYH*p}R=`TsD=}M*vUS$3R}b}Hwt;`d^v<=Ikl;~o zcu4(Y1Whq>Sat`7c_&yUXMFI ze{_mCR2EAVI=z_XH+NgIqVrKr(aGAQiV4f^K!AgH5L0NOXmV=5aXgop@&}o)!#z0Y zLmEo>c#s(m9UPuw<~)%_hQd=EBe_kyy!~pULLVjX_`=SSea_$fVcN4qNHutmRQP;o z^hizG5c~9mM@-rm{XC0E6uuHZwg7`qU}3uSOK_ZnVe)8(sigy5p6iV)E$kjOkk@x9 zFUWZFQlZ{2i(Wt;^;dQxFTFQvIpPj-$H!89*dAS8<0It}WvxLm@5&G0n(Guq3S63{ zsLR`uTA|?8P+wZSW3BlclmqxEWTZz&S(SUC2p3u@+`Ck+qDSJ$dTOg%$SA#%E{`0x z7r)i-d&a)r+7E?14rSk%#_)hJHY7QhuAu}q-tO<2mOj65bbXfC!M~7Ji#Uq_%56)X z*TC327V-iFPP|Kw7kX?D{3EQKGWyF8KP^LRlH_fEDPcE6A1#A@!Pjc+89GxWe4>1x@<3t#lMBjrp? zkaf&h$HH0>QPTnA*LC5xA{TGQjM(%mG0Gpm(BYi&@d*209BSVvonR6D&e3_^B(#3a zydbWZ&THIZoM5o?>^Y$A`FQ zzU^G&n<3Nj&pUtKm{l)0Y5!uS98FMU$gEUyJ1|IIHLl<(YfUM3o~T!l4d@B&nJg@Ao0?f?mXUfkdrvbK62b{<>c&1T%3mL!pledNN zA5sutM^^~nS47|Dij!2H^tXN;MZjTzF7DsK2mHqFRbx%~;?Y@Uaf%U&>HLu+ed&3P zD^<>ufaVuYzLkzOX;WY|WJS{MC09ah83cxG7YkByj8h+R0tDUiF)_@>4;m5ATt#C4)f=ec- zMff}m+#|Hf$NQA7hA@fX@|F(p0ts()`>gI2id1w|3J&`5l_JDx+O=M)$;!yLP5G$k zWY`-cfwgxYDEKJI?JHBT_8h~4IW}8hIJ07Z z@k35KdkN0VY0j0H%ay=BJ_PT`*~Kq}ekr;j63V$& zGlzZjv3 zbgO1Af#^lm5=Q5uex*0z#!82pDYCAid@b6r=*doV?Fyie`R^S_m!|jv0VwZ26i>D+VcA9a#?hPV1j6wsI;ZUo;^q8IjJUs#j{l*$LMWq{T@5Q%OR(1s!0|8v_nm| zI))_oqz1413S&TJb2_7 zW43HJ8hngQr(Hsvj&H(5wV4*-Dz-l55U_5~Buei-Kj;HmXe^&KG5thYzxu`Jv+;sk zL*%w|kj#kNp+L^Dzd_$ItXKKX!Y{(T@J+MeJTHKtjK)%&WB-9MA!R-e3&g@j*v-Xrk*G zR2r+VnlEPw!l$v{V#+rk*-buvq|X!fP{w!U^KLsoiHbG);EAvtyc5t@gNN6*26VY? zCRHe9qvZ(qdw;*5czM20w@R$CwZ3f0Z7&-UY~X#Zz-dz#lHyKO6~}^wgZ5 zeAyFuzhRSx^@N&Lmo-;v;bM|p0yOT|OB&$JG`D%}HBjuO00V@~E{!Sy31EP3+WHHYNJceHdRj zx#M~((6ZVSkLOE5>f_kBhTYg#j1FTH@SM@6DKhVtfHCMd(Z?$6?7EcYGe+MbOsL&f z^q5kAsqLr}BA4{)+nI@J&NIWH{s9;1QxJ{L!o7`M*3p64DT334j5=jH7zPmKtcM(Y zp?xBv4fdHn=!*c{c#%H~MEB0k7LZ4+XhtaPNBY!ZQDvS;;gGfaHo4J-(nn?ykl8|= zO0IXw3q(Hd?}<-KFtrU**Qv0KnoEVD$FR3-(b0Dy-Jd+8VMj7}NPTu*pCu|onmPk{ zFfEXrNwIpn<)B(cpF&8f&0E(BxdRA&JkS~nRGp!puMEcWo9tKQb80z^KkvZ|fG+I6 zC=@4Rwyq=FO-#igBz>l9SV+ZmQ%?jrVb7#Z8Vn{WLKt{owZ!eYuSM(2a3X6U7*ph8 zO3X+xCR*|nMgWR+AxZ-8+D zyOC3LMC`ctskCo<=)v!=ps(}D_9E;DdXTWvTJ#yrF{sTXxvS$TpHTPG1cq9~MI0p{ zI_71kZ>sJ><;quwmUGXH0}B5pTq3DA^f+%fsOp6{@s31CYdMn+;jcUZ7`e9{*C({5 zXRe9g7@WZ#`=xLIs%HEKRjnP^b#LROdT*dQrVRXs$bQE*i>_YHiz{;sL7)R;mv`4n z8QLKTK;6UL&0xWh)QluYx-me6F%>>t?1b@N$8Gvqw6#-G;~x9OkOXfDLhjpu+4;^A zB|GmFktq!UL*9}Ux1lS?u_&u~Q?H7&h*h#vK(X%Gd`qB9x&2)g$T=90JuaSs|0I{Y z&}m=x=?P#g$FAKdt>|^W=dzo+ z9C#X}w+u_$ShIL<-u<}LF!fH{0+;%o<{%`$Cw3@|JY#U3V*CEP1D0ant$C8S69_Av zkacI!{uRNC-hsqNBu%As!4Zxi0FsHs;lebV_0S+j0z+v?c1ZM$Qq zW7{@6wr$&H$F`kxteZKw-^`p@_ndQo?3I<|&$FwZ!mhpFD&V=y4$~n4XcA<9hM!Ik z>R~w=$`~nINkDBSVfU)525!!WOWrJK6ThXLwTe)%M^7|YxD@MS?Uj86-z(1|+hhQK z@t|5XNlD5G2-XL6CF0Dl4TxLkMGyfECG?#GQ{vyi6~10%r7M@T3WbjvU#S1sGT>=U zu=+7FtIR`&L?zh9X?A=GL?#A1ylvA)QYM2|;?s?8SKfLzp&q$Xbn^IHOKPM7RXfOBkGMt!v;^|eg`S%Y$Y66#oZmY&TkIiaRy<2TlWwQ##~ zW(=lUoN|JP6$82oQQDmk<3PbzrdL&z^h#R=s!lIijw-8cu#Q9Nu-Tb4{BLX-5LZ#_ z(9Pm)Zj#%HJme8ni*8bq1GcC#s5y6V-vJa{g@vJKy)R+X)RkWxEQ{|gH!7quaqXQl=nx#{u?Jn}-!zW5*S;->HfH!tP!V082Bk`HB z1dpNYRdUokN7ZHCWVZBKn#gomBz*BUWkpEkIG3iiA5~$qCaS>R;D$?(ivn0`U;QWE zh>}bfdk;NeSgaAFu_N=9tV75)_`4PP+%9LcQf75>maPum?gMp!za9`z`NA?Y>p{x@ zLMk!E#A!r=tbT_O%bd`s(?HmA@hOCGUO9Jt^cnzaa*2QKmENHPTi;wu&U~qxHV9ZM z$MwItV}a+jGxF2TEJwBk6OAgUzK$qZ&%nI2)^m0{6YwT73w>GI9xvD6a|u0>*g9`Ye72JnrdKR%YcUX1?OsH}L*C(E zl|Rsp^Q&=&(Ivp#sJSBV@Z{Q~J#hPzs1s-* zfF$Z{(~j8sijkb?Pkt^BF07oH=psPl{mKWqmQ5s>$lPl7n{6Q~<^e+R^*}0LnAAtE zV_4oR=fol~Ew!Z>y?&;^`Ifej>n2}|!(H8S7%O9>S{l9KG2d#Dx}mw4S=0^IFa!zx%3ZzyHu1 zA?TqrgDS#ngleZ7eZluWT5$9Y;hN9GFuoo^1royNc-N2&z13xBRwVBGxP{)XZ3V?N zh>|mS3F5>e5DLFDSZxI{Y_`MMOgw^4i;~9okzeW*0jbhh3W{R!Rs=v34bc8LQ)64u zmUmp4r?>%n|I=PLVCvXUa4y1McWF``tC-imDsmES)#OSxAX=op2Rj$l+S!q0X;IVY zXTg1-cYmB^NsEgqpmcc-J8@?ZWEap3GGrp}AW7X?9_&j^gaVvz5}ta~p$e|fCf$*# z`)baVK(iIVTV!kN(b6HicAJD&HdlI*Al*qBtz%fCClw-6-)0or+Id1cq5b-9AP^t_ zclulyNc|x9OBJDd*FmFELZI5do^`Cm* z%%+Lh@!l@SPi#b372d55jJi<0zq4EdX$As&hx1R^XFz#Bvpl|ad1G_zph#Wz+Ck;0 zcK0_PH25mr<7o0?Z$7rYfWJdCzBvwNrr;H&NON@3(8cZRvH}F!{B6)95f%h;ULC*a+23 zgbbDn^09nJ1lo&op=Sw}5(xeenIhv^d)w_EW4v%tQm-V%qf|e^$_lz!7%>FObV;f) zJ@|yP7P97bvUDdGL1>%w^;V)uaZf`;R+ypySosf8uqgykBiA<{Ed0;K$4?b6wgTR_ zMkzB?eF>d`qTPARxn#}b(oIs-d%GC>M&Y{5EkJXyqxx0-J`pfHfp_aufo~gi=bUo; ztoO=OXHl(;G3XEOkP!E0RJD&c1-|pJdJRVXWkPJ9MX4gHAI zE(6z0Db$Pn_=*>-4Q2)tWTzl_+2}CiyX?Z~KjY;VE;g}xfgYS@kTY5_!(mBg(0h!A zKe!EEbwZ^t3QKre*l-@$M>+?m(#a zb6PMTu|r#Z-i#5S08Wj`OcXs(;#a}Oot-VGt!xBkMH|=3ELvBo{buw1w-O4KJaf3> zO)9t{HA@qZCqg_Az-xfl(Mh@o^Uywx3tNL$3GM+KSC!I5v{DyEj@tF`CJ}Jut8yfh z<5LCTq!*sTM2W20;g(YKo-o`)p;laf73Qarj`{H#gj4>rPN}UN8)Hbooe7_b0Yy_E z+@tNyI;erzR=YTh7ST%l4wr+uB6~A;(Pk8K285KYq~LubC^JT}MA+d8_Y3egrG{i1 zfQp&ZH`QmxkfI2N_{`z}@snaKkNx2T_B|*pFk7x*LbGS5^F=yRk#j+yjqq@O#&2*Q z{x|k9D~QZRgjXhg?U zTv{hRbWE>{9Fq`3T+N;Ec)A;99Lk)SWEC^(;$j@e?lU`f$wGv;dpg+2=FJ0Wj6t5 zEhliX)xyi5eJ(+7)Xw76K(d4aU%kP1`Nb&X{S{#O7JB^(rm(+{my;ZObZ`|6XS~eQDRqK6Gx__CWTYQkFEKUJA=-Ma7SDCZadD&oi`J_ zzUd}BaM;&KMOK{1FZ-f7KBsLWh@b;#kE-up@xVPm9brd?M08;Px*C?zX!zV({052x#IBjM!V4`<>7|qJtA9OEL*+j$} zL|v*6-y_!cr(>;J#LdOv!(~P|19BeXQ(s zzr2`+eAX5=oP6#j{Sy65r^*RX@Spx1Qkn6|{=9zNGTuCL=r~-_75ZGdxv1Y!|9F}9 z(T50rkBarl|E)`YLr45T2XUJm3+x-Z){VEu9r>(l028jGQR&06Mf>?`^EJ&Y`D^&h zXZzo0-!>?c@0I}p03<;Czx&QA8k-o~8(SOx-`=x-OxRgaowQG&1w%d-1V1br;9?#qe8z7)7nKyZxlj?Rs+a|th37}m)uNg>iIa)#mC4^vPSoN8-e=^3ZYNh8>+s=0n z4G*zuU-BAuWuNuLaAOZ|o>bS);p+7M9mhos4$!x1w$)Oy@C;_Db=K1dGm>1(y3^mF z35t^O4b-wBqi7>ddN$sfN(8>xrOA*gpIP4+QgSJ<&@;+oW%w=Ko1bPjJ3o^Qj#?rq;e_Y0FM`n*>boM?F^wd_RUVem=7 zmWF=-0447r_fsb7j)TzGWVYzu2r=SYgN8_feAQZ7`YD!xQ9UpKdkADX_c&>Qmm2hK zPsEP|;1Be|S4SEAeh1Qz;QVV4pI4SJ9G`rqJGLC)Ya%EVnVDO0O@Ziw`)-In-w)Uj zo93a6%)VX+hfsGY>?XGN>(_@Ym~Q1?v5eKN0I!*ct;e3QKE7U{4Q!L0wjDF~gasEL z0C~FDR}6KH$RJDyW5hZVxV^UyyDuy&n<@Qb{rtZ{umCHrf$CtqF zfc<2~937Z4C03v!DFT)=^A`8=VuUCJM0KW^c~gAUDn`cvQ4GedE@IzlOpMWf{vro< ztc|*wc#>(GS&2Cl=tmpWfNDZ-fnEStL1e#^b`_+P+I8>#4fAgEsn#<7H(0HPS*a%P zD@zP}DUX(?)Y4r&l6JObYaucUB)_ z4h(YygTtG7uLmrn3E3^4z<-q`bm!{u3?Kl2*OvpK{(s2wpQJdbs%^1GkMd3>cwQUT zZIA&gW;KifGlrLz!~-_iCL@eOAuieW_Bx7hkHuXK%JzE@M?&mT=aQq#+567r+YDaA zj-;#|GZX`m2Kmr|eRwvWkB%HYW0It3P(1yhqQ0Y$eJ^_2DX^x(T}kgny9d@o2izS( zh@CLQD7ql(S*tS4%=uCbg)GtAi=nC2=DBOD?W z8KlQh-0-;yntmqF^S+&?z%}*`nsSWP_qs_X##wbr!Onf-;zj6C>DSP09{f3_Qcj$TV^w~Af7~@^~ z9;r5S;WEMWIe@!NE*b2|N8|7Oo1ghiK(xHVp9Jpi_&@$MwaxQuO1XF%K+)kBBRIa; zf%9i(SlJjETMC;SI-1*9e@!d@!=7YjCanYL5kR&*vifc}p1|395o5m>;8ChrIaKL& z!jWSjuv*zxV zW2Hh0OFs z{nrHg8c6wTsR@}z6~P3hy7B4yS$KdSzlLW(|1?_u4^WwS5aV7$K;#Xo@(HrF?` zwsCMYH&k-6wY4{PaImreUm+WnmYyD`qaBroqopAym!zScqO1EezP=*$<8%@oiMi#MNOf)h*WQF;N@7Y}W-3~4e1bxPCYN^^nSlYPI{d=lqrEh3vZf*Rp3@e_;0+<0N_%nQV z^UkX$E>Wuvl+y_EL@Q8^BmE9NDV_QA>s^S{u{xuq;Pfj*!-^LN6>Z`&2p_-F0>MZ* zJr*DAwfAaw1;4E*Umk20SPNpnvK5X zGNTM*UYZ@z%Ayn9oDCRt>aGCx2j4joYP8v1-AWG~9sP+Qi)ljJ!|~S^3cYdXPgrY4eDydeud2b?vxd z`&TUZLx&zc2nFyU0039ee>2s8NyyMl-`-J|f$@)9CoERtcp=$;0{(kU;$nB%QbWavHO80MWe%+B}W#rL`n z7Z2>$qaHC(10c5*f(M^ABrK9+6WX~eC~T*TmG|W_$%9Bh19-uz*hY*B^5qE{Wp;f) zB!F<|=j@vc>n$|q^e<+&rEsX0IzzgJ1=o3Mg8MdM8Z??;M$Ug0H4sM$?8XjMw*J}) z z^xnDVtT#P*w&OM*z_kF{eLr#RfzQdrs-dF@_DTd`Iz15OGf~=ZTIfL9*T;$n?fAOG z>{$;{7-+&9lGf`pg2Y@nYI>2lY`{CHT7Cy%{=jgYbKy-4O|(Ce2urNP$19*$`bp_a z5QejKfZ9rUG^kbCJauV(Djm@!N6ak}gv&3uP4cPjm>_;!6z@?AG}8)!bt5LMD;Ohj z?rmCy7a4Ve;lg!vwo1-HU6yfu2GgAf;$UiJ3Y`x(Q)oZ%Ho}zod>nZ~(mP#w;I99c zG)(Ie1}u%O7Kdk#(?Q^GPGXN(AXTV*=x<8QG1^P7gwF?dTE4<1skroFr9 za`7^IkU@kc3{`W?UL(%mr#BdjZP+Rc%fr zLl254m=VP|Xdy0(-N-9oT}AloWq3t+e%DLPn56J}Q975N6R)5(TIDzw@dwVz{?YPLllh*q`}2}IKFla6Y6x1nr- z;I0X`nDU`LYJ(V;TET2(n9dgIFxX4PnJj0mr`y`3vY}ki(Jl*GJdo@o#|8hSMK)hz zXjY{%yiDoFXs4?Hw3D__Q9pid`$bE0HRVWQ4ntPi{inS94_~rTwTylP3;@vZ-}(}c zfA=NdZSqA?ydSGEZW5ItF<`pRkyPObp(<^lT$@#tH84nTEa}zz5r!*YwmiTrtw}W- z<-AHr`T>quk6sTm@_pR4f{$V60taTJ2qLrrcSd4>kvi8QC_K9GpmZanFKxKT5Fq)D zh%s;je}ksEefRt(Y>OJnP*ht_$PQCbJFOTqh;l)pk0D`#LlWsu{Hstz#z8KRV3Te) zklvOSL#`~3ppp$qtSoYW2cp#e>apk-cJC|X3R04x0NmFV#$oy}eWv?w75auEY2SC(cB&>5*`#O- zo~ntEoBXvz;}Bef?8TyK2J+E_XdZy=Lg8*pvz? zT!HF3b3R*qIu_7U>dwlEBeGoFLOE5(0!2(`!bST#`>+$(3X^RT%BK2G%t#?E>tz5% zff$|w=3Jql{`6dNi*F}do_jK$nOu5P4UnRQBsC7?;03|Ei(Xd%ML7T=2jVqV+8xFL z^Jr3UD{rsms^VOkbxl@o+EqBk9Xl#ZjbvDgQkH@R%{1IB>mIa32Jb0({mJ7|gJ-qW z_Pw>6rXsDEvXr7)d>_`7)8+2qVt`X^rm$`JHW0W{@J)7^aE|S0ZgAkG@waw!yl7yf zXk4~Ak`+D5X7Ev2Jne#_#x3@YeZ7O;5i2htI4=R60NhFuVVDkddD}qYwEm(jJ+K1b zfJ>L-C-{@0Z^W(`6TiUDhaGpLYW=fMCWL%KUI#bcNzPl2;oFKOX7=Zg@{UwlV|n@D zybAuk<1it!4}0{}tTG}ER57o6{QJ1T7pp=}|Di0s&*RGRVdy6+9tG?Y;LGCb>(qP& z5UQcy1o||=Zi*oJOK>jzRFAIOPUV!(?-MqIYNNJD)CM&p2~P8B1Ux@{mecT~^%+zs z=y3%!QDty$&JWusJ1i>4_$;dc?;qf}t`~Quv2i&eC1#wB^a5{mcUsn`Ho(nlo1Ue3 zmQ)(+$~z7D4xZEJ2%w7v=i<|c*|y{=S&M&MWt9EYCVHl?D1@4#3NQ=Pejn|J_??JCw5`cs*9n zTpKmB>Cr#s_paOFFy=N!4R1HOFyh9*NLFCO;1R~RWPUtK@=ut$7kixwF(DJ@Z}1pQ z$2s3m+YAGA5FqW5XF%00qXR&7jtuY2DT^QPEvP?PIyznfK!Pr3LygJPa{?S&)cA`r zqY6HtL}C)fIrNZU7iv7A5bz`X_Hzs@Mvfq+sYm1{%@xCpr>&&=8dY#CR((c3OQ)A6qKbf3qu@;fOQsjsK{e#Dw^9_iC zNJ=~lRH%IIX(S@LSPJVfqH-@SedEo$$qsw@2pO0qIpX0Uv6c%bN5y{q8xckT7)JCC zFaP2ViXQwNM&u%jaCQ#8ODM&wv4f4;}PU=C( zZ9Gso5(+$n>>Btim+8AE-Ry=#m`#<6@!r7uR`$5U>VckKp z$qkA5)V5)Yd}rrm+;K5@Y3$f9bc>muSaB(qaJx1yNVQwRtN4GZxbs}&9-Dxj%N+LW zNcv*JLgioGk=SmSZ$aKNM2!Gt-pCPMxHiTedQrec>7(;pMT^b z_w^k3l){ohzYCNlpW*QpQ_3Y#`BR9l4;pkvf`>?2zR7H@Ga*1B4^u((T+CEn0y?bc^pg@ zaGFUr&bMiarx@)WZy6JvaUMSWFrLyrGj(|UX2GvDuJe=irK`F^imHuCTM}C+{|^1H ze&wg4JqQpe0Dv<3e{-T?V){3~qJ9>W&x-Jw)!nz-PtkfQNDwP_$8KC7#%iUbInuar zih^ic*M$&jS>JBH@Y%^~15s{KuCy>`^;PmdI(VLhF>%M&iH39aPa&ATfUZ+V2XLgB z7QO7EdvbKyK;wm>g8D%n7|K18b}DI#;4lW56x1bOqB=8HwrsfINlbb#odAZhBVi`nN> zgalz$`V#@nzI)tAaFPo*i3j%NVjDx(R^(;yqi9@GmfS?Z-gAW~hwVEEhwTo2GXga5 zy&xvh;iBK%-lzat-nRsKFnlH|(m=7081#~h3J_F^ypt%rI724#Z(xEetbSE;HX4o) zJN=P3!|Q@##q2ZSD`-tq`VPL!L9&f#qf-n8yl$~;Ii=xPvCqVQ1Y(_cT4niLsik#_ zO|oyu1DtFM7{_Pn6`xR!-=oPNb%4yG2?q4)bRt>X7?_8QnXC2O1+rbahNB>a*ar*D za)M^V7=`nU0O6mY5Kc2mqgy{gUVH^q8gZsMwQ6D3yaLhg*+F4SOlLOchN<*oH4E)` zN2SRfDQdX4j0IMW;bpS)w+w_&~n}M{sa$tV@yLhaE zhGqDs8GDta&2se?q+zI?ff2i#?Nr80>gm3BOm6cqaTXYb_u=}VDa*iiIG8oVmx*v( z2~1gk?5UESCRlxax3!!ZS%JqJ1m`zu-*)f%0PG^zG4YPT11}@VnjQOw`)v%imHtpg zVd?g)Z=Y7Ykl}onAub~sLuxD?*>{TWzz@o5z}56{<*pP!G+F{;9A?_|UJPSGMio-0 z?DVHrIroTDtv4vMxA{Up2mV)WyYQz36s3%#VfuVzcr+ydTSWjjD=ig5Eq7Mi+~5x@ zOY4v!daBRBPUO+^zJX@|0GwpOr>PA~w zsuE%gc*H9ZW7hwWT1jrKm9a7mhWuMe=A8Uc48JLK4>7-(*p|R0Vccp0`#njYW+c5g z>c+vUYrvzEYr+x<+_n)+!t0J_hX!?bF1;D4K7v}w70rr6F(~eZwi!A+%*tJT$i+42 zKxo>hvAS1;ND-=-+U3&?n!XL98z}Tv8m2x^`V3OipRW3`#c{`f5AoRNZ!PHnVCU|2iv+;jy9F?hr!+W&|$so z^c%EJHae%-fPk~c7(#djuvBt-p2Xc|QrKlY5 zaAgg>GInxq+6f6Mfn#6o{S`N26QJ1mpaC~y5&m#`_98T^1}$Uokn_!JR$`NshvG~r zuJQ-aU)|?M>7K0K*To6`S89g$=c3-f3POJ>mK7#w+xXL?1YfpftUWGChf^gbTV4q)9{OM24%6bc#`C zMxq;?#Hg3F4iQsDe?a&ia7zXWBh;=K#I>1}eRtjCa4(SN)#TfyE4n|>jI?eqQlYF< z&$Uc0%4uEAx317i_C2Sjlz2&EI>Q(j4-2rK(52r|DI!F1`w96By5p)nT7ss()FLbE z5Cv{Urj5&e22SNg{Cgg$P|MtPc;MUQUa>KJnVe7=556L9u^J}Nbm%PYxe1|BX=`NL zKDtlBm1dYtCdp>RJv0(u>?@1_VN5SOKHMSKoQy|Efz*|~O~0Atg{(mXS?fTZ>7!mQ zWuLMh+8n_z)TJQ*d?YNtDyY4x7K|SEHo);(`~i1jb`Njh+_QB7vuK30e56J*<`PE% zw%$t?*Wh~}Qx$klMC$H@Eg2&QFbmx^sKYwhIPD#1fu z3#-%LMlKL%BV_7Tz4Hr4jY~cw>S_Xo+dL&q0QdA%I$_klKOm|CWLKj<)?xjdJy$G~ zR-m{JYjbSIC}R;`zPZ>Ovh|pK#7Q!sR1v2Wmg}MPB_$m*>3w3i1fiD1k+_el9qe?h zDDCQYY-PLLVvK=SveY+kJzuAw2+n)#zcTWTTkfXwYuAZiyZ%d=`JZ>q{I7ji#>zx| z?VJB|EcTVvN&xZXSmv7Y(hYOf@@wP0M)MclY&GCC#x@=k&~EU*aD3JaE)$o*s&gqN z<@eWSG`1|BIma0_C!ngs|o zU9xKMN!C&(i@f~={LrpCn=GR_&pvB$J=}r(s}RbrIwtDAgn;!w6aw>~l-~~5NB^aK zl3Q7A41nCCjaYTW3GyE@*o|)Fa4{b|N$MpSUNqTz-&t(fO36r?dM(t^Nyu-ljw`NM zwCIKx@K8+mxR^lYuuKf(WwbNR88xh3YvO+Lb6a58M}rGngWCs3AdHS5;>9y*49y!d zUzoY~$!J(Jyff;JDi_NFPiKs7uyQ@08Ys#=vrz@oJmZ{9Q+Ms4{u&X%#;J3P8GTWx zII}k&q=T!evQ;Sk_*)I%5QA}GSts5zdP@o<+1pBCNXqVO=Mjy$C}GP zBH6^h7(XGhtoD7`U7)z@Y3(RSDl%8;q(toa6Wfv9>s7-`(F8rfukBY3xnr%1KD}*w zR<@?RmgVsU4lt&As6b|Ph+3Le92Rc?p(qD$^=(i9HIX?6Bz0L%!F~MueSD8&x3!pV z2ZoScy?1|zMxh=ckd^T&)F|%QnFT?^+*R*QQDi5wXNzB;_99454~bDN_8bBXxFqF4 zP!*{iZZYXeqM+>r(qWJ5R5OOmTd>P%m@+as@`U_tI@NV^u{Th6hqkhOWVxPLX8K6|3U;P+e$@k65X2pUVT9HrH# zEw!1!p;!vXdE7_dfV2mFlN%Yo#(Jc1YH)!jht8&ez_WwBYcT)(y3Vvr5=dx<(1-a9 zb5(|o>k^&_lv-;2$l301U;9_c;E-drvZlpAonwMIR$(jktC_g_7VHGvBy+POwH@>= zwYrYmzomp;UTeB;UiNNqPF8mFX|HcU;|QjX^-*JuqEw_y<%SOYNw_+^QwR04aA`rO zx*Ywi<#}q3?yp4f1tCKEUl4)i-;O)~5D&G{+$SA^PYbzH1Aq=77Tq60qMV7 z>-|$4WcpV?=$sud>!U~T-BE+A=gV9~qcCtJYeChPGCOL>oeYxh_WoBt)Gr77MT1JLFB%{-guYvQ=%*cvpZy2uD-SDDN9e!TRM7s{+a4jA})c0okeM=09!v*Rh{}Y***Mh|65Yf z>bzL_hkr!*5(d@RPX}`=Crfi{3%Y*{kM=e;j{kCyapU3re}slXvn_J-B6!L5OE42I zqs2ku9|lN#HQX2bSHm+hLOJEX3ae%~w3IVHCdjK$)VZi~N9+-du$O+UNj#PEsd*sa z{Ips)rj|$v708HQV2h$G!oF-YjUz}R`OWYGOvJ{6IhcB9G`i|72wL+(>jbkdy?d@+4(m=^i4D9O~A{PPx0Qa8+^5^_0O7+TSl^)@J zv%Al}n^7EsFCI#9R)LwAJoJ~!DzgkJhh}-$Bu;VAr?<2J8vid#&rmqeE)Tb>jj-N( z-sl;s&_H|E0q40s2=yMJv8-VBpKElqT@Q3%k0HW>=eh*U>Ums9{Rq>p`~_`6@7YbJ zT(Cx5nPB$rs=7hWORp?uG;*~2EUF0NPJ=%*SBm{k^Xy?`n>`>DH(VzS1yww{HnNH{ z4=UifdOk4vn0*yRu!<3l=^jspP?-5r=hH*M>Bv1!C55<+xoC-bRhRuBd?ju{FgE0d zh1UCDG;@dJ$$pEg6j$m@+o5RV%87M$xeW_`!~{VI=xv>>feBGr=)#H#Ot-RxcG)M1 z=WdaJ?}Dx|+K;&8k7^WI~O+Fd7ap{5xTcTBSEZ^0R#=lRFDS_qdb33BBk60otjdE1IPiv+__-(V$BsM_-SsBh4ex0h;$yOh zHCCz;{==XxI1o{>a&Gk zYc%*%$D&bvJFf}~-5U*5?1!bAVk>L<*`f4>kz$T>oI3~19L=}n(;_TkQoRdMKiP;C zs-W*P7oPOpo1aFq%LemJ#lF`N&qOnR(`%OOshrsx@ef#8`W`P@N68cz2n9iQ2=uVP zYSmP(7^aDPT{e6BTT+p#B9?Ceu04E&T>V<_qEaTAIxT{d^kRTbFZZaN3kGZ2E+#W z_X^s7xYz$Qpnp%bCsnQF*60yFrmER78LSk|H`5eEzYnOUP}cfsHo>PCjS?>z#4V@l z`d%(g%cdilk^dqtQu(pJ?Bb2LwXr94bxk|H4OVF2|0pr@07)PxJoZ!}7nybGJi4P- z&X!6Q^{fY-;{um$9_?jMiBwjJj_C>i(C!WG|Nf39Y&Tyk)Q$ai>~;i?gXR&*FuOQt z^LkJXnl5_gk;B{7Kfu17J3>)^ZNTYe`7m;5phJKO!@vT`%lb|#>@A2)LyQTMX$Bj6 zKx+8rZa_=b@uQ5I4Q-T2u&oUsgQB5cWWeyeaa) z8l#!ua@7a=p^p;4sn3*AM5;+?$AiR?302Ai@gaOtArH1OB7@PJ4k(9(Dy?)J?L03hD2FZLF)`p}M&TB5wZo9gCilLRHfwoAez#hrb#7 z=T~n%=H!&M>4G1ON0j4cIU-^4?TX~S`ic0*F#P=8Bu5Q`S+jn4cu%DX;l%$_u(AVr zZ0*#fDaFHK<}PV%zNs)Zg@aMis3!DYj6zyr&@Ggbf~-qXf|AVzj^b7jK3YC}6t$lk zv~41kr^n!8vjy^?FSrzLcN5=WJzu?%TprW_3UgBrOw+eZP#k$Ahzh7|+-094)SRON zk?Oo*RC+Ubuf4BK6>u+T_5o6f(BY`I!b<1@SCA=yzOiTfian?2(Pb4j6SYvR_*~gbKfQO^$3|n529W+f9Ww&xhXYnqV0#0=N_4o6D_w;doO4`YePTDlyS?DfV(7PuhTu7e0!;F^K`$ zn5Nxs2}&)&LNHUllt4)vssDAn`8H{{@N?h&71W~}D0@<)H?wYIu9*;axR#iURmt9% zyWzKRY^+&|y{AC8hORkb(yHg+wZ3B)*eHXNb26ct$)_K+M=B8MIc;+MD=k*Rr@}IN zJk>8SFMoTQ4DcIzd+RG4??e4}2J~;qd86w0uNZ{kbyXd@o-AX4a3t6VqU`9a8CD6Q zj?XHSU@`H7r8af1!Li%hITSG#fq%o5U-$YT6y26wQX-osWrwx|6k3L)J zp&VGT^$Eeh{8Gf@B~2X3g^s$Mr>QF^#jz*Uka&S|<{j?)Or^%m{g0%z24EGz?)&@= zj4NvOD+WUKG7{&FDPETHGRjMVeLWG|GQU@DQRUvdK?9%F&5V_^cwg)62_@-=V(&d} zJR<5=0BwvXQ2sxHlHAaQYPo-(Y=$gU1Y5j(HQ4I>d#8KBAN_jzAzjt)b6 z*XX$ZyYhXAEmE<&92}*>!O)sdijexaem+Vuv;AxRpE#8P@0KN9rKnCEOFIVc&+F+? z?n{gG#_W3*oOKbnkf|lk%Jv*2u$C<6?k~>4l?p-)m?qzF<(_sYpdl;(b+DP!1@AV^Pf1}HM(eff?Xi+YWbpk9I-iH2X zy855N<=+qT7n)W!YfWe$o4SN8{I!7QM3PA~G-2Sw*0#U{QHUN?GrI;kBtxW>VR#}3 z2OlrEit#jJiAH3YH9O8diYuNRN8Cq2@G+hbXND+PkAY-~gGacImd-Fpuhcm=w;c)L z?J?FzOTF#&D@sJ-%&w*wrb>HE(Iak0Y0v6CWmDVOw_0~2{8=tW%h4M_Vsj#&JY1=l z)FTfqBwfBFhqa|2T#RX1WgZAOCvi`uDBLE9MFd$J8$8($mQ!!$GMoVnkc!#d*)Kn9 zkC9&eZ>9k5GsF3@3JIgSr+J6ITWV_pR&EGZp>nZ9Q2Z$z#x{Jv!X^`UR)v`X{LL=x8L15y+#W`|l0Q4BQ9OVOU&ASx3%n3&)piN`zW ziWslw@(M$_m$aVg!f5spo0CCqDTh+w(Z}6KsBMdyC>l>&HyI6s79xkg$pY~Q0QL+@+abL}kM_?}IO^nZ0Vv5fw%+nrz%&JN=2bjYB z6hMvrv6?i8QC`AX(vTuQW!!aIgEeP_yIaf=B|ZtVJ4arvHNqT0ZQYPO2&qTI`Q7qv zx^-a#tUNQT0lgPrOk>lk0rS2rpnH!V)KI68a`pI>`J^m73=;9;_kO|x%B*(v_j0N_ zo&1VMg{Gx4%O#4$3l_k&`wVyE3$H|6L%#!L^3?3)pjG>USfL?j%ZTQpE*t6N(VCj} zhqzgXM96nhWae7CgmA&yR9^{-sG#yv0y}y_g9S{j;K-ZPCzuEnO0w3l>KsdI$ZkNc zOTmX4hmI~>?(gvJmDefQt`#P(FP}!P5GaMPL@OaUfYp8g4H^7UXo1B1Rb@0X036~8 zKx#LfsEXSl)qr?PYIFiC7D#j?ylLT{pu=c`giov^3xclzK*ex7!ni}vyo(UgL^v4g zwS^u((=kPp%vo{fX)s!&g@?fCJG(sXJBJ8v%L10-Rj!M-?rQMVhp{kBs1JA*z?{KS zz!A)0jz=W)RX4&T)0-yK?7{X`w6;NzsC_~E*KTaovTd5~s+CWEhrv9am)FHq%!05& zNEMGvJqcfM^!5O@SbL)FdN9HO$;K1Q_XGPhfU%&HpIP>muM)u_dXG3SPqdPa4ynjTFV6OJfhA89P*Y-CnqHQa*ub;j zWnOKt7tTKtqI!v0$J$=a0iJFnd!A-3j<|--W+m#8Oe!H8yRwd`Kpy*2HJ7H2y@eo$ zNMV#!A}O;M_>h78duBxu%oTwVTpG18^K@qAGO%#2AV7%Hgk1yMYzB|~PBrVuQMP?X zy7f`GfF>UQdb1He8J_E`MpwTKRqpl$$_@kjNtz+{mSb zOUaO9w{`Q&i&w>~iko0dH6+`D(82|blr*Lto71z7!@w*gb}56nU3$aqwp82siW@~# zg0?^a(4H)2@V2ggVgZ{gdX=eHVbV%J;}47x@lg1ssDkTn?os%0R%l;?Ggx@i(iPKy z=2jEkrx0fBmKL-co!JHBn^WbgR^ngexqmPRmXnkFIpWBq@K%O!P2&)IlX4%7sOYBJp7ysJ6)XF? z_C?B#dv_34=rk)%S^Quhk~XsD3P&>nVX98+y0XrOyv*HXqWNq>s4<|!vJAaQGNRZM zxJz(mLv8>i1PH#~;CQbRTPh(lp22<_PO>ss;I^`i;8@k!V~LWO1j6Mw;+=7x_nKC` zi7@dTD}gGs!7uz#B${5^*Rkazm-xtvh3d{sQQ*dqgCdxvT^x%p=CEa0^n;;p=n7Ol$hLZ>4``Vmcm{txA=qfm*Fz2t>=W%n$ zuW!ol=vGnd^5RWH!9R*tJg`6@Um$()(e8=Rq2n!;Qu&cf3L;I(Clpx~1FLi*dAH079RE4lTLRQfyu~naE`>ylK;8p71oBTu=h4*(J=8`XO$AmuD`y$x&(cI zPU5Wlzz==(J-Q0;y8qSY*lY6SmGMe#lR>THGv^97`PEX~n6JiK?%t=3lis`K6LzCI z7oN_+=Rgf9^;N1n|A(=63eR-iwzXs1 zc2cozS8Ut1om7&F?WAHGUsSPevtrxE&KP5@wfCIY|L?iaa+H&|eb3eV-Fs_Ysl=CY zM5v0wZI2WGt>Qi89gvk+T!f^wD4{Xf*>>16#+SOiz#TKpQko>ql!HSQ&HGTH z|97ZhLF5A9rbP0@?UhMzvyyli?n-npinLva-hIN&=HM4tDbEi^Sc9cIq0y%la4qVS z2U=^yxFOB{fy5j-srH*v){YpHE76+;py(qNG9}9w6ho14fh+^tDSWH5=0I=eeN*W3 zPAYB8)a;d&L(_{jol6y{;oEWgx-~8vwrJcQ3}g>&m54-j{vcm|sS=4|5U)t9A%*ju z8sikdt{96$to+AXu%Eh+uOwg=u#b1OK;lUU@D7oa_n9IiC})T`lCloNT=YS5;7|h z{d%-PW>J0r2Q%&oU(hthiHHKa&)4VJ8l+dGbu*GQnCin^qZ7FSQp)NPrIECLEM~80 z_u-al+PCJKJk^6#zfo`M+D5QQ{{1tiGwyDn@5ZE>@WS3O*<5e*tk^qPsH%f7B0&C0cT?vP2#(YxSiZ!J)popoST~*(5J+SH z;u|S3z0RXdwp<$Tss0JTb#drMn{~D-RApT2jBzDl@l|vb7_mNG{-&eT zKCzBcfKcfSb+-NtG+qvZ+cd^-CGf8Wb}5e+I`7x;J{a{sNSyO;N5{U#m&CczK05W0 zilFBuVoYL`RjQvm45&lRBR}dqs>Kmu0f2_<3_{w zRaelI7%MNY_UBY4MaVv7 z0JIzdssxxn&kGh$S|8l0ocFde-vLzZkFbR_tx4(xiIU2BeOx7kv?)$*k-LJl$_|z} z@c?p8mNn)~Kmb4WC`7mp#cau@`#xlus`}MUJ$2Lf8We2p74{Hq)x5kk>#~RgD&}}y zY&_X2TrPV3KqcXHmq;s841Odo4jw|1NioF><8&z6k%0SjG8PhutwGkE%?FtEOJnn2 zoEOAy3X^gL8JUazA$aB@G3r8cTCs|AKgMs-Wc4Z%viVw3fnEFY% z%l5OAsx;i+MYKeE3~A$F`)Q4WpYDg zVnC*3y#NHpZIm_2JedFZYf&_cx*fZ+5q8a^V%E12*3++=Lr|8^XS(H^O)(0@F&crV z`hW!0JoyhDn7OZjh-6oC=yc3fYFQOV1X9`(9oh)u`qZ9CQ_(>c*QK$nt?G`b^4+h@ zypXGDYjY?_snj`@dSo4s`%yHv4?&m`JG{wlsm4!Blvr@H>%dVIjV`{}s;yyOx6cJj zACrWa%~H4n&yWLmO|Ml|=irk9cDxc>^=RZ2?eri$MUN6E5e2xywZUTG$w}?+)LEkm$Kb#W~C7I`VOdB=S67wJ?-dr%rTb?-n_H(2aUM3Qs&}x#>GM2 z(*UMR59182G|vMy+}pF=Xv>(X^g6ZlI^s|;6?j3}vc<;u52IY3my3KrtZ)$*wR!0Y zifW1pQ(}W_$?Ksbtrm}gZ?wG&w>%U>+v%Z5V`mcwFAL;-8@ch?E zdO^cBc2ykd%Su*vBdJP*JjsA10}>;_rBc`yaMehNqPk#&xK900U9Yz(yN4xG1Eml83d{rz>T6WjAuRB*3T z$f7|s#{tavJo{N=SU2N!;F##ye%V)d|)K=9WGOP{% zsSJk86q$mVam_~VkDL#|Ba_7iTHt)B^3qh47|R*#Alp*yy_O(K5pkY=hl}nYO&7JU zK*;!K1VA3$qH@A={P%PO$9P#Du{}S&b+Mhb)lkoADlIX%?}Gw`ot7Hpy=>zN{OB3t z47~>sN?92Xq&PO6K0!x%q`YN=+J^YP_f{@HoBL0Fq~bNCuXC}=7EU@&7`t>BNFFBA zj%gMbD8CU^w$6{)TPVAu>{!Gzuy1Bd3(Zl$(D~lE`E-UI^i9OD;cf70m)y?~0A90> z2Biz#R;E+cxQF}&8>ni@y{6GpO0!6}pCS8@?Wg%z7I7h#Nw@D>qkg8W@ww#y>YS>G z4k2qtDkZeEm!96DIVbl-We8^p{-?Z_nKGBK?O z<2|`SAx+d2^&RMGuDke$QByt{3-Lh7Mvw8v8NoMYG^47ZFk8sTUC3K$uk!sv+b}2? z#aw_kT|AVWFmU+C`;J(=+B7oM9+I6;x$w*cEL$Y#&Z0OI<+w^DU>>Ft`R?#DaDF@( zN6PieS;2?=k=^$_(hT&drH=X~rMkTP61dz8KGVN{#UI8{2e3HSgD&1n&I%Ex{P5+Zb4En3~c4qr&#k%M)a#__Rcd$kqD9lF?1Z7K+R@TbAzJy~)O4#g%(y`gt) z`SC~!P?DIfd9Yk1bHJ?H8_5i@p4}v@&5)9nVJ5c z{U@gw{#C|@bUmtTT&Pnn6B8T9N#R$7^uuVyQP^e_BjI7hFH_cOKRwnb;t1~)Cm|}L z(7R8)Zs;2L_)DN($pCoGTtH@Y2|L>DwRe20xe%$?olduo!xj;}W1V z>lwFhsE*zTmrsDkoOrqiVt6$ca~$nGk##AagoNpLU)|q#=74R@C-8#(`Qj8x%av0g z>MAGlO9|8>HSr(8yp#dR#Fi$RvRwmf{sN$K0M=o*>ApU3nal{XVjlfUS4CgxP<}Gn z^&dN><+58*7n+0H))2ryXjy+?<;_3|-Aj;vChXTeD3*Wsod*VW4dl0kq@L-*SP3zi zJ|)p@SD$BdmXV}JzyU>5&xHxfqL3YQ4ksaw%kx2Zqa>~)M@-pCNu~R3vHWI7{G?ZE zq%L{g78@8MW?MD1FDr`;gk7Lch1nt9-k zBcdzB5c_cupKF%SATy0JCgJL2B=rEzQyhGAX(Lj8s;G;EQ;B**97~+F z|I z4%Npb^YeEm>rhI~&XgdR3C@}2q`tD@D|>OlEs8Z6s&>Jxt3_YNco3T;TKtPGBmAdi z5}9JTLnL)@e9A)OnVK$PT+uPSeG5$1ZOS1!LntA`iJqaPc0qgrzR)En2|Cu%Am97t z*1uKcJ+tn9tY1p4_z%eYzc!Z6wY>jA-k)7L!VW)-KyQ%l0S#mXnZF0%kvPQ9ss$qr z|BHB&?>h>-^A(b5H&KqrX>B2#1{482hn*)cc|G@TH*@k8yoq@8XgiPcP&-QEm(78r zF)=%6JHFDlyAU@r<#Q5~M1wdo-1ukscfxe;?9yVDmltq-#Ih?0Er)MoSm)U3Jmz)p z4xf)rtVR3=@voJa^K*`Fx=5?e%lsfDHwBOdP@}%n_M$D2l(Pv#$35ai0e=%7nS& zsAeho!0Mfs%M1%#$v3&O+Dyi53J}$9;9Od!<$MVX=nlJM5Z3?#;%kfJa(sO|PeDPE zHP(|z7C8rQnGmYT(od>l144|Yk&EF?Y)P_@FM)eX)$EdQvkuhBmz$NI#RofbZ}0s` z7~t}pA%xv z8;SY^){C+Hs}$PXm+B1Fj~{(-NuJ527IYO06csWQ+#U_*Vc!ZS3h1V+ zlF+ehkQX&zt=(a)SBh%oaBEY{Ibf|XNY9{3Ga zdmF|{C+dn|-qq02Ivsx%6&cK-g)!rlRFeet_oNk$ZET4QW7X8iJ7x$SkTqYk6-I+^ zH|Gxd4ihwwo<0Vd8*lr4<9)#)D8SGD_+;S)OPIxpe-rr;ur>?iqCx}>D-1%UevrZ* zU{eV7`4X5sNmN~JuEPPRXypbflyulKyF{YYja(UR>U<-9-H9luP7;+Ya?rZB2Bd zw*zXG#F`d|ZpN8H2m&e=ONjl5`iQp3BqNAkOeM3U0-n0s`)E=!)8#%cYr5Dkx_m-_ zMh!a)BOkZuIn|J3DMNVzMRDk1gZWEMTS;N5_vrdZRZE+MCmI;k^2W)Zfs?g#(FrY1 zwv~vVhC_P4)w~ed$MXC{xco*+R zIOi;Ooal(^odaF(57B18?v^JH?ws+wrG>ix6!YBJUfE%B={`j>JdL(&D2Q~wm4mzq zI@*z4vYJ3VKpaL?ioXDxk$Pa5Kw|lecUuN&Z1PDSef*H@egA$K<^^$N15!e@Ya&B3 zxbz8B>N}@x5W;{= z1rsG>ULG9D=kVy~g)ltrPcZR7q<2QD+nSN%(FJ_J5)KDK_?EV7aVhTnBBAWxBHsC= zvbFBUlZs!s4czZ5G9Dkdk^zaXdzY*buM8JsZ*hrnoX)N-Oh%_!dSq>~3+);jWd@HL zwZ!qK5qhS2lj;k2H*Gv`!KYVSbjRD!Mym~}%m)*)E_urS%tk6Dcg)ykyzEv@Qm|6< zAVx*f4G01;n2HG8U^E1oZu=(F=#>+eyHFcO2yY2}z1-_Ji~8{;Fofk_?(Q<`VO-GIItyZc9ST*i!nYw6bZ;h`cC<^W!Ze$WEiULWbyXNk z7>{;@zF(nz1xIf%W_GCc@ILUf2eWBMbnzpXM4o7_`vV?Ng@W%V+j5u%~^u>bnizWOa5s_pmwf5CPjWW~2XV zDQfpxwVBbVwZURKUod-@a{R&i9?RO1&v4B8{%rX?H}?5&op`5^BzVzRd0hD)C^z#z z*6J+PZM(lH_mr|m^}Ie>0uW6@oYhaYi2lV=piVr#g6pi6pA!8Kvt3egwXvpm0Ev_caZaF%-cGV~(Wz_c6Y59~ z_H>vRv)bykYzQ0q4-Ra_A+D12Pcr5ajaql16cn ztTLp%d(>cn*={%sC$F2E=UHCn@NXvX&wt3m6`7b~1&ylIGQ_HuP9Q?d>#sdNRf*L& zhReshe$G`;&1`IDM6{TBy;n`6wl=i-T5r-RlpVz7fVw8iDmRu`k#nkb5H0nxUKmZc zbS6A#h%wDgr%^Evy7v`wC4C|8uW>R-_YzE_VYMcRabx$g!OOwPejOggc&(8o&4=H^ zJFF=1)tZWvJPZpczT#41Z0=8D=_(Qw!_h0Y&Act)`m4=4>?%O#p2$pg|6&5|n?mhW z?I{o{UUakxyu_}x2gX&!^d87iTBXw>Qh8cy35_#X`RbwO{<0B!%y{{G+q?;FeGC*_ z)2U7wk_P!as0G_1wd95)c9VOTe^m-hyU92fF_xLPsL2_T5$}?2O`KA4!R;QuTFAxm)0~lP6c88d%DY3(Z!X?p z{}pnh!Z9##e6c3${{Xp}|5^V28*)n^eQl8#aw#QANM5~wpM@yIPfJNi3Z^wF$v+y_ zVQMUR%y?xbe7sEJeC_4fO0Ax_xFf?@PgNeK58XC3Y*t~!KZtq=Yx)!v(1FD9vw`Mf7i8et+-(c^XMWGqLzJF22o}lFP=-aVsIIplFoPcB9j5VQM!jUjzr`{ ziaN#b)?=2yv=rT~@#CgCLvMyzSPKK!Z#?T_1zR-c4Ihqk%)|5m@U$L0dULc|rnj#D zHWoXf=$6{P%%;ra>M4ev*WsT0X}0QQ$_4Yz07`&zwLeRH#l~!5Rq9SF2NuI27-`+m zW0hQI2Sf}F9=CjTj>TpWXPx>p$04cLTBr+bejTV05y;g!7ixjjwLD%+AgCb}{DC-g z*jx^r>T0x2%kA~fWT9iyl*^@rnn1xm13vN4%=Lqb7 z!EHUNFSxBl5I6p?Ie&b?ZISI-gf z@O6XcwzxO#yMF(On4{B#!ROnLPIKKnUtMo!< zd8163^b#falAexYl?Atw#Yr13?ol`1RFe_iCP)>9!wnh+4D1G9h_p}dB?@-Ijt8jcD=C|rCTXEUPGW^}hb(H+motcAkK(Mte zYqGzQJ-bgkvtDB6;iZlYBBkS+pQ$E?`@&MD{EC`j3X~Ex#k*JOT8;RUTzE7K6{qVD z0W1uz>mVBH;A&d*N%YF#^&na!xnq@S7glLZ zCl|OxKJypg=A=F>)q;EyA5zZc^x7Y62lZ(i!d1pIbuxYcHkM7Ub1Qf{KKnOcffd8~ zPul+%zWtBW=5M~u`S+V+S~Qm>y3!tpq?MaLlrOSM7iM!QQZe^+>)o2IPI+kM=j(mr z$QTGTaP{N98qJ=`V0QXpI;O~H9|g<|%T+KV_jFWKHE}LKER-%{gG%K_>uTusug+#! zFws5^sQbes)EI-@KP-f>Ez-DtuG$hGxJ|~RV)CCA{yYK-6K)LMm`a-Vr)^yrR$8i4 zK#tA80;&{4w7sG@W)%x{tMQY&>=3q`Aw>7v8ei|t4A^U+qpiiV*8oxYY}~ZHUMuYx zdJW7%Eb(nu-k%a?*6CtaGaZX(Xk{yl;a@S38J6y>jmDQxT+$KIgfOYMyG6EAko# z7K#^8%qi2bjrSMdzQ1N~8O}Q1yg(}ZJ}g}TlC6l8bhWJN@jLFIb2N(CYI<2@%JCcn zz^zngU8=fdB|23NQ}Q?8PVY61ky7}JZ$o_XZOejx`1ZChokNqw&)`F%`LKI{76a#VTk9lP-uYFgwBv7~9rG!T2eMtaJ|dA7-}$~ove4iX;V z-oEiy7~+UuL=r%gdPl`$FUR; zCMXMc5y)b<`D~BsupWY$gY%}oS#to%IwaoEO~MZ~s(W|Gy?E}IG85)Wio}Z5%$4&d zg(gb{&ABVduu{ z+hqUZ+t~2U3xDx#EOOE>zU^Nux{-iYMGW0p5_e`N#4G}4)1Sl-{LKmDsaC$9-!U-( zlq*s^_OT$=B7szIVFO=!AhVCM?bvW@Q-5aMxhp&p%c zQ?#;;_TkD!X~WXOetp66MS8T2wrdexg*r|JaJ`DA1)Q`{ZMqtpX5mBcdK|R-dqING+7|G_1(x&%1?q#4N0u)Ir$NJA~nyN!Cp`S zD9Dy3KG{C9i~jz>nR}XP_PO@j(O&}+OJR;58YlTLDG0tYnhn7FimJGM=B=h&p_kZT zV1Q{Xqa_>!WR;rvn<>qB3&J8VlRSi@3RKoMyiKuIkD5yBgS0rAGgb)7 z8bN#r#0*w02C|4?!H^r*WpC(kThChb=60K&0kzu|nX4*=f$9VlmmIL@(N!(^+{;X> zn@Kjh-o`WRRM{Bi2Z)&T09z#wMxbWgfOdfHD)?R#b^yeL`CoXuE9?`k?h9{E$xOq1 z;cW*a;U=mz^WYnM8?lp9MSUb3dgU9+2tk{%FT4#dkL*h?wP|Lbv}ejPX}o{BaEyHw zIhk-n9XqV5W@OWzVP$!IFfU|ovWAIJ%C8fINi z4D2fD-LMr7{hq^`5MDL&{1r^{Y=J{BSspfTA7uH2m`@h2^ix}fII5wt`n=)9sXDdj z_)_~Ag3!~i(o*|Vf4;3Zp-G%nohOj~Z@Ml17u_cO*HV0beMjNutJ%DR`wz1ij=$BK zm8$!t*002fR~p*Kl$d^KB&0&6p>kCtI<4uyXEAWm8DF!QrH9Qagfz1Ly#gIkVlJ*r z=NNgtzPksym~Mg0LSk|j3qNL}ZnE58ac5?6_2ME*?gLD@__lKMIKQSbmj0R%{A5otpcFgN^5PH2KU(Xp5XL*(w*#aXxT4<` zEauK1c+Y6f?mLI3vv%PT9mse4-mHIne;l)9_WRv{=(1M!2Q$SA-|SpBqNt{-9O;S% zVaDMXt-|rg@yTNGnnCTsLj^Cx<;OFnrz!BOO>4}us&t^?Gs4$H+ISkpsA9s*bY&;N z%jJ3-QwR7J{|O=QStB$;wouv=Duo`#A@~8|1|MgsdP!IGJF+#g7(^L~mT{%-5T$BC zlt<~@`DE36HPxc(qM@Q8*n)$IWOrF1*b0~Xcd$jXQ08u07nN|FFDSW8K}3433S$IB z22QmRI;o_6cu+DrEAz<-W5r`O=bAIsqE$r4FK;=(56*?%GMb`{@oP_68vk#4niLz? zwxaq%+0Z&zKr2An^QxObb0ZrnE@vRjF4rXxSPR}TB7Q-3t?$3=xMom&i!kp<5wp;e8xSc(-4HxbgB3mpH!|9jB?c$ zJrA!425CK7nugzyQ?{pS zt9q_hj(%FYW#KmdvuiNkMgDnL$vo$oH;P4P;%5JM(8I06NHX6V)eltUC;YD;lq401O*Q1;YPZ3Ow&ObPo`h^ zV==4(YOvjwgvH#U#>X0AH`XaM#Ew#u^OVCo9T(e#A|JQGx0)`Qh^z}qGfAP5g>o@<~qFcV**LJ0yiBaR%7nK-+H|w31j~m%-b$VnU)7VVi>0HAzWy-ef78naon|g-{$3P z{s~>V0%aMDx>p}8UTOU}NZaadALQ8l^_)K*Ko8ck2`Z}f-m+IbH&%d8IT)Jl zM24KsCv|;4K133+kN8azXt%AU(n98bOTjtbyLHURcuO-faz3nQ{<5 zT=-%{9=dPeK($^X5N#CMFD?rY^LS z<{(xLkZ2B-^LFTk2V^V{*R|dJf9Ux&+x!S#REP`LsLj|AjCLD#G)1J+#EY%FdApfN z3lrt$3Rk!XPF4az>ZL@fTvy!P$;QJDHuW?L+0V8BuUGc7VmHnEUTGE z^+?gxKgtVWymGGh&~4RrEy51t0;hXHHgH;u$#$h#&1lG(A_fbHA8c%f+2mR1O$^cI z0BT-7zv+*fKsq{m;9gRPS$Kvn8@Kd}jexnotr4;^UfI$)SBim{4_6zi%Xh5Ipt99Tw#5j=01U)(fLlorFm!5iCSiQvNFCWyfyg zkvjK7FkuQ6HU*>sY;-R(5Pw5XHi6#I9yvkhN6D#YmE15OPm6o`q!PKrXiKHHPwKQz zasj5r{!8P4(6xUweg^8j_1_xj{ofi_{7d8JUmCAI`#&_EVW^*BSI_?A_%MXnS!1DW zAyL!yd@MxM5n6`Bx4ItvDB1+Zik}8j$bGKhy#A>#>TI!TWo_Y&YvOqgUgL9h&e-&H zz>Fbl8t^k9F`*23MkqTXBiL-}uwE5)DvkH$Z|>K1w**Tb3!=YLB#5#8 z-Y-&rdZloLWPR8Slc+leSa669{>(WROy{xJRZkZ-T@3cO zaDUKl3k1EO;Hd4SpTMd1LZ6U>Zjj4OOTYwf`#nwmF{e>4v$fBdB5^H829<{qAGr*1!Ua;7V@gzMNw61q1l8qYM1w=1y$ z0VqJ;EkNTOiL2y)IU3m{^EUamA8u~UGNC2=h2{d@V3H`8tpJ6*i9{&C*b(ZAm*gZ( z`#oy&Hvn*qyo37mE$_StU2>BdUli7HYil-G-;#VN_>+i~9<`Y0F)n+f2ZT{xpkH@c zd%JGW!(-ozyaU$Np4D#C2Nl$(r`Wpy(f_nzAYX0RNnh}pv75|ZZ$~X#8F%3cGESw@ z4JF{`@?nJ)f;R8ZJFc-;cJC6hiSLTB$u*cIY+LH_l}Q(XzT^PmtGDwanfbYNEp-E` zES#Bu`nv{@{i+kSX0FQ1^7#AYfqAgHxdW!)8co^8Ve~0!Q}Re>=pu(U_mztnU{f4L zCyEWGC|3Bq8eXR{FhU$WE_1~?^J>zrNCDsl!Z|H@W<4^Tb#WJsRrTGp-*Cz`q-_)5 z=M2P*#0vfJWGZUN;hki~zx!JVV_7Qdu30MX>o74h7rHc}Ssjej z`2#(_3O!;+gnNIdAK3M;HHJs?E3n;{SYOHh?E=id`D*_=0OoIFEhoy?`mGRDb10ev z-Ac@_hUktpigUK#W~j?6Xh$3QxrKET(V{03)Zv#7pYI{_k>uJT|}UHNzSs%!%wR?reu!cyV@?{Bo>?!zq)XvQX*f%@U4*LO>ysnVK6do z*v!n4Ho+3K1qyw#IYGR@{F#za$QVO~c(-s|g`)^L!~NAvqZVzRcYd$?(j}5V1pKbA zq40P53?@((Wqw22S#RS$lKXGmkqqX`mXG>XO3`A}ptU^CA^x`_RKaeWKhSougD73b zeE+QYRv8=ko*XEf>sUrKaTR5liKt@g`ErGN!1W9zL7HbC)3`*l@b0n*LYt6?$rvFE zt3+rubHdVi+-VgohSzfA$e-1|L>cos;+!`;B}n0kLLjC@k6LZLDD~0>wIOD{AO|P= zh$^|S91K<8TRPtv6`GsoMQzM(i)|6OEJDx^?x!r@%k+2h_v?Run&&yQjnKWkKiPx& z$O;4u4A_0>9i}jAS1zUvX&z^m|C((rks(LUN>m(`#qvYDp+)im%PVvTg%soLhkFZj zw%T&|0ZwN0$waFuQ&Riso&j~ALJh9h(yl%3nsi{UKAUK(>RxH&Ei{Nh@=1uy7} z`dZJ8_YzVEA0^&OCpHsmR7E0^6*&QfjnP6agfSVYTo!7O6BbxA4=_4tA2}{2b)gZQ zkImui9#}d*W#%{m-VCDXW#eh~Yt+PK7p#s>rhv8SBn=q+$ZZ}j6(U_sT}J4(e3=4% z(!qLz5;WKHX<0YeB<2<@&veTK_sMK_`VVoIG%kHWX%~G?N7eH>-<=cf$$iJU#{Bc` zVf|~k_>A+uGv8j9h+8aEFZ!Spp7L!jxF^R&*G)UgzC-ums1kdwQko#U0JIriF-ftz z&1~`9J#vEw&MVQ{CKo89gZpp*K%kyyEHSqkW3K72TPPkR>*4|J3L%FAd^!*ASCZE> zgY3Z~@6bUHw)lKa15%{gG#oC>*}*bh<~SG&^JbA2@AnNh;DaJY;k4SU=>r)So%9h^ z?>%g(v^e1Oz>kzPIV*phrz#t!Ni>}Y88ATJa$a15<7C*hk=GB37p-iA+H(p56=C~Pzpj@AmDzDkNkJV7f>EwamRVF|>GU^~hK zAYk#~7V%|_X)JTxiuOA0qj$9TYhm&iXnSb+EyWzH3U+ybEiQ$oN4OFV2_lxgH4;fM z6;oTBCKIy3;+RAaIiT2U9pM@?bb4{(p#R7EV-U71l>Bu%OoE4UNO=S-I zLUasK7Si9o>xV1Qy{T9S!P89hCy>8bklCLg*H|X?*4~ZO{eq{3lB)&2rrP<_H>&$* z|1}F!OxzaMx_-vGIBkmLj&M(L<;DJi%H!d=>G{+Iu=e=bVX<=OK~j}6V58RhT%j7i zyHd{j){8lKh#4L(qH0|Os51;fKiYru29+F`8513{1AVQep$2s@)>s`?0y85)nfsx& zCKlIsX?01}mt?q2V~3Yfz(S*pD}1|+^@Vx;HDZ!;F9&5>t zMDxiARW*K5UN3Azn-`BxfjLdcVK?$M1m+Gl-_6fn-cHt6(RwV754);L=v$d+;lfHd zlC1h&>E(T6m;{k9U4{b!^RG~ItMli!rc^~wx7yGCaq=WRN5)pj5YcjmG?s!%5={s zOc@6cYx!k)y-4K9S7q7p?`Jr@I?|Ll#v-M9l}jDgvkvC()${BNQ6LAa%soLJP$M4{ zx>2EorQ@g@Y~%~hkM6&%aaN=kGm>a~>fQ0~z317nf5?%mKeIX9$3V+s5h2cLsxEp9 zq$LKm@Yy8}eP%kMNW};5Ajm^^&tX8D2^&ylM5>@_AIq~Nm1m@#&d&rs=#Uy#SfS=x?jABq_MV8vf0#bZCy- z1F5hhzU0VewL^>F0&a)R;w$k?dJrUX`@@ZM&(w#R1=uZdaK>}iOsaQ`-TQ?p!v4|nH zBt1Blvcc7MwYTvk_SJ7(1WdGh4~Tf{=l$P$Ij^#hpG8WCY(}lg0c3a-4+GtFRvCyY z=`FB!Yd^o1r-{`9m87Y&c11G>rGxJLT(8Jf!$@Fn*(dzsl!l#?gi93Chd5Wxvc*B} zYt=bA_T5u0(%>S2uXx~!NdU67i#7CWz9^3?B$tg$M7d3|8e&gs+R z!GTBgR-bubNFH63yp7F8SC@lS{LJ~Vz3SAmHw)8JX-`YqMK! zyFQ7g<-5`8XAAwNJ-Eqkk@*RlDzAvF2iZ>k{)uY4yyM zwin-y|A(zj$n|w|kQ6uB=?tp-OXXV1Pl8GoYoX zyK5?95no1S_uGRyMLkILLe^1IhxU_an&r)mJv+;Rf9FUE zBi0Yf($T0ng1Z;2``Ex5A&%HS#l7aK_nIC<;}GBx>$+Du1g~p{kCCE~**#Bkvlq`S zs}J%ByT><-Wv>{}TNAyC#EJ?-q^UX_L2u!8VaA0$MoOeYVMIRV5+6fg{%zaAm7fNdNG}>>yeS#< zM}HiE(kM_vjEq!ThFb3TP}+2a7Kpclb+qSbcNxmKge?5f|e#-cWS%C(@vm=PW(``lOSj# z9ux1%9SpF|2thZ3idL)%JqTlRVKyD|6xERZ}DRHPt0B0X`{iu_0 z@Lm(={F#<;G|csjMnN`xW`N~|A~@8~^;nk4%3z6JN}1)~=ow6QbU(Mtd0SI<5v4?C zM}~Hd0HMe#f_Fv($YLW}!Vz^khy2O2^{hqBro_pc)^;yqJ;@Mwl`Uk8y-zUDjo(_n z;CKP&Pu9$;1b?~#e_kSLP>!+(mvF_n*+wvwiC7c{=)#>k$#N5qA82d6{?%ae5mMRY zqgqDc5at!=P8Iu4L9;ge?2b0ST3B&OQ+qMB<$c0YJQq)%P;>+(aoE)f58m&j=;yYe+06*+du+8R{(!5Q$Swi4uDS35G;qrfn*@tsFMAKeh?O zTTDfTi#pmpX>2rmg3{Mt?$?Iw$zony^pR1qVm7+eITZ3T4#A}EI>jOe7e@vr(Ct}L zHzi1B8nEL1r%wgZy8Fr$WlfS)J$yw|Crj?+6C7|$xRTZSmE%Wh)e>^=?$weyg7tY1 z${&Sa|Lqfxler%?LV@;{Om8r=cyPf5J#-e`p}_>PV%I`;Y^PE*`GyW~nbCc@%gkaM zg((yCSTFWVm48&bI*2gNzy6-qqk>~3Wia-Amr)5zJqb28VuXezqx}Pjw);pFx|tEb zK&l!gKjmy2SyQ=B9|j;pOM}|BSbs3#tZ&DwC`SUl#Yzw2Q6$9pOmI~e3!Ec14H`O9 z4F<7TNI`<2H6%9x&-Hca`p(+q~R*zo&}LbZR#5-xQ$F$Bt#)vO$?HcggMjf#kW z>UC&xW~rWFqMt`@gDlx|trW0xXTfJZdUja4^p+e@o87pDQUEL4wXe8?eo8kF4oAln^CSkDidQZ-?+y|;UO#w?|C(2Dx!p@3l3dE07~DnTrgI!8x& z#Mx?8K44$B)$jIC=oU2=Scls525g%Uz1M*Pi>10J!0#=f0q=-eYXC0(l{>70bUvVc4@@xEqaO1RgGyN!gA9Q zd9OdO;+$cZsF5;_tv79bj`g4K2_?^Z95=hQOH>AxBs8Tg6Bspl#Vwl-^m^hGvUX>~ z+PJOGh63G44Xo9KT58$0t$Rj~n1T;RtAvr+ zh(}jlcs|7`ivomU-)?pgnKFkA-myavnkJAha4{aMcL&!HvX}gM@Xxn2-(A8&r|cfb z*}mTktba`V;w-${eUAHLFSK23jpN6<#UE(TPRcfI#`(X``a0a#*nKWP7rb<>e?-6T zobWaKZ?8_qCjsih*9uKVc0cl!1suLSI>(irhd7}Z(+lA|oG$v4x%zPzPQgCm*5q&C zdR-!(G2;8HX9Cv!s&207kKVG0-3 zYh9w9kEQ1IL2lAV4~qU4h;BUMTvLgs5;>#pp>Bb@@T1RpLGMvlZ?BbEF9m}da_Upd z6NP@f5@(MivTNIg$^w0Uf|JM(YbUw7cI%$`pG>O-k?+kj^n#E#bcK-KAE5X4(KSJQ z;cFZY0?8!ED8Bx_$AdS;i>BC~sHirncb(2kkXKJv@j1^B|5su60~<9J z#{s;^KXGOR8C-^fb2v5}`{RHiPLOkBAZ&W>)PV@2>$>f>yX$DXu}wgPM9d^eVhAv@ z=?pl+1Y(>a8gWq^n?aEa%AX-ffCxtZ|3?<}_xkScwZFB!k_JN755L#GzB~HoeJ?KA z)FTb;-E=JZTGznaL*?j`m!DYFF>CL4{ym2jp=bAT-;x7+Dx_p`-$)Zb!a9vsThzhQNK(jYF+ByN41sIuJm@Kq{wQxf>4EdHu zrdG`>xU>~EKL+bK;=mH5pm~$FCjWWCE0=i6K*kdo`A3f#?-^ zMGSrK*6%%X+$#ES+}aSwanFy1Y50RG{jCnJIEGcVyxLdn=RMxkDt{R^64wmt*alU_ z!xnIfQd?+ir@(8G;Yq9MF)a24^M^GE}JB;+S?*pH8UxdE8uL0L`FiXdT8>T&7gOQ@Q_noeT8d_i-WvJy! zp&1g|JJ^XGeyF`A8s<%c9`Llm`4~dc!$;5SDVBM;?gbhC6DP`PPC>2aRY{(akv^kP z_NXHHL#k3^=p3Z28wNM8{0OFvaQN`4u)fTO7iGy^?h(BuX6Cjz>aCR5Ic~@*j!Q9= ztkl|={xYvtrY!O$R^_%AB%Rp-Bgu!*myPt_2d(J>u~d{rzYylls$Mt5dFc*R8vuTa zq3Y8CYnq-liZ{=&|1Hm)sJ%U1hoE0Chx(ykYYXk>6AoMdBWAq5pDcp|IlGbj^iS}n z0{56f&izd%`$*P$jz>^o7=!+TM>292mG7)5bb}zlY8)?0kLV-%QMb;m0p2sz-2FS5?WPqDZn?p_7__xeVt3_ZF;4R1FT} zTaKC(nkSWc1gD?(*42x$E1Zaqiyg4G@?jTf0<3Wcbt-&bgip9o^IwuwQ5RW{wGXPk z_~d0!7Q;&BOCSqvdY75z&dbiWE-gyl`IrD0p-lo{6<|iLs1m=2J(+Ca=_51gj_=RGzTY!&jr6^ab_QS_G^eOY=$w-4U>lwbw z47W_M*Y9EC;-q=zx=!edW+7Vil+{IP_4z;|ERJVqto*wvs}F0(HR60`hJAb54%5<_ zF^1z?8FulU4MyKM#2C(OWLVB$HW*EC#28L6W7z7;rkL&^U<)U1G3)WGddn<#gvE|v z6(?FTb;PxZsxIFOyEr6@xudQ}c3Dsmc5ws~b7O8qbajDD*u_ys%zg4^Bv&77gk2mI z#N08rBD%WRAndM0i95_qxgF8fS{NSg(*5`_J={A_f$uNwa zbT<+kdQ8A{RKf`>44!$<1g3S&YEDU}OnbrD?wMCz7#TI^OkXa2`)|U1NA*S%-T#U+^ZcT+oZLHxNu1q_htJBc!SJ&Ku Ua3KmV`@pXbxL$YCMZSjr4=og_V*mgE literal 0 HcmV?d00001 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 0000000000000000000000000000000000000000..ad3a8224ef25eab39d827901f94b51c7a18d3778 GIT binary patch literal 56190 zcmV*MKx4m9O9KQg000080000X0Jd>4e5OGF0BcMD02Tlg0BvP-VPs)+VJ~!Ob!}p9 zVQFkGaBgP-01yBG0000000000000000002(yLD8RUDr3dK?S5sT2N3xL>lQ35R{gd zMoQ_F29Yk28xf>KkQ9*a6i~Xm1(9x$JoCDr_j|wZoN@j?W1R6ahC|)#z4lsj&H0P9 z<`tr>D1(Phg^fa?@SZ-AQbD26_K`nW81PEx$ZRP5b=~gCb4L{FYA^B!t?cqV428Od zdMfou%{6g-+D%t&X+dnem!q+0>lX8^Cs?7CrfgNOc?WE=^hXoowJl6dwPy!ZY?rM$ zI}P6euERt9Jap3!NIY2>L;sAw_&1A*d@!!NE_i{?AAL=Oh2~k^jGaM9z`?4FE#jz5DlDR)_QE z|NMEinZ9y^iYl}}L&oxfG4erPVjNmy~t6@`uguQ_1&&1iJkMHU%7&YLPJB_K0L%gRaRFw_w@8+ z@0P>}5fObF{$|=a@%X6d!v|947}@pN2D-0bzphMH6wVy5>DLAyAG_x3)sQjByd(W+ z*-U{-OibLKa_oI&ee~x`%8QfzKm2aHcifLQBk-sn8cvkHI`+BTx=gFAq~PS_#KOXA z94XLwrlw}%^p_IWXrhsvoUB#)GO8-f*AJ7Rxw{+Bwsr^OgY4ZGFJA0_JvtaQXc-wH zi;0P`b8_;RXO#5z7B%Zlj@VgjUksx27I$#qLPtk0Ee{I`Y07?WN`D4MtUUSyTV4V25bMs!NGx$gk*5RdnMkm zkZuYeA787( z^+xFCbj^R~h^}sUem<*wvhX@N6({3+MbRdVmZO^_(}cwN>{Wtw`wHoT1fB?ene2 zfo2m!H|}e|+_5?t7#NBzN7+!~FJCez`&_tHR#i2%v|OBvyLA>I9)iMAUhjpXJ@Cri_6Ml zms^daqvAM?F_JxZpPrp>`H<@qU}1^7y9){n3o9!tqr7$~Z{CbxN_ItG8!5Pgs*CP< zsgHw?-=?Z0a;;1|;yMZA+_cN=cS!<~JK>l09!EA^i2|y&&jkc>Zae#~xmm*K`MJj0-Me>PH_AqfOgqVjMn+!z{BZC1;&dzF zff!P$T`VFZ(^HR8DET-JG}SMP*HCr5l%GC*LcLjEw@Mm?m7!2|9!D6;ns|k2Dmk}e zI|F8U3*B5@v0VN_oKSCecOCeJgek?_y`Hyypbd@e-$1AHHH1t3K6o+%YJ(_DW=sas$s z?&ACc0-tKI+{x0 z`}a>Z6zS2)$ul<1CH1AHJWhWGzE6Gcix+iX?)pT*Z5G}?_@(Xp_v<93sK#Uw4-Vrt z+yZBQFBT#Z4q_6L$%9ndqrAd~3#wkR%i5~2GzKm%;u7=Thc29iH*N&b`J55SePnGq z-dQA~rp`O4zCHM5bD|7~mX@~J!3!CMs7zKv<6~7=>SzQtUzgrhl=Jk^z`%f^rRC(x zeh#EWGxud~F3UV`x84C$is#$-cq${emKw*@P4wl%jmho3y+I+bT-nU#cQ=J@MLn@Q z+SF4_k(H8~kd>3`*1KAVjg5_r`lh17rDV-%b?E7F)rDS}nVLY3TCNLeMc~=l**=>s zzn4W2{>}L5SPbg#L_{LDR)d~-5EB!>*rX3e{|~chEy3=6mVw-=*{CU0WBFf+VE6iU zU{cb}cQgVo5ZWRlN-GIRHhSnyL4kG6imW-VsO0}ajYSCjWcxyquvfjACC*KF=vk;+I#$SNwfebuYc_G&IGDQP+TyB9H| zn4^{sKkDsSVgdpJz&K;D{qt*UlWaeo4_4KMkER?~hV#hvJvMlaFnIAoq|nQ>@p9C# zV`MY=ju#ge`f6NkQH?Ov{O0Dn$6;iz3LF<&ujAenBpn|gUl}WA7_#6MblD6qtUtky z6g^?4p`o#ZHyodw&~tDQMl&ij17pPhiwjih%F1s-NSM+M8oUc8l;pNl@M(pE{r#^x zZBA9Gw|^1*^XJd;d=MR=)XkinoQ-tdSat&pW%4QF5UJnJGBPqKLUg^96UWawIyxEE z)!ODsqFyIhr~MQ>F9~aFYyD?yT(;iH#j@RoF9znuh)IF1lD^N%>R(e+)8nA3u5O|A z{J9a3vFl1&kbLzl=5Rc(<;0R*R-R^|4f&Fw*9lJ`9(ADoV%t10PjE;`zx(-Ev2jsZ z+4oP}=I=jzxC)?XwEGbXh5q(!v<&HpxBnsE53-qdng#}!7w1t)NfGJk^mR)`6%{hE zY#QQ`i+lOs8r__Usb>dC=c z(9fT;C})@P!7obW`f^X6pim!TVy<`c_%OhT&HmR({Fe@93(b*M;Ma5SWM;5;FriI@&~V9zkVQ!4;!HUdH$xGq9T56U0t^tRdvev#6&!j zVK$ahCOo#bwg6MBtPJ#f^EU;FC>07cB-vsa`1!T8vXq(S%P)aEQO*VH5pID`Ojt%n zM)JtEPchfPmw& zVNap}YQN$|VS~JZ^2^+L_#i^dex1rHDsS~_Uf&iHqIPq0tF)V!kek6Cc04__228{j zyFBA2W78dDY=^kCw-AU;F`i~EbHZ1#vEj4VZojPxdt|}|govc_N7mK_0DhCdC??CTjZ+hduGGbt za8c^&>cWEPqdy5aGS0aDzBx8FHV1SBm>4m$%3kw&gGxnJb!W^t@=rcfj4U4Q1~w`* zENp XCJ%O-@cOqx|l9Vp0+j9o=kJdr_&$=Qt8EFZzKOD~|R!I2(#wY;0^R6J>c% zf2O`7)l^YQ=l#G)#QP4m07JlipZN~)bzs=OJWY1ggk)W=8cV@W;o{=r{L<2J`lc0V zCDf_~iU;pkaP}+UR<2;P)$S9LCp_Q#4uU&)_=~!{+J>SH2#KQjxAD(KQ&n=dyZL5Q zD=W3KMu%M5$rqDlQV1qV29BwyoY;sejc!7 zYHE5s+HesNfJ44Z$uLcVsAKODP1Ro;8{JfQ=(%5{R&cAUs~44*lWqC~NO3r?sugfx zqM+1kciO1OYTdZW*!8X6r4L*YFVHal-IK)cbK#kH82#zft8`+bXT}sO1&~V-P`>H4 zwKSkn8OMKT%EfZPyUrHrE*o1zNS*=aG&YLYtxZf!G*3)WvBb!J!6AyehfB%zd0ZeJ z&q!Wfgs2SnO5Kga^>M%M1inSEDU8%^_e4Z)0{pbWzHyp$Q3zigF9IMug6avxzZt5S zB>1XeYjM$!z5clQPP+}k)buo`FUa_QJ@`gTQU&Ruei8)tiea@Bb#2R z+urhgUSWN6FcE|QD7$WDDsSlvn1sI9f%=n7m1vsTDPREeO?u(?BZUT$L=4imVB*H@ z?;cxNus{KF8Z}=9!FlV>ovV;FPZSg$tErI!^q_a0l_XL-HP-S^yA0Z z1f5pi%(n!sS&@*E-pSWdR}bh(5|U($PD3I9aIHMrBbBDy*xZbM@7_H-2M6L22KvE; zo9;qT?ZqZPh^=PpZw?O+7nPJq%FE+gSX%Bh)t}(b$;IcKN9l`KUIGxf5+9MSEI5q$C^yD6ImCl3bh5Sc_tMz{Zn3&>l*+&PY#}pNNSJ4vue^TYjAnUxaAWt^1l^ zucAD+n=nD(jA+BJX{~A{ZQDgJj*b2O{ZoPOL1Q-=T%Kt92Lv?r_Y?V??O-BQo8o