diff --git a/Makefile b/Makefile index 0b80973f37..1f8b159a70 100644 --- a/Makefile +++ b/Makefile @@ -169,7 +169,7 @@ PROJ_OBJ += range.o app_handler.o static_mem.o PROJ_OBJ += commander.o crtp_commander.o crtp_commander_rpyt.o PROJ_OBJ += crtp_commander_generic.o crtp_localization_service.o PROJ_OBJ += attitude_pid_controller.o sensfusion6.o stabilizer.o -PROJ_OBJ += position_estimator_altitude.o position_controller_pid.o +PROJ_OBJ += position_estimator_altitude.o position_controller_pid.o position_controller_indi.o PROJ_OBJ += estimator.o estimator_complementary.o PROJ_OBJ += controller.o controller_pid.o controller_mellinger.o controller_indi.o PROJ_OBJ += power_distribution_$(POWER_DISTRIBUTION).o diff --git a/src/modules/interface/controller_indi.h b/src/modules/interface/controller_indi.h index 2f11e2180c..98f3dc3b46 100644 --- a/src/modules/interface/controller_indi.h +++ b/src/modules/interface/controller_indi.h @@ -33,6 +33,7 @@ #include "param.h" #include "position_controller.h" #include "attitude_controller.h" +#include "position_controller_indi.h" #define ATTITUDE_UPDATE_DT (float)(1.0f/ATTITUDE_RATE) @@ -43,13 +44,13 @@ #define STABILIZATION_INDI_FILT_CUTOFF_R STABILIZATION_INDI_FILT_CUTOFF // these parameters are used in the filtering of the angular acceleration -#define STABILIZATION_INDI_G1_P 0.0034724f -#define STABILIZATION_INDI_G1_Q 0.0052575f -#define STABILIZATION_INDI_G1_R -0.0015942f -#define STABILIZATION_INDI_G2_R -0.11281f -#define STABILIZATION_INDI_REF_ERR_P 3.57f -#define STABILIZATION_INDI_REF_ERR_Q 3.57f -#define STABILIZATION_INDI_REF_ERR_R 3.57f +#define STABILIZATION_INDI_G1_P 0.0066146f +#define STABILIZATION_INDI_G1_Q 0.0052125f +#define STABILIZATION_INDI_G1_R -0.001497f +#define STABILIZATION_INDI_G2_R 0.000043475f +#define STABILIZATION_INDI_REF_ERR_P 24.0f +#define STABILIZATION_INDI_REF_ERR_Q 24.0f +#define STABILIZATION_INDI_REF_ERR_R 24.0f #define STABILIZATION_INDI_REF_RATE_P 14.0f #define STABILIZATION_INDI_REF_RATE_Q 14.0f #define STABILIZATION_INDI_REF_RATE_R 14.0f diff --git a/src/modules/interface/position_controller_indi.h b/src/modules/interface/position_controller_indi.h new file mode 100644 index 0000000000..2c7e3750da --- /dev/null +++ b/src/modules/interface/position_controller_indi.h @@ -0,0 +1,87 @@ +/** + * || ____ _ __ + * +------+ / __ )(_) /_______________ _____ ___ + * | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \ + * +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/ + * || || /_____/_/\__/\___/_/ \__,_/ /___/\___/ + * + * Crazyflie control firmware + * + * Copyright (C) 2011-2016 Bitcraze AB + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, in version 3. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + * position_controller_indi.h - INDI Controller Interface + */ + +#ifndef __POSITION_CONTROLLER_INDI_H__ +#define __POSITION_CONTROLLER_INDI_H__ + +// Thrust command (in motor units) +#define MIN_THRUST 0 +#define MAX_THRUST 60000 + +// Cutoff frequency used in the filtering +#define POSITION_INDI_FILT_CUTOFF 8.0f + +#include "controller_indi.h" +#include "stabilizer_types.h" +#include "filter.h" +#include "math3d.h" +#include "log.h" +#include "param.h" + +struct Vectr { + float x; + float y; + float z; +}; + +struct Angles { + float phi; + float theta; + float psi; +}; + +struct IndiOuterVariables { + + Butterworth2LowPass ddxi[3]; + Butterworth2LowPass ang[3]; + Butterworth2LowPass thr[3]; + + float filt_cutoff; + float act_dyn_posINDI; + + struct Vectr linear_accel_ref; + struct Vectr linear_accel_err; + struct Vectr linear_accel_s; // acceleration sensed + struct Vectr linear_accel_f; // acceleration filtered + struct Vectr linear_accel_ft; // acceleration filtered transformed to NED + struct Angles attitude_s; // attitude senssed (here estimated) + struct Angles attitude_f; // attitude filtered + struct Angles attitude_c; // attitude commanded to the inner loop + float phi_tilde; // roll angle increment + float theta_tilde; // pitch angle increment + float T_tilde; // thrust increment + float T_inner; // thrust to inner INDI + float T_inner_f; + float T_incremented; +}; + +void positionControllerINDIInit(void); +void positionControllerINDI(const sensorData_t *sensors, + setpoint_t *setpoint, + const state_t *state, + vector_t *refOuterINDI); + +#endif //__POSITION_CONTROLLER_INDI_H__ diff --git a/src/modules/src/controller_indi.c b/src/modules/src/controller_indi.c index cab6d94f7f..ac7df2ced4 100644 --- a/src/modules/src/controller_indi.c +++ b/src/modules/src/controller_indi.c @@ -31,15 +31,20 @@ static float bound_control_input = 32000.0f; static attitude_t attitudeDesired; static attitude_t rateDesired; static float actuatorThrust; -static float roll_kp = 6.0f; -static float pitch_kp = 6.0f; -static float yaw_kp = 6.0f; +static float roll_kp = 5.0f; +static float pitch_kp = 5.0f; +static float yaw_kp = 5.0f; + +static float attYawError; static float r_roll; static float r_pitch; static float r_yaw; static float accelz; +static vector_t refOuterINDI; // Reference values from outer loop INDI +static bool outerLoopActive = false ; // if 1, outer loop INDI is activated + static struct IndiVariables indi = { .g1 = {STABILIZATION_INDI_G1_P, STABILIZATION_INDI_G1_Q, STABILIZATION_INDI_G1_R}, .g2 = STABILIZATION_INDI_G2_R, @@ -103,6 +108,21 @@ static inline void finite_difference_from_filter(float *output, Butterworth2LowP } } +static float capAngle(float angle) { + float result = angle; + + while (result > 180.0f) { + result -= 360.0f; + } + + while (result < -180.0f) { + result += 360.0f; + } + + return result; +} + + void controllerINDIInit(void) { /* @@ -119,6 +139,7 @@ void controllerINDIInit(void) attitudeControllerInit(ATTITUDE_UPDATE_DT); positionControllerInit(); + positionControllerINDIInit(); } bool controllerINDITest(void) @@ -149,7 +170,7 @@ void controllerINDI(control_t *control, setpoint_t *setpoint, } } - if (RATE_DO_EXECUTE(POSITION_RATE, tick)) { + if (RATE_DO_EXECUTE(POSITION_RATE, tick) && !outerLoopActive) { positionController(&actuatorThrust, &attitudeDesired, setpoint, state); } @@ -158,22 +179,57 @@ void controllerINDI(control_t *control, setpoint_t *setpoint, */ if (RATE_DO_EXECUTE(ATTITUDE_RATE, tick)) { + // Call outer loop INDI (position controller) + if (outerLoopActive) { + positionControllerINDI(sensors, setpoint, state, &refOuterINDI); + } + // Switch between manual and automatic position control if (setpoint->mode.z == modeDisable) { - actuatorThrust = setpoint->thrust; + // INDI position controller not active, INDI attitude controller is main loop + actuatorThrust = setpoint->thrust; + } else{ + if (outerLoopActive) { + // INDI position controller active, INDI attitude controller becomes inner loop + actuatorThrust = refOuterINDI.z; + } } - if (setpoint->mode.x == modeDisable || setpoint->mode.y == modeDisable) { - attitudeDesired.roll = setpoint->attitude.roll; - attitudeDesired.pitch = setpoint->attitude.pitch; + if (setpoint->mode.x == modeDisable) { + + // INDI position controller not active, INDI attitude controller is main loop + attitudeDesired.roll = setpoint->attitude.roll; + + }else{ + if (outerLoopActive) { + // INDI position controller active, INDI attitude controller becomes inner loop + attitudeDesired.roll = refOuterINDI.x; + } } + if (setpoint->mode.y == modeDisable) { + + // INDI position controller not active, INDI attitude controller is main loop + attitudeDesired.pitch = setpoint->attitude.pitch; + + }else{ + if (outerLoopActive) { + // INDI position controller active, INDI attitude controller becomes inner loop + attitudeDesired.pitch = refOuterINDI.y; + } + } + + // attitudeControllerCorrectAttitudePID(state->attitude.roll, state->attitude.pitch, state->attitude.yaw, // attitudeDesired.roll, attitudeDesired.pitch, attitudeDesired.yaw, // &rateDesired.roll, &rateDesired.pitch, &rateDesired.yaw); rateDesired.roll = roll_kp*(attitudeDesired.roll - state->attitude.roll); rateDesired.pitch = pitch_kp*(attitudeDesired.pitch - state->attitude.pitch); - rateDesired.yaw = yaw_kp*(attitudeDesired.yaw - state->attitude.yaw); + //rateDesired.yaw = yaw_kp*(attitudeDesired.yaw - state->attitude.yaw); + attYawError = attitudeDesired.yaw - state->attitude.yaw; + attYawError = capAngle(attYawError); + rateDesired.yaw = yaw_kp*attYawError; + // For roll and pitch, if velocity mode, overwrite rateDesired with the setpoint // value. Also reset the PID to avoid error buildup, which can lead to unstable @@ -228,14 +284,11 @@ void controllerINDI(control_t *control, setpoint_t *setpoint, float attitude_error_q = radians(rateDesired.pitch) - stateAttitudeRatePitch; float attitude_error_r = radians(rateDesired.yaw) - stateAttitudeRateYaw; - indi.angular_accel_ref.p = indi.reference_acceleration.err_p * attitude_error_p - - indi.reference_acceleration.rate_p * body_rates.p; + indi.angular_accel_ref.p = indi.reference_acceleration.err_p * attitude_error_p; - indi.angular_accel_ref.q = indi.reference_acceleration.err_q * attitude_error_q - - indi.reference_acceleration.rate_q * body_rates.q; + indi.angular_accel_ref.q = indi.reference_acceleration.err_q * attitude_error_q; - indi.angular_accel_ref.r = indi.reference_acceleration.err_r * attitude_error_r - - indi.reference_acceleration.rate_r * body_rates.r; + indi.angular_accel_ref.r = indi.reference_acceleration.err_r * attitude_error_r; /* * 5. Update the For each axis: delta_command = 1/control_effectiveness * (angular_acceleration_reference – angular_acceleration) @@ -247,7 +300,7 @@ void controllerINDI(control_t *control, setpoint_t *setpoint, //(they have significant inertia, see the paper mentioned in the header for more explanation) indi.du.p = 1.0f / indi.g1.p * (indi.angular_accel_ref.p - indi.rate_d[0]); indi.du.q = 1.0f / indi.g1.q * (indi.angular_accel_ref.q - indi.rate_d[1]); - indi.du.r = 1.0f / (indi.g1.r + indi.g2) * (indi.angular_accel_ref.r - indi.rate_d[2] + indi.g2 * indi.du.r); + indi.du.r = 1.0f / (indi.g1.r - indi.g2) * (indi.angular_accel_ref.r - indi.rate_d[2] - indi.g2 * indi.du.r); /* @@ -299,6 +352,7 @@ void controllerINDI(control_t *control, setpoint_t *setpoint, control->roll = indi.u_in.p; control->pitch = indi.u_in.q; control->yaw = indi.u_in.r; + } PARAM_GROUP_START(ctrlINDI) @@ -322,6 +376,7 @@ PARAM_ADD(PARAM_FLOAT, act_dyn_q, &indi.act_dyn.q) PARAM_ADD(PARAM_FLOAT, act_dyn_r, &indi.act_dyn.r) PARAM_ADD(PARAM_FLOAT, filt_cutoff, &indi.filt_cutoff) PARAM_ADD(PARAM_FLOAT, filt_cutoff_r, &indi.filt_cutoff_r) +PARAM_ADD(PARAM_UINT8, outerLoopActive, &outerLoopActive) PARAM_GROUP_STOP(ctrlINDI) LOG_GROUP_START(ctrlINDI) diff --git a/src/modules/src/position_controller_indi.c b/src/modules/src/position_controller_indi.c new file mode 100644 index 0000000000..2724935747 --- /dev/null +++ b/src/modules/src/position_controller_indi.c @@ -0,0 +1,351 @@ +/* + * + * Copyright (c) 2019 Ewoud Smeur and Evghenii Volodscoi + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, in version 3. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + * This control algorithm is the Incremental Nonlinear Dynamic Inversion (INDI) + * controller to control the position of the Crazyflie. It can be seen as an extension + * (outer loop) to the already existing INDI attitude controller (inner loop). + * + * The control algorithm was implemented according to the publication in the + * journal od Control Engineering Practice: Cascaded Incremental Nonlinear Dynamic + * Inversion for MAV Disturbance Rejection + * https://doi.org/10.1016/j.conengprac.2018.01.003 + */ + + +#include "position_controller_indi.h" + +// Position controller gains +float K_xi_x = 1.0f; +float K_xi_y = 1.0f; +float K_xi_z = 1.0f; +// Velocity controller gains +float K_dxi_x = 5.0f; +float K_dxi_y = 5.0f; +float K_dxi_z = 5.0f; +// Thrust mapping parameter +float K_thr = 0.00024730f; + +static float posS_x, posS_y, posS_z; // Current position +static float velS_x, velS_y, velS_z; // Current velocity +static float gyr_p, gyr_q, gyr_r; // Current rates + +// Reference values +static struct Vectr positionRef; +static struct Vectr velocityRef; + + +static struct IndiOuterVariables indiOuter = { + .filt_cutoff = POSITION_INDI_FILT_CUTOFF, + .act_dyn_posINDI = STABILIZATION_INDI_ACT_DYN_P +}; + + +void position_indi_init_filters(void) +{ + // tau = 1/(2*pi*Fc) + float tau = 1.0f / (2.0f * PI * indiOuter.filt_cutoff); + float tau_axis[3] = {tau, tau, tau}; + float sample_time = 1.0f / ATTITUDE_RATE; + // Filtering of linear acceleration, attitude and thrust + for (int8_t i = 0; i < 3; i++) { + init_butterworth_2_low_pass(&indiOuter.ddxi[i], tau_axis[i], sample_time, 0.0f); + init_butterworth_2_low_pass(&indiOuter.ang[i], tau_axis[i], sample_time, 0.0f); + init_butterworth_2_low_pass(&indiOuter.thr[i], tau_axis[i], sample_time, 0.0f); + } +} + +// Linear acceleration filter +static inline void filter_ddxi(Butterworth2LowPass *filter, struct Vectr *old_values, struct Vectr *new_values) +{ + new_values->x = update_butterworth_2_low_pass(&filter[0], old_values->x); + new_values->y = update_butterworth_2_low_pass(&filter[1], old_values->y); + new_values->z = update_butterworth_2_low_pass(&filter[2], old_values->z); +} + +// Attitude filter +static inline void filter_ang(Butterworth2LowPass *filter, struct Angles *old_values, struct Angles *new_values) +{ + new_values->phi = update_butterworth_2_low_pass(&filter[0], old_values->phi); + new_values->theta = update_butterworth_2_low_pass(&filter[1], old_values->theta); + new_values->psi = update_butterworth_2_low_pass(&filter[2], old_values->psi); +} + +// Thrust filter +static inline void filter_thrust(Butterworth2LowPass *filter, float *old_thrust, float *new_thrust) +{ + *new_thrust = update_butterworth_2_low_pass(&filter[0], *old_thrust); +} + + +// Computes transformation matrix from body frame (index B) into NED frame (index O) +void m_ob(struct Angles att, float matrix[3][3]) { + + matrix[0][0] = cosf(att.theta)*cosf(att.psi); + matrix[0][1] = sinf(att.phi)*sinf(att.theta)*cosf(att.psi) - cosf(att.phi)*sinf(att.psi); + matrix[0][2] = cosf(att.phi)*sinf(att.theta)*cosf(att.psi) + sinf(att.phi)*sinf(att.psi); + matrix[1][0] = cosf(att.theta)*sinf(att.psi); + matrix[1][1] = sinf(att.phi)*sinf(att.theta)*sinf(att.psi) + cosf(att.phi)*cosf(att.psi); + matrix[1][2] = cosf(att.phi)*sinf(att.theta)*sinf(att.psi) - sinf(att.phi)*cosf(att.psi); + matrix[2][0] = -sinf(att.theta); + matrix[2][1] = sinf(att.phi)*cosf(att.theta); + matrix[2][2] = cosf(att.phi)*cosf(att.theta); +} + + +void positionControllerINDIInit(void) +{ + // Re-initialize filters + position_indi_init_filters(); +} + + +void positionControllerINDI(const sensorData_t *sensors, + setpoint_t *setpoint, + const state_t *state, + vector_t *refOuterINDI){ + + // Read states (position, velocity) + posS_x = state->position.x; + posS_y = -state->position.y; + posS_z = -state->position.z; + velS_x = state->velocity.x; + velS_y = -state->velocity.y; + velS_z = -state->velocity.z; + gyr_p = sensors->gyro.x; + gyr_q = sensors->gyro.y; + gyr_r = sensors->gyro.z; + + // Read in velocity setpoints + velocityRef.x = setpoint->velocity.x; + velocityRef.y = -setpoint->velocity.y; + velocityRef.z = -setpoint->velocity.z; + + // Position controller (Proportional) + if (setpoint->mode.x == modeAbs) { + positionRef.x = setpoint->position.x; + velocityRef.x = K_xi_x*(positionRef.x - posS_x); + } + if (setpoint->mode.y == modeAbs) { + positionRef.y = -setpoint->position.y; + velocityRef.y = K_xi_y*(positionRef.y - posS_y); + } + if (setpoint->mode.z == modeAbs) { + positionRef.z = -setpoint->position.z; + velocityRef.z = K_xi_z*(positionRef.z - posS_z); + } + + // Velocity controller (Proportional) + indiOuter.linear_accel_ref.x = K_dxi_x*(velocityRef.x - velS_x); + indiOuter.linear_accel_ref.y = K_dxi_y*(velocityRef.y - velS_y); + indiOuter.linear_accel_ref.z = K_dxi_z*(velocityRef.z - velS_z); + + // Acceleration controller (INDI) + // Read lin. acceleration (Body-fixed) obtained from sensors CHECKED + indiOuter.linear_accel_s.x = (sensors->acc.x)*9.81f; + indiOuter.linear_accel_s.y = (-sensors->acc.y)*9.81f; + indiOuter.linear_accel_s.z = (-sensors->acc.z)*9.81f; + + // Filter lin. acceleration + filter_ddxi(indiOuter.ddxi, &indiOuter.linear_accel_s, &indiOuter.linear_accel_f); + + // Obtain actual attitude values (in deg) + indiOuter.attitude_s.phi = state->attitude.roll; + indiOuter.attitude_s.theta = state->attitude.pitch; + indiOuter.attitude_s.psi = -state->attitude.yaw; + filter_ang(indiOuter.ang, &indiOuter.attitude_s, &indiOuter.attitude_f); + + + // Actual attitude (in rad) + struct Angles att = { + .phi = indiOuter.attitude_f.phi/180*PI, + .theta = indiOuter.attitude_f.theta/180*PI, + .psi = indiOuter.attitude_f.psi/180*PI, + }; + + // Compute transformation matrix from body frame (index B) into NED frame (index O) + float M_OB[3][3] = {0}; + m_ob(att, M_OB); + + // Transform lin. acceleration in NED (add gravity to the z-component) + indiOuter.linear_accel_ft.x = M_OB[0][0]*indiOuter.linear_accel_f.x + M_OB[0][1]*indiOuter.linear_accel_f.y + M_OB[0][2]*indiOuter.linear_accel_f.z; + indiOuter.linear_accel_ft.y = M_OB[1][0]*indiOuter.linear_accel_f.x + M_OB[1][1]*indiOuter.linear_accel_f.y + M_OB[1][2]*indiOuter.linear_accel_f.z; + indiOuter.linear_accel_ft.z = M_OB[2][0]*indiOuter.linear_accel_f.x + M_OB[2][1]*indiOuter.linear_accel_f.y + M_OB[2][2]*indiOuter.linear_accel_f.z + 9.81f; + + // Compute lin. acceleration error + indiOuter.linear_accel_err.x = indiOuter.linear_accel_ref.x - indiOuter.linear_accel_ft.x; + indiOuter.linear_accel_err.y = indiOuter.linear_accel_ref.y - indiOuter.linear_accel_ft.y; + indiOuter.linear_accel_err.z = indiOuter.linear_accel_ref.z - indiOuter.linear_accel_ft.z; + + // Elements of the G matrix (see publication for more information) + // ("-" because T points in neg. z-direction, "*9.81" because T/m=a=g, + // negative psi to account for wrong coordinate frame in the implementation of the inner loop) + float g11 = (cosf(att.phi)*sinf(-att.psi) - sinf(att.phi)*sinf(att.theta)*cosf(-att.psi))*(-9.81f); + float g12 = (cosf(att.phi)*cosf(-att.theta)*cosf(-att.psi))*(-9.81f); + float g13 = (sinf(att.phi)*sinf(-att.psi) + cosf(att.phi)*sinf(att.theta)*cosf(-att.psi)); + float g21 = (-cosf(att.phi)*cosf(-att.psi) - sinf(att.phi)*sinf(att.theta)*sinf(-att.psi))*(-9.81f); + float g22 = (cosf(att.phi)*cosf(att.theta)*sinf(-att.psi))*(-9.81f); + float g23 = (-sinf(att.phi)*cosf(-att.psi) + cosf(att.phi)*sinf(att.theta)*sinf(-att.psi)); + float g31 = (-sinf(att.phi)*cosf(att.theta))*(-9.81f); + float g32 = (-cosf(att.phi)*sinf(att.theta))*(-9.81f); + float g33 = (cosf(att.phi)*cosf(att.theta)); + + // Next four blocks of the code are to compute the Moore-Penrose inverse of the G matrix + // (G'*G) + float a11 = g11*g11 + g21*g21 + g31*g31; + float a12 = g11*g12 + g21*g22 + g31*g32; + float a13 = g11*g13 + g21*g23 + g31*g33; + float a21 = g12*g11 + g22*g21 + g32*g31; + float a22 = g12*g12 + g22*g22 + g32*g32; + float a23 = g12*g13 + g22*g23 + g32*g33; + float a31 = g13*g11 + g23*g21 + g33*g31; + float a32 = g13*g12 + g23*g22 + g33*g32; + float a33 = g13*g13 + g23*g23 + g33*g33; + + // Determinant of (G'*G) + float detG = (a11*a22*a33 + a12*a23*a31 + a21*a32*a13) - (a13*a22*a31 + a11*a32*a23 + a12*a21*a33); + + // Inverse of (G'*G) + float a11_inv = (a22*a33 - a23*a32)/detG; + float a12_inv = (a13*a32 - a12*a33)/detG; + float a13_inv = (a12*a23 - a13*a22)/detG; + float a21_inv = (a23*a31 - a21*a33)/detG; + float a22_inv = (a11*a33 - a13*a31)/detG; + float a23_inv = (a13*a21 - a11*a23)/detG; + float a31_inv = (a21*a32 - a22*a31)/detG; + float a32_inv = (a12*a31 - a11*a32)/detG; + float a33_inv = (a11*a22 - a12*a21)/detG; + + // G_inv = (G'*G)_inv*G' + float g11_inv = a11_inv*g11 + a12_inv*g12 + a13_inv*g13; + float g12_inv = a11_inv*g21 + a12_inv*g22 + a13_inv*g23; + float g13_inv = a11_inv*g31 + a12_inv*g32 + a13_inv*g33; + float g21_inv = a21_inv*g11 + a22_inv*g12 + a23_inv*g13; + float g22_inv = a21_inv*g21 + a22_inv*g22 + a23_inv*g23; + float g23_inv = a21_inv*g31 + a22_inv*g32 + a23_inv*g33; + float g31_inv = a31_inv*g11 + a32_inv*g12 + a33_inv*g13; + float g32_inv = a31_inv*g21 + a32_inv*g22 + a33_inv*g23; + float g33_inv = a31_inv*g31 + a32_inv*g32 + a33_inv*g33; + + // Lin. accel. error multiplied G^(-1) matrix (T_tilde negated because motor accepts only positiv commands, angles are in rad) + indiOuter.phi_tilde = (g11_inv*indiOuter.linear_accel_err.x + g12_inv*indiOuter.linear_accel_err.y + g13_inv*indiOuter.linear_accel_err.z); + indiOuter.theta_tilde = (g21_inv*indiOuter.linear_accel_err.x + g22_inv*indiOuter.linear_accel_err.y + g23_inv*indiOuter.linear_accel_err.z); + indiOuter.T_tilde = -(g31_inv*indiOuter.linear_accel_err.x + g32_inv*indiOuter.linear_accel_err.y + g33_inv*indiOuter.linear_accel_err.z)/K_thr; + + // Filter thrust + filter_thrust(indiOuter.thr, &indiOuter.T_incremented, &indiOuter.T_inner_f); + + // Pass thrust through the model of the actuator dynamics + indiOuter.T_inner = indiOuter.T_inner + indiOuter.act_dyn_posINDI*(indiOuter.T_inner_f - indiOuter.T_inner); + + // Compute trust that goes into the inner loop + indiOuter.T_incremented = indiOuter.T_tilde + indiOuter.T_inner; + + // Compute commanded attitude to the inner INDI + indiOuter.attitude_c.phi = indiOuter.attitude_f.phi + indiOuter.phi_tilde*180/PI; + indiOuter.attitude_c.theta = indiOuter.attitude_f.theta + indiOuter.theta_tilde*180/PI; + + // Clamp commands + indiOuter.T_incremented = clamp(indiOuter.T_incremented, MIN_THRUST, MAX_THRUST); + indiOuter.attitude_c.phi = clamp(indiOuter.attitude_c.phi, -10.0f, 10.0f); + indiOuter.attitude_c.theta = clamp(indiOuter.attitude_c.theta, -10.0f, 10.0f); + + // Reference values, which are passed to the inner loop INDI (attitude controller) + refOuterINDI->x = indiOuter.attitude_c.phi; + refOuterINDI->y = indiOuter.attitude_c.theta; + refOuterINDI->z = indiOuter.T_incremented; + +} + + +PARAM_GROUP_START(posCtrlIndi) + +// Position controller gain +PARAM_ADD(PARAM_FLOAT, K_xi_x, &K_xi_x) +PARAM_ADD(PARAM_FLOAT, K_xi_y, &K_xi_y) +PARAM_ADD(PARAM_FLOAT, K_xi_z, &K_xi_z) + +// Velocity Controller gain +PARAM_ADD(PARAM_FLOAT, K_dxi_x, &K_dxi_x) +PARAM_ADD(PARAM_FLOAT, K_dxi_y, &K_dxi_y) +PARAM_ADD(PARAM_FLOAT, K_dxi_z, &K_dxi_z) + +PARAM_GROUP_STOP(posCtrlIndi) + + + +LOG_GROUP_START(posCtrlIndi) + +// Angular veocity +LOG_ADD(LOG_FLOAT, gyr_p, &gyr_p) +LOG_ADD(LOG_FLOAT, gyr_q, &gyr_q) +LOG_ADD(LOG_FLOAT, gyr_r, &gyr_r) + +LOG_ADD(LOG_FLOAT, posRef_x, &positionRef.x) +LOG_ADD(LOG_FLOAT, posRef_y, &positionRef.y) +LOG_ADD(LOG_FLOAT, posRef_z, &positionRef.z) + +// Velocity +LOG_ADD(LOG_FLOAT, velS_x, &velS_x) +LOG_ADD(LOG_FLOAT, velS_y, &velS_y) +LOG_ADD(LOG_FLOAT, velS_z, &velS_z) + +LOG_ADD(LOG_FLOAT, velRef_x, &velocityRef.x) +LOG_ADD(LOG_FLOAT, velRef_y, &velocityRef.y) +LOG_ADD(LOG_FLOAT, velRef_z, &velocityRef.z) + +// Attitude +LOG_ADD(LOG_FLOAT, angS_roll, &indiOuter.attitude_s.phi) +LOG_ADD(LOG_FLOAT, angS_pitch, &indiOuter.attitude_s.theta) +LOG_ADD(LOG_FLOAT, angS_yaw, &indiOuter.attitude_s.psi) + +LOG_ADD(LOG_FLOAT, angF_roll, &indiOuter.attitude_f.phi) +LOG_ADD(LOG_FLOAT, angF_pitch, &indiOuter.attitude_f.theta) +LOG_ADD(LOG_FLOAT, angF_yaw, &indiOuter.attitude_f.psi) + +// Acceleration +LOG_ADD(LOG_FLOAT, accRef_x, &indiOuter.linear_accel_ref.x) +LOG_ADD(LOG_FLOAT, accRef_y, &indiOuter.linear_accel_ref.y) +LOG_ADD(LOG_FLOAT, accRef_z, &indiOuter.linear_accel_ref.z) + +LOG_ADD(LOG_FLOAT, accS_x, &indiOuter.linear_accel_s.x) +LOG_ADD(LOG_FLOAT, accS_y, &indiOuter.linear_accel_s.y) +LOG_ADD(LOG_FLOAT, accS_z, &indiOuter.linear_accel_s.z) + +LOG_ADD(LOG_FLOAT, accF_x, &indiOuter.linear_accel_f.x) +LOG_ADD(LOG_FLOAT, accF_y, &indiOuter.linear_accel_f.y) +LOG_ADD(LOG_FLOAT, accF_z, &indiOuter.linear_accel_f.z) + +LOG_ADD(LOG_FLOAT, accFT_x, &indiOuter.linear_accel_ft.x) +LOG_ADD(LOG_FLOAT, accFT_y, &indiOuter.linear_accel_ft.y) +LOG_ADD(LOG_FLOAT, accFT_z, &indiOuter.linear_accel_ft.z) + +LOG_ADD(LOG_FLOAT, accErr_x, &indiOuter.linear_accel_err.x) +LOG_ADD(LOG_FLOAT, accErr_y, &indiOuter.linear_accel_err.y) +LOG_ADD(LOG_FLOAT, accErr_z, &indiOuter.linear_accel_err.z) + +// INDI outer loop variables +LOG_ADD(LOG_FLOAT, phi_tilde, &indiOuter.phi_tilde) +LOG_ADD(LOG_FLOAT, theta_tilde, &indiOuter.theta_tilde) +LOG_ADD(LOG_FLOAT, T_tilde, &indiOuter.T_tilde) + +LOG_ADD(LOG_FLOAT, T_inner, &indiOuter.T_inner) +LOG_ADD(LOG_FLOAT, T_inner_f, &indiOuter.T_inner_f) +LOG_ADD(LOG_FLOAT, T_incremented, &indiOuter.T_incremented) + +LOG_ADD(LOG_FLOAT, cmd_phi, &indiOuter.attitude_c.phi) +LOG_ADD(LOG_FLOAT, cmd_theta, &indiOuter.attitude_c.theta) + +LOG_GROUP_STOP(posCtrlIndi) diff --git a/tools/param_est/data_1901.csv b/tools/param_est/data_1901.csv new file mode 100644 index 0000000000..2a00da0296 --- /dev/null +++ b/tools/param_est/data_1901.csv @@ -0,0 +1,19093 @@ +tick,controller.r_roll,controller.r_pitch,controller.r_yaw,controller.cmd_thrust,controller.cmd_roll,controller.cmd_pitch,controller.cmd_yaw,controller.accelz +3289,-1.59503088070778E-05,0.003872921224684,0.000828228250612,0,0,0,0,1.00976705551147 +3291,0.000251831748756,0.00215102522634,-0.001312573091127,0,0,0,0,1.0101352930069 +3293,-0.002783923409879,0.001706727780402,-0.002711599925533,0,0,0,0,1.0105345249176 +3295,-0.002558840904385,0.002265559276566,-0.0007610177272,0,0,0,0,1.0106897354126 +3297,0.001761235413142,0.00203463062644,0.000742934294976,0,0,0,0,1.01061463356018 +3299,0.00278721167706,0.001221807557158,0.00039657446905,0,0,0,0,1.01026928424835 +3301,0.000381080579245,0.001097918022424,0.002061161212623,0,0,0,0,1.01005971431732 +3303,-0.001234997762367,0.001365354517475,0.003026916878298,0,0,0,0,1.01010859012604 +3305,-0.000458778638858,-0.000374300318072,0.000964447448496,0,0,0,0,1.01008367538452 +3307,0.001487443805672,-0.001499482081272,-0.00051908387104,0,0,0,0,1.01000034809113 +3309,0.001965255243704,-0.000424875091994,0.00086103315698,0,0,0,0,1.0100349187851 +3311,0.002706098137423,0.000461023038952,0.000852690485772,0,0,0,0,1.01025652885437 +3313,0.002862851368263,0.001091828686185,0.001035432913341,0,0,0,0,1.01077401638031 +3315,-0.00024171579571,0.002564041176811,0.001067697652616,0,0,0,0,1.01110231876373 +3317,-0.004317389335483,0.003914585337043,0.000669886707328,0,0,0,0,1.01126754283905 +3319,-0.005505752749741,0.004445073660463,0.000186020333786,0,0,0,0,1.01146399974823 +3321,-0.001462352927774,0.001445587608032,-0.000107204454252,0,0,0,0,1.01170599460602 +3323,0.001990262884647,-0.002518367487937,0.000363261293387,0,0,0,0,1.01173305511475 +3325,0.002820051275194,-0.002816352294758,0.000350496236933,0,0,0,0,1.01138556003571 +3327,0.003498348407447,-0.001600818824954,0.000170256840647,0,0,0,0,1.01106441020966 +3329,0.002374432981014,-0.000872998090927,0.001203445950523,0,0,0,0,1.01087176799774 +3331,-0.000613617594354,-0.001377597567625,0.000857177597936,0,0,0,0,1.01056158542633 +3333,-0.001905017183162,-0.002970959758386,-0.001009355881251,0,0,0,0,1.01016318798065 +3335,-0.000704193953425,-0.004022599197924,-0.000150168983964,0,0,0,0,1.0092579126358 +3337,0.001116232131608,-0.002140753204003,0.001794178388082,0,0,0,0,1.00760579109192 +3339,0.002111413748935,0.000693679729011,0.003587828250602,0,0,0,0,1.00554370880127 +3341,0.001625041593798,0.002061707666144,0.003692750819027,0,0,0,0,1.00373637676239 +3343,0.001398269319907,0.002738802693784,0.002988421823829,0,0,0,0,1.0025120973587 +3345,0.000748033053242,0.001657032058574,0.003953143954277,0,0,0,0,1.00169408321381 +3347,0.000906016444787,-0.001005523721688,0.003722442546859,0,0,0,0,1.00082755088806 +3349,0.001637062523514,-0.00343990791589,0.00026757500018,0,0,0,0,0.99981427192688 +3351,0.000692372210324,-0.004196587949991,-0.00074672215851,0,0,0,0,0.99902331829071 +3353,-0.000826470553875,-0.002823973074555,-0.000103242142359,0,0,0,0,0.998697519302368 +3355,-0.001757681136951,0.000891900330316,-0.000752174353693,0,0,0,0,0.998782694339752 +3357,-0.000131561973831,0.004071353469044,-0.000850069976877,0,0,0,0,0.999009609222412 +3359,0.002361367922276,0.00573036307469,-0.000258617306827,0,0,0,0,0.998797118663788 +3361,0.003085346193984,0.003362682880834,-0.000963944708928,0,0,0,0,0.998414397239685 +3363,0.003084845142439,-0.00096880045021,-0.001028733793646,0,0,0,0,0.998379051685333 +3365,0.001474397373386,-0.003278425894678,-7.69828257034533E-05,0,0,0,0,0.99863862991333 +3367,-0.001696932129562,-0.00183590175584,0.000678202253766,0,0,0,0,0.998982071876526 +3369,-0.002019577194005,0.000995623297058,0.00032069417648,0,0,0,0,0.999183118343353 +3371,-0.001097640022635,0.003048225771636,-0.000399218377424,0,0,0,0,0.998997867107391 +3373,-0.000522228423506,0.003817387856543,-0.00124479830265,0,0,0,0,0.998964369297028 +3375,0.000932092021685,0.002067655092105,-0.001440320746042,0,0,0,0,0.999087631702423 +3377,0.000860373897012,-0.002465134020895,0.000692541711032,0,0,0,0,0.999069690704346 +3379,-0.001046426943503,-0.003525734413415,0.003691089339554,0,0,0,0,0.998745620250702 +3381,-0.000582939828746,-2.16430853470229E-05,0.003412594320253,0,0,0,0,0.998309195041656 +3383,-0.000175230234163,0.003545200685039,-0.000383388163755,0,0,0,0,0.998109400272369 +3385,-0.002597681712359,0.00377663387917,-0.000858982850332,0,0,0,0,0.998232245445251 +3387,-0.004536028020084,0.000891784729902,0.001267559942789,0,0,0,0,0.998613119125366 +3389,-0.003374579595402,-0.001179663231596,-9.3804846983403E-05,0,0,0,0,0.99910831451416 +3391,-0.001870485837571,-0.002359226346016,-0.002753908745945,0,0,0,0,0.999434113502502 +3393,0.001234309514984,-0.001979923807085,-0.004448626656085,0,0,0,0,0.999578773975372 +3395,0.002776834182441,-0.001819455763325,-0.002389546250924,0,0,0,0,0.999505400657654 +3397,0.002305928850546,-0.002852131379768,0.00266624474898,0,0,0,0,0.999527812004089 +3399,0.001601921627298,-0.002721447264776,0.006948417983949,0,0,0,0,0.999867975711822 +3401,0.0012246822007,-0.001731584430672,0.005585178267211,0,0,0,0,1.000319480896 +3403,-1.04835612546594E-06,0.000934561132453,0.001906462362967,0,0,0,0,1.00056791305542 +3405,0.000567975803278,0.002864288166165,-0.001401143963449,0,0,0,0,1.00035953521729 +3407,0.002473295666277,0.000957327254582,-0.002479592105374,0,0,0,0,0.999927699565887 +3409,0.002293651690707,0.001097914297134,-0.001814124872908,0,0,0,0,0.999621570110321 +3411,0.002415639581159,0.00246551935561,-0.001426041009836,0,0,0,0,0.999670386314392 +3413,0.004321273881942,0.001554367132485,-0.00247076456435,0,0,0,0,0.999968528747559 +3415,0.004567984025925,-0.000123293371871,-0.001863528625108,0,0,0,0,1.00038135051727 +3417,0.00263092527166,0.001810690504499,0.000868792529218,0,0,0,0,1.0006992816925 +3419,0.00121852918528,0.00360583839938,0.003122954862192,0,0,0,0,1.00068736076355 +3421,0.00087784382049,0.001657285611145,0.001798622659408,0,0,0,0,1.00055861473084 +3423,-6.62595193716697E-05,-0.001459744409658,-0.000217787441215,0,0,0,0,1.00050461292267 +3425,-0.001595911337063,-0.001229615649208,-0.001159913023002,0,0,0,0,1.00056004524231 +3427,-0.003313122317195,0.002447582315654,-0.00110382924322,0,0,0,0,1.00063693523407 +3429,-0.003699327353388,0.005462438799441,-0.000191990504391,0,0,0,0,1.00063025951386 +3431,0.000116011382488,0.003077932167798,0.003443789435551,0,0,0,0,1.00073325634003 +3433,0.003385998075828,-0.002954737748951,0.00494132284075,0,0,0,0,1.00089430809021 +3435,0.004788589663804,-0.006260673049837,0.000211332691833,0,0,0,0,1.00109124183655 +3437,0.005447012372315,-0.00478013465181,-0.003640085691586,0,0,0,0,1.00131046772003 +3439,0.002001102315262,-0.002282629720867,-0.002940009348094,0,0,0,0,1.0013040304184 +3441,-0.001691896119155,-0.001069389516488,-0.000741945172194,0,0,0,0,1.00129914283752 +3443,-0.001834171358496,-0.001714236685075,0.001292365137488,0,0,0,0,1.00135064125061 +3445,0.000886077061296,-0.002900576917455,0.003081983653829,0,0,0,0,1.00157594680786 +3447,0.003539766883478,-0.001553112873808,0.002035199897364,0,0,0,0,1.00182843208313 +3449,0.004387782886624,8.06191310402937E-05,-0.000657571537886,0,0,0,0,1.00195026397705 +3451,0.001605915022083,0.000507345073856,-0.000618377234787,0,0,0,0,1.0019463300705 +3453,-0.002491075079888,-0.001334872213192,0.000194105159608,0,0,0,0,1.00190138816834 +3455,-0.003487611655146,-0.002420905744657,0.00063802965451,0,0,0,0,1.00189161300659 +3457,-0.002928660484031,0.001768947346136,0.001309312763624,0,0,0,0,1.00178599357605 +3459,-0.000213216524571,0.004374380223453,0.002702279482037,0,0,0,0,1.00175952911377 +3461,0.002648007823154,0.00183658557944,0.001159348641522,0,0,0,0,1.00171947479248 +3463,0.00425879098475,0.000946294807363,0.000912630523089,0,0,0,0,1.00185894966125 +3465,0.006009361706674,0.002253437181935,0.003660150105134,0,0,0,0,1.00225341320038 +3467,0.005936945322901,0.002808328252286,0.000904439541046,0,0,0,0,1.00242245197296 +3469,0.003164863679558,0.003326448379084,-0.004974933341146,0,0,0,0,1.0023068189621 +3471,-0.000260554603301,0.002792273182422,-0.003995944745839,0,0,0,0,1.00204372406006 +3473,-0.00294376257807,0.001381861744449,0.00229250243865,0,0,0,0,1.00180912017822 +3475,-0.003144582267851,0.003595563350245,0.004513973835856,0,0,0,0,1.00170493125916 +3477,-0.001201446633786,0.006872666999698,0.001603889395483,0,0,0,0,1.00153625011444 +3479,-9.14023330551572E-05,0.004294072277844,-0.00392390973866,0,0,0,0,1.00104105472565 +3481,-0.000866303918883,-0.000830089789815,-0.007607131265104,0,0,0,0,1.00052177906036 +3483,-0.001498127938248,-0.000557145802304,-0.006560848560184,0,0,0,0,1.00032162666321 +3485,-0.002592099830508,0.002115220297128,-0.002469870494679,0,0,0,0,1.00023114681244 +3487,-0.001704199588858,0.001689334982075,0.001657735672779,0,0,0,0,1.00032269954681 +3489,0.001237364951521,0.002920386381447,0.002999852411449,0,0,0,0,1.00060820579529 +3491,0.002453847089782,0.005586947780103,0.001156586688012,0,0,0,0,1.00068211555481 +3493,0.001278812997043,0.005992085207254,-0.001254696166143,0,0,0,0,1.00036597251892 +3495,0.001596602844074,0.003625184763223,-0.002901113359258,0,0,0,0,0.999894082546234 +3497,0.004076150245965,0.000747134443372,-0.005047981161624,0,0,0,0,0.99944257736206 +3499,0.003248789114878,0.000128619212774,-0.00525802699849,0,0,0,0,0.998850166797638 +3501,-0.0005567825865,0.001594938570634,-0.00169937312603,0,0,0,0,0.998512029647827 +3503,-0.002428928622976,-0.000473186315503,-7.46149016777053E-05,0,0,0,0,0.998580157756805 +3505,5.68742552786716E-06,-0.003903345670551,-0.001203052815981,0,0,0,0,0.998800873756409 +3507,0.002773527055979,-0.00539842993021,-0.001921769464388,0,0,0,0,0.998918235301971 +3509,0.004061050247401,-0.004458128940314,-0.001141422428191,0,0,0,0,0.998919188976288 +3511,0.003861859440804,-0.00096565077547,-0.00137470162008,0,0,0,0,0.999196350574493 +3513,-0.000392205867684,0.001472170464695,-0.002762384014204,0,0,0,0,0.999887764453888 +3515,-0.004803912714124,0.002205418189988,-0.001062582130544,0,0,0,0,1.00088024139404 +3517,-0.004065093118697,0.002492216182873,-0.000861014297698,0,0,0,0,1.00169491767883 +3519,-0.003242690116167,0.000582424632739,-0.000823047303129,0,0,0,0,1.00218224525452 +3521,-0.004464608151466,-0.002446961821988,0.000313360651489,0,0,0,0,1.00235378742218 +3523,-0.003233011579141,-0.001920762355439,0.000319690996548,0,0,0,0,1.00218200683594 +3525,-0.002224540803581,0.000689039297868,0.000864466070198,0,0,0,0,1.00188255310059 +3527,-0.001732308766805,-0.000141781987622,0.000816214480437,0,0,0,0,1.00172197818756 +3529,-0.000750969105866,-0.003110516117886,-0.000420349097112,0,0,0,0,1.00169932842255 +3531,0.000851017131936,-0.003801447106525,0.001703414600343,0,0,0,0,1.00156342983246 +3533,0.002968153683469,-0.002750959713012,0.002116721821949,0,0,0,0,1.00116765499115 +3535,0.003357296111062,-0.000966315332334,-0.001368648256175,0,0,0,0,1.00053644180298 +3537,0.000874459510669,-0.000218503832002,-0.00234716385603,0,0,0,0,1.00004923343658 +3539,-1.04394111986039E-05,2.2363621610566E-05,0.001014899462461,0,0,0,0,1.00014996528625 +3541,0.000100478653621,-0.001462460495532,0.004387340974063,0,0,0,0,1.00031363964081 +3543,-0.000277477724012,-0.002484559779987,0.003451388794929,0,0,0,0,0.999885618686676 +3545,0.000707245548256,0.001511762966402,0.000993248540908,0,0,0,0,0.999306738376617 +3547,0.002040430437773,0.006828653626144,-0.002157481852919,0,0,0,0,0.999146103858948 +3549,0.004409462213516,0.006472008302808,-0.003854785580188,0,0,0,0,0.999456226825714 +3551,0.003934235312045,0.002435996895656,-0.001956654014066,0,0,0,0,1.00004851818085 +3553,0.00119768618606,0.001999934203923,-0.000186157747521,0,0,0,0,1.00083351135254 +3555,7.29874518583529E-05,0.003288208274171,0.002582454588264,0,0,0,0,1.00183343887329 +3557,3.91192588722333E-05,0.001655417261645,0.002653207164258,0,0,0,0,1.0026193857193 +3559,0.001301839132793,-0.000596602505539,0.000491959042847,0,0,0,0,1.00271034240723 +3561,0.002345788059756,0.000453457265394,-0.001023387303576,0,0,0,0,1.00230181217194 +3563,7.65323202358559E-05,0.001458562444896,-0.002643649931997,0,0,0,0,1.00168144702911 +3565,-0.002819934627041,0.001134318765253,-0.001430764677934,0,0,0,0,1.00098812580109 +3567,-0.002141600707546,0.001906871562824,0.002639924874529,0,0,0,0,1.00056087970734 +3569,-0.001328795216978,0.002267357660458,0.002169000217691,0,0,0,0,1.00060033798218 +3571,-0.002406516112387,0.001161390915513,-0.001068054581992,0,0,0,0,1.00075602531433 +3573,-0.003417073981836,0.000600238039624,-0.000701170414686,0,0,0,0,1.00062870979309 +3575,-0.000901498075109,0.00096017238684,0.002965093124658,0,0,0,0,1.00045108795166 +3577,0.001730158110149,0.002371429931372,0.004176904447377,0,0,0,0,1.00049090385437 +3579,0.002373265568167,0.003501987084746,0.000635223463178,0,0,0,0,1.0005521774292 +3581,0.002606809837744,0.001455391873606,-0.002377779455855,0,0,0,0,1.00035762786865 +3583,0.003088500816375,-0.00087658787379,-0.002674084389582,0,0,0,0,0.999866485595703 +3585,0.00198593782261,-0.001414146274328,2.85415735561401E-05,0,0,0,0,0.999363839626312 +3587,0.000843294255901,-0.001935433712788,5.63018438697327E-05,0,0,0,0,0.998998641967773 +3589,0.00157431117259,-0.002009524730966,-0.003745233640075,0,0,0,0,0.998834908008575 +3591,0.00242303381674,-8.19254455564078E-06,-0.004362372215837,0,0,0,0,0.998957455158233 +3593,-3.24311549775302E-05,0.002293195575476,-0.000555376580451,0,0,0,0,0.999343812465668 +3595,-0.004241249989718,0.002322053303942,0.001945924712345,0,0,0,0,0.999728679656982 +3597,-0.005288890562952,0.000345731212292,8.01379283075221E-05,0,0,0,0,1.00003302097321 +3599,-0.004282797686756,-0.001292587607168,-0.000561943277717,0,0,0,0,1.00008749961853 +3601,-0.002177007729188,-0.000897054967936,-0.00085351895541,0,0,0,0,1.00034713745117 +3603,0.000452241278253,0.003348441328853,-0.001240397337824,0,0,0,0,1.00118803977966 +3605,0.001858335803263,0.006987660191953,-0.000482389266836,0,0,0,0,1.00210011005402 +3607,0.001641341950744,0.005412428639829,0.000257700361544,0,0,0,0,1.00271821022034 +3609,0.000944452127442,0.002511062659323,0.001813135575503,0,0,0,0,1.00307714939117 +3611,0.000278959807474,0.002460916293785,0.003059031441808,0,0,0,0,1.00300908088684 +3613,0.000162974683917,0.002511454280466,0.000869300507475,0,0,0,0,1.0029536485672 +3615,0.000607756548561,0.0009444305324,-0.000905019871425,0,0,0,0,1.00277948379517 +3617,-0.000257796695223,-0.001117401872762,0.000658693083096,0,0,0,0,1.00237369537354 +3619,-0.00179720018059,-0.002808350371197,0.002340343315154,0,0,0,0,1.00165629386902 +3621,-0.001649962505326,-0.003613933455199,0.000839697604533,0,0,0,0,1.0008796453476 +3623,-0.000746264646295,-0.002563966903836,-0.000674922368489,0,0,0,0,1.00067138671875 +3625,0.001371239777654,0.00128437159583,-3.34489996021148E-05,0,0,0,0,1.00091278553009 +3627,0.002693228889257,0.004656450357288,0.002138913376257,0,0,0,0,1.00124907493591 +3629,-0.000214864645386,0.003021971555427,0.004280531778932,0,0,0,0,1.00131952762604 +3631,-0.001661877613515,-0.0016598647926,0.00578987877816,0,0,0,0,1.00124800205231 +3633,-0.002077161334455,-0.003133980790153,0.005484587047249,0,0,0,0,1.00113689899445 +3635,-0.001538393669762,-0.000434136221884,0.00388219114393,0,0,0,0,1.00090718269348 +3637,-0.000636888900772,0.002389343222603,0.000126413287944,0,0,0,0,1.0007004737854 +3639,0.00066531955963,0.002793296705931,-0.00102611607872,0,0,0,0,1.00074768066406 +3641,0.000296230777167,0.00244224187918,-0.000221814712859,0,0,0,0,1.00087463855743 +3643,-0.002615614794195,0.001580143580213,2.61332297668559E-05,0,0,0,0,1.00089263916016 +3645,-0.002955630421638,0.000132229470182,0.001587364007719,0,0,0,0,1.00115084648132 +3647,0.000199357076781,0.00056573440088,0.000864182657097,0,0,0,0,1.00148212909698 +3649,0.001165986293927,0.003856818191707,-0.004812327213585,0,0,0,0,1.00163984298706 +3651,0.000190104692592,0.004571735858917,-0.006686013191938,0,0,0,0,1.00189304351807 +3653,0.001329842838459,0.002317572943866,-0.002680414356291,0,0,0,0,1.00179409980774 +3655,0.001748355105519,0.001176149933599,0.001568525098264,0,0,0,0,1.001056432724 +3657,0.00088306167163,-0.00031977207982,0.002908111782745,0,0,0,0,1.00021004676819 +3659,0.001037092762999,-0.00064704590477,-0.000700141652487,0,0,0,0,0.999437749385834 +3661,-0.000191041035578,-1.79126909642946E-05,-0.003086246550083,0,0,0,0,0.998910307884216 +3663,-0.003771739080548,-0.001560421660542,-0.003580150427297,0,0,0,0,0.998741865158081 +3665,-0.004176659043878,-0.005243007559329,-0.000277867569821,0,0,0,0,0.999028921127319 +3667,-0.00133192143403,-0.006276966072619,0.005279486067593,0,0,0,0,0.999692618846893 +3685,0.004178386181593,0.002456089947373,0.00028007075889,0,0,0,0,1.00062763690948 +3687,0.006049648858607,-0.000256274128333,-0.001637119217776,0,0,0,0,1.00018954277039 +3689,0.004018165636808,-0.001522226491943,-0.003272616537288,0,0,0,0,1.00009441375732 +3691,-0.000781581620686,-0.00226658093743,-0.00336302886717,0,0,0,0,1.00015985965729 +3693,-0.005883239209652,-0.000568905088585,-0.000992477172986,0,0,0,0,1.00011789798737 +3695,-0.006602437701076,0.001973621780053,0.000424482743256,0,0,0,0,0.999930024147034 +3697,-0.003198860911652,0.002594036282972,0.001383211114444,0,0,0,0,0.999918043613434 +3699,0.000783042865805,0.003465459914878,0.00051784038078,0,0,0,0,1.00007104873657 +3701,0.003358285408467,0.003333435859531,-0.003626337973401,0,0,0,0,1.00021910667419 +3703,0.003592484397814,0.00083427602658,-0.003141907276586,0,0,0,0,1.00041997432709 +3705,0.001045138109475,-0.001896397094242,0.00242930278182,0,0,0,0,1.00068378448486 +3707,-0.001889218459837,-0.004094360861927,0.003761966247112,0,0,0,0,1.00090634822845 +3709,-0.001706000999548,-0.005154054611921,0.002114678034559,0,0,0,0,1.00069153308868 +3711,-0.000893364485819,-0.002039635321125,-0.000258893938735,0,0,0,0,1.00015711784363 +3713,-0.002930715912953,0.002855499042198,-0.001525381812826,0,0,0,0,0.999728798866272 +3715,-0.002260638400912,0.004112876951694,-0.001501769176684,0,0,0,0,0.999535858631134 +3717,0.000998607953079,0.001616889145225,0.000317467725836,0,0,0,0,0.999338924884796 +3719,0.000943647755776,-0.000253471836913,0.002326608868316,0,0,0,0,0.99898773431778 +3721,-7.992305472726E-05,0.000258129322901,0.003875221125782,0,0,0,0,0.998744010925293 +3723,-0.00122962507885,0.00153034622781,0.003270551329479,0,0,0,0,0.998673856258392 +3725,-0.002487650373951,0.001857748255134,0.001166609930806,0,0,0,0,0.998736143112183 +3727,-0.001989844953641,5.95370374867343E-06,-0.00041345693171,0,0,0,0,0.998646080493927 +3729,-0.000303367356537,-0.001805368927307,-0.000232819467783,0,0,0,0,0.998382270336151 +3731,0.001920311246067,-0.001702420529909,0.000253007106949,0,0,0,0,0.998148560523987 +3733,0.002084352774546,-0.001477020094171,0.000922426872421,0,0,0,0,0.998169004917145 +3735,0.00031048359233,-0.002592321485281,0.001771018607542,0,0,0,0,0.998417615890503 +3737,-0.00137862295378,-0.003601443953812,0.00232757255435,0,0,0,0,0.998589336872101 +3739,-0.000687057385221,-0.000725706573576,0.004849538672715,0,0,0,0,0.998987317085266 +3741,0.002231873571873,0.003047357080504,0.006232307292521,0,0,0,0,0.99956214427948 +3743,0.003316898364574,0.002877708757296,0.004305822774768,0,0,0,0,1.00008869171143 +3745,0.002151073655114,0.001065438846126,0.00102237786632,0,0,0,0,1.0007336139679 +3747,0.001192595111206,0.000682284589857,-0.000717737188097,0,0,0,0,1.00115966796875 +3749,-0.000816333980765,0.003317489288747,-0.00028189830482,0,0,0,0,1.00125348567963 +3751,-0.003317368216813,0.007008151616901,0.00071434804704,0,0,0,0,1.00148725509644 +3753,-0.004072440322489,0.006777090486139,0.002173613756895,0,0,0,0,1.00155401229858 +3755,-0.002156709553674,0.003108699806035,0.00185626395978,0,0,0,0,1.00116097927094 +3757,-0.000938514480367,0.00058259308571,-0.001277584698983,0,0,0,0,1.00091874599457 +3759,-0.000835441169329,0.001289807027206,-0.003469194751233,0,0,0,0,1.0010449886322 +3761,0.000588673166931,0.003296324750409,-0.002141310600564,0,0,0,0,1.00114500522614 +3763,0.002139106858522,0.002049164380878,0.00147389608901,0,0,0,0,1.00137448310852 +3765,0.000935118703637,-0.001750736031681,0.000256266066572,0,0,0,0,1.00179708003998 +3767,-0.000928097811993,-0.002960975514725,-0.003223947482184,0,0,0,0,1.00200712680817 +3769,-0.000881122774445,-0.001265452825464,-0.00282423873432,0,0,0,0,1.00176453590393 +3771,-4.2086628582183E-07,0.000993271823972,-0.001330198603682,0,0,0,0,1.00129210948944 +3773,0.001714803511277,0.001427647308446,-0.002408885164186,0,0,0,0,1.00114357471466 +3775,0.003840941237286,-0.001159333973192,-0.004902257584035,0,0,0,0,1.00115931034088 +3777,0.004287179093808,-0.001776263234206,-0.00474010547623,0,0,0,0,1.00091004371643 +3779,0.002937143901363,-0.001727725262754,-0.002389281988144,0,0,0,0,1.0004802942276 +3781,4.58155627711676E-05,-0.001756169949658,3.17658123094588E-05,0,0,0,0,1.00013911724091 +3783,-0.002080579288304,-0.002892422489822,0.002281861845404,0,0,0,0,1.00005722045898 +3785,-0.001934404368512,-0.005842318292707,0.001985917566344,0,0,0,0,1.00023305416107 +3787,-0.002291405806318,-0.006600592285395,0.001453952398151,0,0,0,0,1.00072753429413 +3789,-0.002050418639556,-0.008085935376585,0.000142554490594,0,0,0,0,1.00122129917145 +3791,-0.00185592030175,-0.00776227703318,0.000121542725537,0,0,0,0,1.00142526626587 +3793,-0.001909876824357,-0.002433999441564,0.000961212033872,0,0,0,0,1.00140368938446 +3795,-0.001262762118131,0.002258380642161,-0.001319502829574,0,0,0,0,1.00130021572113 +3797,0.000793192826677,0.003188058966771,-0.003021488199011,0,0,0,0,1.00140607357025 +3799,0.00101205194369,0.000292943092063,-0.002260184148327,0,0,0,0,1.00148856639862 +3801,-0.001434307545424,-0.001263406360522,-0.001786282053217,0,0,0,0,1.0013974905014 +3803,-0.003833734197542,0.002901797182858,-0.002165408572182,0,0,0,0,1.00140237808228 +3805,-0.003426668699831,0.006668302696198,-0.00278181466274,0,0,0,0,1.00150322914124 +3807,0.001043499680236,0.004009133204818,-0.002013830468059,0,0,0,0,1.00152933597565 +3809,0.003219446865842,0.000250026787398,0.000254362064879,0,0,0,0,1.00140929222107 +3811,0.000492407300044,-0.002072575734928,-3.16273435601033E-05,0,0,0,0,1.00115847587585 +3813,-0.001537521719001,-0.001747227506712,-0.001943717594258,0,0,0,0,1.00098824501038 +3815,0.0007960734074,-0.000624205684289,-0.002891960320994,0,0,0,0,1.00068664550781 +3817,0.004962742328644,-0.002097397111356,-0.002497379900888,0,0,0,0,1.00001776218414 +3819,0.005551097914577,-0.002122933976352,-0.000511809368618,0,0,0,0,0.999445915222168 +3821,0.002175253815949,-0.00165320141241,0.001056575565599,0,0,0,0,0.999544560909271 +3823,-0.001602230244316,-0.001466409303248,0.001000413554721,0,0,0,0,1.00033128261566 +3825,-0.002977546304464,-0.001681179041043,-0.000998640549369,0,0,0,0,1.00119602680206 +3827,-0.001586242229678,-0.002674239687622,-0.002435509115458,0,0,0,0,1.00183010101318 +3829,-0.001128899981268,-0.003448371775448,-0.001741145853885,0,0,0,0,1.00208222866058 +3831,-0.000963292783126,-0.004470347426832,0.000648954766802,0,0,0,0,1.00231504440308 +3833,0.00117154722102,-0.002638661535457,0.003008810570464,0,0,0,0,1.00236713886261 +3835,0.001852694782428,-0.000204073294299,0.001334980479442,0,0,0,0,1.0019896030426 +3837,0.000628284760751,-0.000662480480969,-0.002248228760436,0,0,0,0,1.00155460834503 +3839,0.001905731740408,-0.000398455566028,-0.002506691962481,0,0,0,0,1.00121188163757 +3841,0.002875556703657,-0.000676303927321,3.84786544600502E-05,0,0,0,0,1.00083804130554 +3843,0.001151553238742,-0.004531809594482,0.001859977259301,0,0,0,0,1.00075316429138 +3845,-0.000679352902807,-0.008464818820357,0.000327474932419,0,0,0,0,1.0010792016983 +3847,0.000989247695543,-0.00737585593015,-0.003853964619339,0,0,0,0,1.00125074386597 +3849,0.003187044989318,-0.003940696828067,-0.004762419499457,0,0,0,0,1.00135600566864 +3851,0.003689081408083,-0.001746957888827,-0.00513099739328,0,0,0,0,1.00161409378052 +3853,0.003021369688213,0.000277191895293,-0.006493095774204,0,0,0,0,1.00193250179291 +3855,0.001554619637318,0.003570775967091,-0.002950578462332,0,0,0,0,1.00212860107422 +3857,-0.000950131565332,0.005464387591928,0.001566156744957,0,0,0,0,1.00205707550049 +3859,-0.003378728171811,0.00293718255125,0.003518341807649,0,0,0,0,1.00202786922455 +3861,-0.003346865065396,0.000461315969005,0.000637069519144,0,0,0,0,1.00209414958954 +3863,-6.68028587824665E-05,0.001154910190962,-0.002147454768419,0,0,0,0,1.00216674804688 +3865,0.001762164989486,0.004252122715116,-0.002271842677146,0,0,0,0,1.00241267681122 +3867,-0.000501518137753,0.005863540340215,-0.00156225671526,0,0,0,0,1.00255656242371 +3869,-0.001684676855803,0.003776047145948,-0.000377438263968,0,0,0,0,1.00243294239044 +3871,-0.000837521627545,-0.002524414798245,-0.001459096092731,0,0,0,0,1.00187337398529 +3873,0.001021399744786,-0.003836540272459,-0.001318281982094,0,0,0,0,1.00093841552734 +3875,0.001434633042663,0.001853312249295,-0.00103890360333,0,0,0,0,1.00034725666046 +3877,0.000543405418284,0.004192339722067,-0.003313865978271,0,0,0,0,1.00048804283142 +3879,0.000428961007856,0.002078661462292,-0.006641992833465,0,0,0,0,1.00089275836945 +3881,-0.000366926658899,0.001760860090144,-0.005248441826552,0,0,0,0,1.00132083892822 +3883,-0.00144381262362,0.003143012756482,0.00048054632498,0,0,0,0,1.00152230262756 +3885,-0.001905567129143,0.001155184698291,0.003820187179372,0,0,0,0,1.00145053863525 +3887,-0.001831801258959,-0.001321900053881,0.002831497928128,0,0,0,0,1.00146913528442 +3889,-0.001002999488264,-0.000467833539005,0.002192679792643,0,0,0,0,1.00135779380798 +3891,0.000623378786258,0.000917382538319,0.001653659855947,0,0,0,0,1.00100290775299 +3893,0.000339262012858,0.001013746950775,0.000474854256026,0,0,0,0,1.00068652629852 +3895,-0.001378346350975,0.001108856289648,0.000416181515902,0,0,0,0,1.00039398670197 +3897,0.001738660153933,-0.00181967462413,0.000602548825555,0,0,0,0,0.999925494194031 +3921,-0.003647752571851,0.001945838797838,0.001300891512074,0,0,0,0,0.99990701675415 +3923,-0.004398335237056,0.003598552197218,0.000849810428917,0,0,0,0,0.999710440635681 +3925,-0.002781030489132,0.0030975677073,-0.000235722138314,0,0,0,0,0.999572396278381 +3927,-0.000158945651492,3.70799607480876E-05,-0.002109715947881,0,0,0,0,0.999377846717834 +3929,0.001496856450103,-0.001176394871436,-0.0030014696531,0,0,0,0,0.999080300331116 +3931,0.002143041230738,-0.000906898523681,-0.003221623599529,0,0,0,0,0.998904705047607 +3933,0.002077545505017,-0.000426967948442,-0.002440584823489,0,0,0,0,0.998875260353088 +3935,0.003484504995868,-0.000587697257288,-0.001789386267774,0,0,0,0,0.999179482460022 +3937,0.004880411084741,0.000578947307076,-0.002469410654157,0,0,0,0,0.999377489089966 +3939,0.004504967946559,0.004153118934482,-0.001134419348091,0,0,0,0,0.999334394931793 +3941,0.001711445860565,0.005516765639186,0.001213455339894,0,0,0,0,0.999451458454132 +3943,0.000165626974194,0.005011432804167,0.001302466145717,0,0,0,0,0.999370992183685 +3945,-0.000780867587309,0.004939960315824,-0.000447710190201,0,0,0,0,0.998983919620514 +3947,-0.0033054407686,0.003064648713917,-0.000564831483644,0,0,0,0,0.9987433552742 +3949,-0.003323385259137,0.001190769020468,-0.000737006543204,0,0,0,0,0.998822331428528 +3951,-0.002898344770074,0.001126125105657,-0.001126370276324,0,0,0,0,0.99909919500351 +3953,-0.002071524038911,-0.001231080503203,0.00155630253721,0,0,0,0,0.999475538730621 +3955,-0.000533158192411,-0.003084777388722,0.002811372745782,0,0,0,0,0.999921679496765 +3957,0.000488478806801,0.000411182612879,0.001132815843448,0,0,0,0,1.00029373168945 +3959,0.002276286482811,0.004222349729389,-3.95074748666957E-05,0,0,0,0,1.00086200237274 +3961,0.003184194909409,0.003902533557266,3.43192150467075E-05,0,0,0,0,1.00161337852478 +3963,0.00042866016156,0.001956798136234,-0.000233158309129,0,0,0,0,1.00220060348511 +3965,-0.001457426231354,-0.000883672211785,-0.000266601564363,0,0,0,0,1.00249242782593 +3967,-0.001591700362042,-0.002621257677674,-0.000192925988813,0,0,0,0,1.00274920463562 +3969,-0.002350042806938,-0.003571212757379,0.001434874953702,0,0,0,0,1.00292038917542 +3971,-0.002673081820831,-0.002891807118431,0.002740189665928,0,0,0,0,1.00270819664001 +3973,-0.000288685783744,-0.000509708013851,0.001208033179864,0,0,0,0,1.00245440006256 +3975,0.002059765392914,0.000662950973492,-0.000593674427364,0,0,0,0,1.00246179103851 +3977,0.001188067137264,-0.000144920559251,-0.000658545759507,0,0,0,0,1.00258457660675 +3979,0.000524855102412,9.15038253879175E-05,-0.00062667374732,0,0,0,0,1.00269317626953 +3981,0.001806778018363,0.001285744248889,-0.000423725694418,0,0,0,0,1.00239443778992 +3983,0.000570329546463,0.000721284537576,-0.000319873855915,0,0,0,0,1.00189507007599 +3985,-0.000727444130462,-0.001430885517038,-0.000239039494772,0,0,0,0,1.00149261951447 +3987,0.0009708860307,-0.001330926199444,0.000148707724293,0,0,0,0,1.00103640556335 +3989,0.001709109870717,-0.003131245262921,-0.001460943487473,0,0,0,0,1.00069344043732 +3991,0.001355692278594,-0.0052256193012,-0.000511789228767,0,0,0,0,1.00061941146851 +3993,0.001151163247414,-0.004538472741842,0.00252763624303,0,0,0,0,1.00060963630676 +3995,0.000532036356162,-0.00215870863758,0.001762559870258,0,0,0,0,1.00039684772491 +3997,0.001482587074861,6.85176200931892E-05,-0.00011947510211,0,0,0,0,0.999816000461578 +3999,0.004321503918618,-0.000596164551098,0.000741756113712,0,0,0,0,0.999217689037323 +4001,0.004173119552434,-0.003984853625298,0.001147226197645,0,0,0,0,0.999027073383331 +4003,8.67848721100017E-05,-0.006696002557874,0.002463163342327,0,0,0,0,0.999269068241119 +4005,-0.002106336178258,-0.005628160201013,0.003687974298373,0,0,0,0,0.999753832817077 +4007,-0.001092948950827,-0.001298701041378,0.002374654635787,0,0,0,0,1.00030028820038 +4009,-0.000524645438418,0.000951890309807,0.000159253380843,0,0,0,0,1.00058221817017 +4011,-0.002195471199229,-0.000151928412379,0.00052622432122,0,0,0,0,1.00051355361938 +4013,-0.003300611628219,-0.002252612728626,0.002233346458524,0,0,0,0,1.00073337554932 +4015,-0.001976148691028,-0.002390635898337,0.001403944450431,0,0,0,0,1.00113332271576 +4017,0.00208232877776,-0.001168795162812,-0.001722839777358,0,0,0,0,1.00130474567413 +4019,0.006015339866281,-0.000200786031201,-0.002205710392445,0,0,0,0,1.00122654438019 +4021,0.005787407513708,0.000530897639692,-0.000889365037438,0,0,0,0,1.00108659267426 +4023,0.002146433107555,0.001200087717734,-0.001944676274434,0,0,0,0,1.00125956535339 +4025,-0.000700478383806,0.002030729316175,-0.003451500087976,0,0,0,0,1.0015743970871 +4027,0.000324236869346,0.000574029050767,-0.003153157187626,0,0,0,0,1.0016405582428 +4029,0.00024486539769,-0.001785175409168,-0.000861217849888,0,0,0,0,1.00163340568542 +4031,-0.001536408206448,-0.002267239615321,-0.000362652877811,0,0,0,0,1.00166487693787 +4033,-0.003137967549264,-0.000999620417133,-0.002353245625272,0,0,0,0,1.00200963020325 +4035,-0.002873337594792,-0.001457289443351,-0.00292506814003,0,0,0,0,1.00239741802216 +4037,-0.002637375378981,-0.00456279842183,-0.002236668020487,0,0,0,0,1.00232553482056 +4039,-0.001429380266927,-0.006325490772724,-0.003134857630357,0,0,0,0,1.00182449817657 +4041,0.001034192391671,-0.003655975917354,-0.004874891601503,0,0,0,0,1.0012571811676 +4043,0.002063978696242,-0.000921629427467,-0.004987522959709,0,0,0,0,1.00092279911041 +4045,0.001458626589738,0.002386752748862,-0.00207791174762,0,0,0,0,1.00047695636749 +4047,0.001313199172728,0.005802812520415,0.001493412069976,0,0,0,0,0.99974775314331 +4049,0.001554321614094,0.006370578426868,0.000727572245523,0,0,0,0,0.999106824398041 +4051,0.00178937392775,0.002582942135632,-0.000627524917945,0,0,0,0,0.998874008655548 +4053,0.001128178322688,-0.002302913693711,-0.001041785231791,0,0,0,0,0.998854756355285 +4073,-0.000857230392285,-0.000762165465858,0.00047663479927,0,0,0,0,1.00159049034119 +4075,-0.001176812802441,-0.003510773181915,0.002353353658691,0,0,0,0,1.00143826007843 +4077,-0.000761937408242,-0.003441629000008,0.001492311246693,0,0,0,0,1.00123345851898 +4079,-0.001472838688642,0.001291401335038,-0.002149575389922,0,0,0,0,1.00107085704803 +4081,-0.000864169211127,0.002032535150647,-0.003362758550793,0,0,0,0,1.00111627578735 +4083,-0.000851278367918,0.000602799991611,-0.001284249825403,0,0,0,0,1.00143361091614 +4085,-0.001787676592357,-0.000497352215461,0.00131098239217,0,0,0,0,1.00178396701813 +4087,-0.000461698538857,-0.00017072353512,0.000321698113112,0,0,0,0,1.00202190876007 +4089,0.001745884655975,0.003524844069034,-0.003320963121951,0,0,0,0,1.00193130970001 +4091,0.001326487865299,0.006394359283149,-0.004332093056291,0,0,0,0,1.00159096717834 +4093,-2.76926257356536E-05,0.006293997634202,-0.001372951897793,0,0,0,0,1.00104939937592 +4095,-0.001983374822885,0.003998918458819,-0.000209230696782,0,0,0,0,1.00055491924286 +4097,-0.001263057929464,0.001583834527992,-0.001595747773536,0,0,0,0,1.00039374828339 +4099,0.000419041200075,-0.000123811885715,-0.001503615290858,0,0,0,0,1.00055170059204 +4101,0.001422067405656,-0.000944475235883,-0.001587574719451,0,0,0,0,1.00060665607452 +4103,0.003331596264616,6.45498221274465E-05,-0.000767292222008,0,0,0,0,1.00033986568451 +4105,0.006760354153812,0.00138547224924,0.000592982338276,0,0,0,0,1.00005555152893 +4107,0.007357281632721,0.001016459893435,0.000258093379671,0,0,0,0,1.00003302097321 +4109,0.003476754762232,0.001594373374246,0.000624468375463,0,0,0,0,1.00028312206268 +4111,-0.000996753806248,0.002851407276466,0.001376611879095,0,0,0,0,1.00015187263489 +4113,-0.002888004062697,0.0009998382302,-0.000972658279352,0,0,0,0,0.999567329883575 +4115,-0.001800653059036,-0.002274977974594,-0.000286045455141,0,0,0,0,0.998967111110687 +4117,0.000151221334818,-0.003826765576378,0.000982034951448,0,0,0,0,0.998620569705963 +4119,0.000496046850458,-0.002010549418628,-0.001874061650597,0,0,0,0,0.99831759929657 +4121,-0.000334375130478,0.002428676234558,-0.005140651017427,0,0,0,0,0.997816503047943 +4123,-0.002038203412667,0.005987646989524,-0.003427201183513,0,0,0,0,0.997487962245941 +4125,-0.002159905619919,0.004933691583574,-0.002265416551381,0,0,0,0,0.9974205493927 +4127,0.000272561330348,0.003169183852151,-0.001816406962462,0,0,0,0,0.997475862503052 +4129,0.0017025093548,0.002908675465733,-0.001936663058586,0,0,0,0,0.997574031352997 +4131,0.000863668159582,0.000863067747559,-0.001731716794893,0,0,0,0,0.997951209545136 +4133,0.001497530960478,-0.002468187827617,-0.001152785262093,0,0,0,0,0.998513758182525 +4135,0.002258094027638,-0.002992702880874,-0.000137532086228,0,0,0,0,0.998986423015594 +4137,0.002175938803703,-0.000879090279341,0.001722420798615,0,0,0,0,0.9994176030159 +4139,0.002464464632794,0.001383910188451,0.001400326378644,0,0,0,0,0.999697387218475 +4141,0.001067534321919,0.001848968677223,0.001169949187897,0,0,0,0,0.999904811382294 +4143,-0.001078501227312,0.000645849388093,0.000427193706855,0,0,0,0,0.999994158744812 +4145,-0.000790249672718,0.00056412408594,-0.003311026608571,0,0,0,0,1.00007164478302 +4147,-0.001154438010417,0.000954940333031,-0.005087319761515,0,0,0,0,1.00042963027954 +4149,0.000293633114779,-0.000621428014711,-0.002907190937549,0,0,0,0,1.00108182430267 +4151,0.002493456238881,-0.000918900535908,0.001753632794134,0,0,0,0,1.0014431476593 +4153,0.001302786869928,-0.001910211285576,0.00246364902705,0,0,0,0,1.00126707553864 +4155,-0.001973223872483,-0.004349157214165,9.35970729187829E-06,0,0,0,0,1.00097835063934 +4157,-0.002935727126896,-0.005580442491919,0.000711154250894,0,0,0,0,1.00122666358948 +4159,-0.000492610386573,-0.003374241525307,0.002402940532193,0,0,0,0,1.00145733356476 +4161,0.00067072204547,-0.000252011057455,0.002338789403439,0,0,0,0,1.00124156475067 +4163,0.000401019322453,0.001739135477692,0.001565633108839,0,0,0,0,1.00096070766449 +4165,0.001203454798087,0.002171859377995,0.000326518726069,0,0,0,0,1.00055730342865 +4167,0.001124330214225,-0.000215069827391,-0.000329306931235,0,0,0,0,1.00006318092346 +4169,0.001293954323046,-0.003867143532261,-0.000939909717999,0,0,0,0,1.0000433921814 +4171,0.000508495373651,-0.005788252223283,0.000259698048467,0,0,0,0,1.00036096572876 +4173,-0.000374755065423,-0.005207034759223,0.001178859034553,0,0,0,0,1.00059151649475 +4175,0.001355058513582,-0.002821148606017,0.000948026950937,0,0,0,0,1.00043952465057 +4177,0.001340767135844,-0.000477057212265,0.000715341127943,0,0,0,0,1.00009846687317 +4179,-0.000248441967415,0.000424052937888,-0.000155658955919,0,0,0,0,0.999592542648315 +4181,0.000119155658467,0.002593955723569,-0.000626051740255,0,0,0,0,0.998871028423309 +4183,-0.000164278666489,0.004667548462749,0.000911811483093,0,0,0,0,0.998341679573059 +4185,-0.001232559909113,0.004264430142939,0.004238835070282,0,0,0,0,0.998021006584168 +4187,-0.002327397931367,0.001843166886829,0.003007088787854,0,0,0,0,0.997782170772552 +4189,-0.002104087965563,0.000558161584195,0.000383661419619,0,0,0,0,0.998075485229492 +4191,-4.03420926886611E-05,0.001271853456274,-0.000232919264818,0,0,0,0,0.998718857765198 +4193,-0.000500991009176,0.001218246296048,-0.001406246679835,0,0,0,0,0.999363601207733 +4195,-0.003799397032708,-0.000591163174249,-0.000946735905018,0,0,0,0,0.999904692173004 +4197,-0.003708281554282,-0.002965126652271,0.00157537846826,0,0,0,0,0.999917209148407 +4199,-0.00032187893521,-0.001535044168122,0.000863450812176,0,0,0,0,0.999530017375946 +4201,0.001665586140007,0.000491579994559,-0.001112099736929,0,0,0,0,0.99919581413269 +4203,0.001999531872571,-2.12203885894269E-05,-0.002166682621464,0,0,0,0,0.999189794063568 +4205,0.002140466822311,0.000812394253444,-0.002114225411788,0,0,0,0,0.999253809452057 +4223,0.000874341814779,-0.002550838282332,0.001010242383927,0,0,0,0,0.99957412481308 +4225,-0.000384714105166,-0.003052968299016,0.001197122619487,0,0,0,0,0.999475538730621 +4227,-0.000501664821059,-0.002347028581426,0.000969244691078,0,0,0,0,0.999233901500702 +4229,0.000374588300474,0.001020259107463,0.000697722076438,0,0,0,0,0.999150514602661 +4231,0.00036884585279,0.004408779554069,0.000747007376049,0,0,0,0,0.999543011188507 +4233,0.000356140721124,0.003771605668589,-0.000318663252983,0,0,0,0,1.00020408630371 +4235,0.000810120836832,0.000955975032412,-0.001981679815799,0,0,0,0,1.00064218044281 +4237,0.00063436140772,-0.000158323862706,-0.001353270723484,0,0,0,0,1.00092697143555 +4239,-0.000979873700999,-0.000356640608516,-8.23422215034952E-06,0,0,0,0,1.00108873844147 +4241,-0.000120897566376,0.000749431143049,-0.000492632330861,0,0,0,0,1.00094223022461 +4243,0.001959424233064,0.002104406012222,0.000791461323388,0,0,0,0,1.0007461309433 +4245,0.000980836339295,0.000303261302179,0.003450431860983,0,0,0,0,1.00036096572876 +4247,-0.002244537463412,-0.003553385613486,0.002903562504798,0,0,0,0,0.999689877033233 +4249,-0.002635959535837,-0.004859095904976,0.00234890775755,0,0,0,0,0.999180853366852 +4251,-0.000510431476869,-0.003444262547418,0.004348981194198,0,0,0,0,0.99906575679779 +4253,6.91100867697969E-05,-0.002114447765052,0.003384850220755,0,0,0,0,0.999300837516785 +4255,0.000408186402638,-0.002485949313268,-0.000320770806866,0,0,0,0,0.999723196029663 +4257,0.002081215148792,-0.002537937369198,-0.002377765951678,0,0,0,0,1.00012266635895 +4259,0.001073531922884,-0.001420197193511,-0.002916933968663,0,0,0,0,1.00076007843018 +4261,-0.000927080225665,0.000790183315985,-0.000485944212414,0,0,0,0,1.00140929222107 +4263,-0.000563833338674,0.002453852677718,0.004172202199698,0,0,0,0,1.00170958042145 +4265,-0.000110894368845,0.001133557758294,0.005871299188584,0,0,0,0,1.00173878669739 +4267,-0.00210347934626,-0.002905141795054,0.002243958413601,0,0,0,0,1.00163888931274 +4269,-0.001629332196899,-0.006198869086802,-0.001955398824066,0,0,0,0,1.00135219097137 +4271,-4.35594738519285E-05,-0.003648065496236,-0.001697883941233,0,0,0,0,1.0008202791214 +4273,0.001426850329153,8.56141123222187E-05,-0.000579747196753,0,0,0,0,1.00029933452606 +4275,0.002702983096242,-0.001794211217202,-0.002334930002689,0,0,0,0,0.999912202358246 +4277,0.002007608069107,-0.003992790356278,-0.002572680125013,0,0,0,0,0.999481856822968 +4279,-0.000283722678432,-0.000355356780346,0.000287498318357,0,0,0,0,0.999246418476105 +4281,-0.002503827214241,0.002157961251214,0.003542690305039,0,0,0,0,0.999282121658325 +4283,-0.001810650574043,-0.000747273443267,0.004003893118352,0,0,0,0,0.999361634254456 +4285,0.001143220462836,-0.003794451244175,0.000424387835665,0,0,0,0,0.999303579330444 +4287,0.001082485308871,-0.002035412704572,-0.002616547513753,0,0,0,0,0.999265074729919 +4289,-0.001718017738312,0.001476796576753,-0.003588597057387,0,0,0,0,0.999534070491791 +4291,-0.0030564207118,0.002947248751298,-0.00378028023988,0,0,0,0,1.00000309944153 +4293,-0.002211774932221,0.00209874776192,-0.001634992193431,0,0,0,0,1.00037252902985 +4295,0.000565211696085,-0.000471103267046,-0.00023631392105,0,0,0,0,1.00103676319122 +4297,0.002054212614894,-0.00241592573002,-0.000731326930691,0,0,0,0,1.00199234485626 +4299,0.001585529884323,0.000268853415037,-0.002323727589101,0,0,0,0,1.00290679931641 +4301,0.001539718359709,0.006331816315651,-0.004695935640484,0,0,0,0,1.00341415405273 +4303,0.000905717432033,0.00894502364099,-0.003960929811001,0,0,0,0,1.00320065021515 +4305,0.001648982870393,0.004295023623854,-2.51591591222677E-05,0,0,0,0,1.0027756690979 +4307,0.004362494684756,-0.001761461026035,0.002696039620787,0,0,0,0,1.00265324115753 +4309,0.004688656888902,-0.004196138121188,0.001573074725457,0,0,0,0,1.00275909900665 +4311,0.001163573586382,-0.003825372317806,0.001415016013198,0,0,0,0,1.00265693664551 +4313,-0.000250435376074,-0.002653957344592,0.001182281179354,0,0,0,0,1.00194776058197 +4315,-2.49239965341985E-05,-0.001716299331747,-0.000303304521367,0,0,0,0,1.00107622146606 +4317,-0.001787443528883,-0.001714824931696,-0.001623083720915,0,0,0,0,1.00050783157349 +4319,-0.002637927420437,-0.000431691674748,-0.001447706483305,0,0,0,0,0.999922037124634 +4321,-0.00197460479103,0.001010047039017,0.000768810859881,0,0,0,0,0.999539792537689 +4323,-0.00190461287275,0.000692571746185,0.001261933590285,0,0,0,0,0.999525129795074 +4325,-0.002017100341618,4.73057625640649E-05,-0.002422611461952,0,0,0,0,0.999401450157166 +4327,-0.000674224051181,0.001250096946023,-0.003921370953321,0,0,0,0,0.99918806552887 +4329,0.001667768345214,0.003328328486532,-0.001612952677533,0,0,0,0,0.999164700508118 +4331,0.002916091587394,0.005330943968147,-0.001303349388763,0,0,0,0,0.999289929866791 +4333,0.00230129272677,0.00641220016405,-0.001040177419782,0,0,0,0,0.999268174171448 +4335,0.001654091756791,0.00507798884064,0.000395762675907,0,0,0,0,0.9989133477211 +4337,0.001238672528416,0.003838385688141,-0.001399524277076,0,0,0,0,0.998635470867157 +4339,-2.76878417935222E-05,0.003166461596265,-0.001909380895086,0,0,0,0,0.998643577098846 +4341,0.000303395703668,0.002158217830583,0.001576344948262,0,0,0,0,0.998718619346619 +4343,0.002993109868839,0.001595425768755,0.002526914700866,0,0,0,0,0.99873673915863 +4345,0.002446504542604,0.002475126180798,0.000805431278422,0,0,0,0,0.99877142906189 +4347,0.000601086823735,0.004476455971599,0.000267925206572,0,0,0,0,0.998505771160126 +4349,-0.000636539189145,0.004660280421376,0.001341076917015,0,0,0,0,0.998002648353577 +4351,-0.001730962190777,0.004263396374881,0.000903185398784,0,0,0,0,0.998066484928131 +4353,-0.001477068290114,0.001404926530086,-0.001063060946763,0,0,0,0,0.998604416847229 +4355,0.000230139048654,-0.001934174564667,-0.001248513930477,0,0,0,0,0.999219954013824 +4379,0.001940535497852,-0.000101975514553,-0.003956376109272,0,0,0,0,1.00193321704865 +4381,0.007596950512379,-0.003280432894826,-0.000991814071313,0,0,0,0,1.00190114974976 +4383,0.00731858285144,-0.004382643382996,0.000925749656744,0,0,0,0,1.00143349170685 +4385,0.00236823875457,-0.00375032867305,-0.000823378039058,0,0,0,0,1.00079548358917 +4387,-0.001287986524403,-0.000397847674321,-0.002250244608149,0,0,0,0,1.00024664402008 +4389,-0.002837382955477,0.002238885732368,-0.001989311072975,0,0,0,0,0.999770641326904 +4391,-0.003952762577683,0.002603680593893,0.001149166608229,0,0,0,0,0.999611437320709 +4393,-0.002474598353729,0.00106503313873,0.003039738861844,0,0,0,0,0.999595761299133 +4395,-7.02222314430401E-05,-0.000840557040647,-0.001119301537983,0,0,0,0,0.999505817890167 +4397,0.000641214486677,-0.001490744180046,-0.002342419931665,0,0,0,0,0.999484479427338 +4399,0.000237374028075,0.000531052355655,0.001109657576308,0,0,0,0,0.999656498432159 +4401,0.001904531265609,0.002459775423631,0.001200961763971,0,0,0,0,1.00022423267365 +4403,0.002492331434041,0.00121947331354,-0.000478716916405,0,0,0,0,1.00075280666351 +4405,0.000933683710173,-0.000269576295977,-0.001489604124799,0,0,0,0,1.00096023082733 +4407,0.000175884139026,5.6786975619616E-05,-0.00116102816537,0,0,0,0,1.00096607208252 +4409,0.001344710704871,0.000163691525813,0.000982937752269,0,0,0,0,1.00101828575134 +4411,0.002777019981295,-0.000538969237823,0.001756959361956,0,0,0,0,1.0009742975235 +4413,0.002469675382599,-0.00222651171498,-0.001033829757944,0,0,0,0,1.00071978569031 +4415,0.000691916444339,-0.002833533333614,-0.002410195767879,0,0,0,0,1.00040149688721 +4417,0.000606160319876,-0.001392055070028,-0.000913334661163,0,0,0,0,0.999919950962067 +4419,0.002472543856129,-0.000694047135767,-0.002075935248286,0,0,0,0,0.999397277832031 +4421,0.00206152163446,-6.75308401696384E-05,-0.003609580686316,0,0,0,0,0.999013841152191 +4423,-4.06443541578483E-05,0.002496082568541,-0.002561209024861,0,0,0,0,0.998924016952515 +4425,-0.000701769720763,0.003671620506793,-0.002404344500974,0,0,0,0,0.999142706394196 +4427,-0.000178037342266,0.003327033016831,-0.002278497442603,0,0,0,0,0.999572515487671 +4429,-0.000411376211559,0.001911210594699,-0.001696289749816,0,0,0,0,0.999752998352051 +4431,0.000102293874079,-0.000831104116514,-0.001851597684436,0,0,0,0,0.999470472335815 +4433,0.000326317298459,-0.002454290864989,-0.000148702674778,0,0,0,0,0.998872101306915 +4435,0.000115239687148,-0.004525593947619,0.001821916433983,0,0,0,0,0.998608291149139 +4437,-0.001101269153878,-0.006078704725951,0.000211427308386,0,0,0,0,0.999090194702148 +4439,-0.003283790312707,-0.003884110134095,-0.001781440805644,0,0,0,0,0.999975144863129 +4441,-0.002635243348777,-0.000589163973927,-0.002006906084716,0,0,0,0,1.00070381164551 +4443,-6.27725748927332E-05,-0.001020797528327,-0.001370198442601,0,0,0,0,1.00109231472015 +4445,0.002609234070405,0.000208955054404,0.000593619246501,0,0,0,0,1.00124537944794 +4447,0.00441559869796,0.00311180530116,0.000998298171908,0,0,0,0,1.00141453742981 +4449,0.003813391784206,0.004622945562005,-0.001187473884784,0,0,0,0,1.00158953666687 +4451,0.002023092238233,0.004752287641168,-0.004049024078995,0,0,0,0,1.00170171260834 +4453,0.000737797003239,0.002344582695514,-0.003845859551802,0,0,0,0,1.00198638439178 +4455,-1.74408432940254E-06,-0.001214554882608,-0.000811134581454,0,0,0,0,1.00241851806641 +4457,-0.000138886302011,-0.004840943962336,-0.001469457405619,0,0,0,0,1.00279235839844 +4459,-0.000222013986786,-0.003588967723772,-0.001992437290028,0,0,0,0,1.00267505645752 +4461,0.000420719297836,0.00042677813326,-0.001139949075878,0,0,0,0,1.00192356109619 +4463,0.002992306370288,-0.000111371169623,-0.004047999624163,0,0,0,0,1.00105774402618 +4465,0.004717694595456,-0.00127205485478,-0.005108901765198,0,0,0,0,1.00044572353363 +4467,0.003019287250936,-9.2308342573233E-05,-0.001794612267986,0,0,0,0,0.999973773956299 +4469,0.00180498638656,0.000130264670588,0.000539233558811,0,0,0,0,0.999729812145233 +4471,8.50970827741548E-05,0.000683858059347,0.001601452473551,0,0,0,0,0.999586045742035 +4473,-0.002127466257662,0.002500771079212,0.000923721760046,0,0,0,0,0.99933135509491 +4475,-0.00298167928122,0.001948944525793,0.000592680589762,0,0,0,0,0.999216735363007 +4477,-0.002855038503185,-0.002517763758078,0.000469348655315,0,0,0,0,0.999411642551422 +4479,-0.000125109319924,-0.006198287010193,-0.00099573796615,0,0,0,0,0.999713242053986 +4481,0.000991090782918,-0.00525766517967,-0.001858243835159,0,0,0,0,1.00041699409485 +4483,0.000859698222484,-0.001811134396121,-4.16985949414084E-06,0,0,0,0,1.00100302696228 +4485,0.002191169885919,-0.001101876026951,0.001470396877266,0,0,0,0,1.00119543075562 +4487,0.001782383187674,-0.001623243442737,0.000503516755998,0,0,0,0,1.00148594379425 +4489,-0.002784366719425,-0.000362026592484,-0.002688094973564,0,0,0,0,1.00161468982697 +4491,-0.004527267999947,0.000186516117537,-0.003356110304594,0,0,0,0,1.00135731697083 +4493,-0.002109244931489,6.12470103078522E-05,-0.000376824405976,0,0,0,0,1.00117218494415 +4495,-0.001833486021496,0.001924570067786,0.000434560730355,0,0,0,0,1.00090837478638 +4497,-0.002999337622896,0.002054977696389,3.24280408676714E-05,0,0,0,0,1.00051188468933 +4499,-0.001855042646639,-0.00115028815344,0.000803381146397,0,0,0,0,1.00019240379334 +4501,0.001463095075451,-0.003329604398459,-0.001934865606017,0,0,0,0,1.00017392635345 +4503,0.004326888360083,-0.002600890351459,-0.004958686884493,0,0,0,0,1.00039434432983 +4505,0.005793534219265,-0.002001934684813,-0.005324484780431,0,0,0,0,1.00074911117554 +4507,0.003850033972412,-0.001184843014926,-0.005466816481203,0,0,0,0,1.00096607208252 +4509,-7.86732489359565E-05,0.001200004015118,-0.000644411600661,0,0,0,0,1.00102210044861 +4511,-0.000855038058944,0.003014025976881,0.005797600373626,0,0,0,0,1.00121545791626 +4531,-0.000713615794666,0.003261290956289,-0.001517873490229,0,0,0,0,0.999532103538513 +4533,0.001330752740614,0.005784648470581,-0.000598463870119,0,0,0,0,0.999925017356873 +4535,0.003117187647149,0.004217909649014,5.85666748520453E-05,0,0,0,0,1.00006723403931 +4537,0.003340516239405,0.002733702538535,0.00163310568314,0,0,0,0,0.999629259109497 +4539,0.00307563925162,0.000270006567007,0.001233737333678,0,0,0,0,0.998953878879547 +4541,0.001785648870282,-0.000836019287817,0.000967783736996,0,0,0,0,0.998479723930359 +4543,0.001419902429916,0.00128189555835,-0.000619259255473,0,0,0,0,0.998269379138946 +4545,-0.000254938437138,-0.00026571698254,0.000106264022179,0,0,0,0,0.998300611972809 +4547,-0.003461561631411,0.000240658540861,0.003702014917508,0,0,0,0,0.998439192771912 +4549,-0.004317468963563,0.003479018807411,0.003501924686134,0,0,0,0,0.998766720294952 +4551,-0.003958673682064,0.003974333871156,0.00132880336605,0,0,0,0,0.99913901090622 +4553,-0.0022850218229,0.001941575552337,0.000209125908441,0,0,0,0,0.999330937862396 +4555,5.52291385247372E-05,0.001264227903448,0.001206679269671,0,0,0,0,0.999402761459351 +4557,0.001374937710352,0.002572047524154,0.001701228437014,0,0,0,0,0.999605298042297 +4559,0.000521325098816,0.002805236261338,6.75365154165775E-05,0,0,0,0,1.00009214878082 +4561,-0.000542337656952,0.000446495279903,0.000943217310123,0,0,0,0,1.00080609321594 +4563,-0.00023597915424,-0.002872214419767,0.004550430458039,0,0,0,0,1.00134670734406 +4565,-0.00022673192143,-0.002308930503204,0.005420541856438,0,0,0,0,1.00135362148285 +4567,0.000382571073715,0.000706904102117,0.004037467297167,0,0,0,0,1.00135183334351 +4569,0.001976308878511,0.001717228791676,0.002332339528948,0,0,0,0,1.0016496181488 +4571,0.001639228430577,0.000350520975189,0.000141504540807,0,0,0,0,1.00173330307007 +4573,-0.001911012805067,-0.000203299030545,0.001197867910378,0,0,0,0,1.00168776512146 +4575,-0.002241716720164,-0.000833333062474,0.003840368939564,0,0,0,0,1.00163173675537 +4577,-0.001099860295653,-0.002945984015241,0.003827441716567,0,0,0,0,1.00119519233704 +4579,-0.002527581527829,-0.00219565955922,0.001671827281825,0,0,0,0,1.00077819824219 +4581,-0.001761995954439,0.002318005077541,-0.000811251229607,0,0,0,0,1.0008419752121 +4583,5.7236753491452E-05,0.007413291372359,-0.000731176463887,0,0,0,0,1.00114238262177 +4585,-0.000772742263507,0.007734233047813,-0.000154467619723,0,0,0,0,1.00144672393799 +4587,-0.001051718252711,0.002370939822868,-0.00308278715238,0,0,0,0,1.00143849849701 +4589,0.001335638342425,-0.000284362817183,-0.005239036399871,0,0,0,0,1.00107753276825 +4591,0.003139877924696,0.001459082704969,-0.001760959392414,0,0,0,0,1.0006263256073 +4593,0.003354989225045,0.00216002156958,0.00122830318287,0,0,0,0,1.00033295154572 +4595,0.003804879030213,0.001538255834021,0.001806772430427,0,0,0,0,1.00011420249939 +4597,0.003456053091213,0.002630373928696,0.001995122758672,0,0,0,0,0.999850869178772 +4599,0.001349907717668,0.003553830552846,-0.000312747491989,0,0,0,0,0.999504029750824 +4601,-0.001252102083527,0.003439500462264,-0.001715970458463,0,0,0,0,0.99912565946579 +4603,-0.003499110694975,0.002685914281756,-0.000780527829193,0,0,0,0,0.999047517776489 +4605,-0.00315934792161,0.003093551145867,0.000131497319671,0,0,0,0,0.999177753925324 +4607,-0.001000095391646,0.002642489504069,0.000809466058854,0,0,0,0,0.999277293682098 +4609,0.000265471055172,0.004687247797847,2.53242214967031E-05,0,0,0,0,0.999376893043518 +4611,0.000204617070267,0.007285505533218,-0.001284657279029,0,0,0,0,0.999542534351349 +4613,-0.001528024557047,0.003634865395725,-0.000568157818634,0,0,0,0,0.999539494514465 +4615,-0.002722977427766,-6.09768794674892E-05,0.001392007456161,0,0,0,0,0.99942272901535 +4617,-0.001148043083958,-0.00184353615623,0.001103090122342,0,0,0,0,0.999351441860199 +4619,0.000494666746818,-0.005267966538668,-0.000112504632853,0,0,0,0,0.999153614044189 +4621,-0.000322803971358,-0.005344477016479,-0.001806491054595,0,0,0,0,0.998894274234772 +4623,-0.002717250259593,-0.003053750377148,-0.00190120015759,0,0,0,0,0.998930931091309 +4625,-0.003456424223259,-0.002117374446243,-0.001066946075298,0,0,0,0,0.999399900436401 +4627,-0.001850603031926,-0.002729151863605,-0.000334355572704,0,0,0,0,1.00023567676544 +4629,-0.001623525749892,-0.003068095305935,0.001441079075448,0,0,0,0,1.00097799301147 +4631,0.00024469482014,-0.00051901570987,0.001992839155719,0,0,0,0,1.00116944313049 +4633,0.003777786856517,0.00195716205053,-0.000491186918225,0,0,0,0,1.00123560428619 +4635,0.002340500708669,-2.80123695119983E-05,-0.002075464930385,0,0,0,0,1.00129163265228 +4637,-0.001376885455102,-0.003033835906535,-0.002435694681481,0,0,0,0,1.00148344039917 +4639,-0.003567609935999,-0.002671295311302,0.000597205013037,0,0,0,0,1.00192022323608 +4641,-0.002460877178237,-0.001307478756644,0.003993190824986,0,0,0,0,1.00231027603149 +4643,-0.000517756619956,-0.001010488369502,0.003054844914004,0,0,0,0,1.00260412693024 +4645,0.000747287471313,-0.001645762007684,0.000909906812012,0,0,0,0,1.00252723693848 +4647,0.001199334859848,-0.002177379792556,-0.00052331777988,0,0,0,0,1.00199794769287 +4649,0.001147353905253,0.000130269632791,-3.87469408451579E-05,0,0,0,0,1.00135564804077 +4651,0.002443096833304,0.002345015527681,0.001222319318913,0,0,0,0,1.00080251693726 +4653,0.001944104908034,0.001164282788523,0.001777978730388,0,0,0,0,1.00027203559875 +4655,0.000698373361956,-0.001861612545326,0.002320486819372,0,0,0,0,0.999661505222321 +4657,3.79071279894561E-05,-0.003172974800691,0.001695880084299,0,0,0,0,0.999287605285644 +4659,-0.000322132691508,-0.003310721367598,0.001854137633927,0,0,0,0,0.999205112457275 +4661,-0.00113164447248,-0.002536390675232,0.002607997274026,0,0,0,0,0.998754501342773 +4663,-0.001187278307043,-0.00334674725309,0.003028937615454,0,0,0,0,0.99828439950943 +4665,-0.001983635826036,-0.003742599627003,0.001335304579698,0,0,0,0,0.998279869556427 +4683,0.003327126381919,-0.001210755552165,0.000548630021513,0,0,0,0,0.998631417751312 +4685,0.003327126381919,-0.001210755552165,0.000548630021513,0,0,0,0,0.998631417751312 +4687,0.005140583496541,-0.003467789152637,-0.001123071764596,0,0,0,0,0.998811960220337 +4689,0.002812863560393,-0.002883875044063,-0.000674201350193,0,0,0,0,0.999066710472107 +4691,0.00335507420823,-0.001754055265337,0.001000088290311,0,0,0,0,0.999497413635254 +4693,0.005390082951635,-0.00016062593204,-0.000690809625667,0,0,0,0,0.999707579612732 +4695,0.004141670186073,0.000852858764119,-0.003235426265746,0,0,0,0,0.999492883682251 +4697,9.65205108514056E-05,0.004707499872893,-0.001398730324581,0,0,0,0,0.999363899230957 +4699,-0.002092472277582,0.008785394020379,0.000791936588939,0,0,0,0,0.999460637569428 +4701,-0.001627203426324,0.008545489981771,0.000171068139025,0,0,0,0,0.999710261821747 +4703,0.000435449328506,0.003975056577474,-0.001050635357387,0,0,0,0,1.000279545784 +4705,0.000899721810129,-0.000653695082292,-0.001414278754964,0,0,0,0,1.00071799755096 +4707,0.000381920108339,-0.002909376751632,-0.001894082524814,0,0,0,0,1.00074625015259 +4709,0.001926524215378,-0.001619448768906,-0.001601748052053,0,0,0,0,1.00064873695374 +4711,0.00388148589991,0.000565907917917,-0.003461212618276,0,0,0,0,1.00088012218475 +4713,0.002473946893588,-0.000366613094229,-0.004264022689313,0,0,0,0,1.00133287906647 +4715,0.00043028165237,-0.00295360875316,-0.001294297166169,0,0,0,0,1.00180184841156 +4717,-0.000540301960427,-0.003658222267404,-0.000281805871055,0,0,0,0,1.00215685367584 +4719,-0.002546673407778,-0.003442488843575,0.001016012509353,0,0,0,0,1.00191974639893 +4721,-0.00318712531589,-0.006304370239377,4.68469079351053E-05,0,0,0,0,1.00183248519897 +4723,-0.001322791795246,-0.006251534447074,-0.001629543607123,0,0,0,0,1.00195503234863 +4725,-0.000960419711191,-0.004988417495042,0.000949761539232,0,0,0,0,1.00200259685516 +4727,-0.000960419711191,-0.004988417495042,0.000949761539232,0,0,0,0,1.00200259685516 +4729,-0.001443041372113,-0.004170706029981,0.002379838144407,0,0,0,0,1.00080919265747 +4731,5.98068181716371E-05,-0.003313532099128,0.004095281939954,0,0,0,0,1.00033295154572 +4733,0.001706683658995,-0.001727938652039,0.004319561645389,0,0,0,0,1.00032925605774 +4735,-0.000540176406503,0.000395458220737,0.001809254521504,0,0,0,0,1.00068688392639 +4737,-0.000540176406503,0.000395458220737,0.001809254521504,0,0,0,0,1.00068688392639 +4739,-0.00256592896767,0.004312431439757,-0.003901046235114,0,0,0,0,1.001420378685 +4741,-0.00097082008142,0.004407691769302,-0.003517981618643,0,0,0,0,1.00135040283203 +4743,0.001606732024811,0.002584808971733,0.000168118043803,0,0,0,0,1.00118887424469 +4745,0.003765047295019,-0.00030925165629,0.002211310202256,0,0,0,0,1.00095915794373 +4747,0.003765047295019,-0.00030925165629,0.002211310202256,0,0,0,0,1.00095915794373 +4749,0.002174307592213,-0.004464390221983,0.003502102568746,0,0,0,0,1.00117862224579 +4751,0.000522887334228,-0.001971946563572,0.001333422609605,0,0,0,0,1.00147008895874 +4753,-0.001378415152431,0.002147488994524,-0.003372439183295,0,0,0,0,1.00143015384674 +4755,0.000384094339097,0.003909601364285,-0.003382807364687,0,0,0,0,1.00172388553619 +4757,0.000384094339097,0.003909601364285,-0.003382807364687,0,0,0,0,1.00172388553619 +4759,0.002279469743371,0.002811079844832,0.000726987433154,0,0,0,0,1.0025429725647 +4761,0.001411428907886,0.002893342403695,0.000341945211403,0,0,0,0,1.00242066383362 +4763,0.00209385366179,0.000796585460193,-0.001528658205643,0,0,0,0,1.00182139873505 +4765,0.002793996594846,-0.00093213794753,-0.001326649915427,0,0,0,0,1.0011967420578 +4767,0.002114895032719,0.00046171824215,-0.001407575211488,0,0,0,0,1.00077879428864 +4769,-0.000455490779132,0.002972819143906,-0.003283604513854,0,0,0,0,1.00081372261047 +4771,-0.001732767792419,0.004024157766253,-0.00337576889433,0,0,0,0,1.00111162662506 +4773,2.9985581022629E-06,0.003761268919334,0.000698731455486,0,0,0,0,1.00113534927368 +4775,0.000286511931336,0.001968741184101,0.004352430347353,0,0,0,0,1.00095009803772 +4777,-2.0916857465636E-05,0.001350569888018,0.003694465616718,0,0,0,0,1.00102758407593 +4779,0.001974566606805,0.000131967972266,0.000911971670575,0,0,0,0,1.00122535228729 +4781,0.002383259823546,-0.00393535150215,-0.003323715180159,0,0,0,0,1.00151360034943 +4783,0.001104693859816,-0.006806014571339,-0.006696061231196,0,0,0,0,1.00190603733063 +4785,0.002239976543933,-0.007457799743861,-0.004642224870622,0,0,0,0,1.00220620632172 +4787,0.001821382436901,-0.005769855808467,0.000218998204218,0,0,0,0,1.00231778621674 +4789,0.000825658498798,-0.003136333543807,0.002515724860132,0,0,0,0,1.00216293334961 +4791,0.001345735625364,-0.00119830633048,0.002093740273267,0,0,0,0,1.00201690196991 +4793,0.000913153926376,-0.000789418176282,-1.73611515492667E-05,0,0,0,0,1.00170183181763 +4795,0.000565207621548,-0.002132306573913,-0.002403250429779,0,0,0,0,1.00124621391296 +4797,0.001341869239695,-0.001626742188819,-0.003872823668644,0,0,0,0,1.00080907344818 +4799,0.001938423374668,0.001308561768383,-0.005557982251048,0,0,0,0,1.00040936470032 +4801,-0.001784232095815,0.003764976514503,-0.002345184795558,0,0,0,0,1.0000684261322 +4803,-0.005868425127119,0.003561542369425,0.001517266267911,0,0,0,0,0.999971449375153 +4805,-0.005027189385146,-0.000282915192656,-0.000369454937754,0,0,0,0,1.00025796890259 +4807,0.000438923627371,-0.004748118575662,-0.00349035882391,0,0,0,0,1.00069808959961 +4809,0.002079481491819,-0.003968523815274,-0.004166947677732,0,0,0,0,1.00126457214355 +4811,-0.001178925856948,-0.000214769301238,-0.000316360354191,0,0,0,0,1.00171339511871 +4813,-0.003369144862518,0.000470501661766,0.004074329510331,0,0,0,0,1.00175380706787 +4815,-0.002069943351671,-0.0007320655277,0.003427508287132,0,0,0,0,1.0015207529068 +4817,0.001680838875473,-0.000209304489545,0.000531036756001,0,0,0,0,1.00118160247803 +4819,0.005319837480783,0.000186056466191,-0.001089271507226,0,0,0,0,1.000608086586 +4821,0.004656597971916,-0.002270366763696,0.00089345354354,0,0,0,0,0.999929130077362 +4823,0.001673867343925,-0.005550120957196,0.003626240184531,0,0,0,0,0.999419808387756 +4825,0.001444003777578,-0.003665146650746,0.004086712375283,0,0,0,0,0.999111533164978 +4827,0.001964281313121,-0.000703385274392,0.002692519221455,0,0,0,0,0.999020099639893 +4829,0.001680324901827,-0.00061385234585,0.002474108943716,0,0,0,0,0.999225676059723 +4831,0.002787456149235,0.00110615696758,0.002348578069359,0,0,0,0,0.999460697174072 +4833,0.00052368233446,0.003481097752228,0.000368899054592,0,0,0,0,0.999621570110321 +4835,-0.001183574320748,0.002134778304026,-0.000575551239308,0,0,0,0,0.999773740768433 +4837,-0.00027472228976,-0.000616178207565,-0.001025265664794,0,0,0,0,0.999995946884155 +4839,-0.000434663001215,-0.00124577304814,-0.000673911592457,0,0,0,0,1.00031590461731 +4841,-0.002436270471662,3.29525537381414E-05,0.00094885379076,0,0,0,0,1.00037443637848 +4843,-0.003476493991911,-0.000518530316185,0.001014245557599,0,0,0,0,1.00020849704742 +4845,-0.00233672070317,-0.002059617545456,-0.000991143751889,0,0,0,0,0.99980878829956 +4847,-0.00102935207542,-0.002458434784785,-0.001168840099126,0,0,0,0,0.999344944953918 +4849,0.000140522286529,-0.003045410150662,0.000191489045392,0,0,0,0,0.999328076839447 +4851,0.000558114959858,-0.00318037928082,0.001215983997099,0,0,0,0,0.99980753660202 +4853,0.001849248073995,-0.003133269026876,0.002658823039383,0,0,0,0,1.00032794475555 +4855,-0.000381274789106,-0.000658141507301,0.004173976834863,0,0,0,0,1.00030922889709 +4857,-0.003704584902152,0.000976181821898,0.003387158736587,0,0,0,0,0.99976921081543 +4859,-0.003252181224525,-0.003514620708302,-0.000391761714127,0,0,0,0,0.998906254768372 +4861,-0.001441880711354,-0.005929017439485,-0.001409928547218,0,0,0,0,0.99818217754364 +4863,-0.001660631154664,-0.001866137958132,-0.000256271043327,0,0,0,0,0.99808919429779 +4865,-0.001869888859801,-6.28327252343297E-05,-0.00196894723922,0,0,0,0,0.998324513435364 +4867,0.000303996290313,-0.001275750459172,-0.003768861293793,0,0,0,0,0.998756885528564 +4869,0.001255989191122,-5.22536038261023E-06,-0.004106144420803,0,0,0,0,0.999255359172821 +4871,0.000666913401801,-0.000934527197387,-0.001114209531806,0,0,0,0,0.999501705169678 +4873,0.002096801996231,-0.005244810134172,0.001523307641037,0,0,0,0,0.999570846557617 +4875,0.000784808362368,-0.006241357885301,0.001242802478373,0,0,0,0,0.999672949314117 +4877,-0.001502998755313,-0.002368814079091,-0.000230422476307,0,0,0,0,1.00007033348084 +4879,-0.001812805654481,0.001879796152934,-0.002451869193465,0,0,0,0,1.00054085254669 +4881,-0.00073736748891,0.005875147413462,-0.00207839300856,0,0,0,0,1.00082242488861 +4883,0.001819069031626,0.006869921926409,-0.000395513285184,0,0,0,0,1.00095224380493 +4885,0.003975988831371,0.003079505404457,-0.001292189466767,0,0,0,0,1.00094056129456 +4887,0.001888976548798,-0.001418616506271,-0.00292163901031,0,0,0,0,1.00086677074432 +4889,5.8829096815316E-05,-0.001902887248434,-0.003600917989388,0,0,0,0,1.00066864490509 +4891,5.95984129176941E-05,8.45200411276892E-05,-0.001125643379055,0,0,0,0,1.00018286705017 +4893,-0.000959703640547,0.001439048093744,0.002865217858925,0,0,0,0,0.999855995178223 +4895,-0.001557681825943,0.001322566065937,0.003263407852501,0,0,0,0,1.00008523464203 +4897,-0.001569674466737,-0.000802229333203,0.003163923043758,0,0,0,0,1.00059521198273 +4899,-0.000975546136033,-0.001355063868687,0.002489539794624,0,0,0,0,1.00107419490814 +4901,0.000805856660008,-0.001606861012988,0.001239975914359,0,0,0,0,1.00117516517639 +4903,0.001872566645034,-0.001947202603333,-0.001083061331883,0,0,0,0,1.00133788585663 +4905,0.002443018369377,-0.002912798663601,-0.002993133384734,0,0,0,0,1.00157833099365 +4907,0.003208026755601,-0.005107212346047,-0.003024655859917,0,0,0,0,1.00162434577942 +4909,0.003639033995569,-0.00455818278715,-0.001701169414446,0,0,0,0,1.00167620182037 +4911,0.000295768753858,-0.0010504553793,0.000810581725091,0,0,0,0,1.00183129310608 +4913,-0.001731699332595,0.002813624218106,0.001737612765282,0,0,0,0,1.00184488296509 +4915,8.20685672806576E-05,0.003283952130005,0.00163819687441,0,0,0,0,1.00126755237579 +4917,0.002120744436979,-0.00106054614298,0.003403529291973,0,0,0,0,1.00018429756165 +4919,0.002274871338159,-0.005253308918327,0.001419680193067,0,0,0,0,0.999301075935364 +4921,0.000871879514307,-0.005432007834315,-0.002872558310628,0,0,0,0,0.998922109603882 +4923,0.00029158857069,-0.004513047169894,-0.003337537869811,0,0,0,0,0.998612403869629 +4925,-0.000963916012552,-0.004490206949413,-0.001919628703035,0,0,0,0,0.998328149318695 +4927,-0.001439221901819,-0.005193152930588,0.000738475529943,0,0,0,0,0.998204410076141 +4929,-0.001734473626129,-0.003545173211023,0.002116772579029,0,0,0,0,0.998385310173035 +4931,-0.001506202621385,-0.001522582489997,-7.86883538239635E-05,0,0,0,0,0.998522460460663 +4933,-0.000612438365351,-0.000413189351093,-0.002373157767579,0,0,0,0,0.998729169368744 +4935,0.002605060581118,-0.000183068521437,-0.002792906714603,0,0,0,0,0.999148964881897 +4937,0.003872445551679,0.002203167881817,-0.00240725511685,0,0,0,0,0.999578714370728 +4939,0.001272519817576,0.003560989163816,-0.000399896816816,0,0,0,0,1.00006020069122 +4941,0.001398750348017,0.000230619640206,0.001198112033308,0,0,0,0,1.00035452842712 +4943,0.003553702030331,-0.000614184711594,0.000525208248291,0,0,0,0,1.00019657611847 +4945,0.001989057753235,0.001041900948621,0.001247633015737,0,-645,-988,8,0.999796569347382 +4947,0.002093666000292,-0.000162369149621,0.001668999320827,20093,-122,-65,19,0.999595403671265 +4949,0.002294240752235,-0.000114716494863,0.002096954034641,20093,-128,-154,14,1.00017094612122 +4951,0.0006308608572,0.002951556816697,0.003269370179623,20093,27,-424,39,1.00088620185852 +4953,0.000270985998213,0.006149434484541,0.007129484321922,20093,-60,-473,49,1.00029504299164 +4955,0.000219950161409,0.00469780061394,0.01012683659792,20093,-81,-133,120,1.00026369094849 +4957,0.002169166924432,0.001852249144576,0.007828395813704,20093,-253,16,56,1.00035524368286 +4959,0.00451295170933,-0.000699128664564,0.003097347915173,20093,-324,29,39,1.00091600418091 +4961,0.002893048571423,-0.001932216342539,0.000549809017684,20093,-11,-46,6,1.00199925899506 +4963,0.001487024826929,0.000826727366075,-0.001381699577905,20093,-9,-377,-13,1.00266408920288 +4965,0.00201238039881,0.004335014149547,-0.005937909241766,20093,-153,-478,-37,1.00292789936066 +4967,0.006025977432728,0.0042420392856,-0.007610965985805,20093,-474,-231,-87,1.00261616706848 +4969,0.008082391694188,0.004001287277788,-0.003819626988843,20093,-354,-208,-24,1.00130486488342 +4971,0.006005027331412,0.00278676324524,0.001315932371654,20093,-41,-130,17,0.999581813812256 +4973,0.002257050480694,-6.88824729877524E-05,0.005574313923717,20093,141,33,40,0.998783111572266 +4975,-0.002180353272706,-0.003389235585928,0.005280188284814,20093,257,119,64,0.998943090438843 +4991,0.007407209370285,0.019864868372679,-0.003411200363189,20093,-378,-610,-41,0.999336123466492 +4993,0.011262229643762,0.011289001442492,0.003940485883504,20093,-538,259,25,0.994144380092621 +4995,0.009903441183269,-0.00390449212864,0.012188088148832,20396,-172,957,143,0.989687323570251 +4997,-0.000637884426396,-0.017968785017729,0.015832109376788,20396,657,1072,109,0.988573968410492 +4999,-0.016201006248593,-0.025678826496005,0.008530493825674,20396,1275,776,102,0.992351591587067 +5001,-0.03057218156755,-0.026933694258332,-0.004662989638746,20396,1368,293,-29,0.999566435813904 +5003,-0.034800082445145,-0.021325711160898,-0.016664355993271,20396,779,-244,-195,1.00664329528809 +5005,-0.018993921577931,-0.003684406867251,-0.019817953929305,20396,-943,-1387,-136,1.00799858570099 +5007,0.013980019837618,0.025116072967649,-0.01049839425832,20396,-2685,-2655,-125,1.00221633911133 +5009,0.046582486480475,0.04347375035286,0.006220147013664,20396,-3096,-2129,40,0.996466159820556 +5011,0.048634842038155,0.024306148290634,0.017961375415325,20396,-1043,793,210,0.991487205028534 +5013,0.010371778160334,-0.017961384728551,0.008317269384861,20396,2475,3084,58,0.985888540744782 +5015,-0.040346428751946,-0.04547606036067,-0.017663443461061,20396,4196,2521,-208,0.992245316505432 +5017,-0.068220354616642,-0.038166869431734,-0.030647404491901,20396,2879,-157,-212,1.00537109375 +5019,-0.047424200922251,-0.008121827617288,-0.007257123943418,20396,-812,-2204,-88,1.00565445423126 +5021,0.02076674811542,0.026954662054777,0.033798351883888,20396,-5259,-3079,229,0.995081841945648 +5023,0.081531450152397,0.04665632545948,0.048003256320953,20396,-5785,-2359,565,0.992580533027649 +5025,0.071120291948319,0.033453956246376,0.014097305946052,20396,-391,262,101,0.996172130107879 +5027,0.000552768120542,0.001948226010427,-0.040823075920343,20396,4940,2008,-479,0.999436378479004 +5029,-0.06114873290062,-0.020048908889294,-0.064652673900127,20396,5181,1655,-446,1.0055536031723 +5031,-0.064351201057434,-0.020694434642792,-0.029916234314442,20396,1168,176,-356,1.00098168849945 +5033,-0.017927534878254,-0.010425838641822,0.027733752503991,20396,-3156,-785,183,0.985601663589478 +5035,0.037116687744856,0.003530564485118,0.048158727586269,20396,-4643,-1252,563,0.987007558345795 +5037,0.055364415049553,0.022833045572043,0.021242078393698,20396,-2207,-1912,146,1.00999414920807 +5039,0.031302962452173,0.03179294615984,-0.007955636829138,20396,1112,-1373,-93,1.02082371711731 +5041,0.00469481991604,0.024402163922787,-0.006802863441408,20396,1719,-40,-47,1.01046502590179 +5043,-0.005938806105405,0.015617159195244,0.001284067868255,20396,747,153,14,0.997471451759338 +5045,-0.00524750398472,0.012964483350515,-0.017626499757171,20933,-90,-224,-121,0.996799170970917 +5047,0.00059728580527,0.01602341234684,-0.042880110442638,20933,-551,-708,-508,1.00506329536438 +5049,0.017779475077987,0.007912727072835,-0.033280666917563,20933,-1604,230,-236,1.00839519500732 +5051,0.031547751277685,-0.011766733601689,0.004972320515662,20933,-1626,1364,51,0.998494684696198 +5053,0.015055145137012,-0.014864644035697,0.032435495406389,20933,831,201,216,0.987648248672485 +5055,-0.016763782128692,0.01040274836123,0.028511624783278,20933,2430,-2227,331,0.991465628147125 +5057,-0.024427734315395,0.03003641217947,0.010645251721144,20933,773,-2079,71,1.00063621997833 +5059,-0.006374655757099,0.00400863494724,-0.005263275932521,20933,-1323,1552,-64,1.00388240814209 +5061,-0.000373191345716,-0.041616667062044,-0.021911157295108,20933,-549,3619,-153,1.00309371948242 +5063,-0.008636560291052,-0.048537727445364,-0.02959100343287,20933,604,1039,-353,1.00246930122375 +5065,0.004382106475532,-0.008326426148415,-0.010526581667364,20933,-1118,-2988,-80,1.00403761863709 +5067,0.046373810619116,0.03034807741642,0.013492122292519,20933,-3885,-3498,152,1.00813126564026 +5069,0.053473889827728,0.040523391216993,0.010688380338252,20933,-1419,-1553,67,1.01133763790131 +5071,0.008214357309043,0.035996746271849,-0.001637645065784,20933,2978,-507,-25,1.0054966211319 +5073,-0.026456555351615,0.022483889013529,0.001494961092249,20933,2717,384,4,0.990504384040832 +5075,-0.017914697527886,-0.004208415746689,-0.005955953616649,20933,-466,1740,-76,0.987326741218567 +5077,0.003149469383061,-0.026603998616338,-0.034224160015583,20933,-1693,1728,-242,1.00387573242188 +5079,0.010922172106803,-0.021492000669241,-0.029466606676579,20933,-880,-269,-356,1.01519978046417 +5081,0.012901050038636,0.000395103968913,0.018396256491542,20933,-473,-1822,114,1.0005955696106 +5083,0.017494125291705,0.025561138987541,0.038216140121222,20933,-755,-2488,441,0.986919581890106 +5085,0.017744101583958,0.044215228408575,0.006216141395271,20933,-426,-2236,37,0.997525215148926 +5087,0.005625734571368,0.032168067991734,-0.010844767093659,20933,613,56,-134,1.00558030605316 +5089,-0.023359473794699,-0.012776052579284,0.00558408210054,20933,2252,3119,31,0.990371108055115 +5091,-0.036480914801359,-0.044203300029039,-0.001794118317775,20933,1365,2690,-28,0.98712557554245 +5093,-0.007785019930452,-0.045424807816744,-0.023475995287299,20933,-2089,473,-168,1.00048923492432 +5095,0.016487892717123,-0.039438493549824,-0.005837934557348,21880,-2152,-51,-76,1.00101470947266 +5097,-0.020486632362008,-0.033829513937235,0.019024048000574,21880,2789,-167,122,0.995902955532074 +5099,-0.062369454652071,-0.016782494261861,0.009044638834894,21880,3882,-1204,98,0.996306419372559 +5101,-0.05027985945344,-0.014842133969069,-0.005537755787373,21880,-269,-172,-45,0.989457905292511 +5103,-0.011957435868681,-0.022035414353013,-0.00584172597155,21880,-2674,630,-76,0.982844769954681 +5105,0.026088017970324,0.013720948249102,-0.009144842624664,21880,-3219,-2996,-70,0.997776091098785 +5107,0.070815347135067,0.052714198827744,-0.008290612138808,21880,-4489,-3892,-106,1.01629984378815 +5109,0.082487143576145,0.040841612964869,0.003750002477318,21880,-2173,1,16,1.01246798038483 +5111,0.031316932290793,0.035183489322662,0.005565121304244,21880,3024,-430,56,0.998723387718201 +5113,-0.005076099652797,0.052806783467531,-0.006110767368227,21880,2515,-2300,-50,0.99259603023529 +5115,0.009949443861842,0.031627509742975,-0.021746464073658,21880,-1391,733,-266,0.994160532951355 +5117,0.013229159638286,-0.002981445984915,-0.031901855021715,21880,-592,2228,-231,1.00275421142578 +5119,0.000723081990145,-0.003383073257282,-0.014282553456724,21880,705,-203,-181,1.00295460224152 +5121,0.01276289857924,-0.0083301467821,0.014952312223613,21880,-1216,181,88,0.993184864521027 +5123,0.020903436467052,-0.014019327238202,0.010901911184192,21880,-1095,317,114,0.992986261844635 +5139,-0.043716091662645,-0.044151112437248,0.0177111774683,21880,2440,-257,196,0.983820259571075 +5141,-0.04779513925314,-0.013665961101651,0.007320910226554,21880,837,-2243,39,1.00176703929901 +5143,-0.022781480103731,0.003081086557359,-0.010299211367965,22542,-1550,-1491,-133,1.02080118656158 +5145,0.006536438129842,0.011025002226234,0.001048416830599,22542,-2323,-983,-5,0.993090927600861 +5147,0.036133829504252,0.051614694297314,-0.002896976191551,22542,-2843,-3995,-47,0.993861794471741 +5149,0.077398285269737,0.0721740052104,-0.011036256328225,22542,-4214,-2786,-89,1.01211512088776 +5151,0.069430008530617,0.053310301154852,0.003958883229643,22542,-707,207,33,0.993418395519257 +5153,0.003323659067974,0.04498503357172,0.007401840295643,22542,4509,-352,38,0.980201423168182 +5155,-0.012568840757012,0.004732433706522,-0.00251910625957,22542,1168,2510,-42,0.97994738817215 +5157,0.007645939011127,-0.028370944783092,-0.004062684252858,22542,-1730,2472,-41,0.962563931941986 +5159,0.010517015121877,0.015489221550524,0.001910308841616,22542,-557,-3708,9,0.970777213573456 +5161,0.0336261279881,0.027719600126147,0.009067088365555,22542,-2318,-1589,49,0.998555958271027 +5163,0.037533156573773,0.011712348088622,0.011616175994277,22542,-1071,615,124,0.997237622737884 +5165,-0.010426012799144,0.027938285842538,0.011545164510608,22542,3388,-1890,68,0.988713562488556 +5167,-0.03479564934969,-0.003863508813083,-0.00559771200642,22542,2116,2000,-77,0.990045964717865 +5169,-0.028083441779018,-0.036096531897783,-0.036554154008627,22542,-260,2496,-263,0.972603678703308 +5171,-0.016325604170561,-0.009113492444158,-0.038055971264839,22542,-769,-2108,-463,0.978031754493713 +5173,0.011202584952116,-0.020190482959151,-0.023289181292057,22542,-2311,757,-178,1.02186119556427 +5175,0.011661181226373,-0.017543325200677,-0.004159832838923,22542,-398,-217,-67,1.0153568983078 +5177,-0.022070137783885,0.016316700726748,0.030593037605286,22542,2548,-2978,191,1.00527107715607 +5179,-0.017196727916598,-0.003595455549657,0.029301457107067,22542,-246,1179,328,1.02769255638123 +5181,0.008246936835349,-0.003724248148501,0.012780884280801,22542,-2117,-255,73,1.00680685043335 +5183,0.014424198307097,0.020947948098183,0.006948791444302,22542,-859,-2418,68,1.00254333019257 +5185,0.02612198330462,0.006514438893646,-0.017164861783385,22542,-1398,613,-131,1.04252576828003 +5187,0.024815546348691,0.016234084963799,-0.011359111405909,22542,-494,-1299,-147,1.03505706787109 +5189,-0.002349394140765,0.038274772465229,0.008980254642665,22542,1782,-2466,46,1.02684855461121 +5191,-0.002737735398114,0.015230951830745,0.006608555559069,23578,-117,1042,63,1.02873146533966 +5193,0.002906283130869,0.004322204273194,0.02033762075007,23578,-641,368,126,0.994782149791718 +5195,0.00287499348633,0.018781341612339,0.015346630476415,23578,-242,-1711,168,1.0036735534668 +5197,0.026200912892819,-0.006538048852235,-0.001699350425042,23578,-2245,1544,-22,1.02809083461761 +5199,0.005513146519661,-0.013020911253989,0.010121379978955,23578,1191,300,108,1.01520967483521 +5201,-0.04520671069622,-0.014868191443384,0.008207225240767,23578,4079,-16,46,1.02465438842773 +5203,-0.042139541357756,-0.055605512112379,0.006725582294166,23578,265,3459,70,1.02074861526489 +5205,-0.030615016818047,-0.01771029829979,0.010883760638535,23578,-570,-2802,66,0.995511054992676 +5207,-0.00657266844064,0.025738077238202,-0.002795400097966,23578,-1812,-3872,-41,1.0125207901001 +5209,0.034029964357615,0.005857553798705,-0.005420880392194,23578,-3582,985,-46,1.01563572883606 +5211,0.02202133089304,0.039140902459622,0.000554040190764,23578,308,-3367,-2,1.00809466838837 +5213,-0.012258260510862,0.011385595425963,-0.003625303506851,23578,2434,1454,-33,1.02892923355103 +5215,-0.018997233361006,-0.033049985766411,-0.007948610931635,23578,612,3366,-102,1.01409113407135 +5217,-0.02478008158505,0.00665545836091,-0.004388114903122,23578,582,-3296,-40,1.0012024641037 +5219,-0.001672972925007,-0.005687289871275,-0.006815908942372,23578,-1802,629,-90,1.01865065097809 +5221,0.028280781581998,0.008472316898406,-0.004919345956296,23578,-2736,-1491,-45,1.00035452842712 +5223,-0.021602168679237,0.003456613281742,0.001963949995115,23578,3735,-44,11,1.00379955768585 +5225,-0.056395336985588,-0.073853299021721,-0.011376883834601,23578,3123,6240,-89,0.995907306671143 +5227,-0.041115649044514,-0.057229474186897,-0.01135369297117,23578,-614,-613,-145,0.938395082950592 +5229,-0.044573340564966,-0.016343925148249,-0.011580939404667,23578,724,-3027,-92,0.947106063365936 +5231,0.007217199075967,0.002857729094103,-0.014321190305054,23578,-4014,-1770,-182,0.959356844425201 +5233,0.030740968883038,0.045059636235237,0.000332452356815,23578,-2296,-4009,-13,0.968688368797302 +5235,-0.003929445985705,0.016953399404883,-0.011441837996245,23578,2360,1386,-151,1.01753604412079 +5237,0.009058363735676,-0.021652495488525,-0.01481478754431,23578,-1233,2724,-119,1.01029586791992 +5239,-0.003908077720553,0.000904222892132,-0.01874689757824,23578,812,-1987,-239,1.01900696754456 +5241,0.021426934748888,0.01090311165899,-0.036912519484758,24025,-2297,-1226,-274,1.02125144004822 +5243,0.066317476332188,0.055428717285395,-0.036493208259344,24025,-4484,-4466,-453,1.0025372505188 +5245,0.038094263523817,0.072232998907566,-0.052807353436947,24025,1269,-2623,-389,1.02132499217987 +5247,0.044973805546761,0.022163251414895,-0.063184060156345,24025,-1440,2818,-776,0.994495987892151 +5249,0.017919464036822,0.042596992105246,-0.080055095255375,24025,1453,-2475,-588,0.992905557155609 +5251,0.008054804056883,0.023608811199665,-0.107044085860252,24025,336,555,-1307,1.00333499908447 +5253,0.050523649901152,0.004865135997534,-0.114863552153111,24025,-4001,856,-845,0.993290662765503 +5255,-0.002059335354716,0.027337225154042,-0.134641453623772,24025,3548,-2479,-1652,1.01474952697754 +5257,-0.016150940209627,-0.027646789327264,-0.140868455171585,24025,1002,3904,-1047,1.01200389862061 +5259,-0.005309808067977,-0.002693625632674,-0.143052116036415,24025,-940,-2166,-1775,1.02109313011169 +5261,-0.01554958242923,0.006303006783128,-0.143354296684265,24025,717,-1164,-1089,1.04076874256134 +5263,0.010031753219664,0.014078920707107,-0.130317196249962,24025,-2239,-1203,-1648,1.03188538551331 +5265,0.002181917894632,0.03964938595891,-0.128225773572922,24025,285,-2837,-1007,1.03796982765198 +5267,0.006429475732148,-0.000292255339446,-0.117877267301083,24025,-653,2446,-1523,1.01977741718292 +5269,0.014064949005842,0.039136406034231,-0.106702446937561,24025,-997,-3823,-879,0.992551684379577 +5271,0.0149802332744,0.015754424035549,-0.093305081129074,24025,-558,1004,-1252,0.984607875347137 +5273,0.0205397605896,0.007176221814007,-0.067355051636696,24025,-950,67,-625,0.969025194644928 +5275,-0.035890605300665,-0.024365428835154,-0.037880349904299,24025,4385,2245,-611,0.977441251277924 +5277,-0.087378814816475,-0.099050395190716,-0.007512714248151,24025,4701,6341,-220,0.97571986913681 +5279,-0.099992088973522,-0.094160728156567,0.019724741578102,24025,2326,790,65,0.969757795333862 +5281,-0.090181857347488,-0.109096027910709,0.034322883933783,24025,398,2251,70,0.991949915885925 +5283,-0.058082178235054,-0.062270350754261,0.044382024556398,24025,-1506,-2706,361,0.997477352619171 +5285,-0.050660718232393,-0.031402174383402,0.051447033882141,24025,33,-2115,195,1.01993775367737 +5287,-0.031622357666493,-0.018825404345989,0.044912569224835,24025,-975,-941,374,1.027303814888 +5289,0.005417420063168,0.017057657241821,0.037109881639481,24561,-2874,-3163,104,1.03132307529449 +5291,0.026011204347015,0.037860471755266,0.021249283105135,24561,-2025,-2451,101,1.05286645889282 +5293,0.070537954568863,0.078849621117115,0.005850842688233,24561,-4354,-4434,-106,1.02863466739655 +5295,0.096500106155872,0.109662458300591,-0.011943830177188,24561,-3589,-4364,-289,1.03309941291809 +5297,0.114257492125034,0.123758681118488,-0.035880740731955,24561,-3108,-3202,-396,1.01864898204803 +5299,0.069660671055317,0.073399774730206,-0.067942500114441,24561,1849,1988,-955,1.01244008541107 +5301,-0.026024866849184,0.000400991761126,-0.105814948678017,24561,6998,4771,-888,0.984724521636963 +5303,-0.035431191325188,-0.057438239455223,-0.134271934628487,24561,1016,4628,-1753,0.93661504983902 +5305,-0.024059429764748,-0.043212059885264,-0.174766525626183,24561,-684,-828,-1386,0.952565610408783 +5307,0.007243209518492,0.004325843881816,-0.196942523121834,24561,-2589,-3918,-2519,0.968521177768707 +5309,-0.012918400578201,0.006830529775471,-0.214166343212128,24561,1408,-712,-1690,1.02115762233734 +5311,-0.040769048035145,-0.030631709843874,-0.21564818918705,24561,2431,2725,-2775,1.03207802772522 +5313,-0.02062763646245,-0.041942592710257,-0.20376256108284,24561,-1353,983,-1656,1.0409107208252 +5315,-0.019615536555648,-0.004662844818085,-0.201406329870224,24561,32,-3055,-2643,1.05691480636597 +5317,0.040696244686842,0.036362830549479,-0.189953997731209,24561,-5105,-3894,-1595,1.03778469562531 +5319,0.059901352971792,0.095777183771134,-0.195470735430718,24561,-2576,-6292,-2608,1.04572904109955 +5321,0.079825878143311,0.078044213354588,-0.191121354699135,24561,-2805,-333,-1637,1.05146837234497 +5323,0.028647143393755,0.028525063768029,-0.17569637298584,24561,2943,2584,-2407,1.06343400478363 +5325,-0.048497278243303,-0.042436141520739,-0.157157018780708,24561,5971,5191,-1434,1.02277386188507 +5327,-0.025171926245093,-0.079503253102303,-0.150373458862305,24561,-1513,3467,-2136,0.996764123439789 +5329,-0.028323978185654,-0.043291125446558,-0.176277294754982,24561,392,-2439,-1591,1.00115644931793 +5331,-0.021061887964606,-0.002152734203264,-0.191576153039932,24561,-423,-3358,-2651,0.999946355819702 +5333,-0.053128842264414,-0.021324964240193,-0.194881081581116,24561,2826,1215,-1752,1.0259907245636 +5335,-0.032045539468527,-0.053151082247496,-0.16383820772171,24561,-1224,2704,-2355,1.02475392818451 +5337,-0.022838160395622,-0.026267111301422,-0.122327193617821,25276,-551,-1989,-1282,1.03079867362976 +5339,-0.002278944244608,-0.018608385697007,-0.090103670954704,25276,-1658,-676,-1509,1.00896000862122 +5341,0.030823746696115,0.015331100672484,-0.067917905747891,25276,-3034,-3085,-924,0.977960526943207 +5343,0.020867001265287,0.036869876086712,-0.066478379070759,25276,145,-2577,-1245,0.956953048706055 +5345,0.051961466670036,0.045566808432341,-0.065120950341225,25276,-3206,-1729,-916,0.93980485200882 +5347,0.041630700230599,0.057739190757275,-0.085390493273735,25276,-182,-2262,-1482,0.949900925159454 +5349,0.040861487388611,0.047055009752512,-0.086691424250603,25276,-786,-388,-1080,0.968138337135315 +5351,-0.015983015298843,-0.012448779307306,-0.077231228351593,25276,4078,3998,-1399,1.00382125377655 +5353,-0.062875308096409,-0.074274182319641,-0.050143230706453,25276,4011,5020,-842,0.995890557765961 +5367,0.075514018535614,0.070904493331909,-0.11415971070528,25276,-2796,-2544,-1869,1.04425370693207 +5369,0.040928646922112,0.050688154995442,-0.143603771924973,25276,1630,245,-1522,1.06397521495819 +5371,0.01053979806602,0.011382832191885,-0.158560633659363,25276,1738,2139,-2415,1.05196380615234 +5373,-0.000375559699023,0.014214687980712,-0.171693444252014,25276,520,-892,-1743,1.03407621383667 +5375,0.026234636083245,0.027627784758806,-0.174101024866104,25276,-2609,-1911,-2627,1.01680290699005 +5377,0.051328927278519,0.040456913411617,-0.168857797980309,25276,-2815,-2002,-1754,1.0261378288269 +5379,0.00957281049341,0.025000343099237,-0.173720702528954,25276,2544,191,-2653,1.02621078491211 +5381,-0.033754173666239,-0.058593433350325,-0.172668188810348,25276,3299,6312,-1810,1.0216463804245 +5383,-0.110968835651875,-0.122372545301914,-0.173509940505028,25276,7066,6070,-2680,1.02292823791504 +5385,-0.123229116201401,-0.151508033275604,-0.155361026525497,25276,2406,3799,-1722,1.00244879722595 +5387,-0.101541757583618,-0.10861261934042,-0.147088229656219,25276,-127,-1736,-2397,1.01569128036499 +5389,-0.029985455796123,-0.042434301227331,-0.123421721160412,25276,-4891,-4543,-1528,1.01863741874695 +5391,0.020589282736182,0.049004442989826,-0.103574253618717,25276,-4166,-7758,-1908,1.03287041187286 +5393,0.074432075023651,0.098016679286957,-0.091064415872097,25276,-5133,-5352,-1324,1.02383172512054 +5395,0.11618197709322,0.142358615994453,-0.081819884479046,25276,-5115,-5940,-1669,1.03859329223633 +5397,0.114434450864792,0.134205833077431,-0.082541018724442,25276,-1780,-1841,-1280,1.05606412887573 +5399,0.078714832663536,0.079034775495529,-0.075303718447685,25276,1006,2166,-1606,1.06241297721863 +5401,-0.005985605530441,-0.002353373216465,-0.064375080168247,25276,5853,5328,-1169,1.02439415454865 +5403,-0.030774066224694,-0.051464639604092,-0.056600995361805,25276,1996,3850,-1397,0.981092989444733 +5405,-0.04870655760169,-0.051859565079212,-0.067529357969761,25276,1699,261,-1201,0.954637110233307 +5407,-0.011378532275558,-0.021654658019543,-0.07206866145134,25276,-2758,-2299,-1591,0.93250185251236 +5409,-0.00705291563645,-0.001200979226269,-0.079530321061611,25276,-485,-1947,-1297,0.944670617580414 +5411,0.009719819761813,0.000842666428071,-0.070058777928352,25276,-1629,-648,-1581,0.966789722442627 +5413,-0.016354640945792,-0.016283018514514,-0.046939548105002,25276,1822,959,-1085,0.997980535030365 +5415,-0.035439714789391,-0.029019208624959,-0.018508676439524,25276,1678,900,-982,0.997257351875305 +5417,-0.040899690240622,-0.043014161288738,-0.000819826265797,25276,713,1132,-772,0.999217629432678 +5419,-0.029461830854416,-0.02616947889328,0.008045197464526,25276,-585,-1257,-671,0.982219755649567 +5421,-0.007728735450655,-0.001557193463668,0.015112621709704,25276,-1695,-2217,-662,0.975556373596191 +5423,0.012785037979484,0.021543860435486,0.014999154955149,25276,-1923,-2481,-589,0.957127392292023 +5425,0.049001984298229,0.054980009794235,0.024956367909908,25276,-3553,-3672,-593,0.957872748374939 +5427,0.063565865159035,0.078015275299549,0.033199705183506,25276,-2349,-3412,-372,0.970679998397827 +5429,0.055217269808054,0.055196832865477,0.041476029902697,25276,-481,317,-474,0.987018823623657 +5431,-0.008748908527195,-0.012382801622152,0.03091611713171,25276,4433,4524,-393,0.985069096088409 +5433,-0.050114385783672,-0.047708567231894,0.011073670350015,25276,3396,2694,-679,0.957257211208344 +5435,-0.050492320209742,-0.055640380829573,-0.010437853634358,25401,562,961,-879,0.948327124118805 +5437,-0.002603862900287,-0.016340088099241,-0.013424801640213,25401,-3659,-3079,-850,0.93976241350174 +5439,0.021328004077077,0.009420800022781,-0.010610218159855,25401,-2342,-2506,-884,0.956495106220245 +5441,0.032874654978514,0.017739549279213,-0.018229980021715,25401,-1578,-1356,-886,0.963526427745819 +5443,-0.005773271434009,-0.018517643213272,-0.036795694380999,25401,2580,2385,-1197,0.992730498313904 +5445,-0.046032968908548,-0.046501491218805,-0.061157692223787,25401,3265,2169,-1188,0.981496453285217 +5447,-0.06604765355587,-0.076419733464718,-0.093629769980908,25401,2245,2890,-1878,0.971878230571747 +5449,-0.052145890891552,-0.054116453975439,-0.126454189419746,25401,-496,-1292,-1654,0.957307755947113 +5451,-0.036300532519817,-0.031425449997187,-0.15158423781395,25401,-784,-1587,-2582,0.967649161815643 +5453,-0.026510180905461,-0.010085862129927,-0.166660502552986,25401,-554,-1844,-1957,0.962404727935791 +5455,-0.006408888380975,-0.003285976592451,-0.178103044629097,25401,-1571,-905,-2924,0.968904972076416 +5457,0.006008026190102,0.01856473274529,-0.180909618735313,25401,-1207,-2295,-2087,0.98175984621048 +5459,0.027189362794161,0.034191153943539,-0.173995241522789,25401,-2204,-2158,-2906,0.988013505935669 +5461,0.0377999804914,0.048108126968145,-0.16855987906456,25401,-1549,-2170,-2032,0.980835735797882 +5463,0.05226419493556,0.064187571406365,-0.171466842293739,25401,-2147,-2705,-2907,0.974868297576904 +5465,0.058575585484505,0.069151170551777,-0.181087359786034,25401,-1565,-1865,-2149,0.982644617557526 +5467,0.061547785997391,0.069506712257862,-0.193692833185196,25401,-1499,-1697,-3201,0.976367712020874 +5469,0.038746733218432,0.043481029570103,-0.209723606705666,25401,775,687,-2380,0.979590713977814 +5471,0.015731479972601,0.021069329231978,-0.23324054479599,25401,1084,699,-3704,0.978672444820404 +5473,-0.010905910283327,-0.017617205157876,-0.258908331394196,25401,1753,2458,-2759,0.980568766593933 +5475,-0.019013686105609,-0.026777397841215,-0.275754511356354,25401,576,528,-4248,0.967728078365326 +5477,-0.01731395535171,-0.02564362436533,-0.273905903100967,25401,-177,-269,-2910,0.972665846347809 +5479,0.004663318861276,0.005847391672432,-0.255424171686172,25401,-1957,-2905,-4056,0.976320624351501 +5481,0.020011644810438,0.025387570261955,-0.222135901451111,25401,-1694,-2324,-2599,0.990402579307556 +5483,0.021815424785018,0.030059527605772,-0.183171659708023,25401,-792,-1382,-3244,1.00211405754089 +5485,-0.009674353525043,-0.008071824908257,-0.141240730881691,25401,2075,2272,-2075,1.01268577575684 +5487,-0.039041101932526,-0.050408717244864,-0.101818904280663,25401,2437,3298,-2311,0.994108259677887 +5489,-0.056911509484053,-0.068439848721027,-0.07500035315752,25401,1796,1720,-1638,0.980554819107056 +5491,-0.044144932180643,-0.05999144166708,-0.055977392941713,25401,-475,-156,-1786,0.973048269748688 +5493,-0.025064595043659,-0.027153531089425,-0.046639800071716,25401,-1286,-2488,-1454,0.976915836334228 +5495,0.005668522790074,0.000410266657127,-0.036256972700358,25401,-2573,-2496,-1564,0.977045297622681 +5497,0.046401757746935,0.046151734888554,-0.03146979957819,25401,-3866,-4465,-1357,0.98876541852951 +5499,0.081327877938747,0.07351066172123,-0.022424722090364,25401,-4128,-3689,-1408,1.00581240653992 +5501,0.080154046416283,0.08822662383318,-0.020382868126035,25401,-1388,-2882,-1286,1.03003084659576 +5503,0.051327805966139,0.032990511506796,-0.022129470482469,25401,893,2855,-1409,1.02797722816467 +5505,-0.00730348052457,-0.020916139706969,-0.035021308809519,25401,3956,3582,-1392,1.02219820022583 +5507,-0.058897558599711,-0.086096078157425,-0.048124343156815,25401,4321,5511,-1721,0.997094988822937 +5509,-0.077516205608845,-0.098227337002754,-0.05799949541688,25401,2124,1736,-1559,0.980236053466797 +5511,-0.083532810211182,-0.086727023124695,-0.063707694411278,25401,1487,70,-1916,0.959529280662537 +5513,-0.067699767649174,-0.04341147467494,-0.060204684734345,25401,-447,-2982,-1586,0.964317798614502 +5515,-0.042512536048889,-0.035372838377953,-0.055471491068602,25401,-1388,-490,-1831,0.969015121459961 +5517,-0.005653982050717,-0.007705201394856,-0.053791671991348,25401,-2825,-2359,-1553,0.983010470867157 +5519,0.01257399097085,0.021243803203106,-0.056894537061453,25401,-1784,-2906,-1859,1.00174820423126 +5521,0.048551011830568,0.064097329974175,-0.054032035171986,25401,-3548,-4489,-1566,1.01992559432983 +5523,0.074668727815151,0.09529908746481,-0.055439785122871,25401,-3387,-4299,-1853,1.02935838699341 +5525,0.101391173899174,0.111693888902664,-0.057637024670839,25401,-3682,-3322,-1601,1.02770948410034 +5527,0.074233010411263,0.089943572878838,-0.074679203331471,25401,393,-465,-2092,1.02689123153687 +5529,0.05191907286644,0.025194553658366,-0.099201627075672,25401,501,3688,-1901,1.00912177562714 +5531,-0.016029022634029,-0.050769753754139,-0.129429310560226,25401,4771,5684,-2754,0.977837324142456 +5533,-0.054341327399016,-0.068209111690521,-0.142157763242722,25902,3176,1659,-2220,0.936895072460175 +5535,-0.070145189762116,-0.049480244517326,-0.14942292869091,25902,1933,-1098,-3015,0.938388466835022 +5537,-0.029971996322274,-0.019137293100357,-0.148133009672165,25902,-2766,-2447,-2288,0.946235954761505 +5539,-0.006356159225106,0.000639595964458,-0.150763064622879,25902,-1912,-1986,-3058,0.980598986148834 +5541,0.006342257838696,0.012956964783371,-0.159772217273712,25902,-1318,-1621,-2395,1.02092266082764 +5543,-0.023460844531655,-0.038058985024691,-0.157259121537209,25902,2191,3704,-3162,1.05507445335388 +5545,-0.042825620621443,-0.052572786808014,-0.149428308010101,25902,1690,1251,-2353,1.03847873210907 +5547,-0.039161290973425,-0.068555265665054,-0.146072253584862,25902,68,1711,-3057,1.02407205104828 +5549,-0.019419059157372,-0.028970824554563,-0.152817532420158,25902,-1430,-2936,-2402,1.00195348262787 +5551,-0.013879573903978,-0.021095212548971,-0.165192633867264,25902,-452,-747,-3311,0.985343992710114 +5553,-0.000335434044246,0.003188052680343,-0.184795334935188,25902,-1253,-2297,-2652,0.977522492408752 +5555,0.023240713402629,0.002996661933139,-0.203914776444435,25902,-2342,-560,-3800,0.992606520652771 +5557,0.037794332951307,0.044521830976009,-0.214517205953598,25902,-1881,-4132,-2893,1.01253688335419 +5559,0.046621423214674,0.056892905384302,-0.207083329558372,25902,-1682,-2345,-3874,1.03687191009521 +5561,0.056144919246435,0.081794023513794,-0.178405612707138,25902,-1805,-3505,-2681,1.04689657688141 +5563,0.04341047257185,0.059634856879711,-0.146175846457481,25902,-106,63,-3189,1.05184423923492 +5565,0.026546899229288,0.034176994115114,-0.11782056838274,25902,490,756,-2291,1.0273095369339 +5567,0.012788706459105,0.02863203547895,-0.112454459071159,25902,450,-634,-2815,1.00379586219788 +5569,0.034533213824034,0.01763435639441,-0.120749562978744,25902,-2395,-54,-2332,0.992721378803253 +5571,0.00922547839582,-0.0019879383035,-0.144295200705528,25902,1327,860,-3214,1.00618731975555 +5573,-0.028197811916471,-0.065549798309803,-0.160667896270752,25902,2738,4905,-2633,1.00909507274628 +5575,-0.110078886151314,-0.138187453150749,-0.180795967578888,25902,7325,6894,-3672,1.02419018745422 +5577,-0.145145371556282,-0.188791826367378,-0.184627935290337,25902,4296,5808,-2830,1.01487147808075 +5579,-0.144027382135391,-0.183358877897263,-0.183600604534149,25902,1974,2098,-3738,1.01359379291534 +5591,0.103724725544453,0.114593781530857,-0.160812944173813,26117,-4028,-4964,-3558,1.02034318447113 +5593,0.116193883121014,0.145784333348274,-0.178053334355354,26117,-2842,-4830,-2903,1.01448166370392 +5595,0.134315341711044,0.133284598588943,-0.199097126722336,26117,-3799,-1808,-4041,1.02289462089539 +5597,0.102282226085663,0.11808805167675,-0.216980129480362,26117,480,-1175,-3207,1.0196967124939 +5599,0.027450488880277,0.025719683617354,-0.221156433224678,26117,4562,5631,-4338,1.01198256015778 +5601,-0.079269930720329,-0.061261508613825,-0.22154076397419,26117,8423,6527,-3278,0.972634553909302 +5603,-0.130499392747879,-0.108094677329063,-0.224649220705032,26117,5461,4566,-4418,0.938642501831055 +5605,-0.109956800937653,-0.106712982058525,-0.229721054434776,26117,-193,900,-3374,0.922783851623535 +5607,-0.056412737816572,-0.10187716782093,-0.228670299053192,26117,-3200,813,-4506,0.925762832164764 +5609,-0.041483953595162,-0.073125101625919,-0.225864127278328,26117,-747,-1495,-3389,0.936811804771423 +5611,-0.037900798022747,-0.042437184602022,-0.220607712864876,26117,102,-1970,-4452,0.971703588962555 +5613,-0.018098009750247,-0.02473065815866,-0.19539974629879,26117,-1414,-1377,-3219,1.00089502334595 +5615,-0.0023723335471,0.0097177894786,-0.161070331931114,26117,-1335,-3077,-3786,1.01842892169952 +5617,0.041908748447895,0.02364937029779,-0.130672812461853,26117,-4028,-1804,-2803,1.01433825492859 +5619,0.065443985164166,0.077348433434963,-0.129684090614319,26117,-3014,-5577,-3444,1.0058718919754 +5621,0.111538201570511,0.104509055614471,-0.13851061463356,26117,-5188,-3947,-2881,0.985296249389648 +5623,0.138500064611435,0.130255550146103,-0.161184206604958,26117,-4499,-4486,-3842,0.972221791744232 +5625,0.129366055130959,0.121574811637402,-0.179916739463806,26117,-1553,-1685,-3196,0.962754666805267 +5627,0.043588660657406,0.075513049960137,-0.191662520170212,26117,5072,1496,-4233,0.975625276565552 +5629,-0.033575188368559,-0.032731398940086,-0.193904906511307,26117,5635,7625,-3327,0.962410092353821 +5631,-0.103010460734367,-0.13013681769371,-0.203999429941177,26814,6301,8526,-4413,0.967970907688141 +5633,-0.15717089176178,-0.170566439628601,-0.215487599372864,26814,5808,4804,-3512,0.968380928039551 +5635,-0.188696905970573,-0.176227405667305,-0.221874609589577,26814,5053,2771,-4662,0.986001372337341 +5637,-0.183467164635658,-0.172686547040939,-0.225329235196114,26814,2020,1765,-3620,0.987175941467285 +5639,-0.156665906310081,-0.184608533978462,-0.222944676876068,26814,444,3431,-4715,1.01072955131531 +5641,-0.149549752473831,-0.156850904226303,-0.220219612121582,26814,1474,-113,-3625,1.03044903278351 +5643,-0.139321759343147,-0.152294740080833,-0.209478735923767,26814,1424,1799,-4597,1.04498434066772 +5645,-0.126501247286797,-0.118588209152222,-0.197570949792862,26814,803,-1021,-3508,1.03422367572784 +5647,-0.099291026592255,-0.1059560328722,-0.178775668144226,26814,-390,524,-4271,1.02825617790222 +5649,-0.074590981006622,-0.077879659831524,-0.159817054867744,26814,-743,-1155,-3281,1.01622891426086 +5651,-0.053602740168572,-0.070725925266743,-0.143909320235252,26814,-645,382,-3890,1.00304412841797 +5653,-0.02323505282402,-0.037304621189833,-0.134994432330132,26814,-1857,-2089,-3137,0.987145662307739 +5655,-0.005546899046749,-0.012711889110506,-0.135195061564446,26814,-1175,-1789,-3814,0.990786194801331 +5657,0.028280183672905,0.009934426285326,-0.136140659451485,26814,-2839,-1990,-3171,0.997639119625092 +5659,0.037852670997381,0.03708165884018,-0.147718444466591,26814,-1303,-2782,-3987,1.01477634906769 +5661,0.077085554599762,0.064227245748043,-0.162060111761093,26814,-3941,-3109,-3377,1.02328670024872 +5663,0.090059474110603,0.095709659159184,-0.186326563358307,26814,-2430,-4070,-4473,1.03609502315521 +5665,0.129496887326241,0.119124062359333,-0.198724895715714,26814,-4748,-3673,-3663,1.03023016452789 +5667,0.142872303724289,0.149903014302254,-0.210059776902199,26814,-3380,-4957,-4788,1.02154076099396 +5669,0.186432436108589,0.187757447361946,-0.212859347462654,26814,-5928,-5761,-3799,0.998978018760681 +5671,0.207530856132507,0.228978052735329,-0.213497057557106,26814,-5077,-7078,-4868,0.982769787311554 +5673,0.24936743080616,0.282305717468262,-0.205197393894196,26814,-6807,-8333,-3785,0.962770283222198 +5675,0.260662049055099,0.310040146112442,-0.193397969007492,26814,-5354,-7555,-4670,0.96900737285614 +5677,0.227546706795692,0.260946154594421,-0.181301236152649,26814,-1249,-834,-3657,0.986114382743835 +5679,0.107868000864983,0.113835521042347,-0.165952831506729,27046,6413,8052,-4380,0.984718799591064 +5681,-0.061340048909187,-0.004068217705935,-0.156198173761368,27046,12590,7841,-3515,0.963573098182678 +5683,-0.189439341425896,-0.127053618431091,-0.148319125175476,27046,11866,10246,-4200,0.941291749477386 +5685,-0.195850282907486,-0.219743683934212,-0.136708855628967,27046,2940,9188,-3409,0.907781541347504 +5687,-0.153482154011726,-0.291461646556854,-0.117090992629528,27046,-838,9346,-3858,0.898120760917664 +5689,-0.167640566825867,-0.249282747507095,-0.10419923812151,27046,3161,85,-3208,0.904779255390167 +5691,-0.195873185992241,-0.201629728078842,-0.094556763768196,27046,5003,-548,-3614,0.936880767345428 +5693,-0.201070412993431,-0.176689073443413,-0.095074743032456,27046,3091,372,-3164,0.995030164718628 +5695,-0.16918908059597,-0.170603036880493,-0.097156420350075,27046,344,1999,-3665,1.03812265396118 +5697,-0.114071413874626,-0.124822683632374,-0.101895846426487,27046,-2398,-1786,-3231,1.079993724823 +5699,-0.048471163958311,-0.05857315659523,-0.103430390357971,27046,-3994,-4088,-3758,1.09907793998718 +5701,0.025673002004624,-0.003248045220971,-0.101764895021915,27046,-5745,-4189,-3250,1.08770310878754 +5703,0.066756755113602,0.072457306087017,-0.103039547801018,27046,-4121,-6907,-3773,1.05054402351379 +5705,0.110523775219917,0.12828104197979,-0.106954008340836,27046,-4820,-6149,-3306,1.03133022785187 +5707,0.152867332100868,0.18028599023819,-0.112313508987427,27046,-5662,-7020,-3904,0.999202489852905 +5709,0.186999067664146,0.202103510499,-0.114680573344231,27046,-5300,-4858,-3382,0.978629052639008 +5711,0.201372116804123,0.231769353151321,-0.122464098036289,27046,-4524,-6343,-4047,0.972074925899506 +5713,0.223287001252174,0.235202863812447,-0.131412163376808,27046,-5040,-4125,-3520,1.00565886497498 +5715,0.192609027028084,0.221261531114578,-0.1381845921278,27046,-1228,-3144,-4258,1.04633104801178 +5717,0.091930590569973,0.114238604903221,-0.137772336602211,27046,5539,5421,-3591,1.05994319915771 +5719,-0.008460437878966,-0.005427562166005,-0.134586319327354,27046,6997,8061,-4241,1.0194365978241 +5721,-0.072440899908543,-0.047437068074942,-0.146505698561668,27046,5275,3085,-3677,0.978772163391113 +5723,-0.054388228803873,-0.036120850592852,-0.160539478063583,27046,-728,-808,-4574,0.955836117267608 +5725,-0.010438777506352,-0.015971336513758,-0.173839002847672,27046,-3318,-1802,-3895,0.943286836147308 +5727,0.024266161024571,-0.002383414888754,-0.180441811680794,27046,-3206,-1515,-4841,0.945685565471649 +5729,0.010716198943555,0.009313880465925,-0.188185855746269,27475,484,-1559,-4028,0.971278250217438 +5731,0.002168979728594,-0.002799065550789,-0.182751208543777,27475,228,329,-4902,1.00963294506073 +5733,-0.03352627903223,-0.019655043259263,-0.176329016685486,27475,2701,901,-3980,1.02442443370819 +5735,-0.027608403936029,-0.0420210249722,-0.165756598114967,27475,-319,1705,-4735,1.0117849111557 +5737,-0.017400411888957,-0.034146834164858,-0.158540427684784,27475,-808,-645,-3889,1.00791263580322 +5739,-0.003712633857504,-0.002272389363498,-0.151793122291565,27475,-1247,-2812,-4601,0.999283850193024 +5741,0.006401478778571,0.016665054485202,-0.133499473333359,27475,-1142,-2166,-3746,0.986908853054047 +5743,0.016581818461418,0.040301397442818,-0.114088170230389,27475,-1326,-2920,-4183,0.975937843322754 +5745,0.032805364578962,0.047008324414492,-0.091269634664059,27475,-1968,-1745,-3478,0.976683139801025 +5747,0.056960172951222,0.068031005561352,-0.083317369222641,27475,-2993,-3203,-3841,0.990842282772064 +5749,0.053344946354628,0.037408515810967,-0.094532445073128,27475,-867,1036,-3518,1.02493417263031 +5751,-0.020980419591069,-0.013586180284619,-0.123988062143326,27475,5317,3268,-4340,1.04738187789917 +5753,-0.081744208931923,-0.084500178694725,-0.140495240688324,27475,5174,5678,-3859,1.03089833259583 +5755,-0.094807095825672,-0.096533618867397,-0.15110120177269,27475,2150,1845,-4685,1.01883447170258 +5757,-0.037719812244177,-0.076346963644028,-0.148072049021721,27475,-3856,-920,-3940,1.00415658950806 +5759,-0.004571681842208,-0.023392546921969,-0.140585690736771,27475,-2606,-3969,-4590,0.995551109313965 +5761,0.009235614910722,0.022994795814157,-0.131203085184097,27475,-1428,-4212,-3851,0.971625328063965 +5763,0.023737043142319,0.042379230260849,-0.119783438742161,27475,-1729,-2634,-4371,0.981320440769196 +5765,0.030982652679086,0.065349645912647,-0.105754382908344,27475,-1281,-3162,-3700,0.994539737701416 +5767,0.025403797626495,0.064623937010765,-0.095749020576477,27475,-327,-1581,-4110,1.00900888442993 +5769,0.038985747843981,0.067537218332291,-0.1070541664958,27475,-1862,-1787,-3728,1.00452518463135 +5771,0.059614788740873,0.07230257242918,-0.125850275158882,27475,-2786,-2139,-4487,1.01544082164764 +5773,0.07090200483799,0.090242855250836,-0.151713967323303,27475,-2183,-3224,-4060,1.02030551433563 +5781,-0.014868631027639,0.001903237309307,-0.186686620116234,27475,50,-386,-4370,0.976869881153107 +5783,-0.01339234597981,-0.013217511586845,-0.173434063792229,27475,-270,613,-5144,0.979380130767822 +5785,-0.024227747693658,-0.032666269689798,-0.155585572123528,27475,743,1184,-4189,0.99729335308075 +5787,-0.037077434360981,-0.065587401390076,-0.133662536740303,27475,1155,2749,-4705,0.994469821453094 +5789,-0.041399259120226,-0.078721731901169,-0.112677581608295,27475,539,1418,-3920,1.00742876529694 +5791,-0.042667169123888,-0.047230869531632,-0.093732357025147,27475,432,-2138,-4258,1.00963461399078 +5793,-0.029031086713076,-0.017015581950545,-0.079455234110355,27475,-905,-2553,-3711,1.02041375637054 +5795,0.01383297983557,0.023243736475706,-0.078849673271179,27475,-3657,-3911,-4102,1.01500880718231 +5797,0.058548551052809,0.058324765414,-0.081572629511356,27475,-4398,-3998,-3743,1.02905416488647 +5799,0.074512578547001,0.095361456274986,-0.097048103809357,27475,-2754,-4882,-4335,1.04464972019196 +5801,0.054329462349415,0.058398637920618,-0.114803403615952,27475,270,1114,-3991,1.04072916507721 +5803,-0.007909464649856,-0.001345264608972,-0.127052381634712,27475,4162,3595,-4710,1.02167356014252 +5805,-0.071630135178566,-0.084595367312431,-0.125010505318642,27475,5194,6479,-4087,0.989866673946381 +5807,-0.08783208578825,-0.118956312537193,-0.114895150065422,27475,2191,3712,-4591,0.96042537689209 +5809,-0.087903164327145,-0.115265421569347,-0.111738540232182,27475,904,742,-4019,0.938335955142975 +5811,-0.058646872639656,-0.072865702211857,-0.108736269176006,27475,-1488,-2494,-4541,0.954689919948578 +5847,0.021842326968908,0.035998705774546,-0.15197391808033,27475,-3721,-7395,-5261,1.04473400115967 +5849,0.065059341490269,0.072707623243332,-0.141772851347923,27475,-4358,-4280,-4462,1.04315328598022 +5851,0.122176744043827,0.109956309199333,-0.112081296741962,27475,-6427,-5087,-4818,1.04274606704712 +5853,0.156707286834717,0.137164428830147,-0.07576783746481,27475,-5107,-4577,-4031,1.03071570396423 +5855,0.175009503960609,0.165435537695885,-0.051994025707245,27475,-4563,-5404,-4129,1.00939691066742 +5857,0.125187233090401,0.154832005500793,-0.059967022389174,27475,1308,-2199,-3935,0.993764340877533 +5859,0.035838957875967,0.083293065428734,-0.080434463918209,27475,5354,3027,-4479,0.984617710113525 +5861,-0.070210874080658,-0.042638603597879,-0.104456312954426,27475,8123,8857,-4259,0.955616474151611 +5863,-0.131091982126236,-0.139738813042641,-0.128562241792679,27475,6036,8495,-5065,0.933020532131195 +5865,-0.133572369813919,-0.165136858820915,-0.1332136541605,27475,1672,3477,-4482,0.922720372676849 +5867,-0.118470340967178,-0.149375915527344,-0.12967973947525,27475,439,630,-5105,0.944671750068665 +5869,-0.089205108582974,-0.088670052587986,-0.141355618834496,27475,-1186,-3719,-4564,0.962779462337494 +5871,-0.037872239947319,-0.069837227463722,-0.152729347348213,27475,-3415,-839,-5405,0.994008898735046 +5873,0.006701734382659,-0.009438088163733,-0.157162487506866,27475,-3642,-4805,-4703,1.03215599060059 +5875,0.036524388939142,0.038145054131746,-0.148483723402023,27475,-3078,-4647,-5385,1.0509922504425 +5877,0.072260275483131,0.076419912278652,-0.123841367661953,27654,-3966,-4471,-4503,1.05646979808807 +5879,0.097775243222714,0.092327654361725,-0.09741148352623,27654,-3800,-3286,-4809,1.04163265228271 +5881,0.125252336263657,0.128786861896515,-0.076733015477657,27654,-4180,-5136,-4200,1.03141415119171 +5883,0.11391369253397,0.133926704525948,-0.076520897448063,27654,-1479,-3242,-4583,1.01347970962524 +5885,0.072496399283409,0.079819038510323,-0.086031280457974,27654,1457,1991,-4281,0.999519646167755 +5887,-0.004141326062381,0.005196521990001,-0.095387920737267,27654,5071,4527,-4822,0.98296457529068 +5889,-0.092898897826672,-0.079514622688294,-0.114331483840942,27654,7219,6467,-4496,0.987115979194641 +5891,-0.138281986117363,-0.121250189840794,-0.136087313294411,27654,5036,4245,-5324,0.976146876811981 +5893,-0.139539241790771,-0.166036710143089,-0.144609525799751,27654,1679,4903,-4731,0.975887894630432 +5895,-0.123015210032463,-0.145625352859497,-0.144283756613731,27654,414,244,-5449,0.988152205944061 +5897,-0.094963379204273,-0.127093702554703,-0.131867006421089,27654,-1006,-125,-4672,1.0062780380249 +5899,-0.069179527461529,-0.096938319504261,-0.112344652414322,27654,-1063,-1193,-5099,1.03434610366821 +5901,-0.070190459489822,-0.089027769863606,-0.096427462995052,27654,751,131,-4452,1.04340577125549 +5903,-0.058106407523155,-0.062804572284222,-0.078125156462193,27654,-233,-1427,-4717,1.03783452510834 +5905,-0.043481592088938,-0.046755444258452,-0.064450450241566,27654,-724,-1031,-4250,1.02753937244415 +5907,-0.010644974187017,-0.034295730292797,-0.057894881814718,27654,-2485,-880,-4495,1.02403163909912 +5909,-0.000482559611555,-0.004535687156022,-0.063994862139225,27654,-1019,-2604,-4261,0.996418416500092 +5911,-0.017989361658692,0.023693302646279,-0.080744199454784,27654,1230,-2950,-4780,0.990122139453888 +5913,-0.007352055516094,0.045885387808085,-0.100925609469414,27654,-951,-2798,-4533,0.988498866558075 +5915,0.024089420214295,0.007148348260671,-0.116011656820774,27654,-2975,2111,-5216,0.996495068073273 +5917,0.039606392383576,0.013982003554702,-0.12322598695755,27654,-1991,-1245,-4710,1.01079046726227 +5919,0.034212578088045,0.003658577799797,-0.119058072566986,27654,-501,131,-5276,1.01587438583374 +5921,0.022366223856807,0.003421752946451,-0.108511961996555,27654,197,-589,-4633,1.01956343650818 +5923,0.003653822466731,-0.017993375658989,-0.093897439539433,29441,956,1280,-5003,1.01624941825867 +5925,-0.016368500888348,-0.014781184494495,-0.078102730214596,29441,1337,-566,-4444,1.01442909240723 +5927,-0.02350209467113,-0.024804333224893,-0.068607717752457,29441,580,580,-4723,1.01003837585449 +5929,-0.003345445962623,-0.0372459217906,-0.069564267992973,29441,-1715,887,-4402,1.00789225101471 +5931,-0.001391776255332,-0.013631578534842,-0.07701875269413,29441,-429,-2004,-4839,0.999142467975616 +5933,-0.006455029826611,0.005656581372023,-0.089154541492462,29441,136,-1995,-4554,1.01049852371216 +5935,0.008845102973282,0.03067372366786,-0.103921122848988,29441,-1554,-2825,-5175,1.01779675483704 +5937,0.024016711860895,0.003599427174777,-0.117274433374405,29441,-1753,1341,-4769,1.02528774738312 +5939,0.010148635134101,0.011086340993643,-0.125884339213371,29441,520,-1251,-5458,1.03401207923889 +5941,-0.008670304901898,-0.008640444837511,-0.122758537530899,29441,1147,988,-4833,1.03682243824005 +5943,-0.023454684764147,-0.020087765529752,-0.113354437053204,29441,1137,621,-5335,1.03523719310761 +5945,-0.033978659659624,-0.03554630279541,-0.104468189179897,29441,929,1080,-4731,1.01807498931885 +5947,-0.025725847110152,-0.037109963595867,-0.095306426286697,29441,-466,203,-5145,0.997999131679535 +5949,-0.01469393260777,-0.023019708693028,-0.086339920759201,29441,-877,-1197,-4627,0.973237693309784 +5951,0.011430195532739,0.01735494658351,-0.082904040813446,29441,-2358,-3688,-5018,0.972514986991882 +5953,0.057008918374777,0.066825494170189,-0.08272760361433,29441,-4387,-5028,-4621,0.97988361120224 +5955,0.110773093998432,0.098303116858006,-0.090641930699349,29441,-5979,-4399,-5129,0.99992161989212 +5957,0.145915687084198,0.150021836161613,-0.098823249340057,29441,-4967,-6430,-4751,1.01212167739868 +5959,0.172145992517471,0.144067689776421,-0.098831005394459,29441,-5048,-2511,-5247,1.02907359600067 +5961,0.16095107793808,0.162764355540276,-0.101412743330002,29441,-1940,-4315,-4790,1.03564834594727 +5963,0.134937450289726,0.176689013838768,-0.101617977023125,29441,-756,-4527,-5302,1.03263926506042 +5965,0.099771730601788,0.161588430404663,-0.098234623670578,29441,596,-1957,-4790,1.03277206420898 +5967,0.051187872886658,0.082335963845253,-0.085234925150871,29441,2180,3621,-5128,1.01628351211548 +5969,0.002902665641159,-0.018935069441795,-0.066206589341164,29441,2906,6769,-4589,0.99021589756012 +5971,-0.059155192226172,-0.115494653582573,-0.043052475899458,29441,4925,8074,-4646,0.953110337257385 +5973,-0.101786695420742,-0.139482721686363,-0.026083098724485,30156,4032,3016,-4325,0.924364507198334 +5975,-0.097096487879753,-0.116002961993217,-0.005685183219612,30156,791,-463,-4215,0.896543085575104 +5977,-0.088322654366493,-0.066903695464134,0.01287233736366,30156,202,-3207,-4063,0.902714252471924 +5979,-0.058671098202467,-0.008405039086938,0.021529622375965,30156,-1598,-4698,-3898,0.92387068271637 +5981,-0.015837363898754,0.015598168596625,0.008240154013038,30156,-3252,-2590,-4096,0.969521701335907 +5983,0.018428603187203,0.05189523845911,-0.034176710993052,30156,-3178,-4106,-4560,1.01999616622925 +5985,0.05702055990696,0.077192716300488,-0.072207935154438,30156,-4006,-3593,-4659,1.05921506881714 +5987,0.066857188940048,0.099901989102364,-0.092455714941025,30156,-2239,-3951,-5262,1.08489429950714 +5989,0.069237172603607,0.049310121685267,-0.091537915170193,30156,-1621,2195,-4812,1.0753915309906 +5991,0.055213529616594,0.014478945173323,-0.090801648795605,30156,-369,1528,-5262,1.04496717453003 +5993,0.02555020712316,0.007518660277128,-0.090430058538914,30156,1272,-340,-4825,1.00193238258362 +5995,0.007318849209696,0.02729245275259,-0.088936939835548,30156,697,-2594,-5260,0.977546572685242 +5997,0.018531242385507,0.026762707158923,-0.073968313634396,30156,-1560,-1091,-4731,0.946465790271759 +5999,-0.004595998674631,0.024765746667981,-0.065982051193714,30156,1232,-1008,-5008,0.948462724685669 +6001,-0.045875683426857,-0.026900473982096,-0.06872271001339,30156,3122,3329,-4711,0.977328956127167 +6003,-0.114153504371643,-0.117083549499512,-0.071068175137043,30156,6270,7629,-5083,1.00607323646545 +6005,-0.162916332483292,-0.168219372630119,-0.083891943097115,30156,5388,5370,-4832,1.00596117973328 +6007,-0.150088086724281,-0.187642648816109,-0.105052307248116,30156,1111,3774,-5502,1.00833296775818 +6009,-0.114691816270351,-0.141551315784454,-0.126041114330292,30156,-1264,-1892,-5145,1.02263557910919 +6011,-0.078479036688805,-0.108551479876041,-0.125458717346191,30156,-1668,-1204,-5768,1.0218733549118 +6013,-0.072316758334637,-0.058896586298943,-0.122078068554401,30156,258,-3286,-5143,1.01668930053711 +6015,-0.026920165866613,-0.036863524466753,-0.121299467980862,30156,-3145,-1555,-5745,1.00607764720917 +6017,0.01799507252872,-0.016066182404757,-0.123232923448086,30156,-3801,-1820,-5177,1.00373339653015 +6019,0.048796683549881,0.019288124516606,-0.11222842335701,30156,-3344,-3421,-5663,0.9997438788414 +6021,0.060094244778156,0.076287403702736,-0.098902322351933,30639,-2022,-5750,-5033,1.00033748149872 +6023,0.08921479433775,0.115933679044247,-0.090651109814644,30639,-3918,-5329,-5431,0.992088556289673 +6025,0.103466711938381,0.154439121484757,-0.095343388617039,30639,-2900,-5603,-5029,0.991613507270813 +6027,0.14280791580677,0.184525609016418,-0.111512549221516,30639,-5584,-5825,-5699,0.999468564987183 +6029,0.155433803796768,0.178311333060265,-0.130391329526901,30639,-3599,-2829,-5294,1.03009903430939 +6031,0.119512431323528,0.13264037668705,-0.137443989515305,30639,123,365,-6031,1.05430603027344 +6033,0.057335052639246,0.047248601913452,-0.124286405742168,30639,3107,4659,-5280,1.05503904819489 +6035,-0.031312648206949,-0.016572654247284,-0.10700236260891,30639,6326,4061,-5697,1.03715896606445 +6037,-0.060567140579224,-0.034960351884365,-0.084216460585594,30639,2450,1044,-5028,1.00376737117767 +6039,-0.013644666410983,-0.034860573709011,-0.063543029129505,30639,-3659,-208,-5204,0.959304988384247 +6041,0.050495076924563,0.013832854107022,-0.044065911322832,30639,-5830,-4448,-4767,0.939948797225952 +6043,0.032157734036446,0.072321034967899,-0.039328563958407,30639,266,-6142,-4934,0.958773612976074 +6045,-0.008413201197982,0.002285381080583,-0.058992944657803,30639,2497,4188,-4881,0.98912113904953 +6047,-0.075695067644119,-0.087551094591618,-0.092483885586262,30639,5526,7076,-5574,1.010213971138 +6049,-0.119349502027035,-0.150644063949585,-0.123618267476559,30639,4341,5923,-5346,1.03104388713837 +6051,-0.127248629927635,-0.130488514900208,-0.14202906191349,30639,2159,-59,-6182,1.05135715007782 +6053,-0.079896315932274,-0.095945820212364,-0.135181427001953,30639,-2687,-1798,-5455,1.05733215808868 +6055,-0.005202346947044,-0.048046633601189,-0.116688773036003,30639,-5706,-3350,-5911,1.04287278652191 +6057,0.033965598791838,0.013046762906015,-0.088775120675564,30639,-3733,-5245,-5161,1.01509714126587 +6059,0.054585572332144,0.0882468521595,-0.061780150979757,30639,-2815,-7527,-5286,0.99929666519165 +6069,-0.017424877732992,0.006074698641896,-0.056087862700224,30639,4790,4157,-4977,1.02288413047791 +6071,-0.070231527090073,-0.09842686355114,-0.048421390354633,30996,4397,8297,-5167,1.0346931219101 +6073,-0.097603030502796,-0.116308115422726,-0.040488220751286,30996,2845,2182,-4883,1.03249871730804 +6075,-0.11058734357357,-0.095345832407475,-0.024219566956163,30996,2238,-688,-4893,1.01991200447083 +6077,-0.099738992750645,-0.080985061824322,-0.013187378644943,30996,188,-589,-4704,1.00377702713013 +6079,-0.065851785242558,-0.08759880810976,-0.008833495900035,30996,-1806,1200,-4720,0.985259652137756 +6081,-0.044068641960621,-0.103281557559967,-0.014424712397158,30996,-1364,1922,-4719,0.962336599826813 +6083,-0.046285882592201,-0.103580161929131,-0.017314538359642,30996,497,1038,-4827,0.94864010810852 +6085,-0.097533985972405,-0.055876106023789,-0.012207938358188,30996,4657,-3253,-4712,0.953957617282867 +6087,-0.08313500136137,-0.048026546835899,-0.005032952409238,30996,-66,-416,-4690,0.966188073158264 +6089,-0.048263717442751,-0.076733760535717,-0.003974793478847,30996,-2179,2539,-4661,0.999202311038971 +6091,-0.020542018115521,-0.068245284259319,-9.62532649282366E-05,30996,-2014,-114,-4637,1.0463330745697 +6093,-0.003783237421885,-0.020933037623763,0.009665939956903,30996,-1510,-3678,-4572,1.08126223087311 +6095,-0.014780947938562,0.018504666164517,0.022793522104621,30996,666,-3731,-4371,1.09464752674103 +6097,0.010837289504707,0.050723377615213,0.029789561405778,30996,-2349,-3637,-4435,1.07867062091827 +6099,0.054810989648104,0.075346037745476,0.021137861534953,30996,-4417,-3617,-4392,1.05656254291534 +6101,0.11810103058815,0.113075532019138,0.009382835589349,30996,-6615,-4965,-4577,1.02885115146637 +6103,0.174097925424576,0.109269708395004,0.00365673028864,30996,-7259,-2186,-4601,0.982303857803345 +6105,0.202175587415695,0.127184063196182,0.008397831581533,30996,-5379,-3804,-4588,0.959215700626373 +6107,0.193755805492401,0.187213510274887,0.015437704510987,30996,-3037,-8095,-4467,0.937979221343994 +6109,0.129834890365601,0.234459757804871,0.011639324016869,30996,2161,-7535,-4568,0.96139270067215 +6111,0.06372506916523,0.194591403007507,-0.011836811900139,30996,3137,-1147,-4793,1.00593185424805 +6113,0.045571692287922,-0.001030266983435,-0.037288494408131,30996,61,13149,-4912,1.04478073120117 +6115,-0.024756740778685,-0.147683277726173,-0.071618676185608,30996,4865,12052,-5505,1.05396676063538 +6117,-0.151335433125496,-0.193388089537621,-0.097341313958168,30996,10664,5235,-5342,1.02071392536163 +6119,-0.210099920630455,-0.169624641537666,-0.100784815847874,31175,7093,280,-5869,0.997091770172119 +6121,-0.166170924901962,-0.157874941825867,-0.087050840258598,31175,-1241,687,-5293,0.978156447410584 +6123,-0.113111466169357,-0.150444954633713,-0.073971189558506,31175,-2411,1208,-5574,0.949986040592194 +6125,-0.081087738275528,-0.113631054759026,-0.065100699663162,31175,-1558,-1675,-5160,0.929729878902435 +6127,-0.093469701707363,-0.031983412802219,-0.066764928400517,31175,1986,-5981,-5506,0.940907895565033 +6129,-0.040956988930702,0.001236881362274,-0.065137431025505,31175,-3562,-3051,-5177,0.962663292884827 +6131,-0.003248428460211,0.016061846166849,-0.070026494562626,31175,-3054,-1969,-5562,1.00386726856232 +6133,0.029045287519693,0.05172910913825,-0.085274904966354,31175,-3121,-3958,-5332,1.04875493049622 +6135,0.069853715598583,0.092181019484997,-0.095078893005848,31175,-4466,-5065,-5876,1.07816469669342 +6137,0.081486567854881,0.100423142313957,-0.094628058373928,31175,-2427,-2734,-5418,1.08129382133484 +6139,0.097831137478352,0.104970678687096,-0.076589599251747,31175,-3196,-2753,-5678,1.046799659729 +6141,0.09752843528986,0.111071802675724,-0.056798774749041,31175,-1846,-2783,-5176,1.01112461090088 +6143,0.084999419748783,0.173578381538391,-0.037586033344269,31175,-954,-8079,-5235,0.991651296615601 +6145,0.103562794625759,0.192904502153397,-0.03216403350234,31175,-3323,-4984,-5018,0.961361706256866 +6147,0.178634777665138,0.165474325418472,-0.039031814783812,31175,-8827,-1580,-5264,0.946688294410706 +6149,0.223638147115707,0.149655759334564,-0.04907713085413,31175,-7024,-1924,-5146,0.932074844837189 +6151,0.172295704483986,0.090838171541691,-0.041973385959864,31175,215,1834,-5310,0.950410842895508 +6153,0.029335074126721,-0.014557094313204,-0.030389511957765,31175,9142,6809,-5030,0.958467066287994 +6155,-0.134527251124382,-0.155252292752266,-0.029505718499422,31175,13231,11713,-5172,0.955291867256165 +6157,-0.229838043451309,-0.212648466229439,-0.026511738076806,31175,9500,6286,-5013,0.944867789745331 +6159,-0.243850857019424,-0.241582155227661,-0.004102513194084,31175,4377,5195,-4880,0.949366867542267 +6161,-0.212765097618103,-0.251370370388031,0.022613031789661,31175,308,3544,-4681,0.977364599704742 +6163,-0.150794327259064,-0.268823325634003,0.047099266201258,31175,-2463,4923,-4280,1.00983798503876 +6165,-0.15488900244236,-0.215326189994812,0.05785396322608,31175,2069,-1382,-4436,1.04237532615662 +6167,-0.175398141145706,-0.099167846143246,0.079139314591885,31175,3922,-7316,-3898,1.06515502929688 +6169,-0.153923898935318,-0.047523189336062,0.106364049017429,31175,305,-3610,-4094,1.06325089931488 +6171,-0.082271791994572,-0.03199141100049,0.130507797002792,31175,-4143,-1163,-3281,1.04701268672943 +6173,-0.034173257648945,0.042812164872885,0.143671333789825,31175,-3282,-6550,-3821,1.02009415626526 +6175,0.0573551915586,0.066059038043022,0.150538101792336,31175,-7845,-3316,-3026,1.01592433452606 +6177,0.171116784214973,0.089089050889015,0.15789632499218,31175,-10962,-3535,-3702,0.990422606468201 +6179,0.231561988592148,0.160558968782425,0.16367481648922,31175,-8512,-8367,-2850,0.949529945850372 +6181,0.246413007378578,0.273802876472473,0.175514832139015,31175,-5067,-12723,-3558,0.945825099945068 +6183,0.293815404176712,0.284436464309692,0.181101024150848,31175,-8710,-6130,-2623,0.972116053104401 +6185,0.314218610525131,0.220621675252914,0.174863159656525,31175,-6576,589,-3537,1.01178467273712 +6187,0.169371694326401,0.177834942936897,0.176640450954437,31175,6970,-683,-2650,1.02918756008148 +6189,-0.03575199097395,0.157528281211853,0.185379341244698,31175,14519,-1706,-3440,1.03025352954865 +6191,-0.121886655688286,0.096219442784786,0.194767087697983,31175,7483,1910,-2409,1.00718474388123 +6193,-0.10028038918972,0.041075970977545,0.1963831782341,31175,-743,2413,-3336,0.976584672927856 +6195,-0.015668405219913,0.011052152141929,0.19885016977787,31175,-6444,1040,-2331,0.958118498325348 +6197,0.087931603193283,-0.033594273030758,0.218057185411453,31175,-9314,2729,-3158,0.958770275115967 +6199,0.142619639635086,-0.065830498933792,0.231771439313889,31175,-6904,2458,-1911,0.939396560192108 +6201,0.092977330088616,-0.049585532397032,0.240828529000282,31175,1521,-1373,-2967,0.937174797058106 +6203,-0.019112046808004,-0.041161261498928,0.243799969553947,31175,7635,-830,-1734,0.943056464195251 +6205,-0.112786166369915,-0.082801721990109,0.23029226064682,31175,7633,3269,-3003,0.957099616527557 +6207,-0.170646205544472,-0.14174447953701,0.204530134797096,31175,6247,5656,-2162,0.969324886798858 +6209,-0.171775698661804,-0.1571936160326,0.178251832723618,31175,1924,2523,-3331,0.992672801017761 +6211,-0.145219936966896,-0.11197154968977,0.148674428462982,31175,-150,-2244,-2795,1.01707792282105 +6213,-0.074619233608246,-0.058569215238094,0.116226814687252,31175,-4546,-3775,-3736,1.04280638694763 +6215,0.008474349044263,-0.001982755959034,0.079258762300015,31175,-6670,-4829,-3598,1.04895532131195 +6217,0.0527871735394,0.055937092751265,0.040507305413485,31568,-4500,-5746,-4248,1.05754125118256 +6219,0.077255681157112,0.123502910137177,-0.002443846082315,31568,-3606,-7687,-4559,1.05311965942383 +6221,0.097384311258793,0.18085640668869,-0.030174871906638,31568,-3448,-7561,-4740,1.04161906242371 +6223,0.150087773799896,0.188098579645157,-0.041879802942276,31568,-6863,-4476,-5033,1.02531409263611 +6225,0.233601346611977,0.091364525258541,-0.037258889526129,31568,-10016,4672,-4800,1.02996242046356 +6227,0.232891127467155,-0.007659328635782,-0.028765516355634,31568,-4478,6277,-4887,1.03012144565582 +6229,0.0986762419343,-0.05065929889679,-0.025081532076001,31568,7404,2862,-4726,1.02021515369415 +6231,-0.08021454513073,-0.078106313943863,-0.028820343315601,31568,13330,2319,-4897,0.991818487644196 +6233,-0.168612718582153,-0.082978524267674,-0.029298888519406,31568,7989,630,-4765,0.959185898303986 +6235,-0.16122467815876,-0.045346148312092,-0.032362520694733,31568,1355,-2842,-4949,0.925506174564362 +6237,-0.108946964144707,0.023762747645378,-0.02851347066462,31568,-2873,-6180,-4770,0.907388925552368 +6239,-0.063432112336159,0.096434704959393,-0.01200208067894,31568,-2915,-7670,-4720,0.889195799827576 +6241,-0.03214406222105,0.14528152346611,-0.000141280266689,31568,-2446,-6517,-4581,0.893349826335907 +6243,-0.001721773762256,0.136734411120415,0.005817977245897,31568,-2826,-2562,-4516,0.934023439884186 +6245,0.039425872266293,-0.021748432889581,0.016619246453047,31568,-4183,10668,-4470,0.97543728351593 +6247,0.027842987328768,-0.16183440387249,0.02593014575541,31568,-307,11700,-4277,1.00247001647949 +6249,-0.043058756738901,-0.186177894473076,0.021985230967403,31568,5010,3490,-4433,1.02911353111267 +6251,-0.086334116756916,-0.148964241147041,0.004272903781384,31568,3836,-1140,-4535,1.05335795879364 +6253,-0.078856855630875,-0.106370024383068,0.000977030140348,31568,-52,-2383,-4582,1.06207096576691 +6255,-0.067326530814171,-0.051495119929314,0.001477765734307,31568,-363,-3955,-4573,1.05878257751465 +6257,-0.035814631730318,0.006748909130692,-0.001698595937341,31568,-2363,-5109,-4605,1.0483478307724 +6259,0.024615881964564,0.053416982293129,-0.016715507954359,31568,-5357,-5081,-4794,1.0417959690094 +6261,0.091570354998112,0.0973881483078,-0.039835628122091,31568,-6744,-5417,-4875,1.0378258228302 +6263,0.123145014047623,0.139087736606598,-0.065616600215435,31568,-4925,-6167,-5383,1.03882110118866 +6265,0.114274650812149,0.141379818320274,-0.093383669853211,31568,-1697,-3132,-5259,1.04733848571777 +6267,0.070511735975742,0.116787411272526,-0.10016842186451,31926,1284,-1113,-5808,1.03859949111938 +6269,0.014413909055293,0.064141571521759,-0.0822778865695,31926,3083,1852,-5204,1.02819633483887 +6271,-0.002596015809104,0.031392730772495,-0.062299348413944,31926,535,826,-5380,1.01223838329315 +6273,0.054691050201655,-0.005553146358579,-0.047952637076378,31926,-5618,1710,-4984,0.998530447483063 +6275,0.136140942573547,-0.034689996391535,-0.044061023741961,31926,-8806,1645,-5179,0.998203456401825 +6277,0.121130913496017,-0.04965664818883,-0.047135211527348,31926,-1457,782,-4991,0.999555230140686 +6279,-0.019474346190691,-0.035671815276146,-0.049483437091112,31926,9592,-1415,-5255,0.993605434894562 +6281,-0.164856791496277,-0.037879429757595,-0.044611819088459,31926,11990,-286,-4987,0.973217666149139 +6297,-0.165524929761887,-0.183351531624794,-0.020406950265169,31926,2521,2550,-4854,1.08769655227661 +6299,-0.138114184141159,-0.189373970031738,-9.26957800402306E-05,31926,-200,2815,-4716,1.08563721179962 +6301,-0.136657699942589,-0.189820736646652,0.016100969165564,31926,1390,2101,-4607,1.05133891105652 +6303,-0.18542705476284,-0.147533029317856,0.029699455946684,31926,6086,-1249,-4369,1.0241334438324 +6305,-0.227776050567627,-0.122804567217827,0.050751127302647,31926,5921,-594,-4369,0.990244209766388 +6307,-0.258340299129486,-0.106690168380737,0.059163946658373,31926,6062,22,-4019,0.963497698307037 +6309,-0.214012578129768,-0.137088060379028,0.062543831765652,31926,-366,3609,-4283,0.948994696140289 +6311,-0.136943876743317,-0.177455559372902,0.070221945643425,31926,-3540,5283,-3884,0.936643600463867 +6313,-0.04277016967535,-0.220566183328629,0.077737979590893,31926,-6333,5801,-4171,0.929537653923035 +6315,0.022846773266792,-0.239721611142158,0.089610263705254,33177,-5289,4876,-3648,0.936830759048462 +6317,0.007127339020371,-0.204325377941132,0.098084971308708,33177,811,57,-4021,0.94855135679245 +6319,-0.084847569465637,-0.07561057806015,0.095693521201611,33177,7767,-8310,-3564,0.976513803005218 +6321,-0.116022489964962,-0.01360265724361,0.096021078526974,33177,3723,-4547,-4024,1.0061526298523 +6323,-0.039669889956713,-0.026834877207875,0.096468009054661,33177,-4988,1080,-3543,1.03123569488525 +6325,0.038226172327995,-0.017116148024798,0.099247708916664,33177,-6282,-739,-3990,1.04222881793976 +6327,0.067577809095383,0.057694159448147,0.098935544490814,33177,-3369,-6607,-3501,1.05475354194641 +6329,0.091810278594494,0.122084818780422,0.093904808163643,33177,-3237,-6679,-4015,1.04473209381104 +6331,0.129986584186554,0.164065435528755,0.080720148980618,33177,-5058,-6028,-3704,1.02666664123535 +6333,0.171645671129227,0.211588278412819,0.072122260928154,33177,-5690,-6831,-4155,0.998085558414459 +6335,0.187964871525764,0.271055281162262,0.072359308600426,33177,-4505,-9110,-3794,0.984902083873749 +6337,0.230459854006767,0.299233824014664,0.083448059856892,33177,-6681,-6826,-4070,0.982723116874695 +6339,0.279098600149155,0.305270344018936,0.096819676458836,33177,-8393,-5970,-3498,0.98291802406311 +6341,0.326299786567688,0.309629023075104,0.101185999810696,33177,-8520,-5410,-3936,0.99338173866272 +6343,0.353641837835312,0.336168438196182,0.102813988924026,33177,-8217,-8087,-3417,1.01201736927032 +6345,0.36807769536972,0.362751811742783,0.107440434396267,33177,-6933,-7919,-3880,1.02407813072205 +6347,0.390778779983521,0.384481489658356,0.107380926609039,33177,-8656,-8683,-3353,1.04227721691132 +6349,0.357317179441452,0.350440561771393,0.093045681715012,33177,-3526,-3576,-3966,1.06730341911316 +6351,0.218310803174973,0.26130411028862,0.074656248092651,33177,5587,1115,-3727,1.08149325847626 +6353,0.013611942529678,0.118491910398006,0.070290386676788,33177,13573,7424,-4115,1.06671106815338 +6355,-0.185362711548805,0.000679062562995,0.063132435083389,33177,16427,7346,-3851,1.04233396053314 +6357,-0.286814421415329,-0.061676148325205,0.053685661405325,33177,10573,4246,-4223,1.01152873039246 +6359,-0.321431159973145,-0.051800418645144,0.053922161459923,33177,6978,-943,-3954,0.998088121414185 +6361,-0.31548860669136,-0.028390942141414,0.06288930028677,33177,3440,-2351,-4155,0.984441220760345 +6363,-0.29413691163063,-0.02266894839704,0.071066983044148,33499,2665,-1107,-3747,0.97521311044693 +6365,-0.216739982366562,-0.070545248687267,0.080285362899304,33499,-2959,3369,-4028,0.988714098930359 +6367,-0.079871945083141,-0.148812666535378,0.092846550047398,33499,-9017,6994,-3481,0.994308412075043 +6369,0.068337693810463,-0.229478850960731,0.106531150639057,33499,-12088,8066,-3836,0.969260275363922 +6371,0.156477406620979,-0.242265284061432,0.117455922067165,33499,-9394,3919,-3177,0.958130836486816 +6373,0.19974485039711,-0.253313899040222,0.13010835647583,33499,-6533,3535,-3659,0.948451638221741 +6375,0.212107375264168,-0.235047355294228,0.136581540107727,33499,-4951,1681,-2934,0.941675245761871 +6377,0.233640089631081,-0.222352087497711,0.138337448239326,33499,-5563,1498,-3583,0.92812442779541 +6379,0.238015860319138,-0.201445907354355,0.133072480559349,33499,-4901,1044,-2956,0.932471871376038 +6381,0.189667254686356,-0.147425025701523,0.115076273679733,33499,-38,-2444,-3725,0.946833789348602 +6383,0.050110545009375,-0.005621341522783,0.087898977100849,33499,8400,-10754,-3476,0.964404463768005 +6385,-0.096463292837143,0.168186321854591,0.065511547029018,33499,11079,-15552,-4055,0.964280426502228 +6387,-0.191673889756203,0.300441116094589,0.053704131394625,33499,9182,-15112,-3875,0.961353957653046 +6389,-0.179069846868515,0.303810328245163,0.055970203131437,33499,949,-5429,-4117,0.983759701251983 +6391,-0.062357235699892,0.223972916603088,0.052795998752117,33499,-8043,1194,-3880,1.01680123806 +6393,0.157693043351173,0.071277424693108,0.033036928623915,33499,-18716,8981,-4270,1.05344879627228 +6395,0.313703149557114,0.008026646450162,0.014405687339604,33499,-17020,3450,-4329,1.09933054447174 +6397,0.255450129508972,0.068961277604103,0.002383579034358,33499,-327,-6297,-4483,1.10950398445129 +6399,0.050886370241642,0.162587746977806,-0.008918471634388,33499,12987,-10330,-4610,1.11365938186646 +6401,-0.093056797981262,0.154838174581528,-0.011178217828274,33499,10785,-2686,-4582,1.10599088668823 +6403,-0.095040783286095,0.085828557610512,-0.01532535161823,33499,842,2516,-4691,1.06616592407227 +6405,-0.019376378506422,0.038163863122463,-0.016242045909166,33499,-5962,1805,-4624,1.02761197090149 +6407,0.026445170864463,0.041180316358805,-0.009167537093163,33499,-4548,-1942,-4624,0.998692333698273 +6409,0.054811310023069,0.046664878726006,-0.000531036348548,33499,-3656,-2143,-4522,0.977689802646637 +6411,0.050712421536446,0.079687438905239,0.000345433363691,33499,-1391,-4744,-4518,0.954743504524231 +6413,0.059374317526817,0.102981053292751,0.009468327276409,33499,-2339,-4264,-4458,0.934135019779205 +6415,0.065091758966446,0.147525951266289,0.020502971485257,33499,-2358,-6724,-4285,0.925749361515045 +6417,0.055415458977223,0.145148754119873,0.024949289858341,33499,-1004,-3099,-4353,0.938124358654022 +6419,0.006714676041156,0.090602077543736,0.020875226706266,33499,2459,1238,-4281,0.962979257106781 +6421,0.002940530423075,-0.044792212545872,0.019449133425951,33499,-683,9111,-4391,0.990284860134125 +6423,0.044302485883236,-0.176761642098427,0.017325976863504,33499,-4624,11147,-4319,0.990120887756348 +6425,0.095227502286434,-0.230631396174431,0.013918483629823,33499,-5953,6018,-4431,0.972835958003998 +6427,0.119212187826633,-0.215602353215218,0.018579330295324,33499,-4641,1339,-4304,0.974215447902679 +6429,0.092567078769207,-0.195388272404671,0.034020453691483,33499,-421,305,-4294,0.987214088439941 +6445,-0.137510523200035,-0.15631927549839,0.045270014554262,33499,6026,-3455,-4201,1.08410394191742 +6447,-0.191854372620583,-0.113366223871708,0.05098532140255,33499,6273,-2001,-3909,1.08500111103058 +6449,-0.220144882798195,-0.066443480551243,0.059588097035885,33499,4491,-3144,-4098,1.06672775745392 +6451,-0.200742691755295,-0.069863744080067,0.066430076956749,33499,1223,664,-3722,1.05013501644135 +6453,-0.158284142613411,-0.105127975344658,0.070050068199635,33499,-1372,3330,-4019,1.04498386383057 +6455,-0.124860882759094,-0.131114646792412,0.064403310418129,33499,-937,3327,-3739,1.0238401889801 +6457,-0.112420499324799,-0.133141964673996,0.061887748539448,33499,176,1413,-4069,1.00683617591858 +6459,-0.105223536491394,-0.140401795506477,0.068163797259331,33499,675,2201,-3688,0.987387657165527 +6461,-0.109882794320583,-0.149054273962975,0.074123486876488,33499,1413,2183,-3978,0.971031725406647 +6463,-0.105271138250828,-0.168754249811173,0.081795960664749,33499,912,3623,-3520,0.963611602783203 +6465,-0.094239883124828,-0.15739206969738,0.087645247578621,33499,114,948,-3875,0.955256938934326 +6467,-0.071267731487751,-0.166170209646225,0.097981460392475,33499,-917,2873,-3319,0.949058651924133 +6469,-0.063349366188049,-0.156654626131058,0.106396861374378,33499,-72,1148,-3734,0.951312482357025 +6471,-0.063431359827519,-0.132423862814903,0.113781198859215,33499,620,29,-3119,0.965074360370636 +6473,-0.06970752030611,-0.04161923378706,0.109818950295448,33499,1062,-6263,-3695,1.00034618377686 +6475,-0.036789663136005,0.001187437213957,0.098395146429539,33499,-2156,-3432,-3286,1.04143345355988 +6477,0.022429814562202,-0.00295790983364,0.078361451625824,33499,-4937,-13,-3899,1.06985771656036 +6479,0.09241496026516,0.007641622330993,0.053920689970255,33499,-6915,-1246,-3801,1.0976744890213 +6481,0.124102912843227,0.045388419181109,0.041652277112007,33499,-4467,-3711,-4147,1.08935046195984 +6483,0.097109287977219,0.112521544098854,0.036659110337496,33499,-86,-7023,-4000,1.06256687641144 +6485,0.022785747423768,0.181130543351173,0.037652812898159,33499,4534,-7921,-4173,1.03280735015869 +6487,-0.041867189109326,0.224248692393303,0.047252491116524,33499,4854,-7191,-3873,1.01562213897705 +6489,-0.045804783701897,0.251476258039474,0.048862230032683,33499,495,-6069,-4092,1.00898885726929 +6491,0.018732665106654,0.225328847765923,0.047544371336699,33499,-5371,-2343,-3866,1.00500595569611 +6493,0.130023390054703,0.175036907196045,0.046808525919914,33499,-10290,477,-4102,0.99201226234436 +6495,0.25752654671669,0.099675826728344,0.0527308806777,33499,-13827,3157,-3801,0.999896883964539 +6497,0.379679888486862,0.030060146003962,0.058573119342327,33499,-14771,3898,-4017,0.989836513996124 +6499,0.457555145025253,0.03162431716919,0.062149506062269,33499,-13690,-1279,-3685,0.987069725990295 +6501,0.447564721107483,0.089130938053131,0.063109315931797,33499,-6493,-6068,-3979,0.989606738090515 +6503,0.360611408948898,0.208431497216225,0.057473659515381,33499,-487,-12644,-3737,0.9832563996315 +6505,0.239210441708565,0.34701019525528,0.04884209856391,33499,4310,-15673,-4072,0.970743715763092 +6507,0.153525695204735,0.443868964910507,0.038647972047329,33499,2659,-15011,-3961,0.973496615886688 +6509,0.032037533819676,0.376279950141907,0.031419966369867,33499,7217,-1529,-4190,1.00120973587036 +6511,-0.180382713675499,0.168223083019257,0.031698297709227,33499,17178,11167,-4035,1.01456010341644 +6513,-0.404280543327332,-0.05398939549923,0.023419838398695,33499,20897,15642,-4244,1.0139582157135 +6515,-0.522714555263519,-0.209711655974388,0.0001448894036,33499,16171,13561,-4402,1.03451228141785 +6517,-0.450010448694229,-0.331756412982941,-0.012980491854251,33499,548,12549,-4498,1.05118477344513 +6519,-0.288205087184906,-0.417393982410431,-0.004355306737125,33499,-7538,12071,-4461,1.03026711940765 +6521,-0.155389726161957,-0.461542189121246,0.01330688316375,33499,-7852,9026,-4322,0.996237993240356 +6523,-0.091829918324947,-0.42796128988266,0.030516404658556,33499,-3615,3908,-4054,0.983035683631897 +6525,-0.06872283667326,-0.397306472063065,0.040475513786078,33499,-1197,2948,-4135,0.972942590713501 +6527,-0.048143908381462,-0.34379231929779,0.041343722492457,33499,-1216,1284,-3925,0.943495333194733 +6529,-0.031745359301567,-0.295705944299698,0.039682950824499,33499,-1227,403,-4137,0.940984964370728 +6531,-0.097759418189526,-0.181913241744041,0.034621238708496,33499,5845,-5544,-4002,0.964381158351898 +6533,-0.220450773835182,-0.014231672510505,0.024123620241881,33499,11492,-12117,-4243,0.985486268997192 +6535,-0.28802415728569,0.080446302890778,0.003667645156384,33499,9125,-8425,-4367,1.03552639484406 +6537,-0.198889344930649,0.047734245657921,-0.010856544598937,33499,-3859,1312,-4487,1.07115828990936 +6539,-0.013658445328474,-0.075581528246403,-0.022925384342671,33499,-13372,9718,-4687,1.06186723709106 +6541,0.108829259872437,-0.148051977157593,-0.02781380712986,33499,-10656,7004,-4612,1.05582475662231 +6543,0.090702533721924,-0.079637318849564,-0.026013931259513,33499,-540,-3915,-4731,1.03496551513672 +6545,-0.016674363985658,0.049649808555842,-0.023223152384162,33499,7565,-10248,-4589,1.02311229705811 +6547,-0.05994276329875,0.095783293247223,-0.008654082193971,33499,3710,-5155,-4533,1.02757513523102 +6549,-0.000443395896582,0.036544520407915,0.014987193048,33499,-4595,3402,-4332,1.03205907344818 +6551,0.106239318847656,-0.052311312407255,0.024920947849751,33499,-9735,6913,-4142,1.02089881896973 +6553,0.114263132214546,-0.028457779437304,0.020494611933827,33499,6806,-10323,-4234,1.0261754989624 +6555,0.011181551031768,0.091006435453892,0.017071103677154,33499,6806,-10323,-4234,1.0261754989624 +6557,-0.106546133756638,0.18975593149662,0.012530944310129,33624,1850,-2607,-4289,1.02034413814545 +6559,-0.010350901633501,0.134444043040276,0.005738935898989,33624,-7087,1623,-4399,1.02013576030731 +6561,0.093468226492405,0.094423145055771,0.001093636150472,33624,-9322,919,-4427,1.01241946220398 +6563,0.137295588850975,0.099876694381237,0.005943459458649,33624,-5497,-2273,-4402,1.01064217090607 +6565,0.137295588850975,0.099876694381237,0.005943459458649,33624,-5497,-2273,-4402,1.01064217090607 +6567,0.182731077075005,0.136073037981987,0.035331912338734,33624,-3929,-4650,-4200,0.999629259109497 +6569,0.200032934546471,0.171616092324257,0.04561685398221,33624,-5013,-5852,-3904,0.994200050830841 +6571,0.218189314007759,0.228744864463806,0.05501301959157,33624,-4994,-7945,-4061,0.97693657875061 +6573,0.236794799566269,0.258118212223053,0.067995607852936,33624,-5810,-6910,-3636,0.968010067939758 +6575,0.236794799566269,0.258118212223053,0.067995607852936,33624,-5810,-6910,-3636,0.968010067939758 +6577,0.238798782229424,0.273248761892319,0.0818862169981,33624,-4980,-5013,-3466,0.946091055870056 +6579,0.253018617630005,0.279768794775009,0.088145770132542,33624,-5440,-5293,-3817,0.943910121917725 +6599,-0.351816326379776,-0.382981061935425,0.119850128889084,33624,5241,1230,-3540,0.969058394432068 +6601,-0.364182978868484,-0.326515078544617,0.118486188352108,33624,6276,906,-2961,0.997936189174652 +6603,-0.301234751939774,-0.336542695760727,0.11192424595356,33624,-632,5267,-3578,1.04387950897217 +6605,-0.228067576885223,-0.313411235809326,0.102056756615639,34625,-1933,3219,-3142,1.09191250801086 +6607,-0.183556839823723,-0.243884816765785,0.091874353587627,34625,-895,-1614,-3703,1.11863493919373 +6609,-0.14088262617588,-0.164984568953514,0.082322597503662,34625,-1085,-3076,-3362,1.12784230709076 +6611,-0.123738594353199,-0.093833185732365,0.085293233394623,34625,271,-3806,-3738,1.11488652229309 +6613,-0.117674641311169,-0.022038573399186,0.09297201782465,34625,1210,-4850,-3225,1.08126580715179 +6615,-0.086531810462475,0.024906935170293,0.101796545088291,34625,-1213,-3764,-3613,1.04919457435608 +6617,-0.063974030315876,0.084466114640236,0.111250810325146,34625,-807,-5720,-2995,1.02014148235321 +6619,-0.03848460316658,0.15089750289917,0.120964929461479,34625,-1470,-7007,-3466,0.992248773574829 +6621,-0.009809697046876,0.21367971599102,0.123067907989025,34625,-2116,-8106,-2838,0.973585069179535 +6623,0.070647887885571,0.244593396782875,0.122223347425461,34625,-6973,-5904,-3441,0.975746989250183 +6625,0.174221619963646,0.264005810022354,0.123390585184097,34625,-10502,-5915,-2817,0.979562282562256 +6627,0.291984528303146,0.255581468343735,0.132380604743958,34625,-12904,-3362,-3354,0.988504886627197 +6629,0.391653090715408,0.243557795882225,0.145035341382027,34625,-13863,-3446,-2545,0.978505730628967 +6631,0.435963422060013,0.25574517250061,0.154399305582047,34625,-9888,-4951,-3182,0.968191266059876 +6633,0.428307294845581,0.297531604766846,0.15791167318821,34625,-6952,-8305,-2373,0.95967447757721 +6635,0.397899866104126,0.350970149040222,0.160038635134697,34625,-4186,-9410,-3120,0.953579664230347 +6637,0.369761824607849,0.391697764396667,0.162763625383377,34625,-4722,-9913,-2296,0.947578907012939 +6639,0.34202715754509,0.430698037147522,0.166784107685089,34625,-3747,-9701,-3050,0.959837436676025 +6641,0.268196761608124,0.308184504508972,0.166082799434662,34625,51,2978,-2234,1.01629662513733 +6643,0.121792927384377,0.013568563386798,0.165399432182312,34625,7789,20042,-3035,1.0457729101181 +6645,-0.053028535097838,-0.309961527585983,0.173922881484032,34625,12452,27415,-2107,1.02612376213074 +6647,-0.206654444336891,-0.500144481658935,0.171827122569084,34625,13042,20076,-2965,1.01973330974579 +6649,-0.264056324958801,-0.578246176242828,0.16860094666481,34625,7536,14397,-2141,1.00528371334076 +6651,-0.295780092477798,-0.545678675174713,0.169973075389862,34625,5710,5040,-2953,0.991656720638275 +6653,-0.306919246912003,-0.48414009809494,0.166486382484436,34625,5043,3109,-2145,0.984158754348755 +6655,-0.298516929149628,-0.404418021440506,0.159736514091492,34625,3014,-139,-2998,0.963590264320374 +6657,-0.268633008003235,-0.346766710281372,0.171616747975349,34625,1605,1346,-2063,0.962717413902283 +6659,-0.269282341003418,-0.270670413970947,0.185018494725227,34625,3364,-1637,-2799,0.969538688659668 +6661,-0.275937169790268,-0.18615360558033,0.186906903982163,34625,4460,-3064,-1857,0.963454484939575 +6663,-0.256377160549164,-0.095236621797085,0.18426501750946,34625,1856,-5128,-2776,0.957498490810394 +6665,-0.20259465277195,-0.03580429404974,0.185635194182396,34625,-939,-3654,-1844,0.951749861240387 +6667,-0.142838507890701,-0.010818409733474,0.187603428959847,34625,-2559,-1597,-2725,0.947680115699768 +6669,-0.090616174042225,0.023845639079809,0.183787629008293,34625,-2595,-2837,-1837,0.954776644706726 +6671,-0.017168594524264,0.033472750335932,0.17726457118988,34625,-5304,-1138,-2769,0.971286118030548 +6673,0.076000206172466,0.028578566387296,0.172243818640709,34625,-8232,-85,-1947,1.00849282741547 +6675,0.102459140121937,0.071022696793079,0.156521886587143,34625,-3691,-4037,-2886,1.03715634346008 +6677,0.10181001573801,0.146962121129036,0.124956592917442,34625,-1952,-7842,-2481,1.07232022285461 +6679,0.17569836974144,0.165899708867073,0.091903083026409,34625,-8187,-3778,-3312,1.12240636348724 +6681,0.234169691801071,0.190190881490707,0.058751098811627,34625,-8403,-4938,-3249,1.13615369796753 +6683,0.196580842137337,0.314856171607971,0.041623692959547,34625,-605,-13580,-3652,1.13062047958374 +6685,0.157651633024216,0.42655012011528,0.04519534483552,34625,-275,-15165,-3403,1.12186706066132 +6687,0.208814576268196,0.405420631170273,0.058771729469299,34625,-7211,-4630,-3530,1.1073522567749 +6689,0.31210196018219,0.353625982999802,0.064977265894413,34625,-13082,-2440,-3166,1.06795477867126 +6691,0.3901227414608,0.334078311920166,0.067779332399368,34625,-11881,-3882,-3460,1.03378748893738 +6693,0.418283522129059,0.360657542943955,0.071082733571529,34625,-9602,-8328,-3089,0.999859094619751 +6695,0.401752054691315,0.391388326883316,0.078197963535786,34625,-5470,-8471,-3380,0.977092385292053 +6697,0.320751488208771,0.352403223514557,0.08569797128439,34625,-366,-3641,-2910,0.985599279403686 +6699,0.103824481368065,0.180655911564827,0.096088297665119,34625,13011,8898,-3246,1.00531482696533 +6701,-0.166434660553932,-0.040297467261553,0.114689201116562,34625,21050,15687,-2548,0.976607322692871 +6703,-0.331349313259125,-0.14080984890461,0.118986688554287,34804,15601,8427,-3073,0.951080560684204 +6705,-0.349809199571609,-0.127543330192566,0.108440138399601,34804,6128,381,-2605,0.942195773124695 +6707,-0.302116215229034,-0.057783249765635,0.115047253668308,34804,113,-4899,-3085,0.937943816184998 +6709,-0.235590025782585,-0.0069509902969,0.132653161883354,34804,-1694,-4244,-2305,0.937540292739868 +6711,-0.17431452870369,0.010664077475667,0.135038331151009,34804,-2587,-2141,-2928,0.941877841949463 +6713,-0.110003814101219,0.050657313317061,0.125998750329018,34804,-3512,-4430,-2365,0.97593879699707 +6715,-0.041424110531807,0.096767477691174,0.119721546769142,34804,-4972,-5443,-3016,1.0094940662384 +6717,0.039554201066494,0.055932570248842,0.124496266245842,34804,-7124,1251,-2365,1.0155428647995 +6719,0.116636894643307,0.006093241740018,0.123823948204517,34804,-7872,2703,-2970,1.0002977848053 +6721,0.166941955685616,0.024500286206603,0.113319344818592,34804,-7079,-2512,-2479,0.998728394508362 +6723,0.198693111538887,0.08337201923132,0.110349968075752,34804,-5890,-6207,-3046,1.00012564659119 +6725,0.199314787983894,0.155625939369202,0.114173114299774,34804,-4126,-8536,-2455,0.996851563453674 +6727,0.187473312020302,0.188692480325699,0.113762326538563,34804,-2707,-5944,-3007,0.983445763587952 +6729,0.166912987828255,0.220488041639328,0.110854081809521,34804,-2162,-6778,-2480,0.988194108009338 +6731,0.143262341618538,0.246339529752731,0.111013352870941,34804,-1310,-6359,-3010,0.993189692497253 +6749,-0.136028721928597,-0.163520663976669,0.110901966691017,34804,-4379,4405,-2411,0.998434603214264 +6751,-0.06337384134531,-0.170618310570717,0.115186467766762,34804,-4883,2093,-2917,0.991730690002441 +6753,-0.013475641608238,-0.172140911221504,0.119467869400978,34804,-3946,2069,-2294,0.975554406642914 +6755,0.022668393328786,-0.154731571674347,0.12093710154295,34804,-3498,186,-2860,0.973131835460663 +6757,0.05526564270258,-0.160331293940544,0.112920485436916,34804,-3841,2237,-2354,0.968883872032166 +6759,0.079394102096558,-0.144360423088074,0.105185404419899,34804,-3480,210,-2953,0.959684729576111 +6761,0.11341317743063,-0.12677900493145,0.101828798651695,34804,-4943,93,-2470,0.953826248645782 +6763,0.163308262825012,-0.090147808194161,0.093145072460175,34804,-6588,-1993,-3021,0.950925707817077 +6765,0.234447121620178,-0.060769602656365,0.08104007691145,34804,-9634,-1769,-2702,0.943572342395782 +6767,0.277717262506485,-0.01840859465301,0.070147149264813,34804,-7866,-3406,-3169,0.941526830196381 +6769,0.309006989002228,0.004910750780255,0.070547103881836,34804,-8095,-2372,-2816,0.931188762187958 +6771,0.316388607025146,0.025390133261681,0.078708358108997,34804,-5993,-2467,-3101,0.930978715419769 +6773,0.299508392810822,0.034520585089922,0.082058943808079,34804,-4639,-1844,-2671,0.958245575428009 +6775,0.215054988861084,-0.030619317665696,0.077467754483223,34804,1900,4456,-3099,0.998082518577576 +6777,0.002722236327827,-0.142160564661026,0.072655484080315,34804,14123,9689,-2769,1.03234124183655 +6779,-0.30717995762825,-0.197166934609413,0.058884419500828,34804,25544,6187,-3217,1.05135500431061 +6781,-0.516199767589569,-0.226345971226692,0.024730129167438,34804,22420,5234,-3327,1.06155788898468 +6783,-0.442145794630051,-0.344982326030731,-0.00879727397114,34804,212,12973,-3681,1.09916985034943 +6785,-0.241553574800491,-0.439809828996658,-0.030833000317216,34804,-11204,13546,-3985,1.1337890625 +6787,-0.190804019570351,-0.362126499414444,-0.051552169024944,34804,-1611,-643,-3984,1.12208724021912 +6789,-0.244378045201302,-0.193151876330376,-0.069490201771259,34804,7165,-9206,-4454,1.11568164825439 +6791,-0.190002620220184,-0.205992802977562,-0.07071278244257,34804,-1770,3693,-4130,1.13666117191315 +6793,-0.039687003940344,-0.313305258750915,-0.068513035774231,34804,-10701,12632,-4458,1.11577761173248 +6795,0.075480207800865,-0.347087472677231,-0.076225966215134,34804,-9914,7359,-4183,1.06751585006714 +6797,0.05163661763072,-0.256146401166916,-0.076554410159588,34804,267,-2356,-4568,1.04601037502289 +6799,-0.044019963592291,-0.130984857678413,-0.064149841666222,34804,6876,-7008,-4116,1.01411843299866 +6801,-0.137520596385002,-0.044239565730095,-0.054096169769764,34804,8351,-5422,-4318,0.986558973789215 +6803,-0.175125226378441,0.011659380979836,-0.043588250875473,34804,4661,-4071,-3987,0.979828119277954 +6805,-0.166551813483238,0.07428503036499,-0.032347347587347,34804,1581,-5624,-4072,0.965406775474548 +6807,-0.153331637382507,0.154615491628647,-0.028944842517376,34804,784,-7905,-3895,0.958949267864227 +6809,-0.130219176411629,0.222035273909569,-0.026919765397906,34804,9,-8413,-4015,0.947192668914795 +6811,-0.10720632225275,0.306358486413956,-0.023253031075001,34804,-519,-10467,-3864,0.950159847736358 +6813,-0.080725371837616,0.384366810321808,-0.016893655061722,34804,-991,-11938,-3902,0.970192015171051 +6815,-0.060945123434067,0.474861323833466,-0.012652073055506,34804,-916,-13501,-3797,0.969641506671906 +6817,-0.02236264385283,0.527333796024323,-0.008133492432535,34804,-2779,-12637,-3803,0.980008184909821 +6819,0.046890169382095,0.54913741350174,-0.00643056165427,34804,-5999,-9886,-3759,1.02160334587097 +6821,0.217238053679466,0.439830511808395,-0.004767405800521,34804,-16158,152,-3769,1.06712126731873 +6823,0.428915143013001,0.28354287147522,-0.011862749233842,34804,-21786,6481,-3800,1.06174516677856 +6825,0.571426331996918,0.210188254714012,-0.017140759155154,34804,-20103,1153,-3923,1.04944431781769 +6827,0.621106505393982,0.194261476397514,-0.009937958791852,34804,-13207,-2387,-3793,1.0471522808075 +6829,0.618578016757965,0.191977098584175,-0.000397787836846,34804,-10748,-3727,-3733,1.03873205184937 +6831,0.59668904542923,0.196020111441612,0.003002044511959,34804,-8019,-3931,-3707,1.01859593391418 +6833,0.588013887405396,0.229321449995041,0.004214175976813,34804,-10087,-6975,-3685,1.00391459465027 +6835,0.59534215927124,0.248225465416908,0.01176459249109,34804,-10368,-5849,-3650,1.00229072570801 +6837,0.582232296466827,0.262196362018585,0.017264707013965,34804,-9952,-6238,-3537,1.00569868087769 +6839,0.546065628528595,0.220081090927124,0.020771555602551,34804,-6820,-1195,-3588,1.01339888572693 +6841,0.474240511655808,0.160037368535995,0.029317051172257,34804,-4235,621,-3392,1.00808119773865 +6843,0.386979103088379,0.060450006276369,0.039324130862951,34804,-1103,5138,-3459,1.00325894355774 +6845,0.285926580429077,-0.036566369235516,0.03835629299283,34804,725,6425,-3274,0.994388997554779 +6847,0.212956249713898,-0.112061567604542,0.034599907696247,34804,228,5902,-3488,0.99030202627182 +6849,0.162504151463509,-0.134979739785194,0.033149313181639,34804,-1020,2749,-3327,0.993510127067566 +6851,0.122595265507698,-0.124998271465302,0.037117160856724,34804,-929,23,-3468,0.99365895986557 +6853,0.085377745330334,-0.122068092226982,0.044314809143543,34804,-774,746,-3192,0.984470307826996 +6855,0.041655115783215,-0.095369204878807,0.051717352122069,34804,454,-1545,-3363,0.981936395168304 +6857,0.002167782047763,-0.071737945079804,0.055656548589468,34804,700,-1513,-3056,0.981658041477203 +6859,-0.025539824739099,-0.041269585490227,0.058138880878687,34804,258,-2561,-3313,0.983681857585907 +6861,-0.043770879507065,-0.011146383360028,0.066899709403515,34804,-89,-2950,-2920,0.984825491905212 +6863,-0.065015234053135,0.023230817168951,0.07446300983429,34804,368,-3765,-3192,0.984597861766815 +6865,-0.081242948770523,0.052864901721478,0.083627864718437,34804,414,-3967,-2717,0.993314385414124 +6867,-0.112809829413891,0.075908273458481,0.091149434447289,34804,1821,-3737,-3066,0.99067211151123 +6869,-0.149748682975769,0.095477111637592,0.099379897117615,34804,3050,-3980,-2522,0.994771182537079 +6871,-0.177957385778427,0.118222460150719,0.100474782288075,34804,2574,-4372,-2989,0.989792346954346 +6873,-0.202928423881531,0.13703690469265,0.100275501608849,34804,3111,-4650,-2500,0.987009346485138 +6875,-0.226207405328751,0.153607279062271,0.103220008313656,34804,2994,-4503,-2956,0.984148800373077 +6877,-0.262275248765945,0.166450947523117,0.107614785432816,34804,4970,-4776,-2400,0.987851560115814 +6879,-0.291894793510437,0.173611655831337,0.109884403645992,34804,4501,-4197,-2895,0.988925278186798 +6881,-0.306982487440109,0.201169282197952,0.110152937471867,34804,4326,-6503,-2355,0.991237699985504 +6883,-0.317544728517532,0.21097332239151,0.110409773886204,34804,3638,-5023,-2876,0.991139590740204 +6885,-0.344183355569839,0.232709601521492,0.110674515366554,34804,5906,-6695,-2333,0.987608134746552 +6887,-0.366390079259872,0.237388178706169,0.109973654150963,34804,5326,-5149,-2864,0.987328350543976 +6889,-0.379749834537506,0.25347974896431,0.108306251466274,34804,5696,-6739,-2345,0.992352366447449 +6891,-0.385448098182678,0.265859961509705,0.104027770459652,34804,4588,-6233,-2890,0.997560262680054 +6893,-0.387919574975967,0.259244948625565,0.094666801393032,34804,5230,-5325,-2489,0.992317318916321 +6895,-0.399707496166229,0.255730032920837,0.085874408483505,34804,5406,-5075,-3002,0.994606673717499 +6897,-0.405638307332993,0.243981912732124,0.078204624354839,34804,5946,-4821,-2669,0.989757895469666 +6899,-0.403639763593674,0.246956303715706,0.069528512656689,34804,4661,-5532,-3104,0.99009895324707 +6901,-0.384489476680756,0.250116735696793,0.065355353057385,34804,3972,-6107,-2810,0.990832507610321 +6903,-0.354795664548874,0.26380455493927,0.062826089560986,34804,2152,-6662,-3142,0.995108425617218 +6905,-0.313593298196793,0.279810905456543,0.059427015483379,34804,1393,-7640,-2871,0.990666270256042 +6907,-0.274759083986282,0.305397510528564,0.056581716984511,34804,491,-8248,-3178,0.987879455089569 +6909,-0.230178266763687,0.313997030258179,0.059812609106302,34804,-86,-7809,-2858,0.982402920722961 +6911,-0.197551384568214,0.343374848365784,0.065741956233978,34804,-68,-9218,-3107,0.97054249048233 +6913,-0.161867961287499,0.356539487838745,0.071123950183392,34804,-464,-8988,-2714,0.960988998413086 +6915,-0.126894608139992,0.370745807886124,0.077427543699741,34804,-1176,-8697,-3018,0.954477846622467 +6917,-0.087047606706619,0.353960603475571,0.08618725091219,34804,-1916,-6975,-2526,0.954648852348327 +6919,-0.04279425740242,0.335086315870285,0.093546159565449,34804,-3008,-5989,-2895,0.957015991210938 +6921,0.013561713509262,0.308133721351624,0.103270247578621,34804,-4713,-5654,-2311,0.961946904659271 +6923,0.085031613707543,0.262466013431549,0.111625820398331,34804,-6797,-3179,-2756,0.97126293182373 +6925,0.193412184715271,0.181399866938591,0.117665819823742,34804,-11407,159,-2128,0.987309813499451 +6927,0.31146252155304,0.096359960734844,0.118478320538998,34804,-13473,1931,-2692,0.986701786518097 +6929,0.403500556945801,0.045053064823151,0.118966117501259,34804,-13783,173,-2097,0.989636182785034 +6931,0.461183041334152,0.012618456967175,0.12303464859724,34804,-11483,-665,-2643,0.990531086921692 +6933,0.496335566043854,-0.029894981533289,0.128361254930496,34804,-11419,749,-1968,0.987811505794525 +6935,0.511457204818726,-0.086141809821129,0.13121722638607,34804,-9386,2460,-2567,0.982210397720337 +6937,0.520486295223236,-0.122129291296005,0.133223727345467,34804,-10177,1802,-1889,0.981596946716309 +6939,0.50359708070755,-0.174461141228676,0.135155469179153,34804,-7222,3494,-2520,0.988461911678314 +6941,0.410531431436539,-0.273668050765991,0.137450397014618,34804,-1295,8863,-1815,0.999918878078461 +6943,0.277619570493698,-0.401340216398239,0.145461246371269,34804,4139,12261,-2429,0.993360280990601 +6945,0.162302479147911,-0.483692526817322,0.153910353779793,34804,4197,11227,-1591,0.982381224632263 +6947,0.091560408473015,-0.529677748680115,0.160909935832024,34804,2277,8464,-2299,0.979101717472076 +6949,0.045957911759615,-0.535586535930633,0.16129432618618,34804,1036,6818,-1477,0.966932952404022 +6951,0.016062557697296,-0.550913631916046,0.153879895806313,34804,408,6811,-2322,0.960512816905975 +6953,-0.020481631159783,-0.55710244178772,0.141874775290489,34804,1443,7426,-1682,0.954413294792175 +6955,-0.052935037761927,-0.567975640296936,0.136236250400543,34804,1584,6986,-2421,0.956140041351318 +6957,-0.086906716227532,-0.561729073524475,0.130907714366913,34804,2357,6860,-1790,0.959119200706482 +6959,-0.116741172969341,-0.554664492607117,0.125971838831902,34804,2345,5762,-2471,0.961041450500488 +6961,-0.137806624174118,-0.541395246982574,0.124423399567604,34804,2304,6277,-1848,0.96506005525589 +6971,-0.045327953994274,-0.365865230560303,0.111748307943344,34804,-2338,1546,-2515,0.980993211269379 +6973,-0.025278272107244,-0.325898736715317,0.11378475278616,34804,-2348,1462,-1928,0.97929859161377 +6975,0.001320824492723,-0.279051065444946,0.116058684885502,34804,-3247,-247,-2468,0.969336569309235 +6977,0.042841736227274,-0.222089394927025,0.128552556037903,34804,-5013,-1312,-1738,0.961760520935059 +6979,0.084329932928085,-0.167984455823898,0.141278028488159,34804,-5531,-2258,-2275,0.948860883712769 +6981,0.116931393742561,-0.118316821753979,0.146162748336792,34804,-5623,-2397,-1512,0.949773609638214 +6983,0.146248981356621,-0.065928749740124,0.145548030734062,34804,-5609,-3544,-2223,0.944424211978912 +6985,0.171138092875481,-0.010586801916361,0.144138768315315,34804,-6017,-4523,-1516,0.94296008348465 +6987,0.201271593570709,0.0298927500844,0.146415501832962,34804,-6543,-4060,-2195,0.944267392158508 +6989,0.202681347727776,0.061276432126761,0.15473572909832,34804,-4942,-3985,-1370,0.955204963684082 +6991,0.111487038433552,0.013460442423821,0.160975709557533,34804,3336,2474,-2071,1.00302004814148 +6993,-0.179725736379623,-0.053257998079062,0.159026384353638,34804,22223,4887,-1292,1.06135725975037 +6995,-0.566439390182495,-0.096507333219051,0.157951846718788,34804,32767,3748,-2067,1.07246243953705 +6997,-0.775200605392456,-0.159891083836555,0.152179881930351,34804,26212,6432,-1347,1.09253191947937 +6999,-0.663448750972748,-0.31262993812561,0.15402615070343,34804,351,14768,-2071,1.1315952539444 +7001,-0.382018864154816,-0.482654571533203,0.153622508049011,34804,-15025,19454,-1304,1.12763595581055 +7003,-0.157221034169197,-0.553177773952484,0.142060488462448,34804,-14835,12552,-2129,1.14500319957733 +7005,-0.122506588697433,-0.466878533363342,0.130059868097305,34804,-1459,1047,-1562,1.14382827281952 +7007,-0.263325721025467,-0.215289890766144,0.102904908359051,34804,12932,-15156,-2378,1.13399374485016 +7009,-0.416101217269898,-0.007533275987953,0.082795456051827,34804,16859,-15004,-2105,1.14267456531525 +7011,-0.417236655950546,0.036397483199835,0.062245380133391,34804,5323,-3889,-2646,1.12691056728363 +7013,-0.27492493391037,-0.01963197439909,0.037359993904829,34804,-6415,4090,-2632,1.11153852939606 +7015,-0.135228723287582,-0.05659494176507,0.021198557689786,34804,-8684,3247,-2924,1.09323489665985 +7017,-0.031401664018631,-0.054159283638001,0.011388468556106,34804,-7543,490,-2937,1.0633397102356 +7019,0.028290927410126,-0.02949389629066,0.008010462857783,34804,-5286,-1529,-3016,1.04588401317596 +7021,0.059748522937298,0.000480591435917,0.006930266972631,34804,-3842,-2345,-2990,1.02235949039459 +7023,0.10009041428566,0.020536754280329,0.007609452586621,34804,-4958,-1913,-3019,0.986899018287659 +7025,0.141849592328072,0.044073078781366,0.011115331202746,34804,-5961,-2590,-2941,0.966500520706177 +7027,0.174440950155258,0.054013315588236,0.017373394221068,34804,-5535,-1684,-2953,0.947290897369385 +7029,0.186790451407433,0.06228968501091,0.022047251462936,34804,-4661,-1811,-2812,0.939146995544434 +7031,0.194827228784561,0.06332229077816,0.026841482147575,34804,-4156,-1204,-2886,0.935263812541962 +7033,0.191588893532753,0.082942791283131,0.034063018858433,34804,-3710,-2985,-2668,0.922275543212891 +7035,0.183717250823975,0.090711824595928,0.045828770846129,34804,-2947,-2112,-2752,0.925102412700653 +7037,0.173200339078903,0.102054215967655,0.052536468952894,34804,-2978,-2741,-2446,0.923478841781616 +7039,0.174699902534485,0.122084863483906,0.056981705129147,34804,-3571,-3484,-2669,0.929066777229309 +7041,0.192706495523453,0.149209722876549,0.060755658894777,34804,-5426,-4694,-2342,0.938751697540283 +7043,0.218077272176742,0.172224119305611,0.06549683958292,34804,-5995,-4482,-2602,0.938213527202606 +7045,0.230771481990814,0.174651280045509,0.06915844976902,34804,-5764,-3405,-2236,0.943547189235687 +7047,0.206906169652939,0.215677693486214,0.069556139409542,34804,-2418,-6474,-2565,0.967852115631104 +7049,0.164987325668335,0.259674698114395,0.068374074995518,34804,-885,-7869,-2237,1.01656889915466 +7051,0.155169188976288,0.258552968502045,0.064344324171543,34804,-2763,-4187,-2591,1.08203947544098 +7053,0.137827649712563,0.116411529481411,0.055237010121346,34804,-2265,7686,-2382,1.15044033527374 +7055,0.009003105573356,-0.045410286635161,0.044346310198307,34804,7793,11630,-2722,1.16740703582764 +7057,-0.180247455835342,-0.089665368199349,0.029450047761202,34804,15230,4010,-2677,1.14059937000275 +7059,-0.274732559919357,-0.095137931406498,0.007260179147124,34804,9485,1183,-2974,1.11666345596313 +7061,-0.270721971988678,-0.079914331436157,-0.003434302052483,34804,2958,-364,-3065,1.09053981304169 +7063,-0.262242585420609,-0.049095891416073,0.001005824538879,34804,2055,-2041,-3020,1.05420100688934 +7065,-0.271344929933548,-0.007910954765975,0.001260051154532,34804,4022,-3367,-3013,1.03044760227203 +7067,-0.253011047840118,0.017585778608918,-0.004815314896405,34804,1340,-2613,-3062,1.03171038627625 +7069,-0.219721063971519,0.036634147167206,-0.010007918812335,34804,258,-2506,-3149,1.02965414524078 +7071,-0.191244035959244,0.036413297057152,-0.012733984738588,34804,-172,-1056,-3120,1.01630830764771 +7073,-0.175621137022972,0.03566762059927,-0.019972406327725,34804,894,-1077,-3271,1.00074148178101 +7075,-0.179505676031113,0.04440750181675,-0.027439339086413,34804,2057,-1827,-3227,0.999826312065124 +7077,-0.196531340479851,0.062011156231165,-0.032143998891115,34804,3652,-2832,-3420,0.999205410480499 +7079,-0.202889010310173,0.058764461427927,-0.034972243010998,34804,2659,-1199,-3287,1.00394284725189 +7081,-0.198000594973564,0.034916754812002,-0.036063972860575,34804,2195,554,-3474,1.00693762302399 +7083,-0.192204281687736,0.009184091351926,-0.035592440515757,34804,1725,1109,-3299,1.00715804100037 +7085,-0.185299947857857,-0.030545126646757,-0.035533297806978,34804,1934,2754,-3477,1.00585377216339 +7087,-0.189215958118439,-0.049677807837725,-0.037673410028219,34804,2464,1497,-3322,1.00065064430237 +7089,-0.196526184678078,-0.075400561094284,-0.039577051997185,34804,3222,2498,-3534,0.991354823112488 +7091,-0.210755944252014,-0.075269229710102,-0.040731992572546,34804,3603,521,-3352,0.98192024230957 +7093,-0.227305114269257,-0.081779859960079,-0.034672521054745,34804,4481,1271,-3486,0.974192321300507 +7095,-0.245483607053757,-0.089847214519978,-0.029352858662605,34804,4490,1358,-3282,0.972224056720733 +7097,-0.226216971874237,-0.110600121319294,-0.025239704176784,34804,2002,2819,-3383,0.978055536746979 +7099,-0.182517424225807,-0.13908776640892,-0.022766452282667,34804,-739,3584,-3243,0.969923913478851 +7101,-0.140403628349304,-0.131370380520821,-0.021107329055667,34804,-935,1172,-3342,0.967622697353363 +7103,-0.1206970885396,-0.117133691906929,-0.012651205062866,34804,159,274,-3180,0.967733085155487 +7105,-0.120764002203941,-0.098639607429504,-0.004513218998909,34804,1840,-83,-3151,0.96354615688324 +7107,-0.109813146293163,-0.074441254138947,-0.000359020516044,34804,691,-1003,-3098,0.952589809894562 +7109,-0.081516772508621,-0.036168586462736,0.007151965051889,34804,-788,-2476,-3013,0.947122931480408 +7111,-0.025267843157053,-0.01229396648705,0.018815483897925,34804,-3726,-1850,-2968,0.943794786930084 +7113,0.023268116638064,-0.003024499164894,0.027400001883507,34804,-3939,-921,-2773,0.938226997852325 +7115,0.068022631108761,0.004285896662623,0.034195296466351,34804,-4251,-896,-2860,0.934599936008453 +7117,0.126470699906349,0.013526206836104,0.038916565477848,34804,-6348,-1182,-2634,0.942912459373474 +7119,0.213832125067711,-0.02838453091681,0.044326767325401,34804,-9452,3098,-2785,0.962189793586731 +7121,0.314245164394379,-0.076556257903576,0.047495048493147,34804,-12494,4412,-2530,0.960638642311096 +7123,0.378742903470993,-0.075664602220059,0.046379428356886,34804,-10323,750,-2766,0.961808621883392 +7125,0.424144387245178,-0.046348318457604,0.048607897013426,34804,-10516,-1604,-2510,0.972615540027618 +7127,0.455722182989121,0.006537332199514,0.06028325855732,34804,-9265,-4128,-2664,0.971758425235748 +7129,0.476840198040008,0.036072388291359,0.072137728333473,34804,-9835,-2950,-2224,0.959030389785767 +7131,0.491138160228729,0.06890944391489,0.079619735479355,34804,-8755,-3600,-2521,0.946980834007263 +7133,0.505405128002167,0.086099706590176,0.082901693880558,34804,-10042,-2909,-2086,0.945795118808746 +7135,0.511570513248444,0.137121126055718,0.088782623410225,34804,-8702,-5918,-2446,0.951357364654541 +7137,0.516126930713654,0.173453792929649,0.095057234168053,34804,-9745,-5759,-1932,0.943530678749084 +7139,0.506550908088684,0.204279169440269,0.092565044760704,34804,-7743,-5514,-2406,0.942455410957336 +7141,0.439184725284576,0.270076096057892,0.087347529828549,34804,-3544,-9541,-2013,0.972006738185883 +7143,0.21821965277195,0.264479249715805,0.074026443064213,34804,11337,-3891,-2521,1.06885266304016 +7145,-0.086200304329395,0.055342979729176,0.063642963767052,34804,21876,13555,-2278,1.1370564699173 +7147,-0.279446333646774,-0.229836449027061,0.06169305741787,34804,16530,23203,-2597,1.1310920715332 +7149,-0.316178381443024,-0.399541318416595,0.050474874675274,34804,6525,18197,-2417,1.12442946434021 +7151,-0.310972183942795,-0.382454037666321,0.049196116626263,34804,2911,3924,-2677,1.11898350715637 +7153,-0.345738053321838,-0.295290529727936,0.069479085505009,34804,7009,-1731,-2189,1.0996572971344 +7155,-0.337096184492111,-0.284558564424515,0.08077135682106,34804,3197,3114,-2450,1.0733060836792 +7157,-0.277118772268295,-0.282977700233459,0.073815993964672,34804,-767,4340,-2129,1.03690648078918 +7159,-0.213829234242439,-0.260094374418259,0.068873271346092,34804,-2362,2025,-2521,1.03024995326996 +7161,-0.214181661605835,-0.196857020258904,0.070912048220635,34804,2636,-1339,-2155,1.03113961219788 +7163,-0.259215146303177,-0.129761457443237,0.070856288075447,34804,6142,-2913,-2498,1.03252160549164 +7165,-0.225546643137932,-0.137659832835197,0.062933720648289,34804,488,2883,-2240,1.04252552986145 +7167,-0.085425108671188,-0.22816376388073,0.061283476650715,34804,-9513,9861,-2555,1.04853427410126 +7169,0.06848156452179,-0.352393120527267,0.065655075013638,34804,-12855,14814,-2201,1.03104519844055 +7171,0.104791767895222,-0.365842759609222,0.059310287237167,34804,-4838,6486,-2559,1.02686738967896 +7173,0.028413074091077,-0.289542227983475,0.053003840148449,34804,4272,-424,-2341,1.0271430015564 +7175,-0.076174445450306,-0.185135379433632,0.047719512134791,34804,7838,-4408,-2632,1.00453662872314 +7177,-0.138635113835335,-0.147496029734611,0.049712758511305,34804,6026,149,-2373,0.992250084877014 +7179,-0.160046860575676,-0.132110014557838,0.052588693797588,34804,3151,1282,-2592,0.981551229953766 +7181,-0.15593595802784,-0.108976766467094,0.048055827617645,34804,1609,637,-2387,0.974229574203491 +7183,-0.155837595462799,-0.098803780972958,0.040068276226521,34804,1625,1238,-2673,0.970102369785309 +7199,0.051003094762564,-0.025675639510155,0.054688412696123,34804,-3722,-412,-2547,0.979328334331512 +7201,0.087641477584839,0.004958542063832,0.056995317339897,34804,-4538,-1535,-2248,0.980751216411591 +7203,0.113662958145142,0.034630596637726,0.059220045804978,34804,-3993,-1877,-2508,0.978770911693573 +7205,0.127781569957733,0.07213469594717,0.060174111276865,34804,-3631,-3127,-2201,0.973591446876526 +7207,0.133680388331413,0.124558731913567,0.058935970067978,34804,-2899,-4821,-2502,0.969848036766052 +7209,0.134912997484207,0.178943634033203,0.058599404990673,34804,-2881,-6124,-2211,0.971018612384796 +7211,0.123918630182743,0.233348399400711,0.061538591980934,34804,-1613,-6599,-2476,0.959744215011597 +7213,0.103458195924759,0.262060344219208,0.067262709140778,34804,-878,-5730,-2100,0.948115885257721 +7215,0.073622591793537,0.307003647089005,0.067471295595169,34804,408,-7092,-2426,0.940119504928589 +7217,0.040737893432379,0.357509553432465,0.065825134515762,34804,965,-8976,-2107,0.94299054145813 +7219,0.038088925182819,0.403385102748871,0.060701318085194,34804,-1056,-8700,-2463,0.9599928855896 +7221,0.100654698908329,0.378614753484726,0.052089624106884,34804,-6876,-4090,-2261,0.999600827693939 +7223,0.261585921049118,0.260637760162354,0.03230594471097,34804,-16035,4917,-2651,1.05277264118195 +7225,0.420030355453491,0.198042809963226,-0.000259187683696,34804,-19032,1410,-2877,1.11561739444733 +7227,0.409334570169449,0.288983434438705,-0.028437156230211,34804,-6056,-10545,-3071,1.15180158615112 +7229,0.291126519441605,0.462463200092316,-0.049076829105616,34804,2725,-19923,-3462,1.17972385883331 +7231,0.244984313845634,0.5219407081604,-0.063605055212975,34804,-1296,-11841,-3323,1.20303356647491 +7233,0.331469655036926,0.452815622091293,-0.082089610397816,34804,-12729,-2595,-3867,1.17697978019714 +7235,0.444520175457001,0.406132727861404,-0.095924004912376,34804,-15717,-2781,-3562,1.1446338891983 +7237,0.497720777988434,0.386408925056458,-0.08964466303587,34804,-13245,-5247,-3975,1.12284529209137 +7239,0.43765589594841,0.354826211929321,-0.082432389259338,34804,-3450,-3303,-3486,1.11314785480499 +7241,0.285421282052994,0.255362987518311,-0.083711437880993,34822,4712,2451,-3921,1.09627282619476 +7243,0.12303027510643,0.135684698820114,-0.082745872437954,34822,8254,6036,-3505,1.06273376941681 +7245,0.017720671370626,0.056850850582123,-0.078139841556549,34822,5613,4117,-3866,1.04240345954895 +7247,-0.04332235082984,0.053308714181185,-0.078473478555679,34822,3363,-1127,-3491,1.02409994602203 +7249,-0.047345466911793,0.095376968383789,-0.075315326452255,34822,-565,-5196,-3849,0.997707784175873 +7251,-0.045214522629976,0.167427763342857,-0.065842472016811,34822,-1118,-8223,-3419,0.982205986976624 +7253,-0.061211626976729,0.230202406644821,-0.054914448410273,34822,545,-8938,-3626,0.98036777973175 +7255,-0.072516851127148,0.300904750823975,-0.053367201238871,34822,258,-10148,-3345,0.975697994232178 +7257,-0.074592418968678,0.377591192722321,-0.056860405951738,34822,-215,-12474,-3665,0.985887050628662 +7259,-0.081428110599518,0.442757278680801,-0.050777308642864,34822,95,-11963,-3340,0.98777037858963 +7261,-0.111629068851471,0.483054399490356,-0.040732499212027,34822,2443,-11771,-3488,0.984687805175781 +7263,-0.154740691184998,0.491201728582382,-0.036344155669212,34822,3792,-8797,-3250,0.984548509120941 +7265,-0.203642904758453,0.537380039691925,-0.040598757565022,34822,5324,-13311,-3496,0.985939919948578 +7267,-0.235998958349228,0.563889861106873,-0.043952647596598,34822,4274,-11406,-3312,0.994268119335175 +7269,-0.264179557561874,0.587543666362762,-0.037669595330954,34822,4914,-12770,-3470,0.995222628116608 +7271,-0.280934303998947,0.571269035339356,-0.027083072811365,34822,3915,-8721,-3205,0.993490517139435 +7273,-0.291540414094925,0.551615178585053,-0.022225830703974,34822,4231,-9359,-3292,0.997636795043945 +7275,-0.294511646032333,0.531766355037689,-0.020822195336223,34822,3251,-8159,-3168,1.00105941295624 +7277,-0.28712660074234,0.493626356124878,-0.022056121379137,34822,2997,-7340,-3292,0.998460292816162 +7279,-0.277861267328262,0.465833365917206,-0.020559372380376,34822,2263,-6880,-3172,1.00298011302948 +7281,-0.272676259279251,0.429722666740418,-0.015481742098928,34822,3052,-6670,-3217,1.00492823123932 +7283,-0.261444121599197,0.403410732746124,-0.009767233394086,34822,2009,-6298,-3103,1.01060175895691 +7285,-0.222267121076584,0.351655036211014,-0.002109338995069,34822,-69,-4472,-3061,1.02615177631378 +7287,-0.156297191977501,0.274691492319107,0.004353329073638,34822,-3316,-996,-3008,1.0362833738327 +7289,-0.100449115037918,0.186607867479324,0.01050265878439,35233,-3169,678,-2913,1.0228750705719 +7291,-0.08962095528841,0.151438310742378,0.017592985183001,35233,-275,-2319,-2917,1.01474261283875 +7293,-0.095777906477451,0.111939266324043,0.029923789203167,35233,1230,-1656,-2684,1.0121785402298 +7295,-0.127775341272354,0.082897692918778,0.036163825541735,35233,3383,-1835,-2787,0.995104610919952 +7297,-0.149459689855576,0.034419070929289,0.038187455385923,35233,3263,207,-2584,0.977302253246307 +7299,-0.17638373374939,-0.00383881200105,0.04244027286768,35233,3785,44,-2739,0.961763799190521 +7301,-0.195266202092171,-0.07164266705513,0.049737632274628,35233,3884,3310,-2443,0.95070344209671 +7303,-0.225665539503098,-0.145622789859772,0.054233301430941,35233,4831,4661,-2652,0.933506369590759 +7305,-0.246573805809021,-0.221598938107491,0.058058980852366,35233,4953,6382,-2342,0.922969400882721 +7307,-0.251610517501831,-0.284404367208481,0.056861411780119,35233,3499,5945,-2626,0.914728224277496 +7309,-0.262714773416519,-0.326747536659241,0.05742771551013,35233,4633,5796,-2345,0.914496123790741 +7311,-0.271518856287003,-0.370469599962234,0.056205250322819,35233,4175,5954,-2623,0.90934830904007 +7313,-0.276094615459442,-0.404381513595581,0.051533408463001,35233,4518,6607,-2410,0.916090130805969 +7315,-0.258354216814041,-0.423379987478256,0.053067434579134,35233,2214,5120,-2638,0.925548791885376 +7317,-0.218745768070221,-0.396058052778244,0.059210810810328,35233,541,2262,-2314,0.935825824737549 +7319,-0.170529410243034,-0.361685991287231,0.067281067371368,35233,-1124,587,-2533,0.938998639583588 +7321,-0.127544596791267,-0.30830505490303,0.07248204946518,35233,-1093,-862,-2148,0.94175398349762 +7323,-0.087013922631741,-0.271817952394485,0.077574126422405,35233,-1709,-716,-2452,0.942600071430206 +7325,-0.055982567369938,-0.232782199978828,0.083783768117428,35233,-1352,-946,-2002,0.946080446243286 +7327,-0.010014950297773,-0.204486593604088,0.086652748286724,35233,-3173,-993,-2378,0.950725555419922 +7329,0.025964898988605,-0.161032423377037,0.085661984980106,35233,-3026,-2349,-1965,0.948935270309448 +7331,0.064645178616047,-0.10158459097147,0.088043697178364,35233,-3729,-4632,-2356,0.945604801177978 +7333,0.111395619809628,-0.03269986063242,0.093163229525089,35233,-5223,-6224,-1859,0.944523215293884 +7347,0.505819857120514,0.173774495720863,0.089024469256401,35304,-10588,-5621,-2293,0.983136355876923 +7349,0.534313142299652,0.190263494849205,0.089869529008865,35304,-11431,-6348,-1839,0.981803178787231 +7351,0.544820964336395,0.217235758900642,0.092861272394657,35304,-9400,-7168,-2253,0.983934879302978 +7353,0.554452657699585,0.213696092367172,0.091923005878925,35304,-10652,-5387,-1803,0.985692739486694 +7355,0.555796205997467,0.207627072930336,0.087353855371475,35304,-9159,-4772,-2277,0.989999353885651 +7357,0.539746999740601,0.180461451411247,0.085234999656677,35304,-8824,-3250,-1871,1.0101410150528 +7359,0.40767452120781,0.046787213534117,0.095384739339352,35304,2273,6586,-2209,1.06601023674011 +7361,0.125949382781982,-0.230577498674393,0.128277599811554,35304,16779,21336,-1339,1.09245896339417 +7363,-0.152436897158623,-0.494566082954407,0.165142074227333,35304,20732,23785,-1709,1.07084846496582 +7365,-0.319256961345673,-0.627774596214294,0.17401097714901,35304,15825,17656,-770,1.0644394159317 +7367,-0.37498676776886,-0.673491418361664,0.165801852941513,35304,8122,10999,-1677,1.04416155815125 +7369,-0.397382885217667,-0.681821405887604,0.173303544521332,35304,6898,9879,-754,1.02038192749023 +7371,-0.42407900094986,-0.7111976146698,0.182802021503449,35304,6928,10677,-1532,1.01180994510651 +7373,-0.453839033842087,-0.719135344028473,0.17422953248024,35304,8517,10769,-721,1.00641739368439 +7375,-0.460353225469589,-0.719832718372345,0.164461344480515,35304,6207,9073,-1630,1.00692570209503 +7377,-0.454711437225342,-0.707058906555176,0.163363486528397,35304,6200,9415,-828,1.0036643743515 +7379,-0.42650505900383,-0.718761742115021,0.163397744297981,35304,3440,10170,-1611,1.00435495376587 +7381,-0.388507336378098,-0.716683030128479,0.152178585529327,35304,3001,10672,-940,1.01036155223846 +7383,-0.349050492048264,-0.694060206413269,0.142510399222374,35304,1700,7687,-1731,1.00845193862915 +7385,-0.307962566614151,-0.67390376329422,0.142143607139587,35304,1633,9011,-1039,1.01088225841522 +7387,-0.276620119810104,-0.648073971271515,0.146691620349884,35698,1384,7112,-1680,1.01876842975616 +7389,-0.24680432677269,-0.641527056694031,0.144279450178146,35698,1576,9762,-995,1.02475440502167 +7391,-0.208270847797394,-0.613434672355652,0.134867802262306,35698,2,6753,-1739,1.02710115909576 +7393,-0.171591535210609,-0.582000851631165,0.134172171354294,35698,-38,7298,-1093,1.01489508152008 +7395,-0.160270407795906,-0.545972406864166,0.140391558408737,35698,1344,5492,-1681,1.00179398059845 +7397,-0.152234554290771,-0.526969254016876,0.143162280321121,35698,1772,7550,-966,0.986992001533508 +7399,-0.151305809617043,-0.489742696285248,0.140154257416725,35698,2032,4849,-1660,0.974101781845093 +7401,-0.143083423376083,-0.425744473934174,0.140783652663231,35698,1681,2908,-969,0.9663245677948 +7403,-0.124741949141026,-0.371605217456818,0.147396862506866,35698,471,2147,-1588,0.949865460395813 +7405,-0.120021671056747,-0.31769335269928,0.153231337666512,35698,1621,2058,-797,0.947157323360443 +7407,-0.119861021637917,-0.260687857866287,0.159251138567925,35698,1762,506,-1483,0.951143503189087 +7409,-0.117123886942863,-0.19393752515316,0.165792033076286,35698,1790,-734,-620,0.961193263530731 +7411,-0.090967431664467,-0.118755586445332,0.169528961181641,35698,-454,-2730,-1385,0.98662143945694 +7413,-0.026519687846303,0.004190039355308,0.159870326519012,35698,-4056,-7931,-656,1.02683103084564 +7415,0.153178468346596,0.223990887403488,0.141206651926041,35698,-14939,-18001,-1554,1.06649255752563 +7417,0.367151111364365,0.469980597496033,0.126379489898682,35698,-21253,-24406,-1009,1.04826271533966 +7419,0.496480703353882,0.607214033603668,0.119548320770264,35698,-16424,-17792,-1683,1.03184628486633 +7421,0.546866834163666,0.657939374446869,0.115310318768024,35698,-12678,-13712,-1119,1.0393944978714 +7423,0.594708323478699,0.657987475395203,0.122317217290401,35698,-12251,-8987,-1645,1.05912458896637 +7425,0.721375584602356,0.58238810300827,0.136959686875343,35698,-21251,-3710,-853,1.07870757579803 +7427,0.897716224193573,0.465197503566742,0.142561614513397,35698,-26137,1918,-1483,1.06768405437469 +7429,1.01045083999634,0.403539896011352,0.134362012147903,35698,-25324,-2029,-872,1.07462561130524 +7431,0.876766264438629,0.573327243328095,0.119663365185261,35698,-4090,-20373,-1619,1.11430311203003 +7433,0.564527988433838,0.817813396453857,0.100326634943485,35698,11998,-30963,-1268,1.12718439102173 +7435,0.298776000738144,0.842697739601135,0.073494948446751,36037,13402,-14229,-1922,1.15344333648682 +7437,0.149958923459053,0.599253296852112,0.073481746017933,36037,6856,7200,-1571,1.19458711147308 +7439,0.019981360062957,0.273210346698761,0.081547021865845,36037,7607,18804,-1856,1.17962300777435 +7441,-0.096763260662556,0.074352629482746,0.079713873565197,36037,8536,12380,-1474,1.14627659320831 +7443,-0.146967709064484,0.032124429941177,0.084783338010311,36037,4328,1899,-1821,1.12025129795074 +7445,-0.158146426081657,0.074594266712666,0.0831683203578,36037,2021,-4941,-1420,1.09974217414856 +7447,-0.169994845986366,0.106484405696392,0.082051582634449,36037,1979,-4511,-1827,1.07598650455475 +7449,-0.194170296192169,0.155030265450478,0.077599883079529,36037,3609,-6734,-1475,1.03799593448639 +7451,-0.207992017269134,0.221435204148293,0.066695287823677,36037,2749,-8705,-1921,1.02415072917938 +7453,-0.240010350942612,0.255636245012283,0.061249826103449,36037,5010,-7426,-1658,1.01253688335419 +7455,-0.286879897117615,0.264213889837265,0.054629780352116,36037,6355,-5294,-1995,0.993461549282074 +7457,-0.31731840968132,0.264108866453171,0.045413985848427,36037,6282,-5227,-1835,0.988854944705963 +7459,-0.324438333511353,0.269514471292496,0.041151288896799,36037,4190,-5266,-2081,0.995401918888092 +7461,-0.323072850704193,0.283600896596909,0.036368303000927,36037,4255,-6686,-1934,1.00376772880554 +7463,-0.31329733133316,0.301665663719177,0.026865569874644,36037,2969,-6766,-2175,1.0068427324295 +7465,-0.293220013380051,0.317347764968872,0.021493365988135,36037,2568,-7488,-2104,1.01038491725922 +7467,-0.259370148181915,0.321476638317108,0.019190339371562,36037,606,-6201,-2225,1.00718176364899 +7469,-0.232963293790817,0.31399205327034,0.017867233604193,36037,1253,-5922,-2143,1.00772047042847 +7471,-0.214850634336472,0.30470022559166,0.013238586485386,36037,1202,-5146,-2264,1.00647234916687 +7473,-0.194909811019897,0.306084632873535,0.004335242323577,36037,1203,-6579,-2300,1.00485742092133 +7475,-0.162372946739197,0.300151735544205,-0.001129651325755,36037,-492,-5468,-2363,1.00057363510132 +7477,-0.12264958769083,0.297988623380661,-0.000849335454404,36037,-1305,-6340,-2361,0.989061415195465 +7479,-0.07725827395916,0.287188768386841,-0.000664822000545,36037,-2574,-5076,-2361,0.988283216953278 +7481,-0.031452305614948,0.288146078586578,-0.001122603775002,36037,-3184,-6542,-2365,0.980126917362213 +7483,0.008533710613847,0.298649817705154,0.001747979433276,36037,-3400,-6906,-2346,0.973916471004486 +7485,0.048525180667639,0.309877902269363,0.001839225180447,36037,-4078,-7776,-2331,0.969606757164001 +7487,0.086119741201401,0.33589181303978,0.000525679148268,36037,-4363,-8703,-2355,0.966792106628418 +7489,0.122749298810959,0.358578264713287,0.007692771032453,36037,-5086,-9549,-2262,0.962263345718384 +7491,0.148756355047226,0.407252997159958,0.02160369604826,36037,-4488,-11525,-2210,0.95702338218689 +7493,0.173363253474236,0.439761728048325,0.031294517219067,36037,-5122,-11764,-1983,0.948614656925201 +7495,0.185017138719559,0.463808834552765,0.032249700278044,36037,-4061,-10785,-2132,0.941500604152679 +7497,0.190495356917381,0.460738062858582,0.036932580173016,36037,-4118,-9780,-1913,0.947091400623322 +7499,0.192118749022484,0.461738675832748,0.040193904191256,36037,-3535,-9330,-2072,0.957182347774506 +7501,0.203789576888084,0.458743661642075,0.03897362574935,36037,-4862,-9968,-1885,0.969595074653626 +7503,0.208072885870934,0.453060150146484,0.040584430098534,36037,-4049,-8950,-2064,0.975044310092926 +7505,0.202522993087768,0.446617007255554,0.042000290006399,36037,-3696,-9736,-1846,0.980531632900238 +7507,0.204018890857697,0.437001794576645,0.041859284043312,36037,-3886,-8656,-2050,0.986178755760193 +7509,0.214384600520134,0.426398366689682,0.040907017886639,36037,-5135,-9326,-1855,0.990899324417114 +7511,0.235536321997642,0.402445942163467,0.038098424673081,36037,-5849,-7343,-2070,0.990617394447327 +7513,0.252431422472,0.392382889986038,0.033406093716621,36037,-6328,-9011,-1940,0.984391450881958 +7515,0.264883249998093,0.364509850740433,0.030664389953017,36037,-5766,-6713,-2117,0.978270292282104 +7517,0.268218725919723,0.354469656944275,0.024056129157543,36037,-5731,-8572,-2047,0.96759569644928 +7519,0.273787289857864,0.337201923131943,0.018670499324799,36037,-5528,-7258,-2196,0.963472485542297 +7521,0.285244852304459,0.331820607185364,0.014965459704399,36037,-6734,-8721,-2155,0.962130308151245 +7523,0.295234948396683,0.329178422689438,0.01143307518214,36037,-6290,-8360,-2245,0.96324074268341 +7525,0.301367998123169,0.302587658166885,0.009581917896867,36037,-6749,-6896,-2218,0.956096053123474 +7527,0.284207582473755,0.280637294054031,0.009231651201844,36037,-4332,-6439,-2260,0.963785648345947 +7529,0.243839725852013,0.24352702498436,0.00451811728999,36037,-2624,-5319,-2278,0.980832517147064 +7531,0.209375619888306,0.219570249319077,-0.004013504832983,36037,-2140,-5549,-2352,0.989225685596466 +7533,0.187036097049713,0.175723671913147,-0.008803566917777,36037,-3097,-3843,-2436,0.998611509799957 +7535,0.153746455907822,0.141541033983231,-0.00832721311599,36037,-1520,-3796,-2384,1.00251126289368 +7537,0.132123976945877,0.085350684821606,-0.004246233031154,36037,-2330,-1573,-2381,1.00619781017303 +7539,0.110401347279549,0.031613729894161,-0.005277634132653,36037,-1795,-875,-2365,1.00557899475098 +7541,0.091137558221817,-0.019013907760382,-0.005892670247704,36037,-1891,-314,-2399,1.0079630613327 +7543,0.069510944187641,-0.070643618702889,-0.013264146633446,36037,-1264,430,-2422,1.00595259666443 +7545,0.055540394037962,-0.112720236182213,-0.016873529180884,36037,-1726,603,-2527,1.00688302516937 +7547,0.043205298483372,-0.152475968003273,-0.017478412017226,36037,-1584,787,-2455,1.00778162479401 +7549,0.033923447132111,-0.183431789278984,-0.018487738445401,36037,-1743,1004,-2547,1.00135445594788 +7551,0.027622768655419,-0.211759403347969,-0.014310764148831,36037,-1816,885,-2438,0.991914570331574 +7553,0.013485056348145,-0.226095005869865,-0.010171488858759,36037,-1080,584,-2450,0.991255402565002 +7555,-0.001514776260592,-0.256968915462494,-0.004733491688967,36037,-789,1803,-2374,0.992769479751587 +7557,-0.02865125797689,-0.284935295581818,-0.00488332984969,36037,543,2611,-2387,0.993101835250854 +7559,-0.059763882309198,-0.315327703952789,-0.009242375381291,36037,1208,2719,-2407,0.995891213417053 +7561,-0.092717356979847,-0.330348312854767,-0.014889519661665,36037,2024,2547,-2506,0.985356152057648 +7563,-0.125427976250649,-0.353918761014938,-0.018350340425968,36037,2303,2921,-2473,0.979235231876373 +7565,-0.15442843735218,-0.372292786836624,-0.016973495483399,36037,2794,3636,-2533,0.969887495040894 +7567,-0.182136431336403,-0.390592843294144,-0.017415495589376,36037,2826,3229,-2470,0.963329672813416 +7569,-0.193749666213989,-0.409327894449234,-0.018234070390463,36037,2258,4431,-2552,0.956174433231354 +7571,-0.203027278184891,-0.392857015132904,-0.020958671346307,36037,1890,948,-2498,0.950892269611358 +7573,-0.209511891007423,-0.395771920681,-0.026122316718102,36037,2227,3242,-2652,0.945316910743713 +7575,-0.225293591618538,-0.386531800031662,-0.032654155045748,36037,2766,1547,-2584,0.945018529891968 +7577,-0.251832991838455,-0.389452517032623,-0.043339770287275,36037,4440,3304,-2864,0.948066055774689 +7579,-0.283240348100662,-0.372312933206558,-0.057006031274796,36037,4826,945,-2760,0.947961151599884 +7581,-0.301054567098618,-0.353024423122406,-0.065134704113007,36037,4721,1270,-3134,0.951900124549866 +7583,-0.314464747905731,-0.342237591743469,-0.070033609867096,36037,4116,1120,-2861,0.948803246021271 +7585,-0.336828410625458,-0.321992963552475,-0.071852795779705,36037,5773,841,-3228,0.95547091960907 +7587,-0.358343243598938,-0.303228914737701,-0.06978090852499,36037,5475,126,-2873,0.964242219924927 +7589,-0.38513907790184,-0.257121205329895,-0.068684481084347,36037,7042,-1933,-3207,0.967649579048157 +7591,-0.404124051332474,-0.213193580508232,-0.067262686789036,36037,6124,-2857,-2869,0.969675660133362 +7593,-0.423389941453934,-0.152514606714249,-0.066637493669987,36037,7310,-4575,-3197,0.973619103431702 +7595,-0.427889138460159,-0.108051151037216,-0.060466524213553,36037,5621,-4339,-2834,0.977287173271179 +7597,-0.423308491706848,-0.048491798341274,-0.054531797766686,36037,5792,-6150,-3067,0.975788295269012 +7599,-0.399937927722931,0.009397541172802,-0.042972572147846,36037,3417,-6971,-2725,0.97943240404129 +7601,-0.375104606151581,0.072821207344532,-0.034809231758118,36037,3734,-8420,-2842,0.981990873813629 +7603,-0.346297234296799,0.125604093074799,-0.031676709651947,36037,2429,-8314,-2654,0.982762813568115 +7605,-0.310252636671066,0.164266556501389,-0.027839263901115,36037,2037,-8200,-2764,0.976392984390259 +7607,-0.272415280342102,0.222938388586044,-0.027647677809,36037,865,-10219,-2633,0.974143862724304 +7609,-0.228795394301414,0.260299414396286,-0.027349002659321,36037,295,-9778,-2761,0.971583783626556 +7611,-0.182217881083488,0.295910477638245,-0.023933678865433,36037,-948,-9745,-2613,0.978510797023773 +7613,-0.138900235295296,0.316759616136551,-0.012676012702286,36037,-1054,-9648,-2590,0.997501254081726 +7615,-0.098575599491596,0.338968515396118,-0.003846107283607,36037,-1634,-9560,-2478,1.00762069225311 +7617,-0.049506228417158,0.337451964616776,0.004469743464142,36037,-2867,-8540,-2388,1.00751769542694 +7619,-0.020502455532551,0.333219408988953,0.007290607318282,36037,-1918,-7750,-2401,1.00631546974182 +7621,-0.012769119814038,0.316392809152603,0.005038246978074,36037,-487,-7263,-2382,1.0143963098526 +7623,-0.000439811206888,0.287454515695572,0.001756085664965,36037,-1003,-5480,-2440,1.01944231987 +7625,0.012010033242405,0.26248499751091,0.001081307418644,36037,-1229,-5951,-2431,1.02912199497223 +7627,0.0218815356493,0.21962596476078,0.003838619217277,36037,-1150,-3643,-2426,1.02884423732758 +7629,0.033660348504782,0.1739621758461,0.005516240373254,36037,-1546,-3144,-2383,1.04244959354401 +7631,0.097295723855496,0.078266635537148,-0.001622715150006,36037,-6099,2077,-2464,1.0708624124527 +7633,0.238058358430862,-0.065629594027996,-0.016888892278075,36037,-14162,7736,-2656,1.08493614196777 +7635,0.391229122877121,-0.193031385540962,-0.033112276345492,36037,-16840,8257,-2685,1.07035779953003 +7637,0.480750203132629,-0.247129082679749,-0.040261007845402,36037,-14605,4299,-2942,1.06411921977997 +7639,0.517092764377594,-0.294439345598221,-0.040699541568756,36037,-10500,4074,-2745,1.06437885761261 +7653,0.416635036468506,-0.324505031108856,-0.102394565939903,36037,-6010,711,-3714,1.01734042167664 +7655,0.376991659402847,-0.305962741374969,-0.101041682064533,36037,-3921,124,-3218,1.00588607788086 +7657,0.346288532018661,-0.315469324588776,-0.101970411837101,36037,-4863,2944,-3725,0.998563766479492 +7659,0.311076462268829,-0.302814036607742,-0.108263596892357,36037,-3458,637,-3286,1.00057315826416 +7661,0.274649649858475,-0.29880964756012,-0.108554646372795,36037,-3436,1841,-3821,0.991249263286591 +7663,0.224674597382545,-0.297251015901566,-0.108210973441601,36037,-1293,1482,-3305,0.98039573431015 +7665,0.168470829725266,-0.301648259162903,-0.109225057065487,36037,-397,2618,-3847,0.978458881378174 +7667,0.104768589138985,-0.29715833067894,-0.116168394684792,36037,1327,1403,-3379,0.974340319633484 +7669,0.055230546742678,-0.278578341007233,-0.120666563510895,36037,917,732,-4002,0.975070059299469 +7671,0.011080668307841,-0.250762611627579,-0.115826636552811,36037,1241,-809,-3399,0.97568666934967 +7673,-0.034717202186585,-0.21914054453373,-0.113889098167419,36037,2103,-1051,-3945,0.976265251636505 +7675,-0.075534835457802,-0.189097911119461,-0.117045685648918,36037,2257,-1755,-3428,0.974813163280487 +7677,-0.111593298614025,-0.153389483690262,-0.115913838148117,36037,2674,-2337,-3993,0.974369406700134 +7679,-0.146093457937241,-0.123386263847351,-0.112303055822849,36037,2863,-2628,-3416,0.977996587753296 +7681,-0.178552135825157,-0.094662308692932,-0.108969047665596,36037,3566,-2739,-3934,0.977783679962158 +7683,-0.213437557220459,-0.054674126207829,-0.107218116521835,36037,3935,-4290,-3401,0.974240779876709 +7685,-0.234517902135849,-0.004420642741025,-0.099631287157536,36037,3753,-5728,-3846,0.967228949069977 +7687,-0.256908029317856,0.053202785551548,-0.093646921217442,36037,3768,-7103,-3326,0.969510853290558 +7689,-0.271230429410934,0.090049512684345,-0.100114114582539,36037,3971,-6325,-3872,0.974591910839081 +7691,-0.28649714589119,0.145183384418488,-0.105639293789864,36037,3804,-8291,-3428,0.980543971061706 +7693,-0.294317185878754,0.190172240138054,-0.104845739901066,36037,3998,-8613,-3948,0.992037057876587 +7695,-0.307551205158234,0.254034101963043,-0.10135955363512,36037,4091,-10572,-3418,0.997527778148651 +7697,-0.311723709106445,0.301526367664337,-0.091702170670033,36037,4161,-10716,-3812,0.996407985687256 +7699,-0.305351704359055,0.349901437759399,-0.084541231393814,36037,2796,-10984,-3319,0.991730511188507 +7701,-0.285583704710007,0.407122373580933,-0.080221712589264,36037,2145,-13301,-3692,0.99510258436203 +7703,-0.246369063854218,0.446893244981766,-0.071604438126087,36037,-274,-11955,-3246,0.99050110578537 +7705,-0.201582014560699,0.484674572944641,-0.059823501855135,36037,-913,-13396,-3464,0.99545407295227 +7707,-0.15587143599987,0.518560528755188,-0.048341877758503,36037,-1951,-12797,-3098,0.999874830245972 +7709,-0.098519340157509,0.549366533756256,-0.045914977788925,36037,-3415,-14192,-3309,1.01025211811066 +7711,0.024324461817741,0.527111828327179,-0.050606448203325,36037,-10021,-9163,-3123,1.03885531425476 +7713,0.179745823144913,0.425511747598648,-0.051899787038565,36037,-14975,-2940,-3390,1.08237445354462 +7715,0.289477109909058,0.194698691368103,-0.043296594172716,36037,-12972,10337,-3083,1.12518513202667 +7717,0.301912635564804,-0.052454359829426,-0.023253455758095,36037,-6835,15135,-3062,1.13186919689178 +7719,0.25297749042511,-0.236380606889725,-1.34843994601397E-05,36037,-1226,13172,-2791,1.12967157363892 +7721,0.208401009440422,-0.312359511852264,0.014105346985161,36037,-1344,7178,-2622,1.12135088443756 +7723,0.191479861736298,-0.315825074911118,0.020019389688969,36037,-2735,1515,-2652,1.09298300743103 +7725,0.192471325397491,-0.296975493431091,0.016594605520368,36037,-4441,281,-2591,1.05899822711945 +7727,0.213823199272156,-0.262897133827209,0.009185180999339,36037,-5890,-32767,-2726,1.03670120239258 +7729,0.247492164373398,-0.223623469471931,-0.001263140584342,36037,-7788,-32714,-2801,1.01876747608185 +7731,0.274194836616516,-0.174937918782234,-0.009953781031072,36037,-7258,-32767,-2859,0.999048888683319 +7733,0.285475313663483,-0.147788763046265,-0.006348066031933,36037,-6930,-32767,-2864,0.978831171989441 +7735,0.277629673480988,-0.127289682626724,0.00255233165808,36037,-4970,-32767,-2776,0.971968948841095 +7737,0.258263379335403,-0.129345118999481,0.009014536626637,36037,-4422,-31762,-2684,0.96529757976532 +7739,0.21774086356163,-0.139851972460747,0.010522153228521,36037,-1895,-31380,-2721,0.954260289669037 +7741,0.177428185939789,-0.164821580052376,0.018301637843251,36037,-1731,-29782,-2572,0.956485509872436 +7743,0.138807043433189,-0.193528935313225,0.029535973444581,36037,-990,-29540,-2589,0.954946517944336 +7745,0.098857179284096,-0.233453899621963,0.03690492361784,36037,-555,-27813,-2347,0.953012406826019 +7747,0.045605003833771,-0.288641005754471,0.039987985044718,36037,1339,-26480,-2512,0.946141242980957 +7749,-0.008808548562229,-0.35959580540657,0.041099507361651,36037,2210,-23717,-2288,0.95671957731247 +7751,-0.060045748949051,-0.452580600976944,0.043167937546969,36037,2707,-21563,-2484,0.966093957424164 +7753,-0.121554836630821,-0.562046945095062,0.044868808239698,36037,4587,-17761,-2231,0.978078424930572 +7755,-0.177071809768677,-0.691382110118866,0.049693129956722,36037,4743,-15579,-2433,0.992609202861786 +7757,-0.21786105632782,-0.812905132770538,0.045266672968865,36037,4746,-12810,-2214,0.99918395280838 +7759,-0.22533506155014,-0.957102119922638,0.03945055231452,36037,2091,-10630,-2496,1.00964665412903 +7761,-0.220831379294395,-1.07399690151215,0.037153672426939,36037,1629,-8779,-2300,1.01596450805664 +7763,-0.188393831253052,-1.20828521251678,0.035734344273806,36037,-1202,-7542,-2516,1.01232874393463 +7765,-0.158993691205978,-1.32439279556274,0.037157151848078,36037,-1073,-4531,-2292,1.00862121582031 +7767,-0.140111953020096,-1.46478986740112,0.040190201252699,36037,-856,-3114,-2480,0.996661722660065 +7769,-0.13189497590065,-1.59920144081116,0.041911244392395,36037,64,1604,-2229,0.988641858100891 +7771,-0.103398330509663,-1.73488187789917,0.040779251605272,36037,-2016,861,-2469,0.983944892883301 +7773,-0.069177642464638,-1.85411274433136,0.028694557026029,36037,-2779,5161,-2377,0.972605228424072 +7775,-0.026626808568835,-1.96757102012634,0.027295341715217,36037,-4099,3170,-2558,0.963161528110504 +7777,-0.003071383107454,-2.06739497184753,0.023247389122844,36037,-3069,7839,-2435,0.953935205936432 +7779,-0.060265194624662,-2.07687592506409,0.019335238263011,36037,3527,-2045,-2609,0.99945330619812 +7781,-0.375040262937546,-1.83067572116852,0.031929526478052,36037,27302,-20212,-2342,1.06714701652527 +7783,-0.893876016139984,-1.39028263092041,0.048012908548117,36037,32767,-32767,-2407,1.09580528736115 +7785,-1.36806190013886,-0.955804765224457,0.054686915129423,36037,32767,-32767,-2098,1.120809674263 +7803,0.213193088769913,0.098631694912911,-0.098469659686089,36037,-3961,-26600,-3467,1.07495760917664 +7805,0.24619597196579,-0.033255390822888,-0.085475772619248,36037,-6543,-23661,-3805,1.06139194965363 +7807,0.255804091691971,-0.181671217083931,-0.072055287659168,36037,-4588,-20517,-3302,1.0379239320755 +7809,0.278026014566421,-0.336777150630951,-0.072471663355827,36037,-6401,-17258,-3676,1.02551209926605 +7811,0.303790271282196,-0.460368007421494,-0.079475291073322,36037,-6559,-18423,-3367,1.0307035446167 +7813,0.34182608127594,-0.593216717243195,-0.073429636657238,36037,-8705,-14752,-3707,1.02084147930145 +7815,0.359685212373733,-0.729813933372498,-0.067139483988285,36037,-6949,-13631,-3297,1.01280379295349 +7817,0.369876712560654,-0.8831507563591,-0.062171045690775,36037,-7339,-8512,-3588,1.01058781147003 +7819,0.369095534086227,-1.00705933570862,-0.065790638327599,36037,-5919,-10432,-3300,1.00479066371918 +7821,0.362193703651428,-1.15023803710938,-0.067346423864365,36037,-6161,-4712,-3658,1.00252234935761 +7823,0.328319549560547,-1.28213882446289,-0.067978508770466,36037,-3131,-5656,-3329,0.99165141582489 +7825,0.289668709039688,-1.43630838394165,-0.078798390924931,36037,-2851,32767,-3802,0.984337270259857 +7827,0.243968456983566,-1.57280814647675,-0.093763537704945,36037,-1207,29683,-3522,0.985908150672913 +7829,0.201770797371864,-1.72252416610718,-0.098542928695679,36037,-1270,32767,-4046,0.986512362957001 +7831,0.171456322073936,-1.85849142074585,-0.096401378512383,36037,-1361,32767,-3558,0.987661778926849 +7833,0.142468184232712,-2.00375938415527,-0.093984007835388,36037,-1332,32767,-4004,0.9956756234169 +7835,0.108625575900078,-2.13052082061768,-0.101501405239105,36037,-272,32767,-3611,0.999885380268097 +7837,0.077286295592785,-2.23761129379272,-0.109646692872047,36037,-160,32767,-4200,1.00395739078522 +7839,0.011856083758175,-2.31985068321228,-0.116483338177204,36037,3343,32767,-3734,1.01632475852966 +7841,-0.135149121284485,-2.27683687210083,-0.118894681334496,36037,11593,32767,-4333,1.0562150478363 +7843,-0.410830855369568,-2.04688191413879,-0.11441658437252,36037,24534,14203,-3742,1.09948170185089 +7845,-0.766426980495453,-1.67843472957611,-0.106458634138107,36037,32767,2524,-4229,1.11802244186401 +7847,-1.050128698349,-1.38371813297272,-0.090287178754807,36037,32767,876,-3596,1.09956955909729 +7849,-1.17926371097565,-1.25461041927338,-0.067961774766445,36037,27960,13497,-3817,1.09272301197052 +7851,-1.1429945230484,-1.19790244102478,-0.070270247757435,36037,13607,15892,-3473,1.13008987903595 +7853,-0.949973583221436,-1.00555527210236,-0.102169938385487,36037,1662,5493,-4251,1.16407644748688 +7855,-0.700209319591522,-0.758586049079895,-0.122587166726589,36037,-7590,-3519,-3854,1.13782346248627 +7857,-0.534539997577667,-0.596011698246002,-0.135501474142075,36037,-2779,1394,-4655,1.11138892173767 +7859,-0.463454276323319,-0.552426338195801,-0.147014781832695,36037,2071,8425,-4048,1.09593617916107 +7861,-0.452402085065842,-0.519875645637512,-0.149360448122025,36037,7190,9784,-4844,1.06767630577087 +7863,-0.441186964511871,-0.478903442621231,-0.139001592993736,36037,6261,7857,-4021,1.04483914375305 +7865,-0.427809715270996,-0.445185661315918,-0.130358085036278,36037,6832,8786,-4644,1.02814841270447 +7867,-0.417567104101181,-0.403105765581131,-0.126426562666893,36037,6203,6960,-3960,1.02532982826233 +7869,-0.394052952528,-0.342623829841614,-0.122705280780792,36037,5763,5459,-4573,1.02737987041473 +7871,-0.35678619146347,-0.266430765390396,-0.115968145430088,36037,3591,2780,-3912,1.03398537635803 +7873,-0.31367427110672,-0.196640461683273,-0.107115127146244,36037,3246,2622,-4405,1.04317474365234 +7875,-0.275707095861435,-0.122757278382778,-0.103559590876102,36037,2541,-32767,-3847,1.05149435997009 +7877,-0.236044064164162,-0.062936492264271,-0.104052290320396,36037,2367,-10888,-4375,1.05555546283722 +7879,-0.192742466926575,0.014541471377015,-0.10006757825613,36037,1094,-13325,-3843,1.05675041675568 +7881,-0.12876570224762,0.076752252876759,-0.086151763796806,36037,-1043,-13386,-4161,1.05622696876526 +7883,-0.054000988602638,0.149297341704369,-0.071955047547817,36037,-3077,-14993,-3666,1.04625582695007 +7885,0.030139477923513,0.210655376315117,-0.062764301896095,36037,-5037,-15615,-3886,1.03568363189697 +7887,0.105964049696922,0.258422344923019,-0.05620351806283,36037,-5450,-14933,-3570,1.02333867549896 +7889,0.183390319347382,0.287423968315125,-0.046980243176222,36037,-7077,-14712,-3705,1.01087999343872 +7891,0.25531393289566,0.303776144981384,-0.038890510797501,36037,-7386,-13519,-3459,1.00057172775269 +7893,0.321758478879929,0.331700325012207,-0.03461753949523,36037,-8655,-15552,-3562,0.996505558490753 +7895,0.385863363742828,0.351103931665421,-0.023535830900073,36037,-8838,-14623,-3360,0.991882920265198 +7897,0.439561516046524,0.350429654121399,-0.011047984473407,36037,-9835,-14022,-3288,0.99856436252594 +7899,0.492570966482163,0.331175953149796,-0.00383772328496,36037,-9772,-11785,-3227,1.01334452629089 +7901,0.541944146156311,0.321313232183456,0.000857107632328,36037,-11388,-13098,-3161,1.01869416236877 +7903,0.595456540584564,0.291447877883911,0.012534681707621,36037,-11526,-10659,-3116,1.0192962884903 +7905,0.629493534564972,0.275529861450195,0.024613792076707,36037,-11961,-12106,-2891,1.01884818077087 +7907,0.660056829452515,0.22384762763977,0.031724985688925,36037,-11092,-8309,-2981,1.01316487789154 +7909,0.668967962265015,0.178319811820984,0.036671623587608,36037,-11093,-8562,-2755,1.01085150241852 +7911,0.675310075283051,0.124350108206272,0.0437276288867,36037,-9878,-6855,-2894,1.01188087463379 +7913,0.671815931797028,0.067326083779335,0.050590265542269,36037,-10570,-6054,-2589,1.01185715198517 +7915,0.672221124172211,0.005160039756447,0.056217957288027,36037,-9716,-4646,-2801,1.0188364982605 +7917,0.679309129714966,-0.042768515646458,0.054184760898352,36037,-11765,-4984,-2542,1.01471555233002 +7919,0.686818838119507,-0.075689673423767,0.049598306417465,36037,-10749,-5619,-2840,1.01259636878967 +7921,0.701241552829742,-0.113542683422565,0.045313782989979,36037,-12958,32767,-2642,1.00769078731537 +7923,0.707332968711853,-0.150712341070175,0.042775958776474,36037,-11268,7937,-2881,1.00849103927612 +7925,0.715202629566193,-0.207482352852821,0.044555325061083,36037,-13042,10568,-2645,1.00613975524902 +7927,0.717573940753937,-0.241602018475533,0.044556699693203,36037,-11482,9182,-2863,1.0029491186142 +7929,0.726425766944885,-0.279419720172882,0.041263587772846,36037,-13632,10548,-2674,0.999802708625793 +7931,0.721749722957611,-0.297005832195282,0.033280745148659,36037,-11379,8985,-2935,0.999215364456177 +7933,0.71536773443222,-0.324362337589264,0.026725104078651,36037,-12683,10730,-2840,1.00563728809357 +7935,0.696393668651581,-0.324556320905685,0.022708658128977,36037,-10326,8348,-3005,1.0124808549881 +7951,0.462227404117584,-0.372304916381836,-0.050457417964935,36037,-6081,10015,-3521,0.99057549238205 +7953,0.406593710184097,-0.364535927772522,-0.058656699955464,36037,-5552,9997,-3842,0.988186419010162 +7955,0.357460260391235,-0.364823311567307,-0.063907153904438,36037,-4660,10089,-3625,0.986153066158295 +7957,0.29340797662735,-0.358759850263596,-0.066801026463509,36037,-3279,10267,-3949,0.983887851238251 +7959,0.220959663391113,-0.344593673944473,-0.068819038569927,36037,-1180,8999,-3671,0.979752480983734 +7961,0.153686285018921,-0.326287239789963,-0.0712029337883,36037,-894,9088,-4016,0.976137340068817 +7963,0.083805099129677,-0.288989305496216,-0.070148065686226,36037,520,6765,-3693,0.97923070192337 +7965,0.014146922156215,-0.255784630775452,-0.068296127021313,36037,1490,7083,-4001,0.985791206359863 +7967,-0.050436485558748,-0.210485845804214,-0.065786510705948,36037,2046,5255,-3676,0.98679906129837 +7969,-0.111880883574486,-0.155224114656448,-0.066250577569008,36037,2973,4046,-4005,0.98660409450531 +7971,-0.166835650801659,-0.083734177052975,-0.06827312707901,36037,3068,1705,-3707,0.981054842472076 +7973,-0.214590296149254,-0.007822060026228,-0.069296889007092,36037,3729,291,-4070,0.979106307029724 +7975,-0.261461466550827,0.066375829279423,-0.070106491446495,36037,3936,-563,-3734,0.98562079668045 +7977,-0.301770001649857,0.143464520573616,-0.064242511987686,36037,4705,-2214,-4033,0.992893218994141 +7979,-0.346482783555984,0.215260446071625,-0.055555086582899,36037,5129,-2520,-3647,1.00417196750641 +7981,-0.386337906122208,0.271129876375198,-0.045374318957329,36037,6188,-2793,-3832,1.01062333583832 +7983,-0.432416290044785,0.331893265247345,-0.038153551518917,36037,6627,-3457,-3538,1.00796687602997 +7985,-0.470173090696335,0.378965795040131,-0.034090768545866,36037,7595,-3986,-3717,0.998156666755676 +7987,-0.507897794246674,0.441455036401749,-0.027390956878662,36037,7321,-5255,-3473,0.986525893211365 +7989,-0.539222955703735,0.496336162090302,-0.022180000320077,36037,8472,-6586,-3586,0.983902752399445 +7991,-0.562366366386414,0.54872739315033,-0.023665692657232,36037,7298,-6230,-3455,0.992180049419403 +7993,-0.583741009235382,0.595170319080353,-0.023877503350377,36037,8730,-7777,-3612,1.00105428695679 +7995,-0.608935654163361,0.632482469081879,-0.02212661318481,36037,8376,-6559,-3452,1.00881385803223 +7997,-0.633287727832794,0.683998823165894,-0.021935625001788,36037,10030,-9796,-3595,1.00750160217285 +7999,-0.647041857242584,0.721507668495178,-0.026618324220181,36037,8392,-8098,-3490,0.998287796974182 +8001,-0.666639685630798,0.779649972915649,-0.033396892249584,36037,10530,-12087,-3731,0.995034158229828 +8003,-0.677079617977142,0.82362425327301,-0.036797653883696,36037,8892,-10320,-3569,0.996082246303558 +8005,-0.678449213504791,0.84932267665863,-0.042173750698567,36037,9719,-11216,-3832,0.999433934688568 +8007,-0.680016994476318,0.875379323959351,-0.048637390136719,36037,8611,-10109,-3660,1.01007890701294 +8009,-0.676076471805573,0.891830563545227,-0.05297976359725,36037,9611,-11584,-3958,1.01160633563995 +8011,-0.667687952518463,0.901969313621521,-0.053890861570835,36037,8035,-9703,-3707,1.00674819946289 +8013,-0.655084311962128,0.909950137138367,-0.055067948997021,36037,8953,-11625,-3981,1.00575578212738 +8015,-0.641059637069702,0.91792356967926,-0.059708941727877,36037,7554,-10139,-3759,1.00784754753113 +8017,-0.606307029724121,0.913298189640045,-0.064266368746758,36037,6869,-11137,-4089,1.01991021633148 +8019,-0.566053092479706,0.918994307518005,-0.068710245192051,36037,4884,-10358,-3833,1.02758193016052 +8021,-0.531223654747009,0.911986887454987,-0.063087478280068,36037,5918,-11308,-4078,1.03298890590668 +8023,-0.493347823619843,0.903288304805756,-0.058835037052631,36037,4263,-9470,-3777,1.0291782617569 +8025,-0.445280522108078,0.890518009662628,-0.062850967049599,36037,3794,-10904,-4077,1.02789092063904 +8027,-0.390502005815506,0.879648506641388,-0.069555833935738,36037,1789,-9336,-3862,1.01707577705383 +8029,-0.34610041975975,0.872591376304626,-0.06576618552208,36037,2628,-11377,-4116,1.01772737503052 +8031,-0.308376997709274,0.848115384578705,-0.060327045619488,36037,1999,-8263,-3811,1.01522970199585 +8033,-0.263016670942307,0.831554114818573,-0.059668529778719,36037,1359,-10382,-4053,1.01231443881989 +8035,-0.214035958051682,0.805867791175842,-0.057982411235571,36037,-31,-7909,-3805,1.008913397789 +8037,-0.176165252923965,0.791471600532532,-0.056599535048008,36037,588,-10213,-4025,1.00396871566772 +8039,-0.137368500232697,0.760771453380585,-0.051426786929369,36037,-312,-7225,-3770,0.999056100845337 +8041,-0.102975033223629,0.728005409240723,-0.047525711357594,36037,-293,-8174,-3928,0.990201056003571 +8043,-0.05916341394186,0.682314097881317,-0.046903040260077,36037,-1741,-5321,-3748,0.989505767822266 +8045,-0.019997881725431,0.656089842319489,-0.047599751502276,36037,-1943,-7749,-3942,0.992367446422577 +8047,0.026919377967715,0.615669310092926,-0.047397825866938,36037,-3183,-5006,-3760,0.997727632522583 +8049,0.067539989948273,0.581116676330566,-0.052509639412165,36037,-3467,-6179,-4016,0.99955153465271 +8051,0.112053483724594,0.537400484085083,-0.053846895694733,36037,-4256,-3877,-3814,1.00463736057282 +8053,0.160361081361771,0.497310936450958,-0.052004866302013,36037,-5571,-4620,-4027,1.00778722763062 +8055,0.204624429345131,0.45304062962532,-0.049694426357746,36037,-5633,-2818,-3795,1.00760841369629 +8057,0.246910497546196,0.411910980939865,-0.048162057995796,36037,-6629,-3320,-3999,0.99609512090683 +8059,0.293908625841141,0.391538172960281,-0.044694617390633,36037,-7217,-3800,-3771,0.993513762950897 +8061,0.345317602157593,0.36966735124588,-0.042388327419758,36037,-9004,-4159,-3946,0.991763532161713 +8063,0.393326371908188,0.340716958045959,-0.04118375480175,36037,-8868,-2591,-3755,0.992336571216583 +8065,0.445333302021027,0.302230298519134,-0.042954526841641,36037,-10847,-2002,-3968,0.982445955276489 +8067,0.487802416086197,0.275563091039658,-0.045299481600523,36037,-10026,-1925,-3793,0.975381553173065 +8069,0.525720417499542,0.238617196679115,-0.047637321054936,36037,-11370,-1175,-4037,0.972757577896118 +8071,0.556465327739716,0.215651974081993,-0.048110172152519,36037,-10412,-1409,-3822,0.964972078800201 +8073,0.589684128761292,0.178801670670509,-0.043465785682201,36037,-12308,-277,-4004,0.958124101161957 +8075,0.614098370075226,0.161038026213646,-0.039037376642227,36037,-11053,-1049,-3769,0.958664357662201 +8077,0.63752692937851,0.119489312171936,-0.034310400485993,36037,-12659,976,-3909,0.963606894016266 +8079,0.658151268959045,0.094809107482433,-0.029292246326804,36037,-11705,369,-3711,0.962288320064545 +8081,0.691772878170013,0.059475272893906,-0.024030046537519,36037,-14583,1500,-3796,0.957899272441864 +8083,0.701093375682831,0.024399926885963,-0.021822050213814,36037,-11830,2127,-3666,0.953753769397736 +8085,0.699626564979553,-0.006391135510057,-0.019465878605843,36037,-12528,2272,-3747,0.954698503017426 +8087,0.688778340816498,-0.027621639892459,-0.020711367949844,36037,-10536,1916,-3664,0.952853977680206 +8089,0.679343223571777,-0.042373705655336,-0.022988772019744,36037,-11937,1746,-3795,0.956925988197327 +8091,0.67354816198349,-0.059218194335699,-0.02907813154161,36037,-10997,2106,-3728,0.951201677322388 +8093,0.665109217166901,-0.072507172822952,-0.039566475898028,36037,-12097,2189,-3996,0.947095096111298 +8095,0.653487682342529,-0.077071227133274,-0.046500477939844,36037,-10606,1548,-3856,0.941434681415558 +8097,0.636811852455139,-0.081050395965576,-0.050285022705793,36037,-11359,1736,-4130,0.943555355072022 +8099,0.623781561851501,-0.101855233311653,-0.053826056420803,36037,-10382,3137,-3918,0.940737068653107 +8101,0.604470074176788,-0.107043355703354,-0.059795867651701,36037,-10935,2312,-4252,0.9322629570961 +8103,0.588290393352508,-0.119019724428654,-0.062108922749758,36037,-9937,2833,-3987,0.926506757736206 +8105,0.542650938034058,-0.104869499802589,-0.063101187348366,36037,-8314,965,-4303,0.9237020611763 +8107,0.493973881006241,-0.090030789375305,-0.064733684062958,36037,-6518,575,-4018,0.927760899066925 +8109,0.436397671699524,-0.072001479566097,-0.064193949103355,36037,-5964,221,-4332,0.925478339195251 +8111,0.374411851167679,-0.059316258877516,-0.06105525046587,36037,-4061,352,-4006,0.924458146095276 +8113,0.311454236507416,-0.042252976447344,-0.059321135282517,36037,-3731,-132,-4290,0.923603296279907 +8115,0.249881699681282,-0.015455360524356,-0.056982487440109,36037,-2460,-1236,-3990,0.924594581127167 +8117,0.185967639088631,0.010534608736634,-0.05339951813221,36037,-1754,-1594,-4237,0.930498659610748 +8119,0.121113151311874,0.046281084418297,-0.049239080399275,36037,-476,-2738,-3949,0.93385773897171 +8121,0.060129441320896,0.065746203064919,-0.046944864094257,36216,11,-2012,-4178,0.937966048717499 +8123,0.00431478349492,0.076610498130322,-0.047928191721439,36216,510,-1391,-3951,0.937300145626068 +8125,-0.049531128257513,0.098705403506756,-0.046383529901505,36216,1269,-2731,-4186,0.939748167991638 +8127,-0.101380594074726,0.106039613485336,-0.046053495258093,36216,1753,-1574,-3949,0.937303781509399 +8129,-0.155736282467842,0.12421315908432,-0.044059198349714,36216,3058,-2881,-4171,0.936447441577911 +8131,-0.209013387560844,0.136253625154495,-0.042440868914127,36216,3458,-2370,-3934,0.933016300201416 +8133,-0.260816484689712,0.155695199966431,-0.042165830731392,36216,4655,-3519,-4160,0.932681679725647 +8135,-0.296834826469421,0.153642401099205,-0.042855475097895,36216,3588,-1650,-3947,0.932624220848084 +8137,-0.34408038854599,0.152207851409912,-0.048217654228211,36216,5821,-1993,-4242,0.934215128421783 +8139,-0.386861234903336,0.152049988508225,-0.051658313721418,36216,5512,-1800,-4019,0.935489177703857 +8141,-0.424130260944366,0.147630468010902,-0.051493763923645,36216,6574,-1733,-4291,0.932392299175262 +8143,-0.460565507411957,0.155830413103104,-0.051999125629664,36216,6301,-2488,-4033,0.934441387653351 +8145,-0.49200314283371,0.152982011437416,-0.05300584435463,36216,7450,-1966,-4318,0.935908675193787 +8147,-0.521596431732178,0.148536041378975,-0.054202727973461,36216,6904,-1514,-4060,0.937033653259277 +8149,-0.543320298194885,0.131625473499298,-0.05085388943553,36216,7812,-647,-4301,0.93863832950592 +8151,-0.57805585861206,0.132453292608261,-0.050453633069992,36216,8325,-1689,-4046,0.940445780754089 +8153,-0.604378640651703,0.120080754160881,-0.047349862754345,36216,9382,-816,-4268,0.944100022315979 +8155,-0.633435726165772,0.111226037144661,-0.043076682835817,36216,8983,-715,-4006,0.943666160106659 +8157,-0.64533531665802,0.088637866079807,-0.038475878536701,36216,9294,402,-4171,0.940119326114654 +8159,-0.663584113121033,0.075252816081047,-0.041742973029614,36216,8933,114,-4006,0.933891355991364 +8161,-0.67319643497467,0.067285098135471,-0.048808343708515,36216,9882,-311,-4301,0.93052589893341 +8163,-0.673327744007111,0.067125864326954,-0.051903318613768,36216,8082,-718,-4087,0.924725592136383 +8165,-0.673411011695862,0.077446639537811,-0.050737723708153,36216,32767,-32767,-4334,0.936394453048706 +8167,-0.663192093372345,0.082329779863358,-0.04734093695879,36216,32767,-6878,-4067,0.953263640403748 +8169,-0.650296926498413,0.102341026067734,-0.046524401754141,36216,32767,-8504,-4293,0.963261544704437 +8171,-0.623742818832397,0.110551275312901,-0.045775145292282,36216,32767,-7595,-4067,0.969000458717346 +8173,-0.600571155548096,0.132311180233955,-0.047664050012827,36216,32767,-9188,-4315,0.971212983131409 +8175,-0.560013294219971,0.128943458199501,-0.048929903656244,36216,32767,-7116,-4099,0.973978340625763 +8177,-0.519904315471649,0.140806525945663,-0.051977079361677,36216,32767,-8713,-4375,0.977758288383484 +8179,-0.460481524467468,0.136080175638199,-0.050372377038002,36216,32767,-7214,-4120,0.982671737670898 +8181,-0.397019416093826,0.140387415885925,-0.047927867621183,36216,32767,-8263,-4336,0.987054407596588 +8183,-0.321960747241974,0.124859012663364,-0.046810571104288,36216,30621,-6373,-4106,0.987722516059876 +8185,-0.24442221224308,0.116022445261478,-0.047169134020805,36216,29974,-7015,-4337,0.98101806640625 +8187,-0.149288758635521,0.117103017866611,-0.047727942466736,36216,27121,-7535,-4123,0.982815682888031 +8189,-0.038371160626412,0.104931175708771,-0.046776656061411,36216,24602,-6681,-4342,0.979426443576813 +8191,0.082030422985554,0.079461485147476,-0.040075369179249,36216,22312,-5172,-4081,0.976987361907959 +8193,0.206491842865944,0.064285039901733,-0.04244289919734,36216,19931,-5865,-4304,0.96803343296051 +8195,0.34349650144577,0.054536253213883,-0.049276739358902,36216,17580,-5999,-4154,0.974205851554871 +8197,0.49710738658905,0.041513051837683,-0.047633372247219,36216,13268,-5705,-4377,0.980652749538422 +8199,0.65832382440567,0.02162884734571,-0.045625362545252,36216,11403,-4850,-4139,0.994938373565674 +8201,0.839187800884247,0.010043879970908,-0.044810947030783,36216,5764,-5339,-4356,1.00916743278503 +8203,1.01323449611664,0.009531771764159,-0.041071735322476,36216,5308,-6099,-4118,1.0171594619751 +8205,1.1810290813446,0.000712660781574,-0.03680320084095,36216,983,-5414,-4272,1.02398788928986 +8207,1.35722029209137,-0.01076587010175,-0.034989044070244,36216,-25,-5052,-4085,1.02685821056366 +8209,1.54303562641144,-0.027916114777327,-0.034178636968136,36216,-6523,-4365,-4248,1.02121019363403 +8211,1.7257936000824,-0.029169352725148,-0.028465436771512,36216,-6201,-5536,-4049,1.02194809913635 +8213,1.90299546718597,-0.035978373140097,-0.021261658519507,36216,-12247,-4988,-4103,1.0252879858017 +8215,2.09242558479309,-0.040387399494648,-0.013259891420603,36216,-32767,4395,-3950,1.03806138038635 +8217,2.28686356544495,-0.035063073039055,-0.001206193817779,36216,-26476,-4278,-3871,1.0319596529007 +8219,2.47763538360596,-0.031760759651661,0.013877501711249,36216,-25042,-4227,-3767,1.03414463996887 +8221,2.65761160850525,-0.02671255543828,0.022553807124496,36216,-32373,-4398,-3593,1.03395116329193 +8223,2.82180094718933,-0.034349545836449,0.023141933605075,36216,-29084,-3408,-3702,1.03072237968445 +8225,2.96507501602173,-0.028057748451829,0.01469362154603,36216,-32767,-4470,-3684,1.02703177928925 +8227,3.10242605209351,-0.016436664387584,0.012437569908798,36216,-32346,-5046,-3775,1.02364838123322 +8229,3.21811008453369,-0.010045036673546,0.014202864840627,36216,-32767,-4767,-3696,1.01410520076752 +8231,3.31462931632996,-0.002093837363645,0.017033571377397,36216,-32767,-4998,-3744,1.0044013261795 +8233,3.40608048439026,-0.002627271926031,0.017869850620627,36216,-32767,-4399,-3656,0.992791593074799 +8235,3.49087238311768,0.001599215785973,0.019616803154349,36216,-32767,-4796,-3726,0.990585744380951 +8237,3.55880236625671,0.004248734097928,0.019458638504148,36216,-32767,-4766,-3640,0.987147033214569 +8239,3.60818290710449,0.004244883544743,0.016943451017141,36216,-32767,-4548,-3744,0.986377358436584 +8241,3.65558457374573,0.002041389700025,0.019413391128183,36216,-32767,-4395,-3641,0.978299200534821 +8243,3.68541550636291,0.013202362693846,0.023627767339349,36216,-32767,-5492,-3698,0.969237327575684 +8245,3.70129132270813,0.015450158156455,0.026476221159101,36216,-32767,-4945,-3567,0.964586675167084 +8261,3.32445240020752,0.100950993597507,0.020483486354351,36216,-32767,-7963,-3719,0.963667333126068 +8263,3.22856736183166,0.103604145348072,0.022667037323117,36216,-32767,17061,-3709,0.96190071105957 +8265,3.11665296554565,0.108900554478168,0.019641691818833,36216,-32767,-2952,-3746,0.956256747245789 +8267,2.9989230632782,0.114183597266674,0.015487115830183,36216,-32767,-2806,-3762,0.953457653522491 +8269,2.87188029289246,0.113545723259449,0.012540246360004,36216,-32767,-2626,-3844,0.954426407814026 +8271,2.73380780220032,0.124896720051765,0.005372093990445,36216,-29143,-3424,-3836,0.943949103355408 +8273,2.57554841041565,0.1264768242836,-0.002889862051234,36216,-30717,-3024,-4050,0.943038284778595 +8275,2.39542865753174,0.133781939744949,-0.010335373692215,36216,-22419,-3297,-3952,0.945169568061829 +8277,2.19159078598022,0.11451119184494,-0.015021960251033,36216,-22266,-1363,-4194,0.951284527778626 +8279,1.9684339761734,0.102974683046341,-0.012395522557199,36216,-14181,-1535,-3976,0.957024395465851 +8281,1.74598252773285,0.090604051947594,-0.015463729389012,36216,-14553,-1486,-4189,0.95165491104126 +8283,1.5154025554657,0.08549614995718,-0.019119089469314,36216,-7919,-1762,-4031,0.95048063993454 +8285,1.27701938152313,0.071094855666161,-0.015979867428541,36216,-6446,-1031,-4186,0.937251329421997 +8287,1.03686153888702,0.054132521152496,-0.016999162733555,36216,-923,-470,-4025,0.922250390052795 +8289,0.80208557844162,0.054024320095778,-0.015473307110369,36216,563,-1779,-4171,0.921854376792908 +8291,0.553067564964294,0.053734075278044,-0.016593459993601,36216,6314,-1658,-4030,0.9144167304039 +8293,0.316733330488205,0.04855377972126,-0.017047865316272,36216,8339,-1321,-4192,0.901344180107117 +8295,0.076992869377136,0.039796318858862,-0.01404745131731,36216,12365,-847,-4021,0.901725172996521 +8297,-0.149989411234856,0.016058823093772,-0.011233338154852,36216,15232,534,-4094,0.907908797264099 +8299,-0.36382931470871,-0.007451522629708,-0.013377141207457,36216,16934,903,-4022,0.90702748298645 +8301,-0.580774426460266,-0.006724116858095,-0.015276772901416,36216,21701,-828,-4121,0.908268332481384 +8303,-0.793861091136932,-0.007161256857216,-0.014896157197654,36216,23348,-726,-4038,0.911738872528076 +8305,-0.99171632528305,-0.015432827174664,-0.014140627346933,36216,27403,-9,-4104,0.914821267127991 +8307,-1.18127810955048,-0.009442905895412,-0.012098676525056,36216,27712,-1122,-4024,0.927952885627747 +8309,-1.35189485549927,-0.015441183000803,-0.011268497444689,36216,31870,-139,-4076,0.931913137435913 +8311,-1.51267671585083,-0.014672735705972,-0.016182251274586,36216,31066,-642,-4057,0.929028868675232 +8313,-1.66842126846313,-0.010927312076092,-0.017363224178553,36216,610,-876,-4156,0.930493712425232 +8315,-1.80883252620697,-0.004447603132576,-0.015922233462334,36216,28575,-1167,-4061,0.931095540523529 +8317,-1.91169142723084,0.009279414080083,-0.017115654423833,36216,31574,-1895,-4179,0.93854683637619 +8319,-1.98824810981751,0.020653150975704,-0.018817633390427,36216,27442,-1857,-4087,0.947999000549316 +8321,-2.05123901367187,0.032476086169481,-0.022656258195639,36216,31878,-2130,-4272,0.952583909034729 +8323,-2.11138367652893,0.041460666805506,-0.023905549198389,36216,28969,-1976,-4130,0.963546752929688 +8325,-2.17056179046631,0.052904412150383,-0.022706530988216,36216,32767,-2432,-4297,0.970757365226746 +8327,-2.2203574180603,0.054625950753689,-0.020141368731856,36216,30788,-1646,-4113,0.972429990768433 +8329,-2.26690936088562,0.074711807072163,-0.018477605655789,36216,32767,-3405,-4272,0.978554725646973 +8331,-2.2972469329834,0.090598121285439,-0.020977107807994,36216,31544,-3187,-4127,0.978860318660736 +8333,-2.31391644477844,0.101858548820019,-0.025393573567271,36216,32767,-3226,-4381,0.981105148792267 +8335,-2.3110466003418,0.105936765670776,-0.022378088906407,36216,30439,-2584,-4147,0.988864719867706 +8337,-2.29749202728271,0.114925235509872,-0.021568248048425,36216,32767,-3301,-4351,0.987399935722351 +8339,-2.27367472648621,0.130901038646698,-0.025721011683345,36216,29477,-3824,-4180,0.991918563842773 +8341,-2.22570991516113,0.146248131990433,-0.024991048499942,36216,31902,-4300,-4418,0.988993227481842 +8343,-2.17259931564331,0.173227518796921,-0.01864330098033,36216,26975,-5263,-4142,0.996650338172913 +8345,-2.10636568069458,0.184715762734413,-0.011349305510521,36216,29667,-4709,-4287,1.00624525547028 +8347,-2.0318717956543,0.21057952940464,-0.00868961121887,36216,24421,-5783,-4083,1.01511859893799 +8349,-1.94588160514832,0.224394202232361,-0.000166044846992,36216,26603,-5598,-4182,1.01640260219574 +8351,-1.85113120079041,0.24951483309269,0.005767112132162,36216,21305,-6372,-3992,1.02402257919312 +8353,-1.73572218418121,0.261058121919632,0.006534139625728,36216,21954,-6119,-4124,1.03282821178436 +8355,-1.62564718723297,0.296266376972198,0.008002328686416,36216,17807,-7866,-3984,1.03326523303986 +8357,-1.50655293464661,0.321918249130249,0.011660403572023,36216,18744,-8221,-4097,1.03917121887207 +8359,-1.39336133003235,0.352812826633453,0.015347052365542,36216,14985,-8496,-3941,1.04596996307373 +8361,-1.26333463191986,0.374225348234177,0.019990146160126,36216,14703,-8910,-4027,1.05233716964722 +8363,-1.13086879253387,0.405008494853973,0.019319411367178,36216,-25593,-9390,-3920,1.05734586715698 +8365,-0.842623114585876,0.472503006458283,0.013103283010423,36466,230,-11620,-3970,1.05835592746735 +8367,-0.696901023387909,0.491622507572174,0.009087836369872,36466,-795,-11005,-4214,1.0606175661087 +8369,-0.561182737350464,0.516897082328796,0.012565356679261,36466,-3251,-10990,-3984,1.05508279800415 +8371,-0.421335697174072,0.526895701885223,0.020143581554294,36466,-4605,-11139,-4104,1.05598258972168 +8373,-0.421335697174072,0.526895701885223,0.020143581554294,36466,-4605,-11139,-4104,1.05598258972168 +8375,-0.157632499933243,0.574939906597137,0.028737310320139,36466,-8224,-12677,-4032,1.06766617298126 +8377,-0.040368385612965,0.59133368730545,0.029580365866423,36466,-9156,-11899,-3883,1.06557047367096 +8379,0.072869330644608,0.595662891864777,0.029984621331096,36466,-10594,-12351,-4034,1.06153988838196 +8381,0.179518714547157,0.597811877727508,0.030129773542285,36466,-11594,-11234,-3887,1.04773986339569 +8383,0.179518714547157,0.597811877727508,0.030129773542285,36466,-11594,-11234,-3887,1.04773986339569 +8385,0.364672243595123,0.598889768123627,0.03248916938901,36466,-12640,-12068,-3878,1.02890336513519 +8387,0.453994035720825,0.589160740375519,0.03542971983552,36466,-15336,-11758,-3987,1.02523338794708 +8389,0.527195930480957,0.581449866294861,0.037905566394329,36466,-14546,-10818,-3848,1.02114880084991 +8391,0.59081220626831,0.564157783985138,0.04484498873353,36466,-15971,-11069,-3875,1.0148766040802 +8393,0.59081220626831,0.564157783985138,0.04484498873353,36466,-15971,-11069,-3875,1.0148766040802 +8411,0.891763091087341,0.389714330434799,0.082258395850659,36895,-24871,-8971,-3375,1.00072705745697 +8413,0.89008629322052,0.36600050330162,0.082061819732189,36895,-22789,-7928,-3546,0.996689140796661 +8415,0.867320001125336,0.354128926992416,0.0831218957901,36895,-22748,-9351,-3346,0.996524810791016 +8417,0.841667711734772,0.332219988107681,0.083248466253281,36895,-20861,-7738,-3534,0.990631401538849 +8419,0.802594363689423,0.322459429502487,0.083306550979614,36895,-20987,-9144,-3325,0.989936113357544 +8421,0.752380847930908,0.303768396377563,0.081470273435116,36895,-18274,-7711,-3541,0.988858997821808 +8423,0.691967606544495,0.29097118973732,0.077355422079563,36895,-18089,-8562,-3375,0.99351292848587 +8425,0.623697817325592,0.266739815473557,0.074060134589672,36895,-15540,-6922,-3588,0.993361175060272 +8427,0.538399219512939,0.252685546875,0.071252539753914,36895,-14183,-7975,-3421,0.990880906581879 +8429,0.449370384216309,0.231520354747772,0.068039134144783,36895,-11887,-6757,-3626,0.986807823181152 +8431,0.356781423091888,0.216820105910301,0.064962059259415,36895,-11017,-7461,-3470,0.979965448379517 +8433,0.262552589178085,0.189048483967781,0.060554582625628,36895,-9090,-5779,-3674,0.981000781059265 +8435,0.163577243685722,0.177977055311203,0.056664470583201,36895,-7637,-7195,-3540,0.977063179016113 +8437,0.06976829469204,0.152809500694275,0.056408531963825,36895,-6521,-5535,-3700,0.974822103977203 +8439,-0.021043738350272,0.124469593167305,0.052629366517067,36895,-5344,-5176,-3549,0.969301640987396 +8441,-0.119423635303974,0.082039728760719,0.044817343354225,36895,-3561,-3350,-3776,0.975096583366394 +8443,-0.230029329657555,0.043015003204346,0.034736696630716,36895,-570,-3131,-3703,0.980241775512695 +8445,-0.342647343873978,0.021282410249114,0.031690526753664,36895,675,-3989,-3864,0.985744297504425 +8447,-0.457474112510681,-0.011018434539437,0.032946351915598,36895,3492,-2745,-3686,0.989133596420288 +8449,-0.568477809429169,-0.045753423124552,0.030830563977361,36895,3920,-2099,-3867,0.989469349384308 +8451,-0.67326283454895,-0.100436218082905,0.025432001799345,36895,6451,332,-3715,0.989657402038574 +8453,-0.776781558990479,-0.129581972956657,0.019131882116199,36895,6596,-1257,-3944,0.987390637397766 +8455,-0.865984737873077,-0.167494371533394,0.015142339281738,36895,8731,267,-3792,0.985726594924927 +8457,-0.962710082530975,-0.20060870051384,0.01301528327167,36895,9091,115,-3983,0.985124886035919 +8459,-1.05790209770203,-0.228218212723732,0.015926957130432,37253,12646,589,-3747,0.985639274120331 +8461,-1.16569745540619,-0.235597804188728,0.018460243940353,37253,13204,-1130,-3941,0.986106157302856 +8463,-1.26433753967285,-0.242328122258186,0.01297217886895,37253,16693,-576,-3774,0.989125490188599 +8465,-1.34238088130951,-0.26610192656517,0.012022498995066,37253,14112,586,-3981,0.98825615644455 +8467,-1.39684092998505,-0.270043730735779,0.016381220892072,37253,16203,-212,-3722,0.993022441864014 +8469,-1.44303631782532,-0.27386286854744,0.019881220534444,37253,13843,-613,-3922,0.996737658977508 +8471,-1.48755598068237,-0.27101144194603,0.022931007668376,37253,17557,-558,-3647,0.99938839673996 +8473,-1.52202498912811,-0.27337110042572,0.029245520010591,37253,14751,-605,-3852,0.996774911880493 +8475,-1.54889822006226,-0.259472101926804,0.02914334461093,37253,17915,-1418,-3581,0.998163163661957 +8477,-1.56269407272339,-0.254746109247208,0.033536788076162,37253,14500,-1263,-3816,1.00213158130646 +8479,-1.58726894855499,-0.240549683570862,0.040851101279259,37253,19026,-1635,-3454,1.00943112373352 +8481,-1.60543072223663,-0.238216057419777,0.042954504489899,37253,16095,-1221,-3743,1.0187087059021 +8483,-1.62370789051056,-0.232845619320869,0.037669114768505,37253,19840,-1017,-3494,1.01870810985565 +8485,-1.63213133811951,-0.226792961359024,0.032637283205986,37253,16471,-1545,-3807,1.02157771587372 +8487,-1.63015782833099,-0.222252354025841,0.030778553336859,37253,19179,-1027,-3581,1.01851856708527 +8489,-1.61985397338867,-0.214615374803543,0.034771982580423,37253,15650,-1732,-3787,1.02426528930664 +8491,-1.60310840606689,-0.211064174771309,0.041725754737854,37253,18364,-1046,-3457,1.02946448326111 +8493,-1.58124446868896,-0.207037061452866,0.04984050244093,37253,14956,-1487,-3676,1.04368317127228 +8495,-1.54003131389618,-0.22332264482975,0.061256118118763,37253,16255,669,-3221,1.04445064067841 +8497,-1.49299824237824,-0.224381700158119,0.06092519313097,37253,12550,-772,-3590,1.04877638816834 +8499,-1.43658423423767,-0.227527052164078,0.057949475944042,37253,14106,-94,-3255,1.04752111434937 +8501,-1.38012516498566,-0.215127259492874,0.053809341043234,37253,10871,-1763,-3629,1.04266822338104 +8503,-1.31338751316071,-0.204512923955917,0.052618786692619,37253,11946,-1352,-3321,1.04276514053345 +8505,-1.25540769100189,-0.171638205647469,0.056298106908798,37253,9535,-3759,-3604,1.04149496555328 +8507,-1.18650722503662,-0.1428602039814,0.05420296266675,37610,10268,-3576,-3315,1.04531466960907 +8509,-1.11365270614624,-0.084595642983914,0.053804587572813,37610,6944,-6760,-3614,1.05198884010315 +8511,-1.0310742855072,-0.046065982431173,0.057152472436428,37610,7244,-5791,-3297,1.05162966251373 +8513,-0.958045780658722,0.007177315186709,0.05713614076376,37610,5140,-7693,-3583,1.05127835273743 +8515,-0.880029618740082,0.046597488224506,0.060080118477345,37610,5532,-7356,-3275,1.0509729385376 +8517,-0.802883565425873,0.094814337790012,0.056320521980524,37610,2994,-8609,-3582,1.05678069591522 +8519,-0.715581476688385,0.12633803486824,0.050744220614433,37610,2536,-8122,-3393,1.06824016571045 +8521,-0.635575354099274,0.151579141616821,0.046750813722611,37610,691,-7832,-3642,1.06976127624512 +8523,-0.544114708900452,0.159151896834374,0.047129843384028,37610,-281,-7002,-3435,1.07337808609009 +8525,-0.455023139715195,0.170202866196632,0.050333369523287,37610,-2324,-7154,-3613,1.0697420835495 +8527,-0.363358199596405,0.174167856574059,0.054691303521395,37610,-3047,-7058,-3342,1.06397533416748 +8529,-0.272532105445862,0.198670670390129,0.051338020712137,37610,-4923,-8603,-3601,1.06033945083618 +8531,-0.16919818520546,0.218902140855789,0.052200667560101,37610,-6937,-9034,-3373,1.05548441410065 +8533,-0.068366758525372,0.242837756872177,0.059045497328043,37610,-8515,-9295,-3543,1.0506317615509 +8535,0.023869538679719,0.258346706628799,0.070987485349178,37610,-9276,-9450,-3151,1.05292224884033 +8537,0.108599670231342,0.269472628831863,0.080468624830246,37610,-9936,-8877,-3387,1.04750335216522 +8539,0.179965570569038,0.289210796356201,0.085804589092732,37610,-10392,-10385,-2973,1.0406528711319 +8541,0.237426921725273,0.300059109926224,0.088933236896992,37610,-9940,-9430,-3319,1.02529180049896 +8543,0.282792031764984,0.308767765760422,0.092805653810501,37610,-10331,-10047,-2884,1.02051627635956 +8563,0.434867739677429,0.27840393781662,0.110262624919415,38146,-8930,-8373,-2614,1.01164948940277 +8565,0.413797587156296,0.234364703297615,0.106168821454048,38146,-8178,-5416,-3117,1.01124441623688 +8567,0.373564720153809,0.209599182009697,0.098862528800964,38146,-7001,-6866,-2722,1.01412928104401 +8569,0.337238073348999,0.169065654277801,0.094281367957592,38146,-6188,-4830,-3186,1.0196236371994 +8571,0.289188027381897,0.134466886520386,0.086534313857555,38146,-5260,-5028,-2840,1.02187883853912 +8573,0.242980360984802,0.094463177025318,0.080875255167484,38146,-4292,-3865,-3267,1.02078318595886 +8575,0.197102338075638,0.070531859993935,0.073327571153641,38146,-4071,-4816,-2971,1.02191483974457 +8577,0.155114486813545,0.058013416826725,0.064865231513977,38146,-3458,-5350,-3367,1.02325594425201 +8579,0.117758318781853,0.042892538011074,0.058402623981237,38146,-3507,-5035,-3132,1.02534055709839 +8581,0.074237436056137,0.027744790539146,0.057609528303146,38146,-2277,-4755,-3410,1.03030467033386 +8583,0.022406328469515,0.008033755235374,0.058511015027762,38146,-988,-4159,-3115,1.02664577960968 +8585,-0.02697772718966,0.001740721287206,0.058348570019007,38146,-450,-5028,-3397,1.0295113325119 +8587,-0.064307868480682,-0.027246790006757,0.058135103434324,38146,-632,-2921,-3104,1.02653563022614 +8589,-0.101039916276932,-0.047697160393,0.052413072437048,38146,-297,-3300,-3430,1.02599120140076 +8591,-0.128451943397522,-0.100022464990616,0.046182096004486,38146,-301,-47,-3221,1.02758073806763 +8593,-0.149992749094963,-0.143223598599434,0.038695987313986,38146,-658,-261,-3518,1.02400767803192 +8595,-0.17154435813427,-0.178144499659538,0.028873136267066,38146,27,35,-3402,1.02198433876038 +8597,-0.206626698374748,-0.198994219303131,0.016791800037026,38146,1171,-985,-3665,1.02025890350342 +8599,-0.231780424714088,-0.228028550744057,0.012399255298078,38146,1335,524,-3583,1.02379357814789 +8601,-0.250772684812546,-0.256762892007828,0.012800772674382,38146,729,510,-3691,1.02567839622498 +8603,-0.2760349214077,-0.274449527263641,0.015747433528304,38146,2138,577,-3533,1.03618562221527 +8605,-0.305247008800507,-0.30184206366539,0.016087437048555,38146,2339,1185,-3666,1.04178714752197 +8607,-0.336877644062042,-0.315711289644241,0.017736967653036,38504,3688,1102,-3500,1.04683554172516 +8609,-0.366805702447891,-0.318159341812134,0.020998923107982,38504,3399,-224,-3629,1.04486918449402 +8611,-0.398837059736252,-0.302402824163437,0.020317746326327,38504,4854,-1102,-3472,1.04131472110748 +8613,-0.425517678260803,-0.28637507557869,0.020974051207304,38504,4162,-1867,-3626,1.03827381134033 +8615,-0.45322373509407,-0.259865432977676,0.020753309130669,38504,5593,-2439,-3475,1.0389301776886 +8617,-0.47409799695015,-0.243737861514091,0.016461074352264,38504,4623,-2368,-3655,1.04280388355255 +8619,-0.499984920024872,-0.224102899432182,0.011270008049905,38504,6416,-2417,-3594,1.04448616504669 +8621,-0.51834762096405,-0.217668682336807,0.008831773884594,38504,5281,-1945,-3706,1.04969346523285 +8623,-0.520596325397491,-0.206246972084045,0.009125994518399,38504,5270,-2009,-3624,1.04289209842682 +8625,-0.5105140209198,-0.193125903606415,0.012116299010813,38504,3346,-2680,-3683,1.04106783866882 +8627,-0.504970729351044,-0.188392996788025,0.015090549364686,38504,4669,-1719,-3558,1.03436994552612 +8629,-0.507278740406036,-0.182629436254501,0.016385480761528,38504,4396,-2214,-3652,1.03357779979706 +8631,-0.508262038230896,-0.190622821450233,0.017452869564295,38504,5405,-689,-3530,1.03343164920807 +8633,-0.504569172859192,-0.191585078835487,0.01728879660368,38504,4141,-1513,-3645,1.03745019435883 +8635,-0.50249433517456,-0.188173890113831,0.020475273951888,38504,5311,-1470,-3495,1.04671466350555 +8637,-0.497909426689148,-0.167601257562637,0.020025761798024,38504,4195,-3313,-3624,1.05211341381073 +8639,-0.474861204624176,-0.156115934252739,0.017989983782172,38504,3553,-2496,-3528,1.05442988872528 +8641,-0.440932899713516,-0.13042514026165,0.014861049130559,38504,1475,-4141,-3658,1.05198299884796 +8643,-0.39213615655899,-0.110622301697731,0.01542785577476,38504,539,-3765,-3564,1.0525803565979 +8645,-0.340807318687439,-0.08471903949976,0.017802849411965,38504,-1046,-4760,-3637,1.04514813423157 +8647,-0.294966787099838,-0.065487191081047,0.023421427235007,38504,-680,-4422,-3475,1.0466902256012 +8649,-0.26188725233078,-0.055954720824957,0.024411711841822,38504,-752,-3969,-3589,1.04780471324921 +8651,-0.235973298549652,-0.028085548430681,0.017899084836245,38504,-106,-5632,-3543,1.05191874504089 +8653,-0.205554395914078,0.009354198351502,0.016567284241319,38504,-1278,-6893,-3643,1.05213117599487 +8655,-0.174880102276802,0.069675453007221,0.020212175324559,38683,-1369,-9550,-3526,1.05240905284882 +8657,-0.154691472649574,0.117952018976212,0.024690065532923,38683,-1211,-9260,-3586,1.05631816387177 +8659,-0.149587914347649,0.154388651251793,0.025179617106915,38683,118,-9261,-3475,1.05524289608002 +8661,-0.148175358772278,0.168952897191048,0.02689004689455,38683,93,-7647,-3569,1.05425691604614 +8663,-0.154558002948761,0.19157749414444,0.026056254282594,38683,1094,-8946,-3467,1.04947686195374 +8665,-0.157284870743752,0.19358329474926,0.028556851670146,38683,580,-7187,-3556,1.04745388031006 +8667,-0.160626649856567,0.191773012280464,0.029226934537292,38683,1025,-7281,-3427,1.04622733592987 +8669,-0.16899611055851,0.189614325761795,0.032041665166617,38683,1214,-6919,-3530,1.05444478988647 +8671,-0.18358638882637,0.185953587293625,0.037872962653637,38683,2252,-7138,-3321,1.05445039272308 +8673,-0.205229803919792,0.181116908788681,0.043070174753666,38683,2754,-6689,-3451,1.0556126832962 +8675,-0.228681728243828,0.158137619495392,0.041045010089874,38683,3694,-5382,-3276,1.04814732074738 +8677,-0.255539327859879,0.147251933813095,0.034306462854147,38683,3940,-5842,-3507,1.04981458187103 +8679,-0.270690321922302,0.132320165634155,0.030581267550588,38683,3884,-5601,-3393,1.05883681774139 +8681,-0.276734173297882,0.120338387787342,0.034567523747683,38683,2864,-5437,-3503,1.06173968315125 +8683,-0.274786531925201,0.084062315523625,0.0418138243258,38683,2839,-3340,-3253,1.06165683269501 +8685,-0.283822357654572,0.070976965129376,0.044420052319765,38683,3294,-4689,-3430,1.06168222427368 +8687,-0.285114198923111,0.052348740398884,0.047839883714914,38683,3350,-4120,-3174,1.06529116630554 +8689,-0.291065126657486,0.039604235440493,0.048242595046759,38683,3295,-4287,-3398,1.06525206565857 +8691,-0.294107139110565,0.021610490977764,0.047846790403128,38683,3744,-3675,-3165,1.0619330406189 +8693,-0.299124091863632,0.012301961891353,0.045791365206242,38683,3468,-4150,-3409,1.06429803371429 +8695,-0.296961575746536,0.010768634267151,0.047395519912243,38683,3548,-4684,-3164,1.06812465190887 +8715,-0.052913945168257,-0.039260074496269,0.075401343405247,38683,-1388,-4076,-2793,1.04348134994507 +8717,-0.036023400723934,-0.038516536355019,0.079794138669968,38683,-1427,-4111,-3128,1.05359077453613 +8719,-0.022869283333421,-0.047371748834848,0.077719017863274,38683,-1310,-3180,-2754,1.05372655391693 +8721,-0.00974381621927,-0.05633993819356,0.076584786176682,38683,-1532,-3137,-3139,1.05563008785248 +8723,0.00379752041772,-0.073309548199177,0.078231848776341,38683,-1774,-2148,-2736,1.05157625675201 +8725,0.00978864915669,-0.082503519952297,0.075390949845314,38683,-1312,-2711,-3136,1.05161488056183 +8727,0.015796544030309,-0.093499578535557,0.068186603486538,38683,-1442,-2210,-2843,1.04963767528534 +8729,0.015803631395102,-0.08394206315279,0.064363479614258,38683,-985,-3990,-3203,1.05255842208862 +8731,0.01936206035316,-0.089087724685669,0.064549289643765,38683,-1341,-2660,-2876,1.05962240695953 +8733,0.015170278958976,-0.083410128951073,0.060639169067144,38683,-692,-3677,-3219,1.06221723556519 +8735,0.00837037153542,-0.095270790159702,0.055865347385407,38683,-436,-2039,-2970,1.055708527565 +8737,-0.019412506371737,-0.089311629533768,0.05251744762063,38683,1481,-3569,-3267,1.04615592956543 +8739,-0.051493689417839,-0.086754903197289,0.054927155375481,38683,2333,-3170,-2974,1.03846406936646 +8741,-0.081669270992279,-0.085587114095688,0.056145414710045,38683,2559,-3238,-3235,1.02745401859283 +8743,-0.103570848703384,-0.0890087261796,0.055566549301148,38683,2477,-2663,-2959,1.02525997161865 +8745,-0.11439498513937,-0.088696599006653,0.055401582270861,38683,1680,-3090,-3233,1.0225738286972 +8747,-0.122393205761909,-0.081338375806809,0.053844191133976,38683,1842,-3521,-2973,1.02893042564392 +8749,-0.131788417696953,-0.085848972201347,0.051441892981529,38683,1876,-2746,-3253,1.04055738449097 +8751,-0.143513470888138,-0.064066976308823,0.044766385108233,38683,2495,-4800,-3074,1.05333888530731 +8753,-0.136511594057083,-0.049760427325964,0.039516586810351,38861,826,-4581,-3329,1.06147825717926 +8755,-0.127959698438644,-0.016306949779391,0.039996966719627,38861,839,-6386,-3127,1.06925535202026 +8757,-0.129844412207603,0.005142739973962,0.040876049548388,38861,1417,-5870,-3315,1.0695469379425 +8759,-0.151398897171021,0.026024501770735,0.03807657584548,38861,3436,-6168,-3146,1.06640100479126 +8761,-0.163993343710899,0.021064920350909,0.037843108177185,38861,2735,-4216,-3331,1.07374429702759 +8763,-0.173564061522484,0.007117490749806,0.034256398677826,38861,3023,-3369,-3187,1.06811606884003 +8765,-0.185967892408371,-0.014785500243306,0.035415600985289,38861,3113,-2487,-3344,1.06126272678375 +8767,-0.185538351535797,-0.050657205283642,0.039276596158743,38861,2574,-847,-3122,1.0532169342041 +8769,-0.183390200138092,-0.086167022585869,0.041269142180681,38861,2114,-461,-3299,1.05374979972839 +8771,-0.17750009894371,-0.125284552574158,0.039773911237717,38861,2123,635,-3109,1.05165874958038 +8773,-0.170224159955978,-0.149302989244461,0.040485344827175,38861,1634,-318,-3300,1.04783725738525 +8775,-0.16320963203907,-0.179468676447868,0.045536227524281,38861,1890,942,-3035,1.04090416431427 +8777,-0.169207394123077,-0.177357271313667,0.048978567123413,38861,2641,-1702,-3236,1.03563284873962 +8779,-0.17558978497982,-0.181343376636505,0.049961801618338,38861,3134,-807,-2978,1.03351008892059 +8781,-0.186667859554291,-0.180556505918503,0.052211452275515,38861,3335,-1473,-3207,1.02844774723053 +8783,-0.194176644086838,-0.186065122485161,0.055491074919701,38861,3595,-533,-2906,1.02321302890778 +8785,-0.207665428519249,-0.190961986780167,0.053783785551787,38861,3896,-826,-3188,1.01399707794189 +8787,-0.224756136536598,-0.193469226360321,0.053034503012896,38861,4859,-535,-2928,1.01274454593658 +8789,-0.240358427166939,-0.200542375445366,0.053719490766525,38861,4617,-437,-3182,1.01385247707367 +8791,-0.254088670015335,-0.208141103386879,0.058820847421885,38861,5195,161,-2853,1.01832437515259 +8793,-0.258723676204681,-0.213252618908882,0.066999793052673,38861,4208,-294,-3082,1.01932847499847 +8795,-0.250397801399231,-0.19523948431015,0.073087483644486,38861,3670,-1787,-2676,1.02077078819275 +8797,-0.227877095341682,-0.183827012777329,0.079432681202889,38861,1932,-1803,-2986,1.02390956878662 +8799,-0.216023817658424,-0.148575156927109,0.087763369083405,38861,2965,-3691,-2493,1.03009021282196 +8801,-0.20764322578907,-0.11531838029623,0.095661051571369,38861,2752,-4276,-2862,1.03526711463928 +8803,-0.204062834382057,-0.074035458266735,0.096558146178722,38861,3457,-5282,-2375,1.04131484031677 +8805,-0.197364747524262,-0.036047771573067,0.098027840256691,38861,2817,-5712,-2831,1.05331647396088 +8807,-0.194775521755219,0.002292679622769,0.096793495118618,38861,3481,-6296,-2358,1.06130111217499 +8809,-0.188544943928719,0.0405033826828,0.089014127850533,38861,2815,-6823,-2878,1.07070660591125 +8811,-0.176299184560776,0.048531860113144,0.083237014710903,38861,2579,-4882,-2504,1.06712567806244 +8813,-0.166469782590866,0.047384526580572,0.084200598299503,38861,2324,-4120,-2899,1.06197011470795 +8815,-0.156775414943695,0.047230783849955,0.088114567101002,38861,2512,-4284,-2433,1.05619275569916 +8817,-0.15216127038002,0.060853283852339,0.092442318797112,38861,2566,-5387,-2829,1.05087971687317 +8819,-0.145601376891136,0.056999370455742,0.094324238598347,38861,2621,-4187,-2346,1.05001056194305 +8821,-0.143441110849381,0.060391776263714,0.090428538620472,38861,2684,-4667,-2829,1.04935479164124 +8823,-0.127352088689804,0.057715352624655,0.08697646856308,38861,1708,-4320,-2419,1.0511486530304 +8825,-0.115375153720379,0.07359254360199,0.082035928964615,38861,1638,-5773,-2874,1.05266499519348 +8827,-0.097753793001175,0.091874584555626,0.080224253237248,38861,1169,-6417,-2485,1.05417597293854 +8829,-0.077760480344296,0.1064118668437,0.082600876688957,38861,571,-6188,-2858,1.05439257621765 +8831,-0.066725768148899,0.121547617018223,0.084750331938267,38861,1175,-6713,-2418,1.05471968650818 +8833,-0.06254031509161,0.127098634839058,0.087681546807289,38861,1517,-5894,-2810,1.05384814739227 +8835,-0.05638786777854,0.138080924749374,0.085390187799931,38861,1404,-6734,-2398,1.05549931526184 +8837,-0.046253480017185,0.14174909889698,0.081986755132675,38861,887,-6029,-2836,1.05650401115417 +8839,-0.038596507161856,0.153924152255058,0.081528730690479,38861,1046,-7133,-2430,1.05503404140472 +8841,-0.025835756212473,0.156867042183876,0.080405078828335,38861,430,-6261,-2835,1.05505740642548 +8843,-0.016868758946657,0.185960903763771,0.075570613145828,38861,598,-8938,-2487,1.05684673786163 +8845,-0.006896606646478,0.206769973039627,0.073882877826691,38861,369,-8338,-2869,1.06563723087311 +8847,-0.001416548038833,0.225526988506317,0.073250882327557,38861,588,-8929,-2502,1.06387138366699 +8849,0.00830065086484,0.231594860553741,0.075219020247459,38861,171,-7738,-2849,1.05855107307434 +8865,0.083702892065048,0.127816215157509,0.075968958437443,39308,-362,-5210,-2798,1.02822470664978 +8867,0.08835843205452,0.104664005339146,0.081994727253914,39308,-898,-4376,-2347,1.02985894680023 +8869,0.092423424124718,0.086032658815384,0.082695752382279,39308,-759,-4268,-2740,1.03202903270721 +8871,0.101615913212299,0.067078106105328,0.074826315045357,39308,-1479,-4104,-2421,1.04445457458496 +8873,0.109624713659287,0.051244109869003,0.067382462322712,39308,-1332,-3999,-2834,1.04714357852936 +8875,0.11351802945137,0.041832026094198,0.064682841300964,39308,-1346,-4401,-2530,1.04555654525757 +8877,0.112923674285412,0.02965359389782,0.05954660102725,39308,-814,-3969,-2878,1.03568887710571 +8879,0.10268996655941,0.024463040754199,0.051245797425509,39308,-208,-4437,-2681,1.02352023124695 +8881,0.087069503962994,0.012591454200447,0.043591264635325,39308,586,-3756,-2981,1.01835525035858 +8883,0.063057772815228,0.010766800493002,0.0386375002563,39308,1388,-4462,-2823,1.01444864273071 +8885,0.046918135136366,-0.005869683343917,0.037896171212196,39308,1172,-3154,-3015,1.01618492603302 +8887,0.033156860619783,-0.00547395600006,0.034924309700728,39308,1117,-4361,-2862,1.01681971549988 +8889,0.027170127257705,-0.012494745664299,0.035039953887463,39308,714,-3744,-3031,1.02139139175415 +8891,0.017841212451458,-0.021035693585873,0.035785961896181,39308,1036,-3461,-2848,1.02230155467987 +8893,0.008561810478568,-0.034454047679901,0.036899425089359,39308,1209,-2961,-3013,1.02366149425507 +8895,-0.010427259840071,-0.047621734440327,0.037750210613012,39308,2186,-2676,-2821,1.0201268196106 +8897,-0.034910876303911,-0.049349054694176,0.034566752612591,39308,2927,-3561,-3024,1.01948463916779 +8899,-0.054596323519945,-0.057676415890455,0.031106151640415,39308,2971,-2833,-2895,1.02169966697693 +8901,-0.070803508162499,-0.056783892214298,0.024810988456011,39308,2876,-3614,-3088,1.02321434020996 +8903,-0.08576787263155,-0.061036095023155,0.019718017429113,39308,3175,-3042,-3026,1.02166509628296 +8905,-0.105365075170994,-0.053322810679674,0.016693906858564,39308,3656,-4122,-3142,1.01725113391876 +8907,-0.11677198857069,-0.054453171789646,0.015322299674153,39308,3466,-3346,-3077,1.01433193683624 +8909,-0.127611368894577,-0.044589038938284,0.009670515544713,39308,3403,-4375,-3189,1.01006531715393 +8911,-0.132508546113968,-0.033278036862612,0.007215488702059,39308,3310,-4562,-3171,1.00755858421326 +8913,-0.129385307431221,-0.025700259953737,0.008559203706682,39308,2490,-4465,-3197,1.00171422958374 +8915,-0.124863639473915,-0.018955623731017,0.010014645755291,39308,2575,-4459,-3138,1.0063339471817 +8917,-0.127528995275497,-0.014163949526846,0.009843591600657,39308,2937,-4422,-3188,1.01620244979858 +8919,-0.122015900909901,0.000899449340068,0.012148725800216,39308,2517,-5369,-3113,1.02814257144928 +8921,-0.109036140143871,0.018730519339442,0.014525380916894,39308,1610,-5827,-3156,1.03967618942261 +8923,-0.099455028772354,0.042360380291939,0.016453478485346,39308,1914,-6657,-3060,1.04065823554993 +8925,-0.092907056212425,0.04660576581955,0.016110464930534,39308,1887,-5271,-3143,1.03532242774963 +8927,-0.09493038058281,0.049795284867287,0.013346923515201,39308,2717,-5326,-3095,1.02662599086761 +8929,-0.094220668077469,0.042483065277338,0.01390424836427,39308,2371,-4403,-3158,1.02610301971436 +8931,-0.089293725788593,0.045678231865168,0.012724380940199,39308,2169,-5276,-3102,1.02346670627594 +8933,-0.081853434443474,0.045681986957789,0.011891761794686,39308,1755,-4990,-3171,1.02925097942352 +8935,-0.073480725288391,0.033029057085514,0.00923041254282,39308,1705,-3965,-3143,1.0297999382019 +8937,-0.066733442246914,0.02960554882884,0.009421805851161,39308,1624,-4528,-3188,1.03591299057007 +8939,-0.059819545596838,0.020665368065238,0.011029911227524,39308,1607,-4039,-3122,1.04284834861755 +8941,-0.053260862827301,0.015216038562358,0.010097477585077,39308,1472,-4185,-3183,1.04416608810425 +8943,-0.046392325311899,-0.002707892097533,0.012769830413163,39308,1408,-3014,-3101,1.0432653427124 +8945,-0.046852689236403,-0.015798034146428,0.014908907003701,39308,1903,-3189,-3149,1.04374825954437 +8947,-0.043982807546854,-0.030793275684118,0.017535222694278,39308,1700,-2752,-3046,1.04691648483276 +8949,-0.035861983895302,-0.029075151309371,0.019468123093248,39308,1154,-4042,-3117,1.05251598358154 +8951,-0.020340252667666,-0.040191121399403,0.022980332374573,39308,448,-2851,-2980,1.0582480430603 +8953,-0.003788623027503,-0.045154951512814,0.022947253659368,39308,106,-3310,-3090,1.05746734142303 +8955,0.011860933154821,-0.035294465720654,0.027182133868337,39308,-92,-4417,-2928,1.06240177154541 +8957,0.027796177193523,-0.028564266860485,0.032745067030192,39308,-304,-4365,-3020,1.05817854404449 +8959,0.035354290157557,-0.018733305856586,0.035917781293392,39308,91,-4674,-2820,1.05405247211456 +8961,0.037044379860163,-0.028992891311646,0.034591648727656,39308,569,-3130,-3003,1.04349315166473 +8963,0.031852707266808,-0.03364410251379,0.034039624035359,39308,1054,-3382,-2839,1.03627860546112 +8965,0.028091434389353,-0.041650902479887,0.033164035528898,39308,1076,-3092,-3008,1.02778553962708 +8967,0.018253730610013,-0.039604887366295,0.031980372965336,39308,1605,-3743,-2859,1.02024233341217 +8969,0.011087468825281,-0.04190319031477,0.034995872527361,39308,1560,-3476,-2992,1.01781713962555 +8971,0.003566502360627,-0.032479356974363,0.034732032567263,39308,1670,-4366,-2822,1.00936043262482 +8973,-0.004679134115577,-0.0348198749125,0.035222172737122,39308,1865,-3556,-2986,1.00906181335449 +8975,-0.016082063317299,-0.038807086646557,0.034767534583807,39308,2262,-3288,-2817,1.01082384586334 +8977,-0.030576867982745,-0.038159124553204,0.034573890268803,39308,2693,-3701,-2986,1.01683747768402 +8979,-0.039007633924484,-0.035683367401362,0.031737569719553,39308,2439,-3783,-2849,1.012042760849 +8981,-0.041802652180195,-0.028275417163968,0.026641175150871,39308,2036,-4309,-3037,1.00828647613525 +8983,-0.04827906191349,-0.040515061467886,0.022215865552425,39308,2488,-2621,-2958,1.00555324554443 +8985,-0.062857381999493,-0.029870197176933,0.021646345034242,39308,3209,-4495,-3069,1.00575566291809 +8987,-0.073696434497833,-0.019843699410558,0.02085735462606,39308,3248,-4532,-2972,1.00633239746094 +8989,-0.08644912391901,0.003089974168688,0.018165806308389,39308,3456,-5835,-3091,1.00369441509247 +8991,-0.088483989238739,0.016637697815895,0.018437102437019,39308,2886,-5387,-2997,1.00323450565338 +8993,-0.092656917870045,0.033148381859064,0.017462961375713,39308,2975,-5812,-3094,1.00086498260498 +8995,-0.090928971767426,0.050465650856495,0.016981039196253,39308,2695,-6227,-3011,1.00684785842896 +8997,-0.08084449917078,0.0640779286623,0.01178773585707,39308,1828,-6070,-3132,1.01052248477936 +9013,0.029975939542055,0.184147745370865,0.012846906669438,39487,-29,-7325,-3123,1.03803861141205 +9015,0.041367955505848,0.18606673181057,0.016248418018222,39487,-45,-7625,-3012,1.03171014785767 +9017,0.047036573290825,0.183692649006844,0.017968598753214,39487,367,-6978,-3086,1.02717006206512 +9019,0.053283743560314,0.168691098690033,0.016359588131309,39487,109,-6211,-3010,1.01822876930237 +9021,0.060449883341789,0.157024011015892,0.016402389854193,39487,47,-6008,-3096,1.01899111270905 +9023,0.07296746969223,0.150547876954079,0.018351677805185,39487,-685,-6601,-2986,1.01696217060089 +9025,0.087056182324886,0.146754086017609,0.016988264396787,39487,-859,-6495,-3090,1.01719105243683 +9027,0.106396041810513,0.119978986680508,0.01592916995287,39487,-1752,-4723,-3014,1.01719343662262 +9029,0.118575781583786,0.106546081602573,0.016972225159407,39487,-1220,-5286,-3088,1.02275204658508 +9031,0.13313689827919,0.088670551776886,0.018322702497244,39487,-1896,-4892,-2986,1.03331232070923 +9033,0.141062468290329,0.081649646162987,0.018758630380035,39487,-1296,-5431,-3074,1.03931891918182 +9035,0.149559304118156,0.065505035221577,0.01985501870513,39487,-1787,-4665,-2967,1.04321348667145 +9037,0.156124666333199,0.055997680872679,0.019001821056008,39487,-1480,-4914,-3071,1.04042935371399 +9039,0.161976739764214,0.043273333460093,0.023632550612092,39487,-1869,-4567,-2921,1.03901970386505 +9041,0.176636964082718,0.018556648865342,0.02614102140069,39487,-2427,-3306,-3019,1.0333263874054 +9043,0.188749015331268,6.48351260679192E-06,0.02357542514801,39487,-2836,-3458,-2920,1.03481078147888 +9045,0.200413793325424,-0.022667435929179,0.02537514641881,40131,-2639,-2859,-3022,1.02964162826538 +9047,0.210635483264923,-0.040002871304751,0.02943954244256,40131,-3152,-2897,-2849,1.03091526031494 +9049,0.216497153043747,-0.075442306697369,0.030088923871517,40131,-2552,-1170,-2986,1.02819526195526 +9051,0.21250019967556,-0.099316127598286,0.031859327107668,40131,-2258,-1439,-2817,1.02550256252289 +9053,0.212846338748932,-0.127264112234116,0.033000081777573,40131,-2203,-918,-2962,1.02268064022064 +9055,0.215374022722244,-0.148443177342415,0.031126648187637,40131,-2876,-776,-2821,1.01467943191528 +9057,0.223099738359451,-0.179373517632484,0.032600078731775,40131,-2980,110,-2961,1.0168524980545 +9059,0.227258309721947,-0.202692553400993,0.034086838364601,40131,-3286,338,-2782,1.01731097698212 +9061,0.234639689326286,-0.219037920236588,0.036511830985546,40131,-3228,-271,-2930,1.02244317531586 +9063,0.243933230638504,-0.234467506408691,0.035087924450636,40131,-4027,393,-2764,1.02104270458221 +9065,0.244981318712234,-0.238582417368889,0.033626720309258,40131,-3036,-757,-2945,1.02065289020538 +9067,0.246461093425751,-0.255851954221725,0.030492497608066,40131,-3619,997,-2813,1.02143692970276 +9069,0.247681140899658,-0.262537270784378,0.02595123462379,40131,-3203,-108,-2994,1.01916205883026 +9071,0.248753473162651,-0.278113752603531,0.023214660584927,40131,-3740,1366,-2894,1.01162528991699 +9073,0.233685836195946,-0.280605018138885,0.024113683030009,40131,-1951,-16,-3004,1.00233256816864 +9075,0.216219499707222,-0.288429826498032,0.025936007499695,40131,-2005,1106,-2857,0.99893319606781 +9077,0.200181216001511,-0.298705548048019,0.024633349850774,40131,-1505,938,-2997,0.992535710334778 +9079,0.192157208919525,-0.309934467077255,0.02141834422946,40131,-2394,1832,-2906,0.994417786598206 +9081,0.183229327201843,-0.316394418478012,0.020459499210119,40131,-1866,1065,-3023,0.99800056219101 +9083,0.165951192378998,-0.316141128540039,0.019478840753436,40131,-1390,1253,-2925,0.998424232006073 +9085,0.153669193387032,-0.327699095010757,0.013444064185023,40131,-1284,1743,-3069,1.00024557113647 +9087,0.137750715017319,-0.327924877405167,0.008336160331965,40131,-1103,1649,-3054,1.00042009353638 +9089,0.11624401807785,-0.331847906112671,0.00970733165741,40131,-156,1415,-3095,1.00512599945068 +9091,0.091124810278416,-0.322837710380554,0.005534475669265,40131,263,1075,-3086,1.00749063491821 +9093,0.07110233604908,-0.311722755432129,0.001732435193844,40131,338,209,-3150,1.01419949531555 +9095,0.049295224249363,-0.303314805030823,0.000875679659657,40131,676,936,-3142,1.02146911621094 +9097,0.025668634101749,-0.285026133060455,0.00175650161691,40131,1222,-539,-3150,1.0275114774704 +9099,0.012858228757978,-0.269718050956726,0.004313095007092,40131,601,22,-3103,1.03269982337952 +9101,-0.000401579600293,-0.247060209512711,0.004764716140926,40131,843,-1266,-3130,1.03333330154419 +9103,-0.019709786400199,-0.227574869990349,0.007603970356286,40131,1586,-845,-3066,1.02899789810181 +9105,-0.046798214316368,-0.192336231470108,0.005868923850358,40131,2503,-2841,-3122,1.02023530006409 +9107,-0.067280560731888,-0.148626208305359,0.001510630943812,40131,2447,-3766,-3140,1.0178679227829 +9109,-0.07586507499218,-0.108408018946648,-0.001079981564544,40131,1618,-4326,-3171,1.01657092571259 +9111,-0.084154404699802,-0.070698074996471,0.000842082255986,40131,1885,-4543,-3152,1.0144807100296 +9113,-0.092384718358517,-0.04629036411643,0.003334362991154,40131,1864,-4044,-3142,1.01075410842896 +9115,-0.095031425356865,-0.022376652806997,0.001029406907037,40131,1700,-4303,-3153,1.00608801841736 +9117,-0.089068986475468,-0.00711373006925,-0.000163099641213,40131,839,-3931,-3167,1.00204980373383 +9119,-0.082359589636326,0.014112409204245,-5.58749306946993E-05,40131,860,-4687,-3168,0.998958051204681 +9121,-0.077089093625546,0.029966674745083,0.000626112276223,40131,751,-4501,-3163,1.00044560432434 +9123,-0.076345346868038,0.039332952350378,0.001864624093287,40131,1215,-4256,-3147,0.997795343399048 +9125,-0.081609472632408,0.060494814068079,0.001971694175154,40131,1601,-5329,-3155,0.997635841369629 +9127,-0.08258455991745,0.07538715004921,0.002947714412585,40131,1471,-5254,-3136,1.00145781040192 +9129,-0.086665458977223,0.094835817813873,0.006861414760351,40131,1622,-5725,-3122,1.00327467918396 +9131,-0.093324676156044,0.097419291734696,0.01042446307838,40131,2109,-4755,-3049,1.0045040845871 +9133,-0.105937473475933,0.103527709841728,0.009726767428219,40131,2552,-4929,-3102,1.00048267841339 +9135,-0.119656920433044,0.113939121365547,0.006998368073255,40131,3083,-5618,-3089,1.00263774394989 +9137,-0.1256053596735,0.116674304008484,0.001368962693959,40131,2410,-4918,-3160,0.99693101644516 +9139,-0.128548458218575,0.123857825994492,-0.005743141751736,40131,2493,-5596,-3240,0.989835262298584 +9141,-0.140885293483734,0.131908684968948,-0.011267148889601,40131,3142,-5565,-3249,0.988647937774658 +9143,-0.154917329549789,0.141562104225159,-0.013376825489104,40131,3777,-6115,-3333,0.9902663230896 +9145,-0.152350887656212,0.134409129619598,-0.012898520566523,40131,2306,-4568,-3264,0.994251012802124 +9147,-0.145433783531189,0.136574611067772,-0.013113499619067,40131,2187,-5554,-3333,1.00157845020294 +9149,-0.140316188335419,0.137725025415421,-0.014298105612397,40131,2014,-5266,-3278,1.01384663581848 +9151,-0.137983769178391,0.132914841175079,-0.01602029055357,40131,2450,-5039,-3371,1.02185988426209 +9153,-0.130847856402397,0.124665074050426,-0.015811681747437,40131,1793,-4457,-3292,1.02945601940155 +9155,-0.119463615119457,0.111874110996723,-0.015125771053135,40131,1558,-4161,-3364,1.03700387477875 +9157,-0.106648780405521,0.102695442736149,-0.01497211959213,40131,1090,-4116,-3291,1.03565430641174 +9159,-0.094708755612373,0.088193580508232,-0.011930891312659,40131,1167,-3688,-3330,1.02861762046814 +9161,-0.087083980441094,0.08185513317585,-0.007426427677274,40131,1222,-4050,-3242,1.02044022083282 +9163,-0.075015559792519,0.069707900285721,-0.005297067109495,40131,876,-3590,-3254,1.01753962039948 +9165,-0.065866939723492,0.057669654488564,-0.006837591528893,40131,841,-3318,-3240,1.01213181018829 +9167,-0.056669697165489,0.048854745924473,-0.004821271635592,40131,813,-3514,-3251,1.00728833675385 +9169,-0.04463155567646,0.036404006183148,-0.002566855633631,40131,354,-2997,-3213,1.00437581539154 +9171,-0.03637108206749,0.026424450799823,0.002381830709055,40131,566,-3075,-3168,1.00581800937653 +9173,-0.025929493829608,0.010202649980784,0.005611471366137,40131,214,-2355,-3158,1.00707077980042 +9175,-0.015948843210936,0.000211652528378,0.008282598108053,40131,116,-2644,-3098,1.0086042881012 +9177,0.000402821198804,-0.024171605706215,0.017030011862516,40131,-582,-1268,-3079,1.00504314899445 +9179,0.010579754598439,-0.038267083466053,0.026528423652053,40131,-322,-1704,-2882,1.00248825550079 +9181,0.015738962218165,-0.052539303898811,0.031382206827402,40131,-7,-1558,-2978,1.00550091266632 +9183,0.021448316052556,-0.067559272050858,0.033123757690191,40131,-178,-1125,-2801,1.00387394428253 +9185,0.020880974829197,-0.075335390865803,0.038556065410376,40131,319,-1655,-2924,1.00154066085815 +9187,0.026179477572441,-0.09469410777092,0.046281643211842,40131,-244,-329,-2640,0.999076247215271 +9189,0.036320488899946,-0.112440407276154,0.05087348818779,40131,-682,-355,-2833,0.998813986778259 +9191,0.050094403326511,-0.134092211723328,0.054142329841852,40131,-1257,533,-2541,0.998541355133056 +9193,0.05725322291255,-0.136968284845352,0.055715631693602,40131,-794,-997,-2792,1.00085616111755 +9195,0.070055566728115,-0.155306413769722,0.063295863568783,40131,-1540,713,-2424,1.0034202337265 +9197,0.08181619644165,-0.165209978818893,0.065480694174767,40131,-1510,-7,-2715,1.00702309608459 +9199,0.094458244740963,-0.170386463403702,0.062951564788818,40131,-1963,104,-2418,1.0132577419281 +9201,0.107931703329086,-0.169960737228394,0.063858017325401,40131,-2052,-590,-2717,1.01242625713348 +9203,0.119089469313622,-0.159948974847794,0.065319240093231,40131,-2304,-1060,-2381,1.01619827747345 +9205,0.13240185379982,-0.156672269105911,0.06775213778019,40131,-2448,-899,-2680,1.01329791545868 +9207,0.147190883755684,-0.151046872138977,0.07076558470726,40131,-3086,-813,-2306,1.00341558456421 +9209,0.159949630498886,-0.148910701274872,0.07442407310009,40131,-2874,-847,-2624,0.98991048336029 +9211,0.16033923625946,-0.133624076843262,0.076761409640312,40131,-2343,-1718,-2224,0.980396747589111 +9213,0.15871624648571,-0.123726725578308,0.078829646110535,40131,-1903,-1692,-2582,0.983378827571869 +9215,0.166090354323387,-0.129971235990524,0.077326647937298,40131,-3013,-168,-2205,0.987028241157532 +9217,0.171924978494644,-0.132104054093361,0.075204439461231,40131,-2707,-640,-2595,0.993787407875061 +9219,0.17049615085125,-0.123070679605007,0.076243594288826,40131,-2544,-1301,-2205,1.00026047229767 +9221,0.161349073052406,-0.097976289689541,0.076598130166531,40131,-1565,-3011,-2573,1.00611674785614 +9223,0.158847033977509,-0.09083990752697,0.077843740582466,40131,-2368,-1621,-2174,1.01321387290955 +9225,0.156638607382774,-0.083094336092472,0.079100795090199,40131,-2075,-1927,-2544,1.01406514644623 +9239,0.092262759804726,0.001199886435643,0.075669571757317,40131,-1047,-4033,-2154,1.00811755657196 +9241,0.074970535933971,0.015493190847337,0.078412815928459,40131,-70,-3680,-2500,1.00668609142303 +9243,0.06520202755928,0.014709710143507,0.085302568972111,40131,-623,-2607,-2028,1.00704908370972 +9245,0.056740630418062,0.022032415494323,0.089327335357666,40131,-479,-3267,-2411,1.00789022445679 +9247,0.049999427050352,0.028331773355603,0.091669052839279,40131,-629,-3339,-1940,1.00878036022186 +9249,0.034112211316824,0.043769020587206,0.093318767845631,40131,346,-4161,-2370,1.01041889190674 +9251,0.022516932338476,0.044855397194624,0.09385996311903,40131,137,-3240,-1900,1.01169097423553 +9253,0.009996924549341,0.054201703518629,0.091672815382481,40131,432,-3883,-2366,1.00459027290344 +9255,-0.007323572412133,0.0717618688941,0.087259851396084,40131,1029,-4865,-1965,1.00057697296143 +9257,-0.025787295773625,0.090128779411316,0.082766443490982,40131,1367,-5065,-2414,0.997764945030212 +9259,-0.039167303591967,0.102078028023243,0.079437166452408,40131,1271,-4979,-2045,0.997672259807587 +9261,-0.049640905112028,0.101054936647415,0.077375553548336,40131,1149,-3866,-2439,0.997370362281799 +9263,-0.062803044915199,0.112099282443523,0.076430886983872,40131,1655,-5116,-2069,1.00065720081329 +9265,-0.072586558759213,0.120393924415112,0.078214533627033,40131,1451,-4850,-2421,1.00990915298462 +9267,-0.075037851929665,0.127755254507065,0.078473694622517,40131,1110,-5150,-2033,1.0113490819931 +9269,-0.079290710389614,0.129362791776657,0.075367785990238,40131,1179,-4547,-2428,1.00947141647339 +9271,-0.090486750006676,0.128765389323235,0.07044044137001,40131,2016,-4641,-2116,1.0062609910965 +9273,-0.102317318320274,0.126454994082451,0.06831619143486,40131,2087,-4272,-2466,1.00422883033752 +9275,-0.105231493711472,0.118743553757668,0.069450847804546,40131,1705,-4019,-2117,1.00453627109528 +9277,-0.10271991789341,0.1188023686409,0.069867305457592,40131,1108,-4375,-2445,1.0027619600296 +9279,-0.100808463990688,0.114098116755486,0.068794921040535,40131,1333,-4200,-2114,1.00554764270782 +9281,-0.094644732773304,0.100214093923569,0.069355733692646,40131,772,-3152,-2438,1.00370383262634 +9283,-0.094037681818009,0.086183629930019,0.073327392339707,40131,1354,-3110,-2048,1.00564014911652 +9285,-0.095355466008186,0.0679165199399,0.07644771784544,40131,1357,-2402,-2378,1.00598204135895 +9287,-0.091783672571182,0.068143129348755,0.077128723263741,40131,1138,-3861,-1991,1.0059107542038 +9289,-0.077810190618038,0.059516228735447,0.0770108923316,40131,46,-2992,-2362,1.0066145658493 +9291,-0.064960010349751,0.061253033578396,0.071955025196076,40131,61,-3879,-2040,1.00265967845917 +9293,-0.050990760326386,0.057384870946407,0.067102700471878,40131,-314,-3320,-2419,1.00318682193756 +9295,-0.035491198301315,0.051917724311352,0.069501295685768,40131,-584,-3228,-2058,1.00093078613281 +9297,-0.024992052465677,0.049031525850296,0.075221285223961,40131,-428,-3284,-2352,1.00483870506287 +9299,-0.014235348440707,0.042544338852167,0.075426086783409,40131,-579,-3013,-1976,1.01306760311127 +9301,-0.004975627176464,0.038972042500973,0.074134320020676,40131,-624,-3100,-2348,1.01274931430817 +9303,0.006282097194344,0.025665022432804,0.074708990752697,40131,-956,-2256,-1972,1.01027846336365 +9305,0.010345758870244,0.021288733929396,0.076253965497017,40131,-480,-2791,-2321,1.00511944293976 +9307,0.007926837541163,0.009698891080916,0.077647872269154,40131,-18,-2108,-1925,1.00164747238159 +9309,0.014817146584392,-0.004626037552953,0.075950130820274,40131,-758,-1699,-2311,0.999596655368805 +9311,0.024215497076511,-0.009219085797668,0.078218258917332,40131,-1139,-2294,-1906,1.00001311302185 +9313,0.029443901032209,-0.018055897206068,0.080958507955074,40131,-865,-1884,-2264,1.00306820869446 +9315,0.027715913951397,-0.009597892872989,0.078697308897972,40131,-418,-3215,-1888,1.00986814498901 +9317,0.034089989960194,-0.015912918373942,0.074505344033241,40131,-1033,-2080,-2296,1.01107800006866 +9319,0.036370549350977,-0.01928442530334,0.069590017199516,40131,-862,-2196,-1983,1.00698781013489 +9321,0.03678735345602,-0.025008473545313,0.069848172366619,40131,-668,-1973,-2317,1.00632202625275 +9323,0.02810949832201,-0.023390268906951,0.07100623100996,40131,34,-2470,-1955,1.00255250930786 +9325,0.0149190640077,-0.017975883558393,0.065194711089134,40131,601,-2852,-2338,1.00157415866852 +9327,0.010487115010619,-0.017271419987083,0.057329885661602,40131,-4,-2487,-2106,1.00293076038361 +9329,0.012775974348188,-0.010990462265909,0.052996255457401,40131,-488,-2998,-2413,1.00380182266235 +9331,0.016848597675562,-0.007056593429297,0.053221043199301,40131,-725,-2869,-2146,1.00241768360138 +9333,0.013327915221453,-0.003009516047314,0.05111388489604,40131,-94,-2940,-2418,0.996319472789764 +9335,0.003211410483345,-0.000290037889499,0.045525688678026,40131,504,-2875,-2230,0.99298506975174 +9337,0.001389262382872,0.001887492835522,0.044057831168175,40131,-52,-2866,-2459,0.989145219326019 +9339,0.000486753036967,0.011295573785901,0.045745689421892,40131,-117,-3531,-2220,0.987936198711395 +9341,0.002792371669784,0.017147950828076,0.046447351574898,40131,-374,-3343,-2436,0.988191723823547 +9343,-0.004780658055097,0.03257293254137,0.043723478913307,40131,439,-4311,-2238,0.989271104335785 +9345,-0.015718806535006,0.028316447511315,0.040947943925858,40131,836,-2783,-2467,0.992932438850403 +9347,-0.021163588389754,0.021756188943982,0.037477854639292,40131,546,-2569,-2305,1.00039410591125 +9349,-0.024040155112743,0.01845520362258,0.036358702927828,40131,380,-2712,-2493,1.01164472103119 +9351,-0.020886490121484,0.012632139027119,0.035875916481018,40131,-71,-2471,-2318,1.01058411598206 +9353,-0.02069067209959,0.01686585508287,0.033033657819033,40131,115,-3225,-2511,1.00359392166138 +9355,-0.026529960334301,0.023282920941711,0.032499108463526,40131,670,-3518,-2353,0.996053576469421 +9357,-0.038038715720177,0.032464161515236,0.031965289264917,40131,1208,-3805,-2513,0.997230350971222 +9359,-0.040071368217468,0.025210935622454,0.032438036054373,40131,643,-2572,-2350,1.00428807735443 +9361,-0.036384504288435,0.019791821017861,0.036402691155672,40131,110,-2580,-2478,1.00494909286499 +9363,-0.04051873087883,0.018763680011034,0.037769723683596,40131,834,-2914,-2282,1.00952649116516 +9365,-0.042942270636559,0.021152403205633,0.036462649703026,40131,660,-3158,-2472,1.01428556442261 +9367,-0.04314224049449,0.024505339562893,0.034809898585081,40131,612,-3324,-2312,1.01730918884277 +9369,-0.038031209260225,0.019755030050874,0.034715447574854,40131,69,-2628,-2479,1.02056884765625 +9371,-0.031000996008515,0.029182072728872,0.034182731062174,40131,-116,-3841,-2313,1.01863539218903 +9373,-0.023628106340766,0.037101436406374,0.03608326241374,40131,-290,-3790,-2465,1.01398372650146 +9375,-0.023439835757017,0.0477787964046,0.037049539387226,40131,264,-4238,-2275,1.00579035282135 +9377,-0.029860571026802,0.049544662237167,0.034737035632134,40131,793,-3541,-2469,0.996098458766937 +9379,-0.032117132097483,0.037661664187908,0.034292887896299,40131,603,-2463,-2302,0.988078832626343 +9381,-0.032113518565893,0.038043364882469,0.036486212164164,40131,378,-3284,-2452,0.987029731273651 +9383,-0.028616050258279,0.042500417679548,0.037718389183283,40131,141,-3719,-2257,0.98592209815979 +9385,-0.026074048131704,0.066023051738739,0.035779889672995,40131,120,-5353,-2451,0.984912514686584 +9387,-0.022307403385639,0.078709676861763,0.03222868219018,40131,15,-4921,-2317,0.987392127513886 +9389,-0.019929740577936,0.082874454557896,0.030507752671838,40131,49,-4236,-2482,0.982835233211517 +9391,-0.016243869438768,0.079084344208241,0.032108549028635,40131,-83,-3780,-2313,0.980594456195831 +9393,-0.016503717750311,0.073442228138447,0.031755827367306,40131,190,-3427,-2469,0.980173945426941 +9395,-0.019736640155315,0.073751159012318,0.031990461051464,40131,474,-4013,-2310,0.979423701763153 +9397,-0.022119591012597,0.07629282027483,0.032821528613567,40131,426,-4081,-2457,0.978897035121918 +9399,-0.020836438983679,0.086829021573067,0.029899191111326,40131,189,-4980,-2331,0.974016010761261 +9401,-0.018623607233167,0.091856308281422,0.028160577639937,40131,53,-4513,-2485,0.974263310432434 +9403,-0.014392842538655,0.093869604170323,0.025224603712559,40131,-121,-4509,-2382,0.97739577293396 +9405,-0.007715277373791,0.089461654424667,0.020570619031787,40131,-419,-3837,-2534,0.983882129192352 +9407,-0.00171198300086,0.081820532679558,0.020491072908044,40131,-465,-3659,-2434,0.985534608364105 +9409,-0.005008759908378,0.090774275362492,0.024457374587655,40131,252,-4842,-2504,0.988088190555572 +9411,-0.010343488305807,0.093073591589928,0.026858605444431,40131,479,-4594,-2356,0.992766618728638 +9413,-0.016291486099362,0.102112114429474,0.024897197261453,40131,603,-5047,-2497,0.99588817358017 +9415,-0.013271488249302,0.097546860575676,0.021292312070727,40131,-66,-4210,-2418,0.99653697013855 +9417,-0.014734809286893,0.091976270079613,0.020286161452532,40131,260,-3894,-2526,0.990959286689758 +9419,-0.029248049482703,0.093382641673088,0.023145698010922,40131,1450,-4608,-2393,0.986704230308533 +9421,-0.039299927651882,0.093301437795162,0.023968132212758,40131,1236,-4342,-2498,0.98523211479187 +9423,-0.039926048368216,0.093071535229683,0.020709678530693,40131,637,-4523,-2419,0.985559523105621 +9425,-0.033497143536806,0.084779046475887,0.017952211201191,40131,-14,-3669,-2536,0.987857699394226 +9427,-0.039577834308148,0.093786962330341,0.016890231519938,40131,1042,-5234,-2462,0.988633930683136 +9429,-0.052106451243162,0.094110429286957,0.01684121415019,40131,1624,-4457,-2542,0.992686450481415 +9431,-0.058151505887508,0.091575548052788,0.016273111104965,40131,1357,-4405,-2467,0.991370737552643 +9433,-0.057780180126429,0.092457115650177,0.015010432340205,40131,804,-4510,-2552,0.990831613540649 +9435,-0.061481840908527,0.09112299233675,0.012119514867663,40131,1266,-4516,-2514,0.988796591758728 +9437,-0.068933829665184,0.091774895787239,0.009988992474973,40131,1548,-4519,-2586,0.987925827503204 +9439,-0.071164339780808,0.079950913786888,0.007553962059319,40131,1341,-3623,-2566,0.984111368656158 +9441,-0.069504670798779,0.071119636297226,0.005448932759464,40131,931,-3576,-2616,0.977570831775665 +9443,-0.067533276975155,0.061880994588137,0.006621365435421,40131,1008,-3552,-2576,0.981134355068207 +9445,-0.074668236076832,0.064093291759491,0.005695564672351,40131,1662,-4292,-2614,0.987787187099457 +9447,-0.087032169103623,0.05855093896389,0.005108557641506,40131,2380,-3781,-2594,0.997692584991455 +9449,-0.087385848164558,0.041250567883253,0.004368577152491,40131,1394,-2589,-2623,0.993567645549774 +9451,-0.084363110363484,0.039354011416435,0.002922866493464,40131,1267,-3747,-2619,0.986104965209961 +9469,-0.06152680143714,-0.01306651160121,-0.004378237761557,40131,795,-2444,-2690,0.996905207633972 +9471,-0.04959362000227,-0.031981151551008,-0.005199417937547,40131,220,-1346,-2721,1.00095236301422 +9473,-0.03937479108572,-0.042347356677055,-0.008832107298076,40131,131,-1869,-2722,0.999937474727631 +9475,-0.032080363482237,-0.051230013370514,-0.009914148598909,40131,282,-1727,-2778,1.00228655338287 +9477,-0.023934965953231,-0.057387374341488,-0.007991041988134,40131,69,-1925,-2718,1.00126016139984 +9479,-0.017602065578103,-0.048322603106499,-0.004773356951773,40131,129,-3029,-2720,0.997447907924652 +9481,-0.008706296794117,-0.044447150081396,-0.004097741097212,40131,-198,-2800,-2693,0.996865034103394 +9483,0.001270774519071,-0.040824174880982,-0.004119335208088,40131,-433,-2729,-2714,0.9942307472229 +9485,0.010516964830458,-0.048353098332882,-0.002354728756472,40131,-502,-1901,-2683,0.993596732616425 +9487,0.016165520995855,-0.040368288755417,-0.00193407968618,40131,-377,-3023,-2689,0.993341326713562 +9489,0.027340296655893,-0.041569665074349,-0.000163498800248,40131,-892,-2425,-2669,0.994544208049774 +9491,0.039452042430639,-0.046400297433138,0.001491420320235,40131,-1236,-1986,-2649,0.997470021247864 +9493,0.044658239930868,-0.037995919585228,0.001838186639361,40131,-735,-3136,-2655,1.00362968444824 +9495,0.04771589115262,-0.034100193530321,0.003627712605521,40131,-740,-2780,-2625,1.00840187072754 +9497,0.054845381528139,-0.036289863288403,0.007387357763946,40131,-1044,-2378,-2617,1.0099641084671 +9499,0.062677197158337,-0.043794821947813,0.008802524767816,40131,-1350,-1782,-2563,1.00611805915833 +9501,0.062946483492851,-0.027967354282737,0.007065015845001,40131,-700,-3761,-2619,0.998913049697876 +9503,0.067087426781654,-0.018732922151685,0.003293712157756,40131,-1201,-3374,-2628,0.994568347930908 +9505,0.072232015430927,-0.020553883165121,0.000143814744661,40131,-1219,-2588,-2666,0.987090110778809 +9507,0.07357669621706,-0.015965638682246,0.000665897619911,40131,-1144,-3074,-2659,0.988169729709625 +9509,0.076540529727936,-0.008396164514124,0.000437417707872,40131,-1163,-3421,-2665,0.993214249610901 +9511,0.07647630572319,0.002773329149932,-0.001193105243146,40131,-1122,-3839,-2682,0.990662693977356 +9513,0.076253861188889,0.000398443982704,-0.002139502670616,40131,-970,-2830,-2683,0.987981677055359 +9515,0.069158792495728,0.016334995627403,-0.001866464503109,40131,-538,-4391,-2691,0.989016771316528 +9517,0.068755559623242,0.021345967426896,8.64381727296859E-05,40131,-886,-3659,-2669,0.991784572601318 +9519,0.06135019287467,0.028003202751279,-0.000686898536514,40131,-426,-3913,-2678,0.98952716588974 +9521,0.055582251399756,0.030733954161406,-0.002497471636161,40131,-346,-3635,-2688,0.987111926078796 +9523,0.051166485995054,0.034717056900263,-0.003430978395045,40131,-506,-3852,-2712,0.984006524085998 +9525,0.050827078521252,0.050021450966597,-0.002866607625037,40131,-696,-4823,-2692,0.983307301998138 +9527,0.049179375171661,0.060279782861471,-0.004121189005673,40131,-704,-4741,-2722,0.98579728603363 +9529,0.043776642531157,0.068988494575024,-0.006972575560212,40131,-261,-4646,-2721,0.986213803291321 +9531,0.040100574493408,0.068363167345524,-0.004949629306793,40131,-429,-4115,-2734,0.987463057041168 +9533,0.036005988717079,0.071218051016331,-0.00598022993654,40131,-266,-4286,-2716,0.984118819236755 +9535,0.029425006359816,0.080872356891632,-0.006350891198963,40131,-69,-5071,-2752,0.982179045677185 +9537,0.027632333338261,0.087049275636673,-0.004653788171709,40131,-329,-4782,-2709,0.981843888759613 +9539,0.025908060371876,0.096229031682015,-0.007848252542317,40131,-379,-5312,-2772,0.981567680835724 +9541,0.021862814202905,0.093976125121117,-0.015279316343367,40131,-102,-4314,-2784,0.982581317424774 +9543,0.011399588547647,0.105130337178707,-0.020044157281518,40131,-32767,-32767,-2919,0.984474837779999 +9545,0.005026804283261,0.099521189928055,-0.019007300958037,40131,-20381,-10377,-2814,0.987908959388733 +9547,-0.005723103880882,0.093834280967712,-0.015741212293506,40131,-20020,-10530,-2872,0.992189884185791 +9549,-0.017823401838541,0.094844222068787,-0.012531554326415,40131,-19850,-10887,-2773,0.994329988956451 +9551,-0.024395506829023,0.091699607670307,-0.014286783523858,40131,-20223,-10776,-2858,0.990287780761719 +9553,-0.033832665532827,0.088374257087708,-0.018484035506845,40131,-20011,-10584,-2817,0.989485144615173 +9555,-0.054859977215529,0.076965220272541,-0.019285842776299,40131,-18879,-10034,-2920,0.993468999862671 +9557,-0.089894540607929,0.065469421446323,-0.022264296188951,40131,-17557,-9764,-2847,0.995638191699982 +9559,-0.133485928177834,0.0437934063375,-0.027995565906167,40131,-16138,-8838,-3027,0.997780859470367 +9561,-0.186435014009476,0.022008715197444,-0.032212235033512,40131,-15034,-8480,-2921,0.993551671504974 +9563,-0.244648590683937,0.00208410108462,-0.034583859145641,40131,-13405,-8348,-3110,0.992069840431213 +9565,-0.306003332138061,-0.018842473626137,-0.032205883413553,40131,-12810,-8012,-2927,0.992827117443085 +9567,-0.376455634832382,-0.048233363777399,-0.03334478661418,40131,-10468,-6899,-3101,0.993336856365204 +9569,-0.45578271150589,-0.082305833697319,-0.037911050021649,40131,-9409,-6193,-2973,0.988844335079193 +9571,-0.545493245124817,-0.113940611481667,-0.039792776107788,40131,-6339,-5687,-3184,0.980378806591034 +9573,-0.636699914932251,-0.154150143265724,-0.038859385997057,40131,-5918,-4725,-2987,0.970546185970306 +9575,-0.726119041442871,-0.187119424343109,-0.037150956690312,40131,-3331,-4393,-3163,0.95927882194519 +9577,-0.817534446716309,-0.215685606002808,-0.036806937307119,40131,-3177,-4645,-2980,0.957352221012116 +9579,-0.904612481594086,-0.247572541236877,-0.039194073528051,40131,-429,-3448,-3199,0.960511684417725 +9581,-0.993387877941132,-0.278995871543884,-0.043841697275639,40131,30023,5721,-3036,0.966143250465393 +9583,-1.08698511123657,-0.322169274091721,-0.049332857131958,40131,8435,199,-3335,0.970173060894012 +9585,-1.18316519260407,-0.359467417001724,-0.050372004508972,40131,8131,-244,-3091,0.96870344877243 +9587,-1.27378594875336,-0.396622180938721,-0.050477676093578,40131,11657,1105,-3371,0.966926753520966 +9589,-1.35454428195953,-0.430836796760559,-0.049113530665636,40131,9930,703,-3092,0.963480234146118 +9591,-1.43482029438019,-0.461516857147217,-0.048357449471951,40131,14014,1862,-3374,0.966510236263275 +9593,-1.50568652153015,-0.496563524007797,-0.046716690063477,40131,11912,1883,-3086,0.97139298915863 +9595,-1.56825602054596,-0.516682624816895,-0.04359819367528,40131,15456,2189,-3348,0.974890649318695 +9597,-1.6127837896347,-0.54073703289032,-0.042814459651709,40131,12149,1934,-3070,0.978762745857239 +9599,-1.64290571212769,-0.546589016914368,-0.043003510683775,40131,14938,1847,-3372,0.97955048084259 +9601,-1.67381143569946,-0.547267496585846,-0.042440820485354,40131,12674,569,-3078,0.983633160591126 +9603,-1.70115458965302,-0.562933206558228,-0.039108961820603,40131,16315,3031,-3357,0.988944411277771 +9621,-1.57861280441284,-0.551563858985901,-0.011815343983471,40131,14542,3547,-2919,1.01653683185577 +9623,-1.52980971336365,-0.537302911281586,-0.008552900515497,40131,16525,3192,-3126,1.02302646636963 +9625,-1.47714674472809,-0.519898414611816,-0.005810813046992,40131,12991,1840,-2887,1.03303122520447 +9627,-1.42586851119995,-0.487725049257278,-0.001626114593819,40131,15277,1331,-3047,1.0342583656311 +9629,-1.36518812179565,-0.462100595235825,0.005285090766847,40131,11414,637,-2818,1.03217089176178 +9631,-1.29181289672852,-0.439074993133545,0.006125429179519,40131,12086,1398,-2955,1.02241325378418 +9633,-1.21433186531067,-0.406780034303665,0.007457282394171,40131,8591,-440,-2808,1.02442276477814 +9635,-1.12724936008453,-0.379043877124786,0.010424022562802,40131,8938,267,-2893,1.02912783622742 +9637,-1.03084421157837,-0.339374631643295,0.011185806244612,40131,5075,-1768,-2787,1.03127241134644 +9639,-0.931274473667145,-0.300657987594604,0.008270356804132,40131,5283,-1636,-2894,1.03176498413086 +9641,-0.838567316532135,-0.252066433429718,0.009802893735468,40131,2965,-3527,-2800,1.0284218788147 +9643,-0.740895986557007,-0.218156114220619,0.014807222411037,40131,2664,-2499,-2786,1.02934646606445 +9645,-0.640727519989014,-0.179101839661598,0.017462007701397,40131,-109,-3792,-2749,1.02633631229401 +9647,-0.546873152256012,-0.140354618430138,0.020900059491396,40131,43,-4035,-2680,1.02758955955505 +9649,-0.455317556858063,-0.104881785809994,0.017995240166783,40131,-1941,-4538,-2745,1.02791249752045 +9651,-0.360805124044418,-0.058165289461613,0.013077426701784,40131,-2854,-5911,-2733,1.03324353694916 +9653,-0.263572812080383,-0.027500191703439,0.012715165503323,40131,-4972,-5281,-2780,1.03260767459869 +9655,-0.167145147919655,0.015342380851507,0.012762019410729,40131,24595,11384,-2700,1.02597343921661 +9657,-0.07792741060257,0.060752872377634,0.015913244336844,40131,-1848,-4540,-2757,1.02038168907166 +9659,0.000164361452335,0.110015526413918,0.020731778815389,40131,-2260,-5765,-2557,1.01814770698547 +9661,0.084531843662262,0.14363044500351,0.023597689345479,40131,-3820,-4909,-2699,1.0253404378891 +9663,0.159402057528496,0.174664437770844,0.020989999175072,40131,-4634,-5542,-2519,1.02794206142426 +9665,0.225976273417473,0.203053310513496,0.016585236415267,40131,-4636,-5442,-2741,1.03364634513855 +9667,0.300720751285553,0.231862410902977,0.017185870558024,40131,-7013,-6374,-2531,1.03234791755676 +9669,0.37270376086235,0.269652843475342,0.020430648699403,40131,-7256,-7151,-2709,1.02627563476563 +9671,0.438364177942276,0.300523906946182,0.023270646110177,40131,-8767,-7730,-2422,1.02215671539307 +9673,0.498935371637344,0.337841004133224,0.02424737252295,40131,-8443,-8209,-2674,1.02158486843109 +9675,0.557586669921875,0.363397568464279,0.025781191885471,40131,-10427,-8495,-2358,1.01958847045898 +9677,0.605106353759766,0.398328721523285,0.025162009522319,40131,-9283,-9048,-2659,1.02004039287567 +9679,0.649700522422791,0.415218323469162,0.025790257379413,40131,-11184,-8882,-2330,1.01637530326843 +9681,0.687566339969635,0.431786596775055,0.024538489058614,40131,-10069,-8382,-2653,1.01074469089508 +9683,0.718868970870972,0.44565424323082,0.021700778976083,40131,-11659,-9336,-2362,1.01261126995087 +9685,0.741733551025391,0.457872003316879,0.019966123625636,40131,-10099,-8629,-2675,1.00931906700134 +9687,0.755452930927277,0.473726719617844,0.020433245226741,40131,-11325,-10117,-2364,1.00435209274292 +9689,0.765399396419525,0.478304445743561,0.021606514230371,40131,-9859,-8572,-2654,1.00387156009674 +9691,0.766160905361176,0.48743924498558,0.018496297299862,40131,-10916,-10054,-2380,1.00277018547058 +9693,0.772507071495056,0.485806077718735,0.01405986212194,40131,20413,-8439,-2697,1.00498342514038 +9695,0.771162271499634,0.492111742496491,0.011149267666042,40131,-6047,-10135,-2464,1.00398123264313 +9697,0.757158994674683,0.48764568567276,0.013298948295415,40131,-3563,-8471,-2694,1.00462019443512 +9699,0.737949967384338,0.476869910955429,0.015644690021873,40131,-4534,-8869,-2417,1.00220513343811 +9701,0.720102250576019,0.471257507801056,0.012071025557816,40131,-3050,-8356,-2695,0.999326407909393 +9703,0.705156862735748,0.45947590470314,0.005910005420446,40131,-4587,-8711,-2538,0.992524206638336 +9705,0.688682913780212,0.447584897279739,0.006116445176303,40131,-2977,-7763,-2730,0.981991171836853 +9707,0.674450516700745,0.42780402302742,0.009886127896607,40131,-4403,-7815,-2504,0.973239779472351 +9709,0.654517650604248,0.42070284485817,0.008930820040405,40131,-2506,-7904,-2704,0.975619852542877 +9711,0.634824156761169,0.398163706064224,0.008869732730091,40131,-3620,-7311,-2526,0.986631035804748 +9713,0.614426255226135,0.369008868932724,0.006786136422306,40131,-2147,-5752,-2714,0.992934882640839 +9715,0.588233888149262,0.347406297922134,0.003280404722318,40131,-2627,-6711,-2609,1.0007860660553 +9717,0.562034845352173,0.322904795408249,0.000725031713955,40131,-1207,-5572,-2752,1.00144195556641 +9719,0.540993511676788,0.304195165634155,-0.00250805565156,40131,-2452,-6357,-2691,0.998697876930237 +9721,0.529149770736694,0.273783564567566,-0.004883246961981,40131,-1973,-4573,-2789,0.996263861656189 +9723,0.500570833683014,0.253222346305847,-0.007345051504672,40131,-1464,-5513,-2765,0.995922923088074 +9725,0.473747968673706,0.215874835848808,-0.007644604425877,40131,-299,-3351,-2807,0.988871932029724 +9727,0.451799392700195,0.178049102425575,-0.011730527505279,40131,-1328,-3146,-2841,0.978596031665802 +9729,0.431987464427948,0.143820539116859,-0.013992567546666,40131,-374,-2613,-2852,0.967327237129211 +9731,0.405430674552918,0.119522787630558,-0.012880014255643,40131,-402,-3229,-2873,0.960449576377869 +9733,0.376105308532715,0.100528962910175,-0.01335133984685,40131,957,-3130,-2849,0.966846346855164 +9735,0.347541391849518,0.076732687652111,-0.016396228224039,40131,547,-2606,-2930,0.977075636386871 +9737,0.324986606836319,0.05450202152133,-0.019176216796041,40131,1080,-2265,-2892,0.982991993427277 +9739,0.31128665804863,0.022487238049507,-0.01814947463572,40131,-53,-1152,-2968,0.987393260002136 +9741,0.298393130302429,-0.004609760362655,-0.01681180857122,40131,659,-1071,-2879,0.985064685344696 +9743,0.278666913509369,-0.025832448154688,-0.01817636564374,40131,801,-1130,-2984,0.988576889038086 +9745,0.257875889539719,-0.044870633631945,-0.022466342896223,40131,1709,-1051,-2922,0.989536583423614 +9747,0.234243884682655,-0.060195326805115,-0.024285040795803,40131,1730,-960,-3070,0.989131689071655 +9749,0.218557357788086,-0.082862906157971,-0.020623845979571,40131,1832,-208,-2915,0.985558152198792 +9751,0.206622883677483,-0.091213934123516,-0.017078123986721,40131,1283,-909,-2997,0.983412325382233 +9753,0.196210950613022,-0.113623902201653,-0.018970932811499,40131,1713,266,-2908,0.986092329025269 +9771,0.14877550303936,-0.158944293856621,-0.026234051212669,40131,1194,-46,-3146,0.98903077840805 +9773,0.144377425312996,-0.154054224491119,-0.027237702161074,40131,1813,-721,-2994,0.990974843502045 +9775,0.146674796938896,-0.146665260195732,-0.029192412272096,40131,966,-692,-3184,0.997182786464691 +9777,0.153661236166954,-0.146735608577728,-0.027637612074614,40131,826,-392,-3003,0.999374747276306 +9779,0.157779589295387,-0.142450973391533,-0.023918870836496,40131,611,-458,-3127,0.999203085899353 +9781,0.159521654248238,-0.1347416639328,-0.019293131306768,40131,1073,-1044,-2952,1.00041031837463 +9783,0.163103699684143,-0.118451029062271,-0.018123134970665,40131,506,-1638,-3058,1.0005669593811 +9785,0.172543913125992,-0.106831923127174,-0.018861792981625,40131,285,-1657,-2953,1.00497019290924 +9787,0.180228814482689,-0.095064006745815,-0.018753755837679,40131,-120,-1637,-3064,1.00267052650452 +9789,0.180932119488716,-0.076704390347004,-0.020194921642542,40131,732,-2517,-2967,1.00019156932831 +9791,0.188369527459145,-0.063263162970543,-0.020656967535615,40131,-294,-2224,-3084,0.996114909648895 +9793,0.197063505649567,-0.043183084577322,-0.020259102806449,40131,-133,-3081,-2972,0.991987943649292 +9795,0.204649120569229,-0.03556090593338,-0.019470827654004,40131,-626,-2215,-3069,0.987982332706451 +9797,0.209446847438812,-0.01789334975183,-0.016357745975256,40131,-101,-3241,-2950,0.983961403369904 +9799,0.218579441308975,-0.005267061758786,-0.011459290981293,40131,-1025,-3037,-2973,0.980886459350586 +9801,0.231018975377083,0.013054341077805,-0.011152737773955,40131,-1033,-3715,-2917,0.982940077781677 +9803,0.238695576786995,0.037682939320803,-0.010951546020806,40131,-1332,-4592,-2961,0.994037449359894 +9805,0.244009613990784,0.053829312324524,-0.009199118241668,40131,-794,-4148,-2906,0.998030543327332 +9807,0.249060943722725,0.068368181586266,-0.008980348706245,40131,-1404,-4383,-2934,0.996096074581146 +9809,0.254347831010818,0.077075719833374,-0.007352016400546,40131,-1032,-3968,-2895,0.994182765483856 +9811,0.249503239989281,0.096407726407051,-0.00492396671325,40131,-802,-5208,-2883,0.989062309265137 +9813,0.246648028492928,0.106586173176765,-0.005154090933502,40131,-433,-4529,-2881,0.99100387096405 +9815,0.250928938388824,0.115125097334385,-0.008409632369876,40131,-1565,-4777,-2923,0.990171670913696 +9817,0.252431780099869,0.132433637976646,-0.007641956675798,40131,-922,-5452,-2899,0.994695842266083 +9819,0.260113716125488,0.147924974560738,-0.005919403862208,40131,-2042,-5849,-2891,0.998455703258514 +9821,0.269480347633362,0.162680074572563,-0.007956550456584,40131,-1827,-5759,-2903,0.9968341588974 +9823,0.276909500360489,0.155516162514687,-0.008621909655631,40131,-2393,-4402,-2923,0.992778897285461 +9825,0.27149161696434,0.155116438865662,-0.004181273281574,40131,-901,-4623,-2878,0.993257284164429 +9827,0.26565945148468,0.149602591991425,-0.001642521121539,40131,-1371,-4483,-2844,0.989720821380615 +9829,0.258011549711227,0.15928527712822,-0.002920410130173,40131,-650,-5462,-2870,0.985242962837219 +9831,0.256697952747345,0.166933327913284,-0.002442859113216,40131,-1657,-5782,-2851,0.984462857246399 +9833,0.25651940703392,0.170629158616066,-0.000620266946498,40131,-1264,-5264,-2854,0.98088937997818 +9835,0.250247955322266,0.1712526679039,-0.002247167052701,40131,-1300,-5426,-2849,0.975517153739929 +9837,0.239871710538864,0.169504478573799,-0.005066254176199,40131,-393,-4929,-2885,0.978075385093689 +9839,0.241080105304718,0.170050159096718,-0.007562656886876,40131,-1780,-5466,-2914,0.984447658061981 +9841,0.244370132684708,0.160699754953384,-0.005988467019051,40131,-1531,-4328,-2893,0.992202460765839 +9843,0.237606629729271,0.157599464058876,-0.0054648257792,40131,-1243,-5063,-2893,0.989227712154388 +9845,0.218357041478157,0.162349134683609,-0.005949134007096,40131,363,-5426,-2893,0.986498296260834 +9847,0.205301001667976,0.156950831413269,-0.00508514419198,40131,-354,-4945,-2891,0.985333383083344 +9849,0.200401052832603,0.152978897094727,-0.005017224699259,40131,-486,-4730,-2888,0.987177610397339 +9851,0.195004597306252,0.136636778712273,-0.00489534670487,40131,-812,-3892,-2893,0.987601220607758 +9853,0.179915145039558,0.132004931569099,-0.002886124886572,40131,463,-4436,-2874,0.990468800067902 +9855,0.173144280910492,0.121130965650082,-0.000390207627788,40131,-426,-4090,-2843,0.992628395557404 +9857,0.168038621544838,0.120484009385109,-0.00046014651889,40131,-146,-4606,-2858,0.995626389980316 +9859,0.163726344704628,0.110129617154598,-0.002085596788675,40131,-506,-3984,-2866,1.00126051902771 +9861,0.159306615591049,0.094798587262631,-0.006456352770329,40131,-130,-3227,-2900,1.00216734409332 +9863,0.149920225143433,0.087613418698311,-0.008227427490056,40131,30,-3873,-2942,0.996818661689758 +9865,0.143698841333389,0.079223036766052,-0.007845318876207,40131,168,-3531,-2911,0.991870582103729 +9867,0.139190822839737,0.077071823179722,-0.008745664730668,40131,-201,-4086,-2952,0.986601710319519 +9869,0.139045730233192,0.058920279145241,-0.007804096210748,40131,-249,-2566,-2913,0.99079692363739 +9871,0.132537811994553,0.050536278635264,-0.007592902518809,40131,-2,-3242,-2943,0.99264007806778 +9873,0.123461492359638,0.051480866968632,-0.009229118004441,40131,565,-3842,-2925,0.998464941978455 +9875,0.119944356381893,0.050639063119888,-0.01071956846863,40131,-63,-3819,-2982,0.999934315681458 +9877,0.116785563528538,0.045578829944134,-0.007114991080016,40131,194,-3347,-2913,1.00342679023743 +9879,0.112300492823124,0.030545188114047,-0.00231114262715,40131,79,-2484,-2887,1.00580441951752 +9881,0.103966504335403,0.029027059674263,-0.001737164217047,40131,707,-3372,-2877,1.00734317302704 +9883,0.101406656205654,0.024078134447336,-0.001108279568143,40131,75,-3097,-2875,1.00692129135132 +9885,0.095744773745537,0.027983319014311,-0.003646904369816,40131,595,-3749,-2891,1.00735414028168 +9887,0.092808715999127,0.021607808768749,-0.00628721062094,40131,224,-2955,-2938,1.00920414924622 +9889,0.094170682132244,0.013454089872539,-0.009052068926394,40131,84,-2679,-2930,1.00836932659149 +9891,0.097899436950684,0.011679835617542,-0.010231113992632,40131,-348,-3122,-2988,1.00873005390167 +9893,0.098425872623921,0.005752158816904,-0.008389696478844,40131,52,-2726,-2928,1.00756204128265 +9895,0.091359093785286,0.00355625897646,-0.004393918905407,40131,494,-2957,-2922,1.00872445106506 +9897,0.090486392378807,-0.006876601837575,-0.000466303550638,40131,237,-2216,-2875,1.0067902803421 +9899,0.090452335774899,-0.007742601446807,-0.001176563091576,40131,-32,-2866,-2886,1.00254654884338 +9901,0.092449299991131,-0.015057422220707,-0.001494055031799,40131,-27,-2311,-2883,0.997990965843201 +9903,0.090210780501366,-0.012560312636197,-0.002714609261602,40131,98,-3025,-2906,0.986347496509552 +9905,0.085594519972801,-0.010385355912149,-0.00478510838002,40131,514,-3047,-2907,0.985466659069061 +9907,0.088210888206959,-0.020669091492891,-0.004506482277066,40131,-237,-1961,-2930,0.987322270870209 +9909,0.087686836719513,-0.028032502159476,-0.00711775617674,40131,162,-2095,-2925,0.98760724067688 +9911,0.086660586297512,-0.035591807216406,-0.009505216963589,40131,20,-1889,-2992,0.988286674022675 +9913,0.084739565849304,-0.031550992280245,-0.008001365698874,40131,277,-2838,-2933,0.988159120082855 +9915,0.093883462250233,-0.04194913059473,-0.00696037337184,40131,-868,-1563,-2965,0.985551178455353 +9917,0.093912944197655,-0.041740886867046,-0.006649750284851,40131,-28,-2392,-2926,0.98172789812088 +9919,0.088440783321858,-0.03359941765666,-0.003516162279993,40131,226,-3005,-2925,0.986606597900391 +9921,0.093031004071236,-0.032161489129067,-0.001515583950095,40131,-375,-2595,-2893,0.988333165645599 +9923,0.104124635457993,-0.037816096097231,-0.000734405999538,40131,-1244,-1931,-2894,0.988640606403351 +9925,0.106767170131207,-0.050162743777037,0.002432361943647,40131,-472,-1327,-2867,0.988379895687103 +9927,0.096370883285999,-0.039008036255837,0.005109017249197,40131,393,-3089,-2826,0.991364479064941 +9929,0.095086358487606,-0.034194983541966,0.002122530713677,40131,-58,-2761,-2869,0.994643986225128 +9931,0.104133911430836,-0.024401728063822,0.001237206743099,40131,-1155,-3197,-2871,0.992744088172913 +9933,0.11419689655304,-0.016493059694767,0.005398065783083,40131,-1182,-3217,-2847,0.992286682128906 +9935,0.114455237984657,-0.01315587759018,0.007592380978167,40131,-737,-2903,-2795,0.983718156814575 +9937,0.107964962720871,-0.006834744475782,0.004699098411947,40131,49,-3228,-2851,0.975662052631378 +9939,0.100683964788914,-0.000411152286688,0.000779512047302,40131,-22,-3321,-2874,0.973072111606598 +9941,0.101368993520737,0.00441331975162,0.000372805487132,40131,-408,-3275,-2882,0.973252713680267 +9943,0.10951479524374,0.0007101019728,0.001068969490007,40131,-1313,-2608,-2871,0.9771329164505 +9945,0.117269061505795,0.009103076532483,0.000531623023562,40131,-1186,-3591,-2881,0.978020489215851 +9947,0.124049313366413,0.017932076007128,0.000931261631195,40131,-1496,-3787,-2872,0.982720255851746 +9949,0.127519533038139,0.026570577174425,-8.6676845967304E-06,40131,-1076,-3861,-2886,0.987616002559662 +9951,0.1237663179636,0.036589447408915,-0.001838646247052,40131,-787,-4170,-2905,0.992428004741669 +9953,0.118085220456123,0.029820643365383,0.000329560483806,40131,-336,-2812,-2884,0.994061350822449 +9955,0.117044240236282,0.032538030296564,0.001154112862423,40131,-916,-3582,-2871,0.993941247463226 +9957,0.122750289738178,0.036382038146257,0.001975335646421,40131,-1265,-3672,-2874,0.994828164577484 +9959,0.125805124640465,0.053246054798365,0.003663764335215,40131,-1402,-4945,-2840,0.998450338840485 +9961,0.128697201609611,0.055346477776766,0.002933677053079,40131,-1201,-3835,-2867,1.00136590003967 +9963,0.130218297243118,0.053570937365294,0.00314828241244,40131,-1412,-3635,-2847,0.99979829788208 +9965,0.122690245509148,0.056817717850208,0.000944546249229,40131,-421,-3955,-2881,0.997402906417847 +9967,0.111137583851814,0.059998046606779,-0.002174263820052,40131,-212,-4111,-2910,0.995507597923279 +9969,0.105957522988319,0.070507004857063,-0.00451176892966,40131,-394,-4692,-2920,0.992798686027527 +9971,0.108294196426868,0.069673493504524,-0.007756312377751,40131,-1207,-3999,-2977,0.991142213344574 +9973,0.105551175773144,0.073351986706257,-0.009396761655808,40131,-606,-4267,-2955,0.990906178951263 +9975,0.106602922081947,0.067220985889435,-0.006367536261678,40131,-1137,-3601,-2963,0.989578783512116 +9977,0.106133490800858,0.064284421503544,-0.004059952218086,40131,-822,-3686,-2920,0.987667500972748 +9979,0.098416425287724,0.069060303270817,-0.001728418283165,40131,-414,-4441,-2910,0.994143843650818 +9981,0.087379977107048,0.072503082454205,-0.000448284379672,40131,163,-4285,-2897,0.997173309326172 +9983,0.078641273081303,0.081619672477245,0.001102551585063,40131,-63,-4991,-2876,0.995749294757843 +9997,0.067187182605267,0.076160699129105,-0.003946427255869,40131,-409,-4277,-2925,0.992887854576111 +9999,0.068192966282368,0.063514158129692,-0.00281667849049,40131,-677,-3241,-2929,0.98965048789978 +10001,0.061023402959108,0.064057804644108,-0.004441367462277,40131,121,-4101,-2929,0.989542186260223 +10003,0.053521696478129,0.052655715495348,-0.001982027897611,40131,134,-3178,-2920,0.991393983364105 +10005,0.047442451119423,0.049349259585142,0.001708199968562,40131,218,-3632,-2888,0.991216421127319 +10007,0.044614318758249,0.053148187696934,0.003375842701644,40131,-93,-4309,-2858,0.991556107997894 +10009,0.043423511087895,0.053413689136505,0.006709250621498,40131,-92,-3967,-2854,0.986144185066223 +10011,0.037624858319759,0.05662090331316,0.00991187710315,40131,216,-4346,-2780,0.985027313232422 +10013,0.033740878105164,0.050447087734938,0.012178069911897,40131,222,-3485,-2815,0.986334383487701 +10015,0.032673634588719,0.047592289745808,0.011235926300287,40131,-46,-3773,-2764,0.988846480846405 +10017,0.032527260482311,0.038691833615303,0.012311512604356,40131,-39,-3138,-2813,0.991731107234955 +10019,0.026002153754234,0.034922353923321,0.009781121276319,40131,447,-3509,-2781,0.989780247211456 +10021,0.016100542619824,0.030343415215612,0.009181812405586,40131,887,-3337,-2834,0.991215825080872 +10023,0.015898557379842,0.022828390821815,0.011208017356694,40131,148,-3046,-2763,0.988709092140198 +10025,0.018570002168417,0.020129529759288,0.014051828533411,40131,-53,-3329,-2799,0.988771736621857 +10027,0.020112678408623,0.006572488695383,0.015598369762302,40131,-50,-2361,-2711,0.98728996515274 +10029,0.01670778170228,-0.000343018356944,0.014999563805759,40131,402,-2731,-2791,0.985496342182159 +10031,0.018248030915856,-0.008283954113722,0.013255635276437,40131,-24,-2525,-2737,0.984980940818787 +10033,0.014261283911765,-0.003064600983635,0.012289746664465,40131,474,-3554,-2808,0.987935781478882 +10035,0.004967323504388,0.002622287487611,0.012388174422085,40131,969,-3664,-2746,0.995162904262543 +10037,0.000443595286924,-0.000413994072005,0.013219028711319,40131,712,-2996,-2801,0.997095584869385 +10039,-0.003430018899962,-0.005837140139192,0.013616648502648,40131,724,-2721,-2731,0.99660736322403 +10041,0.000397349795094,-0.017119655385614,0.01425816398114,40131,120,-2157,-2792,0.997974634170532 +10043,0.008688659407198,-0.018996233120561,0.015720082446933,40131,-343,-2742,-2705,0.998132884502411 +10045,0.018771829083562,-0.04005853459239,0.017668597400189,40131,-591,-1111,-2767,0.997899770736694 +10047,0.011826138943434,-0.044748075306416,0.018385631963611,40131,696,-2102,-2672,0.995722055435181 +10049,0.011525882408023,-0.045961182564497,0.02027958072722,40131,254,-2420,-2747,1.00214302539825 +10051,0.021565400063992,-0.040006946772337,0.018482018262148,40131,-692,-2923,-2668,1.00441896915436 +10053,0.036618202924728,-0.034998048096895,0.015212321653962,40131,-1213,-2999,-2779,1.00382673740387 +10055,0.039679799228907,-0.036522854119539,0.01580734923482,40131,-499,-2422,-2698,0.998666822910309 +10057,0.036828011274338,-0.038395036011934,0.018989861011505,40131,50,-2435,-2751,0.991321742534637 +10059,0.035974282771349,-0.041664201766253,0.021412573754788,40131,-175,-2188,-2629,0.986290633678436 +10061,0.041883748024702,-0.027612429112196,0.020759042352438,40131,-665,-3705,-2736,0.98464423418045 +10063,0.052624091506004,-0.022131623700261,0.023753855377436,40131,-1292,-3114,-2598,0.98999160528183 +10065,0.056331444531679,-0.023287938907743,0.024194190278649,40131,-737,-2662,-2709,0.990339696407318 +10067,0.054526675492525,-0.028295526280999,0.020979909226298,40131,-443,-2243,-2628,0.990529239177704 +10069,0.059424228966236,-0.032662466168404,0.020153472200036,40131,-889,-2278,-2735,0.990100800991058 +10071,0.062928602099419,-0.022510822862387,0.021601624786854,40131,-981,-3399,-2618,0.9911989569664 +10073,0.064596056938171,-0.022568106651306,0.021602541208267,40131,-758,-2713,-2722,0.992532074451446 +10075,0.065182201564312,-0.017927542328835,0.02095628157258,40131,-837,-3063,-2623,0.989858865737915 +10077,0.071110889315605,-0.024247080087662,0.023898111656308,40131,-1185,-2225,-2703,0.982823014259338 +10079,0.073349446058273,-0.022885337471962,0.026005517691374,40131,-1115,-2739,-2560,0.971532881259918 +10081,0.074247218668461,-0.016519071534276,0.024484526365996,40131,-901,-3228,-2696,0.972796499729156 +10083,0.080694168806076,-0.016073606908321,0.020950205624104,40131,-1566,-2770,-2616,0.979703307151794 +10085,0.081365399062634,-0.006392661016434,0.019716493785381,40131,-1021,-3598,-2726,0.989611327648163 +10087,0.077797867357731,0.003812157781795,0.020717056468129,40131,-839,-3789,-2616,0.994040429592133 +10089,0.070956125855446,0.02350439503789,0.019237101078034,40131,-367,-4741,-2726,0.996085345745087 +10091,0.073579929769039,0.027852592989802,0.015317678451538,40131,-1266,-3766,-2676,0.997981369495392 +10093,0.08080880343914,0.031088942661882,0.011546693742275,40131,-1552,-3680,-2777,0.995634436607361 +10095,0.08271437138319,0.036277133971453,0.009560598060489,40131,-1403,-3969,-2742,0.99887228012085 +10097,0.081061959266663,0.042420607060194,0.012179709039629,40131,-960,-4062,-2772,1.00001180171967 +10099,0.07429925352335,0.050527978688479,0.014983043074608,40131,-660,-4420,-2677,0.996092140674591 +10101,0.068819627165794,0.043962981551886,0.015870472416282,40131,-543,-3192,-2745,0.99195659160614 +10103,0.060733091086149,0.052096553146839,0.018885651603341,40131,-362,-4460,-2630,0.989864945411682 +10105,0.063324086368084,0.045455206185579,0.017116520553827,40131,-1067,-3225,-2734,0.990506410598755 +10107,0.068367026746273,0.042778789997101,0.009335787966847,40131,-1458,-3549,-2740,0.987520158290863 +10109,0.069137275218964,0.045807257294655,0.008328748866916,40131,-1049,-3936,-2793,0.991284072399139 +10111,0.064051605761051,0.049609363079071,0.012865975499153,40131,-710,-4148,-2697,0.99298882484436 +10113,0.058933045715094,0.056483518332243,0.014146093279123,40131,-512,-4383,-2752,0.992079019546509 +10115,0.059067852795124,0.058590389788151,0.015655426308513,40131,-1039,-4198,-2663,0.991398990154266 +10117,0.061792016029358,0.062203243374825,0.018882997334004,40131,-1144,-4255,-2717,0.992186367511749 +10119,0.065081283450127,0.052578959614039,0.024305582046509,40131,-1384,-3283,-2559,0.991750240325928 +10121,0.06524109095335,0.048977762460709,0.025771383196116,40131,-1041,-3569,-2667,0.98949408531189 +10123,0.061235703527927,0.054905869066715,0.018566146492958,40131,-822,-4450,-2623,0.987875521183014 +10125,0.057859029620886,0.06016556546092,0.013657200150192,40131,-710,-4386,-2748,0.987092554569244 +10127,0.050167478621006,0.060819573700428,0.013669707812369,40131,-399,-4174,-2679,0.990724623203278 +10129,0.047459926456213,0.049748715013266,0.017460539937019,40131,-631,-3087,-2720,0.99163681268692 +10149,0.009140025824308,-0.022292187437415,0.019990678876638,40131,-271,-2023,-2690,0.989827811717987 +10151,0.00765566341579,-0.027926225215197,0.021165583282709,40131,-215,-2330,-2578,0.993843853473663 +10153,0.013178016990423,-0.033532701432705,0.022046053782106,40131,-783,-2302,-2673,0.996550977230072 +10155,0.015022920444608,-0.032326903194189,0.024450505152345,40131,-584,-2736,-2536,1.00290441513062 +10157,0.011279996484518,-0.038529358804226,0.025765784084797,40131,-100,-2169,-2644,1.00418543815613 +10159,0.009550397284329,-0.033518124371767,0.027011124417186,40131,-247,-2966,-2502,1.00230598449707 +10161,0.017371486872435,-0.040647953748703,0.027728419750929,40131,-1021,-2052,-2627,0.995431542396545 +10163,0.02193752489984,-0.043949950486422,0.03041585162282,40131,-904,-2864,-2581,0.98377937078476 +10165,0.019043682143092,-0.039602391421795,0.033747099339962,40131,-288,-2475,-2440,0.987335801124573 +10167,0.017025124281645,-0.039394721388817,0.031546737998724,40131,-363,-2475,-2440,0.987335801124573 +10169,0.017362611368299,-0.025370853021741,0.028063286095858,40131,-658,-3226,-2476,0.997427642345428 +10171,0.017362611368299,-0.025370853021741,0.028063286095858,40131,-658,-3226,-2476,0.997427642345428 +10173,0.025291789323092,-0.023764919489622,0.032871395349503,40131,-1082,-1932,-2415,0.994198501110077 +10175,0.024237779900432,-0.025440081954002,0.031814347952604,40131,-524,-2577,-2581,0.987743020057678 +10177,0.017413811758161,-0.01637464016676,0.030593652278185,40131,-61,-3430,-2437,0.990939259529114 +10179,0.016015665605664,-0.013960821554065,0.030486345291138,40131,-391,-3021,-2586,0.988215506076813 +10181,0.016015665605664,-0.013960821554065,0.030486345291138,40131,-391,-3021,-2586,0.988215506076813 +10183,0.03247619047761,-0.037116020917893,0.025769332423806,40131,-1283,-1400,-2614,0.979439437389374 +10185,0.028877774253488,-0.032028406858444,0.024694362655282,40131,-500,-2864,-2498,0.983798444271088 +10187,0.028071260079742,-0.025551589205861,0.027119666337967,40131,-635,-3110,-2601,0.997462749481201 +10189,0.031603999435902,-0.014717682264745,0.026104707270861,40131,-1070,-3539,-2478,1.00193679332733 +10191,0.031603999435902,-0.014717682264745,0.026104707270861,40131,-1070,-3539,-2478,1.00193679332733 +10193,0.038093861192465,-0.015289781615138,0.024039568379521,40131,-1180,-2701,-2499,0.999744951725006 +10195,0.040018416941166,-0.013713694177568,0.026090189814568,40131,-1038,-2904,-2601,0.991424739360809 +10197,0.041771974414587,-0.011866846121848,0.02579185180366,40131,-1154,-2913,-2475,0.989153146743774 +10199,0.043623752892017,-0.000972474634182,0.026365958154202,40131,-1107,-3743,-2595,0.991706490516663 +10201,0.043623752892017,-0.000972474634182,0.026365958154202,40131,-1107,-3743,-2595,0.991706490516663 +10203,0.047591593116522,0.006570173893124,0.022310601547361,40131,-1216,-3308,-2619,0.995970666408539 +10205,0.048957530409098,0.007124387193471,0.023302752524614,40131,-1260,-3111,-2497,0.995987355709076 +10207,0.049224324524403,0.007601668592542,0.027061279863119,40131,-1116,-3110,-2583,0.999040782451629 +10209,0.041813604533672,0.019294926896691,0.030743492767215,40131,-548,-4109,-2405,1.00646448135376 +10211,0.037463266402483,0.020372465252876,0.031937211751938,40131,-637,-3338,-2545,1.00731575489044 +10213,0.037624265998602,0.025924310088158,0.031342521309853,40131,-1054,-3793,-2394,1.00767171382904 +10215,0.047965783625841,0.022017471492291,0.032345723360777,40131,-1861,-3012,-2538,1.00161242485046 +10217,0.051547080278397,0.024235351011157,0.03112336806953,40131,-1548,-3543,-2392,0.99487966299057 +10219,0.047105073928833,0.032818708568812,0.025352794677019,40131,-816,-4070,-2581,0.994833886623383 +10221,0.043841451406479,0.039052072912455,0.018637897446752,40131,-953,-4074,-2535,0.996802091598511 +10223,0.03983236849308,0.038276866078377,0.01546860858798,40131,-766,-3492,-2647,0.995126485824585 +10225,0.039870157837868,0.032782398164272,0.017074706032872,40131,-1136,-3137,-2551,0.993186771869659 +10227,0.034874171018601,0.039689242839813,0.018659522756934,40131,-643,-4073,-2623,0.992143630981445 +10229,0.025880437344313,0.039371944963932,0.0191909968853,40131,-282,-3614,-2524,0.992959856987 +10231,0.018756542354822,0.037823736667633,0.019969806075096,40131,-273,-3451,-2611,0.993550717830658 +10233,0.011444113217294,0.045273654162884,0.022326277568936,40131,-185,-4285,-2484,0.996473670005798 +10235,0.012171475216746,0.05083791539073,0.023754959926009,40131,-749,-4162,-2582,0.992923438549041 +10237,0.012855496257544,0.05868124216795,0.021199371665716,40131,-789,-4563,-2494,0.990551710128784 +10239,0.011517461389303,0.053850989788771,0.020729223266244,40131,-600,-3484,-2600,0.99009495973587 +10241,0.001765041262843,0.050007417798042,0.021268166601658,40131,132,-3601,-2491,0.992675244808197 +10243,-0.007197762839496,0.035302046686411,0.022203803062439,40131,210,-2529,-2586,0.996653318405151 +10245,-0.013208875432611,0.029223563149572,0.022666532546282,40131,108,-3110,-2471,0.997184753417969 +10247,-0.021034348756075,0.039729043841362,0.022880408912897,40131,331,-4407,-2579,0.997393250465393 +10249,-0.027907835319638,0.044975880533457,0.024029292166233,40131,411,-4185,-2451,1.00090634822845 +10251,-0.034807056188583,0.044545460492373,0.024179527536035,40131,472,-3707,-2566,1.00143539905548 +10253,-0.030151730403304,0.026870530098677,0.021797671914101,40131,-366,-2262,-2474,1.00312101840973 +10255,-0.031875118613243,0.025244807824493,0.021852869540453,40131,70,-3352,-2579,1.002650141716 +10257,-0.038909677416086,0.025228036567569,0.028162045404315,40131,622,-3508,-2396,1.00718915462494 +10259,-0.041064601391554,0.021587416529656,0.028432277962566,40131,247,-3161,-2530,1.0067925453186 +10261,-0.034909382462502,0.021089347079396,0.026662955060601,40131,-370,-3410,-2409,1.00357794761658 +10263,-0.034238431602717,0.025242483243346,0.027846328914166,40131,-39,-3776,-2530,0.999107718467712 +10265,-0.041991353034973,0.033149752765894,0.026220507919788,40131,755,-4211,-2411,0.998475313186646 +10267,-0.042738121002913,0.020490219816566,0.024208322167397,40131,200,-2512,-2551,0.997479915618896 +10269,-0.039437733590603,0.011450045742095,0.025197496637702,40131,-62,-2652,-2419,1.00045502185822 +10271,-0.029897686094046,0.007450462318957,0.02651103772223,40131,-705,-2946,-2531,1.00694346427917 +10273,-0.022021092474461,0.011441784910858,0.02444207854569,40131,-654,-3587,-2424,1.00738143920898 +10275,-0.020004197955132,0.018542503938079,0.01880269870162,40131,-299,-3900,-2581,1.00464689731598 +10277,-0.018379515036941,0.017870295792818,0.016958016902208,40131,-264,-3359,-2509,0.999785959720612 +10279,-0.0167355556041,0.010405254550278,0.02191760763526,40131,-313,-2743,-2557,0.992698311805725 +10281,-0.016156477853656,-0.003590586362407,0.02506492100656,40131,-225,-2058,-2411,0.990132391452789 +10283,-0.014935075305402,-0.004276551771909,0.023618131875992,40131,-305,-3012,-2542,0.988038659095764 +10285,-0.014372485689819,0.001656251377426,0.02400422282517,40131,-247,-3565,-2420,0.991413176059723 +10287,-0.010911771096289,0.006054595578462,0.025502264499664,40131,-519,-3520,-2525,0.993210196495056 +10289,-0.006375332828611,0.018294662237167,0.023629011586309,40131,-659,-4288,-2421,0.998061656951904 +10291,-0.00201447494328,0.013270194642246,0.022535424679518,40131,-711,-2953,-2542,1.00363647937775 +10293,-0.007498119957745,0.006834851577878,0.023818358778954,40131,79,-2762,-2415,1.00824201107025 +10295,-0.007549038622528,-0.008269122801721,0.02673576399684,40131,-315,-1920,-2510,1.00579130649567 +10297,-0.00564811239019,-0.005795792210847,0.024123653769493,40131,-485,-3189,-2408,0.999018728733063 +10299,0.006848409306258,-0.000482829840621,0.020634042099118,40131,-1421,-3486,-2548,0.995650589466095 +10301,0.023822490125895,0.002835319144651,0.021011605858803,40131,-2054,-3387,-2441,0.986125409603119 +10303,0.026198044419289,0.006939385086298,0.023708717897534,40131,-989,-3502,-2524,0.9757159948349 +10305,0.020795019343495,0.003772799391299,0.025343768298626,40131,-409,-2937,-2387,0.976481199264526 +10307,0.020000720396638,0.003824963234365,0.023294106125832,40131,-686,-3165,-2523,0.98194545507431 +10309,0.03306582942605,0.001330353785306,0.020012941211462,40131,-1940,-2946,-2446,0.989316761493683 +10311,0.042866811156273,0.005750339478254,0.018205991014838,40131,-1790,-3503,-2555,0.996920466423035 +10313,0.044109798967838,0.008199595846236,0.019357103854418,40131,-1308,-3409,-2451,1.00363159179688 +10315,0.046755474060774,0.004217363893986,0.021549547091127,40131,-1358,-2878,-2529,1.00510144233704 +10317,0.048001606017351,0.010311339050531,0.02231926843524,40131,-1391,-3700,-2413,1.00367343425751 +10319,0.05118191242218,0.012612115591765,0.021621279418469,40131,-1486,-3449,-2526,1.00053668022156 +10321,0.050713561475277,0.023603523150086,0.021621799096465,40131,-1321,-4265,-2418,0.995799243450165 +10323,0.05151166766882,0.013009517453611,0.023653518408537,40131,-1344,-2536,-2509,0.992555201053619 +10325,0.048947215080261,0.007704884279519,0.023744970560074,40131,-1161,-2840,-2390,0.991803348064423 +10327,0.049078479409218,0.014084286056459,0.022599855437875,40131,-1285,-3765,-2512,0.999275326728821 +10329,0.054462194442749,0.016459280624986,0.021692149341107,40131,-1854,-3526,-2411,1.01044249534607 +10331,0.05699535086751,0.014707636088133,0.020614847540856,40131,-1597,-3193,-2523,1.01189649105072 +10333,0.05501264706254,0.009490012191236,0.019349908456206,40131,-1375,-2869,-2435,1.00731325149536 +10335,0.046350777149201,0.017685750499368,0.019934546202421,40131,-672,-3946,-2525,1.00322723388672 +10337,0.040267869830132,0.021422669291496,0.021743854507804,40131,-869,-3709,-2404,0.999689757823944 +10339,0.039832755923271,0.022112239152193,0.022314736619592,40131,-1191,-3476,-2505,0.996492445468903 +10341,0.040421448647976,0.023075897246599,0.021874472498894,40131,-1361,-3547,-2400,0.98963874578476 +10343,0.035559754818678,0.022678203880787,0.02191873639822,40131,-834,-3412,-2505,0.984564960002899 +10345,0.032108541578055,0.015107808634639,0.02095608599484,40131,-953,-2810,-2407,0.987294971942902 +10347,0.035714626312256,-0.00087625294691,0.019755681976676,40131,-1460,-1960,-2516,0.990631759166718 +10349,0.031700875610113,-0.000404625287047,0.01933915168047,40131,-928,-3135,-2423,0.995487570762634 +10351,0.026606753468514,-0.002986798528582,0.019688433036208,40131,-725,-2885,-2514,1.00055885314941 +10353,0.018417034298182,-0.000673055881634,0.018555255606771,40131,-432,-3259,-2430,0.998498618602753 +10355,0.008574147708714,-0.002552724210545,0.018414493650198,40131,-138,-2936,-2520,0.996638476848602 +10357,0.002681829733774,-0.003723679576069,0.01885555498302,40131,-346,-2950,-2423,0.996579587459564 +10359,0.001235072151758,-0.001500357408077,0.019332572817803,40131,-639,-3239,-2511,0.995571136474609 +10361,-0.000212496321183,-0.008841670118272,0.018168384209275,40131,-616,-2416,-2429,0.9945307970047 +10363,-0.006281557958573,-0.010886752977967,0.016122395172715,40131,-202,-2789,-2531,0.989155352115631 +10379,-0.035084035247564,-0.013616281561554,0.021742036566138,40131,-103,-2225,-2482,0.99757730960846 +10381,-0.035041503608227,-0.017643922939897,0.01911048963666,40131,-120,-2464,-2405,0.991869926452637 +10383,-0.036376375705004,-0.007361306343228,0.018697753548622,40131,-60,-3667,-2500,0.989376425743103 +10385,-0.035803165286779,-0.000669628905598,0.020325601100922,40131,-143,-3501,-2387,0.989881157875061 +10387,-0.032604169100523,0.002730771899223,0.019784044474363,40131,-427,-3315,-2489,0.992301344871521 +10389,-0.027571884915233,-0.000641464139335,0.021228695288301,40131,-581,-2776,-2374,0.999041736125946 +10391,-0.028198389336467,0.005388545803726,0.021480798721314,40131,-208,-3537,-2474,1.00437188148499 +10393,-0.028072619810701,0.012449478730559,0.021519837900996,40131,-202,-3727,-2367,1.00876033306122 +10395,-0.026632782071829,0.013047655113041,0.019180990755558,40131,-367,-3258,-2487,1.00670254230499 +10397,-0.028532514348626,0.016633464023471,0.017043823376298,40131,-39,-3544,-2417,1.0016462802887 +10399,-0.024656808003783,0.019642427563667,0.019043609499931,40131,-559,-3528,-2486,0.997288107872009 +10401,-0.022291354835034,0.029689427465201,0.018723659217358,40131,-438,-4229,-2395,0.991209328174591 +10403,-0.018041642382741,0.020782308652997,0.018541172146797,40131,-673,-2699,-2486,0.985956609249115 +10405,-0.020592734217644,0.02029355801642,0.021497113630176,40131,-112,-3342,-2359,0.980795681476593 +10407,-0.022775433957577,0.024910321459174,0.024745903909206,40131,-138,-3734,-2440,0.984276235103607 +10409,-0.015403284691274,0.020458994433284,0.024365313351154,40131,-918,-3077,-2322,0.988206326961517 +10411,-0.003054696368054,0.01927668787539,0.022721981629729,40131,-1460,-3246,-2451,0.994571685791016 +10413,0.003697578562424,0.02224568463862,0.021358352154493,40131,-1181,-3642,-2354,0.998261272907257 +10415,-0.003351934952661,0.035970285534859,0.017439465969801,40131,-73,-4562,-2484,1.00106203556061 +10417,-0.001769698690623,0.036951165646315,0.01516286469996,40131,-723,-3741,-2424,0.999547183513641 +10419,0.003843419253826,0.038208942860365,0.014965688809753,40131,-1087,-3716,-2499,0.993372619152069 +10421,0.003842066274956,0.037917949259281,0.012833532877266,40131,-699,-3672,-2450,0.996608674526215 +10423,0.004484639503062,0.033637151122093,0.013275460340083,40131,-745,-3266,-2508,1.00128448009491 +10425,0.006473933812231,0.03829762339592,0.012949289754033,40131,-878,-4055,-2447,1.00421929359436 +10427,0.014630630612373,0.039697270840407,0.010142100974918,40131,-1433,-3775,-2528,1.00979733467102 +10429,0.018392788246274,0.046079285442829,0.009118054993451,40131,-1212,-4329,-2491,1.01478934288025 +10431,0.01869716309011,0.04420430585742,0.012773191556335,40131,-939,-3625,-2509,1.01965987682343 +10433,0.016981355845928,0.048200447112322,0.013158015906811,40131,-820,-4202,-2441,1.01758086681366 +10435,0.018032897263765,0.051451314240694,0.013747139833868,40131,-996,-4116,-2501,1.01543521881104 +10437,0.020318172872067,0.047665044665337,0.019306428730488,40131,-1174,-3645,-2367,1.01203656196594 +10439,0.017793679609895,0.047656662762165,0.020802265033126,40131,-750,-3845,-2449,1.00768506526947 +10441,0.015608823858202,0.039498135447502,0.018992671743035,40131,-781,-3216,-2368,1.00662064552307 +10443,0.012247557751834,0.041356086730957,0.019055917859078,40131,-621,-3903,-2458,1.01091134548187 +10445,0.013995574787259,0.042196497321129,0.022704608738422,40131,-1050,-3920,-2321,1.01619017124176 +10447,0.019131576642394,0.041576318442822,0.024097016081214,40131,-1338,-3744,-2420,1.01856088638306 +10449,0.018845986574888,0.042664285749197,0.023184226825833,40131,-998,-3964,-2312,1.01679754257202 +10451,0.016281146556139,0.037383574992418,0.022830838337541,40131,-759,-3366,-2425,1.01419305801392 +10453,0.014161169528961,0.034659694880247,0.024071924388409,40131,-801,-3569,-2298,1.01145696640015 +10455,0.01683277823031,0.028244968503714,0.023521760478616,40131,-1153,-3165,-2417,1.00840365886688 +10457,0.015629816800356,0.02867528423667,0.018596835434437,40131,-893,-3706,-2359,1.00399780273438 +10459,0.012148274108768,0.022324619814754,0.017025623470545,40131,-655,-3093,-2459,1.0018492937088 +10461,0.006437613628805,0.016626574099064,0.019000729545951,40131,-427,-3082,-2351,0.999971151351929 +10463,0.000278523715679,0.014235042966902,0.020899850875139,40131,-298,-3265,-2429,1.00385844707489 +10465,0.001680474029854,0.006148159038275,0.021653240546584,40131,-870,-2744,-2317,1.00474238395691 +10467,0.0002129094064,0.006468704435974,0.021111648529768,40131,-638,-3347,-2425,1.00133085250855 +10469,-0.003463491797447,0.001160784391686,0.021871998906136,40131,-424,-2868,-2311,0.99703586101532 +10471,-0.010119376704097,-0.002965700812638,0.022277817130089,40131,-120,-2892,-2413,0.995014488697052 +10473,-0.008526898920536,-0.011228441260755,0.021993162110448,40131,-721,-2448,-2306,1.00038850307465 +10475,-0.003834238741547,-0.02224363014102,0.022409271448851,40131,-1022,-2114,-2409,1.00440239906311 +10477,-0.006578017026186,-0.025662029162049,0.020189817994833,40131,-433,-2547,-2324,1.00528454780579 +10479,-0.011345685459673,-0.027110302820802,0.01918332837522,40131,-236,-2714,-2428,1.00486862659454 +10481,-0.018567061051726,-0.022934805601835,0.02101937495172,40131,83,-3116,-2311,1.00156986713409 +10483,-0.013843079097569,-0.034625198692083,0.023656968027353,40131,-874,-1858,-2394,0.999147593975067 +10485,-0.010195643641055,-0.036120437085629,0.019718639552593,40131,-834,-2477,-2323,0.99935394525528 +10487,-0.015606962144375,-0.032577726989985,0.018120402470231,40131,-121,-2958,-2429,1.00073027610779 +10489,-0.020265318453312,-0.03304523602128,0.01859912276268,40131,-76,-2586,-2333,0.998728156089783 +10491,-0.015575573779643,-0.02823381498456,0.022798955440521,40131,-841,-3092,-2394,0.998920500278473 +10493,-0.009685843251646,-0.029084959998727,0.025316523388028,40131,-997,-2602,-2251,1.00312507152557 +10495,-0.011551742441952,-0.027268726378679,0.020872805267572,40131,-428,-2874,-2404,1.01003539562225 +10497,-0.010280831716955,-0.034708835184574,0.015767063945532,40131,-652,-2014,-2360,1.01787483692169 +10499,-0.005600420292467,-0.032785389572382,0.014362053014338,40131,-980,-2782,-2446,1.0169506072998 +10501,-0.004304824396968,-0.021114397794008,0.017069987952709,40131,-756,-3588,-2342,1.01390659809113 +10503,-0.000730855099391,-0.012296857312322,0.022131580859423,40131,-973,-3555,-2390,1.01016485691071 +10505,0.00405554054305,-0.009193137288094,0.021199932321906,40131,-1148,-3159,-2291,1.01127743721008 +10507,0.007985784672201,-0.017396355047822,0.014199862256646,40131,-1129,-2254,-2441,1.0149017572403 +10509,0.005591540597379,-0.01902536302805,0.009142742492259,40131,-652,-2643,-2430,1.01796329021454 +10511,0.004914219956845,-0.023832514882088,0.010886440984905,40131,-760,-2390,-2463,1.02116024494171 +10513,0.005881595890969,-0.023428006097674,0.014209675602615,40131,-878,-2701,-2369,1.02006793022156 +10515,0.006850010249764,-0.013806246221066,0.016340868547559,40131,-907,-3551,-2423,1.01497232913971 +10517,0.009464194066823,-0.008626882918179,0.017380619421601,40131,-1061,-3267,-2330,1.01172351837158 +10519,0.011661534197629,-0.005866593215615,0.015510302037001,40131,-1067,-3163,-2426,1.01126527786255 +10521,0.015308456495404,-0.017647026106715,0.016708014532924,40131,-1258,-1901,-2335,1.00904083251953 +10523,0.008720647543669,-0.013926641084254,0.020706970244646,40131,-405,-3103,-2388,1.00561654567719 +10525,0.000556456448976,-0.01163007132709,0.022320032119751,40131,-196,-3011,-2266,1.00740921497345 +10527,-0.002936823759228,-0.003974527586252,0.020880887284875,40131,-466,-3520,-2383,1.00744342803955 +10529,0.003499840619043,0.001848496729508,0.018998268991709,40131,-1296,-3477,-2302,1.00781452655792 +10531,0.007787499111146,0.003066204022616,0.021241622045636,40131,-1184,-3158,-2378,1.00843048095703 +10533,0.011651206761599,0.002496315632015,0.025499122217298,40131,-1243,-3018,-2222,1.00427007675171 +10535,0.015728496015072,0.002729559317231,0.024527750909329,40131,-1293,-3079,-2351,0.996998608112335 +10537,0.015774022787809,0.011372778564692,0.02080699801445,40131,-1048,-3809,-2274,0.990877211093903 +10539,0.01428088825196,0.02232956327498,0.020063126459718,40131,-884,-4128,-2379,0.989247500896454 +10541,0.016454847529531,0.027961255982518,0.019268523901701,40131,-1227,-3863,-2289,0.991208791732788 +10543,0.018598603084684,0.025726065039635,0.016268799081445,40131,-1219,-3237,-2402,0.993750929832458 +10545,0.017785299569368,0.022418079897761,0.015614715404809,40131,-1043,-3158,-2329,0.995147287845612 +10547,0.00768676912412,0.037891611456871,0.017977088689804,40131,-198,-4688,-2388,0.994914829730988 +10549,0.002922384999692,0.040767170488834,0.019897812977433,40131,-524,-3921,-2276,0.999143600463867 +10551,0.00212268717587,0.041530523449183,0.020602056756616,40131,-790,-3704,-2367,1.0013552904129 +10553,0.003465227317065,0.03511406481266,0.021138487383723,40131,-973,-3166,-2258,1.00434958934784 +10555,-0.001377752167173,0.033753585070372,0.021650100126863,40131,-455,-3453,-2356,1.00592994689941 +10557,-0.010655362159014,0.042702298611403,0.020247630774975,40131,17,-4407,-2266,1.00398313999176 +10559,-0.01493385527283,0.041304286569357,0.01659475825727,40131,-299,-3575,-2388,1.00687682628632 +10561,-0.015660842880607,0.042691491544247,0.015314066782594,40131,-517,-3883,-2321,1.0067310333252 +10563,-0.015373174101114,0.043698042631149,0.018271228298545,40131,-616,-3798,-2374,1.00725245475769 +10565,-0.019403388723731,0.046492420136929,0.016433896496892,40131,-213,-4061,-2306,1.00471377372742 +10567,-0.024485107511282,0.047328487038612,0.011146754957736,40131,-96,-3857,-2421,1.00223505496979 +10569,-0.026689289137721,0.04000286757946,0.009631721302867,40131,-218,-3241,-2384,1.00030744075775 +10571,-0.025341618806124,0.038633093237877,0.013891041278839,40131,-535,-3588,-2400,0.997845828533173 +10573,-0.020975356921554,0.031244842335582,0.01633388735354,40131,-772,-3103,-2303,0.996725857257843 +10575,-0.020352091640234,0.033878695219755,0.01592343300581,40131,-548,-3817,-2384,0.99685138463974 +10577,-0.020186645910144,0.030607735738158,0.01415728405118,40131,-479,-3401,-2326,0.998992681503296 +10579,-0.01972771435976,0.024763030931354,0.012193092145026,40131,-539,-3089,-2407,1.00182175636292 +10581,-0.023890027776361,0.024462198838592,0.014540492556989,40131,-105,-3529,-2319,1.0091986656189 +10583,-0.028492420911789,0.021253392100334,0.017154129222035,40131,-43,-3236,-2371,1.01175081729889 +10585,-0.025390120223165,0.020525736734271,0.014594060368836,40131,-593,-3441,-2316,1.00765681266785 +10587,-0.01653584651649,0.012609381228685,0.010418131016195,40131,-1171,-2781,-2415,1.00240397453308 +10589,-0.019592007622123,0.018304886296392,0.009138950146735,40131,-239,-3873,-2379,0.992137849330902 +10591,-0.027756024152041,0.026608165353537,0.01236935891211,40131,214,-4150,-2401,0.989327669143677 +10605,-0.018218228593469,0.013255970552564,0.012053237296641,40131,-283,-3335,-2339,0.995494425296783 +10607,-0.015914423391223,0.010492128320038,0.009023062884808,40131,-679,-3148,-2418,0.99580991268158 +10609,-0.0078803030774,0.011146941222251,0.005945140495896,40131,-1194,-3420,-2410,0.989512920379639 +10611,-0.006553361192346,0.004986231215298,0.005592616740614,40131,-742,-2828,-2441,0.985318899154663 +10613,-0.013133107684553,0.011608716100454,0.007656946312636,40131,-60,-3864,-2389,0.991309523582458 +10615,-0.014925021678209,0.00981405004859,0.008846838027239,40131,-396,-3213,-2418,1.00560891628265 +10617,-0.012834532186389,0.005936176981777,0.006860576104373,40131,-682,-3017,-2397,1.01516485214233 +10619,-0.009682207368314,-5.47124982404057E-05,0.003925986588001,40131,-822,-2772,-2450,1.02145409584045 +10621,-0.002202152973041,-0.001418635132723,-3.77085816580802E-05,40131,-1241,-3072,-2478,1.0184919834137 +10623,0.000475101784104,0.004652402363718,-0.002231406979263,40131,-936,-3700,-2493,1.01170909404755 +10625,0.002302656183019,0.003240314079449,-0.001688193064183,40131,-914,-3136,-2498,1.0094667673111 +10627,0.004518351517618,0.000655681651551,-0.001403571106493,40131,-965,-3020,-2488,1.007941365242 +10629,0.010210221633315,-0.009930619038641,-0.003161040367559,40131,-1312,-2257,-2516,1.00765013694763 +10631,0.015604933723807,-0.013703878968954,-0.005300587974489,40131,-1358,-2720,-2516,1.0061559677124 +10633,0.014149870723486,-0.007980841211975,-0.001347431447357,40131,-862,-3456,-2495,1.00912737846375 +10635,0.012441822327674,-0.005037003196776,0.003014754969627,40131,-810,-3318,-2459,1.01598525047302 +10637,0.010279843583703,0.002958257449791,0.001373278093524,40131,-772,-3797,-2463,1.02322638034821 +10639,0.013975295238197,-0.001803218969144,-0.001456999336369,40131,-1227,-2812,-2490,1.0241094827652 +10641,0.019822299480438,0.0071005448699,-0.003156029153615,40131,-1515,-3933,-2517,1.0191752910614 +10643,0.027484696358442,0.007015084382147,-0.002279216423631,40131,-1717,-3275,-2496,1.01113951206207 +10645,0.032450474798679,0.001863895333372,-0.001057610730641,40131,-1662,-2847,-2493,1.00046694278717 +10647,0.027960618957877,0.008460931479931,-0.003217060118914,40131,-870,-3774,-2503,0.99988466501236 +10649,0.024978742003441,0.01070655696094,-0.005090594291687,40131,-987,-3510,-2541,1.00334119796753 +10651,0.031564187258482,0.011549488641322,-0.002884762128815,40131,-1729,-3409,-2502,1.00745975971222 +10653,0.035990979522467,0.006611141841859,0.000896000768989,40131,-1713,-2926,-2472,1.01034772396088 +10655,0.027234049513936,0.015075502917171,0.000542593188584,40131,-587,-4005,-2478,1.00748634338379 +10657,0.013275127857924,0.02473845332861,0.000597788835876,40131,-51,-4263,-2475,1.00918984413147 +10659,0.011658768169582,0.023491384461522,2.89566360152094E-05,40131,-885,-3437,-2482,1.00787794589996 +10661,0.016024135053158,0.023491417989135,0.000351530703483,40131,-1419,-3562,-2478,1.00182950496674 +10663,0.018657110631466,0.02073779143393,-0.001942576956935,40131,-1301,-3296,-2496,0.993753671646118 +10665,0.016042545437813,0.023035338148475,-0.005071264691651,40131,-925,-3734,-2543,0.985769867897034 +10667,0.014216518029571,0.020742222666741,-0.002531749662012,40131,-929,-3337,-2501,0.985164940357208 +10669,0.011179637163878,0.023364147171378,-0.00093001278583,40131,-824,-3766,-2495,0.98791640996933 +10671,0.00789703708142,0.022113991901279,-0.003577546216547,40131,-742,-3439,-2509,0.996385633945465 +10673,0.009703421033919,0.011549903079867,-0.003016762901098,40131,-1156,-2629,-2520,1.00147104263306 +10675,0.006927757058293,0.007495224010199,-0.003014612710103,40131,-772,-3030,-2506,1.00168108940125 +10677,0.003732081735507,0.00390357687138,-0.002832522848621,40131,-709,-3005,-2519,1.00060343742371 +10679,-0.003169630421326,0.009205473586917,-0.002298168139532,40131,-337,-3723,-2501,0.999911725521088 +10681,-0.005863871891052,0.002047508489341,-0.002901769476011,40131,-593,-2719,-2520,0.998884320259094 +10683,-0.008464014157653,-0.002418485935777,-0.005056876689196,40131,-570,-2854,-2521,0.995921790599823 +10685,-0.019696956500411,-0.001527786138467,-0.004582396242768,40131,248,-3233,-2541,0.993879497051239 +10687,-0.02676722407341,-0.005555625539273,-0.000458118622191,40131,18,-2835,-2490,0.992738366127014 +10689,-0.027518346905708,-0.005095780827105,0.003319168230519,40131,-364,-3137,-2448,0.991791903972626 +10691,-0.02172002196312,-0.017275553196669,0.005497954320163,40131,-965,-2077,-2449,0.990733504295349 +10693,-0.023380253463984,-0.016917189583182,0.002380287041888,40131,-361,-2927,-2459,0.995225608348846 +10695,-0.023805564269424,-0.019593711942434,-0.000743540120311,40131,-482,-2712,-2492,1.00166738033295 +10697,-0.019113142043352,-0.019943203777075,-0.00148598337546,40131,-880,-2819,-2504,1.00048959255219 +10699,-0.020206302404404,-0.018023518845439,0.000108578773506,40131,-480,-3051,-2487,1.00250124931335 +10701,-0.026813067495823,-0.014844902791083,0.001766246394254,40131,66,-3143,-2466,1.00275123119354 +10703,-0.027162577956915,-0.009706042706966,0.000430653133662,40131,-424,-3390,-2484,0.999694287776947 +10705,-0.018138432875276,-0.012834894470871,-0.002312052063644,40131,-1187,-2715,-2515,0.9969522356987 +10707,-0.010441618971527,-0.007660000119358,-0.003870095591992,40131,-1234,-3413,-2515,0.991053998470306 +10709,-0.010930280201137,-0.001990280812606,-0.00183811923489,40131,-625,-3518,-2510,0.993240475654602 +10711,-0.007173473481089,-0.003665522672236,0.000835366197862,40131,-997,-2975,-2483,0.996985733509064 +10713,-0.004090817179531,-0.007242511957884,0.001416347688064,40131,-988,-2765,-2472,1.00453352928162 +10715,-0.000387506996049,-0.013747422024608,0.001294626388699,40131,-1092,-2478,-2480,1.01374554634094 +10717,-0.001920027541928,-0.013766737654805,0.000225154610234,40131,-689,-2898,-2486,1.01480913162231 +10719,-0.000535581202712,-0.020601758733392,-0.000636339304037,40131,-925,-2345,-2493,1.00897896289825 +10721,0.000721568707377,-0.015632657334209,1.75101231434382E-05,40131,-928,-3212,-2489,0.996357858181 +10723,-0.000934134179261,-0.009284577332437,0.000751505373046,40131,-703,-3440,-2484,0.986853957176208 +10725,-8.37953484733589E-05,-0.009258633479476,0.000547802308574,40131,-891,-2950,-2483,0.979991436004639 +10727,0.004069197457284,-0.004620048217475,5.04636882396881E-05,40131,-1192,-3375,-2489,0.977393090724945 +10729,0.009368278086185,-0.010296616703272,-0.001807720516808,40131,-1381,-2530,-2511,0.976517379283905 +10731,0.010554141364992,-0.007548588793725,-0.001077494700439,40131,-1081,-3191,-2497,0.981988430023193 +10733,0.01536319218576,-0.006944365333766,0.001810220768675,40131,-1455,-3028,-2468,0.992921531200409 +10735,0.019848322495818,0.004726900253445,9.59268363658339E-05,40131,-1463,-4000,-2489,1.00135242938995 +10737,0.02627289108932,0.012178669683635,-0.002828716766089,40131,-1758,-3819,-2523,1.00953245162964 +10757,0.031834486871958,0.024814439937472,-0.010979837737978,40131,-1375,-3449,-2626,1.02569222450256 +10759,0.025589324533939,0.030525229871273,-0.013525331392884,40131,-881,-3955,-2591,1.02320575714111 +10761,0.023436799645424,0.028183955699205,-0.014547339640558,40131,-1201,-3390,-2671,1.01645946502686 +10763,0.021446013823152,0.030504444614053,-0.012697256170213,40131,-1142,-3721,-2588,1.01136875152588 +10765,0.016520017758012,0.038849778473377,-0.011409352533519,40131,-898,-4345,-2636,1.01672995090485 +10767,0.010358409024775,0.039746146649122,-0.010085425339639,40131,-695,-3766,-2572,1.0271543264389 +10769,0.003031079890206,0.038559418171644,-0.009886935353279,40131,-522,-3670,-2621,1.03316235542297 +10771,-0.001827739761211,0.034203555434942,-0.010813413187862,40131,-619,-3324,-2579,1.036003947258 +10773,-0.011269050650299,0.035764820873737,-0.015077823773027,40131,-139,-3838,-2684,1.0347855091095 +10775,-0.018313268199563,0.03543995693326,-0.01784897223115,40131,-225,-3644,-2630,1.0306122303009 +10777,-0.024120716378093,0.033815711736679,-0.01980796828866,40131,-184,-3588,-2743,1.02430939674377 +10779,-0.025140473619104,0.038436185568571,-0.021920962259173,40131,-552,-4053,-2662,1.01690447330475 +10781,-0.021076537668705,0.039326827973127,-0.020434755831957,40131,-929,-3871,-2754,1.0089453458786 +10783,-0.020791737362743,0.044354822486639,-0.01905001886189,40131,-701,-4182,-2646,1.00322020053864 +10785,-0.021323963999748,0.033803179860115,-0.020205993205309,40131,-588,-2977,-2755,1.00049352645874 +10787,-0.027549443766475,0.026647498831153,-0.021249484270811,40131,-130,-3068,-2665,1.0010427236557 +10789,-0.036245048046112,0.029828600585461,-0.019886266440153,40131,241,-3903,-2755,1.00541496276855 +10791,-0.036495365202427,0.031597886234522,-0.019720492884517,40131,-417,-3789,-2658,1.00833415985107 +10793,-0.032752357423306,0.031271677464247,-0.021399131044746,40131,-698,-3683,-2777,1.00656199455261 +10795,-0.027269896119833,0.023461997509003,-0.020845137536526,40131,-950,-2996,-2670,1.00373542308807 +10797,-0.030453892424703,0.025295319035649,-0.019617723301053,40131,-229,-3751,-2759,1.00307500362396 +10799,-0.035794124007225,0.025413598865271,-0.018884355202317,40131,-43,-3599,-2660,1.00435125827789 +10801,-0.038090344518423,0.024886261671782,-0.018256757408381,40131,-155,-3584,-2747,1.00616073608398 +10803,-0.03928155452013,0.023072201758623,-0.019168969243765,40131,-276,-3435,-2665,1.00649583339691 +10805,-0.040818188339472,0.016930494457483,-0.019991707056761,40131,-149,-3057,-2771,1.00706279277802 +10807,-0.044426050037146,0.016548439860344,-0.019106714054942,40131,-14,-3449,-2669,1.0054714679718 +10809,-0.036289528012276,0.005527287721634,-0.015950288623571,40131,-898,-2524,-2726,1.00287735462189 +10811,-0.031507734209299,0.009080964140594,-0.012631116434932,40131,-786,-3622,-2627,1.0048623085022 +10813,-0.03109615854919,0.004579987376928,-0.009520851075649,40131,-423,-2971,-2653,1.00823616981506 +10815,-0.034422375261784,-0.003756582271308,-0.011183969676495,40131,-153,-2584,-2619,1.00464951992035 +10817,-0.034393165260553,-0.001085540978238,-0.014313186518848,40131,-316,-3392,-2712,1.00184452533722 +10819,-0.035616014152765,0.006266867741942,-0.011939945630729,40131,-272,-3847,-2627,1.00537049770355 +10821,-0.037840634584427,0.015233463607729,-0.01106065325439,40131,-76,-4105,-2676,1.01001703739166 +10823,-0.03013182617724,0.006291798315942,-0.014636557549238,40131,-973,-2683,-2648,1.01013362407684 +10825,-0.02084094285965,-0.002535668434575,-0.018056929111481,40131,-1177,-2549,-2761,1.00581908226013 +10827,-0.016762595623732,-0.003288446925581,-0.019953183829784,40131,-898,-3128,-2688,1.00203716754913 +10829,-0.013530878350139,8.70801522978582E-05,-0.020371658727527,40131,-874,-3472,-2792,0.999824404716492 +10831,-0.014475252479315,-0.000476563087432,-0.018778942525387,40131,-570,-3181,-2683,1.00290238857269 +10833,-0.016066351905465,-0.00720058195293,-0.017430828884244,40131,-481,-2623,-2761,1.00877833366394 +10835,-0.017153989523649,6.05524073762354E-05,-0.02003189176321,40131,-518,-3744,-2695,1.00794279575348 +10837,-0.003705120179802,0.001958996523172,-0.019854573532939,40131,-1744,-3375,-2793,1.00224041938782 +10839,0.010476794093847,0.009819952771068,-0.0205536801368,40131,-2008,-3924,-2703,0.992837190628052 +10841,0.017870517447591,0.011925765313208,-0.019456271082163,40131,-1656,-3539,-2792,0.98635733127594 +10843,0.018896576017141,0.007999220862985,-0.018444014713168,40131,-1195,-3053,-2692,0.984937310218811 +10845,0.018942838534713,0.016095403581858,-0.019529763609171,40131,-1171,-4044,-2797,0.986751019954681 +10847,0.023575138300657,0.012613963335753,-0.019823685288429,40131,-1532,-3154,-2705,0.98918479681015 +10849,0.018659263849259,0.011221691966057,-0.018976466730237,40131,-829,-3300,-2794,0.994077980518341 +10851,0.012600721791387,0.005047848913819,-0.013736714608967,40131,-622,-2855,-2667,1.00014615058899 +10853,0.008326175622642,0.008631421253085,-0.01548973005265,40131,-702,-3610,-2756,1.0015949010849 +10855,0.010689104907215,0.018623577430844,-0.020734714344144,40131,-1203,-4209,-2718,1.00234735012054 +10857,0.022298896685243,0.018785068765283,-0.020929319784045,40131,-2071,-3529,-2824,0.999074339866638 +10859,0.032770801335573,0.013394950889051,-0.018379777669907,40327,-2112,-3036,-2705,0.993398725986481 +10861,0.033484447747469,0.004823390860111,-0.016471458598971,40327,-1493,-2679,-2775,0.987155556678772 +10863,0.02231297083199,0.008857820183039,-0.01573589630425,40327,-429,-3645,-2690,0.984402179718018 +10865,0.016853341832757,0.014189580455422,-0.014157514087856,40327,-800,-3829,-2750,0.985098838806152 +10867,0.019740868359804,0.018071576952934,-0.012668857350946,40327,-1410,-3769,-2672,0.986643314361572 +10869,0.021460976451635,0.016993783414364,-0.011663707904518,40327,-1402,-3432,-2724,0.990418970584869 +10871,0.023770838975906,0.009575014933944,-0.013317927718163,40327,-1440,-2844,-2679,0.991356551647186 +10873,0.0191316511482,0.010441753081977,-0.01754223369062,40327,-920,-3474,-2796,0.996246099472046 +10875,0.013478433713317,0.010256151668727,-0.017790963873267,40327,-734,-3376,-2713,1.00226318836212 +10877,0.006777292583138,0.018043641000986,-0.01457432564348,40327,-578,-4083,-2764,1.00931477546692 +10879,0.008517162874341,0.013123304583132,-0.013767917640507,40327,-1198,-3083,-2688,1.01455843448639 +10881,0.007912992499769,0.003867745166644,-0.013193885795772,40327,-1039,-2628,-2750,1.00880253314972 +10883,-0.000285800604615,0.001393232145347,-0.011162002570927,40327,-366,-3087,-2673,1.00181794166565 +10885,-0.004463686142117,-0.000897904625162,-0.01090866420418,40327,-586,-3047,-2726,1.00034439563751 +10887,-0.006852217018604,-0.000374324561562,-0.010473238304257,40327,-689,-3272,-2670,0.999998390674591 +10889,-0.005067224148661,-0.009705985896289,-0.011057896539569,40327,-1003,-2404,-2730,1.0020010471344 +10909,-0.014532215893269,-0.00065885449294,-0.01078106276691,41239,-818,-3014,-2740,1.01152062416077 +10911,-0.011798552237451,0.003175419289619,-0.013660485856235,41239,-965,-3552,-2708,1.01088619232178 +10913,-0.010115810669959,0.001368968514726,-0.012759018689394,41239,-885,-3117,-2765,1.01066172122955 +10915,-0.01023455709219,0.005498233251274,-0.008689805865288,41239,-780,-3604,-2676,1.00585973262787 +10917,-0.006516219582409,0.001301926444285,-0.006482183001935,41239,-1091,-2935,-2693,1.0044184923172 +10919,-0.00263422424905,0.004633414093405,-0.005564430728555,41239,-1174,-3532,-2656,1.00387263298035 +10921,0.000224996096222,0.011737347580493,-0.006041128188372,41239,-1144,-3916,-2690,1.00870871543884 +10923,0.007334887515754,0.006077983416617,-0.006417332217097,41239,-1551,-2911,-2663,1.01469910144806 +10925,0.014596806839109,0.006413561757654,-0.006778184324503,41239,-1702,-3361,-2700,1.0202671289444 +10927,0.014513369649649,0.006137527991086,-0.010450183413923,41239,-1149,-3299,-2693,1.02383160591125 +10929,0.005808115471154,0.02070652320981,-0.009384175762534,41239,-435,-4619,-2732,1.03127765655518 +10931,0.010210834443569,0.023220606148243,-0.001749352086335,41239,-1416,-3753,-2635,1.03469502925873 +10933,0.018448540940881,0.017140729352832,-0.000294414436212,41239,-1871,-3083,-2627,1.0319105386734 +10935,0.021206231787801,0.014496613293886,-0.002045632572845,41239,-1471,-3265,-2637,1.03073704242706 +10937,0.02247541770339,0.016760254278779,-0.002122918376699,41239,-1446,-3673,-2649,1.03039681911469 +10939,0.029808778315783,0.020649710670114,-0.000903667067178,41239,-1938,-3826,-2630,1.02862346172333 +10941,0.03624802082777,0.018871234729886,-0.000759863643907,41239,-2047,-3416,-2633,1.02608871459961 +10943,0.038018487393856,0.019364589825273,-0.001557424548082,41239,-1677,-3569,-2635,1.01784181594849 +10945,0.03512304648757,0.021667715162039,0.000446970778285,41239,-1373,-3752,-2620,1.01170873641968 +10947,0.036269180476666,0.021703276783228,-0.000770232931245,41239,-1626,-3575,-2630,1.00625371932983 +10949,0.034836586564779,0.024417074397206,-0.004189013037831,41239,-1494,-3833,-2675,1.00471448898315 +10951,0.033725950866938,0.026875069364905,-0.004941738210619,41239,-1446,-3829,-2660,1.00647282600403 +10953,0.029595460742712,0.036753863096237,-0.003265116363764,41239,-1245,-4568,-2665,1.01121258735657 +10955,0.027848472818732,0.032071866095066,-0.003299653762952,41239,-1335,-3406,-2650,1.01660966873169 +10957,0.03022519312799,0.02948553301394,-0.00721638975665,41239,-1742,-3576,-2713,1.01622438430786 +10959,0.033529289066792,0.02470774948597,-0.007088797632605,41239,-1797,-3305,-2677,1.01577234268188 +10961,0.029401253908873,0.023070817813277,-0.002045481000096,41239,-1270,-3546,-2653,1.01373195648193 +10963,0.024134323000908,0.023680921643972,-0.00057406059932,41239,-1066,-3685,-2633,1.01068270206451 +10965,0.023361869156361,0.021851271390915,-0.003500222461298,41239,-1427,-3521,-2671,1.00914192199707 +10967,0.018966495990753,0.022897187620401,-0.005867123603821,41239,-1068,-3713,-2671,1.0050243139267 +10969,0.008130326867104,0.024120375514031,-0.005016303621233,41239,-477,-3784,-2690,1.00737047195435 +10971,0.005061862524599,0.021316226571798,-0.00151662225835,41239,-972,-3423,-2642,1.01072716712952 +10973,0.007273207418621,0.013916998170316,-0.002868444425985,41239,-1402,-3012,-2666,1.01436841487885 +10975,0.011973708868027,0.006788880098611,-0.006351757328957,41239,-1635,-2910,-2676,1.01520311832428 +10977,0.01195118855685,0.011819939129055,-0.00500769726932,41239,-1324,-3876,-2692,1.01976883411407 +10979,0.010359602048993,0.006697220727801,-0.000375718140276,41239,-1171,-3057,-2636,1.02910530567169 +10981,0.007855016738176,0.001948119373992,6.00872881477699E-05,41239,-1092,-3013,-2633,1.03521454334259 +10983,0.004095800220966,-0.002270074794069,-0.002399874851108,41239,-933,-2992,-2651,1.04119944572449 +10985,-0.001293648732826,0.003174745244905,-0.001463062944822,41239,-741,-3757,-2652,1.03744328022003 +10987,-0.008299706503749,0.011571071110666,0.000432818836998,41239,-526,-4093,-2632,1.03041017055511 +10989,-0.010739064775407,0.003804535139352,0.001380407018587,41239,-801,-2822,-2619,1.02523994445801 +10991,-0.012481763027608,0.003988195676357,-0.000553189835045,41239,-843,-3396,-2639,1.02430963516235 +10993,-0.009770237840712,0.003739179344848,-0.00400279648602,41239,-1183,-3361,-2683,1.02744710445404 +10995,-0.01096669677645,0.004306382499635,-0.006556952372193,41239,-903,-3428,-2681,1.03257191181183 +10997,-0.019645078107715,0.002991170389578,-0.009326812811196,41239,-200,-3272,-2747,1.03613889217377 +10999,-0.029277922585607,-0.003922225441784,-0.009788756258786,41239,-30,-2774,-2705,1.03609442710876 +11001,-0.031811349093914,-0.008434984833002,-0.011909494176507,41239,-431,-2849,-2779,1.03382205963135 +11003,-0.024968275800347,-0.016517860814929,-0.01170698273927,41239,-1260,-2502,-2721,1.03480696678162 +11005,-0.022117376327515,-0.018872370943427,-0.011199165135622,41239,-969,-2823,-2773,1.03368473052979 +11007,-0.026530344039202,-0.014857153408229,-0.011063088662922,41239,-424,-3381,-2719,1.03053379058838 +11009,-0.028332239016891,-0.011703700758517,-0.011203597299755,41239,-528,-3323,-2776,1.02381241321564 +11011,-0.02830277197063,-0.007514313329011,-0.010999881662428,41239,-708,-3490,-2721,1.02110743522644 +11013,-0.025136867538095,-0.016860101372004,-0.008057595230639,41239,-923,-2332,-2741,1.02298665046692 +11015,-0.023084402084351,-0.020390840247274,-0.007639155257493,41239,-918,-2741,-2699,1.03182542324066 +11017,-0.016686392948032,-0.025838684290648,-0.009026536718011,41239,-1285,-2448,-2754,1.04366481304169 +11019,-0.015553889796138,-0.018315931782127,-0.011231516487897,41239,-956,-3546,-2726,1.04588091373444 +11021,-0.021053500473499,0.000704080215655,-0.013243542052806,41239,-360,-4631,-2806,1.04344272613525 +11023,-0.023900721222162,0.016885193064809,-0.012644313275814,41239,-544,-4669,-2738,1.0413646697998 +11025,-0.022505238652229,0.027702359482646,-0.011684480123222,41239,-833,-4493,-2790,1.03975212574005 +11027,-0.013933195732534,0.025889728218317,-0.011404097080231,41239,-1500,-3520,-2732,1.04269397258759 +11029,-0.012214615009725,0.032660011202097,-0.011965358629823,41239,-1021,-4301,-2796,1.0455561876297 +11031,-0.018890419974923,0.045376222580671,-0.012694460339844,41239,-336,-4855,-2744,1.05019748210907 +11033,-0.020185826346278,0.052628494799137,-0.012246154248715,41239,-672,-4681,-2802,1.05520904064178 +11035,-0.01399604883045,0.054821278899908,-0.014153104275465,41239,-1323,-4261,-2756,1.05332219600678 +11037,-0.007812541909516,0.047366440296173,-0.015693336725235,41239,-1396,-3557,-2846,1.04775941371918 +11039,-0.007754790596664,0.054694294929504,-0.014380224980414,41239,-973,-4648,-2761,1.0419214963913 +11041,-0.007362879347056,0.058662850409746,-0.010291659273207,41239,-980,-4569,-2785,1.03742206096649 +11059,-0.010745881125331,0.044432230293751,-0.017977327108383,41239,-929,-4451,-2801,1.04987192153931 +11061,-0.007727020420134,0.036023668944836,-0.016869034618139,41239,-1186,-3426,-2877,1.04702937602997 +11063,-0.009481461718678,0.029382349923253,-0.014084486290813,41239,-823,-3409,-2777,1.03921365737915 +11065,-0.008939558640122,0.019852083176375,-0.01159487105906,41239,-982,-3093,-2818,1.03533065319061 +11067,-0.007118232548237,0.00971672590822,-0.013567212037742,41239,-1113,-2884,-2776,1.03190982341766 +11069,-0.006831728853285,-0.001015072921291,-0.016094092279673,41239,-993,-2670,-2874,1.0327320098877 +11071,-0.00873238965869,-0.005185991059989,-0.015310936607421,41239,-822,-3095,-2791,1.03577828407288 +11073,-0.008328280411661,0.001843359554186,-0.013877061195672,41239,-969,-3987,-2851,1.03898656368256 +11075,-0.00600217608735,0.007478032261133,-0.011790637858212,41239,-1162,-3978,-2770,1.04029679298401 +11077,-0.004219461698085,0.010016247630119,-0.010817791335285,41239,-1136,-3802,-2817,1.037193775177 +11079,-0.006716321688145,0.005824942141771,-0.012683905661106,41239,-806,-3253,-2778,1.03389656543732 +11081,-0.004583601374179,-0.009451616555452,-0.015336238779128,41239,-1164,-2207,-2873,1.03147923946381 +11083,-0.001600959221832,-0.017479052767158,-0.017569649964571,41239,-1273,-2638,-2815,1.03005397319794 +11085,-0.000380827113986,-0.02006927318871,-0.01779917255044,41239,-1167,-2939,-2905,1.02848863601685 +11087,-0.006768136285245,-0.010943207889795,-0.018235052004457,41239,-531,-3951,-2823,1.02428019046783 +11089,-0.011826195754111,-0.004599609412253,-0.019609859213233,41239,-531,-3826,-2930,1.02468204498291 +11091,-0.0079201515764,-0.005865144077688,-0.020941903814674,41239,-1249,-3276,-2845,1.02678871154785 +11093,-0.00796259008348,-0.003142235102132,-0.019688289612532,41239,-948,-3586,-2935,1.03147029876709 +11095,-0.005536024458706,-0.008943682536483,-0.014415349811316,41239,-1176,-2904,-2804,1.03154301643372 +11097,-0.000495987944305,-0.012124549597502,-0.012162707746029,41239,-1430,-3013,-2849,1.02864575386047 +11099,0.006141774822027,-0.022482611238957,-0.012607331387699,41239,-1647,-2377,-2794,1.02478647232056 +11101,0.005858541466296,-0.022587729617953,-0.013847889378667,41239,-1164,-3062,-2872,1.01955544948578 +11103,0.005952151026577,-0.024215333163738,-0.016110606491566,41239,-1182,-2967,-2821,1.02275562286377 +11105,0.012776497751474,-0.031044950708747,-0.017093185335398,41239,-1802,-2432,-2913,1.02993297576904 +11107,0.017390383407474,-0.035236392170191,-0.019228661432862,41239,-1680,-2612,-2846,1.03502428531647 +11109,0.018524846062064,-0.036993719637394,-0.021764105185866,41239,-1496,-2682,-2972,1.03684318065643 +11111,0.017840567976236,-0.02815336920321,-0.022050332278013,41239,-1320,-3630,-2870,1.03666687011719 +11113,0.020711420103908,-0.02049295604229,-0.021427165716887,41239,-1665,-3608,-2972,1.03650951385498 +11115,0.026115046814084,-0.015723019838333,-0.022244015708566,41239,-1888,-3507,-2875,1.03596663475037 +11117,0.028830019757152,-0.00781183457002,-0.026243822649121,41239,-1796,-3814,-3033,1.0344545841217 +11119,0.029937075451017,-0.005706955678761,-0.025320434942842,41239,-1651,-3453,-2901,1.03055119514465 +11121,0.019017599523068,0.004193615633994,-0.021102646365762,41239,-666,-4132,-2978,1.02741551399231 +11123,0.00970038305968,0.003471844596788,-0.017381614074111,41239,-625,-3379,-2851,1.02293109893799 +11125,0.009970881044865,0.002716038376093,-0.01559148915112,41239,-1326,-3342,-2916,1.02407777309418 +11127,0.012492417357862,0.008106665685773,-0.016399836167693,41239,-1518,-3880,-2847,1.03034651279449 +11129,0.016479007899761,0.006368521600962,-0.020628022029996,41239,-1714,-3334,-2979,1.03652107715607 +11131,0.017788827419281,0.006465699989349,-0.024165917187929,41239,-1518,-3476,-2905,1.03927910327911 +11133,0.020999697968364,0.008083718828857,-0.023750340566039,41239,-1743,-3615,-3020,1.03943741321564 +11135,0.022550659254193,0.021293530240655,-0.0255216229707,41239,-1616,-4630,-2918,1.03536093235016 +11137,0.021030807867646,0.032779820263386,-0.027757713571191,41239,-1427,-4735,-3073,1.03455436229706 +11139,0.016775941476226,0.032581187784672,-0.028880773112178,41239,-1131,-3845,-2947,1.03777205944061 +11141,0.015600997023285,0.030766474083066,-0.030542561784387,41239,-1383,-3764,-3111,1.04009091854095 +11143,0.02110573835671,0.029695073142648,-0.028971558436751,41239,-1905,-3755,-2953,1.03987181186676 +11145,0.021998336538673,0.035341359674931,-0.0256408136338,41239,-1645,-4387,-3059,1.03389024734497 +11147,0.019051527604461,0.034593764692545,-0.022408291697502,41239,-1285,-3863,-2913,1.02887558937073 +11149,0.013833620585501,0.025632049888373,-0.020891318097711,41239,-1078,-3194,-3007,1.02310478687286 +11151,-0.000119182368508,0.019128503277898,-0.022374721243978,41239,-232,-3240,-2917,1.02451717853546 +11153,-0.011935841292143,0.016357459127903,-0.024132657796145,41239,-186,-3488,-3049,1.02686583995819 +11155,-0.015433240681887,0.023926751688123,-0.023916540667415,41239,-758,-4323,-2932,1.02982878684998 +11157,-0.007611088920385,0.018585713580251,-0.021956201642752,41239,-1658,-3345,-3028,1.03196775913239 +11159,-0.003230299102142,0.015602790750563,-0.020119471475482,41239,-1496,-3453,-2910,1.02963650226593 +11161,-0.008551512844861,0.017381967976689,-0.019365647807717,41239,-706,-3839,-3002,1.02771306037903 +11163,-0.012958261184394,0.017216457054019,-0.020189143717289,41239,-726,-3684,-2914,1.02892649173737 +11165,-0.015984555706382,0.019257709383965,-0.022319389507175,41239,-753,-3893,-3041,1.02906012535095 +11167,-0.016103969886899,0.01265718601644,-0.022204672917724,41239,-985,-3163,-2933,1.03209412097931 +11169,-0.023065244778991,0.020965507254005,-0.020476769655943,41239,-357,-4384,-3023,1.03382658958435 +11171,-0.027346815913916,0.025220649316907,-0.020316960290074,41239,-519,-4129,-2924,1.03710746765137 +11173,-0.023812709376216,0.022754548117519,-0.020839858800173,41239,-1088,-3650,-3032,1.03496158123016 +11175,-0.020679613575339,0.022810949012637,-0.017645994201303,41239,-1140,-3803,-2909,1.03334617614746 +11177,-0.022334717214108,0.0234942920506,-0.01425741519779,41239,-727,-3889,-2958,1.03171050548553 +11179,-0.021175999194384,0.025489881634712,-0.01721359603107,41239,-984,-3988,-2909,1.02955329418182 +11181,-0.00969416834414,0.019780861213803,-0.025571759790182,41239,-1867,-3381,-3095,1.02460753917694 +11183,0.003101491602138,0.02257770486176,-0.029562870040536,41239,-2164,-4011,-2999,1.01931703090668 +11185,0.004883942659944,0.032485779374838,-0.026716217398644,41239,-1418,-4723,-3113,1.01728105545044 +11187,0.004501048941165,0.036628991365433,-0.023471312597394,41239,-1247,-4323,-2963,1.01954460144043 +11189,0.004188020247966,0.031629834324122,-0.025382490828633,41239,-1261,-3661,-3103,1.0234317779541 +11191,0.004830443765968,0.020583316683769,-0.026488080620766,41239,-1331,-3020,-2988,1.03019881248474 +11193,0.004932226613164,0.019499028101564,-0.023889385163784,41239,-1305,-3761,-3090,1.03626298904419 +11195,0.009399547241628,0.013449721038342,-0.019762041047216,41239,-1676,-3285,-2947,1.04353761672974 +11197,0.013709614053369,0.001423925510608,-0.017215697094798,41239,-1762,-2686,-3015,1.04714179039001 +11199,0.013914912939072,-0.003173656994477,-0.016926262527704,41239,-1446,-3152,-2931,1.04778587818146 +11201,0.019702024757862,-0.006249472033232,-0.017354786396027,41239,-1975,-3195,-3020,1.04494953155518 +11203,0.024573471397162,0.001462644198909,-0.018348667770624,41239,-1946,-4097,-2944,1.04336583614349 +11205,0.032858286052942,-0.002205496421084,-0.018660679459572,41239,-2376,-3211,-3039,1.04172492027283 +11207,0.037644702941179,-0.000599794264417,-0.021969193592668,41239,-2145,-3627,-2973,1.03562355041504 +11209,0.035708595067263,0.0082569969818,-0.022678066045046,41239,-1704,-4275,-3091,1.03548288345337 +11211,0.026436375454068,0.0171133056283,-0.021570472046733,41239,-996,-4403,-2974,1.03864693641663 +11213,0.024813827127218,0.017623210325837,-0.021412262693048,41239,-1564,-3831,-3080,1.03913629055023 +11215,0.024582391604781,0.014785946346819,-0.022256834432483,41239,-1630,-3537,-2983,1.03816819190979 +11217,0.020376674830914,0.011037799529731,-0.024722265079618,41239,-1322,-3422,-3124,1.03614413738251 +11219,0.014299943111837,0.008286002092063,-0.023096099495888,41239,-1075,-3453,-2994,1.0348436832428 +11221,0.009152723476291,0.004710140172392,-0.019226044416428,41239,-1092,-3332,-3063,1.03404688835144 +11223,0.001525158062577,0.000411732122302,-0.018497446551919,41239,-789,-3228,-2966,1.03241634368896 +11225,-0.000473056046758,-0.010595147497952,-0.016965361312032,41239,-1164,-2565,-3040,1.02949023246765 +11227,-0.00416558329016,-0.010352678596974,-0.01289049256593,41239,-993,-3395,-2931,1.02501332759857 +11229,-0.001578059629537,-0.015595790930092,-0.012554284185171,41239,-1476,-2900,-2991,1.02689111232758 +11231,0.000364990497474,-0.014894975349307,-0.014419432729483,41239,-1464,-3357,-2944,1.02998399734497 +11233,0.000172455576831,-0.020188946276903,-0.016835685819388,41239,-1310,-2804,-3045,1.03618764877319 +11235,-0.003759149229154,-0.021925361827016,-0.016078541055322,41239,-988,-3072,-2959,1.04170894622803 +11237,-0.00390582322143,-0.021437177434564,-0.01532896514982,41239,-1247,-3180,-3030,1.03845953941345 +11239,-0.003814508439973,-0.027001885697246,-0.016118140891194,41239,-1276,-2713,-2963,1.03246080875397 +11241,-0.006091663148254,-0.028628313913941,-0.017164740711451,41239,-1060,-2896,-3055,1.02326333522797 +11243,-0.008672615513206,-0.02743074297905,-0.01776746660471,41239,-1016,-3176,-2978,1.01767551898956 +11245,-0.005519552156329,-0.026902634650469,-0.017876775935292,41239,-1463,-3059,-3067,1.01757025718689 +11247,-0.001899962429889,-0.019499165937305,-0.018064480274916,41239,-1558,-3719,-2983,1.01846635341644 +11249,0.001286211889237,-0.016436910256744,-0.019343880936503,41239,-1571,-3403,-3088,1.01959717273712 +11251,-0.003449676325545,-0.003048051381484,-0.019415488466621,41239,-941,-4375,-2996,1.02396667003632 +11253,-0.011324370279908,0.004873278550804,-0.017872480675578,41239,-579,-4091,-3075,1.03135526180267 +11255,-0.017417835071683,0.013108038343489,-0.015783257782459,41239,-641,-4237,-2975,1.03793883323669 +11257,-0.018840374425054,0.011804327368736,-0.015897378325462,41239,-923,-3540,-3056,1.04617774486542 +11259,-0.013747519813478,0.001828915555961,-0.018380215391517,41239,-1491,-2773,-2996,1.04287970066071 +11261,-0.013186908327043,-0.001885842066258,-0.017724329605699,41239,-1152,-3147,-3080,1.03276002407074 +11263,-0.014199866913259,-0.004492260050029,-0.015726462006569,41239,-1046,-3206,-2982,1.02997291088104 +11265,-0.012934145517647,0.005224844440818,-0.016222476959229,41239,-1198,-4224,-3066,1.03116118907928 +11267,-0.009928515180945,0.010579542256892,-0.01834380440414,41239,-1392,-3993,-3003,1.03823220729828 +11269,-0.012935513630509,0.012606767937541,-0.019392393529415,41239,-883,-3798,-3107,1.0436943769455 +11271,-0.019535480067134,0.019124709069729,-0.020443297922611,41239,-562,-4203,-3022,1.0419088602066 +11273,-0.021791925653815,0.024876950308681,-0.022205235436559,41239,-790,-4273,-3145,1.03792464733124 +11289,-0.032738603651524,0.038811523467302,-0.014753536321223,41239,-357,-4842,-3070,1.03362739086151 +11291,-0.034008145332337,0.042034167796373,-0.014048686251044,41239,-695,-4361,-2995,1.03889203071594 +11293,-0.029767086729407,0.03520554676652,-0.015580457635224,41239,-1083,-3611,-3083,1.04499912261963 +11295,-0.023899216204882,0.02575564943254,-0.018625468015671,41239,-1339,-3235,-3029,1.04357171058655 +11297,-0.016777120530605,0.020232956856489,-0.018918441608548,41239,-1497,-3469,-3126,1.03959369659424 +11299,-0.013142572715879,0.029362158849835,-0.020525582134724,41239,-1329,-4626,-3046,1.03240990638733 +11301,-0.012076698243618,0.035371381789446,-0.022778153419495,41239,-1135,-4547,-3176,1.02701950073242 +11303,-0.011049344204366,0.033660069108009,-0.023494679480791,41239,-1169,-3926,-3071,1.01983988285065 +11305,-0.012479460798204,0.029372738674283,-0.022637005895376,41239,-938,-3728,-3179,1.02040147781372 +11307,-0.012550135143101,0.025605158880353,-0.023317812010646,41239,-1065,-3675,-3075,1.02740144729614 +11309,-0.011179284192622,0.032492216676474,-0.025182757526636,41239,-1160,-4592,-3213,1.03768503665924 +11311,-0.003194394055754,0.032859515398741,-0.024183290079236,41239,-1773,-4088,-3086,1.04777884483337 +11313,0.001025148201734,0.035013355314732,-0.020078489556909,41239,-1568,-4309,-3158,1.04840505123138 +11315,-0.002582237590104,0.032827746123076,-0.018112901598215,41239,-954,-3920,-3048,1.04901909828186 +11317,-0.002749867504463,0.025911519303918,-0.021460404619575,41239,-1205,-3528,-3178,1.04498958587646 +11319,-0.00305778789334,0.022029604762793,-0.024376297369599,41239,-1187,-3655,-3095,1.03699278831482 +11321,-0.003066956298426,0.008242485113442,-0.022754410281777,41239,-1215,-2762,-3198,1.03234350681305 +11323,-0.011620759963989,0.008067071437836,-0.020245678722859,41239,-477,-3725,-3072,1.0321980714798 +11325,-0.015950797125697,0.003818556899205,-0.020981885492802,41239,-692,-3373,-3182,1.03345048427582 +11327,-0.01620608381927,0.000483257928863,-0.02582472935319,41239,-1002,-3391,-3114,1.02893877029419 +11329,-0.016420094296336,0.001933449879289,-0.025643965229392,41239,-964,-3744,-3241,1.02629566192627 +11331,-0.019440429285169,0.002264719456434,-0.022122668102384,41239,-752,-3679,-3094,1.02718830108643 +11333,-0.018112827092409,0.003078668611124,-0.021545123308897,41239,-1035,-3705,-3197,1.02955675125122 +11335,-0.007057385984808,-0.007931720465422,-0.022155398502946,41239,-1931,-2718,-3098,1.02982902526855 +11337,0.002465695841238,-0.016796618700028,-0.024782918393612,41239,-1962,-2691,-3240,1.02533745765686 +11339,0.002000560751185,-0.0255461409688,-0.024227987974882,41239,-1239,-2617,-3118,1.0222989320755 +11341,0.000217464781599,-0.037310723215342,-0.02176808193326,41239,-1127,-2150,-3209,1.01926958560944 +11343,0.000477418361697,-0.044301483780146,-0.023753555491567,41239,-1273,-2458,-3119,1.02148950099945 +11345,0.002353688934818,-0.04398612305522,-0.026305371895433,41239,-1427,-2890,-3267,1.02630686759949 +11347,0.001737453741953,-0.036202516406775,-0.027352467179298,41239,-1233,-3612,-3149,1.03335320949554 +11349,0.002164918463677,-0.038228750228882,-0.025989344343543,41239,-1321,-2791,-3269,1.04201209545136 +11351,0.00316447718069,-0.042725369334221,-0.02566123008728,41239,-1373,-2621,-3142,1.04094839096069 +11353,0.003963749390095,-0.03558798879385,-0.026799006387591,41239,-1372,-3467,-3284,1.03774082660675 +11355,0.008290770463645,-0.03250902146101,-0.027552232146263,41239,-1688,-3292,-3160,1.03264427185059 +11357,0.009033390320838,-0.023050304502249,-0.027286043390632,41239,-1456,-3818,-3295,1.0314781665802 +11359,0.017290091142058,-0.032328922301531,-0.024088401347399,41239,-2104,-2396,-3142,1.02525579929352 +11361,0.020320923998952,-0.038923427462578,-0.01897625438869,41239,-1820,-2398,-3201,1.01503074169159 +11363,0.022513158619404,-0.044443961232901,-0.015664530918002,41239,-1758,-2471,-3088,1.01424753665924 +11365,0.022614063695073,-0.043356623500586,-0.017186047509313,41239,-1653,-2857,-3184,1.01899218559265 +11367,0.023889230564237,-0.043031260371208,-0.020966164767742,41239,-1724,-2888,-3128,1.02559101581573 +11369,0.022979339584708,-0.046462573111057,-0.023356245830655,41239,-1595,-2459,-3261,1.03037822246552 +11371,0.017027409747243,-0.045321676880121,-0.02273197285831,41239,-1120,-2890,-3145,1.03163385391235 +11373,0.010647428222001,-0.040743250399828,-0.021173780784011,41239,-1022,-3102,-3240,1.03394556045532 +11375,0.007304977159947,-0.03295923769474,-0.0188322737813,41239,-1175,-3523,-3123,1.03420400619507 +11377,0.001801802078262,-0.016471976414323,-0.019005462527275,41239,-956,-4338,-3219,1.03342390060425 +11379,-0.003063737880439,-0.003482683561742,-0.019782459363341,41239,-923,-4309,-3133,1.03367805480957 +11381,-0.007471298798919,0.013674491085112,-0.019268566742539,41239,-894,-4883,-3226,1.03414416313171 +11383,-0.003464150475338,0.017509439960122,-0.0174406953156,41239,-1555,-3960,-3121,1.03436994552612 +11385,-0.004475964233279,0.020907025784254,-0.016077164560557,41239,-1188,-4024,-3192,1.0325779914856 +11387,-0.004545944277197,0.01554202195257,-0.014793532900512,41239,-1251,-3283,-3106,1.03278458118439 +11389,-0.00374170136638,0.014387347735465,-0.014423429965973,41239,-1316,-3590,-3176,1.03212022781372 +11391,-0.004837733693421,0.01963377930224,-0.016775697469711,41239,-1174,-4107,-3123,1.02999699115753 +11393,-0.008423618040979,0.017998041585088,-0.01993652805686,41239,-913,-3614,-3245,1.02884125709534 +11395,-0.01595051586628,0.017306847497821,-0.019259084016085,41239,-550,-3654,-3144,1.02436482906342 +11397,-0.023226846009493,0.011966639198363,-0.016422180458903,41239,-410,-3253,-3207,1.02320969104767 +11399,-0.025030391290784,0.00361790577881,-0.014723381027579,41239,-821,-2911,-3117,1.02181029319763 +11401,-0.025764422491193,0.008312843739986,-0.016540318727493,41239,-831,-3914,-3212,1.01892709732056 +11403,-0.024862162768841,0.013852008618414,-0.018229901790619,41239,-1008,-4054,-3145,1.01530659198761 +11405,-0.021378237754107,0.020627178251743,-0.019121522083879,41239,-1194,-4269,-3246,1.01771330833435 +11407,-0.015766359865666,0.011675598099828,-0.021137356758118,41239,-1468,-2991,-3169,1.02362370491028 +11409,-0.015628691762686,0.008764060214162,-0.022309981286526,41239,-1049,-3395,-3288,1.03108644485474 +11411,-0.021028021350503,0.010108327493072,-0.022639561444521,41239,-599,-3709,-3183,1.04397141933441 +11413,-0.025248143821955,0.011737024411559,-0.022937787696719,41239,-577,-3772,-3300,1.04902994632721 +11415,-0.032992396503687,0.015846166759729,-0.024092633277178,41239,-252,-3994,-3198,1.04510903358459 +11417,-0.036760605871677,0.013671058230102,-0.026089567691088,41239,-407,-3536,-3342,1.04009389877319 +11419,-0.033740382641554,0.016347302123904,-0.028806259855628,41239,-998,-3904,-3236,1.03581202030182 +11421,-0.028823584318161,0.017466794699431,-0.029312869533897,41239,-1149,-3835,-3386,1.03358793258667 +11423,-0.020971029996872,0.017952596768737,-0.028866739943624,41239,-1517,-3777,-3242,1.03118944168091 +11425,-0.018136825412512,0.019531343132258,-0.029283981770277,41239,-1163,-3908,-3391,1.02835166454315 +11427,-0.018436636775732,0.012839886359871,-0.029468175023794,41239,-964,-3196,-3252,1.02613925933838 +11429,-0.023826442658901,0.012475065886974,-0.028388319537044,41239,-472,-3664,-3386,1.02440345287323 +11431,-0.026630081236363,0.008324342779815,-0.022833291441202,41239,-658,-3318,-3212,1.02497172355652 +11433,-0.025749623775482,0.000692984147463,-0.019700242206454,41239,-876,-2958,-3289,1.02711510658264 +11435,-0.026948457583785,-0.003287196625024,-0.02184559032321,41239,-758,-3164,-3209,1.03250467777252 +11437,-0.018356973305345,-0.004539295099676,-0.022799346596003,41239,-1543,-3324,-3330,1.03468120098114 +11439,-0.013354843482375,0.00058883294696,-0.021557625383139,41239,-1390,-3869,-3212,1.03818011283875 +11441,-0.017835142090917,-0.000149263665662,-0.018702296540141,41239,-616,-3431,-3286,1.0385810136795 +11443,-0.026574643328786,0.006993121933192,-0.01753624342382,41239,-211,-4104,-3188,1.03786420822144 +11445,-0.024755727499724,0.011274733580649,-0.020639903843403,41239,-965,-3974,-3313,1.04051685333252 +11447,-0.011800578795374,0.010573631152511,-0.025859471410513,41239,-1972,-3597,-3250,1.04328370094299 +11449,-0.005754782818258,0.00561644602567,-0.026269447058439,41239,-1573,-3230,-3384,1.04134392738342 +11451,-0.005929735023528,-0.002450258238241,-0.020905025303364,41239,-1118,-2885,-3221,1.03831648826599 +11453,-0.006911830045283,0.001560068922117,-0.018731663003564,41239,-1048,-3819,-3300,1.03694009780884 +11455,-0.002555563813075,0.002996815135703,-0.019368866458535,41239,-1493,-3646,-3215,1.03913903236389 +11457,0.000340894301189,0.003746954258531,-0.019295012578368,41239,-1442,-3615,-3311,1.03916215896606 +11459,-0.002600856591016,0.009385542012751,-0.019660277292132,41239,-973,-4040,-3221,1.04156827926636 +11461,-0.000194024396478,0.012226919643581,-0.018193742260337,41239,-1392,-3895,-3302,1.03766512870789 +11463,0.001886495971121,0.015345925465226,-0.016367375850678,41239,-1399,-3949,-3202,1.03262555599213 +11465,0.006040710024536,0.009154767729342,-0.018093775957823,41239,-1609,-3208,-3305,1.02695417404175 +11467,0.007604618091136,0.009461767040193,-0.017814731225371,41239,-1447,-3667,-3216,1.02603602409363 +11469,0.010565735399723,0.004957510624081,-0.016283858567476,41239,-1601,-3266,-3287,1.03155338764191 +11471,0.014820469543338,0.003181518055499,-0.016865521669388,41239,-1748,-3430,-3213,1.03470098972321 +11473,0.014830326661468,0.012801676988602,-0.017001220956445,41239,-1464,-4413,-3299,1.03429508209229 +11475,0.015638396143913,0.015969114378095,-0.018400143831968,41239,-1520,-3974,-3228,1.03474104404449 +11477,0.017776215448976,0.015364752151072,-0.019465822726488,41239,-1678,-3727,-3332,1.03510439395905 +11479,0.02250843308866,0.003812910988927,-0.018868949264288,41239,-1909,-2752,-3235,1.04114735126495 +11481,0.025351298972964,0.000135271708132,-0.01985601708293,41239,-1871,-3258,-3341,1.03983449935913 +11483,0.021811421960592,0.000841993722133,-0.018186455592513,41239,-1320,-3587,-3234,1.03806924819946 +11485,0.013756978325546,0.001894270302728,-0.017565613612533,41239,-914,-3625,-3318,1.03164792060852 +11487,0.008494477719069,0.006722972728312,-0.019336488097906,41239,-1015,-3967,-3246,1.02449476718903 +11489,0.009045934304595,0.006109770853072,-0.019404534250498,41239,-1458,-3574,-3344,1.02283382415771 +11491,0.008544395677745,-0.002589382696897,-0.018591133877635,41239,-1363,-2866,-3245,1.02395904064178 +11493,-0.00015614592121,-0.015774479135871,-0.018925793468952,41239,-645,-2310,-3342,1.02818894386292 +11495,-0.00828018039465,-0.024303745478392,-0.019553989171982,41239,-576,-2558,-3256,1.03171181678772 +11497,-0.012599835172296,-0.01936380378902,-0.018708059564233,41239,-753,-3542,-3344,1.03045761585236 +11499,-0.008207308128476,-0.02497698366642,-0.018221633508802,41239,-1469,-2746,-3251,1.03046989440918 +11501,-0.01119380351156,-0.027839155867696,-0.019421748816967,41239,-879,-2825,-3356,1.02880275249481 +11515,-0.019386392086744,-0.022042764350772,-0.023081261664629,41239,-739,-3711,-3301,1.04510617256165 +11517,-0.022357216104865,-0.014969277195633,-0.021629394963384,41239,-675,-3693,-3399,1.0510870218277 +11519,-0.018455266952515,-0.014585601165891,-0.020080028101802,41239,-1260,-3252,-3285,1.04488503932953 +11521,-0.017873629927635,-0.012816748581827,-0.022321047261357,41239,-1000,-3339,-3412,1.03581845760345 +11523,-0.017519120126963,-0.011518884450197,-0.025710811838508,41239,-1014,-3353,-3328,1.03364109992981 +11525,-0.011800080537796,-0.009330078028142,-0.027031261473894,41239,-1456,-3413,-3473,1.03350579738617 +11527,-0.002302805660293,-0.012702621519566,-0.027445884421468,41239,-1884,-2994,-3346,1.03297591209412 +11529,-0.000138799354318,-0.012453559786081,-0.027712818235159,41239,-1367,-3219,-3486,1.02870452404022 +11531,-0.007237553596497,-0.006940318737179,-0.0260578263551,41239,-622,-3705,-3342,1.02680039405823 +11533,-0.01621432043612,-0.000133033987368,-0.021177485585213,41239,-297,-3875,-3414,1.02816128730774 +11535,-0.025004252791405,0.007290605455637,-0.018531588837504,41239,-235,-4042,-3295,1.03150951862335 +11537,-0.02594312466681,-0.002707862993702,-0.021018961444497,41239,-707,-2616,-3417,1.0333993434906 +11539,-0.028270142152906,0.001720732776448,-0.02463754825294,41239,-637,-3742,-3341,1.02984499931335 +11541,-0.024563975632191,0.012959097512066,-0.025139207020402,41239,-1060,-4392,-3470,1.02647566795349 +11543,-0.012415003962815,0.021449446678162,-0.025543948635459,41239,-1890,-4317,-3353,1.01695537567139 +11545,-0.000160059993505,0.018533008173108,-0.028265314176679,41239,-2075,-3476,-3513,1.00836551189423 +11547,0.001464282628149,0.01458899024874,-0.0317497625947,41239,-1337,-3332,-3401,1.00740742683411 +11549,-0.005274420138448,0.016361724585295,-0.031727083027363,41239,-635,-3785,-3559,1.01390111446381 +11551,-0.013563881628215,0.01697550714016,-0.028398927301169,41239,-411,-3697,-3384,1.02275216579437 +11553,-0.019484924152494,0.023110333830118,-0.026512442156673,41239,-452,-4227,-3504,1.02706003189087 +11555,-0.02653805539012,0.029890755191445,-0.024958422407508,41239,-305,-4334,-3366,1.03403663635254 +11557,-0.024845322594047,0.032846707850695,-0.026617031544447,41239,-907,-4174,-3511,1.04233741760254 +11559,-0.020637352019549,0.039476320147514,-0.028160769492388,41239,-1187,-4475,-3394,1.0500100851059 +11561,-0.011244717985392,0.034030426293612,-0.028157187625766,41239,-1677,-3601,-3534,1.04810559749603 +11563,-0.010271769948304,0.031170163303614,-0.031564205884934,41239,-1101,-3691,-3423,1.03999769687653 +11565,-0.016488080844283,0.027305884286761,-0.033113650977612,41239,-461,-3618,-3599,1.02926230430603 +11567,-0.02592683583498,0.033014811575413,-0.031859681010246,41239,-124,-4344,-3431,1.01763045787811 +11569,-0.03136208280921,0.037078950554133,-0.031847972422838,41239,-257,-4355,-3590,1.01620411872864 +11571,-0.025199946016073,0.031211076304317,-0.033899333328009,41239,-1237,-3504,-3452,1.01794326305389 +11573,-0.014868245460093,0.026605740189552,-0.033874273300171,41239,-1641,-3573,-3621,1.01950430870056 +11575,-0.006726450286806,0.026070540770888,-0.034437797963619,41239,-1636,-3823,-3462,1.02046132087708 +11577,-0.004126818384975,0.027823060750961,-0.036345146596432,41239,-1261,-4053,-3657,1.01972365379334 +11579,-0.008917971514165,0.022010374814272,-0.035091258585453,41239,-676,-3396,-3474,1.02067148685455 +11581,-0.015142804943025,0.018227979540825,-0.032046943902969,41239,-452,-3507,-3613,1.01953208446503 +11583,-0.016848135739565,0.030908899381757,-0.031591653823853,41239,-777,-4854,-3456,1.01948416233063 +11585,-0.008346657268703,0.030779464170337,-0.034750048071146,41239,-1623,-3990,-3652,1.01976954936981 +11587,-0.004748802632093,0.025776620954275,-0.037856869399548,41239,-1329,-3526,-3506,1.02144491672516 +11589,-0.00550016341731,0.013726184144616,-0.039332218468189,41239,-1010,-2876,-3713,1.02300977706909 +11591,-0.013107064180076,0.016375705599785,-0.03672843426466,41239,-407,-3946,-3506,1.02457869052887 +11593,-0.017426550388336,0.027250887826085,-0.035371247678995,41239,-549,-4740,-3674,1.03033626079559 +11595,-0.012529479339719,0.02882388047874,-0.036169160157442,41239,-1305,-4059,-3510,1.03120625019073 +11597,-0.011991803534329,0.024522997438908,-0.035636648535729,41239,-976,-3619,-3684,1.02611780166626 +11599,-0.013345062732697,0.015985956415534,-0.037297356873751,41239,-841,-3160,-3524,1.02272188663483 +11601,-0.011226150207222,0.023855656385422,-0.042141683399677,41239,-1101,-4483,-3768,1.02099192142487 +11603,0.001244215993211,0.025685783475638,-0.039579387754202,41239,-2037,-4051,-3548,1.02653920650482 +11605,0.011081060394645,0.017276177182794,-0.033440232276917,41239,-2020,-3212,-3673,1.02282512187958 +11607,0.006345003843308,0.015390637330711,-0.031343728303909,41239,-885,-3642,-3498,1.01467287540436 +11609,-0.001620847266167,0.0138487694785,-0.033966943621636,41239,-538,-3657,-3686,1.00855052471161 +11611,0.001483310014009,0.017234502360225,-0.034393269568682,41239,-1377,-4050,-3526,1.01222920417786 +11613,0.015562278218567,0.012622414156795,-0.029064519330859,41239,-2391,-3424,-3635,1.02072632312775 +11615,0.0194326415658,0.008177723735571,-0.024738598614931,41239,-1696,-3363,-3466,1.0222259759903 +11617,0.01206504739821,0.00225145672448,-0.027481477707625,41239,-809,-3168,-3622,1.02318155765533 +11619,0.010147526860237,-0.001761655439623,-0.033988550305367,41239,-1154,-3251,-3535,1.02286410331726 +11621,0.010131305083633,0.003186961635947,-0.040178295224905,41239,-1322,-3968,-3778,1.0191832780838 +11623,0.012943430803716,0.00062686385354,-0.039983872324228,41239,-1541,-3391,-3584,1.02029824256897 +11625,0.015373420901597,0.004317045677453,-0.037493329495192,41239,-1604,-3903,-3754,1.02470791339874 +11627,0.02283738553524,-0.003567470703274,-0.034172385931015,41239,-2028,-2952,-3552,1.02742493152618 +11629,0.027041366323829,-0.009476176463068,-0.032349947839975,41239,-1940,-3003,-3701,1.02617108821869 +11631,0.0253687184304,-0.006645232439041,-0.031630497425795,41239,-1428,-3674,-3541,1.0293083190918 +11633,0.02377400547266,0.001725278329104,-0.031320836395025,41239,-1480,-4203,-3695,1.0351026058197 +11635,0.02286477573216,0.009878676384687,-0.030294666066766,41239,-1462,-4295,-3538,1.03985869884491 +11637,0.027129186317325,0.002676843898371,-0.026653815060854,41239,-1957,-3096,-3646,1.03884506225586 +11639,0.030468054115772,0.004737357608974,-0.026744881644845,41239,-1890,-3786,-3519,1.03202438354492 +11641,0.031806062906981,0.004184567369521,-0.031278286129236,41239,-1843,-3595,-3707,1.02783715724945 +11643,0.031250048428774,1.10948622022988E-05,-0.032150007784367,41239,-1640,-3273,-3563,1.02330553531647 +11645,0.029996100813151,-0.000541999121197,-0.029207618907094,41239,-1644,-3517,-3689,1.02050745487213 +11647,0.035153634846211,0.000510447658598,-0.028006801381707,41239,-2122,-3654,-3541,1.01613306999207 +11665,0.005513378418982,-0.014472368173301,-0.033195596188307,41239,-1515,-3291,-3770,1.02777779102325 +11667,0.007738692685962,-0.023033242672682,-0.033788219094277,41239,-1565,-2600,-3615,1.02380049228668 +11669,0.001787894871086,-0.02582697942853,-0.035162657499313,41239,-899,-2908,-3800,1.02102136611938 +11671,-0.008136701770127,-0.030917668715119,-0.032305959612131,41239,-469,-2722,-3612,1.01936078071594 +11673,-0.012131359428167,-0.028538648039103,-0.030523240566254,41239,-816,-3224,-3752,1.0237877368927 +11675,-0.005128981545568,-0.036047790199518,-0.030331375077367,41239,-1722,-2460,-3605,1.02826714515686 +11677,-0.005086484365165,-0.031299710273743,-0.033141035586596,41239,-1217,-3332,-3790,1.03220570087433 +11679,-0.005650312639773,-0.033712316304445,-0.036229871213436,41239,-1173,-2843,-3652,1.03026974201202 +11681,-0.009538206271827,-0.038088332861662,-0.036200203001499,41239,-855,-2553,-3833,1.02199935913086 +11683,-0.01784959807992,-0.035546068102121,-0.03791818395257,41239,-439,-3153,-3671,1.01359069347382 +11685,-0.017491292208433,-0.033035583794117,-0.038916785269976,41239,-1030,-3109,-3872,1.01093363761902 +11687,-0.012995740398765,-0.030604790896177,-0.03785465285182,41239,-1420,-3199,-3678,1.01114809513092 +11689,-0.013631589710713,-0.031977016478777,-0.034041676670313,41239,-1016,-2835,-3822,1.01401126384735 +11691,-0.017660738900304,-0.026912515982986,-0.03265330567956,41239,-738,-3425,-3650,1.01249325275421 +11693,-0.022243158891797,-0.018906839191914,-0.031587701290846,41239,-586,-3707,-3800,1.01462268829346 +11695,-0.02191642858088,-0.016728596761823,-0.028782732784748,41239,-981,-3355,-3630,1.020423412323 +11697,-0.022659407928586,-0.009079284965992,-0.027355471625924,41239,-847,-3838,-3757,1.02885162830353 +11699,-0.021050905808807,-0.012425377033651,-0.028368748724461,41239,-1076,-3016,-3633,1.03443872928619 +11701,-0.023394821211696,-0.003698639106005,-0.028339864686132,41239,-719,-3998,-3774,1.03965139389038 +11703,-0.0202602352947,-0.005350523162633,-0.026403052732349,41239,-1189,-3236,-3625,1.03941869735718 +11705,-0.019329519942403,-0.00763776851818,-0.025751084089279,41239,-1014,-3149,-3749,1.0332156419754 +11707,-0.026840135455132,-0.004731873981655,-0.026213895529509,41239,-326,-3569,-3629,1.02683877944946 +11709,-0.029484262689948,-0.007021555211395,-0.027274049818516,41239,-595,-3155,-3773,1.02370417118073 +11711,-0.023798909038305,-0.01043269969523,-0.029320331290364,41239,-1306,-3032,-3657,1.02424454689026 +11713,-0.015799660235643,-0.016481168568134,-0.032544478774071,41239,-1573,-2726,-3841,1.027871966362 +11715,-0.013227343559265,-0.012810442596674,-0.033648267388344,41239,-1232,-3498,-3693,1.02659344673157 +11717,-0.012666618451476,-0.010185889899731,-0.03005582280457,41239,-1086,-3445,-3819,1.0282062292099 +11719,-0.009954761713743,-0.008638268336654,-0.028435871005058,41239,-1287,-3401,-3664,1.02830135822296 +11721,-0.007817471399903,-0.001835124217905,-0.029059791937471,41239,-1270,-3869,-3813,1.02999436855316 +11723,-0.002295956946909,-0.005662197712809,-0.028013676404953,41239,-1598,-3057,-3667,1.03062105178833 +11725,-0.001861547236331,-0.002246633637697,-0.024617498740554,41239,-1238,-3601,-3767,1.03090441226959 +11727,0.001502246479504,-0.004442933481187,-0.022430814802647,41239,-1499,-3186,-3634,1.02832174301147 +11729,0.0019213919295,0.002189747290686,-0.022892596200109,41239,-1292,-3896,-3752,1.02754414081573 +11731,0.000180228016688,0.005826951470226,-0.022368900477886,41239,-1115,-3748,-3639,1.02851068973541 +11733,0.007764727342874,-0.000332398223691,-0.022299606353045,41239,-1908,-2934,-3750,1.03280854225159 +11735,0.014062724076212,-0.001529273227789,-0.020816223695874,41239,-1895,-3292,-3633,1.03319692611694 +11737,0.016634736210108,-0.001677533960901,-0.020318681374192,41239,-1698,-3343,-3731,1.03124260902405 +11739,0.013763447292149,0.009055331349373,-0.021065339446068,41239,-1242,-4294,-3639,1.02693796157837 +11741,0.010297016240656,0.014946420677006,-0.020488746464253,41239,-1172,-4046,-3738,1.0272204875946 +11743,0.007239128928632,0.020019682124257,-0.022005330771208,41239,-1141,-4049,-3651,1.02754509449005 +11745,0.005402540788054,0.022096663713455,-0.020059395581484,41239,-1219,-3896,-3738,1.03114914894104 +11747,0.007211331278086,0.021762270480394,-0.017233371734619,41239,-1494,-3693,-3623,1.03356266021729 +11749,0.003492947900668,0.025559900328517,-0.015464227646589,41239,-1062,-4086,-3688,1.0359388589859 +11751,-0.002046385779977,0.023737406358123,-0.016117997467518,41239,-840,-3624,-3619,1.03259491920471 +11753,-0.006341711152345,0.020064607262611,-0.016094291582704,41239,-867,-3474,-3699,1.02886164188385 +11755,-0.010421019047499,0.016838993877173,-0.010833894833922,41239,-825,-3432,-3586,1.02623319625855 +11757,-0.011338100768626,0.010907780379057,-0.009329725056887,41239,-1030,-3169,-3623,1.02451109886169 +11759,-0.013718334026635,0.010182206518948,-0.015653599053621,41239,-898,-3519,-3622,1.02160441875458 +11761,-0.015390519052744,0.002181597752497,-0.017096664756537,41239,-904,-2888,-3718,1.02225840091705 +11763,-0.017102833837271,0.008992174640298,-0.015689576044679,41239,-893,-4042,-3627,1.02589321136475 +11765,-0.009118207730353,0.006396086886525,-0.012363313697279,41239,-1696,-3346,-3666,1.03184270858765 +11767,-0.00814457423985,0.004785516299307,-0.0107252728194,41239,-1214,-3382,-3596,1.03012442588806 +11769,-0.010821620002389,-0.000175131383003,-0.010070772841573,41239,-895,-3064,-3642,1.0290892124176 +11771,-0.014188582077623,-0.002593426499516,-0.008968939073384,41239,-813,-3216,-3587,1.02464771270752 +11773,-0.013983690179885,-0.003009241539985,-0.011989818885923,41239,-1042,-3338,-3668,1.01661455631256 +11775,-0.011759087443352,-0.003952605184168,-0.016891134902835,41239,-1243,-3299,-3645,1.0107250213623 +11777,-0.006099205464125,-0.005338644608855,-0.017726102843881,41239,-1558,-3227,-3739,1.00655627250671 +11779,-0.006445702631027,-0.010846898891032,-0.015093810856342,41239,-1134,-2868,-3637,1.00770318508148 +11781,-0.005203018896282,-0.018815990537405,-0.014058918692172,41239,-1247,-2534,-3700,1.01078343391418 +11783,-0.005980173591524,-0.016861360520125,-0.015285056084395,41239,-1107,-3307,-3642,1.0146678686142 +11785,-0.006852450780571,-0.017574993893504,-0.017425905913115,41239,-1076,-3061,-3744,1.02293634414673 +11787,-0.011720513924956,-0.013580987229943,-0.018933396786451,41239,-730,-3490,-3671,1.02950131893158 +11789,-0.008947611786425,-0.026559108868241,-0.021003223955631,41239,-1312,-2021,-3791,1.03539967536926 +11791,-0.01349925622344,-0.027709795162082,-0.021286234259606,41239,-726,-2904,-3692,1.0372416973114 +11793,-0.016275869682431,-0.031367659568787,-0.019196268171072,41239,-799,-2602,-3774,1.04020202159882 +11795,-0.021279651671648,-0.030602382495999,-0.019313771277666,41239,-579,-2984,-3683,1.03870165348053 +11797,-0.023135265335441,-0.032741758972406,-0.019226660951972,41239,-754,-2677,-3779,1.0361043214798 +11799,-0.020979795604944,-0.038492206484079,-0.020355712622404,41239,-1091,-2388,-3695,1.0344330072403 +11801,-0.009536423720419,-0.039552599191666,-0.01986569724977,41239,-1919,-2627,-3791,1.03555512428284 +11803,0.000672940921504,-0.035290226340294,-0.014988323673606,41239,-1979,-3132,-3663,1.03624963760376 +11805,0.002125474857166,-0.027158176526427,-0.011055143550038,41239,-1390,-3469,-3691,1.03015434741974 +11807,-0.003921598661691,-0.020279826596379,-0.006423339713365,41239,-752,-3521,-3607,1.02823531627655 +11809,-0.003665751311928,-0.01529171410948,-0.001924840384163,41239,-1223,-3414,-3586,1.03071868419647 +11811,-0.006254214793444,-0.008377513848245,-0.004340321291238,41239,-970,-3685,-3594,1.03314578533173 +11813,-0.009022349491715,-0.016739621758461,-0.010122966952622,41239,-929,-2413,-3685,1.03569650650024 +11815,-0.012217422947288,-0.012958321720362,-0.014890267513692,41239,-843,-3382,-3670,1.03278183937073 +11817,-0.010834787040949,-0.011248853057623,-0.014084772206843,41239,-1186,-3214,-3735,1.02817404270172 +11819,-0.012718936428428,-0.009022819809616,-0.011534522287548,41239,-929,-3317,-3651,1.02247226238251 +11821,-0.012876003049314,-0.006823073606938,-0.01134223677218,41239,-1029,-3316,-3706,1.02536749839783 +11823,-0.008018245920539,-0.007497738115489,-0.007809558883309,41239,-1476,-3124,-3628,1.03130722045898 +11825,-0.003580292919651,-0.004150139167905,-0.003767608897761,41239,-1504,-3438,-3620,1.02847838401794 +11827,-0.002866189461201,0.003847398329526,-0.003737998427823,41239,-1253,-3902,-3602,1.02030372619629 +11829,-0.005147811491042,0.01837177015841,-0.006203408818692,41239,-998,-4603,-3651,1.01226735115051 +11831,-0.012780253775418,0.026297217234969,-0.005669394973665,41239,-512,-4224,-3618,1.00759422779083 +11833,-0.022109685465694,0.025770822539926,-0.006429788190871,41239,-217,-3647,-3656,1.00511360168457 +11835,-0.029214130714536,0.022956421598792,-0.009070108644664,41239,-306,-3414,-3644,1.00644552707672 +11837,-0.024613374844194,0.008910031989217,-0.00999924633652,41239,-1162,-2421,-3700,1.00737512111664 +11839,-0.023935958743095,0.007864368148148,-0.008881155401468,41239,-929,-3326,-3645,1.00759696960449 +11841,-0.027140898630023,0.004015588201582,-0.008616168051958,41239,-549,-3085,-3687,1.01435470581055 +11843,-0.037191219627857,0.010212134569883,-0.010535730049014,41239,40,-3880,-3659,1.02435040473938 +11845,-0.038533825427294,0.017075382173061,-0.01059334538877,41239,-489,-4064,-3713,1.0365492105484 +11847,-0.032166056334972,0.02245495095849,-0.009330184198916,41239,-1192,-4004,-3654,1.04974007606506 +11849,-0.032580684870482,0.024981211870909,-0.00836031883955,41239,-642,-3885,-3690,1.05214750766754 +11851,-0.03865833953023,0.021374385803938,-0.007372446358204,41239,-195,-3354,-3644,1.04756236076355 +11853,-0.046658523380756,0.025471121072769,-0.005597256589681,41239,142,-4009,-3660,1.04154717922211 +11855,-0.048587970435619,0.024061687290669,-0.000140600241139,41239,-331,-3559,-3596,1.03690123558044 +11857,-0.04723896458745,0.021262103691697,0.001498649362475,41239,-492,-3457,-3578,1.02994275093079 +11859,-0.051805473864079,0.02304606884718,-0.000602444342803,41239,-75,-3780,-3600,1.02581644058228 +11861,-0.054103273898363,0.014504378661513,-0.003778118174523,41239,-91,-2944,-3642,1.01949954032898 +11863,-0.049787372350693,0.010970239527524,-0.005510589573532,41239,-716,-3231,-3636,1.01565754413605 +11865,-0.043865580111742,0.006043164990842,-0.004703781101853,41239,-815,-3065,-3655,1.01566779613495 +11867,-0.044763244688511,0.01282774284482,-0.004218089859933,41239,-393,-3997,-3629,1.0207781791687 +11869,-0.042396176606417,0.012907383963466,-0.006906880997121,41239,-563,-3533,-3683,1.02639698982239 +11871,-0.036383487284184,0.011948371306062,-0.007999551482499,41239,-988,-3433,-3658,1.02236497402191 +11873,-0.034938279539347,0.017980564385653,-0.006693545263261,41239,-608,-4047,-3683,1.01467907428741 +11875,-0.036224890500307,0.018471850082278,-0.005833952222019,41239,-451,-3635,-3645,1.01605725288391 +11877,-0.038143161684275,0.017765356227756,-0.005425004288554,41239,-299,-3571,-3670,1.01495289802551 +11879,-0.026410482823849,0.003498343983665,-0.006009401287884,41239,-1507,-2369,-3649,1.01397323608398 +11895,0.016100293025375,0.014537901617587,-0.008409274742007,41239,-1722,-3524,-3675,1.02813529968262 +11897,0.013797167688608,0.016600431874395,-0.007404247764498,41239,-1106,-3781,-3705,1.02866721153259 +11899,0.011354045011103,0.01750872284174,-0.009125309996307,41239,-1029,-3687,-3682,1.03120577335358 +11901,0.011870854534209,0.022526409476996,-0.011140270158649,41239,-1273,-4095,-3752,1.03222906589508 +11903,0.019363392144442,0.016430579125881,-0.013135947287083,41239,-1861,-3178,-3713,1.03229176998138 +11905,0.017077127471566,0.02012394182384,-0.010971277020872,41239,-1153,-3965,-3754,1.03352856636047 +11907,0.015840016305447,0.014447216875851,-0.006331862416118,41239,-1191,-3186,-3670,1.0372006893158 +11909,0.024136947467923,0.017087183892727,-0.004728920292109,41239,-2025,-3832,-3683,1.036248087883 +11911,0.034808605909348,0.019988184794784,-0.002544495975599,41239,-2324,-3883,-3646,1.03345966339111 +11913,0.034014213830233,0.020969534292817,0.003546248655766,41239,-1546,-3777,-3587,1.02569603919983 +11915,0.02846316806972,0.0238321069628,0.006391897797585,41239,-1083,-3940,-3585,1.01881587505341 +11917,0.028535971418023,0.013701766729355,0.004975660704076,41239,-1544,-2873,-3571,1.01092517375946 +11919,0.030603189021349,0.005336174741387,0.000986715778708,41239,-1672,-2873,-3623,1.00435304641724 +11921,0.028368450701237,0.001060654758476,-0.002653364324942,41239,-1394,-3090,-3662,1.00501251220703 +11923,0.025787014514208,-0.002838808577508,-0.004983279388398,41239,-1284,-3072,-3666,1.00531983375549 +11925,0.019990151748061,-0.002157762646675,-0.007913743145764,41239,-1009,-3395,-3726,1.00886833667755 +11927,0.021793883293867,-0.009734372608364,-0.005774010438472,41239,-1549,-2706,-3674,1.0147819519043 +11929,0.016345363110304,-0.008126430213451,-0.003315103938803,41239,-986,-3359,-3674,1.02456390857697 +11931,0.013481692411006,-0.012444979511201,-0.00488958042115,41239,-1103,-2894,-3670,1.03868281841278 +11933,0.011867161840201,-0.009546998888254,-0.009422372095287,41239,-1201,-3420,-3748,1.04273056983948 +11935,0.011676988564432,-0.015497490763664,-0.009962096810341,41239,-1276,-2726,-3707,1.04067873954773 +11937,0.011178801767528,-0.026240644976497,-0.005644105374813,41239,-1282,-2168,-3707,1.03361487388611 +11939,0.009268379770219,-0.028989570215345,-0.001634271233343,41239,-1125,-2748,-3653,1.02903807163239 +11941,0.005757629871368,-0.031921297311783,-0.001935678883456,41239,-976,-2617,-3665,1.02421009540558 +11943,-0.000548607611563,-0.028274480253458,-0.000860289728735,41239,-673,-3199,-3649,1.0236314535141 +11945,0.000138894101838,-0.027472589164972,0.003392010461539,41239,-1181,-2935,-3604,1.02420234680176 +11947,0.002982092322782,-0.023277137428522,0.002643028507009,41239,-1379,-3294,-3626,1.02312541007996 +11949,0.001220778911375,-0.020533809438348,-0.000891826639418,41239,-1021,-3167,-3655,1.02584743499756 +11951,-0.001079530455172,-0.02820042707026,-0.00026769094984,41239,-952,-2360,-3647,1.02591156959534 +11953,-0.010737757198513,-0.025748891755939,0.002043220913038,41239,-254,-3042,-3622,1.02574753761292 +11955,-0.015803512185812,-0.028892548754811,0.000812374113593,41239,-536,-2657,-3641,1.02342748641968 +11957,-0.021449459716678,-0.029833426699042,-0.001624806318432,41239,-371,-2720,-3666,1.01973652839661 +11959,-0.024537820369005,-0.040603216737509,-0.00139942986425,41239,-544,-1924,-3658,1.02093458175659 +11961,-0.027471603825688,-0.047559008002281,-0.002148832660168,41239,-454,-1986,-3674,1.01986420154572 +11963,-0.032005541026592,-0.044343434274197,-0.002459765877575,41239,-320,-2847,-3667,1.02187120914459 +11965,-0.032314416021109,-0.043117128312588,-0.000647340610158,41239,-543,-2618,-3658,1.02597093582153 +11967,-0.030833665281534,-0.03755421563983,0.002404059981927,41239,-752,-3089,-3635,1.02590620517731 +11969,-0.027561873197556,-0.035470142960548,0.003392201149836,41239,-861,-2780,-3612,1.02380669116974 +11971,-0.029244920238853,-0.029417747631669,0.00078518234659,41239,-534,-3220,-3647,1.02454578876495 +11973,-0.033888451755047,-0.028777247294784,0.001027560443617,41239,-181,-2762,-3641,1.02854943275452 +11975,-0.035343751311302,-0.037503592669964,0.007550077047199,41239,-417,-2533,-3565,1.02207148075104 +11977,-0.035343751311302,-0.037503592669964,0.007550077047199,41239,-417,-2533,-3565,1.02207148075104 +11979,-0.034622732549906,-0.035516336560249,0.00755720725283,41239,-598,-2802,-3601,1.0197868347168 +11981,-0.027328295633197,-0.031926836818457,0.002637234283611,41239,-1198,-2373,-3636,1.02916359901428 +11983,-0.021831011399627,-0.033296354115009,-0.00105299486313,41239,-1063,-2504,-3667,1.0299905538559 +11985,-0.024506516754627,-0.028804048895836,-0.002230608137324,41239,-475,-3044,-3671,1.03294765949249 +11987,-0.025332007557154,-0.026252891868353,9.45934516494162E-06,41239,-533,-2880,-3656,1.03469240665436 +11989,-0.025332007557154,-0.026252891868353,9.45934516494162E-06,41239,-533,-2880,-3656,1.03469240665436 +11991,-0.019702488556504,-0.026711635291576,0.0024993813131,41239,-1006,-2428,-3628,1.02913725376129 +11993,-0.016622584313154,-0.015857178717852,-0.00212090369314,41239,-976,-3653,-3672,1.02680587768555 +11995,-0.010507335886359,-0.013404884375632,-0.001858761999756,41239,-1253,-3041,-3681,1.02027595043182 +11997,-0.007662280462682,-0.01166145503521,0.003992266952991,41239,-1081,-3049,-3632,1.00619924068451 +11999,-0.007662280462682,-0.01166145503521,0.003992266952991,41239,-1081,-3049,-3632,1.00619924068451 +12001,-0.011976127512753,-0.018021045252681,0.000881322543137,41239,-870,-2293,-3654,1.0093868970871 +12003,-0.002297739963979,-0.014273936860263,-0.002402665093541,41239,-1623,-3105,-3689,1.01833403110504 +12005,0.008310470730066,-0.012127890251577,-0.001699561602436,41239,-1854,-3051,-3673,1.02866280078888 +12007,0.00826037209481,-0.008695763535798,0.002457961440086,41239,-1089,-3164,-3633,1.02834570407867 +12009,0.00826037209481,-0.008695763535798,0.002457961440086,41239,-1089,-3164,-3633,1.02834570407867 +12011,0.004673722200096,-0.005840422119945,0.003374628024176,41239,-1202,-3113,-3623,1.02030277252197 +12013,0.013281799852848,-0.002048378344625,-0.000274909776635,41239,-1781,-3297,-3665,1.01353418827057 +12015,0.022602260112763,-0.009130754508078,-0.00030769611476,41239,-2007,-2384,-3668,1.00843834877014 +12017,0.019712781533599,-0.005185709800571,0.002062136074528,41239,-1058,-3254,-3650,1.00625848770142 +12019,0.019712781533599,-0.005185709800571,0.002062136074528,41239,-1058,-3254,-3650,1.00625848770142 +12021,0.021252781152725,-0.004951330367476,0.001394802355208,41239,-1585,-3228,-3656,0.993332862854004 +12023,0.027246210724115,0.002004694193602,0.003474661847577,41239,-1877,-3571,-3625,0.996322095394134 +12025,0.027526682242751,0.005316739436239,0.002687012311071,41239,-1419,-3350,-3648,1.00572764873505 +12027,0.022212263196707,0.005763568915427,0.002346665132791,41239,-996,-3167,-3639,1.01644313335419 +12029,0.021888200193644,0.007829800248146,0.003520838683471,41239,-1305,-3297,-3643,1.02442359924316 +12031,0.026437127962709,0.020093284547329,0.004231756553054,41239,-1786,-4247,-3618,1.02607762813568 +12033,0.029002880677581,0.024890786036849,0.006702331826091,41239,-1628,-3744,-3622,1.02985382080078 +12035,0.029143629595637,0.021563721820712,0.008359933272004,41239,-1538,-3160,-3569,1.03203868865967 +12037,0.02583053894341,0.014786785468459,0.008433446288109,41239,-1178,-2777,-3610,1.03198146820068 +12039,0.025338547304273,0.016227973625064,0.011875322088599,41239,-1448,-3420,-3528,1.0319961309433 +12041,0.025448180735111,0.022395791485906,0.012986255809665,41239,-1432,-3818,-3578,1.0311530828476 +12043,0.026895258575678,0.009830023162067,0.008383048698306,41239,-1617,-2314,-3568,1.02444672584534 +12045,0.022072734311223,0.004195085261017,0.005675964988768,41239,-1044,-2713,-3628,1.01775658130646 +12047,0.016736837103963,0.002712375484407,0.009654026478529,41239,-965,-2984,-3553,1.01764321327209 +12049,0.014175773598254,0.008858473971486,0.01288968231529,41239,-1100,-3621,-3578,1.0147545337677 +12051,0.008467061445117,0.014590484090149,0.011509709991515,41239,-802,-3692,-3531,1.01075518131256 +12053,0.001470604562201,0.012147373519838,0.007525646593422,41239,-603,-3055,-3615,1.008584856987 +12055,-0.004068066366017,0.011141178198159,0.006503130309284,41239,-617,-3152,-3590,1.00703060626984 +12057,-0.000254473619862,0.000831040844787,0.00717541621998,41239,-1350,-2328,-3617,1.00979793071747 +12059,0.005286305211484,-0.002499676775187,0.008326319046319,41239,-1560,-2763,-3569,1.00793397426605 +12061,0.003317173570395,-0.001053970423527,0.011568125337362,41239,-989,-3138,-3587,1.0065530538559 +12063,-0.005417517852038,-0.007043002638966,0.014090191572905,41239,-363,-2495,-3500,1.01139080524445 +12065,-0.010324094444513,-0.011718452908099,0.01369449403137,41239,-579,-2539,-3571,1.01946914196014 +12067,-0.005534433294088,-0.020908975973725,0.010279141366482,41239,-1330,-2034,-3544,1.02569496631622 +12069,-0.006803036201745,-0.017851483076811,0.008620121516287,41239,-887,-2991,-3606,1.03039515018463 +12071,-0.010628541000187,-0.022645419463515,0.012270700186491,41239,-629,-2309,-3520,1.0332727432251 +12073,-0.016127999871969,-0.02274926751852,0.011486856266856,41239,-446,-2681,-3585,1.03103268146515 +12075,-0.019489718601108,-0.019975580275059,0.009184763766825,41239,-515,-2878,-3556,1.02699959278107 +12077,-0.024022802710533,-0.018798880279064,0.011072868481279,41239,-393,-2816,-3588,1.02486491203308 +12079,-0.029625676572323,-0.018552137538791,0.013228046707809,41239,-183,-2704,-3508,1.0215585231781 +12081,-0.032201699912548,-0.023861631751061,0.012726706452668,41239,-404,-2266,-3576,1.02129423618317 +12083,-0.028020041063428,-0.026246162131429,0.011781354434788,41239,-896,-2382,-3524,1.01870942115784 +12085,-0.025550380349159,-0.022851882502437,0.014371144585312,41239,-849,-2888,-3564,1.02217519283295 +12087,-0.024595955386758,-0.022638333961368,0.015669774264097,41239,-712,-2616,-3477,1.02973282337189 +12089,-0.021513676270843,-0.019729880616069,0.014695392921567,41239,-940,-2885,-3560,1.03735458850861 +12091,-0.016160182654858,-0.02633048966527,0.014821224845946,41239,-1155,-2054,-3486,1.04043996334076 +12093,-0.019667875021696,-0.018146296963096,0.01435371581465,41239,-488,-3270,-3561,1.03720188140869 +12095,-0.023707808926702,-0.015307562425733,0.014358101412654,41239,-341,-2893,-3491,1.03298544883728 +12097,-0.024050485342741,-0.006437791977078,0.012317438609898,41239,-641,-3477,-3574,1.02713143825531 +12099,-0.018879503011704,-0.00347038032487,0.009253928437829,41239,-1066,-3082,-3550,1.0198187828064 +12101,-0.013241583481431,-0.006645313929766,0.007507252506912,41239,-1214,-2605,-3607,1.01656675338745 +12103,-0.00992183573544,-0.006281624082476,0.008265544660389,41239,-1076,-2842,-3561,1.01643717288971 +12105,-0.012597904540598,-0.005807766225189,0.00849230773747,41239,-623,-2871,-3600,1.0164510011673 +12107,-0.012113199569285,-0.00304082641378,0.008056913502514,41239,-827,-3066,-3564,1.01306080818176 +12123,0.003449858631939,0.01605268009007,0.01131989993155,41239,-1482,-3520,-3521,1.02393412590027 +12125,0.009099668823183,0.011247523128986,0.006429985165596,41239,-1515,-2729,-3611,1.02519118785858 +12127,0.008814894594252,0.010965328663588,0.0054866313003,41239,-1128,-3071,-3590,1.02667701244354 +12129,0.003107433905825,0.015477302484214,0.005916230846196,41239,-622,-3459,-3614,1.02804970741272 +12131,-0.000454902619822,0.023339862003923,0.005288348533213,41239,-741,-3867,-3593,1.02808845043182 +12133,0.002653658622876,0.019785311073065,0.005801603198051,41239,-1249,-2951,-3616,1.03007280826569 +12135,0.008963955566287,0.017799137160182,0.007104414049536,41239,-1609,-3075,-3572,1.03342092037201 +12137,0.005556378979236,0.021299647167325,0.009305841289461,41239,-831,-3483,-3592,1.04026579856873 +12139,0.003377276938409,0.016709731891751,0.011291469447315,41239,-925,-2863,-3522,1.04334485530853 +12141,0.005157161038369,0.023955214768648,0.012953330762684,41239,-1203,-3793,-3566,1.04221773147583 +12143,0.013683683238924,0.026590384542942,0.011547506786883,41239,-1860,-3544,-3518,1.03635561466217 +12145,0.012960284948349,0.031023148447275,0.008565017022192,41239,-1145,-3700,-3595,1.03345584869385 +12147,0.010841073468328,0.025980453938246,0.010888767428696,41239,-1050,-2992,-3525,1.03290987014771 +12149,0.009871215559542,0.026377169415355,0.013543289154768,41239,-1090,-3351,-3561,1.03284382820129 +12151,0.005834023468196,0.032477412372828,0.010956321842969,41239,-823,-3912,-3524,1.02862894535065 +12153,0.004530961159617,0.034786261618137,0.005814108997583,41239,-991,-3620,-3613,1.02583920955658 +12155,0.006980524864048,0.042713306844235,0.00211918191053,41239,-1301,-4222,-3628,1.02307164669037 +12157,0.009363258257508,0.044458493590355,0.004228352569044,41239,-1326,-3734,-3625,1.0201370716095 +12159,0.003852874273434,0.043743032962084,0.009459927678108,41239,-682,-3623,-3542,1.01844215393066 +12161,-0.005810238886625,0.039842631667852,0.013928973115981,41239,-245,-3278,-3558,1.02065360546112 +12163,-0.004573830403388,0.033320557326079,0.012681731022894,41239,-1027,-3049,-3504,1.01704204082489 +12165,-0.003008728381246,0.031638704240322,0.009511220268905,41239,-1086,-3329,-3588,1.01510107517242 +12167,-0.002792395185679,0.023426625877619,0.008835275657475,41239,-981,-2787,-3549,1.02073919773102 +12169,-0.008229404687881,0.029755769297481,0.009529558010399,41239,-507,-3883,-3587,1.03218078613281 +12171,-0.005683979950845,0.029486397281289,0.009537484496832,41239,-1108,-3465,-3540,1.0439977645874 +12173,-0.00151419849135,0.024210598319769,0.010771805420518,41239,-1289,-2983,-3578,1.05137538909912 +12175,-0.005544167477638,0.024788668379188,0.010938760824502,41239,-639,-3467,-3523,1.05156302452087 +12177,-0.01185592263937,0.022730296477676,0.009898945689201,41239,-388,-3201,-3584,1.04961323738098 +12179,-0.017174305394292,0.022298097610474,0.008659430779517,41239,-355,-3363,-3549,1.04513788223267 +12181,-0.014292998239398,0.014239029027522,0.010585268028081,41239,-1005,-2658,-3579,1.0437628030777 +12183,-0.015027976594865,0.018320340663195,0.013993525877595,41239,-712,-3626,-3486,1.03741300106049 +12185,-0.017899120226503,0.01906144246459,0.01461935415864,41239,-535,-3364,-3550,1.03313803672791 +12187,-0.019194301217795,0.004374907817692,0.010696668177843,41239,-594,-2057,-3524,1.02606332302094 +12189,-0.017038032412529,-0.009271650575101,0.005661990027875,41239,-899,-1926,-3611,1.02161765098572 +12191,-0.013006811961532,-0.01452452596277,0.008176784962416,41239,-1063,-2413,-3554,1.0224369764328 +12193,-0.01238667126745,-0.006800377741456,0.013935775496066,41239,-849,-3482,-3554,1.02623379230499 +12195,-0.013342650607228,-0.007731764577329,0.01337605342269,41239,-692,-2820,-3492,1.02780115604401 +12197,-0.018165402114391,-0.014834756962955,0.010424677282572,41239,-369,-2297,-3577,1.02311944961548 +12199,-0.023491537198424,-0.012433624826372,0.009202647954226,41239,-210,-2972,-3540,1.01626801490784 +12201,-0.017054511234164,-0.015035845339298,0.010115039534867,41239,-1181,-2606,-3579,1.01511693000793 +12203,-0.009905606508255,-0.01561520434916,0.011892946437001,41239,-1323,-2688,-3508,1.01403939723969 +12205,-0.000466672383482,-0.031450062990189,0.013831100426614,41239,-1630,-1409,-3553,1.01151180267334 +12207,-0.005993574857712,-0.031529229134321,0.01332469843328,41239,-470,-2459,-3491,1.008380651474 +12209,-0.009875529445708,-0.032571874558926,0.013395621441305,41239,-538,-2433,-3555,1.01401972770691 +12211,-0.007733134087175,-0.02904255874455,0.014212246984243,41239,-985,-2741,-3479,1.01924932003021 +12213,-0.006559943780303,-0.02907669916749,0.014619871973991,41239,-943,-2538,-3545,1.02633476257324 +12215,-0.008810038678348,-0.03124582208693,0.015029189176858,41239,-648,-2278,-3468,1.03098022937775 +12217,-0.004654598422349,-0.023892326280475,0.016827406361699,41239,-1180,-3123,-3529,1.02938556671143 +12219,0.00538178673014,-0.023784264922142,0.017966696992517,41239,-1762,-2550,-3432,1.02652132511139 +12221,0.013231695629656,-0.027010791003704,0.015174462459982,41239,-1704,-2305,-3538,1.01817512512207 +12223,0.008297140710056,-0.026944914832711,0.009577622637153,41239,-751,-2479,-3530,1.01161456108093 +12225,0.007593685761094,-0.026912806555629,0.007047155406326,41239,-1016,-2524,-3594,1.01180946826935 +12227,0.00974650029093,-0.018472760915756,0.008917314000428,41239,-1284,-3204,-3537,1.01337289810181 +12229,0.016023613512516,-0.019737733528018,0.012448768131435,41239,-1643,-2521,-3556,1.01448631286621 +12231,0.017456704750657,-0.010297487489879,0.015331437811256,41239,-1357,-3411,-3461,1.01462769508362 +12233,0.021649098023772,-0.007627214305103,0.018482277169824,41239,-1582,-2971,-3514,1.02037560939789 +12235,0.018435493111611,-0.001836921437643,0.017497733235359,41239,-1044,-3277,-3434,1.02559661865234 +12237,0.015088073909283,-0.003469858318567,0.015056337229908,41239,-956,-2719,-3535,1.02901613712311 +12239,0.015854245051742,-0.005872237030417,0.015823317691684,41239,-1292,-2611,-3452,1.02511584758759 +12241,0.019732775166631,0.001209665089846,0.016170443966985,41239,-1546,-3403,-3526,1.01900804042816 +12243,0.02587453648448,0.003299617907032,0.014624934643507,41239,-1851,-3075,-3465,1.0110377073288 +12245,0.030399670824409,0.007105580996722,0.014721742831171,41239,-1757,-3250,-3535,1.00608313083649 +12247,0.025668013840914,0.014735072851181,0.016587264835835,41239,-1077,-3653,-3440,1.00973641872406 +12249,0.022827344015241,0.014526158571243,0.018660573288798,41239,-1132,-3071,-3506,1.01236653327942 +12251,0.025090452283621,0.01711292937398,0.016850017011166,41239,-1569,-3329,-3435,1.01212406158447 +12253,0.032044656574726,0.018480828031898,0.01538944337517,41239,-1974,-3243,-3527,1.01182651519775 +12255,0.027265455573797,0.024642530828714,0.014856151305139,41239,-1109,-3707,-3457,1.01267182826996 +12271,0.026220647618175,0.030183671042323,0.018102714791894,41239,-1859,-4001,-3412,1.01488327980042 +12273,0.023704875260592,0.026548532769084,0.020266791805625,41239,-1228,-3025,-3485,1.02045226097107 +12275,0.015924979001284,0.021719699725509,0.018099108710885,41239,-785,-2917,-3410,1.02417802810669 +12277,0.010526153258979,0.014025533571839,0.017628723755479,41239,-842,-2562,-3501,1.02739584445953 +12279,0.009415983222425,0.021084813401103,0.017544005066156,41239,-1173,-3766,-3415,1.03185939788818 +12281,0.012637432664633,0.022948844358325,0.016543421894312,41239,-1497,-3382,-3507,1.04256629943848 +12283,0.008624951355159,0.030997142195702,0.0186254568398,41239,-964,-4003,-3400,1.04463231563568 +12285,0.004302349872887,0.034853711724281,0.01926177367568,41239,-845,-3706,-3486,1.04103076457977 +12287,0.003851250745356,0.03069319576025,0.019944999366999,41239,-1146,-3138,-3383,1.03419208526611 +12289,-0.004778820089996,0.027043400332332,0.022668983787298,41239,-412,-3068,-3461,1.02833414077759 +12291,-0.01581285148859,0.018982812762261,0.02414571121335,41239,-50,-2672,-3331,1.02718818187714 +12293,-0.016745517030358,0.013036800548434,0.023547191172838,41239,-785,-2708,-3452,1.02146089076996 +12295,-0.01365418639034,0.009351479820907,0.02042648755014,41239,-1086,-2829,-3372,1.01915955543518 +12297,-0.010920763015747,0.00410614721477,0.019327083602548,41239,-1124,-2631,-3479,1.01550018787384 +12299,-0.010356564074755,0.001835527946241,0.019587520509958,41239,-956,-2805,-3380,1.01353847980499 +12301,-0.010517537593842,-0.002954327501357,0.019792042672634,41239,-918,-2559,-3473,1.01098656654358 +12303,-0.014189780689776,0.002159260679036,0.020847521722317,41239,-582,-3340,-3363,1.0085905790329 +12305,-0.018288532271981,-0.000288066628855,0.019884815439582,41239,-518,-2762,-3470,1.00517880916595 +12307,-0.019570104777813,-0.000998357427306,0.018962610512972,41239,-661,-2878,-3383,0.999702751636505 +12309,-0.015137652866542,-0.005556772463024,0.016782447695732,41239,-1166,-2533,-3490,1.00582134723663 +12311,-0.009149234741926,-0.017261616885662,0.01758043281734,41239,-1343,-1822,-3397,1.01479268074036 +12313,-0.013221226632595,-0.019764574244619,0.020433533936739,41239,-579,-2467,-3463,1.01954793930054 +12315,-0.021566852927208,-0.013287230394781,0.020404225215316,41239,-106,-3177,-3362,1.02215182781219 +12317,-0.027309786528349,0.001025007339194,0.016370629891753,41239,-247,-3961,-3488,1.02312517166138 +12319,-0.028740363195539,-0.002970897359774,0.013517102226615,41239,-482,-2583,-3441,1.02337491512299 +12321,-0.022571029141545,-0.022591147571802,0.011787065304816,41239,-1156,-1187,-3519,1.0204735994339 +12323,-0.020893689244986,-0.030987044796348,0.008879318833351,41239,-826,-1800,-3495,1.02105736732483 +12325,-0.023150503635407,-0.031220072880387,0.01053923740983,41239,-537,-2434,-3527,1.01842939853668 +12327,-0.028335671871901,-0.020258981734514,0.015011813491583,41239,-204,-3347,-3422,1.01886737346649 +12329,-0.02371271699667,-0.018368363380432,0.018485756590962,41239,-1010,-2758,-3471,1.01830852031708 +12331,-0.014266733080149,-0.018937677145004,0.01877848431468,41239,-1470,-2532,-3376,1.02032899856567 +12333,-0.011386659927666,-0.022332226857543,0.015839319676161,41239,-1057,-2311,-3487,1.02821314334869 +12335,-0.004517804831266,-0.026058981195092,0.015456339344382,41239,-1433,-2168,-3414,1.0350341796875 +12337,-0.001279110787436,-0.017519207671285,0.016037102788687,41239,-1225,-3218,-3484,1.03818488121033 +12339,-0.001834086026065,-0.012079696170986,0.016185253858566,41239,-932,-3036,-3403,1.03623127937317 +12341,-0.008382853120565,-0.002621586434543,0.016709523275495,41239,-419,-3487,-3478,1.02972495555878 +12343,-0.008725963532925,-0.000523891532794,0.017222940921784,41239,-835,-2977,-3389,1.02730309963226 +12345,-0.001900293747894,-0.006204897537828,0.015811052173376,41239,-1465,-2346,-3482,1.02464926242828 +12347,0.004954725969583,-0.008637837134302,0.013017293997109,41239,-1572,-2519,-3438,1.02105689048767 +12349,0.012878802604973,-0.006633915007114,0.01026308350265,41239,-1757,-2882,-3520,1.01588308811188 +12351,0.019488839432597,0.009553987532854,0.010486953891814,41239,-1796,-4147,-3466,1.01304829120636 +12353,0.026439184322953,0.018408391624689,0.01299071777612,41239,-1890,-3733,-3500,1.01631712913513 +12355,0.02557535469532,0.015625942498446,0.01149495318532,41239,-1373,-2895,-3454,1.0212961435318 +12357,0.016216656193137,0.006240693386644,0.01361561473459,41239,-587,-2257,-3495,1.0259222984314 +12359,0.016052784398198,-0.002409933367744,0.019311767071486,41239,-1285,-2184,-3360,1.02686846256256 +12361,0.024909652769566,0.00519247027114,0.017617627978325,41239,-2025,-3455,-3465,1.02441394329071 +12363,0.03504191339016,0.014492020010948,0.015230254270136,41239,-2343,-3751,-3406,1.02104926109314 +12365,0.040368255227804,0.023466672748327,0.014310906641185,41239,-2011,-3821,-3487,1.02056348323822 +12367,0.044610768556595,0.018371457234025,0.012516868300736,41239,-2106,-2784,-3437,1.02475523948669 +12369,0.049983903765679,0.012181871570647,0.011129955761135,41239,-2176,-2580,-3508,1.02807867527008 +12371,0.046748109161854,0.010704388841987,0.011116354726255,41239,-1631,-2923,-3453,1.03033125400543 +12373,0.040634512901306,0.004972171969712,0.012116821482778,41239,-1244,-2512,-3500,1.03097712993622 +12375,0.037188500165939,0.004112691152841,0.011031642556191,41239,-1482,-2864,-3453,1.02932941913605 +12377,0.037939004600048,-0.000304579676595,0.010662887245417,41239,-1717,-2530,-3509,1.03025448322296 +12379,0.041421785950661,0.007187560200691,0.014459658414126,41239,-2067,-3515,-3412,1.03018093109131 +12381,0.038797680288553,0.019953085109592,0.017977997660637,41239,-1510,-4054,-3458,1.03281545639038 +12383,0.038087472319603,0.025468563660979,0.018111538141966,41239,-1725,-3664,-3367,1.02924525737762 +12385,0.035321328788996,0.028784519061446,0.016509283334017,41239,-1469,-3512,-3466,1.02386713027954 +12387,0.036989789456129,0.022519949823618,0.012668596580625,41239,-1882,-2777,-3430,1.01824235916138 +12389,0.03590689599514,0.022145280614495,0.009329725988209,41239,-1615,-3159,-3514,1.0163711309433 +12391,0.033912349492312,0.018131403252483,0.009354281239212,41239,-1588,-2869,-3468,1.01989638805389 +12393,0.036181699484587,0.011711282655597,0.010915447026491,41239,-1875,-2581,-3503,1.02001821994782 +12395,0.035327766090632,0.005028308834881,0.014557771384716,41239,-1705,-2471,-3406,1.01618933677673 +12397,0.029601342976093,0.002241731621325,0.01943975687027,41239,-1223,-2704,-3443,1.01181733608246 +12399,0.019083809107542,0.006727270316333,0.022124381735921,41239,-760,-3299,-3315,1.00811386108398 +12401,0.013172253966332,0.005319175776094,0.0222711507231,41239,-982,-2846,-3421,1.01044642925262 +12403,0.01559851039201,0.003554359544069,0.019931012764573,41239,-1642,-2797,-3338,1.01255238056183 +12405,0.012360347434878,0.003963540308177,0.019901251420379,41239,-1169,-2955,-3435,1.01832711696625 +12407,0.008725885301828,0.005326816812158,0.019183523952961,41239,-1108,-3052,-3345,1.01725852489471 +12409,0.002857275074348,0.011116383597255,0.015914807096124,41239,-850,-3443,-3460,1.01688373088837 +12411,0.000542632944416,0.006685095373541,0.015071357600391,41239,-1078,-2669,-3391,1.01391291618347 +12413,-0.007488972973078,0.004411081783474,0.014152150601149,41239,-548,-2771,-3471,1.01259291172028 +12415,-0.012009344063699,0.001880586380139,0.010819103568792,41239,-718,-2729,-3440,1.01889133453369 +12417,-0.00575670786202,-0.007024053484201,0.009485717862844,41239,-1593,-2131,-3502,1.02380478382111 +12419,-0.005020217970014,-0.016503017395735,0.012570459395647,41239,-1202,-1934,-3419,1.02442264556885 +12421,-0.014511477202177,-0.023086987435818,0.021084865555167,41239,-339,-2059,-3421,1.02671825885773 +12423,-0.022716913372278,-0.020798973739147,0.026892455294728,41239,-271,-2695,-3248,1.02678382396698 +12425,-0.019476035609841,-0.023725120350719,0.028256149962545,41239,-1172,-2302,-3368,1.03001427650452 +12427,-0.019807582721114,-0.020882887765765,0.026901923120022,41239,-872,-2714,-3244,1.02867639064789 +12429,-0.029246194288135,-0.013550382107496,0.026297820731998,41239,-115,-3171,-3378,1.02534699440002 +12431,-0.035880360752344,-0.013795040547848,0.022744908928871,41239,-142,-2591,-3290,1.01837313175201 +12433,-0.031430520117283,-0.023230630904436,0.016826063394547,41239,-1063,-1821,-3441,1.0118807554245 +12435,-0.026206852868199,-0.028950359672308,0.015487226657569,41239,-1129,-1938,-3374,1.01057708263397 +12437,-0.028575045987964,-0.018408782780171,0.018228121101856,41239,-602,-3304,-3430,1.01514792442322 +12439,-0.0318673402071,-0.007776383310556,0.018169686198235,41239,-411,-3437,-3340,1.02396595478058 +12441,-0.025900080800057,-0.005484405905008,0.017422437667847,41239,-1222,-2891,-3433,1.03053557872772 +12443,-0.019898688420653,-0.002949542133138,0.017004705965519,41239,-1260,-2930,-3352,1.02938640117645 +12445,-0.014255023561418,-0.007202265784144,0.017705764621496,41239,-1356,-2392,-3429,1.02844226360321 +12447,-0.02042886428535,-0.008688611909747,0.020364353433251,41239,-381,-2538,-3310,1.02385377883911 +12449,-0.020736396312714,-0.022106800228357,0.022824872285128,41239,-829,-1512,-3392,1.02157807350159 +12451,-0.013802549801767,-0.020207244902849,0.018278768286109,41239,-1418,-2591,-3333,1.01792860031128 +12453,-0.009628885425627,-0.01454068813473,0.012511586770415,41239,-1303,-2975,-3461,1.01853537559509 +12455,-0.008920604363084,-0.018331730738282,0.012504636310041,41239,-1051,-2211,-3399,1.01873636245728 +12457,-0.006820121314377,-0.022280305624008,0.018452364951372,41239,-1192,-2165,-3419,1.02291131019592 +12459,-0.006005826871842,-0.022714223712683,0.025047766044736,41239,-1101,-2367,-3249,1.0273289680481 +12461,-0.008105079643428,-0.010750784538686,0.025772048160434,41239,-871,-3458,-3365,1.03183662891388 +12463,-0.009780905209482,-0.004782185889781,0.021644739434123,41239,-855,-3101,-3286,1.0388046503067 +12465,-0.002952233655378,-0.003365736920387,0.01939706876874,41239,-1580,-2802,-3407,1.03520035743713 +12467,0.005715848878026,0.000789170502685,0.015950083732605,41239,-1856,-3055,-3351,1.02665483951569 +12469,0.012215523049235,0.001168254297227,0.013750517740846,41239,-1778,-2790,-3444,1.02320373058319 +12471,0.013104118406773,0.008320620283484,0.014153454452753,41239,-1415,-3386,-3371,1.02351844310761 +12473,0.01623596996069,0.001899519353174,0.01638431660831,41239,-1601,-2312,-3424,1.02377092838287 +12475,0.018660234287381,0.000946007552557,0.017669031396508,41239,-1602,-2684,-3328,1.02088630199432 +12477,0.01918525993824,0.010829724371433,0.017896562814713,41239,-1462,-3604,-3412,1.02199840545654 +12479,0.023404410108924,0.016424708068371,0.015594298951328,41239,-1809,-3395,-3351,1.02416241168976 +12481,0.027606345713139,0.01793727837503,0.013584916479886,41239,-1852,-3108,-3440,1.02503323554993 +12483,0.035218197852373,0.007464305963367,0.015582730062306,41239,-2251,-2091,-3349,1.02295637130737 +12497,0.034255977720022,0.025921992957592,0.013642203062773,41239,-2059,-3332,-3433,1.00805449485779 +12499,0.034143995493651,0.030050070956349,0.014518395066261,41239,-1758,-3535,-3355,1.01360583305359 +12501,0.026087878271937,0.025851907208562,0.012227769941092,41239,-1018,-2831,-3442,1.01981163024902 +12503,0.025140255689621,0.024766229093075,0.011703259311617,41239,-1582,-3085,-3387,1.02902698516846 +12505,0.031465087085962,0.034816391766071,0.013809050433338,41239,-2141,-3988,-3430,1.03774952888489 +12507,0.034943722188473,0.034651197493076,0.016949515789747,41239,-2084,-3323,-3324,1.03679823875427 +12509,0.024130137637258,0.036746770143509,0.019726168364287,41239,-829,-3459,-3387,1.02844572067261 +12511,0.009937237016857,0.036984279751778,0.0214007422328,41239,-424,-3405,-3270,1.02602958679199 +12513,0.00689667603001,0.033564727753401,0.019100315868855,41239,-1147,-3032,-3389,1.02360570430756 +12515,0.00474065868184,0.028580415993929,0.017345203086734,41239,-1189,-2906,-3315,1.02162480354309 +12517,-0.003465893445537,0.017290281131864,0.019122244790197,41239,-632,-2244,-3387,1.02017331123352 +12519,-0.013393216766417,0.014410911127925,0.02067463286221,41239,-324,-2827,-3274,1.01773357391357 +12521,-0.010118034668267,0.0080213136971,0.016060410067439,41239,-1352,-2465,-3405,1.0165901184082 +12523,-0.003538514953107,0.006435944698751,0.010586186312139,41239,-1663,-2791,-3391,1.01094377040863 +12525,-0.006597651634365,0.003580760909244,0.010586588643491,41239,-946,-2653,-3442,1.00785553455353 +12527,-0.017353218048811,0.000881843676325,0.012074353173375,41239,-193,-2617,-3373,1.00600445270538 +12529,-0.02036920003593,0.000344100786606,0.013116755522788,41239,-742,-2769,-3424,1.00471520423889 +12531,-0.015217098407447,-0.015082603320479,0.010649968869984,41239,-1360,-1443,-3388,1.00387895107269 +12533,-0.012705953791738,-0.019669314846397,0.00993955694139,41239,-1241,-2181,-3445,1.00831615924835 +12535,-0.013690057210624,-0.018537752330303,0.014061112888157,41239,-941,-2563,-3347,1.01879107952118 +12537,-0.014654642902315,-0.018409531563521,0.016969062387943,41239,-957,-2525,-3395,1.0268896818161 +12539,-0.017610561102629,-0.01721528545022,0.016311185434461,41239,-729,-2581,-3319,1.03565979003906 +12541,-0.025637721642852,-0.018220676109195,0.014175003394485,41239,-285,-2436,-3413,1.04149508476257 +12543,-0.036155838519335,-0.020148998126388,0.01606877706945,41239,125,-2295,-3320,1.03947496414185 +12545,-0.039813529700041,-0.030851729214192,0.017990967258811,41239,-378,-1547,-3385,1.0373467206955 +12547,-0.03405549004674,-0.042884029448032,0.014945608563721,41239,-1059,-1185,-3332,1.02756595611572 +12549,-0.035258125513792,-0.04266631603241,0.012125403620303,40720,-604,-2137,-3423,1.02176439762115 +12551,-0.041160076856613,-0.041030507534742,0.011152897961438,40720,-98,-2171,-3375,1.02065110206604 +12553,-0.047135803848505,-0.033144406974316,0.014396270737052,40720,-73,-2800,-3407,1.02188944816589 +12555,-0.044401202350855,-0.040090668946505,0.017564743757248,40720,-645,-1551,-3298,1.01867854595184 +12557,-0.039604008197785,-0.031621407717466,0.016114437952638,40720,-933,-2842,-3393,1.01602566242218 +12559,-0.031224973499775,-0.025684647262096,0.014140312559903,40720,-1237,-2688,-3337,1.02035391330719 +12561,-0.023003252223134,-0.021879753097892,0.011538616381586,40720,-1402,-2632,-3423,1.01966989040375 +12563,-0.014488215558231,-0.02083214186132,0.00988401658833,40720,-1502,-2399,-3386,1.01518833637238 +12565,-0.010691245086491,-0.015255745500326,0.008335715159774,40720,-1253,-2840,-3445,1.01226878166199 +12567,-0.007890607230365,-0.00648275250569,0.005354592110962,40720,-1194,-3170,-3439,1.00830185413361 +12569,-0.005174582824111,-0.002688188804314,0.004384731408209,40720,-1249,-2885,-3472,1.00713694095612 +12571,0.000915139564313,-0.001158812199719,0.005869513843209,40720,-1571,-2735,-3433,1.00374948978424 +12573,-0.0018986298237,0.007576027885079,0.008921938948333,40720,-899,-3381,-3441,1.00163018703461 +12575,-0.006147642154247,0.008773943409324,0.00639759702608,40720,-718,-2873,-3427,1.00502848625183 +12577,-0.008494005538523,0.013541486114264,0.001406764378771,40720,-834,-3183,-3492,1.01340210437775 +12579,0.002998593496159,0.005782819818705,-0.000893897900824,40720,-1995,-2187,-3513,1.0166232585907 +12581,0.008820912800729,0.011056715622544,0.00434943055734,40720,-1669,-3183,-3473,1.01674234867096 +12583,0.009855848737061,0.017944751307368,0.011139100417495,40720,-1363,-3441,-3371,1.02117705345154 +12585,0.006784628611058,0.027458351105452,0.011943307705224,39469,-1007,-3728,-3420,1.02468729019165 +12587,0.008817570284009,0.022008759900928,0.008846829645336,39469,-1432,-2634,-3397,1.02430844306946 +12589,0.0119260661304,0.005684983916581,0.00817085057497,39469,-1530,-1573,-3445,1.02088665962219 +12591,0.01712784357369,-0.000878668564837,0.009459247812629,39469,-1809,-2185,-3390,1.01884543895721 +12593,0.024208134040237,0.003438391024247,0.010247360914946,39469,-2002,-3017,-3430,1.01947951316834 +12595,0.030926626175642,0.013344901613891,0.009883867576718,39469,-2158,-3598,-3384,1.01870977878571 +12597,0.027885289862752,0.023447161540389,0.007732583209872,39469,-1347,-3724,-3447,1.01835751533508 +12599,0.023684469982982,0.021761575713754,0.003181682899594,39469,-1273,-2911,-3463,1.0190052986145 +12601,0.020114932209253,0.023652141913772,-0.000419552379753,39469,-1212,-3147,-3504,1.0197149515152 +12603,0.022165413945913,0.019785355776548,-0.000959680473898,39469,-1705,-2725,-3512,1.01915180683136 +12605,0.021938391029835,0.017920315265656,0.000397098192479,39469,-1491,-2803,-3499,1.01291382312775 +12607,0.018784746527672,0.014704502187669,0.00107686384581,39469,-1281,-2682,-3489,1.01045346260071 +12609,0.012323816306889,0.012151896953583,-0.000959691766184,39469,-917,-2673,-3509,1.00754356384277 +12611,0.00625515030697,0.017040582373738,-0.004529550671577,39469,-872,-3296,-3557,1.00394225120544 +12613,0.006054998841137,0.023191794753075,-0.004126877523959,39469,-1279,-3457,-3533,1.0022839307785 +12615,0.010445621795952,0.027806077152491,-0.002799103735015,39469,-1687,-3457,-3538,1.00051975250244 +12617,0.019114362075925,0.018811404705048,-0.002441143849865,39469,-2106,-2316,-3523,1.00065290927887 +12619,0.026773860678077,0.012005052529276,-0.00404650112614,39469,-2187,-2391,-3554,0.998449623584747 +12621,0.023793812841177,0.012579619884491,-0.004191350657493,39469,-1349,-2913,-3536,0.995648205280304 +12623,0.015036085620523,0.015415222384036,-0.005897286348045,38933,-829,-3136,-3578,0.995287716388702 +12625,0.000320575869409,0.022315803915262,-0.007345174904913,38933,-177,-3508,-3560,0.995164930820465 +12627,-0.005538277328014,0.015676567330957,-0.004537528846413,38933,-711,-2465,-3564,0.996322333812714 +12629,-0.003005659440532,0.011157468892634,-0.004048680420965,38933,-1362,-2533,-3539,0.994816660881042 +12631,0.003317089751363,0.004244979470968,-0.006371869705617,38933,-1734,-2266,-3587,0.995486617088318 +12649,-0.032103799283505,-0.036682274192572,-0.007827740162611,38933,-568,-2107,-3576,0.976669549942017 +12651,-0.02850547991693,-0.039645571261644,-0.008112669922411,38933,-965,-1786,-3619,0.972600996494293 +12653,-0.030444683507085,-0.038433328270912,-0.005792579147965,38933,-595,-2171,-3564,0.974828124046326 +12655,-0.031968746334314,-0.052870005369186,-0.00646860897541,38933,-531,-727,-3602,0.981748223304748 +12657,-0.035356592386961,-0.054352402687073,-0.010700994171202,38933,-406,-1722,-3600,0.986125111579895 +12659,-0.037817694246769,-0.053080923855305,-0.012412232346833,38933,-355,-1823,-3675,0.988486468791962 +12661,-0.043236061930657,-0.047840856015682,-0.006864803377539,38933,-130,-2269,-3577,0.987591803073883 +12663,-0.049668468534947,-0.044028285890818,-0.003209766466171,38933,138,-2126,-3569,0.982603788375854 +12665,-0.056519769132137,-0.04497354477644,-0.003374371211976,38933,185,-1842,-3554,0.978426873683929 +12667,-0.056418851017952,-0.043340031057596,-0.008836976252496,38933,-198,-1956,-3637,0.97678679227829 +12669,-0.052334524691105,-0.040437541902065,-0.012817369773984,38933,-632,-2159,-3622,0.980208039283752 +12671,-0.048327688127756,-0.03521453216672,-0.011629426851869,38933,-582,-2329,-3672,0.977270305156708 +12673,-0.048612382262945,-0.027663992717862,-0.008340409956872,38933,-349,-2656,-3594,0.976419866085052 +12675,-0.042860846966505,-0.027614595368505,-0.005679450463504,38933,-772,-2064,-3605,0.977086961269379 +12677,-0.034971833229065,-0.027438739314675,-0.005975000094622,38933,-1110,-2115,-3580,0.979614734649658 +12679,-0.024655669927597,-0.037860300391913,-0.008886197581887,38933,-1379,-1126,-3645,0.976913809776306 +12681,-0.02275463193655,-0.031241124495864,-0.006160138640553,38933,-844,-2501,-3584,0.977186262607574 +12683,-0.021842174232006,-0.027374461293221,-0.001127322437242,38933,-749,-2303,-3555,0.977075040340424 +12685,-0.018692517653108,-0.015907807275653,-0.003053503343835,38933,-983,-3052,-3564,0.973704278469086 +12687,-0.008635435253382,-0.015303358435631,-0.008221790194511,38933,-1617,-2253,-3641,0.975583791732788 +12689,-0.003944858442992,-0.016086736693978,-0.009694428183138,38933,-1302,-2161,-3612,0.97617906332016 +12691,-0.002950304187834,-0.016480443999171,-0.00839257799089,38933,-1044,-2146,-3645,0.976253092288971 +12693,-0.001039517577738,-0.019349567592144,-0.009455460123718,38933,-1143,-1953,-3612,0.981162428855896 +12695,0.003350478829816,-0.019989937543869,-0.012828170321882,38933,-1376,-2051,-3700,0.979554057121277 +12697,0.004617549944669,-0.020696816965938,-0.010338296182454,38575,-1176,-2073,-3622,0.974075555801392 +12699,0.004125214647502,-0.008635495789349,-0.007089469581842,38575,-1039,-3132,-3635,0.963953018188477 +12701,0.010471243411303,0.006093078292906,-0.006986395921558,38575,-1623,-3553,-3601,0.956009149551392 +12703,0.021371809765697,0.012786107137799,-0.007352206390351,38575,-2146,-3094,-3640,0.950681746006012 +12705,0.023626230657101,0.016675246879459,-0.005657562520355,38575,-1527,-2929,-3594,0.950122237205505 +12707,0.027412896975875,0.004241506569088,-0.005328278522938,38575,-1760,-1597,-3619,0.948872268199921 +12709,0.027381699532271,0.005817347671837,-0.00665954593569,38575,-1431,-2606,-3603,0.9567791223526 +12711,0.027699762955308,0.006028601899743,-0.00471758749336,38575,-1530,-2530,-3613,0.966457843780518 +12713,0.027351723983884,0.017192149534822,-0.005747037939727,38575,-1422,-3456,-3598,0.974811792373657 +12715,0.035014033317566,0.022213438525796,-0.007316771894693,38575,-2187,-3132,-3646,0.983460664749146 +12717,0.041013613343239,0.024019492790103,-0.005606756545603,38575,-2090,-2889,-3600,0.978737056255341 +12719,0.045369632542133,0.025058317929506,-0.004972531460226,38575,-2135,-2890,-3620,0.970559179782867 +12721,0.044996906071901,0.027418112382293,-0.007762169465423,38575,-1712,-2983,-3616,0.965849697589874 +12723,0.042018715292215,0.035775303840637,-0.009374978020787,38575,-1565,-3593,-3674,0.964501142501831 +12725,0.044049147516489,0.030484894290567,-0.007650325074792,38575,-1889,-2489,-3618,0.965355157852173 +12727,0.044860016554594,0.030045686289668,-0.007553685456514,38575,-1888,-2896,-3656,0.96172833442688 +12729,0.046800170093775,0.034310627728701,-0.006183865014464,38575,-1939,-3238,-3610,0.966647207736969 +12731,0.04340386390686,0.04599392041564,-0.004078513011336,38575,-1595,-4042,-3617,0.975592613220215 +12733,0.035641878843308,0.052290670573711,-0.005347417201847,38575,-1103,-3660,-3606,0.983440518379211 +12735,0.039564453065395,0.042525455355644,-0.007961867377162,38397,-2097,-2459,-3664,0.986259996891022 +12737,0.045244641602039,0.042395334690809,-0.007459694519639,38397,-2225,-3074,-3623,0.980443239212036 +12739,0.039675619453192,0.039704497903586,-0.00610117893666,38397,-1443,-2930,-3645,0.974862992763519 +12741,0.026895871385932,0.040760222822428,-0.009867461398244,38397,-661,-3149,-3642,0.967586755752564 +12743,0.022748155519366,0.035132668912411,-0.009478566236794,38397,-1280,-2657,-3687,0.964482605457306 +12745,0.025283969938755,0.030602103099227,-0.009108914993703,38397,-1748,-2615,-3639,0.958859384059906 +12747,0.024594642221928,0.027781076729298,-0.007851193659008,38397,-1560,-2751,-3670,0.953278005123138 +12749,0.014883248135448,0.022331740707159,-0.005265009123832,38397,-734,-2439,-3615,0.952033460140228 +12751,0.005994854494929,0.022959709167481,-0.0048827691935,38397,-677,-2926,-3637,0.953471124172211 +12753,0.003387155942619,0.015877267345786,-0.006830143276602,38397,-1081,-2235,-3628,0.954845368862152 +12755,-0.00171212584246,0.018780836835504,-0.009331653825939,38397,-827,-3030,-3692,0.952818870544434 +12757,-0.002458928851411,0.013008640147746,-0.010992597788572,38397,-1130,-2292,-3659,0.952044129371643 +12759,-0.007071012165397,0.012555985711515,-0.013945827260614,38397,-773,-2692,-3749,0.950229704380035 +12761,-0.006368191447109,-0.001475330558606,-0.015618801116943,38397,-1176,-1495,-3694,0.951287508010864 +12763,-0.006943214684725,-0.015660939738155,-0.012956065125764,38397,-1051,-1241,-3741,0.949255168437958 +12765,-0.018744967877865,-0.014141811989248,-0.011605793610215,38397,-98,-2416,-3670,0.94704657793045 +12767,-0.033662404865027,-0.009202992543578,-0.012379065155983,38397,414,-2704,-3738,0.944413304328918 +12769,-0.038276746869087,-0.005317560397089,-0.011798413470388,38397,-317,-2703,-3674,0.939414620399475 +12771,-0.034465920180082,-0.01473599858582,-0.0096714515239,38397,-904,-1578,-3709,0.938882231712341 +12773,-0.036794524639845,-0.017089990898967,-0.011095855385065,38397,-486,-2076,-3672,0.938968896865845 +12775,-0.038331598043442,-0.029002718627453,-0.013085056096315,38397,-444,-1160,-3752,0.942993879318237 +12777,-0.035185977816582,-0.03857883810997,-0.014046418480575,38397,-885,-1234,-3696,0.944273889064789 +12779,-0.034619826823473,-0.035083655267954,-0.014343427494168,38397,-639,-2151,-3770,0.949620485305786 +12781,-0.03377927839756,-0.038650032132864,-0.013289107009769,38397,-725,-1644,-3694,0.949635326862335 +12799,-0.014127919450402,-0.049993213266134,-0.012948148883879,38397,-1699,-1282,-3770,0.951872766017914 +12801,-0.008236726745963,-0.040243349969387,-0.011999603360891,38397,-1379,-2454,-3701,0.95341545343399 +12803,-0.006437668576837,-0.040541913360357,-0.009082024917007,38397,-1097,-1640,-3727,0.953921139240265 +12805,-0.008045176975429,-0.035315811634064,-0.010974675416947,38397,-841,-2177,-3697,0.954554378986358 +12807,0.000825083814561,-0.03929690644145,-0.012683369219303,38397,-1722,-1364,-3773,0.955519735813141 +12809,0.009205296635628,-0.044760763645172,-0.014486646279693,38397,-1805,-1251,-3724,0.9560546875 +12811,0.010777655057609,-0.044314030557871,-0.017476348206401,38397,-1370,-1579,-3833,0.960999011993408 +12813,0.014011027291417,-0.035908341407776,-0.018585091456771,38397,-1511,-2345,-3757,0.963059306144714 +12815,0.018300836905837,-0.018409105017781,-0.017476100474596,38397,-1690,-3203,-3837,0.959315240383148 +12817,0.021934444084764,-0.008573654107749,-0.013432312756777,38397,-1662,-2826,-3725,0.956256985664368 +12819,0.023748526349664,-0.003971087746322,-0.011559774167836,38397,-1604,-2501,-3771,0.947908937931061 +12821,0.026802599430084,-0.010499598458409,-0.008446050807834,38397,-1700,-1618,-3694,0.946272373199463 +12823,0.029978722333908,-0.003654537023976,-0.005293204449117,38397,-1815,-2657,-3699,0.943928182125092 +12825,0.031619720160961,-0.001666166703217,-0.00362891308032,38397,-1681,-2346,-3663,0.944524228572845 +12827,0.032514169812203,-0.007231283001602,-0.004347689449787,38397,-1711,-1708,-3690,0.946519076824188 +12829,0.029297726228833,0.004519020207226,-0.002386270323768,38397,-1315,-3126,-3656,0.954323947429657 +12831,0.031646076589823,0.003685020375997,-0.00074270850746,38397,-1820,-2224,-3649,0.961076378822327 +12833,0.035636633634567,0.003017614362761,-0.001507409033366,38397,-1938,-2213,-3651,0.967486083507538 +12835,0.042710594832897,0.002270260127261,-0.000568171497434,38397,-2357,-2206,-3648,0.965969741344452 +12837,0.035853359848261,0.016606053337455,-0.001721870154142,38397,-1185,-3480,-3654,0.960038959980011 +12839,0.032017439603806,0.015145192854107,-0.003377668559551,38397,-1429,-2357,-3682,0.953594088554382 +12841,0.031085861846805,0.015785397961736,-0.003884156700224,38397,-1558,-2489,-3670,0.942314982414246 +12843,0.031891752034426,0.02167758718133,-0.003660550573841,38397,-1770,-2986,-3688,0.942472219467163 +12845,0.033654041588307,0.029090391471982,-0.004196928814054,38397,-1804,-3168,-3674,0.945074677467346 +12847,0.034387867897749,0.037399761378765,-0.005327460821718,38397,-1814,-3426,-3709,0.949168264865875 +12849,0.0384273044765,0.03484334051609,-0.006469527259469,38397,-2053,-2548,-3692,0.95406574010849 +12851,0.039343047887087,0.038141377270222,-0.009652700275183,38397,-1938,-3098,-3762,0.958952307701111 +12853,0.039416581392288,0.030705232173205,-0.008818571455777,38397,-1804,-2153,-3711,0.968790650367737 +12855,0.032222457230091,0.035728387534618,-0.005660374648869,38397,-1279,-3187,-3717,0.97652542591095 +12857,0.03034015186131,0.029918625950813,-0.003713694633916,38397,-1554,-2268,-3678,0.977650463581085 +12859,0.02817215397954,0.025630014017224,-0.003832208458334,38397,-1591,-2359,-3698,0.971696197986603 +12861,0.016985896974802,0.032461881637573,-0.003710773773491,38397,-715,-3216,-3679,0.965667724609375 +12863,0.007446867413819,0.031139060854912,-0.004279966000468,38397,-725,-2668,-3705,0.963730812072754 +12865,0.007466189563274,0.033859189599753,-0.007774787023664,38397,-1388,-2950,-3709,0.958752393722534 +12867,0.007258490193635,0.030949003994465,-0.008186993189156,38397,-1387,-2565,-3753,0.956783950328827 +12869,-0.001998495543376,0.032509673386812,-0.00592854898423,38397,-592,-2857,-3699,0.954459309577942 +12871,-0.007276472635567,0.024307660758495,-0.002695126459003,38397,-788,-2088,-3691,0.956082820892334 +12873,-0.011084022931755,0.016628403216601,-0.003003713907674,38397,-850,-1973,-3680,0.956345558166504 +12875,-0.016065189614892,0.016571991145611,-0.003473405726254,38397,-661,-2554,-3702,0.954413056373596 +12877,-0.019478775560856,0.016888277605176,-0.003170260228217,38397,-751,-2553,-3683,0.949838161468506 +12879,-0.026613144204021,0.020977696403861,-0.002181644784287,38397,-322,-2923,-3688,0.947654545307159 +12881,-0.028279965743423,0.012290731072426,-0.003382449969649,38397,-738,-1847,-3686,0.948686301708221 +12883,-0.034978549927473,0.00725079793483,-0.002370443195105,38397,-200,-2044,-3692,0.949038326740265 +12885,-0.044312957674265,-0.005801521241665,0.001621416537091,38397,57,-1273,-3653,0.950022220611572 +12887,-0.055179242044687,-0.002492345869541,0.000988882384263,38397,433,-2480,-3653,0.945867121219635 +12889,-0.052560325711966,-0.005025586578995,0.001208884059452,38397,-657,-2031,-3657,0.9484943151474 +12891,-0.050651375204325,-0.006650232244283,0.002221962902695,38397,-530,-2051,-3640,0.947359800338745 +12893,-0.055134296417236,-0.007572869304568,0.003347637830302,38397,-89,-2101,-3643,0.951762199401856 +12895,-0.057281337678433,-0.016097214072943,0.004165504127741,38397,-95,-1390,-3617,0.953549385070801 +12897,-0.058710653334856,-0.015286528505385,0.007247590925545,38397,-229,-2101,-3617,0.95330023765564 +12899,-0.060220204293728,-0.026200819760561,0.011532224714756,38397,-63,-1036,-3531,0.950834512710571 +12901,-0.062064204365015,-0.026816440746188,0.012230155058205,38397,-121,-1815,-3582,0.948325276374817 +12903,-0.059618882834911,-0.029847955331206,0.012513239867985,38397,-330,-1520,-3518,0.950018048286438 +12905,-0.063125021755695,-0.021616037935019,0.01251638494432,38397,41,-2503,-3579,0.948904693126678 +12907,-0.059510089457035,-0.025121800601482,0.012602627277374,38397,-394,-1554,-3516,0.944910526275635 +12909,-0.05231910571456,-0.031405285000801,0.014835689216852,38397,-852,-1306,-3562,0.93944901227951 +12911,-0.049335666000843,-0.025671729817987,0.015491299331188,38397,-494,-2199,-3481,0.934537410736084 +12913,-0.047849513590336,-0.019163373857737,0.016269352287054,38397,-485,-2382,-3550,0.936808705329895 +12915,-0.046818424016237,-0.012378023937345,0.015972493216395,38397,-372,-2479,-3473,0.936384320259094 +12917,-0.044465634971857,-0.02051379904151,0.01465599052608,38397,-574,-1305,-3560,0.938592076301575 +12919,-0.043157894164324,-0.021029885858297,0.008836444467306,38397,-425,-1798,-3556,0.939679026603699 +12921,-0.035984568297863,-0.023747015744448,0.008536094799638,38397,-1020,-1632,-3601,0.943621575832367 +12923,-0.032351758331061,-0.01978250220418,0.009454439394176,38397,-746,-2116,-3549,0.946919322013855 +12925,-0.02907108142972,-0.022920837625861,0.010760080069304,38397,-824,-1598,-3585,0.95306795835495 +12927,-0.024084577336907,-0.030879350379109,0.010875687003136,38397,-965,-1065,-3531,0.955381751060486 +12929,-0.018158802762628,-0.018940947949886,0.013446532189846,38397,-1158,-2715,-3566,0.959961771965027 +12931,-0.01044967956841,-0.013997117988765,0.015476916916669,38397,-1374,-2248,-3476,0.959514379501343 +12933,-0.004212766420096,-0.008156100288033,0.014179018326104,38397,-1375,-2421,-3560,0.952530562877655 +12935,-0.000161852687597,-0.012656131759286,0.016355823725462,38397,-1280,-1586,-3464,0.946114838123322 +12937,-0.004045678768307,-0.005789444316179,0.018442757427693,38397,-652,-2517,-3529,0.938262939453125 +12939,0.003055919660255,-0.001747558126226,0.020515110343695,38397,-1559,-2367,-3413,0.94071614742279 +12941,0.013577704317868,0.009761694818735,0.019630927592516,38397,-1939,-3067,-3518,0.942920565605164 +12943,0.018854646012187,0.01990382373333,0.019802795723081,38397,-1679,-3152,-3418,0.950234413146973 +12945,0.016131442040205,0.019892184063792,0.019432237371802,38397,-1035,-2390,-3517,0.95711475610733 +12947,0.01404338516295,0.023114824667573,0.017873788252473,38397,-1071,-2711,-3439,0.959253072738647 +12949,0.017538649961352,0.01508528739214,0.019384905695915,38397,-1504,-1752,-3515,0.958919823169708 +12951,0.022802758961916,0.016322197392583,0.021344128996134,38397,-1747,-2460,-3396,0.955252408981323 +12953,0.030778326094151,0.011719537898898,0.019954400137067,38397,-2024,-1950,-3509,0.951921463012695 +12955,0.030195346102119,0.020493250340223,0.017437307164073,38397,-1467,-3074,-3440,0.948307693004608 +12957,0.034387145191431,0.018845045939088,0.015659751370549,38397,-1818,-2268,-3536,0.943021059036255 +12959,0.038006957620382,0.015768786892295,0.014295530505478,38397,-1916,-2165,-3475,0.938644349575043 +12961,0.036224499344826,0.030139354988933,0.014978293329477,38397,-1434,-3582,-3540,0.93947035074234 +12963,0.034382913261652,0.043972462415695,0.015185045078397,38397,-1489,-3849,-3463,0.944142878055572 +12965,0.035437472164631,0.050537459552288,0.016163798049092,38397,-1644,-3333,-3530,0.945714473724365 +12967,0.044704250991345,0.040599320083857,0.020378379151225,38397,-2464,-2103,-3400,0.949357748031616 +12969,0.050498675554991,0.036775164306164,0.023332122713328,38397,-2220,-2408,-3478,0.946263551712036 +12971,0.051339846104384,0.027198448777199,0.024035710841417,38397,-1989,-1912,-3354,0.948383927345276 +12973,0.046139765530825,0.030430611222983,0.018876871094108,38397,-1394,-2830,-3506,0.948733627796173 +12975,0.044012859463692,0.033978346735239,0.013913291506469,38397,-1674,-2977,-3471,0.948357105255127 +12977,0.04643914103508,0.031740453094244,0.012398333288729,38397,-1964,-2469,-3549,0.949850022792816 +12979,0.043614491820335,0.036993611603975,0.013559933751822,38397,-1639,-3168,-3474,0.95609039068222 +12981,0.042330555617809,0.036760732531548,0.017588952556253,38397,-1660,-2699,-3512,0.954723000526428 +12983,0.044349782168865,0.040289293974638,0.019313143566251,38397,-2021,-3114,-3404,0.948007464408874 +12985,0.046391543000937,0.033909160643816,0.019875260069966,38397,-1977,-2233,-3494,0.94160807132721 +12987,0.038870729506016,0.038253873586655,0.020908620208502,38397,-1280,-3144,-3383,0.935494482517242 +12989,0.040239036083222,0.030634695664048,0.021937664598227,38397,-1861,-2111,-3477,0.937308013439178 +12991,0.040484428405762,0.02684860676527,0.02218365855515,38397,-1870,-2382,-3366,0.938085079193115 +12993,0.035038873553276,0.028109477832913,0.023251872509718,38397,-1318,-2718,-3466,0.943655788898468 +12995,0.031226433813572,0.030780205503106,0.023974057286978,38397,-1442,-2919,-3342,0.946276128292084 +12997,0.024064550176263,0.033196326345205,0.020239174365997,38397,-1051,-2884,-3483,0.950713872909546 +12999,0.018700692802668,0.026335483416915,0.01516351941973,38397,-1160,-2179,-3443,0.955976724624634 +13001,0.022835563868284,0.035345353186131,0.015071051195264,38397,-1855,-3396,-3517,0.958285689353943 +13003,0.032326772809029,0.030735343694687,0.023607604205608,38397,-2463,-2418,-3341,0.960141181945801 +13005,0.029229553416371,0.032444413751364,0.02720258012414,38397,-1448,-2842,-3431,0.954632997512817 +13007,0.025997469201684,0.014703112654388,0.023211777210236,38397,-1442,-1228,-3343,0.944231629371643 +13009,0.018093332648277,0.005582931451499,0.019862540066242,38397,-955,-1685,-3478,0.940671443939209 +13011,0.006618311163038,0.013945158571005,0.022287331521511,38397,-533,-3093,-3351,0.948102235794067 +13033,-0.0427291020751,0.004527849610895,0.016848981380463,38397,-424,-2063,-3485,0.940323531627655 +13035,-0.044762302190065,-0.005109610501677,0.01813255622983,38397,-362,-1510,-3387,0.938189506530762 +13037,-0.051019940525293,-0.000829403928947,0.018575372174382,38397,-41,-2575,-3471,0.93433690071106 +13039,-0.046375423669815,-0.007454850710928,0.017524132505059,38397,-794,-1682,-3392,0.937206983566284 +13041,-0.051425602287054,0.00134404853452,0.018956691026688,38397,-101,-2923,-3467,0.940120160579681 +13043,-0.065617769956589,0.007745779119432,0.023930177092552,38397,899,-2853,-3314,0.947076201438904 +13045,-0.068964086472988,-0.002851232420653,0.024884559214115,38397,58,-1473,-3423,0.944670379161835 +13047,-0.071506023406983,-0.009343945421278,0.025818217545748,38397,187,-1648,-3288,0.944303452968597 +13049,-0.07311886548996,-0.016922757029533,0.027242241427302,38397,26,-1479,-3403,0.946293652057648 +13051,-0.071609005331993,-0.015883026644588,0.028109971433878,38397,-77,-2069,-3258,0.945613622665405 +13053,-0.067565985023975,-0.025714505463839,0.029882024973631,38397,-426,-1179,-3381,0.946293771266937 +13055,-0.064063683152199,-0.019962750375271,0.027016853913665,38397,-310,-2330,-3267,0.944543480873108 +13057,-0.057530824095011,-0.022844657301903,0.023264031857252,38397,-720,-1704,-3423,0.939456701278686 +13059,-0.056353487074375,-0.023080378770828,0.024240758270025,38397,-229,-1841,-3296,0.934917569160461 +13061,-0.058799095451832,-0.018392067402601,0.024975033476949,38397,-32,-2296,-3408,0.939679801464081 +13063,-0.056966356933117,-0.026306994259358,0.022469559684396,38397,-238,-1222,-3314,0.945701658725738 +13065,-0.052503168582916,-0.026417188346386,0.018696036189795,38397,-589,-1822,-3448,0.945646047592163 +13067,-0.046874798834324,-0.021530481055379,0.020012985914946,38397,-652,-2201,-3340,0.947772979736328 +13069,-0.043312881141901,-0.007132186088711,0.024984313175082,38397,-633,-3124,-3403,0.946293354034424 +13071,-0.035389617085457,-0.013226971030235,0.026536989957094,38397,-985,-1542,-3260,0.950076758861541 +13073,-0.031177999451757,-0.011341582983732,0.024799097329378,38397,-837,-2158,-3400,0.949088931083679 +13075,-0.026088586077094,-0.008274903520942,0.026000343263149,38397,-916,-2271,-3263,0.948871791362762 +13077,-0.019955856725574,-0.002921792212874,0.025301715359092,38397,-1122,-2520,-3393,0.945801496505737 +13079,-0.012996739707887,0.006549163721502,0.023906379938126,38397,-1247,-2960,-3284,0.946922779083252 +13081,-0.008825862780213,0.006977025419474,0.023230222985149,38397,-1133,-2308,-3405,0.945149421691894 +13083,-0.004411214962602,0.010741741396487,0.022570146247745,38397,-1201,-2623,-3297,0.940996706485748 +13085,0.000557383405976,0.007034601643682,0.024610009044409,38397,-1321,-2014,-3392,0.940143942832947 +13087,0.00149955553934,0.024057921022177,0.025910805910826,38397,-1050,-3797,-3254,0.941807210445404 +13089,0.011429089121521,0.031186819076538,0.0229790546,38397,-1832,-3145,-3400,0.947393536567688 +13091,0.017418881878257,0.0332783870399,0.01702849008143,38397,-1662,-2885,-3356,0.949545502662659 +13093,0.014136610552669,0.032171625643969,0.013315516524017,38397,-929,-2581,-3464,0.953608810901642 +13095,0.01422742754221,0.027343695983291,0.012993616983295,38397,-1191,-2300,-3402,0.950262367725372 +13097,0.021565331146121,0.029740747064352,0.013127335347235,38397,-1800,-2806,-3464,0.944072365760803 +13099,0.026745982468128,0.02978103607893,0.015211255289614,38397,-1774,-2692,-3374,0.942901194095612 +13101,0.022346615791321,0.034689005464316,0.015819441527128,38397,-982,-3066,-3444,0.940281689167023 +13103,0.026575412601233,0.018962197005749,0.013882960192859,38397,-1718,-1390,-3388,0.942805528640747 +13105,0.030710147693753,0.025567203760147,0.012019659392536,38397,-1724,-3061,-3469,0.945837736129761 +13107,0.039560217410326,0.0238276142627,0.015038283541799,38397,-2275,-2479,-3373,0.947329223155975 +13109,0.039956592023373,0.023135755211115,0.019638482481241,38397,-1607,-2509,-3415,0.944273769855499 +13111,0.030875964090228,0.029391644522548,0.022605989128351,38397,-866,-3145,-3282,0.946980237960815 +13113,0.025754636153579,0.025591364130378,0.018518321216107,38397,-1022,-2330,-3419,0.94629830121994 +13115,0.030980939045549,0.0216358974576,0.013381971977651,38397,-1915,-2295,-3388,0.946324288845062 +13117,0.036760836839676,0.020834697410464,0.012567677535117,38397,-1976,-2481,-3459,0.95204347372055 +13119,0.035339437425137,0.033659350126982,0.01482492312789,38397,-1530,-3702,-3370,0.956536293029785 +13121,0.036529082804918,0.027921034023166,0.012270368635655,38397,-1662,-2240,-3459,0.9662024974823 +13123,0.035554438829422,0.028021275997162,0.010241579264402,38397,-1575,-2709,-3422,0.964998424053192 +13125,0.034262143075466,0.02656683512032,0.01210124231875,38397,-1469,-2535,-3460,0.959864556789398 +13127,0.035209413617849,0.026379073038697,0.011614396236837,38397,-1713,-2667,-3405,0.951065480709076 +13129,0.036020129919052,0.029355380684137,0.009853160940111,38397,-1660,-2900,-3474,0.949755907058716 +13131,0.035430140793324,0.025738885626197,0.010334202088416,38397,-1625,-2422,-3419,0.94531375169754 +13133,0.030070416629315,0.033309277147055,0.012755108997226,38397,-1148,-3294,-3453,0.937655031681061 +13135,0.025628024712205,0.025764701887965,0.01139057893306,38397,-1216,-2170,-3406,0.936965823173523 +13137,0.020062379539013,0.03762437030673,0.007217625156045,38397,-1003,-3675,-3490,0.938091933727264 +13139,0.026965154334903,0.030281996354461,0.006598104722798,38397,-2051,-2271,-3462,0.943135678768158 +13141,0.02526094391942,0.016433853656054,0.009225497953594,38397,-1366,-1543,-3476,0.942456245422363 +13143,0.019138444215059,0.010765440762043,0.013832588680089,38397,-984,-2073,-3376,0.945114433765411 +13145,0.019932765513659,0.01251601614058,0.010644283145666,38397,-1475,-2607,-3465,0.941033244132996 +13147,0.025388989597559,0.014995906502009,0.005491428077221,38397,-1923,-2719,-3473,0.934618294239044 +13149,0.028896387666464,0.013907548040152,0.004055689554662,38397,-1806,-2427,-3510,0.93658709526062 +13151,0.022657733410597,0.018601004034281,0.001968325348571,38397,-1057,-2950,-3515,0.93994814157486 +13153,0.020487733185291,0.010836279951036,-0.001151882810518,38397,-1288,-1911,-3546,0.946770250797272 +13155,0.01890910603106,0.014004161581397,-0.002324787667021,38397,-1349,-2790,-3566,0.949632704257965 +13157,0.020593170076609,0.008426171727479,0.001713163452223,38397,-1575,-2040,-3528,0.952731907367706 +13159,0.019307194277644,0.010937193408609,0.004488089587539,38397,-1389,-2689,-3487,0.951219201087952 +13161,0.008761900477111,0.01934015378356,0.006560396868736,38397,-539,-3203,-3495,0.955625057220459 +13163,0.001073345658369,0.014767671003938,0.008341198787093,38397,-640,-2225,-3441,0.957877993583679 +13165,-0.002370561705902,0.008345426991582,0.011331763118506,38397,-889,-1986,-3461,0.957825899124146 +13183,-0.021813733503223,0.000389373890357,0.009682708419859,38397,-625,-2312,-3418,0.950038850307465 +13185,-0.019254086539149,-0.017722373828292,0.009997204877436,38397,-1053,-752,-3463,0.94975346326828 +13187,-0.023186441510916,-0.019159935414791,0.009225057438016,38397,-479,-1894,-3423,0.951861143112183 +13189,-0.025592746213079,-0.020649006590247,0.010595178231597,38397,-596,-1891,-3458,0.956650197505951 +13191,-0.030261399224401,-0.015188526362181,0.012517749331892,38397,-297,-2435,-3383,0.953924298286438 +13193,-0.037490665912628,-0.013101667165756,0.010817132890225,38397,-64,-2246,-3455,0.953450322151184 +13195,-0.037226278334856,-0.026161447167397,0.007671901024878,38397,-519,-921,-3439,0.944551289081574 +13197,-0.03789820894599,-0.034999430179596,0.007090313825756,38397,-510,-1135,-3481,0.935272514820099 +13199,-0.035162813961506,-0.041014399379492,0.008677303791046,38397,-713,-1169,-3427,0.935297191143036 +13201,-0.034828752279282,-0.035077281296253,0.010028907097876,38397,-608,-2172,-3460,0.935538828372955 +13203,-0.028507482260466,-0.047997415065765,0.009143807925284,38397,-1066,-546,-3421,0.940540611743927 +13205,-0.032304845750332,-0.038277227431536,0.008452197536826,38397,-335,-2375,-3470,0.944025576114654 +13207,-0.031522735953331,-0.039762988686562,0.008771133609116,38397,-614,-1478,-3425,0.947999179363251 +13209,-0.028963893651962,-0.037130758166313,0.004289830569178,38397,-824,-1865,-3498,0.94679981470108 +13211,-0.023904617875815,-0.029230343177915,0.005479930434376,38397,-1025,-2293,-3463,0.948229074478149 +13213,-0.022096717730165,-0.02534006908536,0.006790942978114,38397,-857,-2107,-3481,0.946955144405365 +13215,-0.01763927936554,-0.024729818105698,0.003376985201612,38397,-1066,-1829,-3488,0.94940972328186 +13217,-0.01440438721329,-0.02884640917182,0.002209332073107,38397,-1060,-1469,-3512,0.957410991191864 +13219,-0.014309336431325,-0.023087566718459,0.001058314810507,38397,-795,-2209,-3516,0.965027689933777 +13221,-0.010983952321112,-0.028910191729665,3.5945533454651E-05,38397,-1106,-1332,-3528,0.973574161529541 +13223,-0.012471754103899,-0.027279457077384,-0.000216154905502,38397,-702,-1828,-3532,0.972421944141388 +13225,-0.013982244767249,-0.028430555015802,0.001304549281485,38397,-708,-1657,-3520,0.971308529376983 +13227,-0.011109493672848,-0.024814249947667,0.000835089944303,38397,-1039,-2002,-3520,0.964217841625214 +13229,-0.007564592175186,-0.00929771643132,-0.000265420938376,38397,-1156,-3112,-3532,0.963298857212067 +13231,-0.000590455369093,-0.005558544769883,-0.000516708940268,38397,-1501,-2309,-3536,0.963302195072174 +13233,0.005606555845588,0.002075644908473,-0.002078230958432,38397,-1534,-2705,-3545,0.961430251598358 +13235,0.011428458616138,-0.00464188028127,0.001274600857869,38397,-1616,-1562,-3516,0.96161276102066 +13237,0.004599579144269,0.005581776145846,0.005968999583274,38397,-591,-2934,-3490,0.965031087398529 +13239,0.006687838584185,-0.002838941989467,0.004940844606608,38397,-1277,-1454,-3473,0.969320774078369 +13241,0.012089780531824,-0.004866025876254,0.004155855160207,38397,-1578,-1899,-3503,0.963762462139129 +13243,0.011895125731826,0.000363328814274,0.008037203922868,38397,-1204,-2482,-3437,0.961228966712952 +13245,0.009044907055795,0.011384178884328,0.008431216701865,38397,-948,-3062,-3473,0.954130232334137 +13247,0.009438598528504,0.018556026741862,0.004313953220844,38397,-1213,-2926,-3480,0.946161091327667 +13249,0.013414825312793,0.013348327018321,-0.000798190070782,38397,-1505,-1932,-3536,0.943968534469604 +13251,0.017890609800816,0.017640899866819,-0.004087084904313,38397,-1647,-2716,-3580,0.944009244441986 +13253,0.025717966258526,0.015351783484221,-0.002383443526924,38397,-1966,-2176,-3549,0.947375178337097 +13255,0.024357322603464,0.025969522073865,0.000406108069001,38397,-1339,-3308,-3528,0.946734607219696 +13257,0.023277245461941,0.023448659107089,0.00257776491344,38397,-1303,-2284,-3516,0.949286997318268 +13259,0.025452468544245,0.027163375169039,0.00333393109031,38397,-1616,-2833,-3494,0.945931971073151 +13261,0.025995802134276,0.036643583327532,0.005621390417218,38397,-1469,-3341,-3495,0.949216783046722 +13263,0.025716161355376,0.035538516938686,0.006038262043148,38397,-1454,-2630,-3462,0.94816529750824 +13265,0.027758177369833,0.034347474575043,0.005244958214462,38397,-1612,-2555,-3497,0.947631001472473 +13267,0.026032032445073,0.025319755077362,0.007147794123739,38397,-1356,-1909,-3449,0.952904105186462 +13269,0.021738935261965,0.027012007310987,0.009440759196877,38397,-1080,-2664,-3468,0.959065735340118 +13271,0.021509813144803,0.020775796845555,0.010864635929465,38397,-1403,-2047,-3404,0.960583329200745 +13273,0.021958027034998,0.022004498168826,0.01023503113538,38397,-1431,-2565,-3462,0.95622181892395 +13275,0.026821928098798,0.018649775534868,0.010391908697784,38397,-1883,-2234,-3409,0.955053448677063 +13277,0.031443297863007,0.016354028135538,0.007876727730036,38397,-1880,-2238,-3477,0.950206637382507 +13279,0.032532028853893,0.010760852135718,0.006539998110384,38397,-1723,-1947,-3454,0.951509714126587 +13281,0.034727264195681,0.006466305814683,0.008953389711678,38397,-1770,-1956,-3469,0.953369379043579 +13283,0.034074150025845,0.015812501311302,0.011291346512735,38397,-1627,-3097,-3397,0.950985252857208 +13285,0.035562857985497,0.009425891563296,0.011540490202606,38397,-1747,-1852,-3450,0.951927661895752 +13287,0.030865211039782,0.018461279571056,0.008248552680016,38397,-1309,-3121,-3432,0.954165399074554 +13289,0.030034622177482,0.013756226748228,0.008802023716271,38397,-1517,-2039,-3469,0.958867907524109 +13291,0.024257188662887,0.018373752012849,0.01198617182672,38397,-1147,-2810,-3387,0.965580761432648 +13293,0.021061001345515,0.016483552753925,0.015504037030041,38397,-1233,-2285,-3421,0.974997460842133 +13295,0.017636673524976,0.013131245970726,0.014628230594099,38397,-1217,-2159,-3355,0.972497582435608 +13297,0.014759356155992,0.007336332462728,0.012039157561958,38397,-1176,-1878,-3443,0.969003319740295 +13299,0.010635985061526,-0.003894762368873,0.011758388020098,38397,-1050,-1308,-3387,0.963454186916351 +13301,0.010512812063098,-0.004082438535988,0.012631509453058,38397,-1317,-2109,-3438,0.956718027591705 +13303,0.016582977026701,-0.003523029619828,0.014595286920667,38397,-1878,-2147,-3352,0.951045036315918 +13305,0.016600152477622,0.011047043837607,0.015367743559182,38397,-1422,-3377,-3418,0.950139045715332 +13307,0.011465299874544,0.012716221623123,0.015033300966024,38397,-1007,-2491,-3345,0.954378008842468 +13309,0.006548596080393,0.017588714137673,0.014398308470845,38397,-930,-2777,-3423,0.958094120025635 +13311,0.009544341824949,0.019654782488942,0.018122201785445,38397,-1574,-2646,-3307,0.966938674449921 +13313,0.014569504186511,0.02302691154182,0.019478037953377,38397,-1765,-2754,-3385,0.96301943063736 +13315,0.017571214586496,0.022491836920381,0.017314167693257,38397,-1696,-2511,-3314,0.959006309509277 +13333,-0.002481682924554,-0.011279723607004,0.026193033903837,38397,-1120,-2239,-3326,0.945005714893341 +13335,-0.004888808354735,-0.006414460483938,0.025198413059116,38397,-963,-2437,-3208,0.946271061897278 +13337,-0.012826084159315,0.010900552384555,0.02533202432096,38432,-456,-3585,-3328,0.948855936527252 +13339,-0.009429385885596,0.001704221824184,0.027147520333529,38432,-1298,-1552,-3181,0.950191617012024 +13341,-0.010269900783897,-0.004015590529889,0.026565030217171,38432,-997,-1718,-3316,0.948502659797668 +13343,-0.009601661004126,-0.012161543592811,0.025317616760731,38432,-1095,-1411,-3199,0.949237823486328 +13345,-0.016251528635621,-0.010637794621289,0.021459063515067,38432,-491,-2136,-3347,0.947591483592987 +13347,-0.022960904985666,-0.011992848478258,0.021160153672099,38432,-341,-1895,-3245,0.951715528964996 +13349,-0.02706241235137,-0.022977631539106,0.02632911130786,38432,-508,-1056,-3311,0.952322125434876 +13351,-0.030854351818562,-0.03126959875226,0.026883747428656,38432,-407,-1067,-3174,0.948963284492493 +13353,-0.02975332736969,-0.042322769761086,0.024195050820708,38432,-828,-757,-3322,0.947703719139099 +13355,-0.031085843220353,-0.032153576612473,0.02403230778873,38432,-569,-2354,-3204,0.948804438114166 +13357,-0.028026381507516,-0.02988000959158,0.022732870653272,38432,-979,-1873,-3329,0.952629923820496 +13359,-0.033907845616341,-0.0230414532125,0.016824781894684,38432,-183,-2248,-3286,0.954225718975067 +13361,-0.03507848456502,-0.021909086033702,0.012804721482098,38432,-559,-1892,-3395,0.959992825984955 +13363,-0.031727362424135,-0.023939797654748,0.012853705324233,38432,-868,-1583,-3331,0.958586990833282 +13365,-0.026178929954767,-0.026229178532958,0.018876092508435,38432,-1154,-1570,-3352,0.958388805389404 +13367,-0.026326606050134,-0.029825096949935,0.021915627643466,38432,-687,-1357,-3222,0.956288576126099 +13369,-0.03058210387826,-0.022901471704245,0.021516770124436,38432,-376,-2261,-3331,0.955238819122314 +13371,-0.028084950521588,-0.028424261137843,0.021655069664121,38432,-839,-32767,-3222,0.950734972953796 +13373,-0.02899113483727,-0.021038034930825,0.020922876894474,38272,-626,-32756,-3332,0.94469678401947 +13375,-0.023649198934436,-0.019468940794468,0.020504675805569,38272,-1108,-32484,-3233,0.947999656200409 +13377,-0.020571444183588,-0.017054861411452,0.019626853987575,38272,-1023,-32748,-3338,0.950750589370728 +13379,-0.020201880484819,-0.020088236778975,0.019994910806418,38272,-797,-32430,-3236,0.959170162677765 +13381,-0.016134290024638,-0.035886324942112,0.020258923992515,38272,-1149,-31463,-3331,0.9650958776474 +13383,-0.01585890725255,-0.055850449949503,0.017952874302864,38272,-849,-30914,-3258,0.966278374195099 +13385,-0.012189543806017,-0.099259093403816,0.014300203882158,38272,-1170,-28849,-3370,0.96765810251236 +13387,-0.00995774846524,-0.143583819270134,0.010055286809802,38272,-1076,-27984,-3350,0.967129945755005 +13389,-0.003097834996879,-0.215950965881348,0.007089510094374,38272,-1524,-25330,-3418,0.963698923587799 +13391,-0.002424729755148,-0.28329011797905,0.005676818545908,38272,-1086,-24271,-3402,0.963471710681915 +13393,0.008532284758985,-0.36814084649086,0.005508942063898,38272,-1983,-22418,-3429,0.960204303264618 +13395,0.013006918132305,-0.447540730237961,0.003255012212321,38272,-1611,-20878,-3432,0.959594964981079 +13397,0.020115770399571,-0.550018846988678,0.003988724667579,38272,-1879,-18637,-3440,0.956338822841644 +13399,0.029110109433532,-0.658267080783844,0.001001599244773,38272,-2198,-15431,-3460,0.946097493171692 +13401,0.03620345145464,-0.767363846302033,-0.000458956696093,38272,-2121,-15037,-3471,0.94370049238205 +13403,0.048570655286312,-0.880708873271942,0.000335790828103,38272,-2774,-11396,-3469,0.941414654254913 +13405,0.057523339986801,-1.00052785873413,-0.000483394192997,38272,-2581,-10811,-3472,0.947522401809692 +13407,0.073579020798206,-1.13627779483795,-0.004705491475761,38272,-3475,-5469,-3530,0.946548044681549 +13409,0.081458657979965,-1.26995611190796,-0.01002371776849,38272,-2882,-5719,-3539,0.956222653388977 +13411,0.08791209757328,-1.41601014137268,-0.009727658703923,38272,-3056,108,-3590,0.96136862039566 +13413,0.084351517260075,-1.5323668718338,-0.007080359384418,38272,-2144,-2829,-3522,0.97034341096878 +13415,0.091564483940601,-1.66411483287811,-0.001551976776682,38272,-3212,3538,-3494,0.981795728206634 +13417,0.099396236240864,-1.77686083316803,0.0003919111914,38272,-3218,904,-3471,0.980843544006348 +13419,0.113145962357521,-1.91025424003601,-0.001001982833259,38272,-4077,8193,-3485,0.977046489715576 +13421,0.115927577018738,-2.02626943588257,0.002963323146105,38272,-3146,5320,-3454,0.967479348182678 +13423,0.127609148621559,-2.15184283256531,0.006998634431511,38272,-4225,12210,-3385,0.957945048809052 +13425,0.13197249174118,-2.25931024551392,0.005102899391204,38272,-3550,8772,-3439,0.955289840698242 +13427,0.142466306686401,-2.36656880378723,0.003487907350063,38272,-4458,15142,-3417,0.943903028964996 +13429,0.142036020755768,-2.45503163337708,-0.001852804212831,38272,-3421,11042,-3486,0.937905311584473 +13431,0.140107870101929,-2.53552007675171,-0.003531759371981,38272,-3612,16821,-3490,0.941701710224152 +13433,0.150200709700584,-2.6127016544342,-0.007731811609119,38272,-4364,13404,-3527,0.94465047121048 +13435,0.163411498069763,-2.68177247047424,-0.01347806956619,38272,-5146,19310,-3598,0.947536170482636 +13437,0.175319224596024,-2.74296569824219,-0.016130669042468,38272,-4936,15108,-3587,0.944376409053802 +13439,0.179155468940735,-2.79097676277161,-0.018205964937806,38272,-4804,20579,-3646,0.953017830848694 +13441,0.189189910888672,-2.83472847938538,-0.018053878098726,38272,-5089,16215,-3602,0.959766805171967 +13443,0.193192735314369,-2.85001659393311,-0.01957318559289,38272,-5129,20245,-3654,0.961589097976685 +13445,0.194208085536957,-2.86034154891968,-0.024500528350473,38272,-4609,15262,-3649,0.963375747203827 +13447,0.191867351531982,-2.86245155334473,-0.030272973701358,38272,-4742,32767,-3773,0.962980628013611 +13449,0.191321477293968,-2.86550545692444,-0.030140006914735,38272,-4549,32767,-3691,0.969713628292084 +13451,0.196983188390732,-2.85578918457031,-0.027572667226195,38272,-5487,32767,-3736,0.971969366073608 +13453,0.198392689228058,-2.82646608352661,-0.025958467274904,38272,-4885,32767,-3666,0.972815692424774 +13455,0.197007164359093,-2.79477572441101,-0.026082005351782,38272,-5077,32767,-3712,0.976029694080353 +13457,0.200088679790497,-2.75013256072998,-0.02682532183826,38272,-5125,32767,-3674,0.97520387172699 +13459,0.208517774939537,-2.69870543479919,-0.0286457054317,38272,-6064,32767,-3738,0.974812924861908 +13461,0.207818537950516,-2.61425733566284,-0.033869907259941,38272,-5066,32767,-3725,0.975802302360535 +13463,0.19660522043705,-2.50879073143005,-0.03797147423029,38272,-4560,32767,-3849,0.979581415653229 +13465,0.191230222582817,-2.39429450035095,-0.034281730651856,38272,-4589,32767,-3732,0.982669472694397 +13485,0.042944960296154,-0.705863893032074,-0.034988380968571,38272,-1876,9860,-3762,0.982307910919189 +13487,0.028876582160592,-0.484149664640427,-0.034466218203306,38272,-2017,6728,-3911,0.982113659381866 +13489,0.005187060218304,-0.254668235778809,-0.030521433800459,38272,-961,2281,-3737,0.983974695205688 +13491,-0.013068810105324,-0.018278639763594,-0.028422085568309,38272,-1036,-1645,-3874,0.99280309677124 +13493,-0.033045429736376,0.22016479074955,-0.023664776235819,38272,-677,-5040,-3696,0.997912883758545 +13495,-0.054853532463312,0.448178142309189,-0.016860973089933,38272,-99,-8593,-3765,0.997212469577789 +13497,-0.077170670032501,0.67795205116272,-0.017179865390062,38272,142,-11071,-3656,0.999554634094238 +13499,-0.092083364725113,0.900260388851166,-0.019601237028837,38272,24,-15706,-3817,0.998684167861938 +13501,-0.118719637393951,1.11944365501404,-0.016419164836407,38272,1082,-16939,-3656,0.996504366397858 +13503,-0.151722878217697,1.32697510719299,-0.009014807641506,38272,2344,-21966,-3719,0.997944235801697 +13505,-0.191003188490868,1.53068387508392,-0.002002028748393,38272,3089,-22224,-3562,0.998969495296478 +13507,-0.216699108481407,1.72089457511902,-0.000880875450093,38272,2974,-27715,-3647,1.00388205051422 +13509,-0.239584699273109,1.89189004898071,-0.006237466353923,38272,2709,-25743,-3595,1.00337243080139 +13511,-0.257212191820145,2.04939556121826,-0.011399570852518,38272,3159,-31453,-3778,0.99990701675415 +13513,-0.27491021156311,2.18984222412109,-0.017639672383666,38272,2961,-28666,-3679,0.996013760566711 +13515,-0.296392619609833,2.30966258049011,-0.022784378379583,38272,4196,-32767,-3914,0.99610847234726 +13517,-0.321663796901703,2.43000245094299,-0.024902166798711,38272,4310,-31632,-3736,0.997743725776672 +13519,-0.343921363353729,2.5323441028595,-0.028983613476157,38272,5176,-32767,-3987,0.996784090995789 +13521,-0.364875197410583,2.62251424789429,-0.032388366758823,38272,4780,-32767,-3796,1.00075054168701 +13523,-0.384379118680954,2.68956923484802,-0.034810595214367,38272,5801,-32767,-4046,1.00265371799469 +13525,-0.401386916637421,2.74114727973938,-0.037118595093489,38272,5200,-32767,-3838,0.997665405273438 +13527,-0.415990620851517,2.78129005432129,-0.040289528667927,38272,6135,-32767,-4093,0.990583658218384 +13529,-0.434763938188553,2.8144416809082,-0.045115560293198,38272,5998,-32767,-3901,0.984357357025146 +13531,-0.449107557535172,2.83532929420471,-0.048181567341089,38272,6850,-32767,-4170,0.986240088939667 +13533,-0.45343142747879,2.83699178695679,-0.051743198186159,38272,5438,-32767,-3956,0.988138377666473 +13535,-0.455054640769959,2.82690286636353,-0.053605265915394,38272,6249,-32767,-4219,0.988738596439362 +13537,-0.453591614961624,2.7933988571167,-0.054499462246895,38272,5239,-32767,-3985,0.989500164985657 +13539,-0.452763140201569,2.75379157066345,-0.057162199169397,38272,6250,-32767,-4245,0.989973902702332 +13541,-0.441015839576721,2.69372153282166,-0.057475056499243,38272,4535,-32767,-4014,0.990051209926605 +13543,-0.434161186218262,2.64016342163086,-0.057076837867498,38272,5724,-32767,-4231,0.989334404468536 +13545,-0.423064529895783,2.56235289573669,-0.059057831764221,38272,4530,-32767,-4034,0.992676496505737 +13547,-0.414603143930435,2.4746778011322,-0.064691722393036,38272,5474,-32767,-4310,0.993759095668793 +13549,-0.399749338626862,2.37823486328125,-0.070390768349171,38272,4121,-32767,-4121,0.998702824115753 +13551,-0.377812176942825,2.27065205574036,-0.072749868035317,38272,4086,-32767,-4402,0.99872237443924 +13553,-0.361398190259934,2.16041827201843,-0.071998707950115,38272,3637,-32767,-4142,0.99834144115448 +13555,-0.342341661453247,2.03419995307922,-0.0697505697608,38272,3885,-32767,-4372,0.994627416133881 +13557,-0.31906858086586,1.91506111621857,-0.069374546408653,38272,2700,-32767,-4133,0.994456946849823 +13559,-0.28024286031723,1.7657653093338,-0.067282997071743,38272,1615,-1630,-4356,0.995837569236755 +13561,-0.255553394556046,1.62037575244904,-0.066586278378964,38272,1823,-26928,-4123,0.995341837406158 +13563,-0.235974445939064,1.4448127746582,-0.067914180457592,38272,2394,-25364,-4383,0.992693781852722 +13565,-0.206757858395576,1.27945697307587,-0.069393135607243,38272,913,-21369,-4152,0.992753446102142 +13567,-0.162370070815086,1.09840774536133,-0.066740527749062,38272,-470,-20026,-4396,0.991577327251434 +13569,-0.137839511036873,0.934830784797668,-0.064849771559239,38272,343,-17158,-4130,0.988859474658966 +13571,-0.097082532942295,0.752997815608978,-0.063493348658085,38272,-1195,-14884,-4388,0.992598831653595 +13573,-0.060954447835684,0.572153747081757,-0.059559274464846,38272,-1535,-11166,-4104,0.997657001018524 +13575,-0.024435078725219,0.388397932052612,-0.053519412875176,38272,-2029,-9192,-4304,1.0065301656723 +13577,0.015063910745084,0.206434026360512,-0.051419351249933,38272,-2846,-6121,-4057,1.01327991485596 +13579,0.058753844350576,0.017611363902688,-0.04682258144021,38272,-3901,-3014,-4258,1.0076208114624 +13581,0.09684582054615,-0.157843977212906,-0.04445630684495,38272,-3937,-1475,-4018,0.996969103813171 +13583,0.135239407420158,-0.340224593877792,-0.041480112820864,38272,-4816,2301,-4226,1.00014817714691 +13585,0.180629462003708,-0.521487593650818,-0.039236273616552,38272,-5719,4209,-3991,0.986907839775085 +13587,0.215945035219192,-0.712731957435608,-0.040387619286776,38272,-5986,9114,-4243,0.982533812522888 +13589,0.237951681017876,-0.889472365379334,-0.042471569031477,38272,-4961,9388,-4023,0.979389607906342 +13591,0.266730666160583,-1.04326140880585,-0.036612555384636,38272,-6451,12088,-4222,0.978190064430237 +13593,0.304947853088379,-1.19429707527161,-0.031632948666811,38272,-7204,12298,-3957,0.977579593658447 +13595,0.335837483406067,-1.33215463161469,-0.032661639153957,38272,-7853,16080,-4192,0.98390144109726 +13597,0.365297794342041,-1.47367918491364,-0.034229017794132,38272,-7594,32767,-3984,0.986934423446655 +13599,0.391372412443161,-1.60058832168579,-0.03642562404275,38272,-8561,26325,-4247,0.992465674877167 +13601,0.413469761610031,-1.71517741680145,-0.039275635033846,38272,-7934,24436,-4028,0.987531185150146 +13603,0.431043714284897,-1.8046327829361,-0.048473577946425,38272,-8767,27709,-4395,0.982244193553925 +13605,0.447453856468201,-1.88567399978638,-0.055869366973639,38272,-8207,25281,-4154,0.980414390563965 +13607,0.458251178264618,-1.94775855541229,-0.060195874422789,38272,-8923,28902,-4533,0.978346884250641 +13609,0.481827348470688,-2.00842428207397,-0.065199695527554,38272,-9421,26456,-4231,0.988356530666351 +13611,0.504104793071747,-2.038902759552,-0.07026057690382,38272,-10713,29002,-4647,0.995595753192902 +13613,0.526137948036194,-2.05760264396667,-0.074274100363255,38272,-10176,25074,-4307,1.00023782253265 +13615,0.532126724720001,-2.05681729316711,-0.079211562871933,38272,-10233,27970,-4748,1.00302612781525 +13617,0.532463610172272,-2.0533926486969,-0.080637909471989,38272,-8957,24361,-4366,1.00559914112091 +13635,0.426739871501923,-1.39525151252747,-0.085756376385689,38272,-7569,32767,-4839,1.00699734687805 +13637,0.406656324863434,-1.27187538146973,-0.083140552043915,38272,-6817,14686,-4458,1.01196753978729 +13639,0.386040419340134,-1.14221096038818,-0.081099420785904,38272,-7280,14742,-4796,1.01600682735443 +13641,0.355440586805344,-1.01250398159027,-0.082138277590275,38272,-5512,11107,-4465,1.01735746860504 +13643,0.319144189357758,-0.87559849023819,-0.085418403148651,38272,-5251,10426,-4865,1.02151811122894 +13645,0.280277609825134,-0.722784817218781,-0.084328331053257,38272,-3997,5770,-4494,1.02316164970398 +13647,0.242167696356773,-0.568478107452393,-0.080543927848339,38272,-3998,4599,-4839,1.0222784280777 +13649,0.199251458048821,-0.41169348359108,-0.076424367725849,38272,-2662,1358,-4454,1.01770234107971 +13651,0.159639522433281,-0.254703104496002,-0.075412653386593,38272,-2635,-411,-4815,1.00575804710388 +13653,0.126454129815102,-0.101594217121601,-0.0687485486269,38272,-2394,-2632,-4415,0.9969722032547 +13655,0.090388990938664,0.047473590821028,-0.057452604174614,38272,-1826,-4615,-4637,0.989476025104523 +13657,0.050672363489866,0.194539055228233,-0.051785904914141,38272,-886,-6390,-4309,0.983730316162109 +13659,0.017062276601791,0.339959412813187,-0.049402516335249,38272,-848,-9118,-4572,0.982837080955505 +13661,-0.020196551457048,0.50012481212616,-0.04335967451334,38272,-59,-11792,-4262,0.981299102306366 +13663,-0.058011077344418,0.653738796710968,-0.036002051085234,38272,668,-14952,-4443,0.986205279827118 +13665,-0.10145665705204,0.803040266036987,-0.028935100883246,38272,1569,-15586,-4172,0.991872787475586 +13667,-0.145721897482872,0.942881643772125,-0.022464165464044,38272,2592,-18949,-4309,0.992775499820709 +13669,-0.186306938529015,1.06371903419495,-0.020281651988626,38272,2641,-17647,-4120,0.99768853187561 +13671,-0.225700870156288,1.16999638080597,-0.023293897509575,38272,3617,-20648,-4336,0.997311413288116 +13673,-0.265655338764191,1.26303505897522,-0.024912644177675,38272,3831,-18984,-4160,0.997368693351746 +13675,-0.308454304933548,1.35484659671783,-0.022739825770259,38325,5313,-23128,-4339,1.0006992816925 +13677,-0.347646445035934,1.44094884395599,-0.0206288266927,38325,5087,-21599,-4138,1.00071084499359 +13679,-0.382730215787888,1.51608836650848,-0.022096486762166,38325,6118,-25147,-4337,0.999721825122833 +13681,-0.413948118686676,1.58493912220001,-0.024236205965281,38325,5637,-23066,-4171,0.997971892356873 +13683,-0.442597836256027,1.64860200881958,-0.028845585882664,38325,6819,-27135,-4419,0.994733512401581 +13685,-0.459917366504669,1.69407272338867,-0.033168733119965,38325,5501,-23658,-4241,0.989289820194244 +13687,-0.481296360492706,1.73177170753479,-0.035007610917091,38325,7142,-27339,-4488,0.979946434497833 +13689,-0.502851128578186,1.75243079662323,-0.035386878997088,38325,6641,-23461,-4265,0.974825918674469 +13691,-0.528812229633331,1.76385629177094,-0.037435151636601,38325,8460,-26725,-4507,0.972257971763611 +13693,-0.543746888637543,1.7577782869339,-0.039256349205971,38325,6995,-22385,-4301,0.976774096488952 +13695,-0.551600098609924,1.74584376811981,-0.039329536259174,38325,7779,-25514,-4518,0.982088625431061 +13697,-0.564076244831085,1.72891294956207,-0.040798418223858,38325,7364,-21953,-4320,0.991786956787109 +13699,-0.570572078227997,1.70260000228882,-0.045535560697317,38325,8252,-24523,-4581,0.995232462882996 +13701,-0.569199800491333,1.67569482326508,-0.048452358692885,38325,6710,-21218,-4382,0.99618011713028 +13703,-0.556743979454041,1.62536835670471,-0.049186233431101,38325,6931,-22267,-4615,0.993912518024445 +13705,-0.545944154262543,1.57514190673828,-0.050824634730816,38325,5961,-18816,-4407,0.990266144275665 +13707,-0.530746877193451,1.50107884407043,-0.050479356199503,38325,6568,-19229,-4625,0.980184435844421 +13709,-0.527455568313599,1.43651950359344,-0.048748668283224,38325,6484,-16459,-4402,0.96769791841507 +13711,-0.514756500720978,1.36432981491089,-0.046787776052952,38325,6728,-17772,-4578,0.968380928039551 +13713,-0.493680417537689,1.28157949447632,-0.049383331090212,38325,4968,-13533,-4414,0.97256737947464 +13715,-0.465085208415985,1.19074213504791,-0.052099902182818,38325,5015,-14176,-4642,0.985019028186798 +13717,-0.435445904731751,1.08998143672943,-0.049492564052343,38325,3741,-10017,-4423,0.993389010429382 +13719,-0.405438899993897,0.995293080806732,-0.04348661005497,38325,4152,-11206,-4548,1.00405550003052 +13721,-0.363519191741943,0.895956695079803,-0.035021048039198,38325,2024,-7771,-4331,1.01003170013428 +13723,-0.329693853855133,0.806859374046326,-0.030943734571338,38325,2817,-8930,-4410,1.01582658290863 +13725,-0.29285591840744,0.699782907962799,-0.030902834609151,38325,1534,-4753,-4308,1.01007962226868 +13727,-0.261155843734741,0.604220390319824,-0.0312884375453,38325,1994,-5485,-4427,1.00175666809082 +13729,-0.219748243689537,0.49476546049118,-0.030359163880348,38325,286,-1901,-4309,1.00114762783051 +13731,-0.172397330403328,0.393610179424286,-0.026498338207603,38325,-468,-1879,-4387,0.998826026916504 +13733,-0.119113370776176,0.283350676298141,-0.017962861806154,38325,-1921,1024,-4229,1.00073862075806 +13735,-0.076121672987938,0.18976041674614,-0.012114969082177,38325,-1660,771,-4235,1.00048732757568 +13737,-0.024429552257061,0.086621075868607,-0.00664448319003,38325,-3125,3266,-4154,1.00131785869598 +13739,0.020065359771252,-0.000476561079267,-0.005448943469673,38325,-3310,3363,-4172,1.00056970119476 +13741,0.06428848952055,-0.08509860932827,-0.002152602188289,38325,-3865,4418,-4126,0.996821999549866 +13743,0.100611560046673,-0.158806398510933,-0.001436056685634,38325,-4049,5033,-4138,0.990898370742798 +13745,0.136267364025116,-0.223920479416847,-0.00302313035354,38325,-4324,5101,-4134,0.986998498439789 +13747,0.184200435876846,-0.297947317361832,-0.002621052321047,38325,-6295,7438,-4163,0.977562010288238 +13749,0.233717381954193,-0.358310967683792,-0.001203821157105,38325,-6793,6843,-4123,0.978326320648193 +13751,0.281051635742187,-0.420366883277893,-0.002024150220677,38325,-7928,8745,-4165,0.977570235729218 +13753,0.31713280081749,-0.467567563056946,-0.00216672453098,38325,-7151,7678,-4133,0.985439896583557 +13755,0.350706845521927,-0.523700654506683,-0.003273843089119,38325,-8210,10230,-4185,0.993419647216797 +13757,0.380297124385834,-0.560508906841278,-0.005238299258053,38325,-7749,8526,-4157,1.00575947761536 +13759,0.414712488651276,-0.594271600246429,-0.003845035796985,38325,-9471,10054,-4195,1.01633870601654 +13761,0.441126465797424,-0.615294992923737,-0.00386883597821,38325,-8580,8476,-4150,1.00956690311432 +13763,0.461608916521072,-0.639933168888092,-0.001590510830283,38325,-9431,10447,-4168,1.00144231319428 +13765,0.475518763065338,-0.647568702697754,-0.003066236386076,38325,-8386,8297,-4147,0.991939544677734 +13767,0.494540423154831,-0.646782159805298,-0.009355781599879,38325,-10072,9057,-4257,0.987030506134033 +13769,0.517000794410706,-0.642318308353424,-0.015808058902621,38325,-9818,7677,-4239,0.983523428440094 +13771,0.526574611663818,-0.626161634922028,-0.019322512671352,38325,-10135,7926,-4373,0.982257306575775 +13773,0.526646554470062,-0.61859118938446,-0.020263183861971,38325,-8591,7427,-4274,0.981960713863373 +13775,0.524747848510742,-0.592018961906433,-0.019163567572832,38325,-9524,6917,-4369,0.992052257061004 +13777,0.530331671237946,-0.569972455501556,-0.017162878066301,38325,-9278,5989,-4258,1.00246131420136 +13779,0.530748009681702,-0.531311631202698,-0.018861182034016,38325,-10045,5357,-4363,1.00835943222046 +13781,0.534351587295532,-0.505848288536072,-0.020908534526825,38325,-9441,5097,-4288,1.01022017002106 +13783,0.517952919006348,-0.47380068898201,-0.020052820444107,38325,-8880,5161,-4377,1.00201106071472 +13785,0.486523419618607,-0.430053949356079,-0.022263236343861,38325,32767,-18147,-4302,0.994645357131958 +13787,0.459012866020203,-0.392813593149185,-0.028975129127503,38325,23100,143,-4485,0.988998711109161 +13789,0.437012881040573,-0.345002442598343,-0.027989413589239,38325,23773,-2064,-4480,0.98233026266098 +13791,0.385182559490204,-0.24213396012783,-0.025253288447857,38325,25139,-3757,-4335,0.979250848293304 +13793,0.364601522684097,-0.19684761762619,-0.0197649654001,38325,24362,-3358,-4390,0.980494499206543 +13795,0.35762146115303,-0.154397144913673,-0.020723117515445,38325,24229,-4064,-4308,0.981966495513916 +13797,0.35762146115303,-0.154397144913673,-0.020723117515445,38325,24229,-4064,-4308,0.981966495513916 +13799,0.395564645528793,-0.076704658567906,-0.019865043461323,38325,21544,-4776,-4307,0.994644105434418 +13801,0.426701992750168,-0.025776686146855,-0.018331525847316,38325,19877,-6444,-4388,0.999967277050018 +13803,0.471950858831406,0.018841637298465,-0.016480825841427,38325,19067,-6647,-4289,1.00316560268402 +13805,0.527461469173431,0.07107288390398,-0.015049658715725,38325,16572,-8126,-4360,1.00442981719971 +13807,0.527461469173431,0.07107288390398,-0.015049658715725,38325,16572,-8126,-4360,1.00442981719971 +13809,0.660804867744446,0.156878173351288,-0.008126696571708,38325,13272,-8665,-4289,1.00110423564911 +13811,0.741324543952942,0.200516149401665,-0.006989690940827,38325,12709,-9296,-4231,0.998482048511505 +13813,0.834780633449554,0.233805447816849,-0.003907152451575,38325,8817,-9556,-4251,0.993963599205017 +13815,0.936068475246429,0.271706074476242,0.001539808348753,38325,8329,-10019,-4175,0.998901069164276 +13817,0.936068475246429,0.271706074476242,0.001539808348753,38325,8329,-10019,-4175,0.998901069164276 +13819,1.15666306018829,0.340489655733109,0.007960014045239,38325,4321,-11025,-4132,1.00967979431152 +13821,1.27132058143616,0.35913360118866,0.008353766053915,38325,-159,-7938,-4139,1.01660263538361 +13823,1.37521469593048,0.39003798365593,0.005724721122533,38325,1344,-11043,-4149,1.01978158950806 +13825,1.48986208438873,0.40465983748436,0.005336803849787,38325,-4066,-10968,-4193,1.02993071079254 +13827,1.48986208438873,0.40465983748436,0.005336803849787,38325,-4066,-10968,-4193,1.02993071079254 +13829,1.72427070140839,0.456909567117691,0.016685597598553,38325,-8642,-12197,-4084,1.0354391336441 +13831,1.82791996002197,0.466113954782486,0.027758408337832,38325,-6062,-10984,-4002,1.0393146276474 +13833,1.93475186824799,0.468804597854614,0.034514088183642,38325,-11764,-11579,-3894,1.04047572612762 +13835,2.03783464431763,0.464580148458481,0.040944587439299,38325,-9656,-10222,-3911,1.03236603736877 +13837,2.12562084197998,0.467925369739533,0.045842371881008,38325,-14168,-11830,-3778,1.02664971351624 +13839,2.21345067024231,0.459336668252945,0.050817552953959,38325,-11801,-10056,-3841,1.01461184024811 +13841,2.29531335830688,0.461993455886841,0.054538499563933,38325,-17262,-11903,-3691,1.00138807296753 +13843,2.37327432632446,0.452590674161911,0.057609334588051,38325,-14190,-10121,-3791,0.992476880550384 +13845,2.44399762153625,0.456583797931671,0.060899019241333,38325,-19712,-12131,-3633,0.983821213245392 +13847,2.51328372955322,0.440488785505295,0.06578154116869,38325,-16456,-9687,-3732,0.97384637594223 +13849,2.55451846122742,0.429305762052536,0.068788535892963,38325,-20289,-10825,-3549,0.966711163520813 +13867,2.6356828212738,0.174173042178154,0.063252650201321,38325,-16049,-6105,-3724,0.970466196537018 +13869,2.59794950485229,0.136824488639832,0.059081878513098,38325,-20242,-4904,-3560,0.97513347864151 +13871,2.54941487312317,0.111299633979797,0.056656371802092,38325,-14461,-5149,-3764,0.980792224407196 +13873,2.50705647468567,0.083616949617863,0.056634191423655,38325,-19402,-4800,-3553,0.977944910526276 +13875,2.4520115852356,0.047324728220701,0.051122456789017,38325,-13548,-3514,-3796,0.972533524036408 +13877,2.38299822807312,0.017490705475211,0.048281699419022,38325,-16400,-3610,-3600,0.96608030796051 +13879,2.3121919631958,-0.01801073551178,0.04992013797164,38325,-11314,-2656,-3799,0.960812866687775 +13881,2.24092721939087,-0.052065461874008,0.049241952598095,38325,-14787,-2189,-3529,0.957230091094971 +13883,2.15738701820374,-0.086831882596016,0.044948536902666,38325,-9021,-1713,-3825,0.952828943729401 +13885,2.06795763969421,-0.115714587271214,0.042108200490475,38325,-11469,-1504,-3550,0.956421136856079 +13887,1.98125505447388,-0.150430366396904,0.040826573967934,38325,-7032,-767,-3844,0.959802210330963 +13889,1.8922643661499,-0.174983024597168,0.03895203396678,38325,-9371,-809,-3522,0.965131819248199 +13891,1.79444754123688,-0.195805758237839,0.035173542797566,38325,-4245,-1047,-3873,0.964701652526856 +13893,1.69447898864746,-0.223701491951942,0.03076502121985,38325,-6006,296,-3560,0.962050437927246 +13895,1.5934511423111,-0.24731981754303,0.023923961445689,38325,-1732,18188,-3940,0.955939590930939 +13897,1.4911767244339,-0.266833782196045,0.022474922239781,38325,-3087,3569,-3601,0.953475713729858 +13899,1.38604438304901,-0.28235337138176,0.020993709564209,38325,1026,3099,-3950,0.949702739715576 +13901,1.29196202754974,-0.309290915727615,0.015756828710437,38325,-910,4941,-3621,0.953711807727814 +13903,1.19834804534912,-0.335809677839279,0.012122499756515,38325,2470,4812,-4000,0.956444144248962 +13905,1.10434305667877,-0.34981632232666,0.012637664563954,38325,1750,4844,-3601,0.953050017356873 +13907,1.01296591758728,-0.352792799472809,0.019955446943641,38325,4629,3549,-3934,0.954841375350952 +13909,0.915733933448792,-0.351634919643402,0.021487656980753,38325,4739,3959,-3477,0.955110311508179 +13911,0.828522503376007,-0.348412901163101,0.01930926553905,38325,6719,3222,-3925,0.956680297851562 +13913,0.750510811805725,-0.334594219923019,0.018816888332367,38325,5814,2947,-3507,0.960278868675232 +13915,0.6755530834198,-0.31362596154213,0.021423498168588,38325,7850,1623,-3897,0.964193642139435 +13917,0.607045114040375,-0.29818132519722,0.020660124719143,38325,7316,2398,-3507,0.970202386379242 +13919,0.543439388275147,-0.29026985168457,0.019905112683773,38325,8812,2379,-3896,0.970378041267395 +13921,0.483097761869431,-0.278578013181686,0.022541677579284,38325,8656,2508,-3491,0.970142364501953 +13923,0.423256754875183,-0.252181708812714,0.024857342243195,38325,10203,656,-3850,0.967614352703094 +13925,0.3760866522789,-0.235176980495453,0.028027879074216,38325,9412,1575,-3460,0.966158390045166 +13927,0.337334245443344,-0.205172419548035,0.028572110459209,38325,9910,-144,-3813,0.96689760684967 +13929,0.305675983428955,-0.178819760680199,0.029331218451262,38325,9454,103,-3493,0.96789288520813 +13931,0.277455806732178,-0.150722205638886,0.032160568982363,38325,10033,-684,-3779,0.97191047668457 +13933,0.247941359877586,-0.108475379645824,0.034470718353987,38325,-32767,-2101,-3498,0.982491135597229 +13935,0.231512427330017,-0.072931475937367,0.034360427409411,38325,-20557,-2262,-3756,0.988720238208771 +13937,0.226028993725777,-0.03637782484293,0.031083567067981,38325,-21648,-2816,-3605,0.989936888217926 +13939,0.227525189518929,-0.005363185890019,0.029548512771726,38325,-22032,-2871,-3784,0.991789817810059 +13941,0.222209364175796,0.03501370921731,0.026802653446794,38325,-21854,-4226,-3726,0.991624891757965 +13943,0.214246392250061,0.070667400956154,0.02285117842257,38325,-21412,-4289,-3829,0.996352314949035 +13945,0.199529141187668,0.107155092060566,0.020686145871878,38325,-21051,-5122,-3874,0.998907506465912 +13947,0.170163407921791,0.141201362013817,0.020734451711178,38325,-19484,-5214,-3846,0.997325897216797 +13949,0.127191081643105,0.174917668104172,0.019594173878431,38325,-18063,-6053,-3962,0.990774571895599 +13951,0.078970372676849,0.213158950209618,0.016416974365711,38325,-17027,-6604,-3880,0.980857491493225 +13953,0.025994455441833,0.243790522217751,0.016124540939927,38325,-15876,-7003,-4081,0.968938589096069 +13955,-0.041717253625393,0.283289045095444,0.01399489864707,38325,-14054,-7787,-3904,0.958683729171753 +13957,-0.120020069181919,0.311352699995041,0.010556224733591,38325,-11816,-8010,-4225,0.956947922706604 +13959,-0.201547533273697,0.331271976232529,0.008844679221511,38325,-10859,-7189,-3951,0.95545905828476 +13961,-0.290784776210785,0.350473761558533,0.010990656912327,38325,-8313,-8142,-4270,0.953603267669678 +13963,-0.387648016214371,0.365224808454514,0.013379381038249,38325,-7099,-7443,-3932,0.949743390083313 +13965,-0.489069432020187,0.382418990135193,0.013909049332142,38325,-4187,-8660,-4277,0.953828632831574 +13967,-0.585422813892365,0.384761929512024,0.011045184917748,38325,-4215,-6986,-3961,0.957856893539429 +13969,-0.679098844528198,0.388431459665298,0.011127354577184,38325,-1525,-7943,-4323,0.957261562347412 +13971,-0.778501212596893,0.396082878112793,0.014279126189649,38325,32767,-7685,-3952,0.958689987659454 +13973,-0.881797134876251,0.391675531864166,0.016549689695239,38325,27032,-7573,-4269,0.95851719379425 +13975,-0.99009382724762,0.387090533971786,0.018254624679685,38325,27370,-6838,-3937,0.961871087551117 +13977,-1.09344077110291,0.373468786478043,0.018250107765198,38325,31030,-6772,-4234,0.959603488445282 +13979,-1.18714535236359,0.364885956048966,0.012518581002951,38325,29762,-6385,-3987,0.954358816146851 +13981,-1.26536512374878,0.352480977773666,0.00601586792618,38325,32671,-6653,-4358,0.957232236862183 +13983,-1.33417570590973,0.337868899106979,0.001646586111747,38325,30782,-5706,-4074,0.956276059150696 +13985,-1.38804352283478,0.3245789706707,0.003235772950575,38325,32767,-6280,-4366,0.961163997650146 +13987,-1.42814254760742,0.314373403787613,0.00619415845722,38325,30830,-5815,-4054,0.973366260528564 +13989,-1.452068567276,0.319585025310516,0.00459338305518,38325,32767,-7658,-4347,0.985853135585785 +13991,-1.44645726680756,0.3102947473526,0.0018501940649,38325,28608,-5951,-4095,0.993683457374573 +13993,-1.42569780349731,0.296698480844498,-0.001672096783295,38325,30450,-6066,-4400,0.995175957679748 +13995,-1.39222753047943,0.274053782224655,-0.001125872135162,38325,26613,-4595,-4126,0.998790085315704 +13997,-1.34097528457642,0.255874812602997,-0.001385347684845,38325,27619,-5198,-4361,0.998483002185822 +13999,-1.27451300621033,0.243983641266823,-0.006171060726047,38325,23299,-5039,-4170,1.00518560409546 +14001,-1.19580054283142,0.232346907258034,-0.008327010087669,38325,23996,-5382,-4425,1.01060044765472 +14003,-1.11397385597229,0.230865210294723,-0.007867325097322,38325,20571,-5691,-4191,1.01776456832886 +14005,-1.01711857318878,0.211042046546936,-0.005096864886582,38325,20434,-4534,-4374,1.01472496986389 +14007,-0.914088070392608,0.204663157463074,-0.000326547422446,38325,16781,-5048,-4147,1.01806926727295 +14009,-0.795278906822205,0.191930651664734,0.001939139096066,38325,-32767,-4799,-4280,1.01550817489624 +14011,-0.67115592956543,0.193139344453812,0.001775869401172,38325,104,-5501,-4139,1.01278185844421 +14013,-0.533772885799408,0.187835082411766,0.005415666848421,38325,-1566,-5338,-4239,1.01606428623199 +14015,-0.393968194723129,0.18308013677597,0.009666888043284,38325,-4735,-5002,-4090,1.01456570625305 +14017,-0.248537108302116,0.1657585054636,0.013314601965249,38325,-6593,-4198,-4132,1.01831364631653 +14019,-0.11447386443615,0.165274009108543,0.015294435434043,38325,-8207,-5118,-4055,1.01822280883789 +14021,0.01759072765708,0.143076077103615,0.020941717550159,38325,-9892,-3546,-4027,1.01734626293182 +14023,0.129857882857323,0.142620101571083,0.024276927113533,38325,-10146,-4851,-3995,1.01445662975311 +14025,0.243818953633308,0.142645686864853,0.028595414012671,38325,-12319,-5187,-3938,1.01370465755463 +14027,0.347143650054932,0.148819759488106,0.031908288598061,38325,-12723,-5471,-3943,1.01304352283478 +14029,0.446270912885666,0.143879786133766,0.02962651476264,38325,-14701,-4914,-3928,1.01053702831268 +14031,0.539451241493225,0.123651310801506,0.029592107981443,38325,-14951,-3277,-3959,1.00306272506714 +14033,0.616103112697601,0.116394810378551,0.032945029437542,38325,-16082,-4359,-3869,1.0060647726059 +14035,0.686727821826935,0.110203638672829,0.033764060586691,38325,-15724,-4136,-3929,1.00847959518433 +14037,0.751029372215271,0.110099710524082,0.034477975219488,38325,-17686,-4813,-3846,1.0085871219635 +14039,0.809657394886017,0.095487356185913,0.036196678876877,38325,-16967,-3365,-3911,1.00603914260864 +14041,0.85108357667923,0.091733314096928,0.038654461503029,38325,-18026,-4289,-3783,1.00415003299713 +14043,0.897182822227478,0.072161085903645,0.039013538509607,38325,-17710,-2710,-3889,0.998241782188416 +14045,0.926392376422882,0.069013625383377,0.036384847015143,38325,-18765,-3986,-3790,0.994436979293823 +14047,0.945102751255035,0.057753257453442,0.036169666796923,38325,-32767,-3122,-3906,0.994757831096649 +14049,0.951567053794861,0.055702291429043,0.033688139170408,38325,-24061,-3869,-3809,0.996810436248779 +14051,0.955923676490784,0.048337396234274,0.032203134149313,38325,-22538,-3284,-3931,1.00126588344574 +14053,0.946734309196472,0.048043429851532,0.03149601444602,38325,-23348,-3892,-3827,1.00337016582489 +14055,0.93018901348114,0.044837076216936,0.030093796551228,38325,-21166,-3547,-3943,1.00417339801788 +14057,0.907921314239502,0.029133822768927,0.027778338640928,38325,-22260,-2489,-3853,0.999842405319214 +14059,0.869402647018433,0.021113963797689,0.024314755573869,38325,-19197,-2868,-3980,0.992017686367035 +14061,0.819277465343475,0.010653430595994,0.016942264512181,38325,-19280,-2558,-3962,0.982104539871216 +14063,0.761971950531006,0.009965666569769,0.012276383116841,38325,-16749,-3230,-4062,0.971424520015717 +14065,0.697162628173828,0.00311560742557,0.015074009075761,38325,-16653,-2687,-3976,0.962891399860382 +14067,0.611992597579956,-0.002065049717203,0.015947913751006,38325,-12985,-2728,-4036,0.962468087673187 +14069,0.526057481765747,-0.003458929480985,0.015241086483002,38325,-12704,-2970,-3968,0.963720619678497 +14071,0.436215370893478,0.001382953720167,0.01733841188252,38325,-10434,-3487,-4025,0.969878911972046 +14073,0.340274930000305,0.006915430538356,0.016674498096109,38325,-9227,-3637,-3959,0.972834408283233 +14075,0.233218401670456,0.001932608545758,0.009872305206954,38325,-6509,-2788,-4075,0.971260070800781 +14077,0.124279521405697,-0.014250408858061,0.00225690100342,38325,-4961,-1720,-4108,0.967043399810791 +14079,0.010004282929003,-0.02398850210011,0.003068916499615,38325,-2911,-2061,-4123,0.963767409324646 +14093,-0.753408074378967,-0.079059734940529,0.005722248926759,38325,3567,-1428,-4006,0.970507860183716 +14095,-0.863102614879608,-0.084042273461819,0.004390425048769,38325,3580,-1401,-4107,0.972176611423492 +14097,-0.971173405647278,-0.084520854055882,0.003915948327631,38325,7156,-1528,-4022,0.968877911567688 +14099,-1.0774632692337,-0.084886960685253,0.005670171696693,38325,6743,-1671,-4097,0.966171205043793 +14101,-1.18633902072907,-0.082479067146778,0.003538049757481,38325,11085,-1720,-4028,0.962620794773102 +14103,-1.28560614585876,-0.087780945003033,0.001572757959366,38325,9658,-1228,-4123,0.96220189332962 +14105,-1.37734854221344,-0.090432904660702,0.002229985082522,38325,13429,-1177,-4038,0.963530540466309 +14107,-1.46593642234802,-0.086512491106987,0.00035529123852,38325,12004,-1854,-4130,0.961854934692383 +14109,-1.53891825675964,-0.086625382304192,0.000674203387462,38325,15268,-1372,-4060,0.960028529167175 +14111,-1.60947930812836,-0.087168388068676,0.002945613116026,38325,13375,-1475,-4112,0.957847774028778 +14113,-1.67371773719788,-0.09203577786684,0.005048170220107,38325,17464,-896,-4006,0.954292178153992 +14115,-1.73248469829559,-0.085921756923199,0.006782748736441,38325,14964,-1917,-4083,0.955889582633972 +14117,-1.78322792053223,-0.072072044014931,0.004779321141541,38325,18965,-2512,-4026,0.960737347602844 +14119,-1.8180605173111,-0.058531265705824,0.004775671754032,38325,15202,-2799,-4096,0.9658282995224 +14121,-1.84519422054291,-0.04776968434453,0.004871563520283,38325,19016,-2646,-4043,0.966115355491638 +14123,-1.8638768196106,-0.04677739366889,0.005356459878385,38325,15460,-2035,-4092,0.969439804553986 +14125,-1.88223075866699,-0.033800665289164,0.005198835860938,38325,19748,-3000,-4049,0.9703688621521 +14127,-1.88412868976593,-0.034015320241451,0.007393842097372,38325,15327,-2105,-4077,0.973680078983307 +14129,-1.87996959686279,-0.023738339543343,0.008406694978476,38325,18869,-2950,-4018,0.977800369262695 +14131,-1.86085939407349,-0.022949310019612,0.00715852715075,38325,14271,-2314,-4078,0.981992423534393 +14133,-1.83255183696747,-0.018016232177615,0.002993729664013,38325,17136,-2644,-4085,0.985560595989227 +14135,-1.79142880439758,-0.008437603712082,0.004529273603112,38325,12464,-3134,-4097,0.992458641529083 +14137,-1.75062942504883,0.004959331825376,0.008139821700752,38325,15656,-3610,-4038,0.993938684463501 +14139,-1.7080169916153,0.023003360256553,0.00557907205075,38325,11893,-4183,-4090,0.993146181106567 +14141,-1.65222585201263,0.031792890280485,0.005045054480433,38325,13686,-3716,-4088,0.987870216369629 +14143,-1.58979213237762,0.052005998790264,0.004679987207055,38325,9468,-4760,-4097,0.977533102035522 +14145,-1.52006638050079,0.065294042229652,0.007093613035977,38325,11197,-4597,-4079,0.9794562458992 +14147,-1.4475462436676,0.084507577121258,0.010190640576184,38325,7339,-5176,-4060,0.985547602176666 +14149,-1.36669313907623,0.09255637973547,0.014923007227481,38325,8507,-4691,-3998,0.992525398731232 +14151,-1.28999316692352,0.11288545280695,0.018221298232675,38325,5347,-5697,-4005,0.999490439891815 +14153,-1.20594310760498,0.129405453801155,0.01688233576715,38325,6190,-5934,-3988,1.01046633720398 +14155,-1.11718463897705,0.144411087036133,0.0160798933357,38325,2499,-5818,-4020,1.01457965373993 +14157,-1.02923929691315,0.159995466470718,0.020799143239856,38325,3492,-6409,-3951,1.01792788505554 +14159,-0.937277138233185,0.167426660656929,0.024162137880921,38325,106,-5669,-3965,1.01835310459137 +14161,-0.848339438438416,0.184363171458244,0.026774767786265,38325,857,-6967,-3886,1.01875507831573 +14163,-0.762103974819183,0.188218683004379,0.030443416908383,38325,-1660,-5785,-3921,1.01776671409607 +14165,-0.682043552398682,0.198290571570396,0.034153677523136,38325,-905,-6788,-3800,1.01984345912933 +14167,-0.598712503910065,0.206894174218178,0.039363037794829,38325,-3534,-6475,-3857,1.01463913917542 +14169,-0.520489037036896,0.221412047743797,0.04211725667119,38325,-3183,-7572,-3709,1.00837564468384 +14171,-0.438317865133285,0.217719152569771,0.043557688593865,38325,-5565,-5844,-3825,1.00430703163147 +14173,-0.361276686191559,0.230706080794334,0.044123709201813,38325,-5524,-7707,-3683,0.999996244907379 +14175,-0.286164373159409,0.225422382354736,0.049677100032568,38325,-7125,-5939,-3780,0.995930254459381 +14177,-0.221107631921768,0.22310009598732,0.050107311457396,38325,-6843,-6587,-3605,0.988391041755676 +14179,-0.154422000050545,0.216826155781746,0.048723820596933,38325,-8356,-5841,-3782,0.991218984127045 +14181,-0.098373554646969,0.220063328742981,0.049818351864815,38325,-8168,-7033,-3602,0.995544731616974 +14183,-0.040408089756966,0.214494198560715,0.052650522440672,38325,-9368,-5954,-3750,0.997731447219849 +14185,0.014388277195394,0.199304550886154,0.057777930051088,38325,-9950,-5470,-3495,0.996162533760071 +14187,0.053431879729033,0.192592531442642,0.059190064668655,38325,-9414,-5645,-3699,0.998236179351806 +14189,0.088514357805252,0.175329640507698,0.057760186493397,38325,-9819,-5017,-3481,0.994763612747192 +14191,0.12206394970417,0.161679819226265,0.055905092507601,38325,-10095,-4782,-3715,0.994791924953461 +14193,0.154819250106812,0.14832030236721,0.05407840013504,38325,-10825,-4926,-3509,0.986737489700317 +14195,0.167484149336815,0.145928725600243,0.050296701490879,38325,-9370,-5428,-3747,0.978282451629639 +14197,0.179773151874542,0.122681774199009,0.048191592097283,38325,-9880,-3849,-3565,0.97289103269577 +14199,0.188162505626678,0.109934858977795,0.048303324729204,38325,-9490,-4222,-3755,0.969855189323425 +14201,0.199620485305786,0.085532903671265,0.049656886607409,38325,-10278,-3203,-3529,0.965877711772919 +14203,0.199061304330826,0.078173786401749,0.052371490746737,38325,-9145,-4186,-3721,0.963061571121216 +14205,0.194674700498581,0.062365595251322,0.052847478538752,38325,-9216,-3482,-3477,0.961600244045258 +14207,0.183533504605293,0.038916949182749,0.050627332180739,38325,-8305,-2496,-3726,0.957884728908539 +14209,0.162834256887436,0.026437198743224,0.048684399574995,38325,-7666,-3159,-3507,0.961328208446503 +14211,0.14129051566124,0.008952186442912,0.04591416195035,38325,-7080,-2503,-3751,0.959838926792145 +14213,0.118118181824684,-0.004166868049651,0.045195709913969,38325,-6864,-2619,-3531,0.957049489021301 +14215,0.088778212666512,-0.018803441897035,0.045320864766836,38325,-5872,-2304,-3749,0.952886164188385 +14217,0.050336580723524,-0.028178561478853,0.041435264050961,38325,-4750,-2485,-3561,0.956265926361084 +14219,0.015672268345952,-0.053829327225685,0.038759633898735,38325,-4513,-997,-3788,0.964593887329102 +14221,-0.027437606826425,-0.062645047903061,0.035839397460222,38325,-3209,-1937,-3609,0.964618027210236 +14223,-0.068086959421635,-0.07966522872448,0.034921731799841,38325,-2919,-1211,-3809,0.963247895240784 +14225,-0.116633281111717,-0.090346962213516,0.034444637596607,38325,-1393,-1313,-3610,0.959167301654816 +14243,-0.481516510248184,-0.187018126249313,0.039543185383082,38325,3160,-501,-3745,0.967727780342102 +14245,-0.511285185813904,-0.195364683866501,0.038809824734926,38325,4172,611,-3496,0.975693047046661 +14247,-0.541416168212891,-0.197862401604652,0.041163757443428,38325,3720,-93,-3726,0.979502499103546 +14249,-0.572983622550964,-0.193227618932724,0.040049597620964,38325,5527,-250,-3477,0.981266975402832 +14251,-0.597023367881775,-0.187977895140648,0.036455683410168,38325,4307,-693,-3751,0.977674782276154 +14253,-0.616905629634857,-0.174315512180328,0.034666649997234,38325,5635,-1107,-3541,0.968816041946411 +14255,-0.630137741565704,-0.171085014939308,0.031748339533806,38325,4254,-701,-3777,0.965795159339905 +14257,-0.643259704113007,-0.160836517810822,0.027562897652388,38325,5814,-1005,-3624,0.964354813098908 +14259,-0.655515193939209,-0.157021105289459,0.028548140078783,38325,4805,-863,-3793,0.969739735126495 +14261,-0.669099509716034,-0.139798358082771,0.030976295471192,38325,6508,-1783,-3586,0.975075781345367 +14263,-0.678018808364868,-0.122936442494392,0.03494281321764,38325,5157,-2216,-3744,0.981640219688416 +14265,-0.680257678031921,-0.118012227118015,0.038887988775969,38325,6142,-1200,-3494,0.978304982185364 +14267,-0.686799585819244,-0.104425385594368,0.037428963929415,38325,5387,-2188,-3720,0.980668485164642 +14269,-0.690394699573517,-0.090830519795418,0.036153879016638,38325,6689,-2192,-3528,0.985498309135437 +14271,-0.681916773319244,-0.071394182741642,0.034546926617622,38325,4523,-3031,-3734,0.981527864933014 +14273,-0.666228413581848,-0.056510806083679,0.036314070224762,38325,5195,-2785,-3530,0.975190699100494 +14275,-0.661355793476105,-0.034289322793484,0.034856505692005,38325,4760,-3727,-3727,0.970425546169281 +14277,-0.65641725063324,-0.028768608346582,0.031065184623003,38325,6073,-2537,-3593,0.973253726959228 +14279,-0.648748576641083,-0.01567729562521,0.02980836853385,38325,4650,-3316,-3757,0.974123120307922 +14281,-0.634163975715637,0.003006140468642,0.030889574438334,38325,5284,-3998,-3597,0.976658582687378 +14283,-0.610202550888062,0.021333608776331,0.031623035669327,38325,3191,-4216,-3740,0.976084470748901 +14285,-0.588083148002625,0.053376868367195,0.031482446938753,38325,4245,-5780,-3595,0.982647061347961 +14287,-0.565005779266357,0.073444128036499,0.03090462833643,38325,2848,-5106,-3741,0.983579576015472 +14289,-0.540757477283478,0.091989606618881,0.033804908394814,38325,3554,-5454,-3570,0.977344989776611 +14291,-0.512883901596069,0.097733229398728,0.041621062904596,38325,1978,-4462,-3663,0.973000109195709 +14293,-0.49509471654892,0.118044137954712,0.043154358863831,38325,3492,-6036,-3459,0.972344279289246 +14295,-0.465519815683365,0.127581879496574,0.03894192352891,38325,1379,-5206,-3676,0.976500034332275 +14297,-0.434486031532288,0.145487785339356,0.032761834561825,38325,1757,-6358,-3579,0.976350605487824 +14299,-0.401501595973969,0.153674185276032,0.032390084117651,38325,395,-5541,-3717,0.97683048248291 +14301,-0.374727040529251,0.163439556956291,0.033916592597962,38325,1234,-6140,-3563,0.977173745632172 +14303,-0.348755478858948,0.172315746545792,0.03596105799079,38325,288,-5926,-3689,0.982560992240906 +14305,-0.318248838186264,0.182774618268013,0.03902355581522,38325,172,-6576,-3500,0.982889175415039 +14307,-0.287104934453964,0.196883589029312,0.038995292037726,38325,-845,-6731,-3663,0.982970654964447 +14309,-0.258210986852646,0.190244272351265,0.038265481591225,38325,-564,-5552,-3504,0.969910562038422 +14311,-0.240716561675072,0.199851736426353,0.040627337992191,38325,-436,-6533,-3647,0.966339588165283 +14313,-0.219509735703468,0.196459457278252,0.043434403836727,38325,-535,-5970,-3439,0.965000033378601 +14315,-0.196334674954414,0.194596171379089,0.040421705693007,38325,-1397,-5721,-3643,0.958707094192505 +14317,-0.168638586997986,0.18775737285614,0.04239409789443,38325,-1753,-5667,-3443,0.956436932086945 +14319,-0.149988636374474,0.193938598036766,0.044149547815323,38325,-1677,-6370,-3612,0.951608121395111 +14321,-0.129570528864861,0.183705821633339,0.04286677762866,38325,-1831,-5439,-3431,0.957514107227325 +14323,-0.108909383416176,0.174091055989265,0.040810644626618,38325,-2371,-5035,-3630,0.965440511703491 +14325,-0.084147535264492,0.161656752228737,0.04159003123641,38325,-2854,-4994,-3437,0.974957227706909 +14327,-0.063481189310551,0.153997525572777,0.042749434709549,38325,-3004,-4957,-3611,0.97454971075058 +14329,-0.050808604806662,0.156466618180275,0.044555068016052,38325,-2508,-6032,-3396,0.977775812149048 +14331,-0.038625113666058,0.144099071621895,0.045756198465824,38325,-2748,-4543,-3584,0.972683370113373 +14333,-0.029132278636098,0.132399648427963,0.04471929743886,38325,-2623,-4674,-3385,0.970754742622376 +14335,-0.020613329485059,0.119380183517933,0.042697630822659,38325,-2747,-4195,-3599,0.967323958873749 +14337,-0.013819894753397,0.114400058984756,0.039895415306091,38325,-2697,-4922,-3434,0.959506452083588 +14339,-0.009705082513392,0.102050229907036,0.043423905968666,38325,-2600,-4041,-3589,0.958877742290497 +14341,-0.011985535733402,0.097633242607117,0.043827973306179,38325,-2107,-4743,-3380,0.956949293613434 +14343,-0.009824158623815,0.077176734805107,0.044851940125227,38325,-2474,-3144,-3573,0.954482555389404 +14345,-0.012160344980657,0.06643833220005,0.044377025216818,38325,-2113,-3824,-3363,0.948942184448242 +14347,-0.016839763149619,0.043453607708216,0.041163414716721,38325,-1899,-2507,-3592,0.948585391044617 +14349,-0.020661735907197,0.028359308838844,0.036354094743729,38593,-1874,-2899,-3448,0.950696408748627 +14351,-0.023588331416249,0.01899778842926,0.035520039498806,38593,-1938,-3140,-3625,0.957583606243134 +14353,-0.029752872884274,0.004481754731387,0.036391526460648,38593,-1565,-2552,-3439,0.957694411277771 +14355,-0.041021518409252,-0.007525889202952,0.038792669773102,38593,-1095,-2567,-3598,0.961437463760376 +14357,-0.048837043344975,-0.026768833398819,0.040180012583733,38593,-1133,-1702,-3385,0.966535866260529 +14359,-0.059218313544989,-0.028668753802776,0.038274984806776,38593,-893,-2971,-3595,0.967982828617096 +14361,-0.06801700592041,-0.046316359192133,0.038237225264311,38593,-726,-1476,-3400,0.968197405338287 +14363,-0.086631268262863,-0.054205749183893,0.040124122053385,38593,105,-2150,-3577,0.964373886585236 +14365,-0.097226053476334,-0.083329044282436,0.04430939629674,38593,-98,-19,-3318,0.959110498428345 +14367,-0.109032601118088,-0.092665247619152,0.046770725399256,38593,-30,-1451,-3524,0.958234488964081 +14369,-0.109771855175495,-0.102361835539341,0.048777401447296,38593,-572,-1050,-3256,0.962864875793457 +14371,-0.121174201369286,-0.10165623575449,0.043638329952955,38593,150,-1988,-3538,0.964506089687347 +14373,-0.131766006350517,-0.116156980395317,0.039897855371237,38593,523,-437,-3353,0.963266730308533 +14375,-0.146159678697586,-0.136215165257454,0.041360598057509,38593,767,52,-3547,0.959610879421234 +14393,-0.210886567831039,-0.142159327864647,0.044732134789229,38951,1609,-1189,-2419,0.970524728298187 +14395,-0.216845408082008,-0.12678362429142,0.043126862496138,38951,1538,-2263,-2634,0.981231868267059 +14397,-0.215691134333611,-0.120570324361324,0.038815788924694,38951,1458,-1437,-2435,0.979790687561035 +14399,-0.216037094593048,-0.111267067492008,0.033363729715347,38951,1210,-1989,-2645,0.974814176559448 +14401,-0.219169229269028,-0.100256361067295,0.030903231352568,38951,1900,-2053,-2475,0.970007359981537 +14403,-0.226228147745132,-0.080375425517559,0.027784602716565,38951,1923,-3137,-2628,0.964137494564056 +14405,-0.224238231778145,-0.081149727106094,0.02360032312572,38951,1698,-1470,-2508,0.96290522813797 +14407,-0.225295320153236,-0.070732124149799,0.020609172061086,38951,1568,-2554,-2624,0.964878141880035 +14409,-0.221378162503242,-0.067303001880646,0.019223952665925,38951,1617,-1948,-2508,0.968680202960968 +14411,-0.21998755633831,-0.057191979140043,0.01371444016695,38951,1406,-2686,-2619,0.971108376979828 +14413,-0.217623919248581,-0.04568837583065,0.010457170195878,38951,1753,-2838,-2561,0.97689300775528 +14415,-0.213294357061386,-0.034537747502327,0.004800456576049,38951,1188,-3056,-2629,0.977097749710083 +14417,-0.205690145492554,-0.019245253875852,-0.000254616606981,38951,1270,-3511,-2639,0.977468073368072 +14419,-0.205092415213585,-0.005824254825711,-0.00101044436451,38951,1421,-3611,-2620,0.975412845611572 +14421,-0.202425941824913,0.014684557914734,-0.002047675661743,38951,1655,-4421,-2548,0.975695908069611 +14423,-0.196150615811348,0.023083506152034,-0.007890240289271,39505,969,-3662,-2551,0.97791576385498 +14425,-0.191519543528557,0.034636192023754,-0.014941604807973,39505,1419,-4111,-2648,0.978415727615356 +14427,-0.18477888405323,0.044994805008173,-0.017176114022732,39505,851,-4123,-2563,0.97851687669754 +14429,-0.181365549564362,0.065207667648792,-0.018114268779755,39505,1417,-5241,-2636,0.973427534103394 +14431,-0.175798520445824,0.079691417515278,-0.019727323204279,39505,881,-4937,-2530,0.974663436412811 +14433,-0.166394591331482,0.088027380406857,-0.022096544504166,39505,814,-4792,-2634,0.97204726934433 +14435,-0.157996147871017,0.093177452683449,-0.025695148855448,39505,491,-4494,-2521,0.972947835922241 +14437,-0.151915013790131,0.091171555221081,-0.029891515150666,39505,882,-4141,-2676,0.972376704216003 +14439,-0.149053409695625,0.103477232158184,-0.030998472124338,39505,821,-5190,-2509,0.97531795501709 +14441,-0.139981657266617,0.108606271445751,-0.033227548003197,39505,536,-4972,-2667,0.979598999023438 +14443,-0.129960879683495,0.12067361921072,-0.038956623524428,39505,91,-5463,-2515,0.983943521976471 +14445,-0.118613019585609,0.116641446948051,-0.038916703313589,39505,83,-4487,-2686,0.987149178981781 +14447,-0.118556700646877,0.1251540184021,-0.040354296565056,39505,690,-5319,-2477,0.987273395061493 +14449,-0.110218033194542,0.127659901976585,-0.044551242142916,39505,207,-5185,-2706,0.981175065040588 +14451,-0.097119279205799,0.131057947874069,-0.051748033612967,39505,-507,-5089,-2509,0.971091568470001 +14453,-0.091893531382084,0.136638283729553,-0.055810246616602,39505,170,-5607,-2793,0.972956538200378 +14455,-0.087473042309284,0.135065779089928,-0.057542953640223,39505,12,-4847,-2504,0.976246416568756 +14457,-0.082538574934006,0.137465268373489,-0.059937566518784,39505,71,-5454,-2797,0.977993249893188 +14459,-0.074812561273575,0.129776477813721,-0.064119704067707,39505,-374,-4391,-2421,0.981555283069611 +14461,-0.071701772511005,0.135143801569939,-0.068958051502705,40041,55,-5684,-2772,0.982529759407043 +14463,-0.065907135605812,0.126444652676582,-0.071293763816357,40041,-337,-4328,-2422,0.981743454933166 +14465,-0.071155019104481,0.134383603930473,-0.072672814130783,40041,671,-5901,-2768,0.983232259750366 +14467,-0.066981658339501,0.1313157081604,-0.073509030044079,40041,-179,-4856,-2390,0.984279334545136 +14469,-0.063154444098473,0.131382942199707,-0.07744961231947,40041,-84,-5337,-2777,0.98567795753479 +14471,-0.054819609969854,0.122359596192837,-0.080814890563488,40041,-628,-4354,-2393,0.990532398223877 +14473,-0.051856338977814,0.110447816550732,-0.082028724253178,40041,-164,-4187,-2784,0.989379584789276 +14475,-0.057115700095892,0.106239654123783,-0.086935557425022,40041,400,-4512,-2389,0.995079338550568 +14477,-0.052047688513994,0.092116542160511,-0.090769447386265,40041,-292,-3778,-2840,0.995804786682129 +14479,-0.039025213569403,0.086245998740196,-0.096349589526653,40041,-1147,-4143,-2409,0.990100741386414 +14481,-0.028640549629927,0.080602988600731,-0.10237492620945,40041,-1057,-4242,-2933,0.992786347866058 +14483,-0.036430735141039,0.087694115936756,-0.109454534947872,40041,313,-5126,-2456,0.998819947242737 +14485,-0.043530531227589,0.08091051876545,-0.113312542438507,40041,452,-4194,-3019,1.0027152299881 +14487,-0.047589037567377,0.074020937085152,-0.11577895283699,40041,222,-3962,-2459,1.0006275177002 +14489,-0.052023380994797,0.064765736460686,-0.115123815834522,40041,426,-3778,-2999,1.00126838684082 +14491,-0.051142372190952,0.048678785562515,-0.117575205862522,40041,-59,-2964,-2430,0.992626070976257 +14493,-0.052127707749605,0.043093767017126,-0.12034747749567,40041,204,-3708,-3020,0.988759875297546 +14495,-0.053048063069582,0.032021645456553,-0.121099218726158,40041,118,-3099,-2415,0.986039161682129 +14497,-0.05202017351985,0.02669920027256,-0.123628608882427,40041,58,-3481,-2979,0.987100601196289 +14499,-0.046749215573073,0.01756920106709,-0.131800964474678,40399,-397,-3039,-2408,0.985299170017242 +14501,-0.047709956765175,0.021747460588813,-0.138514190912247,40399,131,-4099,-3113,0.983321487903595 +14503,-0.045924261212349,0.020074902102351,-0.136730462312698,40399,-146,-3617,-2403,0.982633471488952 +14505,-0.045441146939993,0.017170011997223,-0.137106418609619,40399,13,-3524,-3057,0.981182217597961 +14507,-0.048936765640974,0.008658335544169,-0.141645610332489,40399,289,-2970,-2397,0.980113565921783 +14509,-0.048578292131424,-0.001436924445443,-0.147535145282745,40399,101,-2697,-3140,0.978311836719513 +14511,-0.040268562734127,-0.00233616027981,-0.152391970157623,40399,-663,-3353,-2432,0.981235086917877 +14513,-0.0270179733634,-0.01674722135067,-0.153674945235252,40399,-1154,-2121,-3175,0.983424365520477 +14515,-0.027645552530885,-0.017459692433477,-0.153804779052734,40399,-195,-3137,-2405,0.987471044063568 +14517,-0.030720276758075,-0.029379175975919,-0.153176411986351,40399,76,-2082,-3131,0.995635092258453 +14519,-0.02825266495347,-0.027839308604598,-0.15464474260807,40399,-398,-3131,-2373,1.00450468063355 +14521,-0.014746678993106,-0.02964317239821,-0.156232818961144,40399,-1361,-2791,-3130,1.01363408565521 +14523,-0.009544500149786,-0.028776749968529,-0.157099440693855,40399,-860,-3052,-2353,1.01197135448456 +14525,-0.013532670214772,-0.025089448317885,-0.157306954264641,40399,-111,-3246,-3106,1.01030671596527 +14527,-0.010963984765112,-0.028316842392087,-0.158728465437889,40399,-647,-2750,-2328,1.00597882270813 +14529,0.001746722264215,-0.027455057948828,-0.163091316819191,40399,-1563,-2990,-3138,0.99765682220459 +14531,0.016001312062144,-0.02527710609138,-0.169389262795448,40399,-1875,-3165,-2365,0.991917490959168 +14533,0.017209248617292,-0.00686667766422,-0.173771739006042,40399,-1001,-4567,-3229,0.992253839969635 +14535,0.022249622270465,-0.005494326353073,-0.175458997488022,40399,-1317,-3384,-2327,0.993880927562714 +14537,0.026691615581513,-0.006220492068678,-0.176827341318131,41042,-1402,-3201,-3184,0.998618841171265 +14539,0.027817087247968,-0.006486014928669,-0.177655756473541,41042,-1133,-3246,-2306,1.00894677639008 +14541,0.023031963035464,-0.002691820496693,-0.181445851922035,41042,-708,-3569,-3202,1.0166848897934 +14543,0.018581584095955,0.000875845027622,-0.184582576155663,41042,-617,-3620,-2318,1.02208268642426 +14545,0.014459325931966,-0.009554184041917,-0.183795869350433,41042,-631,-2428,-3194,1.01868617534637 +14547,0.005396355874836,-0.012707689777017,-0.18305578827858,41042,-110,-2934,-2272,1.00837600231171 +14549,-0.000968420528807,-0.011658472009003,-0.18372268974781,41042,-221,-3211,-3158,0.996082365512848 +14551,-0.009225411340594,-0.003628315171227,-0.186443507671356,41042,36,-3855,-2260,0.98623251914978 +14553,-0.015051711350679,-0.00482973922044,-0.187250256538391,41042,-29,-3156,-3164,0.988102972507477 +14555,-0.01358447689563,-0.012922912836075,-0.185838043689728,41042,-594,-2560,-2221,0.991932272911072 +14557,-0.015670370310545,-0.004250382073224,-0.18479435145855,41042,-285,-3869,-3100,0.997174203395844 +14559,-0.022643765434623,-0.002274372149259,-0.183073580265045,41042,142,-3429,-2166,1.00348591804504 +14561,-0.031437080353499,0.003934231121093,-0.183044776320457,41042,452,-3814,-3044,1.01108038425446 +14563,-0.035050008445978,0.003508010180667,-0.183928489685059,41042,89,-3336,-2136,1.01877164840698 +14565,-0.041956141591072,0.011694516986609,-0.187749058008194,41042,500,-4072,-3064,1.02146410942078 +14567,-0.047403398901224,0.010038750246167,-0.19280219078064,41042,412,-3341,-2162,1.01764559745789 +14569,-0.050462152808905,0.012048081494868,-0.195310011506081,41042,386,-3641,-3119,1.010906457901 +14571,-0.058242678642273,0.022310491651297,-0.194722086191177,41042,755,-4371,-2142,1.007807970047 +14573,-0.067330256104469,0.025707492604852,-0.193968176841736,41042,1118,-3969,-3070,1.00755441188812 +14575,-0.072812385857105,0.025593992322683,-0.197335004806519,41042,827,-3682,-2126,1.00600802898407 +14577,-0.071276873350144,0.011308506131172,-0.198403432965279,41042,454,-2472,-3088,1.00599670410156 +14579,-0.074070774018765,0.005160949658602,-0.198761627078056,41042,683,-2957,-2102,1.00443077087402 +14581,-0.073178447782993,0.001044630189426,-0.199568197131157,41042,559,-3028,-3068,1.00784385204315 +14583,-0.064672328531742,-0.00340785458684,-0.200247451663017,41042,-229,-2951,-2079,1.00756359100342 +14585,-0.062174275517464,0.000283397937892,-0.20236311852932,41042,289,-3570,-3068,1.01171946525574 +14587,-0.06269159168005,0.002555634593591,-0.20578570663929,41042,414,-3513,-2085,1.01654458045959 +14589,-0.061587564647198,0.013063019141555,-0.210563719272614,41042,399,-4270,-3133,1.02086114883423 +14591,-0.053036198019981,0.011314379051328,-0.215062990784645,41042,-349,-3352,-2117,1.02091181278229 +14593,-0.053473863750696,0.022332105785608,-0.214591175317764,41042,405,-4465,-3149,1.02289199829102 +14595,-0.060536444187164,0.033167604357004,-0.212120711803436,41042,898,-4574,-2066,1.02308619022369 +14597,-0.064928375184536,0.050845518708229,-0.215995147824287,41042,900,-5415,-3136,1.01848375797272 +14599,-0.060772769153118,0.063168331980705,-0.222108483314514,41042,125,-5130,-2104,1.01391994953156 +14601,-0.048698835074902,0.062094375491142,-0.227201238274574,41042,-524,-4275,-3238,1.01350200176239 +14603,-0.037320103496313,0.057342536747456,-0.230615183711052,41042,-709,-3848,-2134,1.01461279392242 +14605,-0.030301908031106,0.046755138784647,-0.23083321750164,41042,-448,-3367,-3252,1.01931059360504 +14607,-0.028601005673409,0.046854414045811,-0.23127768933773,41042,-131,-4063,-2111,1.0222681760788 +14623,-0.018794678151608,0.032340623438358,-0.240647181868553,41042,-564,-2478,-2064,1.00816595554352 +14625,-0.009135916829109,0.026389082893729,-0.242804408073425,41042,-925,-3469,-3255,1.00937938690186 +14627,-0.00606193440035,0.039090432226658,-0.239995181560516,41042,-509,-4956,-2033,1.01422357559204 +14629,-0.004005078691989,0.050189234316349,-0.238194406032562,41042,-447,-5087,-3174,1.02361941337585 +14631,-0.006587822455913,0.059074517339468,-0.244729071855545,41042,-93,-4988,-2039,1.02593231201172 +14633,-0.005968148820102,0.046562116593123,-0.250797122716904,41042,-314,-3358,-3297,1.02556991577148 +14635,-0.001043674536049,0.041087839752436,-0.252997010946274,41042,-708,-3719,-2071,1.02649104595184 +14637,0.010888425633311,0.036479711532593,-0.253783613443375,41042,-1418,-3782,-3307,1.03170895576477 +14639,0.020485175773501,0.032152071595192,-0.256636559963226,41042,-1360,-3688,-2072,1.03423500061035 +14641,0.018803831189871,0.037697568535805,-0.257530510425568,41042,-591,-4560,-3327,1.03405511379242 +14643,0.009810343384743,0.037299890071154,-0.25579234957695,41042,111,-4060,-2042,1.03286552429199 +14645,-0.000881466199644,0.042299937456846,-0.258683025836945,41042,367,-4616,-3317,1.03452277183533 +14647,-0.006037828978151,0.036763802170754,-0.264182955026627,41042,59,-3704,-2076,1.03750598430634 +14649,-0.009152025915682,0.035643298178911,-0.26761919260025,41042,-35,-4075,-3399,1.03248751163483 +14651,-0.004200452473015,0.02747517824173,-0.266847312450409,41042,-689,-3397,-2072,1.02678143978119 +14653,0.005530486814678,0.025065451860428,-0.269957005977631,41042,-1196,-3819,-3405,1.01696038246155 +14655,0.00469230581075,0.028583236038685,-0.27347469329834,41042,-408,-4260,-2096,1.0100964307785 +14657,-0.003430700395256,0.023872474208474,-0.273975342512131,41042,223,-3639,-3431,1.00851631164551 +14659,-0.012884173542261,0.024824729189277,-0.274750411510468,41042,459,-4031,-2084,1.01134312152863 +14661,-0.018725942820311,0.017449555918574,-0.276385396718979,41042,318,-3350,-3438,1.01607310771942 +14663,-0.022079857066274,0.012029628269374,-0.276191622018814,41042,161,-3396,-2073,1.01643538475037 +14665,-0.028753561899066,0.010090059600771,-0.274267554283142,41042,554,-3629,-3392,1.02775514125824 +14667,-0.035026028752327,0.00809090398252,-0.272579163312912,41042,568,-3587,-2027,1.03709650039673 +14669,-0.048126090317965,0.009590332396328,-0.27120640873909,41042,1337,-3870,-3335,1.04577326774597 +14671,-0.056324724107981,0.005673062056303,-0.272007495164871,41042,1031,-3417,-2002,1.04919588565826 +14673,-0.057148795574904,0.006321425084025,-0.274000734090805,41042,619,-3763,-3346,1.04528975486755 +14675,-0.052334096282721,-0.002291270298883,-0.277731209993362,41042,65,-2968,-2020,1.03639566898346 +14677,-0.058479242026806,-0.00186977093108,-0.281259894371033,41042,1043,-3620,-3411,1.02352726459503 +14679,-0.073471412062645,-0.0022029702086,-0.279812872409821,41042,1810,-3562,-2014,1.01529729366303 +14681,-0.07929652929306,-0.006063991226256,-0.276589512825012,41042,1387,-3238,-3336,1.01336669921875 +14683,-0.072237260639668,-0.007619608659297,-0.278665065765381,41042,246,-3393,-1985,1.01280415058136 +14685,-0.061519712209702,-0.016641324386001,-0.285083889961243,41042,-44,-2689,-3416,1.01411879062653 +14687,-0.066818587481976,-0.009404331445694,-0.285846561193466,41042,1081,-3989,-2015,1.0207085609436 +14689,-0.072024345397949,-0.016275046393275,-0.285659641027451,41042,1292,-2830,-3403,1.03065598011017 +14691,-0.071071304380894,-0.023019263520837,-0.288091033697128,41042,726,-2782,-2012,1.03509223461151 +14693,-0.063103392720223,-0.028623508289456,-0.292380124330521,41042,228,-2711,-3463,1.037881731987 +14695,-0.053711052983999,-0.027012195438147,-0.295128345489502,41042,-100,-3307,-2042,1.03655683994293 +14697,-0.046359963715077,-0.028813157230616,-0.295697152614594,41042,22,-2976,-3485,1.03344929218292 +14699,-0.046836450695992,-0.034212242811918,-0.294924020767212,41042,527,-2688,-2023,1.03630816936493 +14701,-0.050430521368981,-0.026917612180114,-0.29394519329071,41042,891,-3644,-3446,1.0393431186676 +14703,-0.050985306501389,-0.017243379727006,-0.291219830513,41042,613,-3998,-1979,1.04573357105255 +14705,-0.046914763748646,-0.016531575471163,-0.290908545255661,41042,306,-3331,-3392,1.04846024513245 +14707,-0.0419951826334,-0.020703326910734,-0.29628849029541,41042,111,-2948,-1996,1.04870784282684 +14709,-0.032618541270495,-0.025390746071935,-0.304398655891418,41042,-289,-2784,-3534,1.0476655960083 +14711,-0.025903236120939,-0.017967442050576,-0.306594967842102,41042,-234,-3805,-2050,1.04731488227844 +14713,-0.020756611600518,-0.00980138964951,-0.304184824228287,41042,-166,-3942,-3515,1.04446697235107 +14715,-0.02310429699719,0.00794324092567,-0.302131652832031,41042,382,-4909,-2004,1.04249250888824 +14717,-0.023776011541486,0.009114489890635,-0.301785618066788,41042,312,-3746,-3470,1.03989064693451 +14719,-0.019499816000462,0.010130420327187,-0.305746644735336,41042,-133,-3743,-2012,1.03467833995819 +14721,-0.017666656523943,0.015452173538506,-0.308230072259903,41042,44,-4151,-3530,1.03829395771027 +14723,-0.014677999541164,0.018168706446886,-0.308689802885056,41042,-103,-3985,-2016,1.04474294185638 +14725,-0.012670482508838,0.026932623237372,-0.311303645372391,40685,-46,-4590,-3551,1.04890608787537 +14727,-0.007338970433921,0.026915114372969,-0.313479781150818,40685,-371,-3924,-2034,1.04997408390045 +14729,-0.001831999397837,0.032437138259411,-0.315170466899872,40685,-473,-4453,-3582,1.04686665534973 +14731,-0.003477645339444,0.03640291839838,-0.313500016927719,40685,72,-4357,-2020,1.04582619667053 +14733,-0.008758657611907,0.035925269126892,-0.312408298254013,40685,413,-4085,-3534,1.04361057281494 +14735,-0.011997727677226,0.040867377072573,-0.316762775182724,40685,311,-4503,-2027,1.04029190540314 +14737,-0.007763344328851,0.037138782441616,-0.32248592376709,40685,-280,-3888,-3639,1.03791439533234 +14739,-0.007078437134624,0.042769528925419,-0.322370857000351,40685,-37,-4593,-2053,1.04047107696533 +14741,-0.003128179581836,0.040980502963066,-0.317398101091385,40685,-335,-4109,-3565,1.04025363922119 +14743,-0.007846090011299,0.049110740423203,-0.318031400442123,40685,360,-4880,-2009,1.03939461708069 +14745,-0.008998584002256,0.043683752417564,-0.32285663485527,40685,132,-3903,-3616,1.03974008560181 +14747,-0.00656436663121,0.037027169018984,-0.326440751552582,40685,-166,-3664,-2053,1.03339922428131 +14749,-0.004459642805159,0.038322813808918,-0.327669203281403,40685,-165,-4316,-3660,1.02755784988403 +14751,-0.001905624638312,0.041470568627119,-0.330104559659958,40685,-239,-4444,-2066,1.02889847755432 +14753,-0.002352758310735,0.049281749874354,-0.335932582616806,40685,-28,-4979,-3745,1.03017961978912 +14755,0.001963255926967,0.046482879668474,-0.337576329708099,40685,-421,-4110,-2106,1.03392684459686 +14757,0.002552636666223,0.047779724001885,-0.336517006158829,40685,-187,-4516,-3741,1.03646266460419 +14759,0.000514723360538,0.051884982734919,-0.338207364082336,40685,51,-4703,-2158,1.04008805751801 +14761,0.004823234397918,0.04768105968833,-0.342727601528168,40148,-497,-4148,-3864,1.04060339927673 +14763,0.003506400156766,0.044314589351416,-0.343730628490448,40148,-48,-4081,-2191,1.04277992248535 +14765,-0.005411632824689,0.037196636199951,-0.34359684586525,40148,607,-3778,-3869,1.04508948326111 +14767,-0.018758157268167,0.042849700897932,-0.340923279523849,40148,1131,-4722,-2165,1.04892325401306 +14769,-0.015425494872034,0.029344907030463,-0.338823139667511,40148,-107,-3196,-3806,1.04423522949219 +14771,-0.011403146199882,0.022987190634012,-0.340586483478546,40148,-214,-3587,-2156,1.04214155673981 +14773,-0.008342863060534,0.026754315942526,-0.342163920402527,40148,-191,-4397,-3839,1.04375171661377 +14775,-0.008386082947254,0.031006574630737,-0.342833280563354,40148,34,-4470,-2166,1.04030513763428 +14777,-0.010839278809726,0.027536572888494,-0.345174789428711,40148,255,-3900,-3869,1.03460538387299 +14779,-0.012605561874807,0.017220057547093,-0.347401767969132,40148,222,-3238,-2192,1.02854573726654 +14781,-0.013824589550495,0.015271060168743,-0.349245309829712,40148,225,-3812,-3912,1.01994681358337 +14783,-0.012685623019934,0.008413545787334,-0.350089818239212,40148,22,-3361,-2205,1.01486420631409 +14785,-0.015456529334188,0.009780192747712,-0.348687201738358,40148,370,-3958,-3900,1.00735104084015 +14787,-0.018411848694086,0.009169005788863,-0.347485035657883,40148,405,-3819,-2182,1.00566685199738 +14789,-0.015583453699946,0.001314889173955,-0.34883314371109,40148,-29,-3172,-3897,1.00329315662384 +14791,-0.015474203042686,-0.001660713343881,-0.351874530315399,40148,149,-3492,-2208,1.00687563419342 +14793,-0.014063983224332,-0.010331755504012,-0.353149950504303,40148,43,-2927,-3943,1.0173796415329 +14795,-0.0138078648597,-0.013577447272837,-0.353274255990982,40148,119,-3296,-2213,1.02620792388916 +14797,-0.009614829905331,-0.029580159112811,-0.352615833282471,40148,-219,-2081,-4063,1.02922463417053 +14799,-0.017185896635056,-0.031755216419697,-0.355787068605423,39791,730,-3097,-2361,1.02599668502808 +14801,-0.026275785639882,-0.024059003219009,-0.358081340789795,39791,997,-3849,-4132,1.02690434455872 +14803,-0.023769902065396,-0.016522400081158,-0.356824934482574,39791,111,-3998,-2373,1.02454209327698 +14805,-0.013624272309244,-0.012336820363999,-0.357198655605316,39791,-580,-3778,-4127,1.02225148677826 +14807,-0.00693471217528,-0.017256330698729,-0.359242558479309,39791,-426,-3087,-2395,1.02025401592255 +14809,-0.007494156248868,-0.013517974875867,-0.358755320310593,39791,96,-3718,-4151,1.01940071582794 +14811,-0.002373985480517,-0.026619743555784,-0.356351286172867,39791,-378,-2358,-2381,1.01856255531311 +14813,0.000976651790552,-0.035757225006819,-0.353060752153397,39791,-314,-2423,-4089,1.01910662651062 +14815,0.005058342125267,-0.038603372871876,-0.350153416395187,39791,-412,-2902,-2342,1.02652060985565 +14817,0.008084207773209,-0.032932452857494,-0.351023733615875,39791,-410,-3510,-4069,1.02877283096313 +14819,0.007229674141854,-0.023776007816196,-0.353705197572708,39791,-94,-3957,-2371,1.027792096138 +14821,0.007816719822586,-0.023203568533063,-0.355301797389984,39791,-244,-3292,-4124,1.02206838130951 +14823,0.007533193565905,-0.023900713771582,-0.35401850938797,39791,-146,-3237,-2378,1.01473557949066 +14825,0.005047135055065,-0.02815954759717,-0.348267674446106,39791,12,-2856,-4046,1.01289188861847 +14827,-0.002099788049236,-0.025144014507532,-0.344622105360031,39791,478,-3471,-2317,1.01240360736847 +14829,-0.003586845239624,-0.028174066916108,-0.344261139631271,39791,89,-2922,-4002,1.01627480983734 +14831,0.000903867185116,-0.030643623322249,-0.347266346216202,39791,-398,-2983,-2338,1.01651287078857 +14833,0.003093682229519,-0.020608849823475,-0.349655270576477,39791,-275,-3961,-4069,1.01813626289368 +14835,0.0041897832416,-0.018648879602552,-0.350186914205551,39791,-203,-3459,-2493,1.01873731613159 +14849,-0.026746578514576,0.001471563824452,-0.346818387508392,39433,862,-3516,-4211,1.01783406734467 +14851,-0.029342021793127,0.006913346704096,-0.344611376523972,39433,564,-4049,-2504,1.01872503757477 +14853,-0.024097764864564,-0.000783797178883,-0.344249844551086,39433,-28,-2987,-4193,1.02062749862671 +14855,-0.022802099585533,0.007384032942355,-0.344365298748016,39433,202,-4248,-2514,1.01895701885223 +14857,-0.010955858975649,0.004095287527889,-0.34046733379364,39433,-712,-3374,-4160,1.02114760875702 +14859,-0.004835945554078,0.00570157263428,-0.335942029953003,39433,-396,-3753,-2467,1.01696217060089 +14861,-0.004659789148718,0.008827487006783,-0.330684423446655,39433,28,-3903,-4055,1.0121750831604 +14863,-0.012079238891602,0.010829203762114,-0.33113706111908,39433,679,-3854,-2444,1.00762283802032 +14865,-0.016676032915711,0.01013152487576,-0.335015445947647,39433,566,-3654,-4116,1.00644207000732 +14867,-0.014667330309749,0.00646112440154,-0.335298955440521,39433,47,-3386,-2483,1.00745153427124 +14869,-0.005783579312265,0.005902909208089,-0.337738394737244,39433,-572,-3599,-4158,1.00837433338165 +14871,0.003777128411457,-0.001645217649639,-0.338087201118469,39433,-756,-2991,-2512,1.01171207427979 +14873,0.006538740359247,0.001935561653227,-0.335887968540192,39433,-331,-3830,-4128,1.00895512104034 +14875,-0.000871064898092,0.008038515225053,-0.332422614097595,39755,522,-4106,-2464,1.01000893115997 +14877,-0.006561656482518,0.015698663890362,-0.331745505332947,39755,484,-4340,-4087,1.00912618637085 +14879,-0.008713688701391,0.024363204836845,-0.333693742752075,39755,260,-4526,-2481,1.0096492767334 +14881,-0.005017548799515,0.009545551612973,-0.333486407995224,39755,-215,-2628,-4117,1.0063214302063 +14883,-0.005734520033002,0.002599055180326,-0.329855591058731,39755,116,-3096,-2463,1.00532233715057 +14885,-0.011468899436295,-0.004630193114281,-0.329203069210052,39755,571,-2936,-4075,1.00900852680206 +14887,-0.019525231793523,0.004665408283472,-0.33266669511795,39755,844,-4282,-2491,1.017542719841 +14889,-0.010345861315727,0.002222166396678,-0.333957225084305,39755,-503,-3386,-4139,1.02935826778412 +14891,-0.005447957199067,0.001735301571898,-0.332384139299393,39755,-280,-3535,-2498,1.03172433376312 +14893,-0.014109040610492,0.007384080439806,-0.326549112796783,39755,834,-4054,-4060,1.03051221370697 +14895,-0.016186850145459,0.012848217971623,-0.326543599367142,39755,379,-4120,-2465,1.02565431594849 +14897,-0.013420315459371,0.018582407385111,-0.334512442350388,39755,0,-4252,-4162,1.02342522144318 +14899,-0.00676732417196,0.013110094703734,-0.33827131986618,39755,-377,-3347,-2555,1.02541947364807 +14901,-0.006128280423582,0.021128410473466,-0.336142033338547,39755,35,-4468,-4190,1.02887463569641 +14903,-0.003006909275427,0.017364915460348,-0.333577662706375,39755,-178,-3538,-2532,1.02897036075592 +14905,-0.00516719603911,0.025933835655451,-0.334006190299988,39755,232,-4589,-4174,1.02537631988525 +14907,-0.008226089179516,0.025558564811945,-0.333006948232651,39755,340,-3907,-2537,1.02340078353882 +14909,-0.013259190134704,0.022560795769096,-0.333477824926376,39755,582,-3701,-4177,1.01658022403717 +14911,-0.017321448773146,0.023834278807044,-0.336630344390869,39755,550,-4006,-2570,1.00814497470856 +14913,-0.013693084008992,0.022170472890139,-0.334276795387268,39755,-34,-3803,-4195,0.996605813503265 +14915,-0.010622549802065,0.030694745481014,-0.330431580543518,39755,-50,-4631,-2537,0.98643958568573 +14917,-0.01124828401953,0.030918836593628,-0.329436361789703,39755,228,-4098,-4147,0.984043955802918 +14919,-0.012040532194078,0.034023094922304,-0.33250081539154,39755,249,-4303,-2559,0.987554907798767 +14921,-0.006883057765663,0.026267558336258,-0.332997471094132,39755,-250,-3468,-4197,0.9936683177948 +14923,-0.000827932148241,0.026244565844536,-0.335520774126053,39755,-399,-3979,-2589,0.995117127895355 +14925,-0.000885495275725,0.031891815364361,-0.339559555053711,39755,25,-4540,-4284,1.00209546089172 +14927,-0.00321878050454,0.032303705811501,-0.343035489320755,39755,234,-4112,-2650,1.00626587867737 +14929,-0.011873542331159,0.036460153758526,-0.342868030071259,39755,819,-4509,-4333,1.01231515407562 +14931,-0.017527349293232,0.025232205167413,-0.33905765414238,39755,681,-3192,-2634,1.00874757766724 +14933,-0.022132713347674,0.023244876414538,-0.335318386554718,39755,708,-3870,-4254,1.00274384021759 +14935,-0.023391423746944,0.015123705379665,-0.336932688951492,39755,460,-3279,-2628,0.995582461357117 +14937,-0.027999650686979,0.018467912450433,-0.339637070894241,39755,815,-4190,-4314,0.995039224624634 +14939,-0.023432284593582,0.015474693849683,-0.336067020893097,39755,55,-3660,-2632,0.999158263206482 +14941,-0.016895649954677,0.011173856444657,-0.333218574523926,39755,-153,-3532,-4248,0.999472618103027 +14943,-0.018501209095121,0.005961881950498,-0.332451224327087,39755,434,-3370,-2616,1.00286877155304 +14945,-0.025149678811431,-0.002212715568021,-0.331338047981262,39755,925,-3036,-4235,1.00635075569153 +14947,-0.025282554328442,-0.004112449940294,-0.330804258584976,39755,436,-3461,-2561,1.00968611240387 +14949,-0.016996389254928,-0.01412140019238,-0.331541001796722,40470,-266,-2698,-4192,1.00773906707764 +14951,-0.016931559890509,-0.010881005786359,-0.334191530942917,40470,308,-3725,-2590,1.00613272190094 +14953,-0.019519068300724,-0.018584821373224,-0.339484423398972,40470,564,-2774,-4292,1.00414085388184 +14955,-0.026245813816786,-0.014363550581038,-0.342031449079514,40470,937,-3733,-2650,1.0012880563736 +14957,-0.021472258493304,-0.017398741096258,-0.33670774102211,40470,88,-3115,-4265,1.00583469867706 +14959,-0.016333172097802,-0.019189042970538,-0.333480656147003,40470,-43,-3222,-2597,1.00454163551331 +14961,-0.021000932902098,-0.02333920635283,-0.336057066917419,40470,763,-2924,-4264,1.00394117832184 +14963,-0.023567689582706,-0.03312261775136,-0.336444616317749,40470,622,-2435,-2624,1.00140464305878 +14965,-0.018413837999106,-0.033467620611191,-0.335880994796753,40470,20,-3017,-4267,0.998269438743591 +14967,-0.008927834220231,-0.039579249918461,-0.336830109357834,40470,-443,-2586,-2632,0.996554017066956 +14969,-0.006711394991726,-0.035561811178923,-0.3361556828022,40470,38,-3282,-4277,0.997022449970245 +14971,-0.005230815149844,-0.039339121431112,-0.333477169275284,40470,77,-2737,-2615,0.997212290763855 +14973,-0.007007650565356,-0.03102689422667,-0.335306525230408,40470,329,-3649,-4273,1.00277364253998 +14975,-0.003329642117023,-0.023488271981478,-0.334665060043335,40470,-105,-3759,-2629,1.01440930366516 +14977,-0.000346458458807,-0.019183864817023,-0.332376480102539,40470,-111,-3534,-4244,1.01928949356079 +14979,-0.005996447987854,-0.011091844178736,-0.329685121774673,40470,600,-3964,-2600,1.02104890346527 +14981,-0.008853740058839,-0.008736881427467,-0.327183037996292,40470,451,-3551,-4187,1.01674044132233 +14999,0.005608258303255,0.023839266970754,-0.322862774133682,40810,-539,-3159,-2581,1.01092112064362 +15001,0.014125284738839,0.024499841034412,-0.324863702058792,40810,-754,-3982,-4188,1.01113951206207 +15003,0.020671378821135,0.032126780599356,-0.323577553033829,40810,-670,-4561,-2591,1.00909161567688 +15005,0.017432048916817,0.043188437819481,-0.324997067451477,40810,20,-5036,-4194,1.00486958026886 +15007,0.015440751798451,0.03964776173234,-0.323572874069214,40810,5,-3885,-2595,1.00515055656433 +15009,0.019778965041041,0.033984120935202,-0.323491424322128,40810,-574,-3700,-4180,1.00442910194397 +15011,0.020435834303498,0.044414963573217,-0.321834921836853,40810,-267,-4965,-2588,1.00599455833435 +15013,0.022969096899033,0.048960261046887,-0.322033435106277,40810,-507,-4697,-4167,1.00506019592285 +15015,0.024668380618095,0.054056234657765,-0.323209941387177,40810,-415,-4741,-2601,1.01190507411957 +15017,0.02937850728631,0.047367502003908,-0.320987701416016,40810,-782,-3885,-4159,1.01845717430115 +15019,0.028583472594619,0.056217387318611,-0.319785177707672,40810,-309,-5060,-2581,1.02728295326233 +15021,0.03447312489152,0.051580972969532,-0.319163471460342,40810,-974,-4118,-4141,1.03295123577118 +15023,0.041333917528391,0.044008832424879,-0.321383893489838,40810,-1060,-3729,-2596,1.03658866882324 +15025,0.041011031717062,0.044981952756643,-0.322529733181,40810,-657,-4435,-4185,1.04185926914215 +15027,0.042082313448191,0.05137137696147,-0.322684526443481,40810,-679,-4852,-2609,1.043128490448 +15029,0.044219199568033,0.060957297682762,-0.326536893844604,40810,-904,-5335,-4237,1.04304826259613 +15031,0.043982058763504,0.056977994740009,-0.326777398586273,40810,-636,-4216,-2642,1.04231345653534 +15033,0.040996722877026,0.060254573822022,-0.322280347347259,40810,-502,-4893,-4191,1.03635931015015 +15035,0.04371077567339,0.050573017448187,-0.320094853639603,40810,-866,-3740,-2600,1.02890193462372 +15037,0.047841683030129,0.054952923208475,-0.32169982790947,40810,-1136,-4903,-4188,1.01906645298004 +15039,0.053279761224985,0.051103182137013,-0.321878612041473,40810,-1221,-4187,-2617,1.01216423511505 +15041,0.049311194568873,0.051567763090134,-0.321453630924225,40810,-603,-4584,-4190,1.00226151943207 +15043,0.04329701513052,0.050450187176466,-0.318503707647324,40810,-282,-4392,-2597,1.00193905830383 +15045,0.043383304029703,0.039716079831123,-0.314249098300934,40810,-813,-3612,-4108,1.00506460666657 +15047,0.045214746147394,0.037215650081635,-0.315929353237152,40810,-891,-4119,-2582,1.01019513607025 +15049,0.040642697364092,0.031773108989,-0.317112565040588,40810,-439,-3882,-4145,1.01532089710236 +15051,0.031985618174076,0.032979086041451,-0.317101836204529,40810,32,-4336,-2594,1.01858711242676 +15053,0.032879900187254,0.024765918031335,-0.317047536373138,40810,-727,-3585,-4147,1.02238059043884 +15055,0.036744605749846,0.024615712463856,-0.319444179534912,40810,-946,-4129,-2613,1.02159607410431 +15057,0.032542075961828,0.024250755086541,-0.318896383047104,40810,-388,-4153,-4173,1.02410995960236 +15059,0.028422605246306,0.018526406958699,-0.31636455655098,40810,-272,-3653,-2596,1.02207827568054 +15061,0.027416436001659,0.018142137676478,-0.314463168382645,40810,-555,-4067,-4124,1.017702460289 +15063,0.025354186072946,0.012188259512186,-0.31668084859848,40810,-391,-3554,-2601,1.01315701007843 +15065,0.018855573609471,0.016620865091682,-0.319538295269012,40810,-31,-4393,-4187,1.01049733161926 +15067,0.013566077686846,0.007043043617159,-0.319333732128143,40810,-2,-3228,-2623,1.01231026649475 +15069,0.007240704260767,0.00360771920532,-0.316453337669373,40810,149,-3610,-4154,1.01097273826599 +15071,0.006620814092457,-0.001710617914796,-0.312097489833832,40810,-241,-3407,-2576,1.01373744010925 +15073,0.012708200141788,-0.012003248557448,-0.312384992837906,40810,-831,-2855,-4109,1.01178789138794 +15075,0.022028474137187,-0.008772069588304,-0.315853536128998,40810,-1180,-3910,-2604,1.01132833957672 +15077,0.02677252702415,-0.005810167174786,-0.314227908849716,40810,-982,-3901,-4133,1.0097314119339 +15079,0.01930451951921,0.006025709677488,-0.310641229152679,40810,47,-4733,-2571,1.01204776763916 +15081,0.010200437158346,0.00403551524505,-0.309103608131409,40810,256,-3713,-4075,1.01668405532837 +15083,0.003157969564199,0.006853892002255,-0.30994114279747,40810,240,-4100,-2568,1.0151834487915 +15085,0.005555043462664,-0.006666121073067,-0.311598688364029,40810,-502,-2722,-4107,1.01951622962952 +15087,0.004513697698712,-0.010125087574124,-0.309875935316086,40810,-215,-3405,-2570,1.02700734138489 +15089,0.003886193037033,-0.00703455042094,-0.307307422161102,40810,-262,-3895,-4058,1.03844404220581 +15091,0.0111373802647,-0.013456832617521,-0.309459924697876,40810,-910,-3141,-2569,1.04800450801849 +15093,0.015105862170458,-0.012585512362421,-0.313064873218536,40810,-782,-3635,-4128,1.04815173149109 +15095,0.017970656976104,-0.012731701135635,-0.311856240034103,40810,-705,-3593,-2588,1.04629576206207 +15097,0.009501866064966,-0.005181423388422,-0.307285338640213,40810,183,-4222,-4062,1.04144132137299 +15099,0.005423092283309,-0.015737866982818,-0.305486798286438,40631,-37,-2799,-2546,1.04147183895111 +15101,0.000833251804579,-0.018239811062813,-0.308591932058334,40631,39,-3277,-4079,1.03846573829651 +15103,-0.009138912893832,-0.01082693040371,-0.307956516742706,40631,588,-4144,-2565,1.03570020198822 +15105,-0.016901575028896,-0.01365935895592,-0.307659476995468,40631,558,-3318,-4070,1.03060758113861 +15107,-0.018083583563566,-0.022292546927929,-0.310495018959045,40631,90,-2821,-2584,1.03309464454651 +15109,-0.016268882900477,-0.024688821285963,-0.314495205879211,40631,-127,-3157,-4153,1.03612840175629 +15111,-0.015781307592988,-0.006837734021246,-0.316439747810364,40631,-57,-4925,-2628,1.04085421562195 +15113,-0.011554510332644,-0.003277270589024,-0.317433685064316,40631,-368,-3923,-4190,1.0448112487793 +15115,-0.008472522720695,-0.00711573055014,-0.316871494054794,40631,-345,-3362,-2634,1.04063856601715 +15117,-0.015091025270522,-0.007285065483302,-0.313428550958633,40631,459,-3583,-4146,1.03901076316834 +15119,-0.01912471652031,-0.006888832896948,-0.312167674303055,40631,320,-3661,-2605,1.03710532188416 +15121,-0.024661935865879,0.001434174482711,-0.31106698513031,40631,545,-4332,-4121,1.0343724489212 +15123,-0.02317038923502,-0.002791901351884,-0.310654312372208,40631,-9,-3386,-2596,1.03198707103729 +15125,-0.018222101032734,-0.000169761144207,-0.309456557035446,40631,-298,-3907,-4104,1.03373980522156 +15127,-0.009656878188252,-0.011321638710797,-0.309972316026688,40631,-704,-2766,-2594,1.03666126728058 +15129,-0.013470900245011,-0.009460660628974,-0.316525876522064,40631,258,-3694,-4190,1.04000329971313 +15131,-0.021127535030246,-0.015413030982018,-0.322584718465805,40631,626,-3074,-2684,1.04308760166168 +15147,-0.009655931964517,0.000389781838749,-0.311447620391846,40399,-273,-3673,-3488,1.02768206596375 +15149,-0.011079644784331,0.00279657356441,-0.30757799744606,40399,99,-3919,-4992,1.03106141090393 +15151,-0.014922525733709,0.003174220910296,-0.305793106555939,40399,301,-3775,-3499,1.03541803359985 +15153,-0.021527722477913,0.0073211658746,-0.305952131748199,40399,638,-4120,-5024,1.03849351406097 +15155,-0.023802701383829,0.010252518579364,-0.303640216588974,40399,325,-4063,-3535,1.04064190387726 +15157,-0.025479391217232,0.025670746341348,-0.297002226114273,40399,346,-5230,-4968,1.04032850265503 +15159,-0.023840041831136,0.02661494538188,-0.291728585958481,40399,54,-4166,-3501,1.03995048999786 +15161,-0.016419036313891,0.028560535982251,-0.290508925914764,40399,-450,-4322,-4939,1.03672432899475 +15163,-0.010311878286302,0.038016323000193,-0.289790540933609,40399,-455,-4952,-3536,1.03640925884247 +15165,-0.006244129035622,0.041202314198017,-0.286136209964752,40399,-377,-4634,-4935,1.03320825099945 +15167,-0.009100954979658,0.047818429768086,-0.281319171190262,40399,167,-4908,-3524,1.03506994247437 +15169,-0.013180904090405,0.039378557354212,-0.277767807245255,40399,321,-3786,-4883,1.03467321395874 +15171,-0.020460980013013,0.048254314810038,-0.274728000164032,40399,649,-5094,-3525,1.0292409658432 +15173,-0.021503325551748,0.052901327610016,-0.269912362098694,40399,251,-4957,-4836,1.02422118186951 +15175,-0.02541602961719,0.062517754733563,-0.268247455358505,40309,487,-5375,-3524,1.01759088039398 +15177,-0.022435560822487,0.058652177453041,-0.266259342432022,40309,-19,-4459,-4837,1.02032208442688 +15179,-0.013212747871876,0.049994733184576,-0.266337424516678,40309,-622,-3910,-3555,1.01883339881897 +15181,-0.009371035732329,0.053663451224566,-0.264039307832718,40309,-279,-4945,-4854,1.01987314224243 +15183,-0.00768401985988,0.053579770028591,-0.257284253835678,40309,-159,-4599,-3536,1.0210132598877 +15185,-0.010367883369327,0.050542376935482,-0.252881437540054,40309,207,-4439,-4765,1.02483403682709 +15187,-0.009505152702332,0.036694392561913,-0.253155738115311,40309,-70,-3392,-3549,1.02693951129913 +15189,-0.011853367090225,0.037658430635929,-0.252493351697922,40309,203,-4535,-4802,1.03224802017212 +15191,-0.010728013701737,0.039113882929087,-0.249284222722054,40309,-69,-4539,-3564,1.03435504436493 +15193,-0.007252358365804,0.042724829167128,-0.245452105998993,40309,-292,-4824,-4760,1.02770137786865 +15195,-0.008193156681955,0.042334020137787,-0.243286058306694,40309,41,-4472,-3563,1.02553188800812 +15197,-0.004916791338474,0.031476985663176,-0.241225123405457,40309,-323,-3622,-4750,1.02063047885895 +15199,-0.001443751621991,0.027439743280411,-0.238826021552086,40309,-373,-4011,-3572,1.01908302307129 +15201,0.008432859554887,0.012282205745578,-0.23639802634716,40309,-1012,-3008,-4733,1.02051067352295 +15203,0.014481225050986,0.010033490136266,-0.233466982841492,40309,-794,-3894,-3574,1.02649080753326 +15205,0.025491364300251,-0.009841805323958,-0.229167819023132,40309,-1379,-2309,-4686,1.03112041950226 +15207,0.026175852864981,-0.017548868432641,-0.229341387748718,40309,-593,-3101,-3584,1.03290796279907 +15209,0.023063497617841,-0.027668528258801,-0.227256432175636,40309,-332,-2705,-4701,1.03411519527435 +15211,0.017157731577754,-0.028011124581099,-0.220040202140808,40309,-4,-3464,-3557,1.03027832508087 +15213,0.014585164375603,-0.02950194850564,-0.214588686823845,40148,-245,-3278,-4588,1.02776920795441 +15215,0.010233134962618,-0.03211323171854,-0.210480943322182,40148,-24,-3226,-3527,1.01961505413055 +15217,0.006066391244531,-0.026282912120223,-0.210398718714714,40148,-4,-3845,-4574,1.00718569755554 +15219,0.00564955547452,-0.023962557315827,-0.212937518954277,40148,-246,-3683,-3578,1.00544798374176 +15221,0.006085715722293,-0.016802506521344,-0.211610272526741,40148,-337,-4083,-4623,1.00645899772644 +15223,0.01325274631381,-0.024622926488519,-0.206176713109016,40148,-904,-2937,-3567,1.01000845432282 +15225,0.008524247445166,-0.023453965783119,-0.20340022444725,40148,-11,-3533,-4560,1.01758694648743 +15227,0.005741153843701,-0.026895884424448,-0.200409457087517,40148,-90,-3206,-3561,1.03032326698303 +15229,0.009410727769136,-0.032060135155916,-0.196245491504669,40148,-634,-2920,-4509,1.03547894954681 +15231,0.010906900279224,-0.033921159803867,-0.191427186131477,40148,-477,-3200,-3531,1.03890597820282 +15233,0.010230307467282,-0.033949010074139,-0.189607113599777,40148,-348,-3240,-4462,1.03528583049774 +15235,0.006552891340107,-0.024337807670236,-0.190366521477699,40148,-52,-4141,-3555,1.02698993682861 +15237,0.006080644205213,-0.024529712274671,-0.190958008170128,40148,-310,-3368,-4510,1.01879370212555 +15239,0.004955139476806,-0.018202215433121,-0.18872657418251,40148,-220,-3981,-3576,1.01394331455231 +15241,0.009255087934434,-0.023989981040359,-0.185073360800743,40148,-711,-2960,-4472,1.01340138912201 +15243,0.011050869710744,-0.028252277523279,-0.182992547750473,40148,-525,-3064,-3567,1.00929880142212 +15245,0.007425466086715,-0.027353726327419,-0.180101737380028,40148,-113,-3371,-4443,1.01255631446838 +15247,0.00258778850548,-0.030827965587378,-0.176640376448631,40148,64,-3068,-3553,1.01685774326324 +15249,-0.000918173405807,-0.025863565504551,-0.175069704651833,40148,19,-3658,-4413,1.02301490306854 +15251,-6.30913127679378E-05,-0.026826331391931,-0.170061752200127,39952,-306,-3288,-3537,1.02623236179352 +15253,-0.002120219869539,-0.020279942080379,-0.16799184679985,39952,-54,-3840,-4358,1.02345776557922 +15255,-0.008786632679403,-0.015753481537104,-0.170119717717171,39952,359,-3824,-3565,1.02035057544708 +15257,-0.012410286813974,-0.004146272782236,-0.169893488287926,39952,229,-4452,-4409,1.01397550106049 +15259,0.002567883115262,-0.005945465993136,-0.167579382658005,39952,-1348,-3503,-3575,1.01497781276703 +15261,0.018614675849676,-0.007916552014649,-0.167278245091438,39952,-1690,-3412,-4406,1.01232743263245 +15263,0.023881724104285,0.003171474440023,-0.162380248308182,39952,-967,-4548,-3567,1.01214599609375 +15265,0.026723820716143,0.00383504666388,-0.15808130800724,39952,-894,-3804,-4325,1.0111825466156 +15267,0.025855178013444,0.003680807771161,-0.157393783330917,39952,-570,-3749,-3559,1.02365601062775 +15269,0.02484642341733,-0.00782954134047,-0.157623305916786,39952,-616,-2740,-4346,1.03288173675537 +15271,0.013874707743526,-0.000979386502877,-0.153959780931473,39952,309,-4178,-3562,1.04044449329376 +15273,0.010869011282921,0.002748792525381,-0.152182936668396,39952,-267,-3998,-4307,1.04139292240143 +15275,0.007706944365054,0.014141590334475,-0.151369944214821,39952,-171,-4719,-3569,1.04139745235443 +15277,0.008787179365754,0.025235233828426,-0.145629122853279,39952,-539,-4894,-4255,1.0420857667923 +15279,0.018741544336081,0.03033815510571,-0.139842689037323,39952,-1280,-4509,-3514,1.03954017162323 +15281,0.02503383345902,0.029367942363024,-0.138587728142738,39952,-1190,-4109,-4196,1.03775787353516 +15283,0.028689498081803,0.020923886448145,-0.141412049531937,39952,-989,-3415,-3548,1.03120088577271 +15285,0.024156760424376,0.022803261876106,-0.147156804800034,39952,-411,-4219,-4320,1.02425277233124 +15287,0.018279710784555,0.018889933824539,-0.148613080382347,39952,-174,-3718,-3622,1.01780939102173 +15289,0.006655066739768,0.030301246792078,-0.145474404096603,39952,377,-5026,-4325,1.01445209980011 +15291,0.002885031979531,0.024038102477789,-0.142109990119934,39952,-111,-3634,-3602,1.01080858707428 +15293,0.006055863574147,0.019713059067726,-0.141335755586624,39952,-681,-3728,-4300,1.00441431999207 +15295,0.011875613592565,0.017231466248632,-0.139036893844605,39952,-934,-3812,-3604,1.00613403320313 +15297,0.015460484661162,0.013031049631536,-0.133941069245338,39952,-869,-3636,-4236,1.00654053688049 +15299,0.013426938094199,0.012804477475584,-0.128843054175377,39952,-404,-3913,-3556,1.00850880146027 +15301,0.007007264066488,0.008080337196589,-0.128381311893463,39952,-16,-3525,-4192,1.00993812084198 +15303,-0.000407627871027,0.01710538752377,-0.127609327435494,39952,173,-4638,-3569,1.01530647277832 +15305,-0.001904087141156,0.017230823636055,-0.124229125678539,39952,-231,-4024,-4165,1.02024221420288 +15307,-0.001677463995293,0.017052408307791,-0.124467067420483,39952,-357,-3984,-3568,1.02634012699127 +15309,0.002606543479487,0.003443546127528,-0.125372111797333,39952,-723,-2818,-4199,1.0339503288269 +15311,-0.002689713845029,0.008289070799947,-0.124172732234001,39952,48,-4217,-3587,1.03174090385437 +15313,-0.009266605600715,0.007289380766451,-0.121906913816929,39952,236,-3785,-4179,1.03194200992584 +15315,-0.011384869925678,-0.006912117823958,-0.122611291706562,39952,-55,-2635,-3597,1.02485501766205 +15317,-0.022299306467176,-0.003198304912075,-0.123150311410427,39952,759,-3951,-4214,1.02264952659607 +15319,-0.030377026647329,-0.002752238651738,-0.122149236500263,39952,649,-3740,-3614,1.02419555187225 +15321,-0.03183326497674,0.00128446018789,-0.122339360415936,39952,251,-4039,-4225,1.02268946170807 +15323,-0.020581468939781,-0.01257935538888,-0.120547153055668,39952,-865,-2571,-3624,1.01729333400726 +15325,-0.022268306463957,-0.009685332886875,-0.119374111294746,39845,127,-3771,-4210,1.01880371570587 +15327,-0.024068562313914,-0.013963663950563,-0.117368556559086,39845,127,-3229,-3622,1.0229868888855 +15329,-0.02669544890523,-0.012747718952596,-0.115079522132874,39845,276,-3586,-4179,1.02010297775269 +15331,-0.028940167278051,-0.019039072096348,-0.11505302041769,39845,239,-3001,-3625,1.01663112640381 +15333,-0.029985923320055,-0.025747328996658,-0.111870422959328,39845,220,-2805,-4160,1.00701224803925 +15335,-0.031961970031262,-0.021211955696344,-0.104973427951336,39845,273,-3731,-3575,0.999038100242615 +15337,-0.033414710313082,-0.024973262101412,-0.101082488894463,39845,310,-3017,-4051,0.997162222862244 +15339,-0.032184679061174,-0.022435078397393,-0.097680576145649,39845,58,-3556,-3542,0.998680293560028 +15341,-0.025191742926836,-0.028897542506456,-0.096343621611595,39845,-411,-2748,-4012,1.0015105009079 +15343,-0.024326721206308,-0.026685904711485,-0.099790960550308,39845,-19,-3456,-3572,0.999701023101806 +15345,-0.024966213852167,-0.035912647843361,-0.099512882530689,39845,141,-2424,-4065,1.004035115242 +15347,-0.034298151731491,-0.033707231283188,-0.099704183638096,39845,862,-3337,-3588,1.01062560081482 +15349,-0.035183943808079,-0.028264116495848,-0.097962312400341,39845,336,-3571,-4064,1.01623260974884 +15351,-0.026159295812249,-0.03426968306303,-0.092626824975014,39845,-555,-2724,-3556,1.00879156589508 +15353,-0.031594756990671,-0.031943302601576,-0.090709544718266,39845,615,-3272,-3994,1.00068068504334 +15355,-0.03657166287303,-0.028529055416584,-0.09010424464941,39845,608,-3463,-3554,0.99843156337738 +15357,-0.03162445127964,-0.017465876415372,-0.088773526251316,39845,-120,-4114,-3987,0.992662250995636 +15359,-0.021224971860647,-0.022291729226708,-0.088376425206661,39845,-702,-2950,-3557,0.994875252246857 +15361,-0.021625943481922,-0.01790002733469,-0.090785905718803,39845,107,-3616,-4026,0.992707788944244 +15381,0.017611086368561,0.000758736860007,-0.085615962743759,39845,-1020,-2946,-4038,1.02528285980225 +15383,0.027255510911346,-0.009707298129797,-0.086094796657562,39845,-1367,-2681,-3629,1.01762616634369 +15385,0.029025478288531,-0.001849839230999,-0.078082084655762,39845,-897,-4087,-3963,1.01423799991608 +15387,0.024226635694504,0.002826758660376,-0.071413531899452,39845,-305,-3940,-3541,1.00506138801575 +15389,0.016069263219833,0.012268864549697,-0.071443378925324,39845,14,-4421,-3898,0.998784244060516 +15391,0.0168138705194,0.010846488177776,-0.0733338072896,39845,-605,-3619,-3567,0.992275834083557 +15393,0.024409398436546,0.015102439559996,-0.073812447488308,39845,-1259,-4098,-3938,0.989860832691193 +15395,0.032713800668717,0.015997875481844,-0.069505162537098,39845,-1388,-3861,-3553,0.995293080806732 +15397,0.029491046443582,0.03057068772614,-0.073672503232956,39845,-571,-5097,-3949,0.999747633934021 +15399,0.022861625999212,0.029890166595578,-0.078363835811615,39845,-191,-3957,-3627,1.00698816776276 +15401,0.027562538161874,0.019565446302295,-0.082175776362419,39845,-1125,-3144,-4062,1.00869941711426 +15403,0.029936023056507,0.017674488946796,-0.078900285065174,39845,-951,-3700,-3644,1.01539266109467 +15405,0.030138991773129,0.015583652071655,-0.070400647819042,39845,-878,-3675,-3937,1.02040529251099 +15407,0.025981044396758,0.021477604284883,-0.068737238645554,39845,-445,-4316,-3586,1.02538132667542 +15409,0.02214545942843,0.01114543620497,-0.068550564348698,39845,-488,-3018,-3927,1.02516317367554 +15411,0.018530374392867,0.011769160628319,-0.066411592066288,39845,-393,-3802,-3582,1.02071416378021 +15413,0.020077111199498,0.00069868832361,-0.064777530729771,39845,-853,-2802,-3894,1.00870203971863 +15415,0.014101387932897,0.004784226417542,-0.063619554042816,39845,-176,-3948,-3574,0.99559223651886 +15417,0.008814847096801,0.015859732404351,-0.061486784368754,39845,-184,-4634,-3866,0.993710160255432 +15419,0.007929360494018,0.017564687877894,-0.061354041099548,39845,-461,-3966,-3569,0.99303126335144 +15421,0.010675856843591,0.020714862272143,-0.063468031585217,39845,-792,-4147,-3900,0.994257211685181 +15423,0.009651716798544,0.019861636683345,-0.063092067837715,39845,-484,-3822,-3592,0.998875856399536 +15425,0.000397656025598,0.027101518586278,-0.06264054775238,39845,226,-4538,-3901,1.00532627105713 +15427,-0.002315870253369,0.012935165315867,-0.064290463924408,39845,-195,-2775,-3611,1.01279509067535 +15429,-0.003629058133811,0.012198940850794,-0.063950017094612,39845,-280,-3724,-3927,1.01236498355865 +15431,-0.00071119167842,0.007288068532944,-0.061290249228478,39845,-624,-3357,-3601,1.01099026203156 +15433,-0.009886185638607,0.010932992212474,-0.058277349919081,39845,376,-4026,-3871,1.00834536552429 +15435,-0.022285087034106,0.001670811907388,-0.05543664842844,39845,781,-2965,-3571,1.00848376750946 +15437,-0.024096380919218,-0.018021924421191,-0.054467931389809,39845,85,-1888,-3836,1.00543141365051 +15439,-0.028675679117441,-0.018669534474611,-0.053283479064703,39845,319,-3279,-3566,1.0008898973465 +15441,-0.037603639066219,-0.019544634968042,-0.050708055496216,39845,824,-3205,-3800,0.99695736169815 +15443,-0.046163689345121,-0.012198118492961,-0.047028876841068,39845,868,-3934,-3532,0.998493254184723 +15445,-0.040712241083384,-0.019963411614299,-0.045600771903992,39845,-133,-2681,-3749,0.996886134147644 +15447,-0.036050915718079,-0.00939076486975,-0.049514871090651,39845,-207,-4193,-3557,0.997277975082397 +15449,-0.033783685415983,-0.007752357516438,-0.049875356256962,39845,5,-3530,-3808,0.996155142784119 +15451,-0.036771941930056,-0.00878928322345,-0.049061760306358,39845,364,-3360,-3562,0.998032867908478 +15453,-0.039550662040711,-0.009753664024174,-0.048547960817814,39845,470,-3302,-3800,1.00746703147888 +15455,-0.035697132349014,-0.017090806737542,-0.047989193350077,39845,-124,-2778,-3563,1.01152396202087 +15457,-0.033316895365715,-0.014583131298423,-0.047599017620087,39845,8,-3463,-3798,1.01023507118225 +15459,-0.030213272199035,-0.024443106725812,-0.046321276575327,39845,-137,-2479,-3560,1.0090160369873 +15461,-0.025392755866051,-0.026049328967929,-0.04254624247551,39845,-289,-2971,-3746,1.00462865829468 +15463,-0.017577657476068,-0.035790361464024,-0.040410201996565,39845,-648,-2308,-3527,1.00030148029327 +15465,-0.024466577917338,-0.019655853509903,-0.037964906543493,39845,536,-4335,-3699,0.998700976371765 +15467,-0.021955350413919,-0.007983616553247,-0.031947266310454,39845,-199,-4227,-3475,0.996867120265961 +15469,-0.02116153948009,-0.004893198609352,-0.032058384269476,39845,-60,-3636,-3636,0.991415619850159 +15471,-0.016370883211494,-0.01022098120302,-0.031585648655892,39845,-437,-2971,-3479,0.991749823093414 +15473,-0.014113469980657,-0.010509269312024,-0.030770367011428,39845,-266,-3293,-3626,0.996325254440308 +15475,-0.007128045894206,-0.003206908004358,-0.033855024725199,39845,-723,-3968,-3500,1.00179350376129 +15477,0.00562547147274,-0.001484028063715,-0.034386344254017,39845,-1335,-3576,-3675,1.00351083278656 +15479,0.017588645219803,0.000434042449342,-0.031934920698404,39845,-1439,-3629,-3492,1.00077474117279 +15481,0.026920476928353,-0.007080489769578,-0.031234003603458,39845,-1454,-2824,-3643,0.995215356349945 +15483,0.033751204609871,-0.0043612010777,-0.034070167690516,39845,-1319,-3612,-3513,0.988211274147034 +15485,0.034708291292191,-0.002669193316251,-0.032648336142302,39845,-1009,-3555,-3666,0.991379737854004 +15487,0.03047308139503,-0.002703772159293,-0.032393839210272,39845,-501,-3435,-3507,0.993127465248108 +15489,0.024483125656843,0.00108478940092,-0.029851663857699,39845,-371,-3769,-3638,0.997254729270935 +15491,0.022726960480213,-0.002838864922524,-0.02925319224596,39845,-586,-3154,-3491,0.997958123683929 +15493,0.023416263982654,0.007180333137512,-0.030367834493518,39845,-849,-4314,-3650,1.0048189163208 +15495,0.025546759366989,0.015374491922557,-0.026480589061976,39845,-922,-4285,-3477,1.01333606243134 +15497,0.024766782298684,0.022397633641958,-0.025359472259879,39845,-778,-4340,-3596,1.01223313808441 +15499,0.028451403602958,0.013154077343643,-0.024552678689361,39845,-1092,-3010,-3468,1.005166888237 +15501,0.03078848682344,0.012431988492608,-0.024859892204404,39845,-1113,-3616,-3595,0.996610343456268 +15503,0.033265601843596,0.009065393358469,-0.025217702612281,39845,-1094,-3373,-3478,0.994065225124359 +15505,0.036039713770151,0.000827065669,-0.025864301249385,39845,-1244,-2875,-3611,0.989494681358337 +15507,0.036149904131889,-5.64172405574936E-05,-0.024933503940702,39845,-987,-3413,-3480,0.992569923400879 +15509,0.031510550528765,-0.006115921773016,-0.022034140303731,39845,-649,-2919,-3570,0.995099544525146 +15511,0.021746296435595,0.004718060605228,-0.018217535689473,39845,-90,-4313,-3438,0.997182428836822 +15513,0.019592622295022,0.007285394705832,-0.015693619847298,39952,-641,-3764,-3499,1.00307273864746 +15515,0.013551115058363,0.019038002938032,-0.016924615949392,39952,-250,-4584,-3432,1.01616787910461 +15517,0.013692257925868,0.020666981115937,-0.01815558411181,39952,-733,-3918,-3532,1.0218448638916 +15519,0.009474856778979,0.024323789402843,-0.02100170776248,39952,-332,-4087,-3464,1.02160274982452 +15521,0.009247260168195,0.027047410607338,-0.02283032424748,39952,-658,-4107,-3590,1.02064597606659 +15523,0.0102195776999,0.023700131103397,-0.021256951615214,39952,-725,-3585,-3470,1.0203937292099 +15525,0.007180105894804,0.019474504515529,-0.018015885725617,39952,-435,-3494,-3537,1.01889622211456 +15527,0.003751897485927,0.003790512681007,-0.014534197747707,39952,-328,-2421,-3427,1.0143119096756 +15529,-0.004197142552584,0.005251397844404,-0.014737308956683,39952,98,-3672,-3502,1.00810790061951 +15531,-0.004070790484548,0.000381126796128,-0.017733950167894,39952,-474,-3146,-3451,1.00477206707001 +15533,-0.012429173104465,0.008058461360633,-0.019508602097631,39952,271,-4154,-3561,1.0003228187561 +15535,-0.019360311329365,0.009001940488815,-0.015278066508472,39952,252,-3684,-3438,0.995790958404541 +15537,-0.027095073834062,0.018441077321768,-0.012508911080659,39952,465,-4449,-3482,0.990715146064758 +15539,-0.033182967454195,0.026022654026747,-0.012210137210786,39952,397,-4408,-3420,0.993657946586609 +15541,-0.032951399683952,0.018064005300403,-0.011068894527853,39952,0,-3206,-3467,0.996282696723938 +15543,-0.034011173993349,0.010772830806673,-0.006685621105134,39952,60,-3128,-3384,1.00138127803803 +15545,-0.036691512912512,-0.000650730798952,-0.004762346390635,39952,289,-2656,-3394,1.00443994998932 +15547,-0.041652746498585,0.002878018422052,-0.007035362068564,39952,463,-3786,-3387,1.00821149349213 +15549,-0.039192419499159,-0.00228381017223,-0.008125500753522,39952,-24,-3073,-3435,1.01011824607849 +15551,-0.043687887489796,0.003062887582928,-0.01193271856755,39952,474,-3915,-3423,1.01484715938568 +15553,-0.050649348646402,0.001494509051554,-0.011192065663636,39952,851,-3382,-3473,1.0238139629364 +15555,-0.054058499634266,-0.00629259692505,-0.009312788024545,39952,565,-2835,-3407,1.02018845081329 +15557,-0.056768115609884,-0.004946804139763,-0.00871745031327,39952,665,-3480,-3446,1.01483905315399 +15559,-0.056325860321522,-0.005815053358674,-0.009521804749966,39952,344,-3331,-3410,1.00996911525726 +15561,-0.057899434119463,-0.003617753274739,-0.010439351201058,39952,624,-3555,-3469,1.01011610031128 +15563,-0.058055624365807,-0.008076090365648,-0.00707132415846,39952,435,-3034,-3395,1.01140427589417 +15565,-0.059586554765701,0.003747676964849,-0.00289081200026,39952,681,-4350,-3381,1.0139182806015 +15567,-0.052114617079496,-0.000154797991854,-0.001005565980449,39952,-170,-3182,-3354,1.01455938816071 +15569,-0.052159685641527,-0.000824384565931,-0.002006619004533,39952,490,-3377,-3372,1.01038944721222 +15571,-0.052800122648478,-0.000288762588752,-0.002659966936335,39952,444,-3492,-3366,1.01159381866455 +15573,-0.049738969653845,-0.001620858442038,-0.005439142230898,39952,244,-3311,-3413,1.01559245586395 +15575,-0.034999180585146,-0.005078749731183,-0.006423634011298,39952,-890,-3130,-3394,1.01885223388672 +15577,-0.023994386196137,-0.014788733795285,-0.005181607790291,39952,-737,-2491,-3411,1.01595425605774 +15579,-0.021939929574728,-0.012307384982705,-0.003442168235779,39952,-160,-3440,-3374,1.00967335700989 +15581,-0.024699533358216,-0.012563718482852,-0.002929205074906,39952,264,-3199,-3385,1.00966680049896 +15583,-0.024747146293521,-0.005191952455789,-0.004337817430496,39952,38,-3882,-3381,1.01105201244354 +15585,-0.016907220706344,0.000914277974516,-0.002245273673907,39952,-613,-3869,-3378,1.01467716693878 +15587,-0.008017096668482,0.006932764314115,-0.00400571199134,39952,-836,-3955,-3380,1.0140415430069 +15589,-0.005701677873731,0.007031271699816,-0.001221392769367,39952,-396,-3538,-3367,1.01412224769592 +15591,-0.001616671099328,-0.007275575771928,0.002384956460446,39952,-584,-2295,-3336,1.0141863822937 +15593,0.012833339162171,-0.022238375619054,-0.002356777666137,39952,-1150,-2443,-3369,1.01922738552094 +15611,0.02860807813704,0.001046400051564,-0.005837605334818,39952,-1134,-3310,-3422,0.999146401882172 +15613,0.029795460402966,0.015514346770942,-0.005979694891721,39952,-912,-4629,-3396,0.999857902526856 +15615,0.029795460402966,0.015514346770942,-0.005979694891721,39952,-912,-4629,-3396,0.999857902526856 +15617,0.035818465054035,0.001943684415892,-0.002584273926914,39952,-759,-3047,-3373,0.997220575809479 +15619,0.035734456032515,0.001929079880938,-0.001458226353861,39952,-1011,-3383,-3373,1.00338542461395 +15621,0.037786275148392,0.012597573921084,-0.003678370034322,39952,-1129,-4308,-3381,1.01256394386292 +15623,0.039625331759453,0.019886996597052,-0.012425160035491,39952,-1229,-4199,-3504,1.02191948890686 +15625,0.039625331759453,0.019886996597052,-0.012425160035491,39952,-1229,-4199,-3504,1.02191948890686 +15627,0.032709062099457,0.011845110915601,-0.006379477214068,39952,-699,-3570,-3434,1.01893186569214 +15629,0.033612556755543,0.013015751726925,-0.006173143163323,39952,-1029,-3640,-3402,1.01768898963928 +15631,0.033401057124138,0.02551906555891,-0.008846307173371,39952,-1037,-4679,-3465,1.01804685592651 +15633,0.034960344433785,0.032507907599211,-0.007390382234007,39952,-1116,-4345,-3413,1.02043735980988 +15635,0.034960344433785,0.032507907599211,-0.007390382234007,39952,-1116,-4345,-3413,1.02043735980988 +15637,0.024889165535569,0.041404526680708,-0.004359819926322,39952,-361,-4328,-3393,1.01646435260773 +15639,0.017552722245455,0.035586107522249,-0.003800431964919,39952,-279,-3543,-3409,1.00937044620514 +15641,0.003362808376551,0.043844770640135,-0.001358349691145,39952,436,-4623,-3373,1.00721025466919 +15643,-0.005492667667568,0.046063225716353,-0.002848748117685,39952,197,-4297,-3399,1.00579106807709 +15645,-0.008837594650686,0.049148991703987,-0.006512686610222,39952,-164,-4344,-3410,1.00164914131165 +15647,-0.004238876048476,0.038228023797274,-0.00484750745818,39952,-800,-3255,-3423,0.994631767272949 +15649,-0.008860720321536,0.038689326494932,-0.006733718328178,39952,-74,-4020,-3412,0.987912356853485 +15651,-0.019209092482925,0.048132535070181,-0.007259753998369,39952,509,-4896,-3453,0.990103483200073 +15653,-0.024588372558355,0.04747212305665,-0.009863602928817,39952,209,-4085,-3435,0.9938645362854 +15655,-0.027131173759699,0.043640200048685,-0.012122615240514,39952,88,-3896,-3512,0.997271180152893 +15657,-0.026032401248813,0.03939076140523,-0.013363012112677,39952,-226,-3731,-3462,0.995257377624512 +15659,-0.02833759970963,0.041925452649593,-0.013628122396767,39952,101,-4341,-3532,0.998343825340271 +15661,-0.030242854729295,0.032314755022526,-0.010660778731108,39952,58,-3262,-3446,1.00360667705536 +15663,-0.038173217326403,0.028829509392381,-0.009187989868224,39952,678,-3700,-3482,1.00201117992401 +15665,-0.043707434087992,0.022598644718528,-0.010948047041893,39952,526,-3375,-3450,0.999495148658752 +15667,-0.043691702187061,0.017354378476739,-0.011953420937061,39952,211,-3400,-3517,0.993397235870361 +15669,-0.048750542104244,0.012548347935081,-0.011130972765386,39952,580,-3338,-3453,0.989991068840027 +15671,-0.05227167531848,-0.002256567589939,-0.010860337875784,39952,613,-2400,-3506,0.994539856910706 +15673,-0.055969092994928,-0.002108316635713,-0.010600758716464,39952,606,-3479,-3452,0.996301889419556 +15675,-0.05387531593442,-0.008698482997715,-0.00749259442091,39952,255,-2879,-3468,0.999634742736816 +15677,-0.057912204414606,-0.000581871718168,-0.00514311902225,39952,678,-4066,-3416,1.0056483745575 +15679,-0.050961200147867,-0.009378044866025,-0.003499320708215,39952,-123,-2703,-3422,1.01298117637634 +15681,-0.048016857355833,-0.011890265159309,-0.004589674063027,39952,54,-3136,-3413,1.01416921615601 +15683,-0.046613845974207,-0.013604887761176,-0.002728062681854,39952,227,-3128,-3414,1.01289618015289 +15685,-0.049787648022175,-0.014371856115759,0.001030703424476,39952,535,-3215,-3375,1.01069796085358 +15687,-0.047499347478151,-0.020939035341144,0.000807816511951,39952,201,-2645,-3373,1.01066648960114 +15689,-0.044924877583981,-0.029882268980146,0.002826769603416,39952,72,-2393,-3363,1.01229727268219 +15691,-0.042117793112993,-0.026700222864747,0.002753958106041,39952,102,-3234,-3350,1.01180374622345 +15693,-0.040369037538767,-0.024230487644672,0.003042741911486,39952,83,-3275,-3362,1.01165437698364 +15695,-0.038652196526528,-0.016759533435106,0.003442446002737,39952,141,-3684,-3342,1.00699853897095 +15697,-0.031321186572313,-0.02318855188787,0.005169160664082,39952,-32767,-2639,-3347,1.00473320484161 +15699,-0.026803521439433,-0.034308113157749,0.008035504259169,39952,-30690,-2049,-3287,1.00042021274567 +15701,-0.022649442777038,-0.042986012995243,0.011452121660113,39952,-30916,-2173,-3302,1.00105822086334 +15703,-0.014728023670614,-0.051978383213282,0.012385072186589,39952,-31432,-1896,-3234,0.999638378620148 +15705,-0.010286369360983,-0.050693284720183,0.010483995079994,39952,-31412,-2747,-3307,1.00349450111389 +15707,-0.016357839107514,-0.05523643642664,0.005869676824659,39952,-30699,-2132,-3310,1.00958907604218 +15709,-0.041442204266787,-0.049495667219162,-7.98421751824208E-05,39952,-29147,-3053,-3379,1.01546239852905 +15711,-0.076790697872639,-0.050341334193945,-0.010329079814255,39952,-27888,-2440,-3501,1.01853430271149 +15713,-0.127142608165741,-0.042723808437586,-0.021017847582698,39952,-26373,-3256,-3525,1.01458752155304 +15715,-0.193440154194832,-0.037111401557922,-0.027667043730617,39952,-24013,-3092,-3709,1.00865280628204 +15717,-0.267435103654861,-0.038575313985348,-0.033866301178932,39952,-22878,-2641,-3619,1.00074291229248 +15719,-0.352131426334381,-0.039268255233765,-0.043822158128023,39952,-20299,-2584,-3906,0.989528119564056 +15721,-0.450713276863098,-0.037863895297051,-0.050812002271414,39952,-18626,-2833,-3743,0.982668161392212 +15723,-0.560275554656982,-0.033137179911137,-0.054341714829207,39952,-15240,-3060,-4039,0.979021966457367 +15725,-0.681648254394531,-0.035187244415283,-0.056677952408791,39952,-13723,-2604,-3793,0.979770481586456 +15727,-0.811597049236298,-0.02643739618361,-0.058137308806181,39952,-9693,-3449,-4093,0.982227087020874 +15729,-0.946535587310791,-0.011564737185836,-0.058124706149101,39952,-8877,-4140,-3813,0.978810369968414 +15731,-1.07989358901978,-0.011182497255504,-0.06021735444665,39952,-4950,-3082,-4128,0.973836600780487 +15733,-1.21839880943298,-0.012403979897499,-0.059833616018295,39952,-4520,-2967,-3836,0.970975279808044 +15735,-1.36682569980621,-0.013602185063064,-0.060440458357334,39952,32767,-2915,-4142,0.97576904296875 +15737,-1.51130867004395,-0.012455676682294,-0.058772664517164,39952,6537,-3125,-3839,0.981519877910614 +15739,-1.66018414497376,-0.00258634542115,-0.058387186378241,39952,12391,-3880,-4128,0.984269857406616 +15741,-1.80550026893616,-0.00413725245744,-0.055954076349735,39952,11357,-3045,-3830,0.992567121982574 +15743,-1.94585740566254,-0.007594760973006,-0.054965358227491,39952,17024,-2836,-4098,0.993078410625458 +15759,-2.61473441123962,-0.02748754248023,-0.069699078798294,39952,24303,-2762,-4326,1.0257134437561 +15761,-2.65022706985474,-0.028585333377123,-0.064589500427246,39952,19924,-2647,-3948,1.03604197502136 +15763,-2.67165637016296,-0.022618632763624,-0.060854304581881,39952,24744,-3185,-4233,1.04246234893799 +15765,-2.66942024230957,-0.026364486664534,-0.061983667314053,39952,18538,-2474,-3942,1.04071402549744 +15767,-2.65900611877441,-0.029156886041164,-0.062501542270184,39952,23280,-2441,-4267,1.03288018703461 +15769,-2.64311766624451,-0.023607209324837,-0.05772178247571,39952,18223,-3162,-3924,1.03294062614441 +15771,-2.61437344551086,-0.014313716441393,-0.052108585834503,39952,22266,-3534,-4150,1.03593456745148 +15773,-2.57766604423523,-0.006573208142072,-0.053438730537891,39952,32767,-3553,-3904,1.03838717937469 +15775,-2.53057718276978,-0.010305343195796,-0.057342659682036,39952,26684,-2669,-4219,1.04187154769897 +15777,-2.4781768321991,0.004569893237203,-0.057393442839384,39952,21382,-4218,-3941,1.04992485046387 +15779,-2.40834665298462,0.008755596354604,-0.054941531270743,39952,24088,-3535,-4191,1.06281328201294 +15781,-2.32864928245544,0.016615256667137,-0.053538717329502,39952,18285,-3890,-3925,1.07513999938965 +15783,-2.23424816131592,0.024159628897905,-0.049909260123968,39952,20454,-4016,-4131,1.08250856399536 +15785,-2.12403631210327,0.035658828914166,-0.048274796456099,39952,14092,-4429,-3897,1.0811163187027 +15787,-2.01103448867798,0.054512403905392,-0.047127470374107,39952,16374,-5329,-4085,1.0848160982132 +15789,-1.88865280151367,0.061600264161825,-0.042145222425461,39952,10674,-4505,-3862,1.08312094211578 +15791,-1.75373804569244,0.070659443736076,-0.036017023026943,39952,11400,-4910,-3948,1.07685768604279 +15793,-1.60475945472717,0.078203909099102,-0.033516608178616,39952,5414,-4802,-3808,1.07150948047638 +15795,-1.46356081962585,0.092681393027306,-0.031650122255087,39952,6887,-5685,-3883,1.06350469589233 +15797,-1.31849944591522,0.093609265983105,-0.027769517153502,39952,2176,-4585,-3772,1.06357538700104 +15799,-1.17509746551514,0.111444145441055,-0.024655843153596,39952,2562,-6275,-3787,1.06313407421112 +15801,-1.02231419086456,0.11180879175663,-0.020989298820496,39952,-2167,-4852,-3727,1.06102395057678 +15803,-0.873370349407196,0.120094820857048,-0.017149522900581,39952,-2346,-5794,-3692,1.05517649650574 +15805,-0.719513237476349,0.12568336725235,-0.009699687361717,39952,-6267,-5478,-3650,1.05383932590485 +15807,-0.578645527362824,0.140695720911026,-0.005792262032628,39952,-6299,-6658,-3541,1.05656945705414 +15809,-0.443815231323242,0.156220227479935,-0.007791916839778,39952,27388,-6689,-3634,1.06430017948151 +15811,-0.300770729780197,0.154468789696693,-0.004638229962438,39952,-4753,-5736,-3513,1.05786800384521 +15813,-0.172496750950813,0.164878129959106,0.000100873759948,39952,-5913,-6514,-3577,1.05096733570099 +15815,-0.049135103821755,0.164070889353752,0.004483556840569,39952,-7367,-6024,-3395,1.05060577392578 +15817,0.067300945520401,0.167877644300461,0.008835596963763,39952,-8500,-6154,-3513,1.05099284648895 +15819,0.193767607212067,0.159773856401443,0.011074152775109,39952,-11585,-5501,-3317,1.04915106296539 +15821,0.305897325277328,0.171624675393105,0.012041842564941,39952,-11722,-6854,-3485,1.04762732982636 +15823,0.415663003921509,0.167454525828361,0.013512738980353,39952,-14152,-5979,-3278,1.04721319675446 +15825,0.51725572347641,0.171899244189262,0.011119117029011,39952,-14211,-6401,-3485,1.04727077484131 +15827,0.615605771541595,0.173518598079681,0.009040490724146,39952,-16839,-6568,-3322,1.04620146751404 +15829,0.700055837631226,0.176122084259987,0.008537301793695,39952,-15911,-6406,-3498,1.03662264347076 +15831,0.773674726486206,0.177383318543434,0.010193369351328,39952,-17985,-6684,-3303,1.03330957889557 +15833,0.843842208385468,0.169709086418152,0.011658363044262,39952,-17332,-5657,-3471,1.03079402446747 +15835,0.902283370494842,0.164494901895523,0.011909979395568,39952,-19396,-6087,-3290,1.03144884109497 +15837,0.949541330337524,0.150728330016136,0.010702575556934,39952,-17651,-5021,-3472,1.03233122825623 +15839,0.98885577917099,0.153194814920425,0.00923421420157,39952,-19884,-6523,-3328,1.03559720516205 +15841,1.02194571495056,0.145285025238991,0.008508834056556,39952,-18160,-5431,-3482,1.03828799724579 +15843,1.03751194477081,0.144944921135902,0.003227422712371,39952,-19469,-6259,-3403,1.03812634944916 +15845,1.04715025424957,0.134245648980141,-0.002367795677856,39952,-17352,-5139,-3554,1.04300618171692 +15847,1.04169380664825,0.130899056792259,-0.004165899474174,39952,17518,-5878,-3500,1.03807520866394 +15849,1.02535283565521,0.124126136302948,-0.005034409463406,39952,-9603,-5335,-3570,1.03241837024689 +15851,1.0046603679657,0.111141547560692,-0.008451226167381,39952,-11228,-4929,-3564,1.02230381965637 +15853,0.977972090244293,0.100243784487247,-0.013861614279449,39952,-8622,-4749,-3630,1.01930546760559 +15855,0.947424948215485,0.081486195325852,-0.016427600756288,39952,-10006,-4074,-3679,1.02458393573761 +15857,0.914337873458862,0.069957777857781,-0.017599120736122,39952,-7664,-4307,-3658,1.02957677841187 +15859,0.887747764587402,0.047944527119398,-0.017293345183134,39952,-9711,-3318,-3713,1.0330103635788 +15861,0.855736613273621,0.030195435509086,-0.016765803098679,39952,-7289,-3312,-3654,1.02938592433929 +15863,0.819532513618469,0.025229947641492,-0.017074014991522,39952,-8290,-4185,-3727,1.02948033809662 +15865,0.78239119052887,0.013505566865206,-0.016570415347815,39952,-6229,-3515,-3656,1.0309956073761 +15867,0.741861283779144,-0.000285552523565,-0.016350729390979,39952,-7068,-3145,-3737,1.03311908245087 +15869,0.698332011699677,-0.017616281285882,-0.018052434548736,39952,-4893,-2666,-3670,1.02822935581207 +15871,0.65084981918335,-0.017382031306625,-0.018956895917654,39952,-5403,-3873,-3781,1.01753664016724 +15873,0.604537546634674,-0.025217631831765,-0.019610179588199,39952,-3636,-3229,-3684,1.01502323150635 +15875,0.555409073829651,-0.038412611931563,-0.016171036288142,39952,-3987,-2560,-3763,1.01267445087433 +15877,0.496080130338669,-0.049411542713642,-0.011611550115049,39952,-1392,-2638,-3633,1.01209211349487 +15879,0.444538563489914,-0.06546376645565,-0.011423375457525,39952,-2211,-1885,-3725,1.01674652099609 +15881,0.396390348672867,-0.076201610267162,-0.014294720254839,39952,-953,-2241,-3655,1.01751065254211 +15883,0.349615335464478,-0.095476470887661,-0.015274063684046,39952,-1180,-1131,-3789,1.0150899887085 +15885,0.294840306043625,-0.107109792530537,-0.01333757955581,39952,32767,-1689,-3654,1.01159453392029 +15887,0.235552683472633,-0.114833310246468,-0.010752271860838,39952,7516,-1598,-3750,1.01394557952881 +15889,0.191435545682907,-0.124758556485176,-0.00857743807137,39952,7569,-1505,-3625,1.01327621936798 +15891,0.148372814059258,-0.125975012779236,-0.005705293267965,39952,7736,-1836,-3700,1.0126371383667 +15893,0.113353297114372,-0.138073444366455,-0.005332185421139,39952,8035,-1100,-3607,1.0086110830307 +15895,0.082412660121918,-0.143693715333939,-0.007463293615729,39952,7954,-1173,-3733,1.00710690021515 +15897,0.06023495271802,-0.15585395693779,-0.007958685979247,39952,7905,-774,-3629,1.00885570049286 +15899,0.037604421377182,-0.15237857401371,-0.006783655378968,39952,8146,-1612,-3733,1.00845468044281 +15901,0.018156941980124,-0.144052162766457,-0.003011296503246,39952,8365,-2340,-3599,1.0150318145752 +15903,0.018293604254723,-0.143664330244064,-0.000826991919894,39952,6892,-1458,-3662,1.01330304145813 +15905,0.031039675697684,-0.141846463084221,-0.001374293351546,39952,5935,-1838,-3591,1.01432311534882 +15907,0.043271876871586,-0.144189864397049,-0.001308950013481,39952,5669,-1183,-3671,1.0133455991745 +15909,0.048835933208466,-0.13049341738224,-0.001026025041938,39952,6243,-2782,-3592,1.01429331302643 +15911,0.065094500780106,-0.125103369355202,0.002552869264036,39952,5062,-1982,-3619,1.0141898393631 +15913,0.093877665698528,-0.116791106760502,0.003890833817422,39952,3971,-2532,-3561,1.00726211071014 +15915,0.125866070389748,-0.105740629136562,0.003860152792186,39952,2965,-2654,-3595,1.01438450813293 +15917,0.155442804098129,-0.092897906899452,0.005136920604855,39952,3038,-3149,-3554,1.02533233165741 +15919,0.183413162827492,-0.077100656926632,0.005500322207809,39952,2310,-3415,-3563,1.03487944602966 +15921,0.219818010926247,-0.071370892226696,0.008575174026191,39952,1605,-2910,-3531,1.04507172107697 +15923,0.258759081363678,-0.059983637183905,0.014816493727267,39952,265,-3335,-3444,1.04784607887268 +15925,0.299915343523026,-0.057942431420088,0.016699437052012,39952,60,-2807,-3474,1.04335689544678 +15927,0.336054593324661,-0.048879284411669,0.015482208691537,39952,-867,-3326,-3430,1.0364488363266 +15929,0.368677109479904,-0.037343975156546,0.019586745649576,39952,-407,-3757,-3453,1.03325843811035 +15931,0.40327587723732,-0.026475939899683,0.024999167770147,39952,-1964,-3797,-3304,1.03042161464691 +15933,0.447698324918747,-0.014143770560622,0.024575656279922,39952,-2513,-4131,-3415,1.02844560146332 +15935,0.494787395000458,-0.007200060412288,0.022169226780534,39952,-4486,-3825,-3325,1.02092754840851 +15937,0.533312857151032,0.012983087450266,0.021165765821934,39952,-3488,-5077,-3436,1.0146815776825 +15939,0.568508207798004,0.021023333072662,0.020762940868735,39952,-5007,-4366,-3326,1.01426148414612 +15941,0.60227632522583,0.037491172552109,0.022224994376302,39952,-4339,-5171,-3425,1.01813519001007 +15943,0.638279974460602,0.042164176702499,0.025616994127631,39952,-6412,-4470,-3256,1.02255654335022 +15945,0.667533159255981,0.045017782598734,0.025595918297768,39952,-5188,-4320,-3397,1.01879060268402 +15947,0.687911510467529,0.049235574901104,0.026539862155914,39952,-6346,-4557,-3238,1.01493084430695 +15949,0.711533844470978,0.051396306604147,0.026626730337739,39952,-5678,-4379,-3386,1.01274847984314 +15951,0.736403226852417,0.066799208521843,0.02638627961278,39952,-7723,-5656,-3228,1.01390111446381 +15953,0.75901061296463,0.077806189656258,0.027919251471758,39952,-6571,-5415,-3372,1.01642453670502 +15955,0.766593635082245,0.0931206792593,0.028722856193781,39952,-7268,-6112,-3186,1.02084243297577 +15957,0.77638053894043,0.084044352173805,0.029564904049039,39952,-6203,-4102,-3355,1.02449023723602 +15959,0.788279831409454,0.078220583498478,0.029920959845185,39952,-8238,-4394,-3174,1.02594304084778 +15961,0.791645705699921,0.088524833321571,0.031240493059158,39952,-6276,-5586,-3338,1.03076732158661 +15963,0.790628552436829,0.100258067250252,0.030286049470306,39952,-7667,-6045,-3157,1.03121912479401 +15965,0.788623690605164,0.100266091525555,0.025568876415491,39952,-6166,-5059,-3371,1.02562284469605 +15967,0.7861487865448,0.085203066468239,0.025426374748349,39952,-7806,-3919,-3216,1.01957499980927 +15969,0.781088769435883,0.083596743643284,0.029282547533512,39952,-6157,-4739,-3341,1.01284444332123 +15971,0.772085011005402,0.080185770988464,0.029600517824292,39952,-7419,-4705,-3164,1.00907874107361 +15973,0.754712700843811,0.076137393712998,0.02587347663939,39952,-5210,-4489,-3359,1.0035914182663 +15987,0.589312016963959,0.055264677852392,0.015370850451291,39952,-4539,-4244,-3328,1.02561855316162 +15989,0.567678928375244,0.042415089905262,0.013564131222665,39952,-3316,-3479,-3429,1.02248442173004 +15991,0.539527654647827,0.028572250157595,0.011924646794796,39952,-3640,-3263,-3374,1.01968574523926 +15993,0.507112145423889,0.018035553395748,0.008583083748817,39952,-1893,-3307,-3462,1.01384961605072 +15995,0.47764977812767,0.012069380842149,0.008043427020311,39952,-2731,-3567,-3423,1.00897359848022 +15997,0.43905171751976,0.019206823781133,0.005728551186621,39952,-662,-4595,-3480,1.00365304946899 +15999,0.403381526470184,0.001996649196371,0.006118948105723,39952,-1242,-2597,-3447,1.00286817550659 +16001,0.37042373418808,-0.017627101391554,0.008803246542811,39952,-236,-2150,-3459,1.0034111738205 +16003,0.345533460378647,-0.032449953258038,0.009541185572743,39952,-1211,-2197,-3414,1.00835239887238 +16005,0.315417319536209,-0.034214921295643,0.009125499986112,39952,220,-3174,-3456,1.0106406211853 +16007,0.281436115503311,-0.034210905432701,0.009236983954906,39952,366,-3215,-3417,1.00958216190338 +16009,0.253195524215698,-0.042761690914631,0.007046320009977,39952,879,-2548,-3469,1.00802898406982 +16011,0.228645220398903,-0.053828604519367,0.003797613084316,39952,457,-2079,-3485,1.00671470165253 +16013,0.206121504306793,-0.067915976047516,0.005467619281262,39952,1068,-1763,-3480,1.00626277923584 +16015,0.18440967798233,-0.075085811316967,0.009536189027131,39952,907,-1984,-3422,1.00691401958466 +16017,0.157419115304947,-0.069985583424568,0.015834668651223,39952,2030,-3071,-3408,1.00848412513733 +16019,0.13446432352066,-0.075456626713276,0.019222136586905,39952,1759,-2066,-3306,1.00988566875458 +16021,0.113660179078579,-0.080223865807057,0.016996530815959,39952,2180,-2181,-3398,1.00985407829285 +16023,0.103848502039909,-0.099888660013676,0.018438862636685,39952,1296,-607,-3318,1.00504863262177 +16025,0.087020359933376,-0.093826174736023,0.022318767383695,39952,2258,-2714,-3359,1.00292277336121 +16027,0.074396841228008,-0.091993995010853,0.024304680526257,39952,1959,-2228,-3245,1.00450897216797 +16029,0.067148067057133,-0.086932919919491,0.020131336525083,39952,1850,-2695,-3371,1.00391209125519 +16031,0.073124244809151,-0.087812565267086,0.014337693341076,39952,635,-2060,-3359,1.00966560840607 +16033,0.079721041023731,-0.091178543865681,0.015760637819767,39952,670,-1987,-3400,1.01645541191101 +16035,0.077993787825108,-0.086132302880287,0.021882355213165,39952,1100,-2472,-3267,1.02029359340668 +16037,0.078172527253628,-0.08099252730608,0.023632787168026,39952,1142,-2700,-3343,1.023961186409 +16039,0.0787523239851,-0.067718930542469,0.022504463791847,39952,916,-3321,-3253,1.02193212509155 +16041,0.08349284529686,-0.059756923466921,0.024574130773544,39952,729,-3173,-3334,1.02170372009277 +16043,0.091317750513554,-0.053807903081179,0.022800965234637,39952,185,-2988,-3244,1.01795101165771 +16045,0.101717919111252,-0.049585483968258,0.021040301769972,39952,46,-3022,-3355,1.01478362083435 +16047,0.111652195453644,-0.051188409328461,0.022016147151589,39952,-312,-2454,-3249,1.00866222381592 +16049,0.116554133594036,-0.037490453571081,0.026495674625039,39952,203,-3846,-3315,1.0081969499588 +16051,0.124967232346535,-0.02793638035655,0.031409524381161,39952,-446,-3605,-3130,1.01152265071869 +16053,0.131973251700401,-0.01308006234467,0.033102747052908,39952,-199,-4261,-3264,1.01647126674652 +16055,0.144613862037659,-0.005097361747175,0.031950078904629,39952,-1090,-3860,-3115,1.02293968200684 +16057,0.156574234366417,0.00967213883996,0.028684856370092,39952,-945,-4575,-3290,1.02284133434296 +16059,0.168911024928093,0.017159583047032,0.027308864519,39952,-1519,-4187,-3160,1.02497231960297 +16061,0.185963094234467,0.00866409111768,0.02753359079361,39952,-1783,-2898,-3293,1.02406644821167 +16063,0.20047827064991,0.013171182945371,0.026208369061351,39952,-2261,-3915,-3169,1.02238821983337 +16065,0.214762523770332,0.023292886093259,0.022537514567375,39952,-2068,-4444,-3324,1.02102863788605 +16067,0.22755154967308,0.040475349873304,0.021371718496084,39952,-2650,-5278,-3218,1.01797080039978 +16069,0.243131801486015,0.043655458837748,0.023720346391201,39952,-2650,-4255,-3312,1.01459765434265 +16071,0.251722902059555,0.04656120762229,0.024205578491092,39952,-2823,-4368,-3180,1.01364493370056 +16073,0.25634029507637,0.045532509684563,0.023071883246303,39952,-2147,-3998,-3312,1.01750445365906 +16075,0.2640400826931,0.041275046765804,0.023406218737364,39952,-3040,-3778,-3186,1.01630866527557 +16077,0.266372621059418,0.052235335111618,0.023866344243288,39952,-2224,-4968,-3303,1.01503348350525 +16079,0.271000593900681,0.061308890581131,0.023474976420403,39952,-3033,-5073,-3179,1.01575946807861 +16081,0.277579843997955,0.07073624432087,0.022082464769483,39952,-2790,-5147,-3311,1.01110446453094 +16083,0.287119835615158,0.064948752522469,0.020227933302522,39952,-3763,-4099,-3213,1.00934374332428 +16085,0.291079610586166,0.063303507864475,0.020330058410764,39952,-2908,-4274,-3320,1.00816714763641 +16087,0.295651912689209,0.062981396913529,0.021901110187173,39952,-3661,-4486,-3190,1.01131939888 +16089,0.300512135028839,0.055659990757704,0.020345576107502,39952,-3224,-3783,-3316,1.01051044464111 +16091,0.304167568683624,0.050103109329939,0.022119535133243,39952,-3851,-3931,-3186,1.00789427757263 +16093,0.306158691644669,0.044474065303803,0.024368466809392,39952,-3221,-3765,-3285,1.00459098815918 +16095,0.304278403520584,0.052638072520495,0.02706847153604,39952,-3573,-4975,-3124,1.00503551959991 +16097,0.306826204061508,0.048806682229042,0.028033884242177,39952,-3392,-3978,-3255,1.00689077377319 +16099,0.308067470788956,0.050469916313887,0.026704730466008,39952,-3975,-4489,-3124,1.00552952289581 +16101,0.303308933973312,0.049925602972508,0.023525346070528,39952,-2941,-4249,-3282,1.00609862804413 +16103,0.298956483602524,0.040190704166889,0.019792478531599,39952,-3557,-3529,-3204,1.00165629386902 +16105,0.290460646152496,0.033564444631338,0.018295681104064,39952,-2611,-3595,-3315,1.00372540950775 +16107,0.281978726387024,0.021697700023651,0.02230472676456,39952,-3100,-3081,-3173,1.00977313518524 +16109,0.276313006877899,0.02452770806849,0.024303169921041,39952,-2725,-4150,-3270,1.01308643817902 +16111,0.280041038990021,0.017280528321862,0.021455800160766,39952,-4047,-3345,-3180,1.01583755016327 +16113,0.275349795818329,0.019381335005164,0.016706768423319,39952,-2893,-4029,-3319,1.01637160778046 +16115,0.266867816448212,0.013150440528989,0.018076896667481,39952,-3067,-3344,-3218,1.02070093154907 +16117,0.253967553377151,0.00289096776396,0.022210063412786,39952,-2105,-2908,-3278,1.01761782169342 +16119,0.241338700056076,-0.008364209905267,0.02391304820776,39952,-2447,-2622,-3148,1.01256167888641 +16121,0.229240596294403,-0.016658922657371,0.025482259690762,39952,-1902,-2757,-3252,1.00558245182037 +16123,0.222916677594185,-0.016169765964151,0.024610118940473,39952,-2698,-3329,-3137,0.998756527900696 +16125,0.223546400666237,-0.020854311063886,0.022318037226796,39952,-2820,-2942,-3270,0.995111107826233 +16127,0.222767263650894,-0.02249045111239,0.020490799099207,39952,-3182,-3067,-3183,0.995564222335815 +16129,0.213404387235641,-0.027784870937467,0.0200703907758,39952,-2048,-2784,-3282,1.00254261493683 +16131,0.202614188194275,-0.031545180827379,0.020966490730643,39952,-2215,-2763,-3175,1.00796699523926 +16133,0.183855265378952,-0.030674928799272,0.02036920748651,39952,-1030,-3167,-3277,1.01423943042755 +16135,0.169590875506401,-0.034164059907198,0.018614755943418,39952,-1514,-2726,-3200,1.01968848705292 +16137,0.161018207669258,-0.02930230088532,0.017400996759534,39952,-1498,-3455,-3295,1.02263069152832 +16139,0.157416209578514,-0.038764610886574,0.015760513022542,39952,-2156,-2193,-3231,1.02748727798462 +16141,0.146652072668076,-0.043356779962778,0.013398790732026,39952,-1198,-2554,-3320,1.02223002910614 +16143,0.129820257425308,-0.054323505610228,0.014406168833375,39952,-813,-1808,-3246,1.01775538921356 +16145,0.115420058369637,-0.060870300978422,0.015284433029592,39952,-540,-2133,-3305,1.00516724586487 +16147,0.101931199431419,-0.05626092851162,0.017427142709494,39952,-639,-2874,-3208,0.992783546447754 +16149,0.099315531551838,-0.052633553743363,0.017987767234445,39952,-1191,-2952,-3284,0.991929709911346 +16151,0.100636102259159,-0.044243529438973,0.016985151916742,39952,-1711,-3314,-3210,0.996128380298614 +16153,0.098310559988022,-0.049498371779919,0.017306309193373,39952,-1233,-2337,-3286,1.00060701370239 +16155,0.085729584097862,-0.045634403824806,0.018138058483601,39952,-504,-2943,-3194,1.00329113006592 +16157,0.073565952479839,-0.042724616825581,0.019526252523065,39952,-203,-2995,-3268,1.00874638557434 +16159,0.06892391294241,-0.047736428678036,0.019612479954958,39952,-835,-2241,-3174,1.0140106678009 +16161,0.074240542948246,-0.056127592921257,0.019143261015415,39952,-1488,-1967,-3268,1.01689827442169 +16163,0.077005192637444,-0.060815960168839,0.019743109121919,39952,-1521,-2021,-3170,1.0151664018631 +16165,0.073376804590225,-0.053422220051289,0.017229890450835,39952,-862,-3104,-3278,1.0108470916748 +16167,0.068512320518494,-0.047877952456474,0.013331959024072,39952,-861,-2937,-3242,1.01091432571411 +16169,0.06582897901535,-0.03336114436388,0.008541798219085,39952,-845,-3876,-3336,1.01187932491303 +16171,0.068240091204643,-0.026680704206228,0.005863772705197,39952,-1399,-3343,-3327,1.01718401908875 +16173,0.073944725096226,-0.026890674605966,0.009071764536202,39952,-1585,-2897,-3332,1.02029383182526 +16175,0.068097770214081,-0.023327017202973,0.01456555724144,39952,-826,-3161,-3223,1.01933979988098 +16177,0.059104040265083,-0.023921370506287,0.015823133289814,39952,-343,-2897,-3283,1.02066445350647 +16179,0.058321263641119,-0.022982478141785,0.014298386871815,39952,-1061,-2956,-3224,1.02042841911316 +16181,0.071126207709313,-0.031702429056168,0.01216902025044,39952,-2097,-2187,-3306,1.0228214263916 +16183,0.073675699532032,-0.025083001703024,0.011170914396644,39952,-1574,-3310,-3259,1.01886761188507 +16185,0.06873931735754,-0.009392545558512,0.014028975740075,39952,-820,-4238,-3292,1.01806998252869 +16187,0.071247383952141,0.003697217674926,0.01256700605154,39952,-1547,-4228,-3239,1.01583504676819 +16189,0.081281870603561,0.007555900141597,0.010010014288128,39952,-2097,-3629,-3318,1.01261937618256 +16191,0.085151359438896,0.009084932506084,0.010882555507124,39952,-1884,-3485,-3257,1.01057529449463 +16193,0.083551704883576,0.016745904460549,0.013841611333191,39952,-1326,-4032,-3290,1.00880217552185 +16195,0.08320613950491,0.016768243163824,0.016030687838793,39952,-1578,-3505,-3194,1.00664949417114 +16197,0.088230140507221,0.017072692513466,0.012833459302783,39952,-1896,-3512,-3294,1.00309145450592 +16199,0.094422891736031,0.018239365890622,0.011320235207677,39952,-2266,-3613,-3247,1.00137233734131 +16217,0.098985746502876,0.057089403271675,0.012403628788889,39952,-1408,-5264,-3287,1.00129926204681 +16219,0.095998682081699,0.06199512258172,0.011279536411166,39952,-1839,-4664,-3236,1.00547122955322 +16221,0.098614700138569,0.065859869122505,0.011456858366728,39952,-2107,-4545,-3292,1.00873649120331 +16223,0.102570384740829,0.06436800211668,0.014092885889113,39952,-2484,-4272,-3200,1.01331412792206 +16225,0.103936776518822,0.065217979252338,0.014648402109742,39952,-2136,-4347,-3268,1.01411175727844 +16227,0.102772332727909,0.061871461570263,0.013742839917541,39952,-2163,-4126,-3203,1.0176614522934 +16229,0.098768219351769,0.053812779486179,0.009673727676272,39952,-1720,-3571,-3300,1.0218653678894 +16231,0.098653182387352,0.051189664751291,0.00705610960722,39952,-2216,-4026,-3280,1.02573800086975 +16233,0.103506572544575,0.04329601675272,0.008556972257793,39952,-2464,-3452,-3307,1.021977186203 +16235,0.102834686636925,0.044006817042828,0.013078048825264,39952,-2282,-4165,-3208,1.0138897895813 +16237,0.099939696490765,0.031208474189043,0.014820458367467,39952,-1901,-2945,-3261,1.00540018081665 +16239,0.092877477407456,0.026202069595456,0.009492921642959,39952,-1702,-3478,-3250,1.00288438796997 +16241,0.096353851258755,0.019170319661498,0.006658455822617,39952,-2344,-3194,-3316,1.0054486989975 +16243,0.098506972193718,0.016546765342355,0.006971150171012,39952,-2489,-3501,-3279,1.00853133201599 +16245,0.093851789832115,0.017394339665771,0.006219413597137,39952,-1766,-3738,-3318,1.01205015182495 +16247,0.088862285017967,0.014093832112849,0.005632538814098,39952,-1857,-3416,-3294,1.01349627971649 +16249,0.087505750358105,0.014496075920761,0.005612619686872,39952,-1948,-3668,-3322,1.01233530044556 +16251,0.085508540272713,0.004982220474631,0.006475798785687,39952,-2052,-2819,-3283,1.01409316062927 +16253,0.078255496919155,0.002213332569227,0.003351329592988,39952,-1427,-3263,-3336,1.01145148277283 +16255,0.07577346265316,-0.003197154961526,0.002137658186257,39952,-1890,-2972,-3334,1.00599086284637 +16257,0.076424926519394,-0.012842108495534,0.0046471725218,39952,-1997,-2549,-3327,0.994045197963715 +16259,0.06990048289299,-0.009519113227725,0.009166911244392,39952,-1531,-3488,-3251,0.991012930870056 +16261,0.065044082701206,-0.011889595538378,0.010642704553902,39952,-1467,-3074,-3285,0.99628871679306 +16263,0.062472481280565,-0.01154578011483,0.009899218566716,39952,-1711,-3235,-3241,1.00324726104736 +16265,0.068593889474869,-0.019735492765904,0.012129558250308,39952,-2327,-2536,-3273,1.01049208641052 +16267,0.068699933588505,-0.022893212735653,0.010377664119005,39952,-2022,-2793,-3234,1.01154541969299 +16269,0.063070401549339,-0.027076225727797,0.007381528615952,39952,-1431,-2703,-3304,1.01341187953949 +16271,0.059724003076553,-0.031287785619497,0.004965994041413,39952,-1671,-2568,-3297,1.01448464393616 +16273,0.060280539095402,-0.031804565340281,0.005032502580434,39952,-1858,-2881,-3320,1.01611804962158 +16275,0.059319097548723,-0.032443650066853,0.005947988945991,39952,-1878,-2790,-3285,1.0142560005188 +16277,0.053559839725494,-0.026649694889784,0.007069656159729,39952,-1336,-3389,-3305,1.00920164585114 +16279,0.054022394120693,-0.029710976406932,0.006106833461672,39952,-1916,-2647,-3282,1.00470662117004 +16281,0.051824882626534,-0.021121187135577,0.002655325224623,39952,-1590,-3653,-3335,1.00216174125671 +16283,0.046036127954722,-0.018505677580834,0.00125098391436,39952,-1347,-3214,-3339,1.00307464599609 +16285,0.041406650096178,-0.018605906516314,0.002904742723331,39952,-1285,-3055,-3333,1.00080788135529 +16287,0.033288598060608,-0.008927708491683,0.006349005736411,39952,-976,-3859,-3278,1.00156998634338 +16289,0.027352813631296,-0.008837546221912,0.008386956527829,39952,-1000,-3199,-3294,1.00223672389984 +16291,0.021678367629647,-0.012730837799609,0.008493793196976,39952,-976,-2819,-3252,0.997766613960266 +16293,0.020152071490884,-0.028339616954327,0.008344574831426,39952,-1219,-1785,-3293,0.993594467639923 +16295,0.016830565407872,-0.025945894420147,0.005235294345766,39952,-1082,-3047,-3290,0.991198897361755 +16297,0.020299701020122,-0.019658563658595,0.00498401094228,39952,-1585,-3462,-3316,0.992482125759125 +16299,0.024841725826264,-0.020638948306441,0.007192439865321,39952,-1786,-2887,-3266,0.990892469882965 +16301,0.030802298337221,-0.016563663259149,0.01032308768481,39952,-1924,-3337,-3278,0.990722000598908 +16303,0.033087376505137,-0.01496755797416,0.009921548888087,39952,-1769,-3159,-3232,0.99083411693573 +16305,0.033411037176848,-0.005050621926785,0.004949662834406,39952,-1572,-3913,-3314,0.99211585521698 +16307,0.040725480765104,-0.004003384616226,0.001811056863517,39952,-2258,-3285,-3327,0.996015906333923 +16309,0.042637009173632,0.000269527372438,0.00031066374504,39952,-1833,-3581,-3346,0.996864438056946 +16311,0.038803119212389,-0.003695425344631,-0.001407152507454,39952,-1449,-2924,-3365,0.999138653278351 +16313,0.037829592823982,-0.007902896031737,-0.001097010681406,39952,-1574,-2852,-3356,0.996880054473877 +16315,0.040007710456848,-0.001905651763082,0.000726678932551,39952,-1927,-3663,-3340,0.988972127437592 +16317,0.038950745016337,-0.001289544510655,0.003914980217814,39952,-1602,-3288,-3321,0.991787970066071 +16319,0.03308642283082,0.003548300126567,0.006405045744032,39952,-1253,-3665,-3272,0.995880603790283 +16321,0.036903973668814,-0.006929159164429,0.004858748987317,39952,-1937,-2411,-3314,1.00023448467255 +16323,0.042128890752792,-0.004325815010816,-0.001204044907354,39952,-2204,-3367,-3362,1.00429546833038 +16325,0.044549077749252,0.000479355396237,-0.004266774747521,39952,-1965,-3606,-3377,1.01183938980103 +16327,0.046385485678911,0.004432179033756,-0.001530246110633,39952,-2037,-3589,-3366,1.00926995277405 +16329,0.050224125385285,0.011685868725181,0.002275803592056,39952,-2166,-3938,-3333,1.00582683086395 +16331,0.049989268183708,0.013968323357403,0.001177327823825,39952,-1963,-3619,-3334,1.00131738185883 +16333,0.042855307459831,0.020862860605121,-0.002701064338908,39952,-1293,-4044,-3367,0.998458445072174 +16335,0.047152698040009,0.01769133657217,-0.005323188379407,39952,-2270,-3292,-3411,0.991327941417694 +16337,0.049458354711533,0.021553976461291,-0.006398028694093,39952,-2084,-3839,-3393,0.984727382659912 +16339,0.042655132710934,0.021541962400079,-0.005791652482003,39952,-1426,-3590,-3418,0.988229811191559 +16341,0.041865613311529,0.013813029043377,-0.005207440815866,39952,-1772,-2902,-3386,0.993735373020172 +16343,0.042694218456745,0.009003274142742,-0.009538285434246,39952,-1996,-3056,-3464,1.00064551830292 +16345,0.04439365118742,0.006643360946327,-0.010385976172984,39952,-2006,-3184,-3424,1.00891613960266 +16347,0.043027438223362,0.012299714609981,-0.006670732516795,39952,-1876,-3858,-3431,1.01341903209686 +16349,0.04655098170042,0.005734980106354,-0.002605503192171,39952,-2190,-2872,-3372,1.01859307289124 +16367,0.026258131489158,0.040144853293896,-0.006576241459697,39952,-1787,-4258,-3436,1.01455593109131 +16369,0.021548047661781,0.039920497685671,-0.00635323766619,39952,-1313,-3864,-3403,1.01519656181335 +16371,0.019923005253077,0.03514738380909,-0.007038248702884,39952,-1558,-3523,-3443,1.01491594314575 +16373,0.020359450951219,0.02671604603529,-0.005176338832825,39952,-1674,-3097,-3396,1.01281833648682 +16375,0.01668612845242,0.030879532918334,-0.002592840930447,39952,-1364,-4106,-3391,1.01107788085938 +16377,0.015289293602109,0.02468341961503,-0.001685644499958,39952,-1478,-3237,-3373,1.00652706623077 +16379,0.015950305387378,0.018422469496727,-0.005467711016536,39952,-1667,-3168,-3426,1.0012629032135 +16381,0.017890386283398,0.012194841168821,-0.008152027614415,39952,-1761,-3060,-3419,1.00164663791657 +16383,0.019136572256684,0.003381801769137,-0.007182048168033,39952,-1767,-2750,-3448,1.0046501159668 +16385,0.017977053299546,-0.003673430765048,-0.003393261693418,39952,-1549,-2771,-3387,1.00348460674286 +16387,0.020500477403402,-0.015391575172544,0.000337613426382,39952,-1893,-2228,-3360,1.0042337179184 +16389,0.023750236257911,-0.013158828020096,-0.001735131372698,39952,-1957,-3290,-3376,1.00367701053619 +16391,0.03332382440567,-0.015934497117996,-0.004655038006604,39952,-2619,-2839,-3420,1.00568187236786 +16393,0.03012365847826,-0.011969304643571,-0.005011726170778,39952,-1602,-3419,-3400,1.00498485565186 +16395,0.02496568672359,-0.014173714444041,-0.003018917050213,39952,-1438,-2896,-3401,1.00977921485901 +16397,0.022227877750993,-0.017549382522702,-0.004285309463739,39952,-1533,-2801,-3396,1.01167106628418 +16399,0.02444089576602,-0.01447166595608,-0.008285760879517,39952,-1960,-3259,-3465,1.01166570186615 +16401,0.024440888315439,-0.01229604985565,-0.007287345360965,39952,-1770,-3263,-3418,1.0116822719574 +16403,0.02162522636354,-0.009976675733924,-0.00621395278722,39952,-1560,-3270,-3442,1.01235890388489 +16405,0.021685313433409,-0.01886672154069,-0.00646275607869,39952,-1743,-2366,-3414,1.00958740711212 +16407,0.022850923240185,-0.017814649268985,-0.010759771801531,39952,-1880,-3044,-3497,1.00471138954163 +16409,0.024863015860319,-0.013310299254954,-0.013586340472102,39952,-1938,-3393,-3465,1.003173828125 +16411,0.029610188677907,-0.01375646982342,-0.012077205814421,39952,-2265,-2990,-3515,1.00250232219696 +16413,0.031212164089084,-0.010135950520635,-0.010657720267773,39952,-2014,-3365,-3447,1.00145292282105 +16415,0.030319197103381,-0.007620244286954,-0.011079052463174,39952,-1893,-3299,-3505,1.00168168544769 +16417,0.0273492988199,0.005999803543091,-0.013048938475549,39952,-1646,-4306,-3465,1.00170171260834 +16419,0.032023288309574,-0.001548472675495,-0.012146308086813,39952,-2336,-2680,-3520,1.00168323516846 +16421,0.02982384338975,-0.001255875453353,-0.012001484632492,39952,-1753,-3244,-3460,1.00072717666626 +16423,0.026552559807897,-0.00063319131732,-0.010333240963519,39952,-1684,-3275,-3501,1.00184977054596 +16425,0.0211864374578,0.002531342674047,-0.01047811191529,39952,-1415,-3502,-3452,0.999962091445923 +16427,0.010231403633952,0.008293303661048,-0.012410597875714,39952,-876,-3783,-3527,1.0005304813385 +16429,0.004143923986703,0.002621576189995,-0.011237086728215,39952,-1124,-2871,-3460,1.00404560565948 +16431,0.002736853435636,-0.003822933649644,-0.008812768384814,39952,-1443,-2707,-3487,1.00607824325562 +16433,0.005500515457243,-0.020390840247274,-0.008371870033443,39952,-1779,-1754,-3442,1.00903916358948 +16435,0.001526027685031,-0.017947053536773,-0.009314701892436,39952,-1239,-3107,-3495,1.00836932659149 +16437,-0.003700144123286,-0.006793114356697,-0.009339193813503,39952,-1075,-3923,-3450,1.01248002052307 +16439,-0.004288259893656,-0.003598182927817,-0.010045204311609,39952,-1396,-3389,-3505,1.01671612262726 +16441,-0.003370082005858,-0.003903033677489,-0.010465844534338,39952,-1520,-3139,-3460,1.02322506904602 +16443,-0.001694964012131,-0.018753349781036,-0.011119002476335,39952,-1600,-1843,-3520,1.02037310600281 +16445,-0.003093727864325,-0.021321227774024,-0.011551402509213,39952,-1359,-2716,-3469,1.01308274269104 +16447,-0.005380463786423,-0.019167616963387,-0.008352041244507,39952,-1255,-3041,-3489,1.00637638568878 +16449,-0.010803767479956,-0.010151517577469,-0.004836129024625,39952,-32767,-26051,-3425,0.998278081417084 +16451,-0.007816703990102,-0.010797518305481,-0.003235493088141,39952,-32046,-6742,-3430,0.997448980808258 +16453,-0.005976716056466,-0.013305146247149,-0.004220043774694,39952,-32147,-6610,-3421,0.995493829250336 +16455,-0.010892087593675,-0.013241665437818,-0.006074995268136,39952,-31722,-6782,-3465,0.99625438451767 +16457,-0.017903730273247,-0.01821369305253,-0.007631316315383,39952,-31639,-6391,-3446,0.998608708381653 +16459,-0.030943995341659,-0.01699747517705,-0.013186377473176,39952,-31100,-6828,-3550,1.00118565559387 +16461,-0.048994012176991,-0.030193334445357,-0.021411551162601,39952,-30689,-5655,-3544,1.00170278549194 +16463,-0.078417249023914,-0.035684324800968,-0.028432000428438,39952,-29428,-6066,-3734,1.00023460388184 +16465,-0.122295826673508,-0.036063943058252,-0.032242700457573,39952,-28051,-6506,-3623,1.00054264068604 +16467,-0.190130904316902,-0.040098201483488,-0.037255294620991,39952,-25107,-6109,-3844,0.9983891248703 +16469,-0.269715368747711,-0.048107258975506,-0.04165530949831,39952,-23592,-5801,-3694,0.9918332695961 +16471,-0.354686439037323,-0.063475757837296,-0.04904905334115,39952,-21387,-4926,-3991,0.985642611980438 +16473,-0.450959116220474,-0.077555559575558,-0.05719929561019,39952,-19933,-4947,-3810,0.986722767353058 +16475,-0.558508336544037,-0.090930938720703,-0.059744942933321,39952,-16549,-4621,-4128,0.987755119800568 +16477,-0.671863496303558,-0.112480312585831,-0.060668729245663,39952,-15582,-3901,-3844,0.994439542293549 +16479,-0.794151246547699,-0.131882056593895,-0.062758035957813,39952,-11650,-3512,-4177,0.996618568897247 +16481,-0.91854590177536,-0.142644628882408,-0.067357495427132,39952,-11182,-4213,-3902,1.00015914440155 +16483,-1.05034852027893,-0.154195681214333,-0.077217563986778,39952,-6670,-3682,-4363,0.997292637825012 +16485,-1.19347178936005,-0.167398363351822,-0.0810407102108,39952,-5704,-3645,-4009,0.992311894893646 +16487,-1.34005618095398,-0.188511177897453,-0.079453825950623,39952,-647,-2387,-4410,0.989340424537659 +16489,-1.48419201374054,-0.207286328077316,-0.080534383654595,39952,-1131,-2618,-4020,0.980791389942169 +16491,-1.6157044172287,-0.228222772479057,-0.083769246935845,39952,3143,-1687,-4485,0.979071199893951 +16493,-1.74740064144135,-0.245958000421524,-0.078766442835331,39952,2215,-2063,-4024,0.974333345890045 +16495,-1.880695104599,-0.260341465473175,-0.076697990298271,39952,8082,-1555,-4429,0.974619626998901 +16497,-1.99750447273254,-0.286904126405716,-0.081676356494427,39952,5323,-753,-4058,0.974352777004242 +16499,-2.11475944519043,-0.304081857204437,-0.082628168165684,39952,11376,-550,-4532,0.966718792915344 +16519,-2.89159417152405,-0.421371638774872,-0.064081586897373,39952,21976,1626,-4520,1.00957643985748 +16521,-2.90495443344116,-0.425667226314545,-0.066400401294232,39952,16517,509,-4052,1.01501893997192 +16523,-2.91074824333191,-0.418238759040832,-0.065922647714615,39952,22049,416,-4581,1.01940560340881 +16525,-2.90002226829529,-0.425600558519363,-0.06344935297966,39952,15828,895,-4050,1.02687549591064 +16527,-2.87239861488342,-0.428209066390991,-0.059156332165003,39952,20133,1466,-4548,1.02804982662201 +16529,-2.84038043022156,-0.420531272888184,-0.059984531253576,39952,14546,-82,-4045,1.02682518959045 +16531,-2.79924583435059,-0.411232203245163,-0.063050381839275,39952,19061,507,-4625,1.02526545524597 +16533,-2.7467565536499,-0.393279910087586,-0.063142940402031,39952,12809,-1043,-4086,1.02340447902679 +16535,-2.68468117713928,-0.3864686191082,-0.059058051556349,39952,16745,448,-4601,1.02325749397278 +16537,-2.62408852577209,-0.37075799703598,-0.054372366517782,39952,11497,-1049,-4045,1.02766108512878 +16539,-2.54646873474121,-0.359690129756927,-0.049188561737537,39952,14375,-142,-4503,1.02781021595001 +16541,-2.46282720565796,-0.333240240812302,-0.043122217059136,39952,8503,-2212,-3985,1.03235244750977 +16543,-2.37283778190613,-0.30608531832695,-0.034055285155773,39952,11595,-2034,-4316,1.04370439052582 +16545,-2.27532529830933,-0.285125970840454,-0.02558539621532,39952,5715,-2388,-3878,1.05305171012878 +16547,-2.16772603988647,-0.261278390884399,-0.023620471358299,39952,7847,-2410,-4183,1.06111586093903 +16549,-2.05469107627869,-0.238187864422798,-0.024905053898692,39952,2245,-3113,-3885,1.0607396364212 +16551,-1.94572579860687,-0.204688176512718,-0.024215567857027,39952,4881,-3942,-4162,1.05342638492584 +16553,-1.83228623867035,-0.182016342878342,-0.020527366548777,39952,-266,-3814,-3865,1.04637265205383 +16555,-1.71501159667969,-0.152276664972305,-0.017092362046242,39952,1178,-4465,-4048,1.03786957263947 +16557,-1.59375667572021,-0.124744333326817,-0.013225539587438,39952,-3644,-4933,-3822,1.03520560264587 +16559,-1.47573280334473,-0.095853857696056,-0.012366983108223,39952,-2209,-5282,-3953,1.02936685085297 +16561,-1.36406373977661,-0.072994329035282,-0.010047108866274,39952,-5755,-5317,-3805,1.02946698665619 +16563,-1.25386822223663,-0.06290028244257,-0.00485494825989,39952,-4800,-4448,-3842,1.02604818344116 +16565,-1.14344167709351,-0.041238054633141,0.001072796992958,39952,-8430,-5676,-3732,1.02908039093018 +16567,-1.03852987289429,-0.017573824152351,0.004637594800442,39952,-7569,-6142,-3691,1.03223860263824 +16569,-0.943778038024902,0.012252692133188,0.008243780583143,39952,-9868,-7036,-3683,1.03306353092194 +16571,-0.848424851894379,0.031169151887298,0.007766085676849,39952,-9719,-6610,-3606,1.03396022319794 +16573,-0.758097290992737,0.04978059232235,0.005315579939634,39952,-11997,-6801,-3701,1.03390729427338 +16575,-0.676248967647553,0.058883439749479,0.004901651758701,39952,-11377,-6397,-3610,1.03843057155609 +16577,-0.60038959980011,0.067872010171414,0.008311381563544,39952,-13085,-6415,-3678,1.03877305984497 +16579,-0.532051801681519,0.083509989082813,0.012314693070948,39952,-12646,-7311,-3495,1.03822433948517 +16581,-0.470321089029312,0.093225128948689,0.013213102705777,39952,-13865,-6885,-3639,1.03789806365967 +16583,-0.412924498319626,0.110020071268082,0.014174089767039,39952,-13751,-7880,-3442,1.03958380222321 +16585,-0.357999622821808,0.112930811941624,0.015967175364494,39952,-14969,-6747,-3615,1.03703451156616 +16587,-0.312581896781921,0.119172155857086,0.017548155039549,39952,-14521,-7336,-3387,1.03006792068481 +16589,-0.273804128170013,0.107234634459019,0.015939695760608,39952,-15045,-5671,-3608,1.02326655387878 +16591,-0.253008961677551,0.108062796294689,0.012586488388479,39952,-13756,-6836,-3450,1.01787436008453 +16593,-0.237624675035477,0.105726562440395,0.012325146235526,39952,-13939,-6402,-3628,1.01706695556641 +16595,-0.223778247833252,0.097312115132809,0.012176531367004,39952,-13776,-6061,-3461,1.01444137096405 +16597,-0.220751941204071,0.092674121260643,0.010232131928206,39952,-13356,-6111,-3637,1.01185166835785 +16599,-0.223933383822441,0.087136454880238,0.006685208529234,39952,-12607,-6160,-3531,1.00891327857971 +16601,-0.227766528725624,0.083271138370037,0.002833559410647,39952,-12823,-6087,-3684,1.00623083114624 +16603,-0.228687882423401,0.061480425298214,0.003777972888201,39952,-12748,-4630,-3588,1.00407826900482 +16605,-0.246044173836708,0.048014912754297,0.004871673416346,39952,-11648,-4939,-3668,1.00246644020081 +16607,-0.274868488311768,0.035416826605797,0.006208484992385,39952,-10055,-4903,-3583,1.00319385528564 +16609,-0.298958539962769,0.01723993010819,0.006807113531977,39952,-10443,-4192,-3652,1.00055086612701 +16611,-0.330244988203049,0.005764027126133,0.004099612589926,39952,-9015,-4542,-3635,0.998881816864014 +16613,-0.369377970695496,-0.013110187835991,-2.93295233859681E-05,39952,-8367,-3728,-3699,0.997931957244873 +16615,-0.413861662149429,-0.023529879748821,-0.003194380318746,39952,-6710,-4164,-3750,0.999265134334564 +16617,-0.452740430831909,-0.042271435260773,-0.007159641478211,39952,-7163,-3328,-3749,1.00269222259521 +16619,-0.495319277048111,-0.054619934409857,-0.011040032841265,39952,-5465,-3526,-3877,1.00183057785034 +16621,-0.54449075460434,-0.066800907254219,-0.015580664388836,39952,-5041,-3441,-3811,0.99867981672287 +16623,-0.600531697273254,-0.079063653945923,-0.016352148726583,39952,-2689,-3119,-3970,0.993599593639374 +16625,-0.656087815761566,-0.092650443315506,-0.016401544213295,39952,-2863,-2952,-3823,0.994013965129852 +16627,-0.703583657741547,-0.119293235242367,-0.018341878429055,39952,-1486,-1402,-4043,0.995203256607056 +16629,-0.755303025245667,-0.141552701592445,-0.018516322597861,39952,-1546,-1592,-3845,0.993027448654175 +16631,-0.810898303985596,-0.163141742348671,-0.018460527062416,39952,1022,-1010,-4100,0.99434906244278 +16633,-0.862170219421387,-0.171718597412109,-0.02049171552062,39952,173,-2083,-3868,0.991829097270966 +16635,-0.904138565063477,-0.189612358808517,-0.020117262378335,39952,1798,-789,-4159,0.986120402812958 +16637,-0.948983669281006,-0.210718080401421,-0.016703145578504,39952,1222,-557,-3852,0.983785688877106 +16639,-0.994167625904083,-0.230595707893372,-0.013579098507762,39952,3771,99,-4141,0.983001172542572 +16641,-1.03959333896637,-0.250679612159729,-0.010021298192442,39952,2870,31,-3817,0.983499705791473 +16643,-1.0794084072113,-0.262646168470383,-0.005122701171786,39952,5107,139,-4093,0.986254274845123 +16645,-1.11755776405334,-0.256850332021713,-0.002945159561932,39952,3819,-1631,-3780,0.988549411296844 +16647,-1.14585208892822,-0.261836439371109,-0.005182729568332,39952,5727,-277,-4108,0.993201196193695 +16649,-1.17369771003723,-0.267315864562988,-0.00634226296097,39952,4270,-572,-3814,0.995060801506042 +16651,-1.1900429725647,-0.288071036338806,-0.006501542404294,39952,5981,1383,-4170,0.995162487030029 +16671,-1.13160276412964,-0.220825746655464,-0.002857814310119,39952,4128,-1573,-4126,1.02789235115051 +16673,-1.10922801494598,-0.207994699478149,0.000315004581353,39952,2225,-2118,-3837,1.02703773975372 +16675,-1.07979238033295,-0.210138723254204,0.007436018437147,39952,3336,-608,-4006,1.0227872133255 +16677,-1.043452501297,-0.200817123055458,0.013327520340681,39952,652,-1887,-3755,1.01756358146667 +16679,-1.00131022930145,-0.187289446592331,0.017900034785271,39952,1517,-2015,-3866,1.01111853122711 +16681,-0.965227901935577,-0.158682495355606,0.020117042586207,39952,-111,-3798,-3714,1.00803649425507 +16683,-0.929836869239807,-0.125775411725044,0.021608037874103,39952,1170,-4332,-3750,1.01345384120941 +16685,-0.88635128736496,-0.096645392477512,0.022296721115708,39952,-1462,-4676,-3701,1.01846182346344 +16687,-0.837237060070038,-0.073048174381256,0.021854402497411,39952,-1026,-4476,-3680,1.01695847511292 +16689,-0.786178648471832,-0.065002866089344,0.022753391414881,39952,-3171,-3594,-3698,1.01495170593262 +16691,-0.744708061218262,-0.04861618578434,0.024924295023084,39952,-1738,-4328,-3612,1.0124591588974 +16693,-0.704012334346771,-0.039303094148636,0.028097521513701,39952,-3379,-4037,-3660,1.0117529630661 +16695,-0.658157110214233,-0.022183274850249,0.028725488111377,39952,-3260,-4796,-3529,1.00842356681824 +16697,-0.611095011234283,-0.007190210744739,0.032722484320402,39952,-4980,-4899,-3624,1.01233530044556 +16699,-0.566066324710846,0.003633136861026,0.03327127546072,39952,-4541,-4778,-3436,1.01174700260162 +16701,-0.527271330356598,0.022365909069777,0.029033083468676,39952,-5445,-5601,-3644,1.01235377788544 +16703,-0.49680957198143,0.039669238030911,0.027662463486195,39952,-4498,-5857,-3445,1.0163676738739 +16705,-0.466168701648712,0.055560193955898,0.032219961285591,39952,-5623,-5902,-3616,1.01956236362457 +16707,-0.426586151123047,0.055740192532539,0.036159455776215,39952,-6195,-4913,-3317,1.02077972888947 +16709,-0.393104702234268,0.056237131357193,0.035803679376841,39952,-6792,-4842,-3583,1.0183596611023 +16711,-0.366471111774445,0.053955096751452,0.036517210304737,39952,32767,17624,-3307,1.01741468906403 +16713,-0.335209101438522,0.053604271262884,0.035251531749964,39952,4770,-1000,-3578,1.01565515995026 +16715,-0.304640620946884,0.059928115457296,0.032876495271921,39952,4827,-1681,-3333,1.01251196861267 +16717,-0.279793560504913,0.066016353666782,0.030978349968791,39952,4584,-1636,-3599,1.00613570213318 +16719,-0.264410853385925,0.079155325889587,0.030589614063501,39952,5410,-2477,-3325,1.00276911258698 +16721,-0.239318504929543,0.080176874995232,0.027865819633007,39952,4119,-1481,-3612,1.00157189369202 +16723,-0.209117412567139,0.094040878117085,0.023193944245577,39952,3575,-2778,-3382,0.998932719230652 +16725,-0.173176348209381,0.099927581846714,0.018789691850543,39952,2501,-2124,-3666,0.999368369579315 +16727,-0.134482353925705,0.112105414271355,0.017232161015272,39952,1837,-2970,-3418,0.999017477035522 +16729,-0.091706693172455,0.128701090812683,0.018308945000172,39952,915,-3325,-3662,0.99815285205841 +16731,-0.043904814869166,0.137865245342255,0.017342438921332,39952,-248,-3200,-3371,0.997150599956512 +16733,0.005534666124731,0.147495746612549,0.016017390415073,39952,-928,-3129,-3668,0.999985992908478 +16735,0.058503795415163,0.159973159432411,0.020567236468196,39952,-2272,-3836,-3294,1.00470530986786 +16737,0.105669796466827,0.186643555760384,0.027278319001198,39952,-2220,-4956,-3580,1.00859522819519 +16739,0.149123921990395,0.201064199209213,0.03288171812892,39952,-3102,-4685,-3083,1.01407492160797 +16741,0.194789364933968,0.204341873526573,0.030375501140952,39952,-3452,-3596,-3544,1.01789844036102 +16743,0.244961097836494,0.204055726528168,0.023505939170718,39952,-5224,-3743,-3175,1.02331733703613 +16745,0.30147659778595,0.207151308655739,0.01994021050632,39952,-5867,-3687,-3602,1.01817286014557 +16747,0.351348042488098,0.225009500980377,0.021138079464436,39952,-7058,-5449,-3162,1.0135360956192 +16749,0.394979864358902,0.236199229955673,0.021510571241379,39952,29618,-4757,-3577,1.00818049907684 +16751,0.434110790491104,0.256944179534912,0.015655003488064,39952,-1715,-6257,-3171,1.00025510787964 +16753,0.474463552236557,0.268562883138657,0.015497996471822,39952,-1422,-5342,-3604,0.999109387397766 +16755,0.506681978702545,0.284224301576614,0.016640767455101,39952,-2541,-6427,-3112,1.00273239612579 +16757,0.541089236736298,0.290285170078278,0.013979369774461,39952,-2121,-5357,-3599,1.01103174686432 +16759,0.591892778873444,0.286552876234055,0.008757370524108,39952,-5438,-5182,-3190,1.0085905790329 +16761,0.647264719009399,0.297035455703735,0.007758491206914,39952,-5355,-5875,-3627,1.00654745101929 +16763,0.699672937393189,0.312211275100708,0.012538047507405,39952,-7543,-7055,-3101,1.00833237171173 +16765,0.744516611099243,0.32959109544754,0.01234979275614,39952,-6258,-6953,-3580,1.01109790802002 +16767,0.790319323539734,0.321857422590256,0.011897563003004,39952,-8829,-5686,-3085,1.01534581184387 +16769,0.826651811599731,0.322736352682114,0.011931669898331,39952,-7133,-5793,-3566,1.01572263240814 +16771,0.861085116863251,0.324613302946091,0.007721845526248,39952,-9488,-6548,-3121,1.0158725976944 +16773,0.895770013332367,0.325949847698212,0.004456918686628,39952,-8350,-5996,-3602,1.01146590709686 +16775,0.921210289001465,0.324225872755051,0.0046157669276,39952,-10171,-6414,-3149,1.01255178451538 +16777,0.946075737476349,0.309066534042358,0.005123144481331,39952,-8740,-4698,-3583,1.01432013511658 +16779,0.972809374332428,0.305542796850205,0.003851864719763,39952,-11478,-6105,-3175,1.01140439510345 +16781,0.998998939990997,0.298498570919037,0.003969849552959,39952,-9992,-5246,-3578,1.00673413276672 +16783,1.01339435577393,0.300302147865295,0.004863016773015,39952,-11662,-6516,-3163,1.00295221805573 +16785,1.02244007587433,0.294075399637222,0.005933446809649,39952,-9521,-5357,-3551,1.00287103652954 +16787,1.0259575843811,0.280196338891983,0.003301144111902,39952,24548,-5176,-3200,0.999046266078949 +16789,1.02939796447754,0.26603627204895,-0.002492953557521,39952,-3558,-4495,-3597,0.996178984642029 +16791,1.03155636787415,0.255573689937592,-0.006052052602172,39952,-5817,-5142,-3334,0.996634781360626 +16793,1.03048050403595,0.254780352115631,-0.008413057774305,39952,-3625,-5391,-3628,0.997671723365784 +16795,1.03151249885559,0.247736737132072,-0.013033759780228,39952,-6113,-5370,-3422,1.0010769367218 +16797,1.034872174263,0.243445038795471,-0.018943056464195,39952,-4385,-5077,-3693,1.00378775596619 +16799,1.04239058494568,0.235909879207611,-0.019814750179648,39952,-7123,-5241,-3514,1.00439321994782 +16801,1.04680502414703,0.229318842291832,-0.019023129716516,39952,-5017,-4805,-3688,1.00124096870422 +16803,1.04876708984375,0.216407671570778,-0.020298756659031,39952,-7211,-4619,-3542,0.995774507522583 +16805,1.05348789691925,0.194645583629608,-0.021074203774333,39952,-5526,-3306,-3698,0.993207931518555 +16819,1.02731776237488,0.119777500629425,-0.031422708183527,39952,-7807,-2990,-3787,1.00323748588562 +16821,1.01978933811188,0.104127086699009,-0.03131140768528,39952,-5747,-2674,-3765,1.00944590568542 +16823,1.00774681568146,0.085512712597847,-0.032264661043882,39952,-7483,-2391,-3836,1.0098774433136 +16825,0.99040937423706,0.080923184752464,-0.031403064727783,39952,-5008,-3164,-3768,1.00891399383545 +16827,0.977963030338287,0.078302994370461,-0.028506606817246,39952,-7350,-3436,-3804,1.00848913192749 +16829,0.970517337322235,0.068667508661747,-0.029473183676601,39952,-5805,-2652,-3757,1.0036906003952 +16831,0.957713305950165,0.063614584505558,-0.032916732132435,39952,-7367,-3051,-3874,0.996726512908936 +16833,0.940154373645782,0.048431877046824,-0.036453362554312,39952,-5014,-1984,-3809,0.992862284183502 +16835,0.918196678161621,0.04820042848587,-0.034295041114092,39952,-6435,-3175,-3911,0.98827475309372 +16837,0.90220445394516,0.041525602340698,-0.033818949013949,39952,-4936,-2509,-3795,0.991707980632782 +16839,0.885584831237793,0.039027467370033,-0.040710579603911,39952,-6631,-2881,-4000,0.991657495498657 +16841,0.86788821220398,0.04129621013999,-0.042914785444737,39952,-4663,-3158,-3864,0.994137942790985 +16843,0.851910650730133,0.038890674710274,-0.040443625301123,39952,-6456,-2893,-4004,0.996311008930206 +16845,0.834245681762695,0.03041978739202,-0.040498457849026,39952,-4509,-2244,-3853,0.991712689399719 +16847,0.813970327377319,0.016480877995491,-0.042078360915184,39952,-5850,-1701,-4051,0.987177729606628 +16849,0.785961806774139,0.016222286969423,-0.046620287001133,39952,-3388,-2628,-3902,0.982779026031494 +16851,0.763533234596252,0.016551710665226,-0.046290673315525,39952,-5173,-2720,-4108,0.980190992355347 +16853,0.740200996398926,0.01933952793479,-0.043834008276463,39952,-3357,-2890,-3890,0.977104842662811 +16855,0.718418598175049,0.011749211698771,-0.042655561119318,39952,-4763,-2083,-4077,0.978187203407288 +16857,0.694466173648834,0.007782514207065,-0.043067056685686,39952,-2928,-2239,-3892,0.97846257686615 +16859,0.672808706760407,0.016086721792817,-0.043160952627659,39952,-4287,-3294,-4087,0.98441880941391 +16861,0.657247424125671,0.018865089863539,-0.042233157902956,39952,-3248,-2883,-3893,0.989929735660553 +16863,0.63199770450592,0.020682968199253,-0.042904075235128,39952,32457,-2896,-4088,0.993585765361786 +16865,0.60489022731781,0.015673998743296,-0.039681889116764,39952,4186,-2281,-3883,0.995012640953064 +16867,0.586793959140778,0.021277569234371,-0.035890959203243,39952,2518,-3175,-4012,0.99240255355835 +16869,0.573368787765503,0.034028146415949,-0.034158766269684,39952,3503,-3818,-3851,0.98964250087738 +16871,0.55933153629303,0.041725866496563,-0.034909218549728,39952,2524,-3655,-3990,0.986721456050873 +16873,0.555212914943695,0.052884202450514,-0.040338113903999,39952,2953,-3984,-3898,0.98295384645462 +16875,0.560410559177399,0.055783104151487,-0.042499512434006,39952,986,-3551,-4074,0.981854498386383 +16877,0.565245091915131,0.059152625501156,-0.039087913930416,39952,2022,-3532,-3896,0.97664886713028 +16879,0.575498282909393,0.057507947087288,-0.03402453660965,39952,226,-3272,-3979,0.981226682662964 +16881,0.592342793941498,0.052965890616179,-0.029661171138287,39952,617,-2894,-3835,0.988005995750427 +16883,0.608558654785156,0.064624980092049,-0.02731622196734,39952,-890,-4365,-3900,0.995326042175293 +16885,0.625480532646179,0.075203806161881,-0.025358421728015,39952,-33,-4317,-3809,1.00236427783966 +16887,0.649218618869782,0.083847969770432,-0.027829071506858,39952,-2283,-4487,-3895,1.00614309310913 +16889,0.67998880147934,0.080411650240421,-0.029234476387501,39952,-2001,-3419,-3839,1.0125640630722 +16891,0.707290887832642,0.083111122250557,-0.031369525939226,39952,-3703,-4083,-3941,1.01309943199158 +16893,0.737058758735657,0.096674159169197,-0.029700752347708,39952,-2974,-4901,-3845,1.01451802253723 +16895,0.772314488887787,0.107286430895329,-0.024921866133809,39952,-5562,-5077,-3853,1.01044750213623 +16897,0.79973030090332,0.114377126097679,-0.02138495631516,39952,-3961,-4734,-3790,1.00520670413971 +16899,0.826169490814209,0.108847670257092,-0.02172121219337,39952,-6062,-3985,-3818,1.00198125839233 +16901,0.846482157707214,0.118739150464535,-0.02192984521389,39952,-4405,-5040,-3795,1.00221216678619 +16903,0.872201442718506,0.117540404200554,-0.023063253611326,39952,-7033,-4477,-3831,1.00607526302338 +16905,0.896200060844421,0.123480223119259,-0.023735575377941,39952,-5685,-4872,-3809,1.01084578037262 +16907,0.916913688182831,0.123864062130451,-0.019178278744221,39952,-7708,-4732,-3785,1.01934909820557 +16909,0.940649926662445,0.117972813546658,-0.016845943406224,39952,-6629,-3993,-3763,1.01838064193726 +16911,0.965606868267059,0.121713608503342,-0.016647625714541,39952,-9143,-4985,-3760,1.01579558849335 +16913,0.988179326057434,0.126658350229263,-0.019086299464107,39952,-7579,-4942,-3778,1.01208746433258 +16915,1.00230705738068,0.14211793243885,-0.021928906440735,39952,-9328,-6214,-3812,1.00884544849396 +16917,1.01527404785156,0.144977375864983,-0.02268447726965,39952,-7652,-5113,-3804,1.00609791278839 +16919,1.03148877620697,0.142808094620705,-0.024307332932949,39952,-10336,-5030,-3844,0.999198794364929 +16921,1.04535794258118,0.135635703802109,-0.024875046685338,39952,-8537,-4321,-3821,1.00187003612518 +16923,1.05808532238007,0.122118555009365,-0.026630129665136,39952,-10903,-3933,-3889,1.00245463848114 +16925,1.06176245212555,0.121915020048618,-0.026560109108687,39952,-8446,-4674,-3835,1.00307548046112 +16927,1.05834436416626,0.12708654999733,-0.022407129406929,39952,-10137,-5393,-3841,1.00954961776733 +16929,1.05062639713287,0.140745267271996,-0.020367996767163,39952,-7873,-5989,-3794,1.00922548770905 +16931,1.05045688152313,0.135611101984978,-0.0199911352247,39952,-10641,-4843,-3813,1.00908982753754 +16933,1.04816079139709,0.121439695358276,-0.025714352726936,39952,-8629,-3774,-3832,1.00049757957459 +16935,1.03643214702606,0.115892633795738,-0.033951677381992,39952,-9994,-4550,-3993,0.99683940410614 +16937,1.02362561225891,0.109111785888672,-0.037800535559654,39952,-7925,-4174,-3919,0.995556116104126 +16939,1.00442373752594,0.105607956647873,-0.038709077984095,39952,-9348,-4586,-4061,0.997952222824097 +16941,0.985857903957367,0.090541273355484,-0.03664692863822,39952,-7363,-3359,-3916,1.00064206123352 +16943,0.969587862491608,0.088867612183094,-0.035037901252508,39952,-9377,-4488,-4033,1.00035357475281 +16945,0.952571272850037,0.077821739017963,-0.036676175892353,39952,-7375,-3502,-3922,1.00090682506561 +16947,0.924818813800812,0.071524761617184,-0.039533536881209,39952,-8177,-3904,-4102,0.999349355697632 +16949,0.895412564277649,0.068634241819382,-0.038489315658808,39952,-6025,-3983,-3940,1.00032794475555 +16951,0.868523180484772,0.068123109638691,-0.036961708217859,39952,-7662,-4284,-4081,1.0018904209137 +16953,0.842935025691986,0.074654489755631,-0.034494683146477,39952,-5880,-4772,-3918,1.00636696815491 +16955,0.822598040103912,0.061894357204437,-0.03617437928915,39952,-7711,-3327,-4081,1.00847053527832 +16957,0.802036583423615,0.045627348124981,-0.040428768843412,39952,-5968,-2745,-3965,1.00578355789185 +16959,0.771552503108978,0.041567418724299,-0.036700092256069,39952,-6467,-3638,-4103,1.0089647769928 +16961,0.739656686782837,0.043930765241385,-0.033262401819229,39952,-4557,-4070,-3922,1.013711810112 +16963,0.715826511383056,0.04198807105422,-0.035990875214338,39952,-6330,-3811,-4101,1.01569890975952 +16965,0.68875116109848,0.036040030419827,-0.037263844162226,39952,-4445,-3375,-3955,1.01236271858215 +16967,0.652008235454559,0.030457342043519,-0.036727130413056,39952,-4623,-3374,-4121,1.01476728916168 +16969,0.615157306194305,0.022478075698018,-0.039023462682963,39952,-2934,-3044,-3974,1.01387333869934 +16971,0.59104061126709,0.014068786986172,-0.036484077572823,39952,-4763,-2911,-4132,1.01234126091003 +16973,0.565805375576019,0.005785020533949,-0.032545369118452,39952,-3277,-2784,-3936,1.00627279281616 +16975,0.542206704616547,-0.005964011885226,-0.030796410515905,39952,-4200,-2348,-4079,1.00123107433319 +16977,0.514922916889191,-0.012689902447164,-0.029692754149437,39952,-2595,-2624,-3922,0.99789309501648 +16979,0.492728978395462,-0.017537795007229,-0.025294955819845,39952,-3680,-2645,-4024,1.00088286399841 +16981,0.47221377491951,-0.025261713191867,-0.018647437915206,39952,-2641,-2360,-3851,1.0074120759964 +16983,0.444115340709686,-0.032890241593123,-0.017125761136413,39952,-2629,-2178,-3938,1.00553357601166 +16985,0.426141172647476,-0.04428081959486,-0.015139806084335,39952,-2314,-1804,-3831,0.998851656913757 +16987,0.407172232866287,-0.045207485556603,-0.010375678539276,39952,-2823,-2434,-3866,0.990154027938843 +16989,0.384345084428787,-0.043957985937595,-0.006699463818222,39952,-1503,-2688,-3776,0.985550165176392 +16991,0.361679434776306,-0.040196511894465,-0.007695765700191,39952,-1947,-2819,-3835,0.982433199882507 +16993,0.351793736219406,-0.040744986385107,-0.008712752722204,39952,-2080,-2581,-3792,0.98468816280365 +16995,0.34829980134964,-0.043952096253634,-0.010081117041409,39952,-3206,-2240,-3866,0.989088714122772 +16997,0.337243795394897,-0.045197147876024,-0.012082763947547,39952,-1897,-2441,-3818,0.993418335914612 +16999,0.323934018611908,-0.054387599229813,-0.008242128416896,39952,-2218,-1616,-3851,1.00336456298828 +17001,0.312744230031967,-0.046029791235924,-0.004716109950095,39952,-1637,-3087,-3770,1.01335787773132 +17003,0.314506232738495,-0.048217855393887,-0.005091498140246,39952,-3256,-2187,-3813,1.02501440048218 +17005,0.310682445764542,-0.043370205909014,-0.002872231882066,39952,-2234,-2846,-3759,1.02695178985596 +17007,0.303592175245285,-0.039639446884394,0.005068593192846,39952,-2551,-2725,-3692,1.02967154979706 +17009,0.299306422472,-0.036847997456789,0.007278383243829,39952,-2135,-2768,-3689,1.02396202087402 +17011,0.301783293485641,-0.024848824366927,0.004184691235423,39952,-3300,-3541,-3697,1.01289820671082 +17013,0.307193964719772,-0.025058783590794,0.004797063302249,39952,-3039,-2706,-3706,1.00696539878845 +17015,0.311526715755463,-0.016425373032689,0.009875934571028,39952,-3683,-3418,-3627,1.00566399097443 +17017,0.321158617734909,-0.015787739306688,0.012934301048517,39952,-3643,-2886,-3650,1.00745248794556 +17019,0.324996501207352,-0.012472438625991,0.008970405906439,39952,-3965,-3085,-3636,1.00550997257233 +17021,0.33085498213768,0.00054139085114,0.012082974426448,39952,-3619,-3994,-3655,1.01068139076233 +17023,0.335005640983582,0.011955946683884,0.018623391166329,39952,-4256,-4046,-3514,1.01372563838959 +17025,0.341326415538788,0.01560337562114,0.020053014159203,39952,-3914,-3537,-3597,1.01538455486298 +17027,0.352026641368866,0.012334140017629,0.021735232323408,39952,-5114,-2998,-3474,1.02250492572784 +17029,0.360608130693436,0.023932164534927,0.022032497450709,39952,-4473,-4224,-3580,1.02483570575714 +17031,0.373377501964569,0.024862976744771,0.019896302372217,39952,-5739,-3511,-3489,1.02178108692169 +17045,0.409647911787033,0.054064273834229,0.024657445028424,39952,-5107,-4177,-3549,0.995323479175568 +17047,0.408015459775925,0.052549492567778,0.028151620179415,39952,-5822,-3810,-3373,0.992038786411285 +17049,0.409534007310867,0.057084862142801,0.029691196978092,39952,32767,-4242,-3510,0.989636778831482 +17051,0.408769398927689,0.059310149401426,0.031361933797598,40095,22193,-4212,-3328,0.989556789398193 +17053,0.408493220806122,0.067272037267685,0.031810309737921,40095,23001,-4654,-3490,0.988497912883758 +17055,0.40721720457077,0.067317761480808,0.030252151191235,40095,22370,-4218,-3335,0.992320656776428 +17057,0.415333449840546,0.056843809783459,0.027507044374943,40095,22425,-3209,-3515,0.991551280021668 +17059,0.429174333810806,0.053182661533356,0.025869894772768,40095,21053,-3749,-3385,0.994893431663513 +17061,0.462735831737518,0.051338620483875,0.025365944951773,40095,20035,-3767,-3525,1.00058078765869 +17063,0.508765876293182,0.066892147064209,0.026529176160693,40095,17550,-5372,-3371,1.00871098041534 +17065,0.568997263908386,0.074757218360901,0.023595815524459,40095,16675,-4825,-3533,1.01253592967987 +17067,0.636086642742157,0.088157132267952,0.020175904035568,40095,14026,-5594,-3438,1.01640212535858 +17069,0.711318671703339,0.091905407607555,0.020529799163342,40095,13574,-4813,-3550,1.02130281925201 +17071,0.794394671916962,0.098713032901287,0.019797559827566,40095,10285,-5330,-3438,1.02258360385895 +17073,0.891325235366821,0.102761059999466,0.020078834146261,40095,9376,-5031,-3550,1.02380561828613 +17075,0.999915659427643,0.106666959822178,0.024650651961565,40095,5008,-5294,-3378,1.02281212806702 +17077,1.11710822582245,0.115724451839924,0.025652686133981,40095,4527,-5621,-3507,1.02754616737366 +17079,1.2410843372345,0.12471966445446,0.025481583550572,40095,-220,-5997,-3363,1.03770363330841 +17081,1.36216056346893,0.141308426856995,0.031183995306492,40095,460,-6581,-3465,1.04387545585632 +17083,1.48513162136078,0.145264223217964,0.03843504562974,40095,-4430,-6027,-3206,1.04823744297028 +17085,1.60591161251068,0.157900989055634,0.040071342140436,40095,-3402,-6600,-3397,1.05301928520203 +17087,1.73210394382477,0.158693164587021,0.0427107475698,40095,-9119,-6081,-3152,1.06087362766266 +17089,1.85806727409363,0.159305289387703,0.043724704533815,40095,-7898,-5827,-3365,1.05913054943085 +17091,1.98296558856964,0.168603301048279,0.047864578664303,40095,-13668,-6930,-3089,1.05734300613403 +17093,2.09873175621033,0.180955693125725,0.053152620792389,40095,-11249,-7054,-3292,1.05273354053497 +17095,2.20306158065796,0.201420187950134,0.053516335785389,40095,-16451,-8354,-3021,1.04506754875183 +17097,2.30848550796509,0.204433500766754,0.051247783005238,40095,-14254,-6814,-3296,1.04331004619598 +17099,2.41415071487427,0.209451779723167,0.047926049679518,40095,-20754,-7476,-3088,1.0422477722168 +17101,2.51626181602478,0.208968535065651,0.046934902667999,40095,-17838,-6726,-3318,1.04267764091492 +17103,2.60683274269104,0.21661864221096,0.047725349664688,40095,-23677,-7881,-3094,1.03704726696014 +17105,2.69123554229736,0.216814339160919,0.052676513791084,40095,-20015,-6989,-3272,1.04050529003143 +17107,2.76485466957092,0.212934553623199,0.055045444518328,40095,-25989,-7087,-3011,1.04002296924591 +17109,2.82087469100952,0.218777403235435,0.052602782845497,40095,-20855,-7521,-3264,1.04127788543701 +17111,2.86432123184204,0.215014159679413,0.046748265624046,40095,-26471,-7223,-3113,1.03932344913483 +17113,2.90531492233276,0.216951057314873,0.045003615319729,40095,-22056,-7315,-3311,1.03430819511414 +17115,2.94201922416687,0.211676150560379,0.043981052935124,40095,-28332,-7170,-3151,1.02998554706573 +17117,2.96512913703918,0.214230537414551,0.041364967823029,40095,-22743,-7421,-3330,1.0289009809494 +17119,2.97357511520386,0.213029637932777,0.035185053944588,40095,-27937,-7588,-3263,1.02734959125519 +17121,2.96844077110291,0.211255624890327,0.030875496566296,40095,-21901,-7170,-3399,1.02601182460785 +17123,2.95322585105896,0.213147461414337,0.028244744986296,40095,-27026,-7920,-3354,1.02447974681854 +17125,2.93274974822998,0.210192650556564,0.025873990729451,40095,-21420,-7175,-3432,1.02189898490906 +17127,2.90454077720642,0.206736177206039,0.020480152219534,40095,-26415,-7528,-3453,1.0203685760498 +17129,2.86426186561584,0.190653637051582,0.014125754125416,40095,-20133,-6054,-3512,1.02368605136871 +17131,2.81628942489624,0.180216178297996,0.012933919206262,40095,-24656,-6671,-3541,1.02546155452728 +17133,2.76363039016724,0.172825276851654,0.011444456875324,40095,-18884,-6507,-3532,1.0321741104126 +17135,2.71014928817749,0.162737235426903,0.010571519844234,40095,-23593,-6490,-3570,1.03035748004913 +17137,2.64410376548767,0.154002547264099,0.007644784636796,40095,-17250,-6217,-3559,1.01950359344482 +17139,2.56559610366821,0.146481484174728,0.001972655765712,40095,-20450,-6486,-3671,1.02085375785828 +17141,2.47362518310547,0.144766628742218,-0.00227424222976,40095,-13926,-6658,-3630,1.02336442470551 +17143,2.37676811218262,0.136680692434311,-0.003841048805043,40095,-16992,-6350,-3743,1.02518403530121 +17145,2.28016328811645,0.122998990118504,-0.004357218276709,40095,-11716,-5555,-3648,1.02787911891937 +17147,2.17822694778442,0.11957672983408,-0.010976747609675,40095,-14242,-6464,-3825,1.02320182323456 +17149,2.07310128211975,0.109233319759369,-0.019290992990136,40095,-8945,-5654,-3756,1.02359974384308 +17151,1.9569343328476,0.099783763289452,-0.024555383250117,40095,-10393,-5761,-3980,1.02181792259216 +17153,1.84436917304993,0.078385591506958,-0.02776806242764,40095,-5845,-4467,-3821,1.01742947101593 +17155,1.74031436443329,0.055503439158201,-0.028670508414507,40095,-8402,-4117,-4005,1.01019275188446 +17157,1.62590396404266,0.04057477414608,-0.031552582979202,40095,-3197,-4416,-3854,0.999070405960083 +17159,1.50782907009125,0.018963260576129,-0.028645811602473,40095,-4175,-3633,-3984,0.997504770755768 +17161,1.38426220417023,0.004205435980111,-0.030297258868814,40095,411,-3917,-3850,0.991945564746857 +17163,1.27597343921661,-0.003359822789207,-0.031403779983521,40095,-1577,-4278,-4005,0.989267408847809 +17165,1.16714441776276,-0.01138333696872,-0.031639032065868,40327,2059,-4176,-3865,0.987004101276398 +17167,1.05775678157806,-0.034291107207537,-0.034279961138964,40327,1667,-2667,-4019,0.985767006874084 +17169,0.960775792598724,-0.060345597565174,-0.037557225674391,40327,3854,-2167,-3911,0.989126324653626 +17171,0.866796970367431,-0.079046666622162,-0.041239537298679,40327,3388,-2222,-4068,0.99667477607727 +17173,0.781928777694702,-0.094840511679649,-0.041222881525755,40327,5320,-2372,-3941,1.00646686553955 +17175,0.706303775310516,-0.103421799838543,-0.038338247686625,40327,4494,-2512,-4017,1.0090434551239 +17177,0.628900110721588,-0.103543378412724,-0.036887191236019,40327,6823,-3323,-3915,1.01592683792114 +17179,0.565332293510437,-0.116566032171249,-0.034124944359064,40327,5811,-1932,-3958,1.02421486377716 +17181,0.501759946346283,-0.122601889073849,-0.036636102944613,40327,7564,-2574,-3916,1.03106451034546 +17183,0.452921867370606,-0.129690274596214,-0.040047574788332,40327,6522,-2084,-4018,1.04244232177734 +17185,0.408189058303833,-0.136382579803467,-0.04155569896102,40327,7516,-2269,-3953,1.04544842243195 +17187,0.364516228437424,-0.144307166337967,-0.044129014015198,40327,7554,-1726,-4056,1.04574012756348 +17189,0.329094439744949,-0.156389504671097,-0.045949090272188,40327,7981,-1530,-3987,1.04344916343689 +17191,0.305562436580658,-0.165563181042671,-0.046779613941908,40327,7066,-1226,-4072,1.04200887680054 +17193,0.289385139942169,-0.168896749615669,-0.050426535308361,40327,7194,-1901,-4021,1.0398371219635 +17195,0.276769489049911,-0.169469341635704,-0.048463482409716,40327,6775,-1706,-4091,1.03085172176361 +17197,0.269079566001892,-0.166981250047684,-0.043643783777952,40327,6910,-2268,-3978,1.02205622196198 +17199,0.273376375436783,-0.165115147829056,-0.043550029397011,40327,5657,-1878,-4040,1.01523113250732 +17201,0.285113245248795,-0.160959750413895,-0.042539797723293,40327,5323,-2398,-3973,1.01328063011169 +17203,0.301312983036041,-0.152641728520393,-0.040044877678156,40327,4379,-2471,-4013,1.01765251159668 +17205,0.326682537794113,-0.142658725380898,-0.036094181239605,40327,3771,-3008,-3931,1.02595734596252 +17207,0.356257855892181,-0.125712275505066,-0.037573043256998,40327,2535,-3467,-4010,1.03169548511505 +17209,0.390211462974548,-0.116945520043373,-0.041113287210465,40327,2240,-3233,-3969,1.03973984718323 +17211,0.422398746013641,-0.103682428598404,-0.0449492149055,40327,1251,-3506,-4119,1.03847718238831 +17213,0.458553969860077,-0.099469274282456,-0.046895157545805,40327,1065,-3109,-4013,1.03994452953339 +17215,0.499254643917084,-0.094089321792126,-0.048004940152168,40327,-664,-3045,-4168,1.04075956344605 +17217,0.541887998580933,-0.082105718553066,-0.04402657225728,40327,-668,-3870,-3999,1.04405701160431 +17219,0.590283811092377,-0.077700838446617,-0.039680063724518,40327,-2793,-3206,-4090,1.04500889778137 +17221,0.640620708465576,-0.065999194979668,-0.039531279355288,40327,-2755,-4044,-3973,1.04501295089722 +17223,0.692913591861725,-0.052777729928494,-0.040125086903572,40327,-4883,-4217,-4123,1.04605007171631 +17225,0.741850018501282,-0.024403780698776,-0.040223594754934,40327,-4274,-5811,-3983,1.05233860015869 +17227,0.792551815509796,-0.015004952438176,-0.037173599004746,40327,-6576,-4534,-4129,1.05874705314636 +17229,0.848103225231171,-0.016261612996459,-0.034183371812105,40327,-6488,-3797,-3948,1.06281697750092 +17231,0.897369623184204,-0.00489288661629,-0.036886144429445,40327,-8411,-4829,-4141,1.05887854099274 +17233,0.940857589244842,0.006820894312114,-0.041594784706831,40327,-7220,-5053,-4005,1.05348360538483 +17235,0.98278534412384,0.022920785471797,-0.040018226951361,40327,-9558,-5608,-4211,1.04474890232086 +17237,1.02914893627167,0.024748794734478,-0.034464869648218,40327,-9000,-4608,-3964,1.03999066352844 +17239,1.06807351112366,0.028506217524409,-0.033720251172781,40327,-11053,-4816,-4151,1.03409814834595 +17241,1.09589552879334,0.035703204572201,-0.035526368767023,40327,-8978,-5157,-3978,1.03231120109558 +17243,1.12155365943909,0.039635870605707,-0.038407005369663,40327,-11320,-5023,-4225,1.02677822113037 +17245,1.14359521865845,0.048187669366598,-0.040437716990709,40327,-9623,-5447,-4020,1.0299711227417 +17247,1.1652444601059,0.051345240324736,-0.03994594886899,40327,-12125,-5174,-4264,1.03674352169037 +17249,1.1839884519577,0.064793862402439,-0.037530172616243,40327,-10364,-6055,-4009,1.04962408542633 +17251,1.20792889595032,0.06571039557457,-0.038164772093296,40327,-13396,-5271,-4268,1.0558215379715 +17253,1.22164237499237,0.070860639214516,-0.041645243763924,40327,-10965,-5574,-4047,1.04969072341919 +17255,1.22071504592896,0.080887123942375,-0.044754981994629,40327,-12252,-6194,-4372,1.04286885261536 +17257,1.22093284130096,0.083113476634026,-0.049290247261524,40327,-10420,-5572,-4110,1.03477132320404 +17271,1.10765433311462,0.06118343397975,-0.057324916124344,40327,-10047,-4210,-4548,1.01361274719238 +17273,1.07841408252716,0.050085738301277,-0.061040755361319,40327,-7926,-4259,-4239,1.01054239273071 +17275,1.04248261451721,0.04169062525034,-0.064698174595833,40327,-8872,-4371,-4625,1.00672662258148 +17277,0.99713009595871,0.030692223459482,-0.064167685806751,40327,-5966,-4001,-4273,0.997837007045746 +17279,0.946508347988129,0.01489185821265,-0.058461271226406,40327,-6610,-3421,-4533,0.995980203151703 +17281,0.894550323486328,-0.003589479951188,-0.056147091090679,40327,-4341,-2976,-4229,0.998036324977875 +17283,0.839700937271118,-0.006885717157274,-0.058991126716137,40327,-4882,-3968,-4523,1.00199997425079 +17285,0.791275799274445,-0.015895269811154,-0.063445761799812,40327,-3387,-3472,-4289,1.00318610668182 +17287,0.737832546234131,-0.020483670756221,-0.064598627388477,40327,-3582,-3649,-4582,0.997735500335693 +17289,0.680671155452728,-0.033605687320232,-0.056278191506863,40327,-1405,-2912,-4251,0.997344136238098 +17291,0.629925847053528,-0.04780388623476,-0.053915720432997,40327,-2215,-2503,-4433,0.995615482330322 +17293,0.585906147956848,-0.05125130712986,-0.057533863931894,40327,-1167,-3328,-4267,0.99691504240036 +17295,0.549572825431824,-0.057371504604817,-0.061260253190994,40327,-2094,-2894,-4514,1.00160753726959 +17297,0.520911931991577,-0.057016830891371,-0.061553433537483,40327,-1478,-3488,-4303,1.0038857460022 +17299,0.496039092540741,-0.059997536242008,-0.055062334984541,40327,-2176,-3047,-4446,1.00884854793549 +17301,0.468908876180649,-0.06605377048254,-0.049983661621809,40327,-961,-2869,-4230,1.00693011283875 +17303,0.440318405628204,-0.078442022204399,-0.048219654709101,40327,-1112,-2042,-4350,1.00891804695129 +17305,0.408938229084015,-0.094812542200089,-0.048401109874249,40327,108,-1678,-4225,1.01068508625031 +17307,0.385012149810791,-0.104453079402447,-0.047748040407896,40327,-637,-1774,-4316,1.01224887371063 +17309,0.372351825237274,-0.115243390202522,-0.046798598021269,40327,-779,-1734,-4218,1.01144850254059 +17311,0.352578490972519,-0.105114296078682,-0.042356323450804,40327,-478,-3136,-4256,1.01520347595215 +17313,0.322477281093597,-0.093441016972065,-0.040645200759173,40327,1127,-3605,-4179,1.01536023616791 +17315,0.301461279392242,-0.100429594516754,-0.04165805503726,40327,391,-1936,-4257,1.01710724830627 +17317,0.291433483362198,-0.108279287815094,-0.039804596453905,40327,99,-1946,-4176,1.01685631275177 +17319,0.287584841251373,-0.111311800777912,-0.036500714719296,40327,-633,-2007,-4186,1.01413452625275 +17321,0.280149936676025,-0.111572824418545,-0.036243185400963,40327,47,-2390,-4154,1.01116442680359 +17323,0.274462401866913,-0.11898547410965,-0.037390634417534,40327,-308,-1520,-4188,1.01109158992767 +17325,0.271106153726578,-0.122683227062225,-0.038738831877709,40327,-136,-1930,-4172,1.01186561584473 +17327,0.264240652322769,-0.123493060469627,-0.042817041277886,40327,-74,-1847,-4247,1.01643037796021 +17329,0.265953153371811,-0.128860145807266,-0.045351885259152,40327,-442,-1662,-4220,1.0111780166626 +17331,0.272209525108337,-0.120015867054462,-0.045617070049048,40327,-1158,-2537,-4287,1.001544713974 +17333,0.279189825057983,-0.110236257314682,-0.0436050593853,40327,-1030,-2956,-4211,0.997441470623016 +17335,0.276432871818542,-0.098961859941483,-0.04004392400384,40327,-607,-2997,-4252,0.993324041366577 +17337,0.281559467315674,-0.1000632122159,-0.039152823388577,40327,-954,-2273,-4184,0.997298300266266 +17339,0.295430272817612,-0.107379645109177,-0.040454719215632,40327,-2131,-1479,-4249,0.999835133552551 +17341,0.305346220731735,-0.10007830709219,-0.039750311523676,40327,-1671,-2822,-4191,1.0005464553833 +17343,0.315603882074356,-0.092495277523995,-0.037128962576389,40327,-2234,-2745,-4232,1.00104594230652 +17345,0.324748039245606,-0.080739125609398,-0.033146094530821,40327,-1936,-3373,-4148,1.00753593444824 +17347,0.340676516294479,-0.086780190467835,-0.033044032752514,40327,-3099,-1814,-4194,1.01636350154877 +17349,0.352055191993713,-0.081783123314381,-0.033571228384972,40327,-2542,-2830,-4153,1.01634407043457 +17351,0.365358769893646,-0.087449684739113,-0.034212790429592,40327,-3377,-1787,-4209,1.01269841194153 +17353,0.370868593454361,-0.085965640842915,-0.032843556255102,40327,-2459,-2474,-4151,1.00435125827789 +17355,0.368801206350327,-0.075891941785812,-0.028719760477543,40327,-2405,-3064,-4163,0.994774103164673 +17357,0.370801001787186,-0.072990864515305,-0.027269659563899,40327,-2277,-2723,-4115,0.99287223815918 +17359,0.379925340414047,-0.070897199213505,-0.027944495901466,40327,-3457,-2530,-4162,0.996863424777985 +17361,0.391739070415497,-0.070431835949421,-0.026979066431522,40327,-3356,-2547,-4115,1.00109481811523 +17363,0.404632657766342,-0.061435721814633,-0.027057435363531,40327,-4201,-3148,-4166,1.00217843055725 +17365,0.415024757385254,-0.048377703875303,-0.027821125462651,40327,-3675,-3733,-4123,1.00558269023895 +17367,0.425779670476914,-0.037077758461237,-0.030953725799918,40327,-4475,-3670,-4246,1.01283466815948 +17369,0.436678946018219,-0.020066315308213,-0.032796788960695,40327,-4118,-4399,-4161,1.01850664615631 +17371,0.446974873542786,-0.014462341554463,-0.028171092271805,40327,-4886,-3606,-4248,1.01389944553375 +17373,0.453640878200531,-0.006576286628842,-0.024107094854117,40327,-4164,-3925,-4105,1.00657296180725 +17375,0.462973237037659,-0.001651662052609,-0.023111686110497,40327,-5194,-3760,-4210,1.00022494792938 +17377,0.478402435779572,0.00301150069572,-0.025249009951949,40327,-5263,-3825,-4117,0.993522822856903 +17379,0.493165850639343,0.000312594609568,-0.025231402367354,40327,-6196,-3236,-4241,0.993595242500305 +17381,0.505910575389862,-0.005953604355454,-0.02346227131784,40327,-5597,-2906,-4109,0.99564665555954 +17383,0.511331796646118,0.000738039496355,-0.024640673771501,40327,-5948,-3911,-4239,0.99609100818634 +17385,0.516783773899078,0.00322320102714,-0.024988707154989,40327,-5369,-3658,-4124,0.996334373950958 +17387,0.513860464096069,0.021818578243256,-0.02296750433743,40327,-5529,-5108,-4252,1.00183796882629 +17389,0.511711657047272,0.024595938622952,-0.020913755521178,40327,-4893,-3989,-4101,1.01344180107117 +17391,0.50574404001236,0.023568207398057,-0.025269439443946,40327,-5327,-3731,-4286,1.02042257785797 +17393,0.499458014965057,0.026186617091298,-0.028364816680551,40327,-4560,-4005,-4157,1.02740943431854 +17395,0.494300246238709,0.027647687122226,-0.027193957939744,40327,-5348,-4123,-4150,1.02373707294464 +17397,0.486936956644058,0.03089109249413,-0.026439994573593,40327,-5212,-3078,-4286,1.01802229881287 +17399,0.480950355529785,0.024615561589599,-0.020140172913671,40327,-4030,-4052,-4111,1.01614439487457 +17401,0.460185438394547,0.025884483009577,-0.011529866605997,40327,-4768,-3955,-4146,1.01844835281372 +17403,0.460185438394547,0.025884483009577,-0.011529866605997,40327,-4768,-3955,-4146,1.01844835281372 +17405,0.437275558710098,0.012753007933498,-0.009879410266876,40327,-4295,-3137,-4111,1.01459181308746 +17407,0.413946807384491,0.011992139741778,-0.012387217022479,40327,-2623,-3577,-4064,1.01707077026367 +17409,0.395213901996613,0.014171846210957,-0.014682168141008,40327,-3249,-3829,-4172,1.01694738864899 +17411,0.383605062961578,0.006540834438056,-0.016532981768251,40327,-3122,-3006,-4095,1.01299667358398 +17413,0.383605062961578,0.006540834438056,-0.016532981768251,40327,-3122,-3006,-4095,1.01299667358398 +17415,0.354001581668854,0.002061562379822,-0.013219885528088,40327,-2485,-3295,-4075,1.00076735019684 +17417,0.340108633041382,-0.008454965427518,-0.010026764124632,40327,-2874,-2556,-4092,1.00015115737915 +17419,0.323934257030487,-0.014720104634762,-0.008089117705822,40327,-2095,-2788,-4042,0.998581349849701 +17421,0.305450052022934,-0.021279191598296,-0.008404140360653,40327,-2048,-2624,-4056,1.0009286403656 +17423,0.305450052022934,-0.021279191598296,-0.008404140360653,40327,-2048,-2624,-4056,1.0009286403656 +17425,0.265611827373505,-0.0294399112463,-0.010587486438453,40327,-1621,-2278,-4070,0.999741077423096 +17427,0.25071769952774,-0.033876795321703,-0.008551015518606,40327,-1232,-2613,-4046,1.00583410263062 +17429,0.230370447039604,-0.03642863035202,-0.008616652339697,40327,-774,-2632,-4038,1.01780700683594 +17431,0.21534575521946,-0.04568986222148,-0.009385401383042,40327,-738,-2078,-4051,1.01991271972656 +17433,0.21534575521946,-0.04568986222148,-0.009385401383042,40327,-738,-2078,-4051,1.01991271972656 +17435,0.187735363841057,-0.047215033322573,-0.005462244618684,40327,-312,-2663,-4024,1.0178827047348 +17437,0.173473030328751,-0.042012646794319,-0.006867537274957,40327,-321,-3047,-4009,1.01355588436127 +17439,0.165105104446411,-0.049712717533112,-0.006953127216548,40327,-505,-2083,-4033,1.01191794872284 +17441,0.154468938708305,-0.055118355900049,-0.003391677280888,40327,-275,-2053,-3949,1.00883293151855 +17443,0.145785734057426,-0.053521201014519,7.67651072237641E-05,40327,-198,-2665,-3983,1.00897634029388 +17445,0.135913178324699,-0.054913021624088,-0.000665193772875,40327,-12,-2321,-3915,1.00492310523987 +17447,0.123413912951946,-0.054734073579311,-0.002601398387924,40327,412,-2518,-3999,1.00189983844757 +17449,0.123014725744724,-0.062301676720381,-0.001575390226208,40327,-449,-1722,-3913,1.00250828266144 +17451,0.120959378778934,-0.052723061293364,0.001426811912097,40327,-275,-3188,-3969,1.00247204303741 +17453,0.118036702275276,-0.050514657050371,0.005225293338299,40327,-147,-2583,-3849,1.0024733543396 +17455,0.1096505895257,-0.043234780430794,0.008732321672142,40327,370,-3131,-3916,0.998832583427429 +17457,0.10387022793293,-0.041202884167433,0.010810134932399,40327,316,-2699,-3794,0.997911334037781 +17459,0.109654761850834,-0.038994990289211,0.011010313406587,40327,-609,-2806,-3897,0.995631098747253 +17461,0.119925476610661,-0.026513785123825,0.012361945584416,40327,-1064,-3669,-3794,0.996382653713226 +17463,0.126293733716011,-0.021217370405793,0.010981928557158,40327,-862,-3266,-3894,0.997607707977295 +17465,0.122091710567474,-0.013196725398302,0.007734498474747,40327,-32,-3552,-3864,0.994443237781525 +17467,0.114227935671806,-0.016793107613921,0.009111833758652,40327,357,-2682,-3905,0.996159791946411 +17469,0.109920680522919,-0.021220158785582,0.011831930838525,40327,202,-2522,-3803,1.00336968898773 +17471,0.108933798968792,-0.026666849851608,0.01259233430028,40327,-26,-2395,-3879,1.01561713218689 +17473,0.116077154874802,-0.037874560803175,0.011360968463123,40327,-687,-1749,-3782,1.02114880084991 +17475,0.122924469411373,-0.037126641720533,0.01000573951751,40327,-758,-2668,-3893,1.02178919315338 +17477,0.12327791005373,-0.02943460829556,0.011146558448672,40327,-296,-3217,-3793,1.0231009721756 +17479,0.127748027443886,-0.015066410414875,0.008935181424022,40327,-631,-3943,-3898,1.01845908164978 +17481,0.142429172992706,-0.011591871269047,0.010288557037711,40327,-1616,-3186,-3826,1.01947867870331 +17483,0.160084128379822,-0.009663909673691,0.012495363131166,40327,-2023,-3119,-3871,1.01582765579224 +17485,0.168824672698975,0.002674576360732,0.011462318710983,40327,-1609,-4049,-3831,1.0146119594574 +17501,0.232360675930977,0.055219244211912,0.015213440172374,40327,-2206,-3745,-3863,1.01304233074188 +17503,0.23686695098877,0.055653471499682,0.017910268157721,40327,-2235,-3998,-3835,1.01116299629211 +17505,0.242167517542839,0.055675592273474,0.019501533359289,40327,-2615,-4088,-3814,1.01051795482636 +17507,0.248220920562744,0.062941066920757,0.018328867852688,40327,-2539,-4614,-3832,1.00738084316254 +17509,0.252493411302567,0.065013147890568,0.018251167610288,40327,-2745,-4412,-3842,1.00691711902618 +17511,0.25376433134079,0.064547955989838,0.02006933093071,40327,-2312,-4109,-3820,1.00931894779205 +17513,0.249245330691338,0.062387578189373,0.021513652056456,40327,-2102,-4094,-3801,1.02029871940613 +17515,0.248935535550117,0.053645201027393,0.01883558742702,40327,-2164,-3385,-3828,1.02101695537567 +17517,0.247314974665642,0.053783133625984,0.018674839287996,40327,-2320,-4144,-3821,1.01995074748993 +17519,0.245240017771721,0.054178189486265,0.023844951763749,40327,-2021,-4070,-3794,1.01960372924805 +17521,0.24560484290123,0.062797911465168,0.024636533111334,40327,-2484,-4925,-3764,1.01487910747528 +17523,0.248640641570091,0.059424284845591,0.022151783108711,40327,-2474,-3902,-3805,1.016930103302 +17525,0.24847149848938,0.060663934797049,0.020599253475666,40327,-2527,-4387,-3808,1.01674926280975 +17527,0.244094431400299,0.063008554279804,0.021658467128873,40327,-1917,-4389,-3808,1.02191996574402 +17529,0.237311631441116,0.055649753659964,0.022507095709443,40327,-1900,-3718,-3778,1.0231204032898 +17531,0.231888741254806,0.054788053035736,0.024878414347768,40327,-1699,-4066,-3785,1.02369129657745 +17533,0.232559978961945,0.044861972332001,0.028482332825661,40327,-2377,-3376,-3692,1.0245246887207 +17535,0.225179404020309,0.04546432942152,0.032377615571022,40327,-1492,-4056,-3731,1.02216947078705 +17537,0.215710371732712,0.040678881108761,0.035782251507044,40327,-1381,-3689,-3599,1.01707458496094 +17539,0.202442571520805,0.047147151082754,0.033849317580462,40327,-762,-4517,-3718,1.00825965404511 +17541,0.192919567227364,0.042691219598055,0.029059277847409,40327,-1027,-3754,-3677,1.00623035430908 +17543,0.190509885549545,0.029480528086424,0.027280028909445,40327,-1377,-2869,-3761,1.00388503074646 +17545,0.18806354701519,0.024460854008794,0.027997879311442,40327,-1476,-3438,-3660,0.996977806091309 +17547,0.187017038464546,0.024921396747232,0.029996855184436,40327,-1434,-3792,-3739,0.993891477584839 +17549,0.178617984056473,0.030599899590016,0.032583709806204,40327,-907,-4324,-3613,0.995929837226868 +17551,0.166795909404755,0.012696092016995,0.034963242709637,40327,-377,-2314,-3701,0.998246073722839 +17553,0.156673938035965,-0.003924574237317,0.034594021737576,40327,-430,-2180,-3535,1.00459063053131 +17555,0.146015748381615,-0.01279581617564,0.035774476826191,40327,-158,-2595,-3690,1.01776599884033 +17557,0.136045590043068,-0.018192006275058,0.039604634046555,40327,-96,-2747,-3450,1.02558481693268 +17559,0.119617633521557,-0.013888528570533,0.039505235850811,40327,647,-3515,-3658,1.03134727478027 +17561,0.105227492749691,-0.017559139057994,0.037892609834671,40327,744,-2869,-3464,1.02975273132324 +17563,0.094572350382805,-0.024877468124032,0.034207914024592,40327,621,-2517,-3687,1.02443861961365 +17565,0.088953763246536,-0.045559618622065,0.033844906836748,40327,411,-1184,-3464,1.02195680141449 +17567,0.075565978884697,-0.045168098062277,0.036535173654556,40327,1126,-2758,-3664,1.01941323280334 +17569,0.066054880619049,-0.03875182569027,0.039375942200422,40327,1105,-3216,-3402,1.02068436145782 +17571,0.063373364508152,-0.040698226541281,0.038573727011681,40327,581,-2637,-3642,1.01330626010895 +17573,0.060443885624409,-0.047551307827234,0.037825491279364,40327,779,-2104,-3400,1.01254737377167 +17575,0.048657841980457,-0.05438582226634,0.04014752060175,40327,1495,-2068,-3623,1.01674485206604 +17577,0.037761032581329,-0.047780554741621,0.039434336125851,40327,1773,-3035,-3372,1.01965832710266 +17579,0.040364034473896,-0.053566984832287,0.037381418049336,40327,644,-2132,-3634,1.02545464038849 +17581,0.050075020641089,-0.051297649741173,0.038374412804842,40327,153,-2642,-3371,1.02431619167328 +17583,0.061933137476444,-0.049022492021322,0.037375271320343,40327,-272,-2749,-3625,1.023078083992 +17585,0.070331513881683,-0.048216179013252,0.034318834543228,40327,-42,-2569,-3415,1.01823115348816 +17587,0.067588187754154,-0.043681684881449,0.031801499426365,40327,736,-2965,-3656,1.01861500740051 +17589,0.064259462058544,-0.044576905667782,0.03242103010416,40327,944,-2483,-3435,1.02365469932556 +17591,0.065591558814049,-0.0378792360425,0.034859903156757,40327,521,-3182,-3628,1.02665102481842 +17593,0.078342199325562,-0.048048421740532,0.039666626602411,40327,-384,-1751,-3338,1.02697205543518 +17595,0.084113009274006,-0.044775832444429,0.041865970939398,40327,-19,-2817,-3571,1.02467572689056 +17597,0.08897053450346,-0.049209699034691,0.042912468314171,40327,50,-2128,-3290,1.02635085582733 +17599,0.091904647648335,-0.042484905570746,0.039497748017311,40327,109,-3076,-3578,1.0261150598526 +17601,0.103306323289871,-0.036150112748146,0.033738672733307,40327,-611,-3075,-3407,1.02511501312256 +17603,0.108436264097691,-0.033729732036591,0.03436978161335,40327,-252,-2875,-3607,1.01683509349823 +17605,0.105739817023277,-0.032912895083428,0.035861678421497,40327,386,-2714,-3380,1.00793087482452 +17607,0.113532029092312,-0.043013114482164,0.034301321953535,40327,-485,-1828,-3600,1.00378572940826 +17609,0.12880702316761,-0.043067187070847,0.033967688679695,40327,-1246,-2465,-3381,1.00491750240326 +17611,0.138233199715614,-0.036734472960234,0.036086857318878,40327,-936,-3073,-3581,1.00828814506531 +17613,0.142191305756569,-0.023077676072717,0.038421906530857,40327,-628,-3764,-3351,1.00486886501312 +17615,0.147011116147041,-0.015047883614898,0.036238335072994,40327,-716,-3495,-3572,1.00921237468719 +17617,0.15380921959877,-0.019298834726214,0.032530665397644,40327,-1016,-2535,-3418,1.0184223651886 +17619,0.150093480944633,-0.006473931483924,0.032423421740532,40327,-140,-3952,-3593,1.02931988239288 +17621,0.150906726717949,-0.003105223644525,0.033291358500719,40327,-547,-3328,-3426,1.03721976280212 +17623,0.153134897351265,0.001910914783366,0.032842855900526,40327,-602,-3510,-3585,1.0404257774353 +17625,0.162794396281242,-0.003481604391709,0.032719187438488,40327,-1377,-2694,-3427,1.03634989261627 +17627,0.162212952971458,0.00607939530164,0.032141506671906,40327,-531,-3893,-3584,1.0308290719986 +17629,0.150810018181801,0.015825724229217,0.034365441650152,40327,327,-4096,-3431,1.02948486804962 +17631,0.149570047855377,0.019818985834718,0.033167500048876,40327,-297,-3697,-3573,1.02638947963715 +17633,0.153443887829781,0.021513745188713,0.029977278783918,40327,-793,-3625,-3486,1.02165353298187 +17635,0.163127765059471,0.016647208482027,0.034496933221817,40327,-1268,-3027,-3560,1.01663649082184 +17637,0.163380697369576,0.024845844134688,0.041627168655396,40327,-686,-4158,-3351,1.01421451568604 +17639,0.165142461657524,0.020538818091154,0.043156538158655,40327,-727,-3134,-3495,1.01465809345245 +17641,0.165944680571556,0.017919676378369,0.040882542729378,40327,-763,-3258,-3345,1.01373493671417 +17643,0.162252441048622,0.01745499484241,0.038117729127407,40327,-293,-3370,-3524,1.01575970649719 +17645,0.164093300700188,0.019316846504808,0.035113129764795,40327,-800,-3597,-3408,1.01331984996796 +17647,0.164260610938072,0.025575261563063,0.036228444427252,40327,-596,-3972,-3533,1.01352345943451 +17649,0.16302227973938,0.023172752931714,0.042775381356478,40327,-561,-3373,-3320,1.02048432826996 +17651,0.16038453578949,0.023341238498688,0.045851215720177,40327,-336,-3513,-3461,1.02433228492737 +17653,0.165491729974747,0.012892265804112,0.043331794440746,40327,-1058,-2644,-3293,1.0246080160141 +17655,0.164325341582298,0.018103696405888,0.040484022349119,40327,-497,-3804,-3492,1.02088367938995 +17657,0.163403645157814,0.015023147687316,0.043855980038643,40327,-600,-3214,-3284,1.02227187156677 +17659,0.159612864255905,0.007042847573757,0.045676436275244,40327,-241,-2706,-3450,1.02100312709808 +17661,0.1543198376894,0.006002297624946,0.043371804058552,40327,-141,-3219,-3270,1.02153587341309 +17663,0.150108188390732,0.009322784841061,0.041958436369896,40327,-71,-3551,-3469,1.02090191841125 +17665,0.145344942808151,0.012671280652285,0.042972717434168,40327,-28,-3645,-3278,1.01957535743713 +17667,0.139570087194443,-0.001768563990481,0.042527560144663,40327,199,-2125,-3459,1.01619303226471 +17669,0.130351543426514,-0.010907387360931,0.040664542466402,40327,551,-2368,-3264,1.01133286952972 +17671,0.127838492393494,-0.012679108418524,0.041031211614609,40327,149,-2870,-3462,1.00725674629211 +17673,0.130829706788063,-0.009887897409499,0.042990040034056,40327,-309,-3235,-3232,1.00249981880188 +17675,0.124634653329849,-0.009395387023687,0.045499779284,40327,476,-3075,-3424,1.0007039308548 +17677,0.118252120912075,-0.0213334672153,0.046891812235117,40327,581,-1989,-3162,0.999986827373504 +17679,0.114751167595386,-0.02545559592545,0.046251021325588,40327,446,-2504,-3411,0.999834775924683 +17681,0.117649219930172,-0.030143938958645,0.04396865144372,40327,-47,-2353,-3175,0.99777626991272 +17683,0.115827985107899,-0.017346523702145,0.04304550588131,40327,332,-3819,-3424,0.997328102588654 +17685,0.115554362535477,-0.026612889021635,0.045905150473118,40327,234,-2072,-3149,1.00061881542206 +17687,0.113374531269073,-0.04156157374382,0.047898676246405,40327,-32767,-1472,-3383,1.00698828697205 +17689,0.114753261208534,-0.053414683789015,0.046033632010222,40327,-6822,-1436,-3100,1.01501417160034 +17691,0.115251183509827,-0.050344813615084,0.04416174441576,40327,-6786,-2613,-3398,1.02061688899994 +17693,0.11215628683567,-0.039880655705929,0.044457204639912,40327,-6503,-3230,-3129,1.02795612812042 +17695,0.099663630127907,-0.037856753915548,0.047609504312277,40327,-5676,-2699,-3366,1.02818930149078 +17697,0.0798264965415,-0.034000672399998,0.045072674751282,40327,-4820,-2837,-3121,1.01970982551575 +17699,0.062032870948315,-0.039135850965977,0.039441414177418,40327,-4786,-2152,-3413,1.01296293735504 +17701,0.03927705436945,-0.043052028864622,0.035654947161675,40327,-3976,-2113,-3209,1.0035982131958 +17703,0.007466684561223,-0.043855454772711,0.039978962391615,40327,-3011,-2375,-3402,1.00180506706238 +17705,-0.023949952796102,-0.046060331165791,0.040141001343727,40327,-2323,-2171,-3145,0.999135315418243 +17707,-0.054035037755966,-0.043130774050951,0.035386275500059,40327,-2233,-2632,-3425,1.00033986568451 +17709,-0.08606767654419,-0.048137314617634,0.033439446240664,40327,-1235,-1906,-3211,1.00180780887604 +17711,-0.122333474457264,-0.04399511218071,0.034340634942055,40327,-762,-2683,-3424,1.00415968894959 +17713,-0.15662556886673,-0.049532275646925,0.035534661263228,40327,140,-1819,-3177,1.00711643695831 +17729,-0.450439780950546,-0.032225634902716,0.026434414088726,40327,5400,-2495,-3285,1.01838290691376 +17731,-0.478293687105179,-0.021603615954518,0.027713838964701,40327,4506,-3371,-3440,1.01347458362579 +17733,-0.497206032276154,-0.020959267392755,0.024133073166013,40327,5417,-2616,-3323,1.00651407241821 +17735,-0.518916606903076,-0.0088917510584,0.021590558812022,40327,4895,-3642,-3477,1.00290048122406 +17737,-0.53777951002121,-0.006303602829576,0.025218339636922,40327,6322,-2981,-3326,0.998023867607117 +17739,-0.558597385883331,-0.002256134292111,0.028786269947887,40327,5667,-3154,-3423,0.992834270000458 +17741,-0.570516884326935,-0.00929868966341,0.029476925730705,40327,6618,-2245,-3268,0.994851648807525 +17743,-0.576920032501221,-0.011778599582613,0.026942476630211,40327,5178,-2542,-3431,0.9990593791008 +17745,-0.584730505943298,-0.00604177871719,0.025478744879365,40327,6836,-3210,-3314,1.00920534133911 +17747,-0.592867970466614,0.00146119191777,0.026224508881569,40327,5821,-3442,-3432,1.01868748664856 +17749,-0.601738631725311,0.016778083518148,0.026571117341518,40327,7475,-4267,-3327,1.02389848232269 +17751,-0.601633787155151,0.032986927777529,0.025021692737937,40327,5654,-4523,-3436,1.02838575839996 +17753,-0.599406242370606,0.053216945379973,0.023925548419356,40327,6927,-5217,-3403,1.02708292007446 +17755,-0.594861388206482,0.052472334355116,0.025896366685629,40327,5536,-3608,-3429,1.02814197540283 +17757,-0.580598413944244,0.050435602664948,0.026861654594541,40327,6046,-3595,-3363,1.02655422687531 +17759,-0.568501651287079,0.063740789890289,0.025865649804473,40327,4906,-4795,-3427,1.02997756004334 +17761,-0.555828452110291,0.063543736934662,0.027497285977006,40327,-25504,-3957,-3370,1.02853989601135 +17763,-0.543185174465179,0.063611447811127,0.031938645988703,40327,-543,-3870,-3384,1.02332186698914 +17765,-0.519453942775726,0.054313730448485,0.034063551574946,40327,-400,-3176,-3279,1.0167453289032 +17767,-0.49997290968895,0.061019778251648,0.033086217939854,40327,-1436,-4329,-3373,1.01429498195648 +17769,-0.478177428245544,0.064253225922585,0.030805731192231,40327,-715,-4250,-3326,1.01383721828461 +17771,-0.462263584136963,0.073752753436565,0.026358146220446,40327,-1521,-4735,-3417,1.0091438293457 +17773,-0.455672591924667,0.076595485210419,0.02273278310895,40327,194,-4443,-3433,1.00660920143127 +17775,-0.445611834526062,0.069308370351791,0.020349888131023,40327,-1150,-3498,-3458,1.00700664520264 +17777,-0.436276406049728,0.073741659522057,0.021443422883749,40327,-138,-4540,-3443,1.00720286369324 +17779,-0.434047371149063,0.073510944843292,0.028341166675091,40327,-573,-4091,-3402,1.00939631462097 +17781,-0.444549262523651,0.080218747258186,0.035339970141649,40327,1591,-4860,-3287,1.01242959499359 +17783,-0.446729123592377,0.071082450449467,0.037784349173308,40327,109,-3453,-3335,1.01745474338532 +17785,-0.443464517593384,0.064806252717972,0.034921586513519,40327,763,-3712,-3269,1.02248215675354 +17787,-0.439672499895096,0.055332526564598,0.032698433846235,40327,-234,-3230,-3367,1.02677464485168 +17789,-0.436452329158783,0.047488179057837,0.033564478158951,40327,835,-3343,-3260,1.02197873592377 +17791,-0.439032435417175,0.046216703951359,0.034639175981283,40327,396,-3707,-3350,1.02291548252106 +17793,-0.441564112901688,0.036461558192968,0.036554392427206,40327,1517,-3043,-3207,1.03020453453064 +17795,-0.439813196659088,0.033300153911114,0.037463158369064,40327,285,-3402,-3326,1.0362468957901 +17797,-0.439500391483307,0.029235228896141,0.036152835935354,40327,1480,-3343,-3198,1.04269564151764 +17799,-0.44955325126648,0.039052806794643,0.035305019468069,40327,-30090,-4426,-3337,1.038445353508 +17801,-0.455776274204254,0.043093197047711,0.038618210703135,40327,-2914,-4159,-3181,1.03264403343201 +17803,-0.453248262405396,0.03799894079566,0.040611516684294,40327,-4540,-3360,-3296,1.01963543891907 +17805,-0.449665099382401,0.028971780091524,0.038584027439356,40327,-3567,-3003,-3159,1.0110011100769 +17807,-0.449211567640305,0.009497162885964,0.035037208348513,40327,-4302,-1930,-3329,1.00324380397797 +17809,-0.465084791183472,0.007694425992668,0.034859225153923,40327,-1778,-3181,-3172,0.994474947452545 +17811,-0.486958682537079,0.006674239877611,0.034779228270054,40327,-2006,-3212,-3325,0.988200724124908 +17813,-0.509234607219696,0.02091651968658,0.034124232828617,40327,-445,-4558,-3190,0.992307186126709 +17815,-0.529663741588593,0.02458224631846,0.035139229148626,40327,-1321,-3812,-3318,1.00289607048035 +17817,-0.556022346019745,0.022815441712737,0.033276408910751,40327,793,-3457,-3197,1.01016449928284 +17819,-0.585740625858307,0.016297608613968,0.029068315401673,40327,347,-2974,-3355,1.01757323741913 +17821,-0.613606452941895,0.0173300486058,0.028103863820434,40327,2046,-3575,-3247,1.0195118188858 +17823,-0.638741433620453,0.02491832152009,0.031989667564631,40327,1007,-4115,-3331,1.01952147483826 +17825,-0.661651313304901,0.017383765429258,0.0340994335711,40327,2700,-2973,-3172,1.0190042257309 +17827,-0.686235666275024,0.01526015624404,0.032672360539436,40327,1899,-3289,-3321,1.01825904846191 +17829,-0.71353667974472,0.00633694184944,0.034184835851193,40327,4124,-2696,-3153,1.01853597164154 +17831,-0.73711234331131,-0.004962540231645,0.031807471066713,40327,2834,-2344,-3322,1.01475632190704 +17833,-0.759362041950226,-0.01527320034802,0.028537165373564,40327,4804,-2237,-3190,1.01447582244873 +17835,-0.78046727180481,-0.025260895490646,0.031472869217396,40327,3582,-2138,-3319,1.01050639152527 +17837,-0.804149687290192,-0.030767444521189,0.037310600280762,40327,-25601,-2317,-3065,1.01190543174744 +17839,-0.828948438167572,-0.039764698594809,0.040537130087614,40327,-460,-1985,-3249,1.02020156383514 +17841,-0.851933777332306,-0.035364143550396,0.036198634654284,40327,1648,-2929,-3066,1.02106666564941 +17843,-0.860065698623657,-0.033390402793884,0.032668903470039,40327,-911,-2843,-3296,1.01607131958008 +17845,-0.871456205844879,-0.028657995164394,0.032285615801811,40327,1427,-3046,-3112,1.00688004493713 +17847,-0.894450604915619,-0.030175419524312,0.034314155578613,40327,954,-2623,-3279,1.00656270980835 +17849,-0.920811235904694,-0.034975856542587,0.032766181975603,40327,3618,-2250,-3094,1.00797522068024 +17851,-0.943709909915924,-0.031841352581978,0.029968820512295,40327,1986,-2915,-3302,1.00793790817261 +17853,-0.962223291397095,-0.0290089212358,0.029539214447141,40327,4072,-2888,-3132,1.00807869434357 +17855,-0.985028266906738,-0.019552314653993,0.028347229585052,40327,2927,-3531,-3307,1.00984573364258 +17857,-1.00620627403259,-0.025170428678393,0.026882618665695,40327,5339,-2336,-3161,1.01299321651459 +17859,-1.02918648719788,-0.025653190910816,0.027087338268757,40327,3951,-2721,-3310,1.01372385025024 +17861,-1.05177021026611,-0.019237708300352,0.026738803833723,40327,6567,-3272,-3164,1.01918625831604 +17881,-1.11360061168671,0.01105675380677,0.03891495987773,40327,2792,-2935,-3017,1.03317928314209 +17883,-1.11917889118195,0.018191229552031,0.037539213895798,40327,1203,-3865,-3201,1.03442335128784 +17885,-1.12342262268066,0.017610939219594,0.037754904478788,40327,3591,-3337,-3029,1.03371548652649 +17887,-1.13313794136047,0.018765764310956,0.036768142133951,40327,2099,-3450,-3200,1.03279864788055 +17889,-1.13564169406891,0.014064966700971,0.036569904536009,40327,4065,-2989,-3034,1.03747296333313 +17891,-1.13761222362518,0.013247771188617,0.035324927419424,40327,2017,-3232,-3204,1.03607726097107 +17893,-1.15452980995178,0.022541120648384,0.036037463694811,40327,5819,-4134,-3041,1.03064548969269 +17895,-1.16825807094574,0.017438476905227,0.037728317081928,40327,3720,-2993,-3182,1.02634763717651 +17897,-1.174192070961,0.013295199722052,0.036794267594814,40327,5776,-3024,-3019,1.02471470832825 +17899,-1.16642081737518,0.010260260663927,0.039072882384062,40327,2587,-3040,-3167,1.02147960662842 +17901,-1.16676414012909,0.028256872668862,0.039414629340172,40327,5691,-4857,-2993,1.01900851726532 +17903,-1.17010641098022,0.036687858402729,0.04124453291297,40327,3870,-4250,-3146,1.01873970031738 +17905,-1.17163872718811,0.033199429512024,0.044288344681263,40327,6289,-3413,-2932,1.01865780353546 +17907,-1.1752473115921,0.02771020680666,0.044520366936922,40327,4403,-3136,-3117,1.02193355560303 +17909,-1.18090915679932,0.027965765446425,0.0439796410501,40327,7171,-3613,-2924,1.02885067462921 +17911,-1.17966842651367,0.036289390176535,0.043998505920172,40327,4566,-4260,-3114,1.03553783893585 +17913,-1.17273712158203,0.036646772176027,0.04206920042634,40327,6572,-3775,-2945,1.03771042823792 +17915,-1.16524803638458,0.038497149944306,0.040375992655754,40327,4357,-3843,-3133,1.03314650058746 +17917,-1.15353274345398,0.031013231724501,0.04243216663599,40327,6352,-3137,-2930,1.03317725658417 +17919,-1.14298057556152,0.027899902313948,0.04356187582016,40327,4256,-3349,-3104,1.03060746192932 +17921,-1.13256752490997,0.028477964922786,0.041034165769816,40327,6544,-3681,-2937,1.0323486328125 +17923,-1.12090373039246,0.024311307817698,0.036974720656872,40327,4294,-3233,-3143,1.03321218490601 +17925,-1.10880732536316,0.028745470568538,0.037455573678017,40327,6468,-3972,-2972,1.03615045547485 +17927,-1.09458339214325,0.026926329359412,0.039471447467804,40327,4159,-3449,-3120,1.04092001914978 +17929,-1.07706427574158,0.031062547117472,0.039267241954804,40327,5975,-3993,-2946,1.0453165769577 +17931,-1.04724419116974,0.021073201671243,0.037166319787502,40327,2776,-2791,-3130,1.04802978038788 +17933,-1.02560150623322,0.017906252294779,0.033518936485052,40327,5241,-3258,-3000,1.04489552974701 +17935,-1.0079185962677,0.013518461957574,0.032357923686504,40327,3474,-3088,-3158,1.03907120227814 +17937,-0.989648103713989,0.01709177531302,0.031282488256693,40327,5286,-3737,-3020,1.02991592884064 +17939,-0.968782305717468,0.024977123364806,0.030444452539086,40327,3063,-4136,-3166,1.03020441532135 +17941,-0.943026125431061,0.017538337036967,0.030444715172052,40327,4364,-2965,-3024,1.0315580368042 +17943,-0.919642627239227,0.015215000137687,0.029648669064045,40327,2539,-3271,-3166,1.02889621257782 +17945,-0.900350093841553,0.010748035274446,0.029659869149327,40327,4485,-3072,-3025,1.02659010887146 +17947,-0.880602300167084,0.018520349636674,0.028822146356106,40327,2584,-4045,-3167,1.02812027931213 +17949,-0.853154122829437,0.009209680370986,0.028622576966882,40327,3464,-2697,-3031,1.0295193195343 +17951,-0.827922403812408,0.004106371663511,0.024210089817643,40327,1760,-2917,-3194,1.03185677528381 +17953,-0.800452649593353,-0.001834388822317,0.023350920528174,40327,2910,-2754,-3083,1.03546869754791 +17955,-0.777130305767059,-0.003452331293374,0.024205103516579,40327,1470,-3053,-3190,1.03462469577789 +17957,-0.758298218250275,0.000478644185932,0.025318663567305,40327,3131,-3504,-3057,1.04016613960266 +17959,-0.739381015300751,-0.001263601123355,0.026952777057886,40327,1527,-3074,-3166,1.04576897621155 +17961,-0.719208538532257,-0.003543400904164,0.026924017816782,40327,2677,-2998,-3031,1.04948794841766 +17963,-0.699486255645752,-0.015532688237727,0.026695186272264,40327,1165,-2132,-3163,1.04947197437286 +17965,-0.679270684719086,-0.016127202659845,0.026759739965201,40327,2274,-2907,-3023,1.04382467269897 +17967,-0.653219223022461,-0.021395673975349,0.028835946694017,40327,298,-2520,-3144,1.04083096981049 +17969,-0.631593883037567,-0.016209300607443,0.027103466913104,40327,1645,-3304,-3014,1.03982412815094 +17971,-0.613904774188995,-0.009991506114602,0.029757749289274,40327,564,-3497,-3132,1.03796637058258 +17973,-0.59318470954895,-0.009133693762124,0.032848153263331,40327,1329,-3098,-2945,1.03171443939209 +17975,-0.573612093925476,-0.014877192676067,0.033496793359518,40327,70,-2563,-3101,1.03032314777374 +17977,-0.558954358100891,-0.021856786683202,0.033163849264383,40327,1419,-2315,-2930,1.02897536754608 +17979,-0.549185216426849,-0.009336424060166,0.035137481987476,40327,627,-3937,-3084,1.03043830394745 +17981,-0.536718368530273,-0.010220903903246,0.035985805094242,40327,1403,-2934,-2895,1.02616679668427 +17983,-0.522445738315582,-0.002263967879117,0.033907245844603,40327,115,-3704,-3086,1.02147912979126 +17985,-0.503264248371124,-0.0049560200423,0.03571067750454,40327,548,-2901,-2894,1.01868164539337 +17987,-0.492032170295715,-0.004387109074742,0.03976097330451,40327,75,-3142,-3039,1.01670444011688 +17989,-0.483127504587174,-0.007882055826485,0.042011737823486,40327,1117,-2798,-2812,1.01723968982697 +17991,-0.470576643943787,-0.012052749283612,0.04029730707407,40327,-159,-2689,-3028,1.01867270469666 +17993,-0.467283576726914,-0.006561977788806,0.039618760347366,40327,1429,-3458,-2834,1.01931643486023 +17995,-0.465295642614365,-0.008834931068122,0.040937580168247,40327,683,-2868,-3017,1.01796972751617 +17997,-0.462308436632156,-0.00399428838864,0.040683947503567,40327,1538,-3440,-2815,1.01958644390106 +17999,-0.456735223531723,-0.006575527600944,0.038326554000378,40327,466,-2875,-3028,1.02009260654449 +18001,-0.457286447286606,0.003231178037822,0.036913130432367,40327,1877,-3898,-2855,1.0244654417038 +18003,-0.447697281837463,-0.008832672610879,0.035111308097839,40327,211,-2160,-3044,1.02389490604401 +18005,-0.446401417255402,-0.010084965266287,0.031560704112053,40327,1740,-2886,-2908,1.02352476119995 +18007,-0.447585135698319,-0.011373043060303,0.029550280421972,40327,1142,-2888,-3076,1.02485191822052 +18009,-0.452903389930725,-0.011638716794551,0.030414579436183,40327,2496,-2924,-2916,1.02547931671143 +18011,-0.45558425784111,-0.003926125820726,0.031788598746061,40327,1532,-3631,-3055,1.0289990901947 +18013,-0.455870121717453,-0.00315668922849,0.032568946480751,40327,2347,-3132,-2887,1.02794480323792 +18015,-0.456267356872559,-0.005545301828533,0.029691275209189,40327,1548,-2879,-3064,1.02264475822449 +18017,-0.452969670295715,-0.00907932780683,0.026997841894627,40327,2196,-2725,-2946,1.02456724643707 +18019,-0.455123782157898,0.00672250520438,0.029067693278194,40327,1825,-4352,-3063,1.02826011180878 +18021,-0.455540031194687,0.013322575949133,0.038754180073738,40327,2668,-3813,-2808,1.03173494338989 +18023,-0.457859694957733,0.018568944185972,0.042181599885225,40327,2045,-3770,-2967,1.03204989433289 +18025,-0.468553006649017,0.026648756116629,0.041114110499621,40327,3781,-4132,-2777,1.03528797626495 +18027,-0.473750054836273,0.023647615686059,0.038073871284723,40327,2655,-3260,-2988,1.04097068309784 +18029,-0.470152139663696,0.023690603673458,0.039945833384991,40327,2955,-3507,-2783,1.04178535938263 +18031,-0.46993413567543,0.020725548267365,0.044752288609743,40327,2389,-3226,-2935,1.03181600570679 +18033,-0.475501656532288,0.023836582899094,0.045856598764658,40327,3874,-3745,-2706,1.0212596654892 +18035,-0.475421249866486,0.019678762182593,0.042312934994698,40327,2658,-3132,-2945,1.01089477539063 +18037,-0.478116810321808,0.023175526410341,0.040237702429295,40327,3889,-3776,-2764,1.00303161144257 +18039,-0.482694059610367,0.020911244675517,0.042859748005867,40327,3278,-3294,-2934,1.00460171699524 +18041,-0.47853609919548,0.012743853963912,0.039825160056353,40327,3590,-2783,-2760,1.00487005710602 +18043,-0.474324375391007,0.016079483553767,0.03303648903966,40327,2713,-3630,-2995,1.00759041309357 +18045,-0.468454599380493,0.018912982195616,0.030099516734481,40327,3489,-3671,-2869,1.0111973285675 +18047,-0.466077327728272,0.027728347107768,0.030737956985831,40327,2908,-4197,-3005,1.01500773429871 +18049,-0.463680773973465,0.018954377621412,0.034857120364904,40327,3847,-2834,-2808,1.0154002904892 +18051,-0.471605718135834,0.024755362421274,0.039012186229229,40327,3908,-3943,-2942,1.02106690406799 +18053,-0.471091330051422,0.024965757504106,0.04114194214344,40327,4285,-3584,-2728,1.02421319484711 +18055,-0.466809749603272,0.027840010821819,0.040277503430843,40327,3151,-3785,-2927,1.02692425251007 +18057,-0.460355788469315,0.02667753957212,0.040315859019756,40327,3868,-3532,-2731,1.03413212299347 +18059,-0.451804429292679,0.025174194946885,0.039494417607784,40327,2813,-3443,-2925,1.03433334827423 +18061,-0.446841239929199,0.02818943746388,0.034369360655546,40327,3927,-3868,-2795,1.03114092350006 +18063,-0.443789839744568,0.028769874945283,0.033306524157524,40327,3269,-3655,-2962,1.02662813663483 +18065,-0.433763951063156,0.031367890536785,0.036473549902439,40327,3515,-3902,-2764,1.0187451839447 +18067,-0.420635759830475,0.018072221428156,0.040599968284369,40327,2385,-2520,-2906,1.01803195476532 +18069,-0.415396720170975,0.016848277300596,0.039347622543573,40327,3725,-3397,-2721,1.01927018165588 +18071,-0.407353788614273,0.013543820008636,0.038820423185825,40327,2721,-3176,-2911,1.0202522277832 +18073,-0.39720606803894,0.015252502635121,0.039443079382181,40327,3245,-3580,-2713,1.01892375946045 +18075,-0.386742144823074,0.020501971244812,0.042087282985449,40327,2409,-3893,-2882,1.02444767951965 +18077,-0.376099675893784,0.013409015722573,0.040874097496271,40327,3021,-2912,-2689,1.02937614917755 +18079,-0.365680277347565,0.008256287313998,0.040340941399336,40327,2259,-2973,-2887,1.03328597545624 +18081,-0.357531815767288,-0.000752641703002,0.042612634599209,40327,3042,-2546,-2659,1.03194713592529 +18083,-0.350853085517883,0.009576812386513,0.043942548334599,40327,2455,-4096,-2855,1.02523231506348 +18085,-0.340073317289352,0.014824694953859,0.044326487928629,40327,2701,-3835,-2633,1.02137124538422 +18087,-0.32649952173233,0.013054521754384,0.043855410069227,40327,1745,-3284,-2847,1.01940786838532 +18089,-0.312558382749557,0.001713063451462,0.046665064990521,40327,2146,-2443,-2596,1.02007853984833 +18091,-0.301544487476349,-0.004843095783144,0.045201022177935,40327,1690,-2685,-2830,1.02043080329895 +18093,-0.297160744667053,0.00439671613276,0.044115159660578,40327,2697,-3961,-2618,1.0247368812561 +18095,-0.292265892028809,0.006675257347524,0.046296425163746,40327,2109,-3484,-2815,1.02707862854004 +18111,-0.20926858484745,-0.002241418464109,0.037653680890799,40327,1273,-3463,-2844,1.01953899860382 +18113,-0.195518478751183,0.001027435064316,0.036150995641947,40327,861,-3459,-2674,1.01871931552887 +18115,-0.184463664889336,0.012386851944029,0.038220144808292,40327,580,-4207,-2834,1.01351284980774 +18117,-0.178947076201439,0.015711832791567,0.041974805295467,40327,1242,-3706,-2600,1.01199448108673 +18119,-0.179982453584671,0.025376239791513,0.041844565421343,40327,1445,-4277,-2801,1.01589107513428 +18121,-0.174580797553062,0.016524486243725,0.043033432215452,40327,1247,-2852,-2580,1.01942944526672 +18123,-0.169189989566803,0.011306709609926,0.038812104612589,40327,893,-3015,-2815,1.02363038063049 +18125,-0.165052279829979,0.009555643424392,0.036711923778057,40327,1236,-3249,-2647,1.03151035308838 +18127,-0.161510303616524,0.007279773242772,0.038157314062119,40327,973,-3169,-2813,1.03884899616241 +18129,-0.155501171946526,0.017584500834346,0.037781719118357,40327,995,-4239,-2628,1.04374265670776 +18131,-0.152617365121841,0.023449581116438,0.0359021499753,40327,945,-3989,-2821,1.03780841827393 +18133,-0.15769599378109,0.032619796693325,0.034334357827902,40327,1889,-4416,-2664,1.02835059165955 +18135,-0.163644835352898,0.024787599220872,0.030849911272526,40327,1792,-3039,-2850,1.02412128448486 +18137,-0.170255988836288,0.020382659509778,0.029722131788731,40327,-32767,32767,-2711,1.02569162845612 +18139,-0.164545685052872,0.011171133257449,0.031803291290999,40327,-29416,4404,-2838,1.02739489078522 +18141,-0.156862750649452,0.007014966569841,0.030605889856815,40327,-29504,4132,-2694,1.02441084384918 +18143,-0.158643618226051,0.013530280441046,0.030682725831866,40327,-29206,3314,-2840,1.02312707901001 +18145,-0.165437713265419,0.014975145459175,0.028564017266035,40327,-28569,3674,-2714,1.02331221103668 +18147,-0.178855627775192,0.019091358408332,0.020337641239166,40327,-28321,3473,-2906,1.02475273609161 +18149,-0.205210536718369,0.029889488592744,0.006229722406715,40327,-26759,2826,-2975,1.02505147457123 +18151,-0.249463975429535,0.057574823498726,-0.00753507995978,40327,-25319,1292,-3097,1.0235196352005 +18153,-0.305905282497406,0.083063997328281,-0.018986525014043,40327,-23169,948,-3276,1.02244973182678 +18155,-0.376752436161041,0.105373613536358,-0.029424326494336,40327,-21762,1026,-3250,1.01769506931305 +18157,-0.466703027486801,0.124489136040211,-0.038339283317328,40327,-18292,757,-3511,1.01708662509918 +18159,-0.57133948802948,0.138507157564163,-0.046542622148991,40327,-16648,1159,-3374,1.01682984828949 +18161,-0.685222089290619,0.163059204816818,-0.05448130145669,40327,-13073,-239,-3709,1.01478624343872 +18163,-0.801251232624054,0.192601233720779,-0.058459758758545,40327,-12528,-729,-3465,1.01089155673981 +18165,-0.92803692817688,0.230084806680679,-0.058669995516539,40327,-8138,-2272,-3767,1.00701117515564 +18167,-1.06919693946838,0.264607697725296,-0.059597034007311,40327,-6763,-2152,-3482,1.00187432765961 +18169,-1.2069810628891,0.284384489059448,-0.062391705811024,40327,-2640,-1932,-3817,0.999746859073639 +18171,-1.34382247924805,0.300156116485596,-0.066350005567074,40327,-2880,-1378,-3539,0.999869048595428 +18173,-1.48430192470551,0.318588763475418,-0.06634134799242,40327,2365,-2459,-3866,1.00282454490662 +18175,-1.6316591501236,0.345474928617477,-0.06056647002697,40327,2384,-2900,-3510,1.00552225112915 +18177,-1.78415811061859,0.377622216939926,-0.054935615509749,40327,8546,-4496,-3729,1.00314223766327 +18179,-1.93332636356354,0.403101146221161,-0.051136866211891,40327,7368,-3731,-3453,1.00124204158783 +18181,-2.0811972618103,0.424488097429276,-0.049462392926216,40327,13626,-4592,-3655,0.997939944267273 +18183,-2.21932911872864,0.43729704618454,-0.048026736825705,40327,11348,-3440,-3438,0.994841933250427 +18185,-2.3446364402771,0.455516844987869,-0.045957192778587,40327,17014,-4996,-3598,0.995612323284149 +18187,-2.46548557281494,0.481019973754883,-0.0439761467278,40327,14436,-5118,-3416,1.00272655487061 +18189,-2.57845664024353,0.509154796600342,-0.044173408299685,40327,20774,-6737,-3551,1.00889945030212 +18191,-2.67646360397339,0.532349526882172,-0.048169057816267,40327,16736,-5857,-3449,1.0154139995575 +18193,-2.76738405227661,0.542859435081482,-0.053218971937895,40327,23210,-6208,-3628,1.0237649679184 +18195,-2.85984539985657,0.556012988090515,-0.05743345245719,40327,19974,-5664,-3517,1.03232681751251 +18197,-2.9423201084137,0.578293204307556,-0.058536183089018,40327,26487,-7817,-3656,1.04258465766907 +18199,-3.00288510322571,0.591278493404388,-0.059445928782225,40327,20833,-6362,-3534,1.0519802570343 +18201,-3.04774785041809,0.595235586166382,-0.063535928726196,40327,26616,-6979,-3680,1.05344021320343 +18203,-3.08061456680298,0.597171664237976,-0.072147391736508,40327,21113,-5867,-3625,1.04785537719727 +18205,-3.11164879798889,0.607260763645172,-0.0815175101161,40327,27821,-7827,-3856,1.03891038894653 +18207,-3.14082956314087,0.613628149032593,-0.086771741509438,40327,22899,-6639,-3731,1.04019963741303 +18209,-3.15330004692078,0.613323450088501,-0.086161427199841,40327,28362,-7405,-3877,1.04451465606689 +18211,-3.14768385887146,0.611116349697113,-0.086863599717617,40327,21719,-6213,-3736,1.04893755912781 +18213,-3.12584900856018,0.601071298122406,-0.093267656862736,40327,26662,-6741,-3935,1.05551755428314 +18215,-3.09298849105835,0.60704505443573,-0.103337898850441,40327,20192,-6963,-3854,1.05828821659088 +18217,-3.05125761032104,0.614304959774017,-0.106514111161232,40327,25208,-8422,-4053,1.06245374679565 +18219,-3.00305414199829,0.620271623134613,-0.106896571815014,40327,18985,-7383,-3884,1.05872714519501 +18221,-2.94610857963562,0.620013773441315,-0.105603814125061,40327,23567,-8202,-4009,1.05862438678741 +18223,-2.88119387626648,0.612518727779388,-0.103898487985134,40327,17182,-6541,-3868,1.05915629863739 +18225,-2.79996037483215,0.609836935997009,-0.106925584375858,40327,20556,-8099,-4003,1.06264340877533 +18227,-2.70779013633728,0.600753784179688,-0.110081665217876,40327,13824,-6490,-3913,1.06486821174622 +18229,-2.6154510974884,0.59963446855545,-0.110622078180313,40327,17792,-8276,-4027,1.06551492214203 +18231,-2.50852179527283,0.586036741733551,-0.105075649917126,40327,10910,-6185,-3882,1.06804823875427 +18233,-2.40447163581848,0.578701496124268,-0.103103809058666,40327,14466,-7712,-3931,1.0626437664032 +18235,-2.29018139839172,0.563800513744354,-0.100954584777355,40327,8160,-5993,-3856,1.06910681724548 +18237,-2.17222666740417,0.550968885421753,-0.097889788448811,40327,10553,-7080,-3870,1.07458662986755 +18239,-2.04854440689087,0.536913692951202,-0.09726020693779,40327,4830,-5876,-3831,1.08116388320923 +18241,-1.92238771915436,0.524740815162659,-0.098088949918747,40327,6670,-6902,-3875,1.08098542690277 +18243,-1.79623878002167,0.513629496097565,-0.095707900822163,40327,1734,-5952,-3821,1.08303272724152 +18245,-1.67038321495056,0.492891222238541,-0.092245981097221,40327,3237,-5963,-3820,1.08804929256439 +18247,-1.55059659481049,0.483938246965408,-0.089766994118691,40327,-744,-5865,-3781,1.09815835952759 +18249,-1.42563736438751,0.456150442361832,-0.088746346533299,40327,-151,-5043,-3801,1.09227645397186 +18251,-1.30398893356323,0.436397433280945,-0.087305188179016,40327,-3937,-4580,-3764,1.09201169013977 +18253,-1.18376219272614,0.41324982047081,-0.083220906555653,40560,-3321,-4848,-3768,1.09249567985535 +18255,-1.07672166824341,0.400808483362198,-0.081297650933266,40560,-5781,-4747,-3724,1.09036457538605 +18257,-0.967913746833801,0.375805050134659,-0.081217385828495,40560,-5689,-4251,-3775,1.09167122840881 +18259,-0.870463907718658,0.35806405544281,-0.082347728312016,40560,-7780,-3891,-3732,1.08151173591614 +18261,-0.776705026626587,0.332717210054398,-0.081374540925026,40560,-7492,-3645,-3816,1.07364809513092 +18263,-0.689335882663727,0.315678507089615,-0.081614404916763,40560,-9470,-3450,-3730,1.06469202041626 +18265,-0.601368725299835,0.294003218412399,-0.082238174974918,40560,-9785,-3385,-3866,1.06119382381439 +18267,-0.525151491165161,0.274959772825241,-0.089012995362282,40560,-10920,-2822,-3785,1.0576411485672 +18269,-0.452392101287842,0.252246558666229,-0.093941353261471,40560,-11047,-2738,-4048,1.05596208572388 +18271,-0.389144480228424,0.228681311011314,-0.09378245472908,40560,-11905,-1917,-3825,1.05054652690887 +18273,-0.345038443803787,0.219888493418694,-0.097926087677479,40560,-10723,-3292,-4133,1.05183935165405 +18275,-0.30495285987854,0.199542790651321,-0.099319569766522,40560,-11464,-1800,-3872,1.05842792987823 +18277,-0.271973222494125,0.184430807828903,-0.098933190107346,40560,-11133,-2320,-4189,1.0575544834137 +18279,-0.240870907902718,0.163406908512115,-0.101455226540566,40560,-11782,-1286,-3897,1.05073428153992 +18281,-0.2171980291605,0.154628053307533,-0.104831382632256,40560,-11412,-2331,-4299,1.04541063308716 +18283,-0.194754719734192,0.132399812340736,-0.107610665261745,40560,-11891,-794,-3951,1.0443502664566 +18285,-0.193642258644104,0.115167945623398,-0.110475331544876,40560,-10248,-1113,-4418,1.03848588466644 +18287,-0.199675530195236,0.097189322113991,-0.107213914394379,40560,32767,-17563,-3963,1.03269600868225 +18289,-0.214143127202988,0.082167468965054,-0.105607718229294,40560,3315,-3617,-4408,1.02688300609589 +18291,-0.232090145349503,0.077194258570671,-0.110797747969627,40560,3634,-4143,-4002,1.02510035037994 +18293,-0.246460005640984,0.057820796966553,-0.117107927799225,40560,3894,-2950,-4583,1.02704703807831 +18295,-0.260299324989319,0.034088585525751,-0.120295003056526,40560,3814,-2207,-4085,1.0265554189682 +18297,-0.281704097986221,0.00418279087171,-0.11859792470932,40560,5047,-1344,-4673,1.02902626991272 +18299,-0.308638155460358,-0.011318787932396,-0.11860653012991,40560,5532,-2148,-4093,1.02957367897034 +18301,-0.322277843952179,-0.025801040232182,-0.116559810936451,40560,5241,-1958,-4701,1.03190660476685 +18303,-0.328227937221527,-0.041221790015698,-0.113111667335033,40560,4414,-1713,-4076,1.03053820133209 +18305,-0.339790016412735,-0.051779359579086,-0.108629174530506,40560,5485,-1802,-4655,1.03021097183228 +18307,-0.348642438650131,-0.063401691615582,-0.104667998850346,40560,5028,-1644,-4038,1.03162837028503 +18309,-0.353966861963272,-0.063274212181568,-0.102710358798504,40560,5377,-2358,-4619,1.03996598720551 +18311,-0.349381327629089,-0.087897457182407,-0.10068541765213,40560,4195,-333,-4030,1.04778397083282 +18313,-0.347977012395859,-0.102354370057583,-0.09414679557085,40560,4916,-641,-4579,1.05179798603058 +18315,-0.346450835466385,-0.115797899663448,-0.088099874556065,40560,4490,-687,-3963,1.0488463640213 +18317,-0.345938861370087,-0.123886123299599,-0.086285978555679,40560,5057,-693,-4530,1.04271483421326 +18319,-0.337809175252914,-0.1314377784729,-0.083910413086414,40560,4009,-827,-3953,1.04268860816956 +18321,-0.322632879018784,-0.142726555466652,-0.081500940024853,40560,3731,-97,-4514,1.03924036026001 +18323,-0.312233477830887,-0.149311751127243,-0.078025229275227,40560,3584,-574,-3931,1.03957426548004 +18345,0.010268597863615,-0.207609847187996,-0.054468896239996,40542,2977,-3036,-4368,1.04523265361786 +18347,0.065576553344727,-0.228593721985817,-0.049870684742928,40542,1556,-2388,-3842,1.04727554321289 +18349,0.119281619787216,-0.230328693985939,-0.048241324722767,40542,467,-3256,-4336,1.04681944847107 +18351,0.178407683968544,-0.246826007962227,-0.044446472078562,40542,-369,-2376,-3821,1.04751098155975 +18353,0.230586037039757,-0.264351040124893,-0.044768035411835,40542,-1292,-1481,-4346,1.04591131210327 +18355,0.27663066983223,-0.272997111082077,-0.0456124804914,40542,-927,-2473,-3846,1.04438579082489 +18357,0.319407850503921,-0.277574181556702,-0.041446421295405,40542,-2166,-2099,-4336,1.04125714302063 +18359,0.359521210193634,-0.275657415390015,-0.038903150707483,40542,-1819,-3095,-3817,1.04624319076538 +18361,0.408787488937378,-0.288286924362183,-0.034994717687368,40542,-4231,-1253,-4285,1.04757797718048 +18363,0.456178247928619,-0.295612543821335,-0.032374646514654,40542,32161,-2044,-3789,1.04309630393982 +18365,0.49571904540062,-0.303599506616592,-0.030450562015176,40542,954,-1239,-4260,1.03707826137543 +18367,0.530736446380615,-0.29949352145195,-0.030057393014431,40542,1826,-2699,-3789,1.03270852565765 +18369,0.572327315807343,-0.308617234230041,-0.029791908338666,40542,-610,-968,-4270,1.02935755252838 +18371,0.60957396030426,-0.312328636646271,-0.029597941786051,40542,346,-1843,-3801,1.02184665203094 +18373,0.651167392730713,-0.312013953924179,-0.030112817883492,40542,-2104,-1479,-4288,1.02212429046631 +18375,0.699139356613159,-0.308867424726486,-0.033003486692906,40542,-1936,-2270,-3841,1.01925504207611 +18377,0.744766294956207,-0.302896767854691,-0.032832898199558,40542,-4166,-1925,-4322,1.02654767036438 +18379,0.790214657783508,-0.311680883169174,-0.027811255306006,40542,-3337,-1265,-3821,1.02837061882019 +18381,0.834996938705444,-0.3118616938591,-0.024609694257379,40542,-5857,-1230,-4243,1.0331164598465 +18383,0.876867949962616,-0.311663717031479,-0.021172318607569,40542,-4642,-1794,-3790,1.03731715679169 +18385,0.912485718727112,-0.301016569137573,-0.02497155033052,40542,-6800,-2073,-4246,1.03657293319702 +18387,0.955054640769958,-0.301411122083664,-0.026277245953679,40542,-6171,-1789,-3839,1.03251111507416 +18389,0.988372325897217,-0.297703832387924,-0.024011254310608,40542,-8247,-1518,-4239,1.02761483192444 +18391,1.01541328430176,-0.292464822530746,-0.021702967584133,40542,-6321,-2212,-3822,1.03010165691376 +18393,1.03842234611511,-0.285035997629166,-0.020650155842304,40542,-8714,-1880,-4193,1.02778780460358 +18395,1.0547057390213,-0.270102798938751,-0.020615858957172,40542,-6534,-3122,-3827,1.02808749675751 +18397,1.06588065624237,-0.264064639806747,-0.021521661430597,40542,-8726,-2021,-4189,1.028324842453 +18399,1.06544828414917,-0.251945525407791,-0.019822025671601,40542,-5925,-3085,-3833,1.02968466281891 +18401,1.06443023681641,-0.256445020437241,-0.021411778405309,40542,27808,-1282,-4185,1.03166127204895 +18403,1.05958414077759,-0.251989543437958,-0.023585014045239,40703,130,-2440,-3870,1.02429842948914 +18405,1.04859983921051,-0.246836349368095,-0.020878922194243,40703,-1584,-2029,-4176,1.01640927791595 +18407,1.03512644767761,-0.238052725791931,-0.021272486075759,40703,729,-2856,-3865,1.00670504570007 +18409,1.02517259120941,-0.236244410276413,-0.023033820092678,40703,-1646,-1866,-4197,0.999826371669769 +18411,1.02279794216156,-0.240611523389816,-0.021904608234763,40703,-250,-1788,-3880,0.999420583248138 +18413,1.02107191085815,-0.229590997099876,-0.019663764163852,40703,-2527,-2549,-4157,1.00110530853271 +18415,1.01733291149139,-0.224564909934998,-0.016250766813755,40703,-438,-2603,-3851,1.00244057178497 +18417,1.00428652763367,-0.215148076415062,-0.013603908009827,40703,-1800,-2598,-4079,1.0036815404892 +18419,0.996856212615967,-0.209862023591995,-0.010147550143302,40703,-238,-2754,-3817,1.00962543487549 +18421,0.995902180671692,-0.197401627898216,-0.009419902227819,40703,-2885,-3024,-4019,1.01499474048615 +18423,0.995545089244842,-0.188944086432457,-0.011236789636314,40703,-1083,-3209,-3831,1.02258539199829 +18425,0.995821714401245,-0.18871083855629,-0.009184876456857,40703,-3328,-2205,-4012,1.02299547195435 +18427,0.985096335411072,-0.179164215922356,-0.004388335626572,40703,-551,-3357,-3791,1.02240335941315 +18429,0.97046309709549,-0.167940691113472,-0.00164462137036,40703,-2205,-3260,-3910,1.02331697940826 +18431,0.958852529525757,-0.150426924228668,0.002240605885163,40703,-463,-4277,-3750,1.02187943458557 +18433,0.957756876945496,-0.148138299584389,0.005854095332325,40703,-3323,-2886,-3809,1.0262166261673 +18435,0.952345132827759,-0.146154165267944,0.005668519996107,40703,-1164,-3173,-3729,1.02579700946808 +18437,0.942434787750244,-0.139862477779388,0.003893528832123,40703,-2789,-3265,-3826,1.02705180644989 +18439,0.934752643108368,-0.136514440178871,0.00230594817549,40703,-1095,-3360,-3755,1.02765834331512 +18441,0.924431920051575,-0.127240121364594,0.005919163580984,40703,-2807,-3642,-3794,1.03216981887817 +18443,0.916405200958252,-0.126920357346535,0.013853498734534,40703,-1148,-3238,-3678,1.03775882720947 +18445,0.895349979400635,-0.113730877637863,0.019036952406168,40703,-1904,-4089,-3629,1.04536187648773 +18447,0.878154218196869,-0.118003167212009,0.019683239981532,40703,-273,-2998,-3637,1.04502820968628 +18449,0.86640989780426,-0.115805685520172,0.018541401252151,40703,-2426,-3227,-3634,1.04348242282867 +18451,0.85205465555191,-0.10528913885355,0.018484460189939,40703,-422,-4199,-3645,1.04480624198914 +18453,0.837250590324402,-0.100354626774788,0.020874073728919,40703,-2040,-3637,-3594,1.04145479202271 +18455,0.819755613803864,-0.097288258373737,0.02316158823669,40703,-42,-3746,-3612,1.03593301773071 +18457,0.80437695980072,-0.094093836843968,0.026177683845162,40703,-1754,-3579,-3524,1.03311932086945 +18459,0.786083340644836,-0.085803136229515,0.025679586455226,40703,204,-4254,-3592,1.03081214427948 +18461,0.770381569862366,-0.094777539372444,0.02529301866889,40703,-1457,-2662,-3530,1.0287960767746 +18463,0.751048564910889,-0.098986059427261,0.025410249829292,40703,501,-3137,-3592,1.021240234375 +18465,0.730207741260529,-0.09996272623539,0.026734489947558,40703,-700,-3107,-3512,1.01854085922241 +18467,0.714476823806763,-0.103023655712605,0.024158572778106,40703,506,-3124,-3598,1.01452016830444 +18469,0.70030927658081,-0.100898317992687,0.01923118531704,40703,-945,-3275,-3597,1.01431751251221 +18471,0.68696129322052,-0.099516458809376,0.018546359613538,40703,480,-3454,-3636,1.01569139957428 +18473,0.672610342502594,-0.096282750368118,0.017757993191481,40703,-715,-3397,-3608,1.01837539672852 +18475,0.654414713382721,-0.103354506194592,0.018480552360416,40703,1056,-2758,-3635,1.02458238601685 +18477,0.634171068668366,-0.106690123677254,0.018724566325545,40703,112,-2724,-3599,1.0241721868515 +18497,0.513371884822845,-0.146630346775055,0.028548173606396,40703,192,-2155,-3485,1.02305698394775 +18499,0.501324474811554,-0.146915078163147,0.029013799503446,40703,1629,-2333,-3550,1.02499389648438 +18501,0.495710343122482,-0.145519137382507,0.028494419530034,40703,119,-2154,-3481,1.02468061447144 +18503,0.497661292552948,-0.153209403157234,0.027322467416525,40703,504,-1655,-3559,1.02655780315399 +18505,0.493740200996399,-0.152513071894646,0.02352049574256,40703,-144,-1935,-3539,1.02826285362244 +18507,0.48479962348938,-0.146848186850548,0.022657888010144,40703,1294,-2642,-3590,1.03196680545807 +18509,0.475737571716309,-0.14655302464962,0.025960087776184,40703,350,-1949,-3504,1.03119969367981 +18511,0.46789288520813,-0.146632045507431,0.028697766363621,40703,1291,-2176,-3546,1.03042304515839 +18513,0.463582038879395,-0.152279213070869,0.028177818283439,40703,55,-1365,-3476,1.03262853622437 +18515,0.456587880849838,-0.144410580396652,0.02743274718523,40703,1231,-2716,-3553,1.03286731243134 +18517,0.454858601093292,-0.149405792355537,0.031203862279654,40703,-135,-1388,-3434,1.02818381786346 +18519,0.452925056219101,-0.150592774152756,0.034245241433382,40703,764,-1916,-3503,1.01897299289703 +18521,0.452628135681152,-0.148365363478661,0.034582942724228,40703,-366,-1858,-3390,1.01553761959076 +18523,0.457088112831116,-0.151355892419815,0.032494802027941,40703,88,-1713,-3511,1.01241588592529 +18525,0.463588178157806,-0.155659541487694,0.031479671597481,40703,-1205,-1212,-3424,1.00870609283447 +18527,0.462217301130295,-0.162143915891647,0.034337028861046,40703,265,-1242,-3495,1.00981652736664 +18529,0.455522358417511,-0.151277035474777,0.03638232499361,40703,-287,-2304,-3359,1.01228642463684 +18531,0.455637723207474,-0.149860203266144,0.035971015691757,40703,88,-1919,-3480,1.0149929523468 +18533,0.458943754434586,-0.146905824542046,0.034685358405113,40703,-1209,-1743,-3372,1.01655447483063 +18535,0.463974684476852,-0.146224036812782,0.033384788781405,40703,-547,-1856,-3494,1.02167558670044 +18537,0.459346622228622,-0.142188996076584,0.032520193606615,40703,-808,-1832,-3390,1.02285492420197 +18539,0.451378434896469,-0.132696703076363,0.033305425196886,40703,398,-2619,-3491,1.02129530906677 +18541,0.44855672121048,-0.132255002856255,0.035741232335568,40703,-937,-1685,-3344,1.0196408033371 +18543,0.447052597999573,-0.127188056707382,0.037914916872978,40703,-166,-2325,-3455,1.01518142223358 +18545,0.447932898998261,-0.126739352941513,0.03974286839366,40703,-1361,-1726,-3289,1.0158052444458 +18547,0.450412750244141,-0.120848663151264,0.038082003593445,40703,-665,-2422,-3449,1.01642155647278 +18549,0.451444715261459,-0.114151865243912,0.037993311882019,40703,-1585,-2322,-3299,1.0214067697525 +18551,0.449927717447281,-0.112205848097801,0.04028507322073,40703,-539,-2214,-3428,1.02502059936523 +18553,0.442284941673279,-0.104526810348034,0.039904989302158,40703,-972,-2499,-3267,1.02913534641266 +18555,0.439059913158417,-0.103946663439274,0.038628030568361,40703,-424,-2190,-3434,1.03317105770111 +18557,0.436325520277023,-0.095927104353905,0.036996196955443,40703,-1394,-2621,-3292,1.03678262233734 +18559,0.434762418270111,-0.102167174220085,0.036967225372791,40703,-644,-1685,-3441,1.03860318660736 +18561,0.429033726453781,-0.097309857606888,0.037530653178692,40703,-1228,-2334,-3280,1.03454494476318 +18563,0.423242509365082,-0.091367915272713,0.037349000573158,40703,-338,-2671,-3433,1.0310742855072 +18565,0.422642886638641,-0.090360961854458,0.03856748342514,40703,-1647,-2138,-3260,1.02314126491547 +18567,0.41500735282898,-0.085012651979923,0.041701190173626,40703,-247,-2682,-3397,1.01915621757507 +18569,0.400236546993256,-0.082459531724453,0.047155655920506,40703,-409,-2330,-3149,1.02141273021698 +18571,0.383877545595169,-0.069811686873436,0.048245362937451,40703,676,-3387,-3345,1.02572643756866 +18573,0.38341435790062,-0.065243221819401,0.044607274234295,40703,-1298,-2713,-3167,1.02854132652283 +18575,0.390085428953171,-0.067433871328831,0.039639662951231,40703,-1202,-2328,-3398,1.02560031414032 +18577,0.384942024946213,-0.069411769509316,0.038422252982855,40703,-1133,-2144,-3234,1.02227854728699 +18579,0.370848178863525,-0.070956073701382,0.035202860832214,40703,417,-2292,-3422,1.02022838592529 +18581,0.35481783747673,-0.065215945243836,0.034277986735106,40703,-6,-2729,-3276,1.02242183685303 +18583,0.346482276916504,-0.066434055566788,0.03331820294261,40703,223,-2349,-3430,1.02238392829895 +18585,0.340144634246826,-0.058947399258614,0.030851284042001,40703,-588,-2938,-3309,1.0215175151825 +18587,0.336246192455292,-0.055367209017277,0.029237626120448,40703,-73,-2824,-3454,1.02656507492065 +18589,0.332802325487137,-0.051542110741139,0.033341277390719,40703,-796,-2777,-3273,1.02998352050781 +18591,0.323245167732239,-0.043269421905279,0.038426764309406,40703,396,-3312,-3385,1.03991234302521 +18593,0.312339097261429,-0.045994721353054,0.040470335632563,40703,-48,-2369,-3181,1.05187201499939 +18595,0.297651499509811,-0.050072118639946,0.041454870253801,40703,1016,-2308,-3358,1.05134296417236 +18597,0.290940582752228,-0.061260044574738,0.041778244078159,40703,-115,-1491,-3163,1.04347598552704 +18599,0.286822855472565,-0.057210043072701,0.041043821722269,40703,308,-2760,-3355,1.03532683849335 +18601,0.28919193148613,-0.055936120450497,0.041570317000151,40703,-844,-2445,-3157,1.03175568580627 +18603,0.287831157445908,-0.058637090027332,0.039899442344904,40703,-9,-2230,-3356,1.02951276302338 +18605,0.281941682100296,-0.057085584849119,0.038600124418736,40703,-231,-2431,-3185,1.02757096290588 +18607,0.276331752538681,-0.054264396429062,0.038299459964037,40703,357,-2663,-3361,1.02525794506073 +18609,0.269467622041702,-0.050541054457426,0.038204696029425,40703,-54,-2672,-3182,1.02619802951813 +18611,0.268763571977615,-0.057665128260851,0.036695808172226,40703,17,-1880,-3366,1.02993500232697 +18613,0.268484950065613,-0.059456195682287,0.036320447921753,40703,-606,-2097,-3200,1.03341519832611 +18615,0.262957215309143,-0.061366379261017,0.035839956253767,40703,348,-2173,-3366,1.03757953643799 +18617,0.260761201381683,-0.066997870802879,0.035708114504814,40703,-439,-1666,-3203,1.03250360488892 +18619,0.253169119358063,-0.060952987521887,0.03809429705143,40703,542,-2717,-3345,1.02311730384827 +18621,0.248583793640137,-0.059571079909802,0.040816139429808,40703,-166,-2261,-3135,1.01692843437195 +18623,0.242915317416191,-0.053118873387575,0.044743049889803,40703,461,-2830,-3293,1.01204562187195 +18625,0.244500294327736,-0.062254153192043,0.046416345983744,40703,-631,-1436,-3062,1.00946652889252 +18627,0.247912794351578,-0.063898324966431,0.042540788650513,40703,-350,-2066,-3301,1.00691211223602 +18629,0.249923124909401,-0.065489865839481,0.040449198335409,40703,-831,-1901,-3126,1.0052011013031 +18643,0.218025386333466,-0.065631650388241,0.042575020343065,40703,596,-2208,-3276,1.02151250839233 +18645,0.219694465398788,-0.065972208976746,0.037899933755398,40703,-676,-1859,-3130,1.02469909191132 +18647,0.226683497428894,-0.061516776680946,0.03658127039671,40703,-739,-2378,-3311,1.02540576457977 +18649,0.231462687253952,-0.063102655112743,0.035957835614681,40703,-1169,-1789,-3146,1.02893245220184 +18651,0.228087827563286,-0.05891377478838,0.034763619303703,40703,-104,-2368,-3318,1.03105115890503 +18653,0.225908637046814,-0.067523159086704,0.036618161946535,40703,-672,-1175,-3133,1.03435587882996 +18655,0.225718915462494,-0.072044275701046,0.037060614675284,40703,-385,-1522,-3296,1.03777194023132 +18657,0.224734976887703,-0.061484143137932,0.03519007563591,40703,-823,-2606,-3142,1.03816390037537 +18659,0.220445036888123,-0.052945706993342,0.035490266978741,40703,-102,-2700,-3301,1.03486430644989 +18661,0.213134244084358,-0.044948764145374,0.037750091403723,40703,-255,-2664,-3104,1.0331484079361 +18663,0.207707747817039,-0.048657428473234,0.037713345140219,40703,81,-1860,-3280,1.03112399578094 +18665,0.200549677014351,-0.041686180979014,0.033603765070438,40703,-132,-2620,-3146,1.02829885482788 +18667,0.192468166351318,-0.034089658409357,0.031175661832094,40703,416,-2856,-3319,1.03043043613434 +18669,0.18281477689743,-0.023380022495985,0.036018554121256,40703,267,-3168,-3110,1.02843606472015 +18671,0.174004524946213,-0.019435506314039,0.041514217853546,40703,667,-2790,-3242,1.02620935440063 +18673,0.171184748411179,-0.019578689709306,0.042976040393114,40703,-104,-2439,-3021,1.02671682834625 +18675,0.170586466789246,-0.01350399106741,0.041464876383543,40703,66,-3016,-3235,1.02853798866272 +18677,0.169189289212227,-0.015521252527833,0.038068421185017,40703,-246,-2361,-3071,1.03307414054871 +18679,0.168040990829468,-0.015316189266741,0.03369913995266,40703,78,-2559,-3282,1.03351509571075 +18681,0.163986474275589,-0.007755397818983,0.035299468785524,40703,-35,-3171,-3097,1.03382050991058 +18683,0.162701994180679,-0.001266453531571,0.039551496505737,40703,102,-3205,-3236,1.03650379180908 +18685,0.161807611584663,0.005399465095252,0.040841292589903,40703,-289,-3326,-3023,1.04255342483521 +18687,0.157751515507698,2.75116562988842E-05,0.036248575896025,40703,310,-2375,-3252,1.04474759101868 +18689,0.149620294570923,0.002252146601677,0.032897051423788,40703,367,-2958,-3111,1.04393041133881 +18691,0.149070784449577,-0.003441653447226,0.035994242876768,40703,126,-2302,-3248,1.03992569446564 +18693,0.146575063467026,-0.001310682157055,0.037546895444393,40703,-40,-2889,-3051,1.03523170948029 +18695,0.140147849917412,0.003026576945558,0.033561322838068,40703,620,-3112,-3259,1.03346955776215 +18697,0.136734083294869,0.009852246381342,0.030765820294619,40703,137,-3402,-3124,1.03415203094482 +18699,0.134828835725784,0.016458375379443,0.030037803575397,40703,321,-3469,-3278,1.03449010848999 +18701,0.132112264633179,0.00875726249069,0.028625844046474,40703,-32767,-32767,-3144,1.03327000141144 +18703,0.123592853546143,0.003113998565823,0.025827484205365,40703,-5850,-27676,-3302,1.02997648715973 +18705,0.118696272373199,0.000176344125066,0.030916901305318,40703,-6341,-27943,-3113,1.02852809429169 +18707,0.11584934592247,0.003529703244567,0.031461212784052,40703,-6254,-28573,-3258,1.02499687671661 +18709,0.110968872904778,0.006842012517154,0.02734600007534,40703,-6323,-28744,-3149,1.02402853965759 +18711,0.107931822538376,-0.00460329791531,0.021147327497602,40703,-6232,-27646,-3324,1.02053904533386 +18713,0.099228657782078,-0.021755080670118,0.016187064349651,40703,-5962,-27059,-3279,1.02347421646118 +18715,0.081036984920502,-0.05640546604991,0.014020246453583,40703,-4860,-25478,-3370,1.02973592281342 +18717,0.056934654712677,-0.094120368361473,0.011215450242162,40703,-4268,-24636,-3342,1.03793978691101 +18719,0.038898799568415,-0.151130765676498,0.008375380188227,40703,-4349,-22721,-3407,1.04850649833679 +18721,0.019087880849838,-0.217927396297455,0.003326448379084,40703,-4036,-20719,-3444,1.05209624767303 +18723,-0.009880692698061,-0.287006795406342,-0.004197278991342,40703,-2931,-20054,-3493,1.05189990997314 +18725,-0.038330461829901,-0.372313022613525,-0.00553543958813,40703,-2537,-16995,-3563,1.04645621776581 +18727,-0.064800821244717,-0.457297384738922,-0.005128961056471,40703,-2360,-16546,-3502,1.03942215442657 +18729,-0.080593302845955,-0.56430447101593,-0.009990658611059,40703,-2783,-12353,-3635,1.03095018863678 +18731,-0.100534804165363,-0.666377723217011,-0.016939159482718,40703,-2334,-12307,-3586,1.02112197875977 +18733,-0.120677068829536,-0.784110069274902,-0.019658727571368,40703,-1827,-7947,-3773,1.012087225914 +18735,-0.152762979269028,-0.892073929309845,-0.019041586667299,40703,-714,-8527,-3606,1.00209021568298 +18737,-0.182933539152145,-1.00669836997986,-0.019249707460404,40703,-93,-4385,-3796,1.00342428684235 +18739,-0.205750271677971,-1.13015031814575,-0.021296972408891,40703,-590,-3777,-3627,1.00398397445679 +18741,-0.226603880524635,-1.24162805080414,-0.024873023852706,40703,-5,-532,-3895,1.00699436664581 +18743,-0.247036874294281,-1.35412883758545,-0.029626522213221,40703,-118,-1015,-3693,1.01566779613495 +18745,-0.271647959947586,-1.46693754196167,-0.027625424787402,40703,1051,3599,-3964,1.02451884746552 +18747,-0.289269059896469,-1.58656466007233,-0.024968544021249,40703,356,3270,-3670,1.02637481689453 +18749,-0.31328871846199,-1.68543589115143,-0.02316196449101,40703,1770,6638,-3952,1.02861332893372 +18751,-0.331100076436996,-1.79054880142212,-0.021334217861295,40703,1061,5703,-3655,1.02615547180176 +18753,-0.349977344274521,-1.88472104072571,-0.023890402168036,40703,2094,10126,-4002,1.02222907543182 +18755,-0.362255424261093,-1.97689437866211,-0.024553030729294,40703,1221,8092,-3687,1.02306520938873 +18757,-0.3675357401371,-2.06170606613159,-0.024923441931605,40703,1519,13004,-4059,1.01945316791534 +18759,-0.372403234243393,-2.13169384002686,-0.021761002019048,40703,954,9451,-3680,1.02271139621735 +18761,-0.377033829689026,-2.20356154441833,-0.018509829416871,40703,1744,15138,-4026,1.02477288246155 +18763,-0.381696164608002,-2.26661658287048,-0.018299248069525,40703,1195,11689,-3669,1.02750992774963 +18765,-0.378724008798599,-2.3374879360199,-0.018038889393211,40703,1355,18064,-4066,1.03143417835236 +18767,-0.376322537660599,-2.37616062164307,-0.016939878463745,40703,738,12380,-3672,1.04248535633087 +18769,-0.375127077102661,-2.40178990364075,-0.014434819109738,40703,1554,16747,-4062,1.05654835700989 +18771,-0.379564732313156,-2.41943287849426,-0.015130100771785,40703,1400,12397,-3673,1.06169211864471 +18773,-0.374751389026642,-2.42941355705261,-0.01829625852406,40703,1410,16974,-4141,1.06165933609009 +18775,-0.356715232133865,-2.43628859519958,-0.022259438410401,40703,-411,12788,-3737,1.05892169475555 +18793,-0.22321780025959,-2.09030413627625,-0.012396684847772,40703,-1106,10105,-4153,1.05415403842926 +18795,-0.2051150649786,-2.00478553771973,-0.014273486100137,40703,-2170,4350,-3757,1.0456759929657 +18797,-0.185693398118019,-1.91921436786652,-0.013856142759323,40703,-2181,7000,-4162,1.03773856163025 +18799,-0.16942885518074,-1.83671641349792,-0.011727124452591,40703,-2504,2877,-3753,1.0332887172699 +18801,-0.153535827994347,-1.74892127513886,-0.007942676544189,40703,-2415,4753,-4079,1.03579640388489 +18803,-0.138264611363411,-1.66254460811615,-0.002116568386555,40703,-2848,747,-3699,1.04232585430145 +18805,-0.127637639641762,-1.57192754745483,0.005458519328386,40703,-2433,2281,-3903,1.04466795921326 +18807,-0.120405465364456,-1.47566211223602,0.009826024994254,40703,-2508,-2072,-3625,1.04534554481506 +18809,-0.112051717936993,-1.37981712818146,0.011797021143138,40703,-2517,-688,-3800,1.04581594467163 +18811,-0.107876993715763,-1.28324592113495,0.012653874233365,40703,-2457,-4369,-3612,1.04383409023285 +18813,-0.110709197819233,-1.19063782691956,0.013472949154675,40703,-1737,-3090,-3749,1.04639387130737 +18815,-0.108198098838329,-1.09467566013336,0.016914449632168,40703,-2324,-6630,-3588,1.04672253131866 +18817,-0.105228967964649,-0.990996360778809,0.024005716666579,40703,-2234,-6771,-3594,1.04856598377228 +18819,-0.111260458827019,-0.894101202487946,0.026794943958521,40703,-1661,-9263,-3521,1.0517019033432 +18821,-0.121048390865326,-0.80789190530777,0.027125496417284,40703,-1049,-8218,-3526,1.05178463459015 +18823,-0.123845100402832,-0.734957098960876,0.028159579262138,40703,-1697,-9599,-3512,1.04903244972229 +18825,-0.123012997210026,-0.655282318592072,0.027738383039832,40703,-1762,-10025,-3491,1.04273784160614 +18827,-0.124906994402409,-0.580687999725342,0.029194869101048,40703,-1730,-11768,-3504,1.03954970836639 +18829,-0.135463699698448,-0.522820472717285,0.032534595578909,40703,-727,-10477,-3408,1.03589820861816 +18831,-0.153255730867386,-0.468223333358765,0.035981591790915,40703,-162,-11844,-3455,1.03242015838623 +18833,-0.166909292340279,-0.418579190969467,0.035998899489641,40703,35,-11501,-3346,1.02914476394653 +18835,-0.174922198057175,-0.367967814207077,0.033795714378357,40703,-514,-12939,-3467,1.02920210361481 +18837,-0.184998244047165,-0.318285673856735,0.032848741859198,40703,106,-13096,-3357,1.03565669059753 +18839,-0.19333204627037,-0.288879305124283,0.031817637383938,40703,-183,-12542,-3476,1.04519808292389 +18841,-0.207949593663216,-0.262132495641708,0.028972653672099,40703,850,-12362,-3386,1.05016827583313 +18843,-0.218633487820625,-0.240963369607925,0.025606380775571,40703,403,-12651,-3515,1.05030989646912 +18845,-0.237095326185226,-0.212027579545975,0.023056840524078,40703,1655,-13357,-3440,1.04361474514008 +18847,-0.257281512022018,-0.188715189695358,0.024149861186743,40703,1707,-13589,-3522,1.04199123382568 +18849,-0.264194041490555,-0.186014160513878,0.025320328772068,40703,1339,-11945,-3404,1.04163086414337 +18851,-0.268145978450775,-0.192590042948723,0.02450748346746,40703,780,-11440,-3516,1.0408011674881 +18853,-0.272789657115936,-0.200621217489242,0.025127096101642,40703,1406,-10988,-3410,1.04006695747375 +18855,-0.281687796115875,-0.203086271882057,0.02374086715281,40703,1416,-11625,-3518,1.04045152664185 +18857,-0.287907153367996,-0.213131204247475,0.022798532620072,40703,1852,-10681,-3436,1.0445876121521 +18859,-0.295835614204407,-0.227216497063637,0.024404067546129,40703,1643,-10481,-3511,1.04615688323975 +18861,-0.302539169788361,-0.248868152499199,0.025876127183437,40703,2214,-9294,-3403,1.05147194862366 +18863,-0.304150015115738,-0.28441521525383,0.022452909499407,40703,1410,-8141,-3521,1.04963278770447 +18865,-0.308244436979294,-0.313716232776642,0.01866820268333,40703,2230,-7694,-3504,1.04280638694763 +18867,-0.309963166713715,-0.345072776079178,0.018516328185797,40703,1607,-7557,-3546,1.03565216064453 +18869,-0.311040073633194,-0.372719585895538,0.019806779921055,40703,2170,-6829,-3507,1.03296220302582 +18871,-0.310693502426147,-0.410602241754532,0.019015120342374,40703,1577,-6108,-3542,1.03654766082764 +18873,-0.309749931097031,-0.453913182020187,0.017947312444449,40703,2118,-4332,-3551,1.03653931617737 +18875,-0.309982895851135,-0.490249991416931,0.022684529423714,40703,1718,-4998,-3517,1.03764891624451 +18877,-0.300893932580948,-0.533910274505615,0.027630742639303,40703,1495,-2909,-3458,1.0395565032959 +18879,-0.29110786318779,-0.570569694042206,0.028728827834129,40703,835,-3705,-3474,1.03942799568176 +18881,-0.275449842214584,-0.62553870677948,0.029427571222186,40703,711,-473,-3462,1.03622364997864 +18883,-0.269210338592529,-0.666063189506531,0.031019426882267,40703,869,-1897,-3458,1.0355464220047 +18885,-0.258221596479416,-0.711232542991638,0.034762769937515,40703,850,393,-3421,1.03514111042023 +18887,-0.247963175177574,-0.741480112075806,0.034817099571228,40703,363,-1350,-3432,1.03358912467957 +18889,-0.233938947319984,-0.774482190608978,0.031223118305206,40703,302,757,-3473,1.03535139560699 +18891,-0.216411352157593,-0.806045293807983,0.029820868745446,40703,-537,-98,-3467,1.03463220596313 +18893,-0.200811982154846,-0.832952976226806,0.028591925278306,40703,-284,1512,-3522,1.03549945354462 +18895,-0.185480162501335,-0.864200413227081,0.027366990223527,40703,-766,973,-3485,1.04229819774628 +18897,-0.168478161096573,-0.882963061332703,0.027267539873719,40703,-846,2017,-3561,1.04259836673737 +18899,-0.144201561808586,-0.907553255558014,0.029537862166762,40703,-1953,1405,-3472,1.04011118412018 +18901,-0.12273907661438,-0.9253289103508,0.032100584357977,40703,-1861,2939,-3525,1.03997433185577 +18903,-0.108075253665447,-0.933830559253693,0.035932194441557,40703,-1756,939,-3431,1.04496693611145 +18905,-0.094822771847248,-0.939170181751251,0.035890635102987,40703,-1701,2596,-3490,1.04144096374512 +18907,-0.076135158538818,-0.944339990615845,0.034289002418518,40703,-2488,1172,-3444,1.03044617176056 +18909,-0.053224872797728,-0.954310834407806,0.03265755623579,40703,-3059,3491,-3536,1.02217936515808 +18911,-0.039095837622881,-0.949511408805847,0.031612847000361,40703,-2696,860,-3465,1.02331304550171 +18913,-0.033325254917145,-0.94983971118927,0.030863938853145,40703,-2155,3052,-3562,1.02877449989319 +18915,-0.021559542044997,-0.949077129364014,0.028915537521243,40703,-2790,1472,-3487,1.0328950881958 +18917,-0.003407289041206,-0.943952977657318,0.029442150145769,40703,-3538,2894,-3584,1.03581011295319 +18919,0.009444725699723,-0.935484170913696,0.030583208426833,40703,-3336,1054,-3478,1.03252577781677 +18921,0.014453719370067,-0.913325369358063,0.028491144999862,40703,-2923,1492,-3585,1.02657389640808 +18923,0.022419039160013,-0.893200695514679,0.026111179962754,40703,-3206,-71,-3512,1.02107322216034 +18925,0.034920457750559,-0.866481065750122,0.027239739894867,40703,-3844,707,-3582,1.01962494850159 +18927,0.049363646656275,-0.851229548454285,0.028192948549986,40703,-4102,-27,-3501,1.02114236354828 +18929,0.050114937126637,-0.828209280967712,0.028299080207944,40703,-3318,625,-3550,1.01924753189087 +18931,0.041445966809988,-0.803165078163147,0.03078155964613,40703,-2388,-1140,-3484,1.02230143547058 +18933,0.03222119808197,-0.777526259422302,0.033356156200171,40703,-2364,-121,-3477,1.02863156795502 +18935,0.028629215434194,-0.742816150188446,0.032319858670235,40703,-2616,-2441,-3474,1.037193775177 +18937,0.030538970604539,-0.709729254245758,0.029926922172308,40703,-3167,-1509,-3506,1.04490065574646 +18939,0.033124644309282,-0.675303936004639,0.027572836726904,40703,-3168,-3161,-3507,1.04887926578522 +18941,0.030246468260884,-0.648669183254242,0.02948934212327,40703,-2860,-1821,-3497,1.05259358882904 +18943,0.025954101234675,-0.620774567127228,0.031358502805233,40703,-2616,-3273,-3481,1.05035614967346 +18945,0.013872915878892,-0.583794474601746,0.029946418479085,40703,-1988,-3430,-3467,1.04523551464081 +18947,0.001469282549806,-0.548712968826294,0.032174903899431,40703,-1723,-4648,-3475,1.04259884357452 +18949,-0.005760078784078,-0.516509056091309,0.035015657544136,40703,-2055,-4022,-3386,1.04186618328094 +18951,-0.011327497661114,-0.497848778963089,0.034304544329643,40703,-2060,-4057,-3458,1.03946685791016 +18953,-0.026609893888235,-0.471992939710617,0.035209655761719,40703,-1155,-4150,-3375,1.03255224227905 +18955,-0.041379898786545,-0.442601710557938,0.039153803139925,40703,-988,-5493,-3422,1.02603340148926 +18957,-0.057132944464684,-0.405606687068939,0.043817885220051,40703,-632,-5901,-3257,1.02392792701721 +18959,-0.077206701040268,-0.361933320760727,0.045948579907417,40703,-98,-7575,-3371,1.02477765083313 +18961,-0.090049497783184,-0.340847611427307,0.043093252927065,40703,-306,-5727,-3242,1.0216109752655 +18963,-0.097462631762028,-0.326865881681442,0.038016069680452,40703,-704,-5881,-3420,1.01380836963654 +18965,-0.102088175714016,-0.314620286226273,0.037633143365383,40703,-702,-5468,-3285,1.011345744133 +18967,-0.115038692951202,-0.299453496932983,0.038989085704088,40703,-42,-6302,-3409,1.0098751783371 +18969,-0.136614084243774,-0.278638511896133,0.039729535579681,40703,1085,-6625,-3242,1.01117241382599 +18971,-0.157255604863167,-0.262037336826324,0.041258599609137,40703,1142,-6902,-3388,1.01493752002716 +18973,-0.171527743339539,-0.245470345020294,0.039659112691879,40703,1171,-6829,-3232,1.01947331428528 +18975,-0.175562515854835,-0.237521424889564,0.037859749048948,40703,261,-6610,-3406,1.02508234977722 +18977,-0.182177722454071,-0.225918620824814,0.0382732860744,40703,841,-6771,-3237,1.02969348430634 +18979,-0.192688584327698,-0.216073557734489,0.037821233272553,40703,1021,-7038,-3401,1.03652429580688 +18981,-0.199630871415138,-0.207911342382431,0.037299443036318,40703,1200,-6803,-3236,1.03754353523254 +18983,-0.204986557364464,-0.196260705590248,0.035866633057594,40703,887,-7443,-3408,1.0361225605011 +18985,-0.21285817027092,-0.194725498557091,0.034395225346089,40703,1542,-6539,-3261,1.03111088275909 +18987,-0.221607580780983,-0.194287970662117,0.032800853252411,40703,1434,-6666,-3424,1.0215402841568 +18989,-0.22882878780365,-0.193148329854012,0.033548966050148,40703,1830,-6534,-3269,1.02092278003693 +18991,-0.241552278399467,-0.189925789833069,0.034226946532726,40703,2079,-6926,-3409,1.01951467990875 +18993,-0.253536254167557,-0.19177357852459,0.032811176031828,40703,2665,-6331,-3280,1.02310919761658 +18995,-0.251243323087692,-0.207103133201599,0.030060037970543,40703,1231,-5347,-3433,1.02707314491272 +18997,-0.244946137070656,-0.211128130555153,0.031695701181889,40703,1308,-5846,-3298,1.02875375747681 +18999,-0.239774376153946,-0.21770553290844,0.035378262400627,40703,946,-5808,-3393,1.02566313743591 +19001,-0.238428056240082,-0.217489913105965,0.031582787632942,40703,1637,-6030,-3295,1.02255976200104 +19003,-0.236415699124336,-0.232184380292892,0.027677463367581,40703,1207,-5001,-3442,1.02028393745422 +19005,-0.23590050637722,-0.246798887848854,0.026457354426384,40703,1732,-4482,-3357,1.01466810703278 +19007,-0.240066632628441,-0.253021448850632,0.028492659330368,40703,1783,-5281,-3433,1.01541101932526 +19021,-0.151467368006706,-0.330282926559448,0.034589819610119,40703,-222,-2760,-3277,1.03434610366821 +19023,-0.138793885707855,-0.344858080148697,0.03695160895586,40703,-623,-3164,-3359,1.02937424182892 +19025,-0.121194675564766,-0.347901821136475,0.039754621684551,40703,-1050,-3411,-3215,1.02248930931091 +19027,-0.098861321806908,-0.361882090568542,0.039479337632656,40703,-1858,-2883,-3338,1.01251089572907 +19029,-0.084175154566765,-0.364352256059647,0.036355078220368,40703,-1417,-3113,-3259,1.00313806533813 +19031,-0.074484072625637,-0.376984894275665,0.031894903630018,40703,-1289,-2677,-3387,1.00606918334961 +19033,-0.0650629773736,-0.380643576383591,0.030438071116805,40703,-1336,-2675,-3332,1.01420915126801 +19035,-0.04935871437192,-0.384451299905777,0.034405689686537,40703,-2074,-3108,-3367,1.02691984176636 +19037,-0.032388098537922,-0.386260002851486,0.039896983653307,40703,-2415,-2621,-3218,1.03861260414124 +19039,-0.016551814973354,-0.386678159236908,0.042986128479242,40703,32767,32767,-3304,1.04358077049255 +19041,-0.001526898005977,-0.390565156936646,0.041255958378315,40703,3955,22970,-3194,1.04503011703491 +19043,0.010407345369458,-0.386070102453232,0.03725528717041,40703,4095,21915,-3340,1.04486215114594 +19045,0.024896426126361,-0.397045761346817,0.03782980889082,40703,3594,23932,-3228,1.04709279537201 +19047,0.035909421741963,-0.398432344198227,0.037052243947983,40703,3822,22868,-3337,1.04703164100647 +19049,0.050602044910193,-0.387082606554031,0.033019535243511,40703,3175,22519,-3271,1.05099785327911 +19051,0.075593300163746,-0.361660480499268,0.030061485245824,40703,2265,20769,-3382,1.04729926586151 +19053,0.104638747870922,-0.318926990032196,0.028261849656701,40703,1274,19496,-3303,1.04555666446686 +19055,0.129936456680298,-0.263828873634338,0.027742844074965,40703,1453,17558,-3395,1.04742443561554 +19057,0.149258032441139,-0.186925515532494,0.027909997850657,40703,1229,15201,-3266,1.05236303806305 +19059,0.176080942153931,-0.110558323562145,0.024825086817145,40703,650,14095,-3411,1.05485451221466 +19061,0.2104452252388,-0.030237475410104,0.023911206051707,40703,-884,12643,-3261,1.05000734329224 +19063,0.243441700935364,0.060532089322806,0.024709640070796,40703,-817,10797,-3406,1.04232037067413 +19065,0.272232979536057,0.163831770420074,0.022720685228706,40703,-1563,7997,-3212,1.04025769233704 +19067,0.298879981040955,0.275768458843231,0.016369316726923,40703,-1247,6292,-3457,1.04139816761017 +19069,0.323084384202957,0.383148491382599,0.011680190451443,40703,-2159,4182,-3273,1.04772055149078 +19071,0.343308687210083,0.502747774124146,0.010317610576749,40703,-1537,2482,-3491,1.05190801620483 +19073,0.366706073284149,0.632761955261231,0.011089160107076,40703,-2941,-1559,-3201,1.05530452728271 +19075,0.394174814224243,0.77511465549469,0.014207107014954,40703,-2922,-3176,-3455,1.0549578666687 +19077,0.418704658746719,0.917094826698303,0.021985301747918,40703,-4031,-7209,-2982,1.05427300930023 +19079,0.437957644462586,1.03816974163055,0.027173861861229,40703,-3126,-5680,-3352,1.05418491363525 +19081,0.458800107240677,1.15836882591248,0.025131555274129,40703,-4597,-9865,-2874,1.05204522609711 +19083,0.479420900344849,1.28614234924316,0.026890447363258,40703,-4004,-10084,-3337,1.04845976829529 +19085,0.489304661750794,1.41702449321747,0.030567545443773,40703,-4495,-15256,-2743,1.04410266876221 +19087,0.49207153916359,1.53726649284363,0.032412201166153,40703,-3106,-13637,-3280,1.04119002819061 +19089,0.490711122751236,1.63583791255951,0.031367488205433,40703,-3914,-17024,-2676,1.04140794277191 +19091,0.492963522672653,1.73710715770721,0.031135857105255,40703,-3284,-15739,-3268,1.04050850868225 +19093,0.494283199310303,1.84637880325317,0.032781753689051,40703,-4371,-21841,-2606,1.04436004161835 +19095,0.491139054298401,1.95140171051025,0.035153452306986,40703,-3077,-19777,-3219,1.04283511638641 +19097,0.479616075754166,2.03713440895081,0.036810230463743,40703,-3411,-23994,-2517,1.03796815872192 +19099,0.469251930713654,2.10206627845764,0.035145606845617,40703,-2446,-19855,-3196,1.03336048126221 +19101,0.460722833871841,2.16156792640686,0.031147239729762,40703,-3505,-24959,-2560,1.02831423282623 +19103,0.451997846364975,2.21687388420105,0.02949926070869,40703,-2507,-21666,-3213,1.03068387508392 +19105,0.438669085502625,2.25825309753418,0.027780845761299,40703,-2985,-26101,-2581,1.035320520401 +19107,0.422042578458786,2.29402732849121,0.023910604417324,40703,-1693,-22278,-3230,1.03350186347961 +19109,0.4068883061409,2.31866383552551,0.022580659016967,40703,-2514,-26792,-2629,1.02831029891968 +19111,0.387566775083542,2.34520983695984,0.021878825500608,40703,-1174,-23288,-3223,1.02544343471527 +19113,0.375941425561905,2.36170077323914,0.020758923143149,40703,-2434,-27842,-2639,1.02717852592468 +19115,0.364916086196899,2.35952925682068,0.019367581233382,40703,-26302,-32767,-3220,1.02760779857636 +19117,0.349447846412659,2.34048366546631,0.017974242568016,40703,-6045,-32767,-2679,1.02744138240814 +19119,0.328644901514053,2.31473684310913,0.013514223508537,40703,-4717,-32767,-3242,1.02542889118195 +19121,0.303732991218567,2.28689765930176,0.008693753741682,40703,-4787,-32767,-2803,1.0225065946579 +19123,0.282435864210129,2.24053931236267,0.004172660410404,40703,-4183,-32767,-3291,1.02491247653961 +19125,0.257961422204971,2.18894219398499,-0.005379396490753,40703,-4214,-32767,-2990,1.02900326251984 +19127,0.231895416975021,2.12430310249329,-0.012250839732587,40703,-3257,-32268,-3391,1.03255617618561 +19129,0.206056028604507,2.05653619766235,-0.015192382968962,40703,-3396,-32767,-3130,1.02864718437195 +19131,0.180927202105522,1.99063348770142,-0.01902499049902,40703,-2710,-31252,-3428,1.02503824234009 +19133,0.161299988627434,1.89503169059753,-0.026026139035821,40703,-3221,-31863,-3283,1.0245840549469 +19135,0.133530914783478,1.78598833084106,-0.031745851039887,40703,-1938,-26148,-3509,1.02601087093353 +19137,0.099830836057663,1.66225457191467,-0.034432113170624,40703,-1296,-26938,-3419,1.0245943069458 +19139,0.058681908994913,1.55658984184265,-0.036502625793219,40703,25,-23920,-3538,1.0260763168335 +19141,0.038190774619579,1.43096625804901,-0.041012767702341,40703,-1293,-23812,-3534,1.02189242839813 +19143,0.017415221780539,1.2990517616272,-0.046253532171249,40703,-881,-19063,-3603,1.0163733959198 +19145,-0.001870975480415,1.15919637680054,-0.047398224473,40703,-752,-19033,-3654,1.01489305496216 +19147,-0.014625329524279,1.00628876686096,-0.056427843868733,40703,-1017,-13955,-3674,1.01393473148346 +19149,-0.03326603025198,0.860438823699951,-0.062661215662956,40703,-294,-14286,-3885,1.01936173439026 +19151,-0.056334260851145,0.712220013141632,-0.064899690449238,40703,314,-10534,-3738,1.02126824855804 +19153,-0.072365470230579,0.553995907306671,-0.062584057450295,40703,24858,20031,-3937,1.03320336341858 +19155,-0.088467538356781,0.389145493507385,-0.061933621764183,40703,4461,-159,-3724,1.04316115379334 +19157,-0.103330411016941,0.236860290169716,-0.066217586398125,40703,4795,556,-4038,1.04544484615326 +19159,-0.117916814982891,0.078666545450688,-0.066417388617992,40703,4845,3687,-3764,1.04608726501465 +19161,-0.13483452796936,-0.064756080508232,-0.062539890408516,40703,5528,4769,-4051,1.04071950912476 +19163,-0.132027313113213,-0.22345869243145,-0.055570885539055,40703,3886,8069,-3700,1.0460764169693 +19165,-0.13343209028244,-0.353775918483734,-0.048978298902512,40703,4475,8605,-3947,1.04160630702972 +19167,-0.128813624382019,-0.482201099395752,-0.046467330306769,40703,3793,9758,-3647,1.03417873382568 +19169,-0.115818180143833,-0.583617627620697,-0.043619327247143,40703,3234,10450,-3931,1.03563463687897 +19171,-0.08653362095356,-0.682271480560303,-0.036328826099634,40703,1494,10745,-3587,1.03764176368713 +19173,-0.053175080567598,-0.782020449638367,-0.035792753100395,40703,833,13837,-3886,1.03723621368408 +19175,-0.025459818542004,-0.860154211521149,-0.03893193975091,40703,779,12168,-3615,1.0406596660614 +19177,0.003245555795729,-0.929076552391052,-0.035266764461994,40703,290,14382,-3915,1.03612101078033 +19179,0.030162107199431,-0.975760102272034,-0.03203533962369,40703,62,11983,-3578,1.04296147823334 +19181,0.061863619834185,-1.03573501110077,-0.031107781454921,40703,-861,15914,-3894,1.04767465591431 +19183,0.09439080953598,-1.07403290271759,-0.033706016838551,40703,-1263,13255,-3600,1.05220520496368 +19185,0.128779292106628,-1.10632348060608,-0.037180587649345,40703,-2152,15561,-3988,1.0555591583252 +19187,0.187745228409767,-1.10151898860931,-0.04180233925581,40703,-2996,32767,-4050,1.05043196678162 +19189,0.187745228409767,-1.10151898860931,-0.04180233925581,40703,-2996,32767,-4050,1.05043196678162 +19191,0.222729444503784,-1.09080862998962,-0.038960583508015,40703,-3374,20668,-3660,1.04845988750458 +19193,0.256480604410171,-1.06919288635254,-0.037753354758024,40703,-4303,19906,-3662,1.0497077703476 +19195,0.310669332742691,-1.00468528270721,-0.034488070756197,40703,-4614,19751,-3961,1.05168735980988 +19197,0.338364124298096,-0.955009996891022,-0.035315338522196,40703,-4724,17067,-3657,1.0575168132782 +19199,0.363214641809463,-0.883742332458496,-0.041925966739655,40703,-5637,16318,-4035,1.06079399585724 +19201,0.363214641809463,-0.883742332458496,-0.041925966739655,40703,-5637,16318,-4035,1.06079399585724 +19203,0.420877248048782,-0.722287833690643,-0.044485412538052,40703,-6988,13096,-4047,1.06081855297089 +19205,0.443475604057312,-0.617654800415039,-0.044033359736204,40703,-6184,9215,-3738,1.05562245845795 +19207,0.461004555225372,-0.505436539649963,-0.048089310526848,40703,-7049,8078,-4064,1.05109322071075 +19209,0.475894629955292,-0.395006507635117,-0.050995111465454,40703,-6290,5933,-3796,1.04915320873261 +19211,0.475894629955292,-0.395006507635117,-0.050995111465454,40703,-6290,5933,-3796,1.04915320873261 +19213,0.498660236597061,-0.161369636654854,-0.045909747481346,40703,-6389,1866,-3770,1.05511999130249 +19215,0.497300118207931,-0.022930271923542,-0.042244244366884,40703,-6708,-1192,-3949,1.05837547779083 +19217,0.494501858949661,0.119090437889099,-0.04213510453701,40703,-5715,-3371,-3750,1.06093156337738 +19219,0.487641572952271,0.257081657648087,-0.042901214212179,40703,-6369,-5660,-3936,1.05971717834473 +19221,0.487641572952271,0.257081657648087,-0.042901214212179,40703,-6369,-5660,-3936,1.05971717834473 +19223,0.470073908567429,0.522839784622192,-0.033732213079929,40703,-6315,-9584,-3812,1.05292081832886 +19225,0.460164695978165,0.651093661785126,-0.032513335347176,40703,-5130,-10184,-3694,1.04920291900635 +19227,0.443669736385346,0.770147860050201,-0.028616208583117,40703,-5375,-12895,-3741,1.05133628845215 +19229,0.419395118951798,0.886087596416473,-0.025823326781392,40703,-3711,-12931,-3650,1.05367684364319 +19231,0.419395118951798,0.886087596416473,-0.025823326781392,40703,-3711,-12931,-3650,1.05622971057892 +19233,0.370997488498688,1.10536110401154,-0.021174861118198,40703,-3115,-15875,-3619,1.05799973011017 +19249,0.08773110806942,1.68677926063538,-0.015549545176327,40703,1250,-21753,-3580,1.02683484554291 +19251,0.051535055041313,1.71863269805908,-0.016546165570617,40703,1734,-25199,-3587,1.03325653076172 +19253,0.021570859476924,1.73958003520966,-0.018418783321977,40703,1809,-21783,-3599,1.04519736766815 +19255,-0.007013972848654,1.76143062114716,-0.021807219833136,40703,2148,-25894,-3650,1.04897880554199 +19257,-0.032898258417845,1.76997208595276,-0.025658566504717,40703,2311,-22070,-3650,1.04574763774872 +19259,-0.06355856359005,1.76584494113922,-0.028214247897267,40703,3243,-24842,-3725,1.04073750972748 +19261,-0.093472018837929,1.74517166614532,-0.029437612742186,40703,3508,-20367,-3678,1.03932011127472 +19263,-0.119461625814438,1.71559309959412,-0.030791956931353,40703,3853,-22937,-3753,1.03440177440643 +19265,-0.143486604094505,1.68667912483215,-0.031576730310917,40703,3866,-19665,-3694,1.03115653991699 +19267,-0.165697306394577,1.64989054203033,-0.030407819896937,40703,4387,-22073,-3746,1.03097474575043 +19269,-0.18704842031002,1.61554169654846,-0.032032757997513,40703,4381,-18959,-3699,1.03326976299286 +19271,-0.200635179877281,1.5645010471344,-0.034629132598639,40703,4434,-20354,-3799,1.03729605674744 +19273,-0.212388649582863,1.5116605758667,-0.041133292019367,40703,4156,-16814,-3765,1.04190015792847 +19275,-0.217326372861862,1.447958111763,-0.042638186365366,40703,4192,-18192,-3897,1.04985272884369 +19277,-0.220002666115761,1.37271583080292,-0.043664369732142,40703,3723,-13836,-3786,1.04864525794983 +19279,-0.228243499994278,1.29880690574646,-0.047058068215847,40703,4722,-15619,-3958,1.05031061172485 +19281,-0.227970138192177,1.22057342529297,-0.051423277705908,40703,3741,-11993,-3844,1.04522180557251 +19283,-0.222939029335976,1.13789391517639,-0.054771948605776,40703,3797,-12890,-4059,1.04185056686401 +19285,-0.22465492784977,1.04459369182587,-0.054887227714062,40703,3948,-8871,-3874,1.04104554653168 +19287,-0.226008474826813,0.959949851036072,-0.055527504533529,40703,4404,-10302,-4081,1.03660976886749 +19289,-0.213029488921165,0.869974374771118,-0.054017007350922,40703,2841,-7008,-3875,1.03527545928955 +19291,-0.204012274742126,0.788472175598145,-0.054763462394476,40703,3404,-8107,-4087,1.03650593757629 +19293,-0.188974887132645,0.697791874408722,-0.052511993795633,40703,2450,-4814,-3871,1.04442155361176 +19295,-0.167546153068542,0.595578849315643,-0.049439534544945,40703,2013,-3775,-4044,1.04644274711609 +19297,-0.139988929033279,0.503041505813599,-0.044952616095543,40703,935,-2128,-3825,1.05505859851837 +19299,-0.114772349596024,0.42024564743042,-0.041243590414524,40703,975,-2522,-3968,1.05934762954712 +19301,-0.096607826650143,0.347358018159866,-0.044545918703079,40703,1049,-1464,-3828,1.06063294410706 +19303,-0.076378799974918,0.265978455543518,-0.042448870837689,40703,785,-242,-4002,1.06271839141846 +19305,-0.049942702054978,0.19632326066494,-0.038000974804163,40703,-163,379,-3789,1.05953991413116 +19307,-0.011237846687436,0.120405234396458,-0.0349698998034,40703,-1560,1676,-3932,1.05710995197296 +19309,0.019688425585628,0.058105275034905,-0.032484211027622,40703,-1463,1811,-3757,1.0542448759079 +19311,0.054047629237175,-0.011010609567165,-0.029714960604906,40703,-2312,3329,-3886,1.04350733757019 +19313,0.083574794232845,-0.062161903828383,-0.027815818786621,40703,-2291,2774,-3729,1.03697550296783 +19315,0.111555807292461,-0.109493143856525,-0.026339158415794,40703,-2833,3415,-3857,1.03545248508453 +19317,0.138494431972504,-0.149485141038895,-0.024705676361919,40703,-2935,3307,-3712,1.02804470062256 +19319,0.169538602232933,-0.183600783348084,-0.022842403501272,40703,-4059,3766,-3825,1.03453576564789 +19321,0.203063026070595,-0.22671465575695,-0.020050192251802,40703,-4404,4753,-3684,1.04035913944244 +19323,0.229396298527718,-0.261878162622452,-0.019121190533042,40703,-4776,5250,-3790,1.04616320133209 +19325,0.260191917419434,-0.296617388725281,-0.020752400159836,40703,-5127,5308,-3693,1.05174469947815 +19327,0.278782039880753,-0.300696551799774,-0.022768149152398,40703,-5125,3818,-3839,1.05801296234131 +19329,0.293693482875824,-0.312301576137543,-0.025874549522996,40703,-4590,4048,-3732,1.06451785564423 +19331,0.302753895521164,-0.306990444660187,-0.030250109732151,40703,-4952,3418,-3931,1.06412446498871 +19333,0.321315586566925,-0.30083954334259,-0.029976788908243,40703,-5380,2786,-3766,1.06460058689117 +19335,0.345078885555267,-0.29667741060257,-0.029230507090688,40703,-6843,3496,-3921,1.06118524074554 +19337,0.362425923347473,-0.289970934391022,-0.031317636370659,40703,-6036,2759,-3780,1.05027031898499 +19339,0.373053818941116,-0.281158924102783,-0.030569367110729,40703,-6524,3071,-3938,1.04769122600555 +19341,0.378302991390228,-0.250289112329483,-0.030149102210999,40703,-5566,620,-3778,1.05025196075439 +19343,0.388573080301285,-0.224643245339394,-0.03050477989018,40703,-6916,1096,-3939,1.04873466491699 +19345,0.392783910036087,-0.190211474895477,-0.029996579512954,40703,-5875,-360,-3782,1.04825484752655 +19347,0.387190908193588,-0.152493804693222,-0.026712317019701,40703,-5917,-805,-3897,1.05233943462372 +19349,0.375038951635361,-0.114413477480412,-0.025526575744152,40703,-4622,-1603,-3756,1.05503630638123 +19351,0.363673746585846,-0.072690233588219,-0.029111595824361,40703,-5276,-2285,-3928,1.05406391620636 +19353,0.355319976806641,-0.031720094382763,-0.029539801180363,40703,-4774,-2924,-3788,1.04790997505188 +19355,0.347905308008194,0.013729580678046,-0.025985654443503,40703,-5470,-3905,-3893,1.04011940956116 +19357,0.338791131973267,0.048866156488657,-0.023051902651787,40703,-4639,-3631,-3748,1.03450298309326 +19359,0.324175238609314,0.087375909090042,-0.025447702035308,40703,-4731,-4598,-3888,1.02627968788147 +19361,0.304991632699966,0.132125109434128,-0.028863085433841,40703,-3582,-5517,-3792,1.02386450767517 +19363,0.289442777633667,0.168871566653252,-0.026581410318613,40703,-4237,-5822,-3906,1.02383768558502 +19365,0.267296314239502,0.20561420917511,-0.021748904138804,40703,-2962,-6041,-3747,1.02564311027527 +19367,0.245409712195396,0.232223778963089,-0.018420657142997,40703,-3188,-6179,-3815,1.02929377555847 +19369,0.221190333366394,0.271563827991486,-0.017353544011712,40703,-2265,-7245,-3720,1.03342795372009 +19371,0.200210988521576,0.309018224477768,-0.015563700348139,40703,-2616,-8289,-3786,1.04294276237488 +19373,0.167434349656105,0.349293053150177,-0.012764114886522,40703,-972,-8535,-3691,1.04729306697845 +19375,0.12972104549408,0.382168680429459,-0.012530156411231,40703,-356,-9273,-3753,1.0461266040802 +19377,0.101652130484581,0.40885129570961,-0.013341129757464,40703,-25128,32767,-3697,1.04337072372437 +19379,0.079860433936119,0.437644183635712,-0.015372385270894,40703,-4918,20412,-3789,1.03955936431885 +19381,0.056223332881928,0.460604906082153,-0.015589490532875,40703,-4325,21397,-3715,1.03777837753296 +19399,-0.272423416376114,0.971298933029175,-0.039224840700626,40703,1467,6291,-4092,1.04338598251343 +19401,-0.30100691318512,1.07703423500061,-0.041739337146282,40703,1219,6714,-3922,1.04148066043854 +19403,-0.3353630900383,1.19126868247986,-0.045681342482567,40703,2816,2105,-4167,1.0419225692749 +19405,-0.372431635856628,1.31132411956787,-0.049647592008114,40703,2966,2099,-3983,1.04220652580261 +19407,-0.400345981121063,1.43161845207214,-0.044289834797382,40703,3534,-2511,-4145,1.04604959487915 +19409,-0.427191704511642,1.54885733127594,-0.038806669414044,40703,3164,-1448,-3915,1.04634606838226 +19411,-0.455977082252502,1.66615080833435,-0.03662071749568,40703,4659,-6496,-4044,1.04888606071472 +19413,-0.486962020397186,1.79680573940277,-0.035531379282475,40703,4490,-6420,-3897,1.04953622817993 +19415,-0.512803077697754,1.93278133869171,-0.032622985541821,40703,5562,-12672,-3976,1.04820346832275 +19417,-0.535606026649475,2.05374026298523,-0.029660876840353,40703,4803,-9992,-3860,1.04955649375916 +19419,-0.554994821548462,2.16372632980347,-0.030082084238529,40703,5987,-15180,-3919,1.04789340496063 +19421,-0.564888000488281,2.26647877693176,-0.032373480498791,40703,4518,-12431,-3881,1.04729497432709 +19423,-0.574843645095825,2.37642121315002,-0.033520247787237,40703,5859,-19364,-3926,1.0449423789978 +19425,-0.585968554019928,2.4896502494812,-0.034699112176895,40703,5140,-17178,-3898,1.04236042499542 +19427,-0.594769179821014,2.5878164768219,-0.035527963191271,40703,6336,-22796,-3910,1.04202735424042 +19429,-0.598812103271484,2.66959095001221,-0.035646490752697,40703,5059,-18405,-3905,1.04756796360016 +19431,-0.598122656345367,2.73710560798645,-0.038522139191628,40703,5947,-23955,-3904,1.05475127696991 +19433,-0.600448966026306,2.80978012084961,-0.042989291250706,40703,5204,-20740,-3954,1.06033360958099 +19435,-0.607759416103363,2.87681102752686,-0.045408394187689,40703,6916,-27190,-3942,1.06903958320618 +19437,-0.605440497398376,2.92509984970093,-0.043783284723759,40703,5192,-21694,-3959,1.07074296474457 +19439,-0.595346212387085,2.96319341659546,-0.043143954128027,40703,5710,-27589,-3873,1.06947958469391 +19441,-0.584762215614319,2.98836493492126,-0.046961057931185,40703,4548,-22041,-3978,1.06765842437744 +19443,-0.577225089073181,3.00907778739929,-0.049561057239771,40703,5833,-28192,-3909,1.06427311897278 +19445,-0.564677238464356,3.01908206939697,-0.051010571420193,40703,4356,-22520,-4003,1.06381273269653 +19447,-0.546897828578949,3.02156519889832,-0.056042436510325,40703,4845,-28215,-3949,1.06167697906494 +19449,-0.530169546604157,3.01438212394714,-0.057484362274408,40703,3787,-22360,-4044,1.06150329113007 +19451,-0.512790203094482,2.99272704124451,-0.059245578944683,40703,4539,-27138,-3958,1.06452345848084 +19453,-0.49351105093956,2.97359681129456,-0.062222931534052,40703,3290,-22052,-4074,1.06982898712158 +19455,-0.469745635986328,2.94107413291931,-0.060300506651402,40703,3586,-26621,-3947,1.07329726219177 +19457,-0.447573214769363,2.91214108467102,-0.061007186770439,40703,2618,-21582,-4062,1.07617294788361 +19459,-0.421072840690613,2.85497355461121,-0.062314957380295,40703,2786,-24538,-3955,1.07478141784668 +19461,-0.395244300365448,2.79508423805237,-0.069299653172493,40703,1778,-18765,-4115,1.07122755050659 +19463,-0.361705809831619,2.72241830825806,-0.073825880885124,40703,1479,-22322,-4087,1.0675950050354 +19465,-0.32967147231102,2.64352536201477,-0.071226097643375,40703,540,-16256,-4126,1.05850994586945 +19467,-0.306677579879761,2.57101774215698,-0.06488361209631,40703,1475,-20871,-3988,1.05839788913727 +19469,-0.272946834564209,2.48096966743469,-0.062254283577204,40703,-272,-14089,-4061,1.05084276199341 +19471,-0.236974611878395,2.39158177375793,-0.065876096487045,40703,-479,-17684,-4015,1.05564332008362 +19473,-0.202805370092392,2.28985905647278,-0.071587219834328,40703,-1218,-11402,-4123,1.05961430072784 +19475,-0.181458741426468,2.19906044006348,-0.076777778565884,40703,-265,-15305,-4170,1.05930805206299 +19477,-0.152396410703659,2.09824347496033,-0.075494058430195,40703,-1511,-9527,-4150,1.0641360282898 +19479,-0.117545932531357,1.996302485466,-0.073389671742916,40703,-2226,-11967,-4163,1.06249392032623 +19481,-0.088311925530434,1.88796854019165,-0.066470056772232,40703,-2408,-6692,-4089,1.06098008155823 +19483,-0.064851783216,1.79578197002411,-0.063480228185654,40703,-2240,-10078,-4079,1.05773341655731 +19485,-0.025696197524667,1.67855620384216,-0.061756953597069,40703,-4007,-3682,-4057,1.05625486373901 +19487,0.006856204476208,1.56568002700806,-0.064994633197785,40703,-4060,-5434,-4138,1.05682718753815 +19489,0.034385371953249,1.45640051364899,-0.072543956339359,40703,-4058,-1594,-4133,1.06108295917511 +19491,0.057200189679861,1.35749673843384,-0.075244821608067,40703,-4212,-3536,-4298,1.05697679519653 +19493,0.07257741689682,1.26991260051727,-0.067490644752979,40703,-3780,-911,-4103,1.05869448184967 +19495,0.096905812621117,1.17173135280609,-0.059366881847382,40703,-5014,-966,-4149,1.05440843105316 +19497,0.118425652384758,1.08014035224915,-0.056095894426108,40703,-4941,1742,-4028,1.0572726726532 +19499,0.132300868630409,0.981961667537689,-0.055329706519842,40703,-4916,1795,-4142,1.05103778839111 +19501,0.151107087731361,0.902385711669922,-0.055884916335344,40703,-5296,3159,-4030,1.04655385017395 +19503,0.172300294041634,0.81950843334198,-0.051837865263224,40703,-6193,3097,-4142,1.04503083229065 +19505,0.181729257106781,0.757545232772827,-0.051894389092922,40703,-5165,3775,-4008,1.04136729240417 +19507,0.193711712956429,0.683779835700989,-0.054896295070648,40703,-6002,4476,-4214,1.04238104820251 +19509,0.19971676170826,0.62895941734314,-0.056250065565109,40703,-5292,4967,-4044,1.04114961624146 +19511,0.213161960244179,0.577043414115906,-0.056140016764402,40703,-6545,4531,-4257,1.04524278640747 +19513,0.218693807721138,0.533331692218781,-0.056180652230978,40703,-5655,5451,-4050,1.04177451133728 +19515,0.215683877468109,0.492564350366592,-0.05691647157073,40703,-5530,5034,-4288,1.04186582565308 +19517,0.211762979626656,0.453404784202576,-0.056769281625748,40703,-5005,6217,-4062,1.04166889190674 +19519,0.205559954047203,0.428075641393662,-0.055731989443302,40703,-5237,4939,-4281,1.03989994525909 +19521,0.20424185693264,0.404703587293625,-0.054836455732584,40703,-5202,5760,-4056,1.04110503196716 +19523,0.200736433267593,0.399231374263763,-0.052227064967156,40703,-5465,3969,-4252,1.03952312469482 +19525,0.205054044723511,0.381358653306961,-0.049997236579657,40703,-5733,5689,-4030,1.03293979167938 +19527,0.197428464889526,0.376421570777893,-0.046536348760128,40703,-5226,4291,-4194,1.033975481987 +19529,0.186268612742424,0.378850132226944,-0.042381580919027,40703,-4469,4267,-3984,1.03546679019928 +19531,0.170792117714882,0.387269914150238,-0.043237119913101,40703,-4346,3153,-4165,1.0378395318985 +19551,0.014608670957387,0.629140496253967,-0.025562668219209,40703,-1994,-3702,-3959,1.05564153194428 +19553,-0.00722589623183,0.670965492725372,-0.019177913665772,40703,-1356,-3112,-3853,1.0561101436615 +19555,-0.034166444092989,0.714155852794647,-0.013007360510528,40703,-578,-5080,-3803,1.0546817779541 +19557,-0.059398643672466,0.754996836185455,-0.005173414945602,40703,-375,-4414,-3756,1.05338990688324 +19559,-0.086747080087662,0.802492499351501,-0.001812751754187,40703,312,-7006,-3656,1.05373501777649 +19561,-0.105902969837189,0.852500975131989,-0.002555607119575,40703,-129,-6678,-3736,1.05419909954071 +19563,-0.129322871565819,0.889460325241089,-0.002684871666133,40703,752,-7893,-3649,1.05561029911041 +19565,-0.155568152666092,0.918468952178955,-0.00109327188693,40703,1126,-6371,-3723,1.05224001407623 +19567,-0.18311308324337,0.95350170135498,0.002998437732458,40703,1980,-9060,-3563,1.049311876297 +19569,-0.199855163693428,0.990362584590912,0.006516960915178,40703,1143,-8247,-3666,1.04441940784454 +19571,-0.211836099624634,1.02477264404297,0.007373398169875,40703,1411,-10464,-3489,1.04113626480103 +19573,-0.225671455264091,1.04300487041473,0.007131692953408,40703,1383,-7985,-3656,1.04042911529541 +19575,-0.245978772640228,1.06726694107056,0.007047686260194,40703,2651,-10746,-3475,1.03842949867249 +19577,-0.264626502990723,1.08367502689362,0.007144887000322,40703,2381,-8776,-3650,1.04050374031067 +19579,-0.282637059688568,1.10431659221649,0.007277655415237,40703,3183,-11434,-3458,1.03893327713013 +19581,-0.301370918750763,1.12206423282623,0.011649420484901,40703,3027,-9780,-3613,1.03793585300446 +19583,-0.313626945018768,1.13624620437622,0.014290046878159,40703,3391,-11857,-3360,1.04210102558136 +19585,-0.321868062019348,1.15232014656067,0.016021886840463,40703,2697,-10470,-3575,1.04481327533722 +19587,-0.32470566034317,1.15388524532318,0.018928870558739,40703,3033,-11626,-3285,1.04511034488678 +19589,-0.327056050300598,1.15429365634918,0.019151067361236,40703,2483,-9765,-3544,1.04436004161835 +19591,-0.329558163881302,1.14788699150085,0.019953388720751,40703,3225,-11347,-3257,1.04621493816376 +19593,-0.331014961004257,1.13745975494385,0.020504802465439,40703,2614,-9136,-3526,1.04974365234375 +19595,-0.333425283432007,1.12802517414093,0.017041452229023,40703,3413,-11185,-3283,1.05771970748901 +19597,-0.330328583717346,1.11499953269959,0.014784776605666,40703,2417,-9009,-3556,1.06034660339355 +19599,-0.329252988100052,1.10481512546539,0.01624040864408,40703,3231,-11121,-3282,1.05771327018738 +19601,-0.328347265720367,1.0853705406189,0.018354460597038,40703,2684,-8496,-3523,1.05171549320221 +19603,-0.327967405319214,1.06932127475739,0.017937980592251,40703,3399,-10481,-3253,1.04215598106384 +19605,-0.316309154033661,1.03438377380371,0.016046619042754,40703,1880,-7011,-3530,1.03879523277283 +19607,-0.301726788282394,1.00034558773041,0.012832578271628,40703,2089,-8422,-3310,1.03385889530182 +19609,-0.290082603693008,0.974370896816254,0.012832464650273,40703,1632,-7122,-3544,1.03436756134033 +19611,-0.273144125938415,0.939760744571686,0.015270323492587,40703,1577,-7717,-3281,1.03386235237122 +19613,-0.255987256765366,0.909251987934112,0.015993652865291,40703,863,-6168,-3514,1.03992342948914 +19615,-0.237191542983055,0.867053985595703,0.017000298947096,40703,968,-6280,-3261,1.04347610473633 +19617,-0.222270786762238,0.837250888347626,0.017467334866524,40703,639,-5459,-3495,1.04126536846161 +19619,-0.20806148648262,0.803893268108368,0.0175891648978,40703,923,-6148,-3251,1.03933906555176 +19621,-0.195336416363716,0.779792666435242,0.016506696119905,40703,498,-5290,-3494,1.03714835643768 +19623,-0.171135798096657,0.745086312294006,0.019820438697934,40703,-320,-5323,-3232,1.0396169424057 +19625,-0.143356114625931,0.708737552165985,0.024760767817497,40703,-1256,-3614,-3429,1.03828835487366 +19627,-0.125289663672447,0.679189324378967,0.027242897078395,40703,-571,-4831,-3152,1.04192626476288 +19629,-0.106996834278107,0.646255373954773,0.025670528411865,40703,-1049,-3154,-3414,1.04158222675323 +19631,-0.083615556359291,0.618558168411255,0.026178374886513,40703,-1597,-4169,-3173,1.04469573497772 +19633,-0.057541415095329,0.580121278762817,0.027984222397208,40703,-2288,-1979,-3390,1.04604041576386 +19635,-0.036527153104544,0.551931083202362,0.028493208810687,40703,-2172,-3204,-3149,1.04296922683716 +19637,-0.018199743703008,0.516044497489929,0.030668320134282,40703,-2291,-1381,-3364,1.04212117195129 +19639,-0.002960548270494,0.488049179315567,0.029977774247527,40703,-2307,-2294,-3139,1.03839540481567 +19641,0.023662351071835,0.453656286001205,0.0343446880579,40703,-3494,-701,-3331,1.03752958774567 +19643,0.054791454225779,0.422281831502914,0.035907734185457,40703,-4396,-1073,-3071,1.03172898292542 +19645,0.076059795916081,0.40062215924263,0.035073079168797,40703,-3897,-931,-3317,1.03170120716095 +19647,0.092280127108097,0.378681689500809,0.035576105117798,40703,-3973,-1107,-3071,1.02807426452637 +19649,0.108549058437347,0.356976747512817,0.035423271358013,40703,-4055,-360,-3307,1.02910208702087 +19651,0.125267997384071,0.328114807605743,0.032989248633385,40703,-4600,160,-3102,1.03350245952606 +19653,0.137246906757355,0.315569013357162,0.02929806150496,40703,-4225,-459,-3342,1.03567731380463 +19655,0.149177104234695,0.302744865417481,0.028075495734811,40703,-4719,-609,-3159,1.03802680969238 +19657,0.155831411480904,0.290722727775574,0.027482988312841,40703,-4188,-165,-3348,1.03566706180573 +19659,0.161857470870018,0.283080786466599,0.027207296341658,40703,-4591,-679,-3173,1.03586864471436 +19661,0.172812685370445,0.269945800304413,0.025410179048777,40703,-4825,195,-3356,1.03584802150726 +19663,0.177883759140968,0.26498943567276,0.022200383245945,40703,-4878,-589,-3234,1.03367340564728 +19665,0.183078274130821,0.252541214227676,0.020708773285151,40703,-4654,387,-3383,1.02950286865234 +19667,0.180365562438965,0.251333653926849,0.019652772694826,40703,-4458,-643,-3264,1.02853572368622 +19669,0.178154408931732,0.237689167261124,0.01800917647779,40703,-4149,683,-3398,1.02433729171753 +19671,0.16776630282402,0.237496390938759,0.018293272703886,40703,-3799,-493,-3279,1.0270768404007 +19673,0.158440321683884,0.243387207388878,0.017799451947212,40703,-3448,-794,-3395,1.03661489486694 +19675,0.159112945199013,0.250699877738953,0.014520555734634,40703,-4534,-1241,-3314,1.03923356533051 +19677,0.157346740365028,0.261932402849197,0.010780920274556,40703,-4061,-1446,-3440,1.03478229045868 +19679,0.147397190332413,0.268454760313034,0.008837412111461,40703,-3664,-1479,-3371,1.0294383764267 +19681,0.135656490921974,0.283929467201233,0.008099384605885,40703,-3117,-2077,-3455,1.02272403240204 +19683,0.132468611001968,0.290964514017105,0.007610795088112,40703,-3984,-1895,-3380,1.02127456665039 +19703,-0.003937698435038,0.386070489883423,0.010022327303887,40703,-1363,-3665,-3329,1.02848529815674 +19705,-0.018013244494796,0.397616982460022,0.009747593663633,40703,-1012,-3706,-3426,1.02863001823425 +19707,-0.030219586566091,0.39885476231575,0.010194760747254,40703,-931,-3549,-3319,1.03032898902893 +19709,-0.039287175983191,0.409307211637497,0.011536613106728,40703,-1068,-3873,-3410,1.02669739723206 +19711,-0.050514679402113,0.426358073949814,0.012654299847782,40703,-656,-5206,-3273,1.02406454086304 +19713,-0.064469061791897,0.441698133945465,0.011435884051025,40703,-347,-4778,-3407,1.01861143112183 +19715,-0.077927201986313,0.449771672487259,0.012103953398764,40703,-28,-5039,-3266,1.01731657981873 +19717,-0.089236348867416,0.444892168045044,0.012273844331503,40703,-157,-3477,-3396,1.0163346529007 +19719,-0.102696739137173,0.444084107875824,0.013297059573233,40703,399,-4412,-3250,1.01911652088165 +19721,-0.112663559615612,0.449675619602203,0.014347577467561,40703,117,-4396,-3377,1.02142238616943 +19723,-0.115716584026814,0.458385854959488,0.010419057682157,40703,-98,-5430,-3277,1.02315545082092 +19725,-0.121286377310753,0.466858595609665,0.00381587818265,40703,-33,-4957,-3445,1.02400815486908 +19727,-0.126310542225838,0.459747552871704,0.004594396334142,40703,250,-4423,-3345,1.02475678920746 +19729,-0.134933412075043,0.452786237001419,0.009798971936107,40703,426,-3759,-3401,1.0236029624939 +19731,-0.135071739554405,0.44120591878891,0.011046486906707,40703,92,-3903,-3267,1.02471709251404 +19733,-0.136611700057983,0.444851160049439,0.008135798387229,40703,-7,-4505,-3408,1.02526068687439 +19735,-0.136744767427444,0.448024362325668,0.007744913455099,40703,159,-5176,-3306,1.03192186355591 +19737,-0.135643228888512,0.444809347391128,0.00730486959219,40703,-161,-4119,-3410,1.03430116176605 +19739,-0.13421668112278,0.440683156251907,0.005094634369016,40703,54,-4641,-3335,1.03547930717468 +19741,-0.130373641848564,0.440440237522125,0.005067833233625,40703,-385,-4372,-3422,1.0349817276001 +19743,-0.125446155667305,0.439996540546417,0.005237610079348,40703,-286,-4990,-3325,1.03469908237457 +19745,-0.120929934084415,0.423444718122482,0.005463705398142,40703,-523,-3063,-3416,1.03266882896423 +19747,-0.117189928889275,0.410301297903061,0.004735934082419,40703,-293,-3691,-3333,1.02691864967346 +19749,-0.112673498690128,0.407181948423386,0.000991007080302,40703,-600,-3881,-3444,1.0216349363327 +19751,-0.101248301565647,0.403842896223068,0.000254928920185,40703,3971,-32767,-3391,1.01829373836517 +19753,-0.091886445879936,0.39835786819458,0.005045424681157,40703,-360,-9763,-3414,1.01340913772583 +19755,-0.080969087779522,0.383491307497024,0.003791525028646,40703,-484,-9432,-3352,1.01445412635803 +19757,-0.071342878043652,0.381853461265564,-0.001841054297984,40703,-641,-9942,-3459,1.01846730709076 +19759,-0.059184927493334,0.368955999612808,-0.004475347697735,40703,-909,-9481,-3454,1.02787017822266 +19761,-0.053574819117785,0.349390894174576,-0.007283819373697,40703,-588,-8328,-3495,1.0340017080307 +19763,-0.048411320894957,0.321031153202057,-0.007613214664161,40703,-574,-7724,-3506,1.03856074810028 +19765,-0.043920129537582,0.29129958152771,-0.005650665145367,40703,-632,-6881,-3484,1.03847062587738 +19767,-0.03425057604909,0.259993255138397,-0.006265115458518,40703,-1119,-6623,-3504,1.03644609451294 +19769,-0.018485819920898,0.223645940423012,-0.007792557124048,40703,-1798,-5523,-3499,1.03516674041748 +19771,-0.000561691762414,0.192829504609108,-0.009593052789569,40703,-2264,-5632,-3561,1.03106451034546 +19773,0.015017240308225,0.147981226444244,-0.007502946536988,40703,-2274,-3884,-3499,1.03190290927887 +19775,0.024834349751473,0.107187889516354,-0.012301073409617,40703,-2107,-3562,-3607,1.02472853660584 +19777,0.033231530338526,0.072701059281826,-0.014958876185119,40703,-2042,-3562,-3552,1.02020299434662 +19779,0.047676704823971,0.036828987300396,-0.012838349677622,40703,-2825,-2770,-3622,1.01363277435303 +19781,0.059988960623741,0.002010574098676,-0.010911078192294,40703,-2736,-2507,-3527,1.01345348358154 +19783,0.070059776306152,-0.046611208468676,-0.011469413526356,40703,-2906,-461,-3621,1.01534342765808 +19785,0.073056101799011,-0.090757742524147,-0.011777271516621,40703,-2296,-451,-3536,1.01770555973053 +19787,0.079320952296257,-0.136424943804741,-0.008932781405747,40703,-2826,860,-3612,1.01863300800323 +19789,0.085745580494404,-0.167428404092789,-0.004288200754672,40703,-2767,-194,-3487,1.01943135261536 +19791,0.090808466076851,-0.203422799706459,-0.000453402288258,40703,-2975,1370,-3530,1.02285647392273 +19793,0.098412081599236,-0.24737523496151,-0.001352307270281,40703,-3084,2011,-3469,1.02273416519165 +19795,0.10216012597084,-0.279029607772827,-0.003653314663097,40703,-3118,2433,-3583,1.02145767211914 +19797,0.106982424855232,-0.310673207044601,-0.003429959295318,40703,-3063,2203,-3487,1.02276027202606 +19799,0.109318502247334,-0.327093422412872,-0.004714043345302,40703,-3201,2288,-3613,1.02908992767334 +19801,0.115332968533039,-0.354135006666184,-0.003712560515851,40703,-3330,2685,-3492,1.03079545497894 +19803,0.120645493268967,-0.369771391153336,-0.003425092902035,40703,-3662,3122,-3608,1.02810108661652 +19805,0.127145379781723,-0.394244730472565,-0.007314592599869,40703,-3601,3285,-3521,1.02676045894623 +19807,0.126202151179314,-0.4058538377285,-0.009980459697545,40703,-3366,3634,-3689,1.02036345005035 +19809,0.123980820178986,-0.410322040319443,-0.009304660372436,40703,-2999,2309,-3539,1.01335215568542 +19811,0.128564059734344,-0.418512672185898,-0.009111165069044,40703,-3870,3826,-3685,1.01085293292999 +19813,0.135687172412872,-0.42294779419899,-0.010810087434948,40703,-3907,2722,-3554,1.01028513908386 +19815,0.139390364289284,-0.428557276725769,-0.011679202318192,40703,-4057,4038,-3720,1.01204931735992 +19817,0.14114373922348,-0.429331690073013,-0.010878407396376,40703,-3677,2791,-3560,1.01143991947174 +19819,0.140670776367188,-0.423761487007141,-0.009773157536983,40703,-3855,3391,-3701,1.01421010494232 +19821,0.146811679005623,-0.424044698476791,-0.010681238025427,40703,-4150,2919,-3564,1.01911187171936 +19823,0.146894037723541,-0.417084991931915,-0.011945012025535,40703,-4076,3411,-3729,1.02676045894623 +19825,0.141440540552139,-0.409858196973801,-0.01106976903975,40703,-3323,2412,-3571,1.03130114078522 +19827,0.128091529011726,-0.384912967681885,-0.00938121881336,40703,16764,-32767,-3699,1.03430140018463 +19829,0.116976760327816,-0.367660731077194,-0.010530110448599,40703,679,-4778,-3572,1.03498041629791 +19831,0.101942017674446,-0.351954698562622,-0.012118092738092,40703,919,-3951,-3733,1.03317666053772 +19833,0.087093882262707,-0.337121337652206,-0.01316568441689,40703,1345,-4896,-3595,1.03348934650421 +19835,0.084836259484291,-0.321964591741562,-0.013159452006221,40703,251,-4256,-3748,1.0328381061554 +19837,0.092318966984749,-0.307377934455872,-0.016324473544955,40703,-351,-5169,-3622,1.03273952007294 +19853,0.120188027620316,-0.294774353504181,-0.003715916071087,40703,-201,-3815,-3554,1.02239561080933 +19855,0.119910210371017,-0.300150960683823,0.000668554683216,40703,-585,-2479,-3576,1.02160882949829 +19857,0.122500590980053,-0.310925334692001,0.000718174967915,40703,-602,-2655,-3526,1.02066874504089 +19859,0.131154522299767,-0.32761162519455,-0.000257196166785,40703,-1441,-1090,-3590,1.02386569976807 +19861,0.144040152430534,-0.333964556455612,-0.001328748301603,40703,-1688,-2494,-3541,1.02804434299469 +19863,0.160211771726608,-0.344005346298218,-0.002783655654639,40703,-2501,-1155,-3624,1.03024232387543 +19865,0.173845171928406,-0.351078152656555,-0.003360241884366,40703,-2223,-32767,-3558,1.02666258811951 +19867,0.182512059807777,-0.351549088954926,0.001898362883367,40703,-2392,-7645,-3576,1.02348530292511 +19869,0.185130521655083,-0.355797201395035,0.010021572001278,40703,-1662,-8135,-3467,1.02413749694824 +19871,0.18580912053585,-0.357432037591934,0.012445757165551,40703,-1941,-7353,-3455,1.02369296550751 +19873,0.195993319153786,-0.37392121553421,0.010581195354462,40703,-2428,-6891,-3464,1.0236724615097 +19875,0.207500606775284,-0.39110741019249,0.005783344618976,40703,-3149,-5579,-3540,1.02171099185944 +19877,0.22332951426506,-0.419990688562393,0.003246317850426,40703,-3305,-5219,-3515,1.02318203449249 +19879,0.230914950370789,-0.445411503314972,0.00385224679485,40703,-3338,-3990,-3570,1.0214501619339 +19881,0.232709363102913,-0.478527992963791,0.000462599768071,40703,-2527,-3928,-3536,1.02446973323822 +19883,0.238863795995712,-0.518332421779633,-0.002021048916504,40703,-3460,-1617,-3648,1.03064560890198 +19885,0.241972073912621,-0.550020515918732,0.000196058361325,40703,-2850,-2824,-3541,1.02811825275421 +19887,0.238411992788315,-0.576797306537628,0.004136636387557,40703,-2844,-1407,-3577,1.02315545082092 +19889,0.235821902751923,-0.604165375232697,0.005831806920469,40703,-2450,-2146,-3504,1.01730000972748 +19891,0.244774118065834,-0.648291170597076,0.005798514932394,40703,-3941,1230,-3565,1.01756405830383 +19893,0.260722547769546,-0.695646822452545,0.006239254958928,40703,-4235,844,-3503,1.01790356636047 +19895,0.265867978334427,-0.723479390144348,0.008837716653943,40703,-4108,1546,-3530,1.0151299238205 +19897,0.260739505290985,-0.750693917274475,0.009748358279467,40703,-2834,474,-3481,1.01082134246826 +19899,0.251970887184143,-0.774844288825989,0.010581779293716,40703,-2986,2400,-3509,1.01007449626923 +19901,0.250135064125061,-0.814388036727905,0.012723001651466,40703,-3020,2579,-3461,1.01185286045074 +19903,0.249813377857208,-0.838952422142029,0.011394208297134,40703,-3660,3792,-3504,1.018958568573 +19905,0.250328570604324,-0.861672341823578,0.005584602244198,40703,-3294,2392,-3511,1.02751386165619 +19907,0.258600503206253,-0.888616383075714,0.003531855763868,40703,-4530,5119,-3601,1.0250004529953 +19909,0.258988261222839,-0.909799754619598,0.004912838339806,40703,-3517,3338,-3518,1.01736271381378 +19911,0.248847007751465,-0.924481868743896,0.004513097461313,40703,-3161,5196,-3591,1.01042807102203 +19913,0.240317031741142,-0.930707454681396,0.001415571896359,40703,-2716,2951,-3545,1.00643730163574 +19915,0.242065191268921,-0.940875113010406,0.00228997413069,40703,-4007,5529,-3617,1.01054084300995 +19917,0.248676463961601,-0.946071445941925,0.004573710262775,40703,-4023,3493,-3525,1.01311874389648 +19919,0.247782737016678,-0.942080318927765,0.00185002933722,40703,-4003,4922,-3613,1.01578009128571 +19921,0.244727373123169,-0.946800172328949,-0.003359616501257,40703,-3379,3867,-3582,1.01705241203308 +19923,0.233854696154594,-0.942262947559357,-0.001204928033985,40703,-3159,5279,-3643,1.02142870426178 +19925,0.229086518287659,-0.941335320472717,0.004178233444691,40703,-3130,3785,-3533,1.02579236030579 +19927,0.222491279244423,-0.928919017314911,0.003071751445532,40703,-3369,4906,-3586,1.02905178070068 +19929,0.215516477823257,-0.919013798236847,0.001079210545868,40703,-2869,3220,-3556,1.03144931793213 +19931,0.207475274801254,-0.905179560184479,0.002703771227971,40703,-3109,4817,-3586,1.02769982814789 +19933,0.203041926026344,-0.884069085121155,0.005199328996241,40703,-2958,2307,-3529,1.02091240882874 +19935,0.201849564909935,-0.866856396198273,0.003754109842703,40703,-3592,4330,-3569,1.01943671703339 +19937,0.198870718479157,-0.85036563873291,0.000510930200107,40703,-3086,2531,-3562,1.02053332328796 +19939,0.192731156945229,-0.830680310726166,-0.000341398088494,40703,-3168,-32767,-3611,1.02372014522553 +19941,0.18481071293354,-0.8107950091362,0.003549427026883,40703,-2610,-10098,-3542,1.02816498279572 +19943,0.171381533145905,-0.786521732807159,0.007952434942126,40703,-2367,-9014,-3506,1.02699530124664 +19945,0.162171497941017,-0.763190984725952,0.009785993024707,40703,-2261,-10806,-3499,1.02615249156952 +19947,0.155038058757782,-0.737169504165649,0.005090399179608,40703,-2632,-9737,-3542,1.02439641952515 +19949,0.14786396920681,-0.715672731399536,-0.001317686634138,40703,-2266,-11156,-3576,1.02491295337677 +19951,0.141386568546295,-0.702810049057007,0.000964855833445,40703,-2530,-9172,-3593,1.02473533153534 +19953,0.136395826935768,-0.694228887557983,0.005951268132776,40703,-2319,-10354,-3527,1.02292013168335 +19955,0.126919224858284,-0.697851836681366,0.006368800066412,40703,-2141,-7898,-3529,1.02478170394897 +19957,0.109760582447052,-0.697450339794159,0.004616279155016,40703,-1120,-9539,-3536,1.02941370010376 +19959,0.09699147194624,-0.705798804759979,0.004850989673287,40703,-1462,-7242,-3544,1.03675723075867 +19961,0.089848503470421,-0.721775054931641,0.007159457076341,40703,-1592,-7827,-3519,1.03930068016052 +19963,0.089779548346996,-0.741809725761414,0.00874634925276,40703,-2279,-5619,-3491,1.03911292552948 +19965,0.089025191962719,-0.768084108829498,0.007824532687664,40703,-2073,-6216,-3513,1.03728830814362 +19967,0.085478596389294,-0.788188278675079,0.004214555025101,40703,-2005,-4636,-3549,1.03244209289551 +19969,0.081709817051888,-0.816635549068451,0.005136503838003,40703,-1787,-5129,-3532,1.03096759319305 +19971,0.074567630887032,-0.849375247955322,0.005900274030864,40703,-1600,-2491,-3530,1.02783000469208 +19973,0.067953981459141,-0.884360432624817,0.002929567359388,40703,-1416,-3425,-3547,1.02643811702728 +19975,0.061236426234245,-0.923445880413055,0.001405028626323,40703,-1431,-555,-3579,1.02424335479736 +19977,0.051064033061266,-0.958162188529968,0.002815185347572,40703,-941,-2084,-3549,1.02093839645386 +19979,0.043604761362076,-0.996048510074616,0.002182588446885,40703,-1100,855,-3568,1.0200879573822 +19981,0.040806721895933,-1.02919960021973,0.002521543763578,40703,-1334,-840,-3551,1.02020454406738 +19983,0.044422890990973,-1.06963360309601,0.004390012472868,40703,-1918,2593,-3544,1.02560913562775 +19985,0.047238640487194,-1.10637986660004,0.007081615738571,40703,-1842,900,-3520,1.02740383148193 +19987,0.045043870806694,-1.13533866405487,0.009279903024435,40703,-1531,3227,-3491,1.02550506591797 +19989,0.043608959764242,-1.16671192646027,0.009039225056767,40703,-1499,1790,-3506,1.02528476715088 +19991,0.039939314126968,-1.19197750091553,0.010411172173917,40703,-1368,4300,-3483,1.02364110946655 +19993,0.036434851586819,-1.22156298160553,0.014940023422241,40703,-1262,2887,-3465,1.02643406391144 +19995,0.037603013217449,-1.25302934646606,0.01495130546391,40703,-1692,6180,-3431,1.02822458744049 +19997,0.039352644234896,-1.27749216556549,0.01337683480233,40703,-1694,3791,-3474,1.02912437915802 +19999,0.044158075004816,-1.2957923412323,0.012468094006181,40703,-2076,6402,-3460,1.03181290626526 +20001,0.049854528158903,-1.30480945110321,0.012294470332563,40703,-2145,3568,-3481,1.03731620311737 +20003,0.056351032108069,-1.32005774974823,0.011615145020187,40703,-2420,7070,-3470,1.04554164409637 +20005,0.059423606842756,-1.33514368534088,0.008972608484328,40703,-2118,4944,-3503,1.05045211315155 +20007,0.061830293387175,-1.34988784790039,0.006623743101954,40703,-2242,8033,-3528,1.04880857467651 +20009,0.067832753062248,-1.3571754693985,0.005642488133162,40703,-2475,5225,-3526,1.04431700706482 +20011,0.073532804846764,-1.35563278198242,0.002515171654522,40703,-2692,7485,-3573,1.0398622751236 +20013,0.079264976084232,-1.35347819328308,-4.06004655815195E-05,40703,-2651,5026,-3566,1.03413689136505 +20015,0.086484372615814,-1.34859251976013,-0.000698983552866,40703,-3042,7658,-3608,1.02718544006348 +20017,0.092161163687706,-1.34243321418762,0.001421955414116,40703,-2869,5112,-3557,1.02588963508606 +20019,0.098427452147007,-1.32336139678955,0.001532666385174,40703,-3206,6755,-3579,1.027095079422 +20021,0.105330124497414,-1.29386687278748,0.00113762752153,40703,-3188,3267,-3560,1.02761709690094 +20023,0.109914913773537,-1.26175117492676,-1.75623390532564E-05,40703,-3310,5326,-3592,1.03080654144287 +20025,0.114344492554665,-1.2334691286087,-0.002289941767231,40703,-3187,2985,-3584,1.03329908847809 +20027,0.115744292736053,-1.21337354183197,-0.000497709319461,40703,-3222,5889,-3594,1.03404116630554 +20029,0.113919958472252,-1.19764506816864,0.003475283971056,40703,-2783,3851,-3545,1.03548347949982 +20031,0.115405976772308,-1.16854953765869,0.00338526442647,40703,-3274,4995,-3546,1.03562355041504 +20033,0.119314260780811,-1.13677847385407,0.00194994173944,40703,-3321,2292,-3556,1.03618502616882 +20035,0.122950911521912,-1.09577202796936,0.000689907523338,40703,-3601,3409,-3574,1.03742170333862 +20037,0.127367973327637,-1.05374395847321,-0.001050658640452,40703,-3526,801,-3576,1.03907883167267 +20039,0.135702222585678,-1.02109313011169,0.000102425015939,40703,-4204,3195,-3579,1.04210817813873 +20041,0.139235302805901,-0.985230803489685,0.004663168918341,40703,-3694,660,-3537,1.04598772525787 +20043,0.13864378631115,-0.950114667415619,0.006462713703513,40703,-3680,2248,-3502,1.05067110061646 +20045,0.133428573608398,-0.906849086284637,0.004869310650975,40703,-3047,-624,-3535,1.05133628845215 +20047,0.129154786467552,-0.864201664924622,0.005757576785982,40703,-3327,665,-3507,1.05246412754059 +20049,0.122092574834824,-0.819837689399719,0.006377097219229,40703,-2812,-1618,-3524,1.04864382743835 +20051,0.121547028422356,-0.78497850894928,0.006876640953124,40703,-3527,243,-3490,1.04408299922943 +20053,0.129775196313858,-0.755406260490418,0.004411176312715,40703,-4074,-1184,-3536,1.03648340702057 +20055,0.131871268153191,-0.717683970928192,0.003746005706489,40703,-3941,-778,-3523,1.03108859062195 +20057,0.118158578872681,-0.671574473381043,0.005145782139152,40703,-2397,-3303,-3531,1.03295528888702 +20059,0.102226547896862,-0.632770359516144,0.006324222311378,40703,-2223,-1986,-3490,1.04128563404083 +20061,0.087580308318138,-0.602194905281067,0.005637340713292,40703,-1939,-2955,-3526,1.04237461090088 +20063,0.075603239238262,-0.571125745773315,0.00677313329652,40703,-2115,-2213,-3483,1.03998243808746 +20065,0.066810294985771,-0.542528748512268,0.005023561883718,40703,-2096,-3464,-3529,1.03336715698242 +20079,0.013642266392708,-0.410161554813385,0.013245183043182,40703,-1368,-2299,-3394,1.02484905719757 +20081,0.006433615460992,-0.39974170923233,0.010875505395234,40703,-1400,-3581,-3480,1.02517676353455 +20083,-0.001149806776084,-0.379484087228775,0.011173512786627,40703,-1238,-3742,-3416,1.02695381641388 +20085,-0.009971252642572,-0.359580665826797,0.012756555341184,40703,-1046,-4710,-3465,1.02639377117157 +20087,-0.021711578592658,-0.342365562915802,0.012433484196663,40703,-608,-4013,-3402,1.02787339687347 +20089,-0.025291154161096,-0.340587973594665,0.013863397762179,40703,-1191,-3573,-3455,1.03078615665436 +20091,-0.025962371379137,-0.337848633527756,0.013393985107541,40703,-1326,-2951,-3389,1.03395712375641 +20093,-0.024662779644132,-0.34568840265274,0.008858897723258,40703,-1538,-2703,-3487,1.03971469402313 +20095,-0.032814104110003,-0.357253193855286,0.005590800661594,40703,-661,-1500,-3479,1.04428160190582 +20097,-0.048312306404114,-0.36546716094017,0.005157771054655,40703,19,-2275,-3512,1.04760527610779 +20099,-0.057304739952087,-0.366495043039322,0.001476092496887,40703,-183,-1984,-3527,1.04703962802887 +20101,-0.056049015372992,-0.365289092063904,-0.004057918209583,40703,-1042,-2830,-3574,1.0456348657608 +20103,-0.05033615231514,-0.377340108156204,-0.004765650257468,40703,-1331,-895,-3602,1.04293119907379 +20105,-0.048393223434687,-0.393039494752884,-0.002234221901745,40703,-1178,-1092,-3563,1.03747379779816 +20107,-0.051394380629063,-0.401754826307297,-0.002385792089626,40703,-668,-609,-3575,1.03520131111145 +20109,-0.056240759789944,-0.407966643571854,-0.002686297753826,40703,-556,-1417,-3566,1.03682684898376 +20111,-0.063456296920776,-0.405166655778885,-0.001915008411743,40703,-148,-1241,-3571,1.04007995128632 +20113,-0.060329988598824,-0.41785654425621,-0.00111652223859,40703,-1041,-668,-3555,1.03854835033417 +20115,-0.052389457821846,-0.431904166936874,-0.002011785749346,40703,-1383,548,-3572,1.038458943367 +20117,-0.048148114234209,-0.44083696603775,-0.00351653737016,40703,-1271,-451,-3572,1.04303860664368 +20119,-0.038951613008976,-0.445281088352203,-0.004583235364407,40703,-1668,244,-3603,1.04156970977783 +20121,-0.025471625849605,-0.452878922224045,-0.007159414235502,40703,-2240,-209,-3598,1.03612101078033 +20123,-0.013960163109005,-0.47446745634079,-0.008100885897875,40703,-2223,2113,-3645,1.02937960624695 +20125,-0.014899264089763,-0.490647822618485,-0.008317133411765,40703,-1351,1126,-3607,1.02761852741241 +20127,-0.011571235023439,-0.504588782787323,-0.010742630809546,40703,-28716,-32767,-3679,1.02993154525757 +20129,-0.006117874290794,-0.51053649187088,-0.016875993460417,40560,-6496,-29577,-3668,1.0346075296402 +20131,-0.003925359807909,-0.514978170394897,-0.020367506891489,40560,-6298,-28675,-3794,1.03628742694855 +20133,-0.000476044224342,-0.520843744277954,-0.018852831795812,40560,-6476,-29535,-3685,1.0349600315094 +20135,-0.000362212245818,-0.528732538223267,-0.016882808879018,40560,-6248,-28299,-3756,1.02905356884003 +20137,-0.00752342492342,-0.545266628265381,-0.017618492245674,40560,-5658,-28512,-3679,1.02760004997253 +20139,-0.012927968986333,-0.581016004085541,-0.022470265626907,40560,-5693,-25528,-3826,1.02878260612488 +20141,-0.016091069206596,-0.625938236713409,-0.028578909114003,40560,-5860,-25387,-3758,1.02754807472229 +20143,-0.019575657323003,-0.682957828044891,-0.038002960383892,40560,-5764,-22395,-4015,1.02468073368073 +20145,-0.031099379062653,-0.736316740512848,-0.044974897056818,40560,-5081,-23216,-3877,1.02523529529572 +20147,-0.04082702100277,-0.81082010269165,-0.044318284839392,40560,-5007,-19062,-4098,1.02907204627991 +20149,-0.050132229924202,-0.892704725265503,-0.044528655707836,40560,-4994,-18886,-3881,1.03158402442932 +20151,-0.058519639074802,-0.987204074859619,-0.048002447932959,40560,-4836,-14682,-4152,1.03515660762787 +20153,-0.073517918586731,-1.08892416954041,-0.048754386603832,40560,-4269,-14523,-3918,1.03366386890411 +20155,-0.093389168381691,-1.19405388832092,-0.042559463530779,40560,-3448,-10388,-4098,1.02841711044312 +20157,-0.10870124399662,-1.30866229534149,-0.038717210292816,40560,-3742,-10222,-3857,1.02335393428803 +20159,-0.118812710046768,-1.42522585391998,-0.044959131628275,40560,-3722,-5537,-4139,1.01309061050415 +20161,-0.129252374172211,-1.55252969264984,-0.047434374690056,40560,-3783,-5477,-3925,1.01202321052551 +20163,-0.14482082426548,-1.67542743682861,-0.045899003744125,40560,-2894,-626,-4166,1.01205050945282 +20165,-0.164926022291184,-1.80406296253204,-0.046410609036684,40560,-2554,-1317,-3926,1.01666390895844 +20167,-0.174305602908134,-1.94148874282837,-0.050297096371651,40417,-2835,5243,-4237,1.01351308822632 +20169,-0.18453124165535,-2.0677535533905,-0.05051850900054,40417,-2943,2878,-3963,1.01272797584534 +20171,-0.196939364075661,-2.18848752975464,-0.043550740927458,40417,-2211,8694,-4179,1.01273727416992 +20173,-0.212507084012032,-2.29628586769104,-0.038432490080595,40417,-2111,5536,-3889,1.01097011566162 +20175,-0.22248911857605,-2.41723608970642,-0.038044393062592,40417,-1914,13170,-4138,1.01435673236847 +20177,-0.226410880684853,-2.52543759346008,-0.037644442170858,40417,-2686,9665,-3892,1.01604557037354 +20179,-0.227565079927444,-2.62159967422485,-0.036636415868998,40417,-2404,15558,-4147,1.02456653118134 +20181,-0.236919820308685,-2.72927784919739,-0.037279587239027,40417,-2082,13464,-3898,1.03153359889984 +20183,-0.24797248840332,-2.83099269866943,-0.037179134786129,40417,-1294,20309,-4182,1.03211915493011 +20185,-0.25275456905365,-2.92587924003601,-0.034329112619162,40417,-2109,16384,-3887,1.0320211648941 +20187,-0.259615153074264,-2.99209380149841,-0.033475127071142,40417,-1319,21432,-4169,1.02927827835083 +20189,-0.265606045722961,-3.05273747444153,-0.034788690507412,40417,-1757,16849,-3900,1.02750742435455 +20191,-0.267773181200027,-3.09805130958557,-0.036851104348898,40417,-1440,22775,-4239,1.02334308624268 +20193,-0.26442763209343,-3.13095188140869,-0.038195971399546,40417,-2357,17139,-3934,1.02103590965271 +20195,-0.258649885654449,-3.15419507026672,-0.040085855871439,40417,-2079,23270,-4307,1.02637815475464 +20197,-0.252529621124268,-3.17053008079529,-0.042298302054405,40417,-2645,17709,-3974,1.03207576274872 +20199,-0.244311079382896,-3.19137716293335,-0.043664559721947,40417,-2408,24877,-4379,1.0409437417984 +20201,-0.239025250077248,-3.19376611709595,-0.045601721853018,40417,-2704,18255,-4010,1.05043745040894 +20203,-0.235188230872154,-3.17632126808166,-0.045127473771572,40417,-2170,23077,-4424,1.06063425540924 +20205,-0.229721143841743,-3.14309883117676,-0.042832225561142,40417,-2778,16188,-4005,1.06836533546448 +20207,-0.222114875912666,-3.10361695289612,-0.043290548026562,40417,-2589,21507,-4424,1.0745290517807 +20209,-0.217053338885307,-3.06093621253967,-0.043853558599949,40417,-2865,15517,-4026,1.07729017734528 +20211,-0.211407005786896,-3.00788950920105,-0.042374491691589,40417,-2559,20145,-4433,1.07812535762787 +20213,-0.19711209833622,-2.95284152030945,-0.036922045052052,40417,-3751,14230,-3992,1.07594192028046 +20215,-0.184522524476051,-2.8900306224823,-0.032207578420639,40417,-3433,18650,-4330,1.07330226898193 +20217,-0.176586255431175,-2.81391215324402,-0.030096635222435,40417,-3540,11831,-3957,1.07489621639252 +20219,-0.169771522283554,-2.72538185119629,-0.031297978013754,40417,-3203,15208,-4332,1.08074426651001 +20221,-0.155241519212723,-2.62982511520386,-0.031717717647553,40417,-4273,8834,-3981,1.0827043056488 +20223,-0.143701195716858,-2.53774237632751,-0.030341545119882,40417,-3917,12903,-4329,1.08491396903992 +20225,-0.139082044363022,-2.44325542449951,-0.026782546192408,40417,-3760,7193,-3959,1.08246517181396 +20227,-0.138009324669838,-2.33914279937744,-0.024100793525577,40417,-3231,9726,-4256,1.08018732070923 +20229,-0.134328916668892,-2.228759765625,-0.023531347513199,40417,-3729,3850,-3947,1.08002865314484 +20231,-0.131643921136856,-2.11967778205872,-0.020073913037777,40417,-3419,6626,-4207,1.08097493648529 +20233,-0.127885401248932,-2.00257158279419,-0.012474057264626,40417,-3797,901,-3880,1.08251512050629 +20235,-0.12695774435997,-1.88298630714417,-0.010363830253482,40417,-3342,2752,-4087,1.08654725551605 +20237,-0.126606807112694,-1.77062618732452,-0.009717740118504,40417,-3543,-1412,-3869,1.08873283863068 +20239,-0.128380820155144,-1.65652024745941,-0.005413370672613,40417,-3101,83,-4019,1.08746039867401 +20241,-0.133344188332558,-1.53992164134979,0.000644090585411,40291,-3038,-4451,-3803,1.08468377590179 +20243,-0.136017426848412,-1.42954087257385,0.006380181759596,40291,-2894,-2814,-3864,1.07587456703186 +20245,-0.147348970174789,-1.31810986995697,0.009860466234386,40291,-2350,-6790,-3743,1.07178235054016 +20247,-0.157441973686218,-1.21856367588043,0.014181790873408,40291,-1985,-5038,-3757,1.06909584999084 +20249,-0.17192342877388,-1.12375640869141,0.01933160237968,40291,-1732,-8008,-3680,1.06753492355347 +20251,-0.185662284493446,-1.03480076789856,0.024012874811888,40291,-1223,-6927,-3627,1.06776595115662 +20253,-0.196927517652512,-0.944210112094879,0.026302065700293,40291,-1551,-9984,-3631,1.06398952007294 +20255,-0.206035673618317,-0.855217158794403,0.026732826605439,40291,-1171,-9593,-3577,1.06025433540344 +20257,-0.216112032532692,-0.778656542301178,0.029801527038217,40291,-1299,-11137,-3606,1.05659008026123 +20259,-0.226568877696991,-0.705854713916779,0.032608233392239,40291,-684,-10677,-3489,1.05398380756378 +20261,-0.231606215238571,-0.638404667377472,0.033519636839628,40291,-1368,-12346,-3577,1.05688071250916 +20263,-0.235110387206078,-0.576546430587769,0.033186450600624,40291,-974,-11867,-3466,1.06099367141724 +20265,-0.245726436376572,-0.531487762928009,0.031672436743975,40291,-691,-12183,-3586,1.06264805793762 +20267,-0.261675775051117,-0.493016391992569,0.031843036413193,40291,436,-11469,-3475,1.06145215034485 +20269,-0.277305960655212,-0.460226476192474,0.030882125720382,40291,209,-12270,-3588,1.05780053138733 +20271,-0.290274262428284,-0.437327206134796,0.027815502136946,40291,794,-11208,-3520,1.05426859855652 +20273,-0.29816609621048,-0.418003499507904,0.02710334956646,40291,58,-11878,-3611,1.04900789260864 +20275,-0.302348166704178,-0.4066102206707,0.026530001312494,40291,467,-10850,-3530,1.04008293151855 +20277,-0.305537074804306,-0.411716997623444,0.026803752407432,40291,-61,-10196,-3610,1.03455877304077 +20279,-0.311914622783661,-0.420425355434418,0.028653303161264,40291,893,-9159,-3506,1.03135871887207 +20281,-0.317095965147018,-0.423719108104706,0.029043946415186,40291,363,-10125,-3592,1.03138375282288 +20283,-0.317615270614624,-0.427596479654312,0.02973248064518,40291,688,-9367,-3496,1.03221011161804 +20285,-0.32460480928421,-0.430984109640122,0.032439183443785,40291,721,-9982,-3566,1.03290617465973 +20287,-0.327501714229584,-0.458217412233353,0.033235054463148,40291,1142,-7170,-3459,1.03594076633453 +20289,-0.320470362901688,-0.490019142627716,0.031451243907213,40291,-216,-7055,-3569,1.04449200630188 +20291,-0.308679461479187,-0.523123145103455,0.031460780650377,40291,-103,-5631,-3483,1.0534702539444 +20309,-0.228504031896591,-0.875519514083862,0.029344387352467,40291,-1003,-201,-3578,1.03681671619415 +20311,-0.211609914898872,-0.927062332630158,0.033647131174803,40291,-1567,3072,-3533,1.04060506820679 +20313,-0.191900283098221,-0.974023878574371,0.033461380749941,40291,-2392,1987,-3549,1.04060065746307 +20315,-0.176201209425926,-1.01933884620667,0.029410740360618,40291,-1980,4418,-3607,1.0392814874649 +20317,-0.158747181296349,-1.06564843654633,0.026326965540648,40291,-2645,3571,-3600,1.03317332267761 +20319,-0.149073287844658,-1.09986090660095,0.030354710295796,40291,-1925,5255,-3619,1.02615511417389 +20321,-0.139611795544624,-1.13334476947784,0.035708297044039,40291,-2297,3978,-3537,1.02982723712921 +20323,-0.128196358680725,-1.15547382831573,0.035371914505959,40291,-2345,5662,-3573,1.03783226013184 +20325,-0.103506498038769,-1.17996490001678,0.034960385411978,40291,-3865,4386,-3543,1.04691755771637 +20327,-0.076600067317486,-1.20069873332977,0.03449434414506,40291,-4264,6688,-3595,1.05272042751312 +20329,-0.056504644453526,-1.21694421768188,0.034900464117527,40291,-4193,4733,-3545,1.05240821838379 +20331,-0.044607613235712,-1.23949217796326,0.030721765011549,40291,-3704,7867,-3646,1.0509535074234 +20333,-0.032824404537678,-1.25303077697754,0.025447575375438,40291,-3935,5486,-3612,1.04983508586884 +20335,-0.014532584697008,-1.26594841480255,0.025116754695773,40291,-4660,8043,-3717,1.04667663574219 +20337,0.001630219281651,-1.27571642398834,0.024379244074226,40291,-4756,5986,-3623,1.04409968852997 +20339,0.00949830096215,-1.28143179416657,0.023248586803675,40291,-4320,8212,-3746,1.04029893875122 +20341,0.017034580931068,-1.28300333023071,0.022423354908824,40291,-4383,5956,-3641,1.03647828102112 +20343,0.023165499791503,-1.26758515834808,0.021016558632255,40291,-4441,6905,-3774,1.03318953514099 +20345,0.033466022461653,-1.24961054325104,0.020851824432612,40291,-4846,4523,-3656,1.03577983379364 +20347,0.043863859027624,-1.2284654378891,0.019168632104993,40291,-5116,6299,-3792,1.03842127323151 +20349,0.053399309515953,-1.21367192268372,0.019183633849025,40291,-5116,4668,-3671,1.04446864128113 +20351,0.060189601033926,-1.19604849815369,0.020518779754639,40291,-5165,6460,-3773,1.04528796672821 +20353,0.062196671962738,-1.16833996772766,0.019616108387709,40291,-4750,3514,-3672,1.04148006439209 +20355,0.063470117747784,-1.15135502815247,0.020189525559545,40291,-4864,6198,-3775,1.03910207748413 +20357,0.063141375780106,-1.12134790420532,0.020109264180064,40291,-4643,3081,-3672,1.03954124450684 +20359,0.061435360461474,-1.08089470863342,0.019256383180618,40291,-4662,3768,-3777,1.04323661327362 +20361,0.057656239718199,-1.04466211795807,0.018589280545712,40291,-4363,1912,-3686,1.04771101474762 +20363,0.054838392883539,-1.00988042354584,0.01719269528985,40291,-4521,3383,-3790,1.04710590839386 +20365,0.048595651984215,-0.972280085086822,0.015574301593006,40291,-4100,1123,-3710,1.04279220104218 +20367,0.046090625226498,-0.933826446533203,0.014217969961464,40291,-4447,2214,-3810,1.03348994255066 +20369,0.04417335242033,-0.895981550216675,0.015323560684919,40291,-4387,325,-3715,1.02407991886139 +20371,0.035399273037911,-0.849831819534302,0.018771473318338,40291,-3868,594,-3741,1.02066969871521 +20373,0.022098438814283,-0.801931321620941,0.01949217915535,40291,-3291,-1465,-3688,1.02170646190643 +20375,0.009804145433009,-0.766067266464233,0.019066570326686,40291,-3228,223,-3726,1.0259325504303 +20377,-0.002337474608794,-0.727827489376068,0.018145700916648,40291,-3048,-1596,-3698,1.02934384346008 +20379,-0.014015808701515,-0.684075117111206,0.019636942073703,40291,-2916,-1453,-3698,1.03780341148376 +20381,-0.020642664283514,-0.644266307353973,0.022495547309518,40291,-3195,-2703,-3669,1.04511046409607 +20383,-0.035555172711611,-0.599622488021851,0.022532798349857,40291,-2359,-2703,-3641,1.0530880689621 +20385,-0.049128443002701,-0.560223639011383,0.020227961242199,40291,-2297,-3712,-3684,1.05331718921661 +20387,-0.067267656326294,-0.51889556646347,0.017135128378868,40291,-1615,-3633,-3687,1.0496791601181 +20389,-0.082964360713959,-0.484900802373886,0.016786037012935,40291,-1652,-4276,-3707,1.04426097869873 +20391,-0.096812896430492,-0.454796582460403,0.018615759909153,40291,-1429,-3757,-3658,1.03638517856598 +20393,-0.114978983998299,-0.416625171899796,0.019554752856493,40291,-995,-5453,-3687,1.03300094604492 +20395,-0.135762572288513,-0.377545535564423,0.019214488565922,40291,-256,-5563,-3647,1.03398704528809 +20397,-0.153199374675751,-0.351407676935196,0.021095294505358,40291,-458,-5459,-3675,1.02844130992889 +20399,-0.167966783046722,-0.333595126867294,0.023602416738868,40291,-98,-4693,-3600,1.02351474761963 +20401,-0.180815786123276,-0.323157995939255,0.022161815315485,40291,-331,-4691,-3666,1.02240145206451 +20403,-0.193650439381599,-0.309948116540909,0.017969831824303,40291,239,-4699,-3655,1.01682782173157 +20405,-0.202231645584106,-0.294607222080231,0.017736345529556,40291,-259,-5413,-3695,1.01920163631439 +20407,-0.21110400557518,-0.279322654008865,0.014982608146966,40291,313,-5315,-3684,1.02109658718109 +20409,-0.214083924889564,-0.266734451055527,0.011980442330241,40291,-411,-5590,-3734,1.0216646194458 +20411,-0.21287801861763,-0.2597296833992,0.014762213453651,40291,-289,-5024,-3690,1.02203869819641 +20413,-0.218649178743362,-0.248205706477165,0.018106969073415,40291,-62,-5764,-3691,1.02291560173035 +20415,-0.230707764625549,-0.239215523004532,0.019871164113283,40291,1028,-5485,-3621,1.02775979042053 +20417,-0.240732043981552,-0.232027634978294,0.019512480124831,40291,648,-5678,-3679,1.02934491634369 +20419,-0.241060972213745,-0.234167620539665,0.015203442424536,40291,439,-4764,-3666,1.03144824504852 +20421,-0.240099370479584,-0.242461562156677,0.01135956030339,40291,-53,-4414,-3734,1.03244411945343 +20423,-0.242612719535828,-0.249648034572601,0.00901846960187,40291,709,-4147,-3736,1.02901029586792 +20425,-0.244533091783524,-0.25655210018158,0.008821019902825,40291,310,-4299,-3751,1.02571558952332 +20427,-0.239856213331223,-0.261017292737961,0.008816692978144,40291,238,-4143,-3738,1.02308058738709 +20429,-0.235803872346878,-0.263177067041397,0.00882990565151,40291,-149,-4527,-3751,1.02341604232788 +20431,-0.231044471263885,-0.272839933633804,0.009887188673019,40291,183,-3556,-3730,1.02438175678253 +20433,-0.230856165289879,-0.28408607840538,0.0099659524858,40291,146,-3552,-3742,1.02498173713684 +20435,-0.217019945383072,-0.306357741355896,0.00759287411347,40291,-597,-2076,-3772,1.02509307861328 +20437,-0.203970521688461,-0.315996319055557,0.006171893328428,40291,-1074,-3170,-3769,1.0238071680069 +20439,-0.193636193871498,-0.327346295118332,0.008569726720452,40291,-651,-2467,-3763,1.02578103542328 +20441,-0.179937765002251,-0.342046827077866,0.011096496134997,40291,-1391,-2382,-3736,1.02352428436279 +20461,-0.0363261513412,-0.455680578947067,0.018842089921236,40291,-3325,-1150,-3681,1.02573692798615 +20463,-0.01254019420594,-0.463383972644806,0.018925106152892,40291,-4339,6,-3673,1.0284880399704 +20465,0.008564420044422,-0.467105478048325,0.020839253440499,40291,-4447,-806,-3667,1.02828192710876 +20467,0.01992410607636,-0.467326313257217,0.025452932342887,40291,-3995,-349,-3595,1.02965605258942 +20469,0.031876433640719,-0.472110211849213,0.0286098793149,40291,-4149,-538,-3612,1.02923667430878 +20471,0.039322275668383,-0.465432703495026,0.028947070240975,40291,-4059,-756,-3552,1.03029358386993 +20473,0.04503882676363,-0.463223904371262,0.027615601196885,40291,-3924,-1046,-3617,1.02993857860565 +20475,0.055945366621018,-0.460512578487396,0.024105774238706,40291,-4608,-429,-3608,1.02995669841766 +20477,0.06612316519022,-0.463148951530456,0.020736131817103,40291,-4586,-581,-3664,1.02489256858826 +20479,0.076170809566975,-0.462044656276703,0.019662074744701,40291,-4910,-171,-3665,1.01484334468842 +20481,0.082004480063915,-0.454174518585205,0.021050032228232,40291,-4550,-1342,-3661,1.0111700296402 +20483,0.086411535739899,-0.452043235301971,0.024429036304355,40291,-4731,-286,-3600,1.01586484909058 +20485,0.08893109858036,-0.439206600189209,0.025928895920515,40291,-4466,-1795,-3627,1.02023005485535 +20487,0.097456865012646,-0.427775979042053,0.022331468760967,40291,-5261,-1235,-3618,1.0269079208374 +20489,0.102987743914127,-0.415072321891785,0.014394778758288,40291,-4943,-2025,-3705,1.02826738357544 +20491,0.100849106907845,-0.402889221906662,0.006684281863272,40291,-4604,-1591,-3799,1.02919983863831 +20493,0.0970244333148,-0.400209218263626,0.004096384160221,40291,-4247,-1423,-3777,1.03132343292236 +20495,0.093411147594452,-0.392343789339066,0.006484250538051,40291,-4438,-1356,-3797,1.03255677223206 +20497,0.096141189336777,-0.387411713600159,0.008278984576464,40291,-4762,-1675,-3750,1.03001224994659 +20499,0.090211473405361,-0.372051566839218,0.007797915954143,40291,-4278,-2133,-3778,1.02336835861206 +20501,0.075486958026886,-0.360682994127274,0.007623245473951,40291,-3271,-2435,-3755,1.02163922786713 +20503,0.059043355286121,-0.34710618853569,0.00818831846118,40291,-3076,-2331,-3762,1.02081751823425 +20505,0.053143199533224,-0.333728790283203,0.008453354239464,40291,-3626,-2892,-3750,1.01684808731079 +20507,0.04872440546751,-0.32732355594635,0.008751780726016,40291,-3802,-2068,-3758,1.01253259181976 +20509,0.041843727231026,-0.31205353140831,0.00537850568071,40291,-3431,-3273,-3771,1.01146459579468 +20511,0.036429677158594,-0.294919550418854,0.000518387707416,40291,-3552,-3303,-3857,1.00860476493835 +20513,0.034169603139162,-0.28295636177063,-0.002757815876976,40291,-3682,-3402,-3829,1.00507247447968 +20515,0.023457538336516,-0.27691838145256,-0.005684254691005,40291,-2980,-2756,-3934,0.999558985233307 +20517,0.009573888033628,-0.265046000480652,-0.006106705404818,40291,-2519,-3610,-3855,0.996982991695404 +20519,-0.007508235052228,-0.248129963874817,-0.006119307130575,40291,-2041,-3965,-3931,0.993746221065521 +20521,-0.023745004087687,-0.245370864868164,-0.002966094296426,40291,-1881,-3209,-3836,0.995163977146149 +20523,-0.037711679935455,-0.242934435606003,-0.004454797133803,40291,-1787,-2986,-3905,0.996815383434296 +20525,-0.049517843872309,-0.23417828977108,-0.009840137325227,40291,-1825,-3771,-3885,0.997343003749847 +20527,-0.054885942488909,-0.223432660102844,-0.012739734724164,40291,-2116,-3891,-3999,0.998543202877045 +20529,-0.063937067985535,-0.207834526896477,-0.013092503882945,40291,-1804,-4623,-3911,1.00216555595398 +20531,-0.075359933078289,-0.204980760812759,-0.013501985929906,40291,-1339,-3621,-4004,1.00688827037811 +20533,-0.095164798200131,-0.198114797472954,-0.01436254940927,40291,-566,-4130,-3923,1.00990736484528 +20535,-0.10818150639534,-0.199229940772057,-0.013325748965144,40291,-665,-3416,-4003,1.01272928714752 +20537,-0.123472176492214,-0.191678941249847,-0.01241802982986,40291,-447,-4266,-3912,1.01590609550476 +20539,-0.140297204256058,-0.18166945874691,-0.011023188009858,40291,176,-4487,-3979,1.01507985591888 +20541,-0.153098672628403,-0.177854284644127,-0.010493350215256,40291,6160,31862,-3902,1.01273798942566 +20565,-0.113815367221832,0.014396669343114,-0.023243432864547,40291,-852,-2191,-4011,1.01452374458313 +20567,-0.105049476027489,0.039608366787434,-0.026262061670423,40291,-725,-2930,-4127,1.01858747005463 +20569,-0.093883097171784,0.062280397862196,-0.026489010080695,40291,-1209,-2776,-4036,1.02343666553497 +20571,-0.083465725183487,0.090158455073834,-0.024805940687656,40291,-1147,-3999,-4104,1.02532184123993 +20573,-0.07203233987093,0.127720788121223,-0.023042613640428,40291,-1503,-4849,-4015,1.02485978603363 +20575,-0.054397989064455,0.160899892449379,-0.020759452134371,40291,-2111,-5605,-4038,1.02557134628296 +20577,-0.03913664072752,0.195206567645073,-0.019781176000834,40291,18508,30375,-3994,1.02557897567749 +20579,-0.027663163840771,0.220557197928429,-0.019180543720722,40291,1410,-23,-4003,1.02509009838104 +20581,-0.014226445928216,0.250072091817856,-0.018046570941806,40291,1077,-133,-3983,1.02071261405945 +20583,0.00288044475019,0.275301605463028,-0.015134422108531,40291,550,-978,-3945,1.01696467399597 +20585,0.025825086981058,0.300474375486374,-0.015594683587551,40291,-146,-637,-3966,1.00782251358032 +20587,0.045666847378016,0.33665332198143,-0.020707761868835,40291,-308,-2872,-4002,1.00241589546204 +20589,0.06851126998663,0.376741290092468,-0.02341558970511,40291,-738,-2922,-4020,1.0044766664505 +20591,0.087164372205734,0.423712223768234,-0.024544965475798,40291,-894,-5201,-4026,1.00777208805084 +20593,0.109253376722336,0.453024834394455,-0.025064108893275,40291,-1274,-3408,-4031,1.01168036460876 +20595,0.132726401090622,0.492810130119324,-0.027270687744022,40291,-1997,-5985,-4042,1.01019990444183 +20597,0.152673110365868,0.542164146900177,-0.02799104899168,40291,-1771,-6319,-4051,1.00984215736389 +20599,0.17545647919178,0.586980044841766,-0.023313295096159,40291,-2692,-8080,-3967,1.0117974281311 +20601,0.198410570621491,0.629803240299225,-0.020906401798129,40291,-2693,-7349,-4001,1.01416218280792 +20603,0.224509850144386,0.650845766067505,-0.023994462564588,40291,-3787,-7668,-3962,1.01462709903717 +20605,0.243647918105125,0.677244126796722,-0.029141129925847,40291,-3142,-7125,-4055,1.01405739784241 +20607,0.263232469558716,0.704923272132874,-0.028970757499337,40291,-4031,-9318,-4010,1.01527106761932 +20609,0.2857446372509,0.738307476043701,-0.024917859584093,40291,-4079,-8803,-4025,1.01771593093872 +20611,0.301488995552063,0.770677030086517,-0.023184491321445,40291,-4486,-11041,-3926,1.02375841140747 +20613,0.316599041223526,0.791083633899689,-0.023385619744659,40291,-4103,-8965,-4012,1.02549397945404 +20615,0.328198671340942,0.811356365680695,-0.023437153548002,40291,-4741,24886,-3923,1.02250051498413 +20617,0.340117573738098,0.826628029346466,-0.019960913807154,40291,-4337,-3371,-3985,1.01876366138458 +20619,0.347311317920685,0.84694254398346,-0.020496536046267,40291,-4869,-5987,-3883,1.01189911365509 +20621,0.353445261716843,0.85288417339325,-0.021293113008142,40291,-4249,-3392,-3991,1.01009488105774 +20623,0.365960717201233,0.854916870594025,-0.021463444456458,40291,-5690,-5116,-3898,1.00692439079285 +20625,0.377599060535431,0.873800098896027,-0.025678858160973,40291,-5135,-4937,-4018,1.00325429439545 +20627,0.390098363161087,0.896690964698792,-0.030388930812478,40291,-6222,-7624,-4004,1.0015926361084 +20629,0.394515156745911,0.925998032093048,-0.032381054013968,40291,-5016,-6774,-4063,1.00409650802612 +20631,0.398201942443848,0.935091853141785,-0.031335026025772,40291,-5878,-7612,-4016,1.00725078582764 +20633,0.393003851175308,0.946146547794342,-0.026447495445609,40291,-4465,-6119,-4021,1.00701260566711 +20635,0.38591057062149,0.953505277633667,-0.023011879995465,40291,-5056,-8141,-3927,1.00577569007874 +20637,0.377590596675873,0.965322196483612,-0.02288636751473,40291,-4175,-6821,-3994,1.0027152299881 +20639,0.368931651115417,0.978100955486298,-0.023256370797753,40291,-4818,-9305,-3932,1.00090789794922 +20641,0.361201703548431,0.982407033443451,-0.024067496880889,40291,-4130,-6914,-4000,0.999206721782684 +20643,0.352871239185333,0.987529814243317,-0.02646872960031,40291,-4731,-9295,-3969,0.997864603996277 +20647,0.331532627344132,1.00055229663849,-0.024545440450311,40291,-4269,-10028,-3952,1.00362539291382 +20649,0.318328499794006,1.00220310688019,-0.022561492398381,40291,-3398,-7805,-3987,1.00574231147766 +20651,0.308286845684052,0.989336848258972,-0.020995320752263,40291,-4149,-8851,-3916,1.01020038127899 +20653,0.290695190429687,0.985121130943298,-0.022660207003355,40291,-2811,28515,-3985,1.01418673992157 +20655,0.274964570999145,0.967383801937103,-0.022678846493363,40291,-3320,-2444,-3941,1.01843810081482 +20657,0.254753619432449,0.959994614124298,-0.022193757817149,40291,-2217,-1231,-3981,1.02086937427521 +20659,0.23655866086483,0.951142430305481,-0.019170127809048,40291,-2623,-3134,-3905,1.02176475524902 +20661,0.217151433229446,0.949392020702362,-0.02133278362453,40291,-1828,-1811,-3973,1.01446902751923 +20663,0.199550718069077,0.948780953884125,-0.02836936339736,40291,-2137,-4006,-4023,1.00514268875122 +20665,0.181901067495346,0.943247735500336,-0.031761702150107,40291,-1523,-1781,-4045,1.00138688087463 +20667,0.164251253008843,0.944182336330414,-0.029501657932997,40291,-1618,-4367,-4046,1.00249838829041 +20669,0.151200383901596,0.943156719207764,-0.026143958792091,40291,-1470,-2431,-4007,1.00074791908264 +20671,0.135149046778679,0.955430328845978,-0.025013638660312,40291,-1302,-5702,-4001,0.998684108257294 +20673,0.118839733302593,0.967352569103241,-0.020912343636155,40291,-816,-4045,-3971,0.999855279922485 +20675,0.100433543324471,0.973295569419861,-0.014738459140062,40291,-610,-5875,-3878,1.00458264350891 +20677,0.087822139263153,0.970811307430267,-0.012046858668327,40291,-664,-3412,-3909,1.01068270206451 +20679,0.076119519770146,0.968147814273834,-0.013757837936282,40291,-723,-5519,-3864,1.00927352905273 +20681,0.064407259225845,0.97675085067749,-0.014714874327183,40291,-411,-4641,-3925,1.00500738620758 +20683,0.05292234197259,0.981705963611603,-0.01406660862267,40291,-380,-6639,-3863,0.999994158744812 +20685,0.042320691049099,0.984405517578125,-0.013514286838472,40291,-182,-4687,-3915,0.99400806427002 +20687,0.034378711134195,0.987992942333221,-0.009612890891731,40291,-338,-6998,-3809,0.996038615703583 +20689,0.035760276019573,0.983909130096436,-0.004886850714684,40291,-947,-4558,-3853,1.00377428531647 +20691,0.032097015529871,0.989255785942077,-0.004607475828379,40291,-601,28548,-3751,1.00622808933258 +20693,0.029398463666439,0.984170079231262,-0.003849575994536,40291,-562,1232,-3843,1.00852203369141 +20695,0.017436159774661,0.992187798023224,-0.002270578406751,40291,239,-1995,-3723,1.01359915733337 +20697,0.017601566389203,0.993532538414001,-0.002239836612716,40291,-589,325,-3828,1.02160704135895 +20699,0.019040858373046,1.00757491588593,-0.00699229631573,40291,-734,-2978,-3775,1.01794695854187 +20701,0.020732482895255,1.02212333679199,-0.007731204852462,40291,-734,-1350,-3863,1.01317524909973 +20703,0.017968039959669,1.04104626178741,-0.003574075875804,40291,-415,-4199,-3725,1.00604951381683 +20705,0.01942022703588,1.05848050117493,-0.001731861731969,40291,-691,-2417,-3818,0.999451994895935 +20707,0.026064980775118,1.06210374832153,-0.001806520856917,40291,-1221,-3787,-3695,0.991455793380737 +20709,0.03473549336195,1.07598197460175,0.000129243548145,40291,-1425,-2765,-3802,0.986608147621155 +20711,0.044311054050922,1.09391808509827,0.002029958879575,40291,-1729,-5684,-3643,0.988565862178802 +20713,0.050089977681637,1.1161367893219,0.003339232644066,40291,-1444,-4308,-3775,0.991920471191406 +20715,0.047131337225437,1.14151406288147,0.002902762964368,40291,-877,-7374,-3627,0.999525725841522 +20717,0.046389479190111,1.15945303440094,0.001913195359521,40291,-930,-5018,-3780,1.01090466976166 +20719,0.050686426460743,1.18199825286865,-0.00086565350648,40291,-1470,-8232,-3659,1.0193282365799 +20721,0.057402554899454,1.19799792766571,-0.001577818999067,40291,-1631,-5849,-3799,1.0233758687973 +20723,0.058503698557615,1.22827863693237,-0.000545154383872,40291,-1393,-9971,-3641,1.02018690109253 +20725,0.06244470924139,1.25113618373871,0.003214655909687,40291,-1520,-7546,-3761,1.02115476131439 +20727,0.072429455816746,1.2628265619278,0.008237403817475,40291,-2283,-9652,-3527,1.0165479183197 +20729,0.083287686109543,1.27740633487701,0.010054772719741,40291,-2338,-7793,-3708,1.01164734363556 +20731,0.089291788637638,1.28970444202423,0.013879366219044,40291,-2290,-10592,-3458,1.0129634141922 +20733,0.090332910418511,1.29956781864166,0.017524117603898,40291,-1766,-8251,-3649,1.01672875881195 +20735,0.092004530131817,1.28954184055328,0.016257271170616,40291,-2044,-9463,-3429,1.01790654659271 +20737,0.090618349611759,1.29144775867462,0.012382832355797,40291,-1626,-8046,-3677,1.01780617237091 +20739,0.095246039330959,1.29449868202209,0.01451878529042,40291,-2335,-10947,-3446,1.02219831943512 +20741,0.098607785999775,1.29548418521881,0.017812918871641,40291,-2112,-8522,-3632,1.01841640472412 +20743,0.100732035934925,1.2836172580719,0.017448807135224,40291,-2275,-10184,-3409,1.01249170303345 +20745,0.100719466805458,1.26846551895142,0.014279689639807,40291,-1934,-7462,-3649,1.00425612926483 +20747,0.099291890859604,1.27162599563599,0.013158340938389,40291,-2029,-11557,-3457,0.993074297904968 +20749,0.100113809108734,1.26674604415894,0.014103550463915,40291,-2018,-8657,-3644,0.993063628673553 +20751,0.101435594260693,1.24822008609772,0.011016359552741,40291,-2293,-10099,-3481,1.00001764297485 +20753,0.100054077804089,1.22644245624542,0.006246806122363,40291,-1894,-7344,-3692,1.01067781448364 +20755,0.103285886347294,1.20171666145325,0.005859190132469,40291,-2489,-9359,-3545,1.01800584793091 +20757,0.101408287882805,1.18410289287567,0.010189270600677,40291,-1912,-7493,-3660,1.02568900585175 +20759,0.102495573461056,1.15436553955078,0.015787927433848,40291,-2355,-8672,-3430,1.03073644638062 +20761,0.098472595214844,1.1384015083313,0.015751322731376,40291,-1750,-7394,-3615,1.03897595405579 +20763,0.095045372843742,1.10952770709991,0.014846865087748,40291,-1940,-8422,-3443,1.04530453681946 +20765,0.090229324996471,1.08809614181519,0.017086112871766,40291,-1605,-6700,-3600,1.03926932811737 +20767,0.092965379357338,1.05039346218109,0.020465770736337,40291,-2383,-7235,-3376,1.0275547504425 +20769,0.092054650187492,1.01994514465332,0.02105575054884,40291,-1941,-5471,-3566,1.01334738731384 +20771,0.083765909075737,0.994035840034485,0.021595442667604,40291,-1471,-7549,-3364,1.01161277294159 +20773,0.085787959396839,0.961963176727295,0.02096089348197,40291,-2088,-4896,-3560,1.00941610336304 +20775,0.090077139437199,0.939981579780579,0.019290586933494,40291,-2488,-7313,-3395,1.00741410255432 +20777,0.090872451663017,0.909848392009735,0.018694687634707,40291,-2100,-4637,-3570,1.00630271434784 +20779,0.087253361940384,0.886964857578278,0.019254114478827,40291,-1901,-6730,-3396,1.01118123531342 +20799,0.093080259859562,0.618299722671509,0.02252802811563,40291,-2065,-3942,-3353,0.992423176765442 +20801,0.090815924108028,0.598972141742706,0.024044649675489,40291,-2066,-2573,-3498,1.0006468296051 +20803,0.093894831836224,0.568139672279358,0.021510105580092,40291,-2691,-2526,-3365,1.01326513290405 +20805,0.097903490066528,0.534982860088348,0.019596831873059,40291,-2650,-859,-3524,1.01568901538849 +20807,0.100624345242977,0.514835119247437,0.020017150789499,40291,-2819,-2610,-3380,1.0104523897171 +20809,0.101407214999199,0.499193042516708,0.022823536768556,40291,-2508,-1773,-3497,1.010218501091 +20811,0.102358251810074,0.49189567565918,0.022388931363821,40291,-2771,-3327,-3348,1.00963819026947 +20813,0.102048449218273,0.478817760944366,0.023125074803829,40291,-2480,-1828,-3490,1.01537775993347 +20815,0.099464178085327,0.474787652492523,0.024630373343825,40291,-2519,-3443,-3317,1.01669418811798 +20817,0.097485296428204,0.471688657999039,0.021051228046417,40291,-2336,-2598,-3499,1.02176034450531 +20819,0.101884089410305,0.453797817230225,0.016429230570793,40291,-3093,-2261,-3413,1.01631677150726 +20821,0.102731913328171,0.444716095924377,0.016052085906267,40291,-2656,-1932,-3529,1.00904452800751 +20823,0.097063459455967,0.43999707698822,0.016641117632389,40291,-2316,-3115,-3412,1.00813245773315 +20825,0.087668985128403,0.450005382299423,0.014509463682771,40291,-1743,-3517,-3536,1.00552082061768 +20827,0.094240762293339,0.441993921995163,0.016503032296896,40291,-3175,-3053,-3413,0.998920738697052 +20829,0.104413188993931,0.435008883476257,0.01722214370966,40291,-3419,-2229,-3514,0.993170022964478 +20831,0.107488185167313,0.434505701065064,0.014798223972321,40291,-3179,-3606,-3430,0.994833827018738 +20833,0.10399754345417,0.439311563968658,0.012893476523459,40291,-2476,-3277,-3540,0.994229853153229 +20835,0.106517247855663,0.441372036933899,0.013236405327916,40291,-3168,-4049,-3445,0.994363129138946 +20837,0.10827212035656,0.439599305391312,0.013582535088062,40291,-2954,-2956,-3532,0.994585454463959 +20839,0.104559481143951,0.446002036333084,0.010990128852427,40291,-2735,-4595,-3468,0.993162155151367 +20841,0.099281497299671,0.444018721580505,0.007759553380311,40291,-2363,-3156,-3569,0.998183071613312 +20843,0.093068115413189,0.445225536823273,0.007152346428484,40291,-2403,-4358,-3513,1.00403344631195 +20845,0.084410011768341,0.446515619754791,0.009254936128855,40291,-1944,-3579,-3557,1.01213991641998 +20847,0.076555639505386,0.440568923950195,0.014831040985882,40291,-2044,-3915,-3422,1.01171863079071 +20849,0.068572580814362,0.448655009269714,0.017847001552582,40291,-1792,-4247,-3495,1.00735139846802 +20851,0.069866940379143,0.453552663326263,0.016213174909353,40291,-2614,-5051,-3403,1.00563204288483 +20853,0.064076080918312,0.465937972068787,0.010902604088187,40291,-1909,-4961,-3539,1.00629091262817 +20855,0.063468173146248,0.46240684390068,0.007486910093576,40291,-2400,-4748,-3502,1.00275576114655 +20857,0.061583764851093,0.470303386449814,0.00517587037757,40291,-2175,-4864,-3576,0.99574464559555 +20859,0.060225166380406,0.477685332298279,0.005698394495994,40291,-2322,-5957,-3520,0.989517986774445 +20861,0.055593758821488,0.484567940235138,0.008046804927289,40291,-1914,-5169,-3555,0.984886288642883 +20863,0.052349340170622,0.486929684877396,0.007519092876464,40291,-2081,-5926,-3496,0.991002202033997 +20865,0.052310045808554,0.487028300762177,0.008546371944249,40291,-2215,-4898,-3549,0.997376680374146 +20867,0.05320031195879,0.494662523269653,0.009395839646459,40291,-2401,-6604,-3474,1.0051953792572 +20869,0.052328646183014,0.493719309568405,0.007095183711499,40291,-2173,-5102,-3557,1.01364123821259 +20871,0.044596571475267,0.497913062572479,0.003162033623084,40291,-1656,-6592,-3546,1.01701045036316 +20873,0.032272886484861,0.511570811271668,0.000227294047363,40291,-1079,-6590,-3603,1.02470183372498 +20875,0.031515050679445,0.519779860973358,0.001120619126596,40291,-1960,-7420,-3567,1.0243958234787 +20877,0.029468394815922,0.529148459434509,0.003373701358214,40291,-1783,-6732,-3580,1.02212059497833 +20879,0.033138703554869,0.523427903652191,0.004503701813519,40291,-2314,-6681,-3526,1.01577472686768 +20881,0.034584533423185,0.522490859031677,0.000105809580418,40291,-2116,-6099,-3601,1.00606346130371 +20883,0.032889071851969,0.515843033790588,-0.002428580773994,40291,-1931,-6694,-3608,1.00663924217224 +20885,0.026860607787967,0.518182575702667,-0.001079649548046,40291,-1479,-6471,-3609,1.01033449172974 +20887,0.02526880800724,0.510766088962555,0.001036864588968,40291,-1816,-6743,-3567,1.02017605304718 +20889,0.032947722822428,0.48938050866127,0.002520590089262,40291,-2553,-4554,-3583,1.02472519874573 +20891,0.040173463523388,0.479748338460922,0.003146867034957,40291,-2696,-6262,-3543,1.02774167060852 +20893,0.043416328728199,0.464707046747208,-0.001578146824613,40291,-2397,-4836,-3610,1.02866399288178 +20895,0.039355877786875,0.4570532143116,-0.006464072037488,40291,-1889,-6209,-3657,1.0316721200943 +20897,0.040903367102146,0.443818867206574,-0.005423860624433,40291,-2251,-4838,-3637,1.02760314941406 +20899,0.038874860852957,0.446352422237396,-0.007114848122001,40291,-2043,-6936,-3665,1.01513040065765 +20901,0.033123005181551,0.44516721367836,-0.00933057628572,40291,-1629,-5890,-3664,1.00869154930115 +20903,0.035601370036602,0.434672921895981,-0.008872898295522,40291,-2329,-5985,-3687,1.00122773647308 +20905,0.041346143931151,0.428075522184372,-0.007768511772156,40291,-2582,-5423,-3654,0.999098002910614 +20907,0.048343241214752,0.416174173355103,-0.005750954151154,40291,-2861,-5740,-3653,1.00469017028809 +20909,0.046753361821175,0.408485591411591,-0.006947777699679,40291,-2149,-5222,-3649,1.0081433057785 +20911,0.050005186349154,0.384594470262527,-0.008654390461743,40291,-2616,-4513,-3691,1.01281440258026 +20913,0.053478125482798,0.368558198213577,-0.011634488590062,40291,-2621,-4195,-3682,1.01913487911224 +20915,0.056829288601875,0.354055732488632,-0.009589266963303,40291,-2757,-4823,-3704,1.02564442157745 +20917,0.05940455943346,0.343665331602097,-0.007661005016416,40291,-2660,-4372,-3656,1.03312838077545 +20919,0.061815612018108,0.334261000156403,-0.009066657163203,40291,-2804,-4993,-3699,1.04154789447784 +20921,0.064412824809551,0.3281309902668,-0.012150716036558,40291,-2756,-4576,-3688,1.03832876682282 +20923,0.067469164729118,0.329890370368958,-0.014229714870453,40291,-2974,-5851,-3761,1.03073394298553 +20925,0.070058219134808,0.320606112480164,-0.014817954972386,40291,-2863,-4364,-3708,1.02291190624237 +20927,0.070792704820633,0.311909884214401,-0.011599152348936,40291,-2888,-4929,-3733,1.01859748363495 +20929,0.077138192951679,0.291784554719925,-0.005693308543414,40291,-3262,-3289,-3647,1.01952922344208 +20931,0.084544979035854,0.274090528488159,-0.004363377112895,40291,-3615,-3776,-3650,1.01692044734955 +20949,0.103893794119358,0.230189234018326,-0.003385632764548,40291,-3578,-3352,-3633,1.00586986541748 +20951,0.101296477019787,0.229835763573647,-0.006121772807091,40291,-3375,-4769,-3677,1.01110661029816 +20953,0.103704407811165,0.223619699478149,-0.009722926653922,40291,-3598,-3860,-3678,1.01386296749115 +20955,0.103831999003887,0.222893863916397,-0.009433131664991,40291,-3644,-4709,-3718,1.0148491859436 +20957,0.099741376936436,0.213251128792763,-0.003907451406121,40291,-3120,-3547,-3639,1.0111049413681 +20959,0.085800923407078,0.215031996369362,0.000552857469302,40291,-2373,-4831,-3602,1.00794565677643 +20961,0.077896878123283,0.225683182477951,-0.002436896553263,40291,-2567,-5255,-3629,1.00865495204926 +20963,0.079619310796261,0.230437353253365,-0.00809224601835,40291,-3438,-5374,-3704,1.00511026382446 +20965,0.087087146937847,0.229859858751297,-0.00800673943013,40291,-3834,-4595,-3668,0.996970951557159 +20967,0.091519072651863,0.218603789806366,-0.006698230747134,40291,-3871,-4119,-3689,0.995828688144684 +20969,0.081849798560143,0.218578323721886,-0.005402360111475,40291,-2571,-4553,-3651,0.99825519323349 +20971,0.076142378151417,0.221608370542526,0.000242094247369,40291,-2934,-5278,-3607,0.997687876224518 +20973,0.074377536773682,0.22725647687912,0.002599151339382,40291,-3064,-5166,-3596,0.994458615779877 +20975,0.0702153891325,0.228507742285728,0.00241006584838,40291,-2977,-5354,-3582,0.997041523456574 +20977,0.059851732105017,0.229774385690689,-0.00016173622862,40291,-2271,-4977,-3614,0.998834848403931 +20979,0.053143799304962,0.23681016266346,-0.00194947514683,40291,-2534,-5984,-3634,1.00184464454651 +20981,0.054924882948399,0.237161368131638,-0.001492153154686,40291,-3092,-5108,-3624,1.00154805183411 +20983,0.054626353085041,0.239568710327148,-0.002124069491401,40291,-3040,-5789,-3636,0.999071180820465 +20985,0.055222257971764,0.233902275562286,-0.002004296751693,40291,-3034,-4723,-3627,0.99338686466217 +20987,0.050512332469225,0.236195251345634,-0.001546244719066,40291,-2684,-5816,-3629,0.991525828838348 +20989,0.043338447809219,0.233157783746719,-0.000927774119191,40291,-2328,-4992,-3620,0.991525828838348 +20991,0.023198056966066,0.222640365362167,0.00709081441164,40595,25322,-5109,-3564,0.986038148403168 +20993,0.017317231744528,0.222253650426865,0.012075557373464,40595,25283,-5584,-3467,0.986945509910584 +20995,0.015622429549694,0.23168534040451,0.014954885467887,40595,25175,-6040,-3508,0.993053734302521 +20997,0.016563847661018,0.23368838429451,0.013913155533373,40595,25077,-6026,-3444,1.00436210632324 +20999,0.016563847661018,0.23368838429451,0.013913155533373,40595,25077,-6026,-3444,1.00436210632324 +21001,0.04175366833806,0.233466953039169,0.006531738676131,40595,23326,-5906,-3529,1.01429843902588 +21003,0.085918553173542,0.238072589039802,0.00740995677188,40595,21395,-5973,-3556,1.01582038402557 +21005,0.140651419758797,0.245736852288246,0.01112920884043,40595,19683,-6810,-3473,1.02173674106598 +21007,0.207535833120346,0.243860617280006,0.013138515874744,40595,18226,-5691,-3515,1.02174007892609 +21009,0.207535833120346,0.243860617280006,0.013138515874744,40595,18226,-5691,-3515,1.02174007892609 +21011,0.369012534618378,0.251829981803894,0.003054875414819,40595,14511,-6042,-3583,1.02385544776917 +21013,0.46036171913147,0.270188689231873,0.001237149350345,40595,12141,-8182,-3590,1.02126741409302 +21015,0.565681457519531,0.28014063835144,0.005209991708398,40595,10527,-7274,-3568,1.02412891387939 +21017,0.676429331302643,0.300396621227264,0.013212147168815,40595,7256,-8920,-3452,1.03297507762909 +21019,0.676429331302643,0.300396621227264,0.013212147168815,40595,7256,-8920,-3452,1.03297507762909 +21021,0.920316219329834,0.306090593338013,0.017031945288181,40595,2431,-7834,-3409,1.04454004764557 +21023,1.04860520362854,0.321224510669708,0.017213402315974,40595,1749,-8489,-3481,1.05133450031281 +21025,1.18375957012177,0.33698382973671,0.026303362101317,40595,-3037,-9444,-3305,1.05077028274536 +21027,1.31523036956787,0.343032121658325,0.03145331889391,40595,-2585,-8294,-3379,1.05565655231476 +21029,1.31523036956787,0.326264172792435,0.031144699081779,40595,-7356,-7080,-3252,1.06056749820709 +21031,1.57364416122437,0.331980109214783,0.031914912164211,40595,-6402,-8251,-3371,1.06397497653961 +21033,1.6982204914093,0.335462749004364,0.037208374589682,40595,-11448,-8833,-3186,1.07134711742401 +21035,1.82022714614868,0.346034973859787,0.045610394328833,40595,-10090,-8947,-3272,1.07502257823944 +21037,1.94395852088928,0.343375831842422,0.055602844804525,40595,-15964,-8679,-2977,1.07402193546295 +21039,2.05204033851624,0.353960305452347,0.056777637451887,40595,-13066,-9214,-3188,1.0703626871109 +21041,2.15785884857178,0.34869572520256,0.056569375097752,40595,-18860,-8729,-2973,1.07022297382355 +21043,2.25549626350403,0.344295501708984,0.055321574211121,40595,-15990,-8157,-3191,1.06707692146301 +21045,2.34441208839416,0.337373524904251,0.057208199054003,40595,-21470,-8575,-2971,1.06565403938293 +21047,2.42000460624695,0.331975966691971,0.058547239750624,40595,-17617,-8059,-3161,1.05901539325714 +21049,2.49213457107544,0.335744947195053,0.056241821497679,40595,-23534,-9460,-2991,1.05760335922241 +21051,2.55769848823547,0.332490414381027,0.053074948489666,40595,-19793,-8370,-3193,1.0527218580246 +21053,2.60160279273987,0.332488834857941,0.05115818977356,40595,-24210,-9282,-3061,1.04944360256195 +21055,2.6311240196228,0.322013556957245,0.052949167788029,40595,-19237,-7851,-3189,1.0512957572937 +21057,2.64994359016418,0.323166251182556,0.050166819244623,40595,-24169,-9354,-3081,1.0482931137085 +21059,2.67352294921875,0.309185534715652,0.050053175538778,40595,-20420,-7560,-3204,1.03969204425812 +21061,2.68187499046326,0.301606565713882,0.052766103297472,40595,-24941,-8520,-3053,1.03276360034943 +21063,2.67953395843506,0.298215925693512,0.055251605808735,40595,-19672,-8297,-3164,1.03176891803741 +21065,2.66009044647217,0.291274785995483,0.051814936101437,40595,-23618,-8530,-3071,1.03079783916473 +21067,2.63661336898804,0.284894555807114,0.04402732104063,40595,-18562,-8023,-3237,1.02602303028107 +21069,2.60549283027649,0.282952576875687,0.039229385554791,40595,-22909,-8893,-3226,1.02172768115997 +21071,2.55928921699524,0.281073004007339,0.035950522869825,40595,-16829,-8421,-3291,1.01570391654968 +21073,2.50802636146545,0.267198652029037,0.033482745289803,40595,-20866,-7917,-3298,1.01289474964142 +21075,2.45360255241394,0.257543295621872,0.030132286250591,40595,-15690,-7652,-3331,1.01248741149902 +21077,2.38645911216736,0.248934730887413,0.027636868879199,40595,-18683,-8114,-3367,1.01462709903717 +21079,2.30975127220154,0.238947093486786,0.027943983674049,40595,-12946,-7478,-3346,1.01638722419739 +21081,2.22167110443115,0.234728455543518,0.024621432647109,40595,-15374,-8304,-3404,1.01750254631042 +21083,2.1419620513916,0.213945016264915,0.021174328401685,40595,-11168,-6455,-3394,1.02071380615234 +21085,2.05361199378967,0.203123241662979,0.01651237718761,40595,-13429,-7418,-3488,1.02899813652039 +21087,1.96461880207062,0.187737599015236,0.01028623431921,40595,-8732,-6561,-3471,1.03298044204712 +21089,1.86967992782593,0.179069131612778,0.009358460083604,40595,-10690,-7267,-3563,1.03061151504517 +21091,1.76406502723694,0.164582312107086,0.011494711972773,40595,-5355,-6377,-3465,1.02697741985321 +21093,1.6576896905899,0.149754986166954,0.012410490773618,40595,-7069,-6417,-3512,1.01984190940857 +21095,1.55210399627686,0.137798592448235,0.009018963202834,40595,-2915,-6244,-3484,1.01189339160919 +21097,1.44212377071381,0.113180220127106,0.006440819706768,40595,-3866,-5166,-3559,1.00597774982452 +21099,1.32914364337921,0.090448796749115,0.005868948530406,40595,308,-4843,-3507,1.00062048435211 +21101,1.21592569351196,0.076029032468796,0.004652893636376,40595,-411,-5344,-3553,1.00367295742035 +21103,1.1098712682724,0.065608389675617,0.003952199127525,40595,2555,-5403,-3522,1.00375533103943 +21105,1.01122891902924,0.052992023527622,0.005578833632171,40595,1512,-5152,-3525,1.0031121969223 +21107,0.917289614677429,0.031649254262447,0.005701748654246,40595,4138,-4161,-3510,1.00516271591187 +21109,0.826899349689483,0.019981108605862,0.005751475226134,40595,3658,-4707,-3495,1.00868213176727 +21111,0.730054795742035,0.006496636662632,0.000669743807521,40595,6805,-4377,-3544,1.01462209224701 +21113,0.641474664211273,-0.013507566414774,-0.001737690530717,40595,6365,-3563,-3553,1.01707744598389 +21115,0.564689457416534,-0.027776103466749,-0.000864744593855,40595,7599,-3825,-3554,1.01279616355896 +21117,0.489549785852432,-0.046070531010628,-0.001855738344602,40595,7766,-3135,-3524,1.01008450984955 +21119,0.413649022579193,-0.064476154744625,-0.000253566395259,40595,9630,-2982,-3549,1.00536143779755 +21121,0.338601142168045,-0.078627087175846,0.000433754990809,40595,10166,-2874,-3467,1.00924181938171 +21123,0.281838774681091,-0.09383124858141,-0.000864983012434,40595,10145,-2754,-3550,1.01089549064636 +21125,0.240450873970985,-0.099910818040371,0.000575341982767,40595,9358,-3078,-3443,1.01435148715973 +21127,0.215405851602554,-0.11185260117054,-0.001575671252795,40595,8863,-2685,-3552,1.01876366138458 +21129,0.187236651778221,-0.109348766505718,-0.00477227056399,40595,9315,-3498,-3494,1.02158522605896 +21131,0.163914605975151,-0.1162478774786,-0.005432642064989,40595,9539,-2935,-3576,1.02633512020111 +21133,0.149914890527725,-0.124853849411011,-0.005150307901204,40595,8976,-2402,-3482,1.0275194644928 +21135,0.141014158725739,-0.124859601259232,-0.004808163270354,40595,8912,-3251,-3568,1.03089702129364 +21137,0.139971926808357,-0.124067112803459,-0.003948938567191,40595,8287,-3036,-3465,1.03730440139771 +21139,0.146838530898094,-0.114399380981922,-0.00357843353413,40595,7780,-4039,-3556,1.04223787784576 +21141,0.163435384631157,-0.116367489099503,-0.004204878117889,40595,6722,-2910,-3472,1.0436840057373 +21143,0.181434169411659,-0.108584202826023,-0.004151730332524,40595,6558,-3937,-3557,1.04477572441101 +21145,0.203470885753632,-0.096406266093254,-0.002429871121421,40595,5744,-4191,-3466,1.05008220672607 +21147,0.235267266631126,-0.090424470603466,-0.001916101784445,40595,4849,-4024,-3539,1.04995656013489 +21149,0.269133150577545,-0.08310341835022,0.000324917520629,40595,3863,-4015,-3443,1.04852473735809 +21151,0.305191099643707,-0.068481408059597,0.002176645211875,40595,3561,-4919,-3508,1.04797685146332 +21153,0.343490123748779,-0.044106598943472,0.004725737497211,40595,2335,-5841,-3425,1.04643213748932 +21155,0.394194662570953,-0.037121322005987,0.008905540220439,40595,1219,-4801,-3460,1.04998898506165 +21157,0.443444758653641,-0.023013042286038,0.01240701135248,40595,-112,-5448,-3352,1.0498126745224 +21159,0.488328456878662,-0.006118754856288,0.013266627676785,40595,223,-5947,-3427,1.05502247810364 +21161,0.539934754371643,0.006501596886665,0.015081589110196,40595,-1937,-5834,-3345,1.05945861339569 +21163,0.58978283405304,0.029340956360102,0.017705695703626,40595,-1696,-6889,-3394,1.06704092025757 +21179,0.950383424758911,0.087683290243149,0.02726055495441,40595,-6549,-6830,-3320,1.05103385448456 +21181,0.978977859020233,0.105268947780132,0.028938824310899,40595,-8512,-7945,-3271,1.04833698272705 +21183,1.01336514949799,0.109928898513317,0.030679047107697,40595,-7886,-6934,-3295,1.04519188404083 +21185,1.03795826435089,0.122588366270065,0.032412923872471,40595,-9509,-7926,-3248,1.04071044921875 +21187,1.05276930332184,0.121013678610325,0.035479355603457,40595,-7397,-6705,-3260,1.04151391983032 +21189,1.06201648712158,0.121308341622353,0.038705948740244,40595,-9155,-7081,-3174,1.0384783744812 +21191,1.07613885402679,0.11921764165163,0.039311595261097,40595,-8045,-6701,-3232,1.03682470321655 +21193,1.09023714065552,0.113161943852901,0.038155857473612,40595,-10332,-6552,-3172,1.0355703830719 +21195,1.09469330310822,0.114522896707058,0.036446750164032,40595,-7997,-6937,-3249,1.03367555141449 +21197,1.09789085388184,0.110529847443104,0.03417307510972,40595,-10054,-6713,-3215,1.03315472602844 +21199,1.09699857234955,0.110229648649693,0.032196093350649,40595,-8032,-6811,-3277,1.03531205654144 +21201,1.08825147151947,0.099073380231857,0.034911140799522,40595,-9421,-6073,-3194,1.03690361976624 +21203,1.07227039337158,0.09327157586813,0.038293071091175,40595,-6978,-6225,-3232,1.04011523723602 +21205,1.05363762378693,0.088906243443489,0.038157850503922,40595,-8518,-6442,-3144,1.04308843612671 +21207,1.03990411758423,0.081873394548893,0.032358914613724,40595,-7043,-6020,-3270,1.04018759727478 +21209,1.02475655078888,0.076170675456524,0.030005052685738,40595,-8652,-6173,-3223,1.03503978252411 +21211,1.00207436084747,0.059904925525189,0.032417915761471,40595,-6216,-5082,-3267,1.03070271015167 +21213,0.970102906227112,0.05939207598567,0.035342112183571,40595,-6901,-6303,-3140,1.02222561836243 +21215,0.944859623908997,0.054442241787911,0.034705895930529,40595,-32767,-5845,-3248,1.01786994934082 +21217,0.911651968955994,0.045635491609573,0.032283432781696,40595,-12275,-5508,-3157,1.01535081863403 +21219,0.863634765148163,0.031605824828148,0.033097110688686,40595,-9177,-4891,-3255,1.01857995986938 +21221,0.819704949855804,0.018697157502174,0.035304598510265,40595,-10368,-4813,-3087,1.0190908908844 +21223,0.779609024524689,0.012283736839891,0.032538689672947,40595,-8869,-5174,-3254,1.01950335502625 +21225,0.734767317771912,-0.004879210609943,0.026837751269341,40595,-9234,-4142,-3153,1.01631319522858 +21227,0.674264252185822,-0.011743504554033,0.026443134993315,40595,-6189,-4802,-3291,1.01260161399841 +21229,0.606859266757965,-0.019814107567072,0.025947442278266,40595,-5799,-4553,-3140,1.01449704170227 +21231,0.5440314412117,-0.033465892076492,0.024646513164044,40595,-4388,-4002,-3298,1.01950395107269 +21233,0.483732342720032,-0.041626393795014,0.020288230851293,40595,-4510,-4185,-3175,1.01674270629883 +21235,0.427123695611954,-0.047265008091927,0.016147563233972,40595,-3335,-4366,-3351,1.01526606082916 +21237,0.354959547519684,-0.045709654688835,0.014137380756438,40595,-1729,-4787,-3236,1.01463115215302 +21239,0.284359365701675,-0.062121652066708,0.012802124023438,40595,-406,-3364,-3370,1.01566112041473 +21241,0.216458231210709,-0.077609091997147,0.013432295061648,40595,118,-3023,-3201,1.01509189605713 +21243,0.14833214879036,-0.086502119898796,0.014354350976646,40595,1308,-3522,-3354,1.01677215099335 +21245,0.077643550932407,-0.084381379187107,0.013067258521915,40595,2537,-4145,-3192,1.01682269573212 +21247,0.011800372041762,-0.082339815795422,0.008916618302464,40595,3106,-4330,-3385,1.01828014850616 +21249,-0.046407051384449,-0.091680496931076,0.007996745407581,40595,3710,-3169,-3236,1.01358330249786 +21251,-0.106580279767513,-0.09771554172039,0.01058288384229,40595,4463,-3493,-3369,1.00911569595337 +21253,-0.16176749765873,-0.10302060842514,0.011658141389489,40595,-25900,-3230,-3174,1.00928258895874 +21255,-0.201513782143593,-0.116774834692478,0.010012112557888,40595,-816,-2622,-3366,1.00757598876953 +21257,-0.236193969845772,-0.116541758179665,0.008072473108768,40595,27,-3360,-3194,1.00489366054535 +21259,-0.273487985134125,-0.110167421400547,0.008435148745775,40595,144,-4108,-3371,1.0038024187088 +21261,-0.314931780099869,-0.099060140550137,0.006311194505543,40595,1908,-4372,-3231,1.01061511039734 +21263,-0.355703771114349,-0.101626448333263,0.004268512595445,40595,1713,-3546,-3394,1.01599264144897 +21265,-0.397503465414047,-0.111287653446198,0.004704331979156,40595,3417,-2649,-3231,1.0147088766098 +21267,-0.44435116648674,-0.11638618260622,0.006731544155627,40595,3598,-3105,-3372,1.01978862285614 +21269,-0.489774435758591,-0.115712344646454,0.007580873556435,40595,5363,-3271,-3188,1.02554607391357 +21271,-0.531381607055664,-0.104923628270626,0.012129902839661,40595,4691,-4358,-3328,1.03073370456696 +21273,-0.565549731254578,-0.10809401422739,0.016272231936455,40595,6025,-3074,-3091,1.03641438484192 +21275,-0.595043420791626,-0.103799626231194,0.016107723116875,40595,4993,-3862,-3294,1.03347194194794 +21277,-0.618694722652435,-0.09756101667881,0.01279017329216,40595,6407,-3869,-3139,1.03216874599457 +21279,-0.640669524669647,-0.094229735434055,0.009021611884236,40595,5392,-3888,-3337,1.02634084224701 +21281,-0.663430869579315,-0.087116822600365,0.009849195368588,40595,7374,-4054,-3180,1.02081418037415 +21283,-0.683706879615784,-0.08561210334301,0.013136960566044,40595,6196,-3841,-3303,1.01812303066254 +21285,-0.703486442565918,-0.076117560267449,0.016535457223654,40595,8126,-4363,-3111,1.01900577545166 +21287,-0.711760103702545,-0.070201180875301,0.020123690366745,40595,6067,-4343,-3249,1.02216744422913 +21289,-0.713802874088287,-0.052808348089457,0.020297709852457,40595,7343,-5282,-3089,1.02387046813965 +21291,-0.715628981590271,-0.035550761967898,0.01714226976037,40595,5995,-5628,-3264,1.02883732318878 +21293,-0.705975711345673,-0.031336218118668,0.014322525821626,40595,6699,-4667,-3178,1.03563284873962 +21295,-0.688330352306366,-0.022417943924666,0.012257159687579,40595,4539,-5205,-3294,1.03804171085358 +21297,-0.667683362960815,-0.020259715616703,0.010272741317749,40595,5607,-4691,-3234,1.04291522502899 +21299,-0.652526795864105,-0.006064881104976,0.012144415639341,40595,4518,-5810,-3292,1.04707777500153 +21301,-0.632650136947632,-0.00413912255317,0.018740020692349,40595,5390,-4944,-3150,1.05393493175507 +21303,-0.608942270278931,0.002407287945971,0.021871877834201,40595,3580,-5384,-3222,1.05804228782654 +21305,-0.580850064754486,0.017353929579258,0.02108714915812,40595,4245,-6230,-3142,1.05846917629242 +21307,-0.54794055223465,0.027991192415357,0.023629635572434,40595,2322,-6054,-3207,1.05010294914246 +21309,-0.519926488399506,0.038987882435322,0.026388129219413,40595,3532,-6313,-3099,1.04491627216339 +21311,-0.488952577114105,0.046591710299254,0.027723114937544,40595,1866,-6124,-3176,1.04533207416534 +21313,-0.450505882501602,0.057997163385153,0.026606032624841,40595,1892,-6669,-3113,1.04525709152222 +21315,-0.40728697180748,0.056001108139753,0.027164150029421,40595,38,-5600,-3177,1.05025720596313 +21317,-0.369621813297272,0.059850160032511,0.029287060722709,40595,840,-6186,-3080,1.04970991611481 +21319,-0.334623217582703,0.065543457865715,0.033139318227768,40595,-229,-6316,-3133,1.05249953269959 +21321,-0.290312647819519,0.063813611865044,0.035369209945202,40595,-756,-5880,-3009,1.04847455024719 +21323,-0.245376065373421,0.069012112915516,0.032609388232231,40595,-2071,-6362,-3133,1.0463832616806 +21325,-0.206225290894508,0.065189905464649,0.029805541038513,40595,-1619,-5783,-3072,1.03980946540833 +21327,-0.176536664366722,0.065467156469822,0.030280631035566,40595,-1853,-5990,-3146,1.03496992588043 +21329,-0.14585967361927,0.056205570697785,0.032660227268934,40595,-32767,-5282,-3026,1.03487837314606 +21331,-0.110041439533234,0.069217503070831,0.0351074449718,40595,-8461,-6985,-3109,1.03391849994659 +21333,-0.066318392753601,0.075019218027592,0.035836894065142,40595,-9403,-6705,-3004,1.03667902946472 +21335,-0.029507486149669,0.072232216596603,0.034662425518036,40595,-9695,-5935,-3108,1.03753459453583 +21337,-0.0065509211272,0.068244636058807,0.034886498004198,40595,-8900,-5927,-3004,1.04049277305603 +21339,0.006204880774021,0.062607511878014,0.032050769776106,40595,-8517,-5627,-3123,1.03703463077545 +21341,0.012997950427234,0.065863698720932,0.02853687107563,40595,-8084,-6433,-3072,1.03320682048798 +21343,0.021214179694653,0.063302986323834,0.028019027784467,40595,-8446,-5890,-3148,1.03036570549011 +21345,0.016959950327873,0.074949078261852,0.026794958859682,40595,-7390,-7206,-3099,1.03224503993988 +21347,0.006468548439443,0.070994600653648,0.024202197790146,40595,-6934,-5935,-3172,1.02755546569824 +21349,-0.010960947722197,0.068955861032009,0.022444000467658,40595,-6028,-6162,-3142,1.01636040210724 +21351,-0.03244461864233,0.066387362778187,0.02554395981133,40595,-5615,-6001,-3161,1.01458430290222 +21353,-0.053103391081095,0.059531468898058,0.029085878282786,40595,-5126,-5702,-3052,1.01765930652618 +21355,-0.06749539077282,0.054099645465612,0.025461092591286,40595,-5627,-5649,-3159,1.02146816253662 +21357,-0.081295661628246,0.044857196509838,0.020067004486919,40595,-5152,-5317,-3140,1.02407658100128 +21359,-0.104821093380451,0.041760660707951,0.018014527857304,40595,-4429,-5662,-3208,1.02739894390106 +21361,-0.133788868784904,0.033339586108923,0.020581277087331,40595,-3200,-5211,-3121,1.03381633758545 +21363,-0.166427403688431,0.020610800012946,0.023197384551168,40595,-2861,-4686,-3170,1.03789174556732 +21365,-0.205549597740173,0.011137389577925,0.02234822884202,40595,-32767,-4786,-3075,1.04365146160126 +21367,-0.241800159215927,0.001973487436771,0.018235998228192,40595,-12023,-4681,-3200,1.03972625732422 +21369,-0.28100398182869,-0.004926788620651,0.011979594826698,40595,-10575,-4712,-3178,1.030064702034 +21371,-0.321336388587952,-0.016551218926907,0.007696285378188,40595,-10594,-4239,-3270,1.02046549320221 +21373,-0.364179193973541,-0.021093942224979,0.007137808948755,40595,-8953,-4615,-3216,1.01683592796326 +21375,-0.402367651462555,-0.031941913068295,0.007866187952459,40595,-9551,-4066,-3267,1.01858580112457 +21377,-0.45149838924408,-0.042409513145685,0.004866424016655,40595,-7027,-3837,-3221,1.01764798164368 +21379,-0.516199588775635,-0.054554790258408,0.003072573803365,40595,-5942,-3632,-3297,1.01414251327515 +21381,-0.583412408828735,-0.066638663411141,0.004044677130878,40595,-3481,-3303,-3205,1.01158332824707 +21383,-0.648761630058289,-0.067110829055309,0.002915766788647,40595,-3854,-4259,-3295,1.01272988319397 +21385,-0.713323593139648,-0.071201801300049,-0.001000894117169,40595,-1395,-3774,-3258,1.01570081710815 +21387,-0.779620110988617,-0.074121825397015,-0.004592991434038,40595,-1708,-3953,-3345,1.0196989774704 +21389,-0.854238033294678,-0.073901310563088,-0.006189580541104,40595,1842,-4006,-3316,1.02031135559082 +21391,-0.925774574279785,-0.085559099912644,-0.003005747450516,40595,1031,-3130,-3332,1.01966714859009 +21405,-1.35045826435089,-0.131204530596733,-0.010938229039311,40595,9867,-2502,-3322,1.0170773267746 +21407,-1.39834141731262,-0.131088018417358,-0.012502324767411,40595,7826,-3105,-3386,1.01993906497955 +21409,-1.43784534931183,-0.13622984290123,-0.015018898993731,40595,10905,-2347,-3367,1.0254784822464 +21411,-1.47175645828247,-0.135443717241287,-0.01579374819994,40595,8432,-3027,-3408,1.02895712852478 +21413,-1.50237834453583,-0.130460366606712,-0.014855513349176,40595,11883,-3094,-3373,1.03581058979034 +21415,-1.5244654417038,-0.129618152976036,-0.012617020867765,40595,8929,-3052,-3385,1.02989959716797 +21417,-1.53854393959045,-0.124147586524487,-0.012329516001046,40595,11878,-3168,-3351,1.01818811893463 +21419,-1.54756116867065,-0.12311827391386,-0.014561599120498,40595,8932,-3098,-3397,1.01187670230865 +21421,-1.5585150718689,-0.12236700206995,-0.014508917927742,40595,12585,-2795,-3381,1.0054247379303 +21423,-1.55825710296631,-0.129573836922646,-0.010639008134604,40595,9042,-2355,-3369,1.00613498687744 +21425,-1.54463148117065,-0.127641826868057,-0.010376968421042,40595,11222,-2738,-3332,1.0069420337677 +21427,-1.52966487407684,-0.117397680878639,-0.009361123666167,40595,8199,-3717,-3359,1.01049613952637 +21429,-1.51083028316498,-0.106993772089481,-0.00396386673674,40595,10914,-3628,-3272,1.01589322090149 +21431,-1.4919581413269,-0.081555731594563,-0.001995587022975,40595,7988,-5268,-3306,1.02420544624329 +21433,-1.46398437023163,-0.067118875682354,-0.004027262795717,40595,10092,-4523,-3299,1.02684962749481 +21435,-1.43001246452332,-0.048081014305353,-0.005516284611076,40595,6609,-5256,-3329,1.03346860408783 +21437,-1.38406944274902,-0.03873822838068,-0.008037783205509,40595,8071,-4593,-3364,1.03967356681824 +21439,-1.33717155456543,-0.024104230105877,-0.008586598560214,40595,4909,-5264,-3351,1.03948700428009 +21441,-1.29005825519562,-0.016971752047539,-0.004777899943292,40595,6978,-4773,-3339,1.04239571094513 +21443,-1.23695659637451,-0.011971754021943,-0.004208949860185,40595,3542,-4737,-3321,1.04514193534851 +21445,-1.1864572763443,0.003447602503002,-0.007066605612636,40595,5539,-5695,-3378,1.04520583152771 +21447,-1.13957142829895,0.021605860441923,-0.007178683765233,40595,3060,-6160,-3342,1.04448795318604 +21449,-1.08897411823273,0.049615763127804,-0.001095616375096,40595,4398,-7362,-3332,1.04496622085571 +21451,-1.02526390552521,0.056107956916094,0.006149212364107,40595,644,-5840,-3252,1.04316568374634 +21453,-0.967359066009522,0.068350188434124,0.007580550853163,40595,2298,-6557,-3238,1.04453659057617 +21455,-0.90716826915741,0.071343898773193,0.005733516532928,40595,-422,-5837,-3254,1.04452884197235 +21457,-0.853390395641327,0.082029923796654,0.003483451437205,40595,1079,-6691,-3291,1.04332399368286 +21459,-0.801064789295197,0.09899427741766,0.004200262948871,40595,-1058,-7269,-3265,1.04858112335205 +21461,-0.748297274112701,0.108246326446533,0.009922389872372,40595,-241,-7052,-3226,1.04820728302002 +21463,-0.698065459728241,0.120394468307495,0.013010083697736,40595,-2105,-7278,-3204,1.04815173149109 +21465,-0.640152037143707,0.125613287091255,0.012791305780411,40595,-2099,-7091,-3198,1.0460489988327 +21467,-0.585382580757141,0.131389915943146,0.012288731522858,40595,-3813,-7033,-3209,1.04034507274628 +21469,-0.527729749679565,0.1209322437644,0.011691130697727,40595,-3698,-5944,-3207,1.03322505950928 +21471,-0.47956320643425,0.128903970122337,0.012165892869234,40595,-4674,-7207,-3209,1.02800166606903 +21473,-0.43768247961998,0.133848264813423,0.015839857980609,40595,-3874,-7313,-3161,1.02225530147553 +21475,-0.400722652673721,0.12891598045826,0.014577008783817,40595,-4859,-6341,-3191,1.01368057727814 +21477,-0.362262338399887,0.121393732726574,0.014779449440539,40595,-4737,-6281,-3167,1.00943911075592 +21479,-0.324561357498169,0.117838308215141,0.021884877234697,40595,-5897,-6334,-3140,1.00386416912079 +21481,-0.288186013698578,0.120046928524971,0.023393243551254,40595,-5701,-7018,-3062,1.00867962837219 +21483,-0.260146975517273,0.111581943929195,0.019440783187747,40595,-6055,-5948,-3155,1.01766324043274 +21485,-0.243665650486946,0.109723590314388,0.012436023913324,40595,-4931,-6611,-3185,1.02649366855621 +21487,-0.224056467413902,0.100197359919548,0.011434615589678,40595,-5913,-5759,-3209,1.03647363185883 +21489,-0.208011165261269,0.098801463842392,0.01198766939342,40595,-5436,-6517,-3184,1.04243516921997 +21491,-0.192092582583427,0.097106084227562,0.010237447917461,40595,-6069,-6322,-3216,1.05142760276794 +21493,-0.179479286074638,0.090809814631939,0.010552866384387,40595,-5630,-6077,-3197,1.05147540569305 +21495,-0.174906060099602,0.082235142588616,0.013800585642457,40595,-5477,-5658,-3191,1.04648101329803 +21497,-0.178059831261635,0.069447137415409,0.015798948705196,40595,-4491,-5304,-3125,1.0339469909668 +21499,-0.189727991819382,0.067459270358086,0.015087213367224,40595,-4075,-5951,-3180,1.02080035209656 +21501,-0.197421938180923,0.061460785567761,0.014706028625369,40595,-3810,-5691,-3133,1.01438677310944 +21503,-0.203432098031044,0.056498397141695,0.010978819802404,40595,-4246,-5610,-3206,1.01303732395172 +21505,-0.20922788977623,0.03410167992115,0.012928776443005,40595,-3709,-4090,-3141,1.01400780677795 +21507,-0.219608515501022,0.015991086140275,0.014934281818569,40595,-3656,-4103,-3177,1.01159083843231 +21509,-0.239355996251106,0.006821000017226,0.01552011910826,40595,-2178,-4597,-3098,1.01429438591003 +21511,-0.257532894611359,0.000491244427394,0.012937745079398,40595,-2495,-4726,-3188,1.01599228382111 +21513,-0.270925790071487,-0.003272235393524,0.010809037834406,40595,-2062,-4815,-3147,1.02290463447571 +21515,-0.287610113620758,-0.01743514277041,0.010953770950437,40595,-2099,-3904,-3200,1.02420830726624 +21517,-0.313532650470734,-0.032676219940186,0.012560654431582,40595,-395,-3513,-3114,1.01963555812836 +21519,-0.333847105503082,-0.050313029438257,0.007421331014484,40595,-1084,-3168,-3221,1.01296555995941 +21521,-0.35347655415535,-0.054153189063072,-0.001297371578403,40595,-95,-3963,-3268,1.00822567939758 +21523,-0.380051583051682,-0.065996967256069,-0.005131714046001,40595,139,-3332,-3307,1.01082146167755 +21525,-0.407167226076126,-0.095335751771927,-0.00230850186199,40595,1447,-1436,-3265,1.01293540000916 +21527,-0.43461886048317,-0.111568562686443,-0.000360535195796,40595,1124,-2320,-3273,1.01133835315704 +21529,-0.449839651584625,-0.117662720382214,-0.002157915383577,40595,1436,-2684,-3256,1.01178550720215 +21531,-0.465321779251099,-0.108413890004158,-0.003298062365502,40595,867,-4135,-3292,1.012943983078 +21533,-0.482444316148758,-0.115820214152336,-0.000655282754451,40595,2263,-2555,-3239,1.01698648929596 +21535,-0.508480727672577,-0.118873216211796,0.003593567525968,40595,2418,-3047,-3243,1.02083158493042 +21537,-0.529990077018738,-0.129075706005096,0.003263242542744,40595,3532,-2074,-3188,1.02224683761597 +21557,-0.602404773235321,-0.104300014674664,0.000916839984711,40595,-26158,-8388,-3223,1.02525806427002 +21559,-0.605046093463898,-0.094475910067558,0.003306860337034,40595,-27288,-9152,-3237,1.02233147621155 +21561,-0.607909917831421,-0.092009097337723,-7.19880699762143E-06,40595,-26085,-8460,-3237,1.01981854438782 +21563,-0.615899860858917,-0.080291323363781,-0.007240866776556,40595,-26805,-9494,-3308,1.02000951766968 +21565,-0.623640418052673,-0.081852331757546,-0.010354607366026,40595,-25529,-8347,-3362,1.02156758308411 +21567,-0.645578622817993,-0.089723654091358,-0.017029857262969,40595,-25427,-7964,-3376,1.02063536643982 +21569,-0.686626315116882,-0.096575431525707,-0.024084975942969,40595,-22156,-7737,-3523,1.02043533325195 +21571,-0.740250647068024,-0.112400025129318,-0.030765997245908,40595,-21815,-7070,-3474,1.02253103256226 +21573,-0.808111310005188,-0.122341431677341,-0.039496697485447,40595,-18256,-7085,-3705,1.02677071094513 +21575,-0.883599817752838,-0.128921717405319,-0.045308131724596,40595,-18151,-7483,-3579,1.02655792236328 +21577,-0.969357013702393,-0.129828661680222,-0.048222776502371,40595,-14276,-7592,-3815,1.02001988887787 +21579,-1.06599998474121,-0.146119505167007,-0.050303462892771,40595,-13900,-6524,-3620,1.01044797897339 +21581,-1.17246913909912,-0.164149329066277,-0.051513742655516,40595,-9322,-5789,-3858,0.999366939067841 +21583,-1.27977645397186,-0.175346359610558,-0.052056524902582,40595,-9852,-6438,-3640,0.988901674747467 +21585,-1.38555121421814,-0.188029855489731,-0.052575439214707,40595,-5644,-5749,-3879,0.988393783569336 +21587,-1.50105679035187,-0.205743014812469,-0.055810671299696,40595,-5771,-5492,-3673,0.990774273872376 +21589,-1.62955868244171,-0.230163857340813,-0.059530511498451,40595,321,-4178,-3970,0.997029900550842 +21591,-1.75906145572662,-0.249228909611702,-0.061834555119276,40595,-630,-4709,-3723,1.0007575750351 +21593,-1.88540637493134,-0.264459103345871,-0.06424156576395,40595,4818,-4219,-4040,1.00534653663635 +21595,-2.00293374061584,-0.294357717037201,-0.061404582113028,40595,2569,-3208,-3730,1.01084887981415 +21597,-2.11864471435547,-0.315905034542084,-0.058868400752544,40595,8446,-2836,-3995,1.01411318778992 +21599,-2.22056865692139,-0.342782497406006,-0.061310898512602,40595,5245,-2627,-3738,1.0123895406723 +21601,-2.33023428916931,-0.358658820390701,-0.064685329794884,40595,12164,-2438,-4087,1.00533401966095 +21603,-2.44536328315735,-0.379185140132904,-0.065729789435864,40595,10191,-2436,-3779,1.00076067447662 +21605,-2.55478429794312,-0.39483642578125,-0.062800511717796,40595,16611,-1747,-4094,0.997140049934387 +21607,-2.64977169036865,-0.410390734672546,-0.060559596866369,40595,12565,-2206,-3755,1.00132632255554 +21609,-2.7288920879364,-0.426124721765518,-0.061490666121245,40595,18187,-1090,-4113,1.0071005821228 +21611,-2.80065512657166,-0.435359209775925,-0.063111260533333,40595,14038,-2146,-3784,1.01566803455353 +21613,-2.8675172328949,-0.446320027112961,-0.063006438314915,40595,20556,-943,-4169,1.02466297149658 +21615,-2.92360949516296,-0.464873969554901,-0.059589195996523,40595,15721,-890,-3772,1.03059315681458 +21617,-2.97440147399902,-0.47429633140564,-0.058503661304712,40595,22201,-431,-4160,1.03797352313995 +21619,-3.01288199424744,-0.490070104598999,-0.058052390813828,40595,16839,-549,-3774,1.03895223140717 +21621,-3.04453873634338,-0.490291893482208,-0.056950226426125,40595,23075,-645,-4186,1.04132306575775 +21623,-3.0548243522644,-0.490014404058456,-0.057567808777094,40595,16560,-1512,-3785,1.04308640956879 +21625,-3.05448722839355,-0.484687805175781,-0.062154199928045,40595,22071,-944,-4287,1.04297280311584 +21627,-3.04456353187561,-0.485335439443588,-0.064969956874847,40595,16114,-1325,-3851,1.04722273349762 +21629,-3.01902675628662,-0.490618526935577,-0.059217058122158,40595,20832,98,-4298,1.05051290988922 +21631,-2.98741388320923,-0.483516722917557,-0.050610166043043,40595,14882,-1716,-3768,1.05205762386322 +21633,-2.95347166061401,-0.467775166034699,-0.047293767333031,40595,20297,-1589,-4190,1.0536003112793 +21635,-2.91021871566772,-0.441499084234238,-0.046440839767456,40595,14062,-3510,-3754,1.05257570743561 +21637,-2.85150647163391,-0.431815952062607,-0.039079025387764,40595,17965,-1561,-4115,1.0516881942749 +21639,-2.78651237487793,-0.430890738964081,-0.034877512603998,40595,11813,-1678,-3688,1.05146884918213 +21641,-2.71900510787964,-0.420640110969543,-0.034579299390316,40595,16233,-1613,-4091,1.05834662914276 +21643,-2.6398069858551,-0.40412512421608,-0.036024264991284,40595,9719,-3014,-3709,1.05686283111572 +21645,-2.55891537666321,-0.381134510040283,-0.033803764730692,40595,13662,-3014,-4091,1.05312442779541 +21647,-2.47273087501526,-0.36382594704628,-0.027491586282849,40595,7784,-3502,-3664,1.04858088493347 +21649,-2.37719035148621,-0.342050045728684,-0.022492945194244,40595,10576,-3429,-3961,1.05041491985321 +21651,-2.26964211463928,-0.326339155435562,-0.019567770883441,40595,4224,-3796,-3620,1.05752408504486 +21653,-2.15921854972839,-0.297681391239166,-0.020542234182358,40595,6799,-4528,-3931,1.06098520755768 +21655,-2.04723310470581,-0.278426170349121,-0.015040076337755,40595,1505,-4628,-3599,1.06181025505066 +21657,-1.93839776515961,-0.254362255334854,-0.009267305023968,40595,4046,-4807,-3784,1.06033849716187 +21659,-1.82771646976471,-0.224122703075409,-0.006178588606417,40595,-860,-6105,-3545,1.06842696666718 +21661,-1.71445429325104,-0.193920254707336,-0.004056733101606,40595,719,-6151,-3690,1.06615054607391 +21663,-1.6061018705368,-0.165074869990349,0.000663144805003,40595,-3283,-6790,-3503,1.06498110294342 +21665,-1.5030552148819,-0.149939462542534,0.006591289769858,40595,-1438,-5737,-3539,1.05890262126923 +21667,-1.39711844921112,-0.124184049665928,0.007690518628806,40595,-5611,-7114,-3458,1.05386817455292 +21669,-1.29501509666443,-0.098944485187531,0.011532186530531,40595,-4294,-7259,-3444,1.05423545837402 +21671,-1.20213747024536,-0.06989399343729,0.012971064075828,40595,-7066,-8110,-3422,1.05398654937744 +21673,-1.10503852367401,-0.053032524883747,0.013632752001286,40595,-6657,-7385,-3382,1.05820953845978 +21675,-1.01930522918701,-0.024194916710258,0.016685990616679,40595,-8855,-8751,-3395,1.05737614631653 +21677,-0.936284005641937,-0.010778514668346,0.024231527000666,40595,-8108,-7823,-3219,1.06032586097717 +21679,-0.853162229061127,-0.00625078799203,0.02755818516016,40595,-10805,-7285,-3316,1.0578339099884 +21681,-0.773938357830048,0.001161883817986,0.026382269337773,40595,-10261,-7602,-3179,1.05595898628235 +21683,-0.71396678686142,0.012289337813854,0.028441270813346,40595,-10970,-8046,-3305,1.05422937870026 +21685,-0.664820969104767,0.029603468254209,0.032697807997465,40595,-9734,-8801,-3074,1.05764317512512 +21687,-0.611959993839264,0.030552241951227,0.035036809742451,40595,-11798,-7614,-3253,1.06438863277435 +21689,-0.561112284660339,0.03881561383605,0.034438319504261,40595,-11442,-8337,-3038,1.0673645734787 +21707,-0.481409043073654,0.02522348985076,0.020321795716882,40595,-8016,-8051,-3319,1.03646326065063 +21709,-0.499818414449692,0.010895592160523,0.018477289006114,40595,-7252,-6465,-3217,1.03843808174133 +21711,-0.520187795162201,-0.006779364310205,0.013814901933074,40595,-7587,-5974,-3360,1.03369343280792 +21713,-0.551790297031403,-0.023440824821591,0.01238792296499,40595,-5393,-5764,-3318,1.02944934368134 +21715,-0.587658941745758,-0.041462402790785,0.01220911834389,40595,-5425,-5463,-3369,1.02131736278534 +21717,-0.621170043945313,-0.05588885396719,0.014100390486419,40595,-4042,-5411,-3327,1.00895082950592 +21719,-0.650140762329102,-0.077629178762436,0.016821367666125,40595,-4908,-4677,-3336,1.00349497795105 +21721,-0.686577796936035,-0.086471065878868,0.013675669208169,40595,-2651,-5312,-3361,1.00410449504852 +21723,-0.723377645015717,-0.103495009243488,0.008371122181416,40595,-3151,-4629,-3394,1.00571703910828 +21725,-0.768566071987152,-0.112848743796349,0.005290092900395,40595,-531,-4835,-3486,1.01339399814606 +21727,-0.817237436771393,-0.122745916247368,0.007361220661551,40595,-769,-4837,-3403,1.02238976955414 +21729,-0.867390632629395,-0.130302160978317,0.010423076339066,40595,1644,-4643,-3448,1.0318740606308 +21731,-0.911324381828308,-0.14816215634346,0.00929447170347,40595,474,-3867,-3392,1.03787875175476 +21733,-0.951758086681366,-0.174184858798981,0.006590728182346,40595,2578,-2559,-3543,1.0369199514389 +21735,-0.988051056861877,-0.193455517292023,0.008167942985892,40595,1304,-3060,-3404,1.03163516521454 +21737,-1.02240693569183,-0.213371768593788,0.008182956837118,40595,3578,-2293,-3571,1.02699160575867 +21739,-1.0561648607254,-0.225920230150223,0.00202266103588,40595,2411,-3000,-3452,1.02175390720367 +21741,-1.09218168258667,-0.227630972862244,-0.000439377909061,40595,5159,-3293,-3697,1.01718890666962 +21743,-1.12915670871735,-0.2342199832201,-0.001159548875876,40595,4035,-3227,-3481,1.01084566116333 +21745,-1.16625344753265,-0.243571013212204,-0.002164080506191,40595,6801,-2411,-3746,1.00938868522644 +21747,-1.19442772865295,-0.258129775524139,-0.001162989181466,40595,4724,-2225,-3490,1.00968909263611 +21749,-1.22012829780579,-0.26397180557251,-0.000831019657198,40595,7256,-2245,-3766,1.01522648334503 +21751,-1.2417403459549,-0.27378836274147,0.002312020165846,40595,5344,-2243,-3475,1.02238738536835 +21753,-1.25928509235382,-0.275975584983826,0.005763696040958,40595,7730,-2207,-3717,1.02453827857971 +21755,-1.26758778095245,-0.281604409217834,0.006234760396183,40595,5194,-2326,-3457,1.02701711654663 +21757,-1.26733136177063,-0.288402408361435,0.006156468298286,40595,7020,-1567,-3741,1.02313315868378 +21759,-1.26976335048676,-0.287263363599777,0.007170342840254,40595,5246,-2619,-3459,1.01982486248016 +21761,-1.26590287685394,-0.29178175330162,0.010886684060097,40595,7173,-1560,-3704,1.01843500137329 +21763,-1.2571849822998,-0.287687301635742,0.012929322198033,40595,4708,-2711,-3429,1.02242588996887 +21765,-1.23552513122559,-0.297818392515182,0.01255304645747,40595,5832,-948,-3705,1.02063190937042 +21767,-1.22090017795563,-0.291205108165741,0.014474499970675,40595,4195,-2724,-3427,1.02031588554382 +21769,-1.20949065685272,-0.280466258525848,0.015288791619241,40595,6577,-2607,-3668,1.02697777748108 +21771,-1.19624602794647,-0.263707786798477,0.012915785424411,40595,4363,-3735,-3446,1.0320543050766 +21773,-1.17899143695831,-0.253608077764511,0.010254345834255,40595,6086,-2885,-3708,1.03926682472229 +21775,-1.14775013923645,-0.248871549963951,0.011482754722238,40595,2791,-2987,-3464,1.03924381732941 +21777,-1.11256182193756,-0.226249098777771,0.016137577593327,40595,4111,-4132,-3616,1.03314018249512 +21779,-1.07610952854157,-0.212922126054764,0.018579710274935,40595,32767,4805,-3421,1.02887547016144 +21781,-1.04411196708679,-0.194005951285362,0.018366727977991,40595,9675,-2818,-3557,1.02563381195068 +21783,-1.01243114471436,-0.183894798159599,0.021738858893514,40595,7676,-2642,-3404,1.0208967924118 +21785,-0.981492340564728,-0.171230837702751,0.024535950273275,40595,9125,-2662,-3461,1.0143336057663 +21787,-0.94376277923584,-0.154521659016609,0.02690177038312,40595,6644,-3458,-3371,1.0213428735733 +21789,-0.893215298652649,-0.130695387721062,0.026597645133734,40595,6648,-4049,-3388,1.02953112125397 +21791,-0.836106657981873,-0.107311889529228,0.026550523936749,40595,4058,-4553,-3373,1.04245018959045 +21793,-0.779697597026825,-0.08898787945509,0.025773860514164,40595,4706,-4275,-3345,1.05228638648987 +21795,-0.714883327484131,-0.062267418950796,0.026195457205176,40595,2063,-5397,-3375,1.05851900577545 +21797,-0.641083121299744,-0.045141447335482,0.028317807242274,40595,1477,-4865,-3256,1.06370949745178 +21799,-0.57343202829361,-0.013235725462437,0.029995040968061,40595,66,-6449,-3345,1.05905485153198 +21801,-0.505553603172302,0.012779309414327,0.0356904566288,40595,-100,-6419,-3088,1.059849858284 +21803,-0.430270135402679,0.032885134220123,0.035641554743052,40595,-2361,-6268,-3299,1.0538318157196 +21805,-0.358786165714264,0.046218600124121,0.035938084125519,40595,-2608,-6059,-3032,1.05540788173676 +21807,-0.296550542116165,0.052965804934502,0.039185401052237,40595,-3239,-5615,-3266,1.05566561222076 +21809,-0.234003484249115,0.072840683162212,0.041242185980082,40595,-3920,-6977,-2925,1.05388104915619 +21811,-0.169675529003143,0.095329038798809,0.0411217212677,40595,-5162,-7378,-3241,1.05274307727814 +21813,-0.10285297781229,0.121143691241741,0.039978798478842,40595,-6334,-8222,-2864,1.04800474643707 +21815,-0.03634063526988,0.136470392346382,0.041076220571995,40595,32767,14130,-3229,1.04564023017883 +21817,0.017392069101334,0.157202869653702,0.041386667639017,40595,4789,-4843,-2786,1.04028224945068 +21819,0.065594993531704,0.167205438017845,0.043470282107592,40595,4778,-3959,-3198,1.03958141803741 +21821,0.110191658139229,0.17719666659832,0.040543586015701,40595,3970,-4433,-2755,1.03443193435669 +21823,0.148313418030739,0.195692896842957,0.039632298052311,40595,4323,-5016,-3209,1.03594255447388 +21825,0.192831829190254,0.203767210245132,0.040871113538742,40595,2627,-4773,-2702,1.0322357416153 +21827,0.249655619263649,0.218039110302925,0.041322637349367,40595,1501,-5086,-3180,1.03034973144531 +21829,0.30886971950531,0.234425485134125,0.038330212235451,40595,-359,-5927,-2676,1.02941620349884 +21831,0.364193111658096,0.260686039924622,0.036714792251587,40595,-117,-6625,-3194,1.02782201766968 +21833,0.418409496545792,0.27895200252533,0.037515234202147,40595,-1893,-6857,-2611,1.02555394172668 +21835,0.470998734235764,0.303187280893326,0.034030716866255,40595,-1588,-7177,-3194,1.02132260799408 +21837,0.528764665126801,0.320975691080093,0.030131734907627,40595,-4107,-7603,-2625,1.02340197563171 +21839,0.587013006210327,0.335963934659958,0.02917393296957,40595,-3847,-7093,-3207,1.0265519618988 +21841,0.641964972019196,0.349721819162369,0.033121678978205,40595,-5955,-7891,-2538,1.03340482711792 +21843,0.700248599052429,0.357418179512024,0.037410464137793,40595,-5717,-7000,-3129,1.03254449367523 +21845,0.750511705875397,0.375439643859863,0.039892356842756,40595,-7643,-8735,-2411,1.03774857521057 +21847,0.796464502811432,0.382594048976898,0.038706369698048,40595,-6508,-7455,-3097,1.04608273506165 +21849,0.836863517761231,0.389378786087036,0.034507177770138,40595,-8653,-8288,-2440,1.05551266670227 +21851,0.877859234809876,0.380190551280975,0.029303055256605,40595,-7658,-6390,-3138,1.06177914142609 +21853,0.914811551570892,0.386954843997955,0.024576472118497,40595,26033,-8389,-2544,1.05630147457123 +21855,0.952253401279449,0.395496159791946,0.025885364040732,40595,-2756,-8019,-3141,1.04487371444702 +21857,0.981710851192474,0.4111308157444,0.024894116446376,40595,-4844,-9566,-2499,1.03280079364777 +21859,1.00035297870636,0.428379654884338,0.022143565118313,40595,-2448,-9268,-3145,1.03224647045136 +21861,1.02027654647827,0.426691591739655,0.020135650411248,40595,-5132,-8738,-2525,1.0304182767868 +21863,1.04225850105286,0.422199934720993,0.021256893873215,40595,-3656,-7784,-3130,1.02921056747437 +21865,1.06845366954803,0.414485663175583,0.021684667095542,40595,-6729,-8269,-2511,1.02808701992035 +21867,1.09294843673706,0.427683770656586,0.018609127029777,40595,-4954,-9288,-3127,1.02764987945557 +21869,1.12563121318817,0.416316717863083,0.015816979110241,40595,-8520,-8194,-2568,1.02534973621368 +21871,1.14492332935333,0.410909593105316,0.015226756222546,40595,-5747,-7875,-3131,1.01823306083679 +21873,1.16180884838104,0.401749491691589,0.014723944477737,40595,-8409,-8277,-2588,1.01388549804688 +21875,1.17831516265869,0.389484465122223,0.012397415935993,40595,-6468,-7231,-3132,1.00650227069855 +21877,1.19001543521881,0.378629058599472,0.00811898894608,40595,-8957,-7935,-2683,1.00441765785217 +21879,1.20125663280487,0.367443263530731,0.005163618829101,40595,-6880,-7138,-3166,1.00678431987762 +21881,1.21477687358856,0.360460877418518,0.004852502606809,40595,-9956,-8070,-2735,1.00906097888947 +21883,1.2205365896225,0.344415813684463,0.006824497133493,40595,-7239,-6600,-3140,1.01530921459198 +21885,1.21627640724182,0.339265704154968,0.002641353756189,40595,-9177,-8009,-2780,1.01840543746948 +21887,1.21201992034912,0.32483172416687,-0.002176648704335,40595,-6879,-6569,-3188,1.02482354640961 +21889,1.20057857036591,0.31763431429863,-0.002628554822877,40595,-8878,-7638,-2861,1.02715396881104 +21891,1.18142175674438,0.298050343990326,0.000327075686073,40595,-23877,32767,-3160,1.03198039531708 +21893,1.16571581363678,0.270005255937576,-0.002490248298272,40595,-11508,16204,-2905,1.03471493721008 +21895,1.15023362636566,0.256730020046234,-0.009964706376195,40595,-9184,15884,-3221,1.02927660942078 +21897,1.13516342639923,0.23976144194603,-0.01734914444387,40595,-11539,16020,-3108,1.02385759353638 +21899,1.11423277854919,0.230516776442528,-0.023283239454031,40595,-8757,16096,-3307,1.02007293701172 +21901,1.08828973770142,0.214386895298958,-0.029523976147175,40595,-10463,16506,-3276,1.02101147174835 +21903,1.05499577522278,0.218502596020699,-0.03906400129199,40595,-7482,15448,-3413,1.01791632175446 +21905,1.01686954498291,0.244256362318993,-0.048535361886025,40595,-8869,13136,-3474,1.01761698722839 +21907,0.969008922576904,0.282778650522232,-0.054610326886177,40595,-5635,12181,-3519,1.02279329299927 +21909,0.919162154197693,0.337648004293442,-0.057078890502453,40595,-6849,9625,-3493,1.02505397796631 +21911,0.87812077999115,0.384090274572372,-0.061528358608484,40595,-5208,10235,-3565,1.02696990966797 +21913,0.841772973537445,0.434045761823654,-0.067997179925442,40595,-6925,8467,-3539,1.02725374698639 +21915,0.79817932844162,0.487668037414551,-0.071452751755715,40595,-4232,8265,-3630,1.0288610458374 +21917,0.746928870677948,0.556655049324035,-0.072646401822567,40595,-4644,5119,-3490,1.02294659614563 +21919,0.692664563655853,0.63398277759552,-0.074710503220558,40595,-2266,4440,-3648,1.01428711414337 +21921,0.641120553016663,0.719124853610992,-0.077965654432774,40595,-3188,1265,-3414,1.0103394985199 +21941,0.162655353546143,1.64335095882416,-0.078121855854988,40595,3008,-14976,-2590,1.03463089466095 +21943,0.124137043952942,1.71729981899261,-0.081908419728279,40595,3817,-12810,-3569,1.03507363796234 +21945,0.083850368857384,1.79651522636414,-0.084228835999966,40595,4227,-17979,-2510,1.03613352775574 +21947,0.047665551304817,1.88019621372223,-0.087587662041187,40595,4730,-16463,-3572,1.03864800930023 +21949,0.019380811601877,1.9521267414093,-0.090324960649014,40595,4422,-20625,-2423,1.04413032531738 +21951,-0.001478014397435,1.99455809593201,-0.090416416525841,40595,4351,-15842,-3553,1.05012619495392 +21953,-0.029245184734464,2.02365851402283,-0.094154514372349,40595,5213,-19417,-2373,1.05020105838776 +21955,-0.058273818343878,2.06198811531067,-0.098831497132778,40595,5790,-17246,-3570,1.04493319988251 +21957,-0.076285392045975,2.09537625312805,-0.10190537571907,40595,5334,-21628,-2367,1.0404098033905 +21959,-0.087755553424358,2.12104749679565,-0.110486693680286,40595,5016,-17954,-3609,1.03764641284943 +21961,-0.091519802808762,2.13083052635193,-0.119194477796555,40595,4632,-21291,-2501,1.039106965065 +21963,-0.095316804945469,2.13591861724854,-0.126698583364487,40595,4645,-17484,-3681,1.03776049613953 +21965,-0.097990021109581,2.14103031158447,-0.130141377449036,40595,4731,-21915,-2582,1.03905761241913 +21967,-0.101430185139179,2.13904666900635,-0.131161913275719,40595,4780,-17824,-3674,1.04440820217133 +21969,-0.104274488985538,2.12699627876282,-0.1344253718853,40595,4911,-21256,-2608,1.05111002922058 +21971,-0.097994081676006,2.10128235816956,-0.142527654767036,40595,4108,-16383,-3716,1.05184936523438 +21973,-0.088656790554524,2.08125448226929,-0.149136751890183,40595,3855,-20736,-2784,1.04986751079559 +21975,-0.076697044074535,2.04936385154724,-0.149297907948494,40595,3463,-15982,-3729,1.04683244228363 +21977,-0.064477495849133,2.00723075866699,-0.149455145001411,40595,3322,-18715,-2817,1.04060041904449 +21979,-0.047423999756575,1.95018923282623,-0.153725981712341,40595,2735,-13515,-3729,1.03676307201386 +21981,-0.026901399716735,1.89274501800537,-0.157285332679749,40595,2166,-16493,-2976,1.03481125831604 +21983,-0.006394957192242,1.84548056125641,-0.159189224243164,40595,1939,-13424,-3740,1.03073370456696 +21985,0.015280365012586,1.78658723831177,-0.160574302077293,40595,1426,-15354,-3080,1.03092563152313 +21987,0.036050643771887,1.73091888427734,-0.161830604076386,40595,1331,-11846,-3735,1.03576242923737 +21989,0.07421774417162,1.64837384223938,-0.160722658038139,40595,-707,-12058,-3179,1.0393693447113 +21991,0.099938444793224,1.56908118724823,-0.160567879676819,40595,52,-8441,-3708,1.04745733737946 +21993,0.122177429497242,1.48940896987915,-0.161569863557816,40595,-367,-10265,-3309,1.04860615730286 +21995,0.152452260255814,1.42256820201874,-0.159437999129295,40595,-1058,-7774,-3686,1.04375064373016 +21997,0.187438651919365,1.35918891429901,-0.158464521169663,40595,-2399,-9832,-3376,1.04352056980133 +21999,0.228519737720489,1.28053915500641,-0.15596504509449,40595,-2988,-5377,-3651,1.04358732700348 +22001,0.265430003404617,1.20015728473663,-0.154679268598557,40595,-3897,-6479,-3462,1.04183876514435 +22003,0.300365388393402,1.12192034721375,-0.154676660895348,40595,-3682,-3547,-3636,1.03609037399292 +22005,0.32415771484375,1.06322252750397,-0.150697991251946,40595,-4021,-6189,-3527,1.03087174892426 +22007,0.356466472148895,0.98381096124649,-0.149267122149468,40595,-4429,-1837,-3595,1.02326548099518 +22009,0.385467320680618,0.90798157453537,-0.149870023131371,40595,-5531,-2759,-3646,1.02530586719513 +22011,0.411314368247986,0.829696953296661,-0.14884153008461,40595,-4912,6,-3593,1.03487432003021 +22013,0.431164801120758,0.772656619548798,-0.147344619035721,40595,-5787,-2166,-3732,1.03704130649567 +22015,0.45349571108818,0.718360602855682,-0.145517930388451,40595,-5446,-341,-3574,1.04207646846771 +22017,0.485144376754761,0.656436800956726,-0.142967939376831,40595,-7712,-132,-3787,1.04151237010956 +22019,0.511302411556244,0.603842198848724,-0.138033032417297,40595,-6759,1003,-3530,1.04624581336975 +22021,0.5303995013237,0.538999319076538,-0.135556817054749,40595,-7771,1828,-3805,1.04239702224731 +22023,0.541144788265228,0.501197099685669,-0.14014744758606,40595,-6316,1291,-3553,1.03581511974335 +22025,0.555789768695831,0.460464000701904,-0.144527927041054,40595,-8111,1259,-3988,1.03194046020508 +22027,0.564741253852844,0.43518328666687,-0.149471461772919,40595,-6773,1249,-3630,1.03238296508789 +22029,0.578845322132111,0.39498171210289,-0.149289712309837,40595,-8699,2208,-4111,1.04141390323639 +22031,0.592969059944153,0.357665628194809,-0.149190977215767,40595,-7809,3161,-3643,1.04473066329956 +22033,0.598053991794586,0.336758017539978,-0.147779569029808,40595,-8619,1724,-4152,1.04306268692017 +22035,0.601357281208038,0.322221279144287,-0.144380435347557,40595,-7423,2002,-3627,1.04260122776032 +22037,0.601141452789307,0.314174383878708,-0.143280282616615,40595,-8555,1143,-4135,1.04096138477325 +22039,0.604476869106293,0.291629672050476,-0.145247340202332,40595,-7742,2989,-3649,1.03510212898254 +22041,0.601270377635956,0.284195274114609,-0.147346094250679,40595,-8619,1565,-4226,1.03588557243347 +22043,0.594239711761475,0.282436013221741,-0.146013557910919,40595,-7127,1619,-3673,1.04095637798309 +22045,0.576741218566895,0.290651768445969,-0.142751157283783,40595,-7470,325,-4191,1.04033124446869 +22047,0.555043578147888,0.295549303293228,-0.14582271873951,40595,-5780,937,-3689,1.0372154712677 +22049,0.538182497024536,0.305843710899353,-0.147195994853973,40595,-7151,-89,-4255,1.03329849243164 +22051,0.527597844600678,0.319132030010223,-0.14324626326561,40595,-6433,-26,-3689,1.03033065795898 +22053,0.508650541305542,0.321589589118958,-0.142121598124504,40595,-6764,189,-4206,1.03021121025085 +22055,0.483401954174042,0.33322685956955,-0.14140522480011,40595,-4987,-142,-3693,1.02371108531952 +22057,0.453896701335907,0.356822192668915,-0.139156356453896,40595,-5338,-1935,-4167,1.02183139324188 +22059,0.427826553583145,0.374194860458374,-0.137106642127037,40595,-4344,-1189,-3679,1.02680158615112 +22061,0.399470508098602,0.398274511098862,-0.137248739600182,40595,-4731,-2696,-4134,1.03103137016296 +22063,0.375288397073746,0.412622094154358,-0.138127535581589,40595,-3915,-1592,-3700,1.03321373462677 +22065,0.350515991449356,0.434388637542725,-0.136366978287697,40595,-4364,-3188,-4117,1.03297924995422 +22067,0.326443165540695,0.452147662639618,-0.130010843276978,40595,-3388,-2488,-3658,1.03727507591248 +22069,0.297281891107559,0.481554478406906,-0.126661092042923,40595,-3334,-4592,-3988,1.03785347938538 +22071,0.269338667392731,0.515052795410156,-0.126872166991234,40595,-2434,-4626,-3648,1.03502082824707 +22073,0.241739124059677,0.542525172233582,-0.127904817461968,40595,-2679,-5561,-3982,1.03277885913849 +22075,0.210573136806488,0.564295411109924,-0.127409890294075,40595,-1478,-4628,-3662,1.02774155139923 +22077,0.177207931876183,0.588935077190399,-0.124543912708759,40595,-1325,-6257,-3928,1.02861738204956 +22079,0.148197948932648,0.613324820995331,-0.123640604317188,40595,1515,-2072,-3645,1.02978622913361 +22081,0.117622993886471,0.636291205883026,-0.123639106750488,40595,-226,-6480,-3896,1.02988660335541 +22083,0.088213339447975,0.657366275787354,-0.121448434889317,40595,397,-5644,-3638,1.03251683712006 +22085,0.058760959655047,0.679601848125458,-0.118265047669411,40595,609,-7320,-3815,1.03468942642212 +22087,0.036113869398832,0.69673490524292,-0.11663805693388,40595,630,-6127,-3611,1.04071319103241 +22089,0.012291727587581,0.717717051506043,-0.115757405757904,40595,943,-8045,-3769,1.04499018192291 +22091,-0.016481842845678,0.737172424793243,-0.11367342621088,40595,1816,-7091,-3595,1.04866814613342 +22093,-0.036736186593771,0.748097479343414,-0.113732576370239,40595,1488,-8037,-3733,1.04405343532562 +22095,-0.047621980309486,0.760843336582184,-0.115258745849133,40595,995,-7182,-3610,1.03482723236084 +22097,-0.056179847568274,0.768997251987457,-0.115932784974575,40595,979,-8420,-3753,1.03137218952179 +22099,-0.070873200893402,0.785061597824097,-0.115812882781029,40595,1624,-8012,-3618,1.03110027313232 +22101,-0.081236623227596,0.789879202842712,-0.115114189684391,40595,1546,-8762,-3734,1.03232431411743 +22103,-0.085357531905174,0.788378894329071,-0.117330826818943,40595,1109,-7057,-3632,1.03073346614838 +22105,-0.093547761440277,0.795127868652344,-0.117613784968853,40595,1632,-9242,-3762,1.03466951847076 +22107,-0.100989662110806,0.79839962720871,-0.113975286483765,40595,1612,-7802,-3612,1.0429949760437 +22109,-0.100634515285492,0.80637264251709,-0.110503517091274,40595,1173,-9769,-3677,1.05248939990997 +22111,-0.090420328080654,0.804405868053436,-0.11239580065012,40595,239,-7779,-3604,1.06541061401367 +22113,-0.082916468381882,0.800565898418427,-0.116340517997742,40595,405,-9092,-3755,1.06408560276032 +22115,-0.079850345849991,0.785453975200653,-0.115414127707481,40595,634,-6831,-3628,1.05871641635895 +22117,-0.074526570737362,0.773101210594177,-0.1140256524086,40595,21183,-32767,-3752,1.04885268211365 +22119,-0.066998280584812,0.764266312122345,-0.115882083773613,39219,3661,-16154,-3635,1.04366159439087 +22121,-0.057721447199583,0.748143196105957,-0.116811096668243,39219,3437,-16842,-3804,1.04395687580109 +22123,-0.048373494297266,0.736356973648071,-0.115324854850769,39219,3319,-15877,-3636,1.0437308549881 +22125,-0.032997757196426,0.710211157798767,-0.113556265830994,39219,2652,-15833,-3793,1.0441107749939 +22127,-0.012425914406777,0.690276324748993,-0.117727994918823,39219,2044,-14951,-3658,1.04031109809875 +22129,0.011521334759891,0.662285685539246,-0.122078269720078,39219,1362,-15225,-3923,1.03791570663452 +22131,0.031028691679239,0.632358849048615,-0.124219514429569,39219,1523,-13702,-3710,1.02983212471008 +22133,0.044837240129709,0.59965580701828,-0.123477295041084,39219,1573,-14146,-3982,1.02701258659363 +22135,0.073500327765942,0.548372089862824,-0.123697631061077,39219,270,-11236,-3715,1.02622628211975 +22137,0.115190744400024,0.501509189605713,-0.127715080976486,39219,-1583,-11791,-4108,1.01997351646423 +22139,0.166126877069473,0.439824610948563,-0.130201742053032,39219,-2677,-9160,-3771,1.01542377471924 +22141,0.19799055159092,0.392938435077667,-0.130782976746559,39219,-2287,-10236,-4232,1.01625847816467 +22143,0.226262956857681,0.330424159765244,-0.126039311289787,39219,-1982,-7709,-3757,1.01635777950287 +22145,0.250850051641464,0.268574982881546,-0.121491454541683,39219,-2725,-7300,-4224,1.01718926429749 +22147,0.285138368606567,0.199889913201332,-0.120513528585434,39219,-3352,-5517,-3735,1.02048301696777 +22149,0.321503102779388,0.139007538557053,-0.118906922638416,39219,-4821,-5358,-4284,1.0195484161377 +22151,0.350920170545578,0.086565904319286,-0.116702072322369,39219,-4074,-5119,-3727,1.02672445774078 +22153,0.384200364351273,0.018336407840252,-0.116114020347595,39219,-5742,-2899,-4332,1.03652191162109 +22167,0.592155158519745,-0.426608502864838,-0.122733749449253,38361,-2819,-5763,-3863,1.02316534519196 +22169,0.621370077133179,-0.485434472560883,-0.117981016635895,38361,-4801,-4134,-4729,1.02032709121704 +22171,0.657639384269714,-0.544274210929871,-0.114778786897659,38361,-4629,-4270,-3838,1.01412510871887 +22173,0.69724839925766,-0.602044701576233,-0.111513704061508,38361,-7015,-2160,-4733,1.0068439245224 +22175,0.73687070608139,-0.665741682052612,-0.10841279476881,38361,-6266,-1986,-3824,0.994040429592133 +22177,0.770423710346222,-0.727626144886017,-0.104577340185642,38361,-8042,393,-4732,0.996313810348511 +22179,0.800483047962189,-0.800574779510498,-0.101294033229351,38361,-6790,863,-3806,1.00478482246399 +22181,0.824111521244049,-0.861730217933655,-0.102562338113785,38361,-8513,2805,-4792,1.00185859203339 +22183,0.849886119365692,-0.91768616437912,-0.100117705762386,38361,-7515,1644,-3830,0.997905015945435 +22185,0.874897301197052,-0.959237456321716,-0.0989920347929,38361,-9784,3319,-4816,0.993754208087921 +22187,0.901628732681274,-1.00570499897003,-0.098394878208637,38361,-8678,2592,-3851,0.999954521656036 +22189,0.919183194637299,-1.05292737483978,-0.101650454103947,38361,-10342,5627,-4908,0.996466338634491 +22191,0.931509435176849,-1.08828485012054,-0.100648500025272,38361,-8452,3391,-3900,1.00192666053772 +22193,0.948953092098236,-1.128089427948,-0.096701949834824,37557,-11201,6739,-4893,1.00026142597198 +22195,0.960485339164734,-1.16495501995087,-0.099189668893814,37557,-9204,5046,-3924,0.993165135383606 +22197,0.964600384235382,-1.19032645225525,-0.104612208902836,37557,-10888,7175,-5018,0.992482304573059 +22199,0.964474141597748,-1.19348919391632,-0.103968225419521,37557,-8828,3520,-3992,0.993780255317688 +22201,0.967772364616394,-1.20425748825073,-0.09911485761404,37557,-11258,6843,-4958,0.992298185825348 +22203,0.968319296836853,-1.21165204048157,-0.102907307446003,37557,-9334,4573,-4017,0.990559875965118 +22205,0.96987372636795,-1.22054553031921,-0.105890884995461,37557,-11568,7474,-5050,0.993539869785309 +22207,0.95936244726181,-1.22634732723236,-0.103540793061256,37557,-8820,5173,-4055,0.997410416603088 +22209,0.952148973941803,-1.23348808288574,-0.101952873170376,37557,-11050,8068,-5015,0.999667644500732 +22211,0.942028164863586,-1.23260676860809,-0.101373888552189,37557,-8999,5297,-4072,1.00247383117676 +22213,0.927571833133698,-1.21963703632355,-0.100517734885216,37557,-10519,6911,-4998,0.998880743980408 +22215,0.903472483158112,-1.19887149333954,-0.101157516241074,37557,-7835,3899,-4101,0.990819096565247 +22217,0.87450361251831,-1.16999614238739,-0.101811960339546,37557,-8990,5463,-5003,0.984254896640778 +22219,0.845726430416107,-1.13949608802795,-0.10126107186079,37557,-7039,2840,-4132,0.981693923473358 +22221,0.823740482330322,-1.11662435531616,-0.099543958902359,37557,-9003,5501,-4963,0.983718872070312 +22223,0.795930087566376,-1.08341479301453,-0.099226161837578,37557,-6738,2310,-4146,0.982269048690796 +22225,0.766290366649628,-1.05193960666657,-0.097616098821163,37557,-7838,4284,-4926,0.980269193649292 +22227,0.733376085758209,-1.01190316677094,-0.094662584364414,37557,-5792,1237,-4140,0.980101943016052 +22229,0.702475547790527,-0.97477787733078,-0.089206084609032,37557,-7014,-23275,-4816,0.984265267848968 +22231,0.664568901062012,-0.931595265865326,-0.083239637315273,37199,-4737,-4177,-4085,0.984662473201752 +22233,0.61975485086441,-0.890052139759064,-0.08281184732914,37199,-4954,-2730,-4732,0.983123004436493 +22235,0.584931075572968,-0.858552038669586,-0.080712899565697,37199,-4072,-4060,-4090,0.98029214143753 +22237,0.549165010452271,-0.812695682048798,-0.078662842512131,37199,-4696,-3996,-4675,0.97275447845459 +22239,0.510627329349518,-0.763757705688477,-0.078227512538433,37199,-2964,-6376,-4092,0.968929529190064 +22241,0.471127837896347,-0.720290839672089,-0.079707339406014,37199,-3359,-5048,-4675,0.966192841529846 +22243,0.445448398590088,-0.68753057718277,-0.076661020517349,37199,-3140,-6058,-4100,0.965375006198883 +22245,0.418676286935806,-0.65808117389679,-0.073606751859188,37199,-3583,-4809,-4597,0.967388153076172 +22247,0.382850915193558,-0.624429702758789,-0.073486156761646,37199,-1679,-6799,-4096,0.964925825595856 +22249,0.347246527671814,-0.594836056232452,-0.070072837173939,37199,-1937,-5623,-4553,0.965394020080566 +22251,0.303549349308014,-0.564883828163147,-0.067235372960568,37199,-109,-7186,-4069,0.964488089084625 +22253,0.270515292882919,-0.546677708625793,-0.067639350891113,37199,-991,-5394,-4527,0.962062895298004 +22255,0.24196146428585,-0.525144398212433,-0.068518549203873,37199,-408,-6971,-4093,0.955637335777283 +22257,0.212234497070312,-0.50884872674942,-0.064382374286652,37199,-366,-5702,-4493,0.951275944709778 +22259,0.182217478752136,-0.495962023735046,-0.059947773814201,37199,481,-6603,-4048,0.945362687110901 +22261,0.152470514178276,-0.482429504394531,-0.058802504092455,37199,552,-5774,-4433,0.937368333339691 +22263,0.127526015043259,-0.478294610977173,-0.058138161897659,37199,858,-6074,-4049,0.940699934959412 +22265,0.101791769266129,-0.464482724666595,-0.058996606618166,37199,1059,-5936,-4443,0.944977045059204 +22267,0.08361703902483,-0.451807349920273,-0.057221483439207,37199,983,-6918,-4055,0.952417194843292 +22269,0.063074499368668,-0.431435018777847,-0.056088499724865,36663,1301,-6806,-4415,0.954660713672638 +22271,0.045398943126202,-0.420853674411774,-0.052894618362188,36663,1492,-7078,-4038,0.959628164768219 +22273,0.026556428521872,-0.418023020029068,-0.051473807543516,36663,1770,-5636,-4371,0.960525631904602 +22275,0.005666376557201,-0.412582367658615,-0.050624217838049,36663,2305,-6699,-4033,0.960992813110352 +22277,-0.000769773789216,-0.415167391300201,-0.045139852911234,36663,1354,-5164,-4304,0.954244792461395 +22279,-0.007170389872044,-0.410395711660385,-0.040833249688149,36663,1477,-6553,-3976,0.948086619377136 +22281,-0.017526531592012,-0.415811151266098,-0.039114683866501,36663,1951,-4821,-4240,0.946641981601715 +22283,-0.02909554168582,-0.417414039373398,-0.040396027266979,36663,2198,-5865,-3983,0.949299454689026 +22285,-0.025452079251409,-0.427587300539017,-0.039405442774296,36663,1118,-4155,-4255,0.955292820930481 +22287,-0.023234905675054,-0.423269301652908,-0.03991050645709,36663,1168,-6067,-3989,0.955151379108429 +22289,-0.020356729626656,-0.416769474744797,-0.036271683871746,36663,1124,-5386,-4226,0.961960434913635 +22291,-0.015792837366462,-0.42412793636322,-0.031343154609203,36663,930,-5083,-3938,0.965047776699066 +22293,-0.009273487143219,-0.432938396930695,-0.029065394774079,36663,714,-3885,-4154,0.967293202877045 +22295,-0.000350641203113,-0.442584186792374,-0.027747781947255,36663,428,-4510,-3921,0.962685883045196 +22297,0.005906319711357,-0.444317877292633,-0.032864212989807,36663,513,-4063,-4209,0.957235932350159 +22299,0.016899915412068,-0.457425475120544,-0.033887602388859,36663,56,-3898,-3972,0.958558678627014 +22315,0.156176164746285,-0.522056579589844,-0.015743946656585,36305,-2818,-2467,-3877,0.925465047359467 +22317,0.176546111702919,-0.535254180431366,-0.014372798614204,36305,-3338,-904,-4042,0.92279976606369 +22319,0.193558990955353,-0.538867056369782,-0.017353499308229,36305,-3012,-2508,-3894,0.927200853824616 +22321,0.215134233236313,-0.554064750671387,-0.015438512898982,36305,-4106,-257,-4060,0.934061050415039 +22323,0.226161524653435,-0.555884540081024,-0.010151990689337,36305,-3125,-2185,-3851,0.93825775384903 +22325,0.246670812368393,-0.567448675632477,-0.007400054018945,36305,-4628,-88,-3971,0.939054727554321 +22327,0.271431714296341,-0.56737208366394,-0.010978331789374,36305,-4848,-1940,-3861,0.937263607978821 +22329,0.298169523477554,-0.57188618183136,-0.011610932648182,36305,-6020,-292,-4024,0.940110445022583 +22331,0.32104766368866,-0.578831195831299,-0.00919574405998,36305,-5541,-1051,-3854,0.936042845249176 +22333,0.334853619337082,-0.581919670104981,-0.008539100177586,36305,-5805,-9,-3990,0.940839648246765 +22335,0.340619206428528,-0.586421191692352,-0.007385387551039,36305,-4728,-889,-3847,0.941130578517914 +22337,0.352294862270355,-0.576562941074371,-0.003600010415539,36305,-6059,-819,-3929,0.943104982376099 +22339,0.370090305805206,-0.579554975032806,-0.000154481371283,36305,-6152,-872,-3801,0.949050188064575 +22341,0.380643844604492,-0.575751125812531,-0.00481573631987,36305,-6587,-179,-3943,0.946383535861969 +22343,0.3974769115448,-0.582756578922272,-0.008896723389626,36305,-6630,-314,-3865,0.943248152732849 +22345,0.403449863195419,-0.573643803596497,-0.005521748680621,35948,-6792,-365,-3950,0.941317319869995 +22347,0.412270039319992,-0.581745624542236,-0.003399136243388,35948,-6435,-24,-3831,0.940239310264587 +22349,0.414383590221405,-0.580387890338898,-0.009368871338665,35948,-6853,527,-3995,0.934497356414795 +22351,0.421960771083832,-0.57847261428833,-0.006693550851196,35948,-6656,-558,-3857,0.934121429920196 +22353,0.425300300121307,-0.570305407047272,-0.004833031911403,35948,-7289,108,-3939,0.932482957839966 +22355,0.432349473237991,-0.561581552028656,-0.001836131210439,35948,-6944,-1060,-3827,0.935668289661408 +22357,0.430472254753113,-0.560178101062775,0.000193241881789,35948,-7176,662,-3876,0.937282919883728 +22359,0.422507673501968,-0.555610775947571,-0.0008149430505,35948,-5907,-621,-3822,0.939073264598846 +22361,0.41506364941597,-0.555390000343323,-0.000977225136012,35948,-6705,897,-3887,0.936453878879547 +22363,0.406102508306503,-0.537240624427795,-0.004984309431165,35948,-5775,-1631,-3853,0.930450320243835 +22365,0.407114118337631,-0.530870020389557,-0.00837029889226,35948,-7364,272,-3971,0.919916331768036 +22367,0.393888741731644,-0.516092836856842,-0.008687836118042,35948,-5468,-1477,-3882,0.911045730113983 +22369,0.379109144210815,-0.513297855854034,-0.0068553625606,35948,-5945,454,-3951,0.909779250621796 +22371,0.370079219341278,-0.5010085105896,-0.006438543554395,35948,-5589,-1306,-3869,0.906190931797028 +22373,0.362953066825867,-0.483817726373673,-0.004879929125309,35948,-6382,-856,-3923,0.910054862499237 +22375,0.355479925870895,-0.476977378129959,-0.007046257145703,35948,-5645,-1063,-3876,0.908597707748413 +22377,0.343722075223923,-0.460556417703629,-0.00626073172316,35948,-5888,-987,-3936,0.9119593501091 +22379,0.321601092815399,-0.455525457859039,-0.004022813867778,35948,-4256,-1054,-3857,0.918795883655548 +22381,0.299232006072998,-0.446923047304153,-0.006768832914531,36216,-4552,-462,-3942,0.92036497592926 +22383,0.291203111410141,-0.437847375869751,-0.00521050626412,36216,-4959,-1414,-3868,0.922789931297302 +22385,0.270890742540359,-0.411726295948029,-0.003220101352781,36216,-4358,-2108,-3897,0.92194664478302 +22387,0.254392236471176,-0.399452030658722,-0.002372860908508,36216,-3940,-2025,-3850,0.921284019947052 +22389,0.238017141819,-0.384135395288467,-0.006276060827076,36216,-4206,-1617,-3930,0.91406661272049 +22391,0.22319895029068,-0.365671277046204,-0.009044864214957,36216,-3713,-2795,-3898,0.911123156547546 +22393,0.207787871360779,-0.347419738769531,-0.009181085042655,36216,-3885,-2273,-3963,0.908891320228577 +22395,0.188599497079849,-0.333078950643539,-0.008885517716408,36216,-2992,-2825,-3899,0.907413303852081 +22397,0.171931803226471,-0.323565781116486,-0.008588218130171,36216,-3286,-1904,-3956,0.906004667282104 +22399,0.152847617864609,-0.307679146528244,-0.009890693239868,36216,-2557,-3169,-3908,0.902413487434387 +22401,0.141701847314835,-0.303274661302567,-0.011788100004196,36216,-3239,-1745,-3993,0.901447236537933 +22403,0.122763656079769,-0.294820219278336,-0.011719323694706,36216,-2191,-2699,-3923,0.908027529716492 +22405,0.09627091139555,-0.285579085350037,-0.010214592330158,36216,-1451,-2263,-3975,0.922207713127136 +22407,0.08003568649292,-0.272442579269409,-0.010433937422931,36216,-1806,-3240,-3916,0.922290682792664 +22409,0.06135368347168,-0.253213822841644,-0.012185488827527,36216,-1476,-3399,-3999,0.920153141021728 +22411,0.051780857145786,-0.252357959747314,-0.010073485784233,36216,-1898,-2548,-3916,0.912984132766724 +22413,0.032688729465008,-0.243257150053978,-0.006869571749121,36216,-1004,-2751,-3939,0.902972340583801 +22415,0.014475387521088,-0.237525567412376,-0.005374581087381,36216,-753,-3016,-3886,0.898719668388367 +22417,0.001089726341888,-0.216810703277588,-0.00428593531251,36216,-905,-3921,-3909,0.89545476436615 +22419,-0.000591740419623,-0.212083667516708,-0.003113313345239,36216,-1716,-3226,-3871,0.893523573875427 +22421,-0.013028146699071,-0.196409076452255,-0.005374372471124,36216,-735,-3813,-3922,0.894394218921661 +22423,-0.019590046256781,-0.188931569457054,-0.006062600295991,36216,-1082,-3680,-3893,0.895216047763824 +22425,-0.027693824842572,-0.177082940936089,-0.006364067550749,36216,-789,-3773,-3934,0.898271858692169 +22427,-0.039126187562943,-0.163789793848991,-0.006489446852356,36216,-433,-4390,-3897,0.900128781795502 +22429,-0.04032276943326,-0.165562376379967,-0.004230421036482,36216,-1058,-2914,-3910,0.902607262134552 +22431,-0.041349869221449,-0.158691242337227,-0.001127534196712,36216,-1122,-3940,-3862,0.912132561206818 +22433,-0.03887714445591,-0.151890113949776,0.000395914074033,36216,-1317,-3690,-3856,0.918073952198029 +22435,-0.039149828255177,-0.14466156065464,-0.001133959391154,36216,-1183,-4109,-3862,0.921990275382996 +22437,-0.041036911308765,-0.146606132388115,-0.000746702426113,36216,-933,-3090,-3869,0.919457674026489 +22439,-0.045827895402908,-0.138935089111328,-0.00156508712098,36216,-735,-4166,-3865,0.909775197505951 +22441,-0.039501134306192,-0.144034460186958,-0.001731020864099,36216,-1525,-2851,-3882,0.901759803295136 +22443,-0.03395376354456,-0.132868468761444,-0.001511595444754,36216,-1620,-4448,-3866,0.895785391330719 +22445,-0.019695131108165,-0.133777290582657,-0.000231462341617,36216,-2407,-3276,-3865,0.899078667163849 +22447,-0.00229468382895,-0.129406943917275,-0.001565430546179,36216,-2909,-3962,-3866,0.898028671741486 +22465,0.067264474928379,-0.139666229486465,0.006086860783398,36395,-3495,-3321,-3788,0.914519548416138 +22467,0.086312778294087,-0.143529206514359,0.010365383699536,36395,-4326,-2918,-3782,0.917597353458404 +22469,0.09525328874588,-0.150017246603966,0.01129134837538,36395,-3920,-2304,-3726,0.917905449867248 +22471,0.103939533233643,-0.159232765436173,0.009317505173385,36395,-3873,-2249,-3788,0.920350611209869 +22473,0.106322944164276,-0.165728643536568,0.010379815474153,36395,-3670,-1986,-3736,0.915836095809936 +22475,0.116510055959225,-0.165127694606781,0.009939746931195,36395,-4203,-2800,-3782,0.910900115966797 +22477,0.132706731557846,-0.166103333234787,0.01210817694664,36395,-5141,-2312,-3714,0.905091404914856 +22479,0.136998131871223,-0.157921627163887,0.012239435687661,36395,-4130,-3379,-3765,0.904640197753906 +22481,0.14309886097908,-0.171214312314987,0.012550065293908,36395,-4631,-1271,-3706,0.906656980514526 +22483,0.145104840397835,-0.174113988876343,0.01382030826062,36395,-4141,-2281,-3752,0.908263862133026 +22485,0.157952487468719,-0.186084404587746,0.015991769731045,36395,-5401,-1045,-3663,0.908466696739197 +22487,0.160989254713059,-0.177379041910172,0.01610946841538,36395,-4506,-2986,-3734,0.906467318534851 +22489,0.167919531464577,-0.181633099913597,0.017261222004891,36395,-5211,-1594,-3645,0.90827214717865 +22491,0.16839924454689,-0.185048580169678,0.017720256000757,36395,-4498,-1930,-3720,0.908800423145294 +22493,0.170941278338432,-0.182732611894608,0.019840078428388,36395,-5025,-1975,-3612,0.916629612445831 +22495,0.173042878508568,-0.185246095061302,0.018656270578504,36538,-4753,-1913,-3711,0.914513826370239 +22497,0.175298869609833,-0.186463668942452,0.016619360074401,36538,-5141,-1586,-3646,0.913165271282196 +22499,0.171601891517639,-0.186000213027,0.015267892740667,36538,-4391,-2036,-3732,0.913479566574097 +22501,0.170903667807579,-0.180122330784798,0.012083347886801,36538,-4931,-2120,-3697,0.907886028289795 +22503,0.178757295012474,-0.187635898590088,0.010684095323086,36538,-5393,-1364,-3762,0.905326426029205 +22505,0.176791876554489,-0.178320869803429,0.009253613650799,36538,-5034,-2323,-3729,0.904176831245422 +22507,0.185033589601517,-0.18162277340889,0.009301331825554,36538,-5591,-1675,-3770,0.908038020133972 +22509,0.186718642711639,-0.174710392951965,0.004350255709142,36538,-5538,-2135,-3785,0.908023238182068 +22511,0.186208367347717,-0.178228422999382,0.00339482864365,36538,-5066,-1633,-3810,0.908952713012695 +22513,0.180223360657692,-0.177173346281052,0.002558905398473,36538,-4949,-1605,-3805,0.905519664287567 +22515,0.171774923801422,-0.17883338034153,0.00141430052463,36538,-4369,-1682,-3823,0.910367488861084 +22517,0.170689955353737,-0.181475803256035,0.004424676299095,36538,-5212,-1189,-3782,0.91088742017746 +22519,0.16309155523777,-0.179891020059586,0.008045236580074,36538,-4379,-1820,-3777,0.91477507352829 +22521,0.153909638524055,-0.183666974306107,0.011174856685102,36538,-4428,-974,-3701,0.925874054431915 +22523,0.142245203256607,-0.177899762988091,0.011283135972917,36538,-3855,-2065,-3753,0.923167526721954 +22525,0.130109697580338,-0.17875762283802,0.01034972909838,36538,-3896,-1175,-3708,0.919383227825165 +22527,0.120317973196507,-0.172139421105385,0.009392092935741,36538,-3731,-2126,-3765,0.911641716957092 +22529,0.116873018443584,-0.17885909974575,0.009717331267893,36538,-4361,-673,-3714,0.906071782112122 +22531,0.110269501805305,-0.1783107817173,0.007386905606836,36538,-3866,-1520,-3777,0.902647793292999 +22533,0.106104016304016,-0.175424233078957,0.008048614487052,36538,-4188,-1346,-3732,0.902379631996155 +22535,0.100110769271851,-0.169568762183189,0.007806823123246,36538,-3812,-1945,-3773,0.89963173866272 +22537,0.091745957732201,-0.166161671280861,0.003229074878618,36538,-3703,-1463,-3788,0.904974341392517 +22539,0.082014501094818,-0.167418271303177,0.000785363023169,36538,-3326,-1391,-3821,0.905385792255402 +22541,0.075823694467545,-0.155125364661217,0.004764596000314,36538,-3641,-2205,-3769,0.909502863883972 +22543,0.070146225392819,-0.150303199887276,0.007133393548429,36538,-3482,-2001,-3776,0.914247810840607 +22545,0.065333381295204,-0.144951730966568,0.003039558418095,36538,-3584,-1798,-3789,0.918071508407593 +22549,0.052580758929253,-0.134551122784615,-0.000744555843994,36538,-3173,-1884,-3833,0.925836980342865 +22551,0.041427683085203,-0.130961284041405,-0.000567916955333,36538,-2724,-2059,-3829,0.92655223608017 +22553,0.038846660405398,-0.12467947602272,-0.002581107895821,36538,-3369,-2077,-3855,0.923669576644897 +22555,0.034386157989502,-0.118005275726318,-0.005320525728166,36538,-3121,-2408,-3862,0.925358355045319 +22557,0.032713290303946,-0.118793867528439,-0.003773322096094,36538,-3371,-1612,-3870,0.918337881565094 +22559,0.022627890110016,-0.113932482898235,4.10782122344244E-05,36538,-2568,-2282,-3826,0.9128338098526 +22561,0.013177583925426,-0.116580449044704,0.004887304268777,36538,-2497,-1462,-3768,0.909207940101624 +22563,-0.000378651428036,-0.095454655587673,0.009026947431266,36538,-1996,-3659,-3764,0.911879599094391 +22565,-0.004987056367099,-0.090509928762913,0.011491283774376,36538,-2549,-2368,-3689,0.917649507522583 +22567,-0.014274998567999,-0.073717907071114,0.009189946576953,36538,32767,-32767,-3761,0.926766157150269 +22569,-0.020542021840811,-0.075860567390919,0.006426073610783,36538,28282,-7005,-3747,0.930000364780426 +22571,-0.02758476510644,-0.074771270155907,0.004926554393023,36538,28539,-7423,-3789,0.925885081291199 +22573,-0.035198006778956,-0.069233223795891,0.006400670856237,36538,28938,-7674,-3747,0.927826642990112 +22575,-0.027764458209276,-0.076599411666393,0.004077241756022,36538,27823,-6803,-3794,0.923131823539734 +22577,-0.013773951679468,-0.076803095638752,0.001380546949804,36538,27361,-7157,-3805,0.924733281135559 +22579,0.009264470078051,-0.086993671953678,0.000350179092493,36538,26483,-6460,-3820,0.921364963054657 +22581,0.042218293994665,-0.081399708986282,-0.004502368625253,36538,25384,-7518,-3875,0.924713551998138 +22583,0.091710343956947,-0.097056768834591,-0.008856972679496,36538,23689,-5932,-3884,0.931210875511169 +22585,0.154726639389992,-0.099032245576382,-0.012381372973323,36538,21657,-6690,-3969,0.932906925678253 +22587,0.238736391067505,-0.113415934145451,-0.01185255497694,36538,19337,-5788,-3907,0.934027254581451 +22589,0.327700227499008,-0.113887377083302,-0.01110399607569,36538,17166,-6556,-3955,0.935412168502808 +22591,0.431091368198395,-0.121175780892372,-0.010776393115521,36538,15336,-6178,-3901,0.940090537071228 +22593,0.539091110229492,-0.129605650901794,-0.012355517596006,36538,12468,-5722,-3971,0.944867432117462 +22595,0.661777675151825,-0.140301823616028,-0.009985499083996,36538,10693,-5645,-3898,0.952893316745758 +22597,0.790196895599365,-0.142385691404343,-0.009081485681236,36538,6927,-5946,-3932,0.952040255069733 +22599,0.927870571613312,-0.158456385135651,-0.006532694213092,36538,5733,-4978,-3875,0.95635175704956 +22601,1.06858193874359,-0.171994388103485,-0.002592483302578,36538,1399,-4611,-3853,0.955857574939728 +22603,1.2142825126648,-0.183496862649918,2.8110334824305E-05,36538,851,-4909,-3831,0.957552969455719 +22605,1.36191987991333,-0.186952993273735,0.001882319687866,36538,-4127,-5056,-3794,0.962107062339783 +22607,1.50774836540222,-0.174077346920967,0.004337472375482,36538,-3705,-6748,-3800,0.972014963626862 +22609,1.65454006195068,-0.16947914659977,0.006518208421767,36538,-9223,-5876,-3735,0.976254940032959 +22611,1.80052304267883,-0.174462676048279,0.00876893941313,36538,-8393,-5428,-3768,0.977254092693329 +22613,1.94339025020599,-0.190109983086586,0.011484081856907,36538,-14172,-4049,-3666,0.970423221588135 +22615,2.08290338516235,-0.194731205701828,0.018379501998425,36538,-12595,-5117,-3700,0.9704749584198 +22617,2.22307968139648,-0.215742632746696,0.025175908580422,36538,-19199,-3208,-3489,0.963389873504639 +22619,2.34616827964783,-0.229044139385223,0.027236634865403,36538,-15945,-3947,-3633,0.96297013759613 +22621,2.45912432670593,-0.235797569155693,0.029134096577764,36538,-21884,-3852,-3422,0.958936214447022 +22623,2.56785178184509,-0.237855449318886,0.025222590193153,36538,-18962,-4561,-3641,0.957136452198029 +22625,2.67757701873779,-0.249377369880676,0.023422535508871,36538,-26118,-3222,-3468,0.954316258430481 +22627,2.76827001571655,-0.253369301557541,0.02510691061616,36538,-21519,-4128,-3636,0.95432311296463 +22629,2.85292863845825,-0.269173294305801,0.02473178692162,36538,-28179,-2516,-3427,0.945233523845673 +22631,2.91997146606445,-0.265149980783462,0.019466444849968,36538,-23063,-4452,-3667,0.935249447822571 +22633,2.97364521026611,-0.263782531023026,0.013809905387461,36538,-28999,-3759,-3537,0.933622539043426 +22635,3.02210378646851,-0.258153945207596,0.012595368549228,36538,-24321,-4588,-3709,0.934897422790527 +22637,3.06461119651794,-0.268023401498795,0.011476235464215,36538,-30806,-2804,-3542,0.935941338539124 +22639,3.08535552024841,-0.274180829524994,0.007315981201828,36538,-24415,-3432,-3740,0.932019770145416 +22641,3.09950423240662,-0.284306526184082,0.004244002513587,36538,-30513,-2428,-3598,0.931562960147858 +22643,3.10837650299072,-0.290399849414825,-0.003518105717376,36538,-25091,-3112,-3809,0.927289724349976 +22645,3.10615420341492,-0.293843507766724,-0.007017330732197,36538,-30634,-2650,-3704,0.927151918411255 +22647,3.08549690246582,-0.299521565437317,-0.008519266732037,36538,-23854,-2913,-3839,0.924122989177704 +22649,3.05492329597473,-0.296724945306778,-0.013763641938567,36538,-28957,-2950,-3761,0.926940262317658 +22651,3.01532602310181,-0.296963751316071,-0.016960389912129,36538,-22680,-3239,-3894,0.93127316236496 +22653,2.9611713886261,-0.292086362838745,-0.017867086455226,36538,-26898,-3074,-3793,0.934655964374542 +22655,2.89188814163208,-0.288455367088318,-0.018703216686845,36538,-19935,-3538,-3902,0.934815108776092 +22657,2.82020282745361,-0.292541056871414,-0.023723499849439,36538,-24478,-2329,-3842,0.927634358406067 +22659,2.74550318717957,-0.303166389465332,-0.028338616713882,36538,-18543,-2206,-3965,0.927115678787231 +22661,2.6654109954834,-0.309720605611801,-0.02955318801105,36538,-22437,-1780,-3879,0.926584661006928 +22663,2.56841468811035,-0.313837081193924,-0.032087545841932,36538,-15441,-2412,-3988,0.92200642824173 +22665,2.46522212028503,-0.313262850046158,-0.036663543432951,36538,-18506,-2125,-3942,0.915043652057648 +22667,2.34417676925659,-0.320799916982651,-0.040783438831568,36538,-11449,-1957,-4045,0.914212048053741 +22669,2.22714281082153,-0.333837568759918,-0.045585509389639,36538,-14529,-708,-4014,0.909711360931396 +22671,2.10735964775085,-0.329596966505051,-0.044463619589806,36538,-8984,-2556,-4069,0.914270877838135 +22673,1.99138534069061,-0.335462719202042,-0.045525033026934,36538,-11550,-1064,-3997,0.917366862297058 +22675,1.87052488327026,-0.332742542028427,-0.049097832292318,36538,-6247,-2280,-4098,0.923224985599518 +22677,1.74375760555267,-0.326509267091751,-0.048927132040262,36538,-7422,-1940,-4033,0.933035969734192 +22679,1.61240613460541,-0.329051554203033,-0.04785293713212,36538,-2418,-1834,-4087,0.931401193141937 +22681,1.48230993747711,-0.332015454769134,-0.047896422445774,36538,-32767,28314,-4004,0.932180523872376 +22683,1.36124050617218,-0.341100513935089,-0.046958316117525,36538,-30514,3895,-4078,0.932048916816711 +22685,1.2376936674118,-0.337009727954864,-0.047008410096169,36538,-31077,3606,-3978,0.927763938903809 +22687,1.11067581176758,-0.347802042961121,-0.046520069241524,36538,-27198,4290,-4072,0.925547420978546 +22689,0.98116797208786,-0.358928650617599,-0.047666031867266,36538,-27127,5217,-3953,0.920462429523468 +22691,0.852022230625153,-0.351097375154495,-0.052322909235954,36538,-23924,3187,-4108,0.922064244747162 +22693,0.722682058811188,-0.328670650720596,-0.058212481439114,36538,-23469,2505,-4100,0.922992706298828 +22695,0.583009362220764,-0.31988462805748,-0.065386518836022,36538,-19782,2843,-4196,0.917911529541016 +22697,0.422010332345962,-0.308041006326675,-0.072147496044636,36538,-16717,3110,-4282,0.91595858335495 +22699,0.257775396108627,-0.297621786594391,-0.07334054261446,36538,-13691,2572,-4252,0.914739429950714 +22701,0.086756557226181,-0.27687868475914,-0.075072154402733,36538,-10818,2128,-4350,0.916724801063538 +22703,-0.078053236007691,-0.255268603563309,-0.077650830149651,36538,-9012,1316,-4285,0.916520655155182 +22705,-0.253519266843796,-0.246662765741348,-0.082391701638699,36538,-5078,2661,-4473,0.911847829818726 +22707,-0.43312206864357,-0.23000505566597,-0.090802118182182,36538,-2882,1449,-4381,0.906968355178833 +22709,-0.618431746959686,-0.200051501393318,-0.094719015061855,36538,1616,513,-4675,0.90784364938736 +22711,-0.792837500572205,-0.176665633916855,-0.092012599110603,36538,2052,324,-4398,0.906286895275116 +22713,-0.964658081531525,-0.150087654590607,-0.093503914773464,36538,6497,54,-4725,0.909217357635498 +22715,-1.13044512271881,-0.133448243141174,-0.096161909401417,36538,6588,286,-4437,0.914518713951111 +22717,-1.29482567310333,-0.119081720709801,-0.094616435468197,36538,32767,-20215,-4785,0.911449909210205 +22719,-1.4509779214859,-0.102202452719212,-0.090362377464771,36538,32767,-3594,-4409,0.910261750221252 +22721,-1.60414218902588,-0.074034072458744,-0.085039116442204,36538,32767,-4644,-4731,0.908762276172638 +22723,-1.73903942108154,-0.063566267490387,-0.081040047109127,36538,32767,-3658,-4357,0.914115488529205 +22725,-1.86187171936035,-0.048055179417133,-0.083337403833866,36538,32767,-4136,-4749,0.924671947956085 +22727,-1.97437417507172,-0.022540811449289,-0.093014977872372,36538,32767,-5306,-4452,0.930824995040894 +22729,-2.06558775901794,-0.015798447653651,-0.097892917692661,36538,32767,-4013,-4964,0.935907185077667 +22731,-2.14084124565125,-0.000570910982788,-0.097933650016785,36538,32767,-4880,-4502,0.934844374656677 +22733,-2.2085382938385,0.020147114992142,-0.10098984837532,36538,32767,-5606,-5049,0.943364679813385 +22735,-2.25203657150269,0.043825589120388,-0.103790812194347,36538,32767,-6134,-4560,0.950207769870758 +22737,-2.28133416175842,0.066390059888363,-0.103899292647839,36538,32767,-6506,-5138,0.962092161178589 +22739,-2.27761054039001,0.060253586620092,-0.101455084979534,36538,32767,-4267,-4563,0.964757263660431 +22741,-2.26462173461914,0.057254679501057,-0.101050794124603,36538,32767,-4566,-5113,0.956532895565033 +22743,-2.23556065559387,0.063107185065746,-0.103949151933193,36538,32767,-5197,-4598,0.955810129642487 +22745,-2.1939435005188,0.086231648921967,-0.106096372008324,36538,32767,-6942,-5209,0.954541981220245 +22747,-2.12853598594666,0.085873432457447,-0.104266218841076,36538,32767,-5121,-4621,0.951021015644074 +22749,-2.05108666419983,0.089388385415077,-0.102404750883579,36538,32767,-5638,-5184,0.952212333679199 +22751,-1.96238815784454,0.085614427924156,-0.098120607435703,36538,32767,-4919,-4598,0.95327365398407 +22753,-1.8563631772995,0.091167718172073,-0.095057599246502,36538,32767,-5870,-5113,0.956199765205383 +22755,-1.73520374298096,0.108836501836777,-0.093413695693016,36538,29218,-6837,-4583,0.9651238322258 +22757,-1.60546278953552,0.116953201591969,-0.094037964940071,36538,30329,-6521,-5131,0.967561185359955 +22759,-1.46404719352722,0.125343501567841,-0.094949267804623,36538,24777,-6469,-4612,0.974705874919891 +22761,-1.30613470077515,0.122093491256237,-0.094603128731251,36538,24269,-5847,-5154,0.974943697452545 +22777,0.263418465852737,0.154586583375931,-0.043665379285812,36538,-3949,-6386,-4625,1.01363921165466 +22779,0.694938361644745,0.147453859448433,-0.033130407333374,36538,-10538,-6018,-4509,1.01857197284698 +22781,0.886108934879303,0.14982208609581,-0.026409665122628,36538,-10559,-6827,-4222,1.00812757015228 +22783,1.07574105262756,0.15492781996727,-0.019024088978767,36538,-15287,-7430,-4357,1.00799095630646 +22785,1.25953221321106,0.165770292282105,-0.012116742320359,36538,-15719,-7744,-4130,1.00223112106323 +22787,1.25953221321106,0.165770292282105,-0.012116742320359,36538,-15719,-7744,-4130,1.00223112106323 +22789,1.60430514812469,0.171324878931046,0.003642584895715,36538,-19707,-7629,-4026,0.993566334247589 +22791,1.77069807052612,0.153084605932236,0.013495909050107,36538,-32767,14823,-3990,0.988407969474792 +22793,1.9157087802887,0.150297835469246,0.02045407705009,36538,-32767,-3216,-3912,0.987478673458099 +22795,2.05558037757874,0.139742940664291,0.025214495137334,36538,-32767,-2814,-3850,0.985549747943878 +22797,2.05558037757874,0.139742940664291,0.025214495137334,36538,-32767,-2814,-3850,0.985549747943878 +22799,2.30829358100891,0.144467413425446,0.01847492530942,36538,-32767,-3613,-3940,0.97365403175354 +22801,2.40077233314514,0.145897135138512,0.01240430213511,36538,-32767,-3547,-3967,0.966696679592133 +22803,2.48076844215393,0.13911871612072,0.009086854755878,36538,-32767,-3166,-4056,0.961951375007629 +22805,2.54283976554871,0.135517820715904,0.003540714504197,36538,-32767,-3083,-4030,0.951026678085327 +22807,2.54283976554871,0.135517820715904,0.003540714504197,36538,-32767,-3083,-4030,0.951026678085327 +22809,2.63054490089416,0.12901297211647,0.000601683626883,36538,-32767,-2974,-4054,0.950019955635071 +22811,2.65323066711426,0.130180314183235,-0.001475679222494,36538,-32767,-3668,-4194,0.954520761966705 +22813,2.66361880302429,0.132878959178925,-0.005271653644741,36538,-32767,-3578,-4099,0.958226203918457 +22815,2.65545248985291,0.151471167802811,-0.009620214812458,36538,-32767,-5305,-4320,0.957491457462311 +22817,2.65545248985291,0.151471167802811,-0.009620214812458,36538,-32767,-5305,-4320,0.957491457462311 +22819,2.58303833007812,0.154300585389137,-0.013168015517294,36538,-32767,-4216,-4379,0.953151226043701 +22821,2.51895618438721,0.147757083177567,-0.017591491341591,36538,-32767,-3231,-4198,0.959317624568939 +22823,2.44820690155029,0.151068925857544,-0.023006461560726,36538,-32767,-4292,-4506,0.958056092262268 +22825,2.36848330497742,0.162128612399101,-0.02601358294487,36538,-32767,-4747,-4265,0.957784414291382 +22827,2.28364753723145,0.156234964728355,-0.02468322403729,36538,-32767,-3766,-4547,0.952116847038269 +22829,2.18028903007507,0.158104732632637,-0.025343414396048,36538,-31808,-4083,-4271,0.941101551055908 +22831,2.06664705276489,0.155493348836899,-0.029205275699496,36538,-32767,-4042,-4616,0.936430513858795 +22833,1.94217264652252,0.161810293793678,-0.031819120049477,36538,-27855,-4507,-4326,0.929474711418152 +22835,1.81190836429596,0.166662976145744,-0.032811623066664,36538,-29249,-4807,-4687,0.926832377910614 +22837,1.66546761989594,0.160767450928688,-0.03487865254283,36538,-23175,-3674,-4359,0.926526844501495 +22839,1.50062739849091,0.157225668430328,-0.039599377661944,36538,-22497,-4105,-4773,0.917825996875763 +22841,1.32640135288239,0.147500693798065,-0.041892465204001,36538,-17042,-3262,-4420,0.918537497520447 +22843,1.15417051315308,0.143939793109894,-0.039868358522654,36538,-16966,-3927,-4778,0.91329836845398 +22845,0.975767314434052,0.126521795988083,-0.040560264140368,36538,-12275,-2454,-4424,0.912985682487488 +22847,0.784538090229034,0.118446528911591,-0.042996179312468,36538,-10086,-3234,-4799,0.915495991706848 +22849,0.594976305961609,0.121099390089512,-0.043869741261005,36538,-6409,-3849,-4459,0.908254981040955 +22851,0.402741491794586,0.123638115823269,-0.043728481978178,36538,-4127,-4107,-4826,0.911510169506073 +22853,0.210820242762566,0.109452039003372,-0.04200879111886,36538,-950,-2511,-4458,0.907981932163238 +22855,0.014714756980538,0.088003560900688,-0.040842417627573,36538,2311,-1833,-4763,0.904691874980926 +22857,-0.175999253988266,0.067408666014671,-0.035474319010973,36538,4467,-1468,-4424,0.908206343650818 +22859,-0.363984316587448,0.050715457648039,-0.033016748726368,36538,7927,-1596,-4637,0.909793555736541 +22861,-0.547623574733734,0.031119970604777,-0.033340372145176,36538,9424,-1023,-4418,0.914877533912659 +22863,-0.732587993144989,0.026083810254932,-0.034119166433811,36538,13918,-2047,-4629,0.91246098279953 +22865,-0.893897294998169,-0.001133621204644,-0.031627934426069,36538,13097,-11,-4413,0.90990549325943 +22867,-1.05453741550446,-0.020926607772708,-0.026406137272716,36538,-32767,-217,-4491,0.91650801897049 +22869,-1.21224725246429,-0.04345715790987,-0.021481651812792,36538,5682,284,-4347,0.923386931419373 +22871,-1.34662973880768,-0.055680077522993,-0.017992336302996,36538,8912,-165,-4358,0.917506992816925 +22873,-1.47008800506592,-0.062361244112253,-0.024355342611671,36538,7400,-539,-4369,0.913064301013946 +22875,-1.58282017707825,-0.07193349301815,-0.022060928866267,36538,11716,-39,-4391,0.909197926521301 +22877,-1.70256328582764,-0.06960766762495,-0.013398876413703,36538,11053,-1031,-4295,0.899923503398895 +22879,-1.82236957550049,-0.075424492359161,-0.008002514019609,36538,16735,-194,-4226,0.90188330411911 +22881,-1.9245491027832,-0.089332975447178,-0.005102672148496,36538,13677,466,-4237,0.904139041900635 +22883,-2.02402687072754,-0.099837400019169,-0.005833452101797,36538,19307,595,-4179,0.907683491706848 +22885,-2.11150789260864,-0.107294648885727,-0.006298453081399,36538,16104,326,-4244,0.918406307697296 +22887,-2.18874454498291,-0.103382088243961,-0.00384120317176,36538,21226,-324,-4154,0.930343925952911 +22889,-2.25978088378906,-0.106773860752583,0.002804666990414,36538,17934,91,-4179,0.949004113674164 +22891,-2.31792116165161,-0.107785433530808,0.00940122269094,36538,22851,165,-3996,0.963953971862793 +22893,-2.3692934513092,-0.102975279092789,0.007208249066025,36538,19041,-483,-4145,0.975020051002502 +22895,-2.40168642997742,-0.110171392560005,0.005800896789879,36538,23324,718,-4037,0.976536631584168 +22897,-2.42473125457764,-0.112880766391754,0.007453945931047,36538,18796,265,-4139,0.965453028678894 +22899,-2.43723011016846,-0.110887303948402,0.010382289998233,36538,23473,128,-3984,0.962014257907867 +22901,-2.44279050827026,-0.096148036420345,0.016187889501453,36538,18815,-1157,-4075,0.965107262134552 +22903,-2.42777919769287,-0.098597779870033,0.019017305225134,36538,22355,301,-3893,0.966060519218445 +22905,-2.40562653541565,-0.090437971055508,0.017438629642129,36538,17312,-707,-4062,0.96753454208374 +22907,-2.37152099609375,-0.076531104743481,0.018587727099657,36538,21067,-1175,-3913,0.967831015586853 +22909,-2.32512712478638,-0.064998626708984,0.020947709679604,36538,15415,-1264,-4033,0.966698229312897 +22925,-1.69502413272858,0.046031747013331,0.04240707680583,36538,5147,-2264,-3864,0.966219305992126 +22927,-1.5853773355484,0.060938000679016,0.043961919844151,36538,7118,-3362,-3672,0.959703326225281 +22929,-1.48047018051147,0.078306414186955,0.050398360937834,36538,3219,-3661,-3804,0.962497651576996 +22931,-1.36818552017212,0.102467454969883,0.054044429212809,36538,4011,-4731,-3565,0.967255413532257 +22933,-1.25430774688721,0.120261706411839,0.055061005055904,36538,-107,-4326,-3765,0.97477662563324 +22935,-1.13471674919128,0.119696266949177,0.055397499352694,36538,202,-3286,-3548,0.978550136089325 +22937,-1.01285696029663,0.133305951952934,0.060987252742052,36538,-3686,-4257,-3717,0.983678698539734 +22939,-0.892263770103455,0.14940357208252,0.069361448287964,36538,-3406,-4999,-3386,0.977031469345093 +22941,-0.782820880413055,0.178599059581757,0.071091026067734,36538,-5750,-6078,-3639,0.980630874633789 +22943,-0.671595454216003,0.191063776612282,0.068291567265987,36681,-6016,-5476,-3406,0.981430113315582 +22945,-0.557977855205536,0.208387911319733,0.060867309570313,36681,-9025,-5730,-3701,0.980808913707733 +22947,-0.45007786154747,0.216314196586609,0.062467437237501,36681,-9165,-5640,-3475,0.984100937843323 +22949,-0.360130310058594,0.239387392997742,0.069300398230553,36681,-10017,-6673,-3637,0.980518460273743 +22951,-0.26396968960762,0.243722215294838,0.071974247694016,36681,-11240,-5915,-3366,0.97857004404068 +22953,-0.178712084889412,0.253632664680481,0.072135761380196,36681,-12218,-6033,-3609,0.971876680850983 +22955,-0.09173484146595,0.244900479912758,0.0761778652668,36681,-13356,-5092,-3307,0.966949045658112 +22957,-0.01615146920085,0.254638165235519,0.081967376172543,36681,-13871,-6134,-3533,0.967701137065887 +22959,0.059627018868923,0.255783706903458,0.087046429514885,36681,-15072,-6085,-3173,0.970448851585388 +22961,0.127106055617332,0.260759383440018,0.086154714226723,36681,-15431,-5987,-3493,0.970085084438324 +22963,0.19306081533432,0.257523834705353,0.086495280265808,36681,-16656,-5909,-3170,0.966336250305176 +22965,0.238856583833694,0.253468990325928,0.08810942620039,36681,-15629,-5343,-3470,0.95608514547348 +22967,0.270696610212326,0.25690495967865,0.086234137415886,36681,-15644,-6484,-3163,0.948924779891968 +22969,0.305639922618866,0.246092438697815,0.084164813160896,36681,-15995,-4861,-3486,0.940136849880218 +22971,0.331467717885971,0.243821039795876,0.085305966436863,36681,-16393,-5966,-3160,0.944868266582489 +22973,0.346146792173386,0.239209339022636,0.089122526347637,36681,-15337,-5309,-3442,0.94951206445694 +22975,0.352418422698975,0.237959623336792,0.09192867577076,36681,-15539,-6046,-3070,0.950795650482178 +22977,0.360671103000641,0.22253192961216,0.091109454631806,36681,-15307,-4396,-3417,0.951820909976959 +22979,0.35324826836586,0.221111088991165,0.089850969612599,36681,-14789,-5856,-3078,0.952150106430054 +22981,0.343039751052856,0.206188470125198,0.091652244329453,36824,-13954,-4291,-3402,0.949100077152252 +22983,0.324395924806595,0.198989436030388,0.088579833507538,36824,-13726,-5158,-3073,0.948819041252136 +22985,0.304110199213028,0.18317286670208,0.08497167378664,36824,-12882,-3979,-3436,0.947125196456909 +22987,0.279043048620224,0.16747097671032,0.081149496138096,36824,-12725,-4106,-3137,0.944639980792999 +22989,0.239744201302528,0.156024292111397,0.079189129173756,36824,-10784,-3969,-3466,0.949808537960052 +22991,0.202550753951073,0.130648985505104,0.080052241683006,36824,-10789,-2879,-3123,0.949804246425629 +22993,0.161507189273834,0.113771915435791,0.07779486477375,36824,-9691,-3025,-3464,0.943540394306183 +22995,0.113845556974411,0.097577497363091,0.079546362161636,36824,-8728,-3045,-3104,0.936785876750946 +22997,0.0571254119277,0.090736456215382,0.081826895475388,36824,-7183,-3451,-3425,0.926578223705291 +22999,2.52549161814386E-05,0.061415266245604,0.07883132994175,36824,-6291,-1548,-3085,0.921932637691498 +23001,-0.063446551561356,0.045371051877737,0.071318410336971,36824,-5030,-2161,-3486,0.920572459697723 +23003,-0.121835492551327,0.031303357332945,0.064429715275765,36824,-4264,-2175,-3229,0.923507988452911 +23005,-0.181057155132294,0.019382886588574,0.06303808093071,36824,-3653,-2092,-3533,0.9244185090065 +23007,-0.249964654445648,0.000661854050122,0.063404060900211,36824,-1396,-1343,-3218,0.92543751001358 +23009,-0.317222744226456,-0.035621274262667,0.066652894020081,36824,-1068,448,-3498,0.924675345420837 +23011,-0.38391700387001,-0.053684819489718,0.066249437630177,36824,720,-484,-3151,0.925248205661774 +23013,-0.450232714414597,-0.07530914247036,0.063463903963566,36824,893,0,-3508,0.927868247032166 +23015,-0.515558481216431,-0.085464790463448,0.060752082616091,36824,2903,-503,-3191,0.923495471477508 +23017,-0.578347682952881,-0.102197580039501,0.059251300990582,36824,2660,81,-3526,0.915228128433228 +23019,-0.638476014137268,-0.116565056145191,0.057428635656834,36824,4732,346,-3207,0.909491956233978 +23021,-0.693191826343536,-0.124549441039562,0.05968414619565,36824,3969,-166,-3512,0.911969244480133 +23023,-0.746127367019653,-0.133195102214813,0.058395024389029,36824,6225,269,-3180,0.916550576686859 +23025,-0.795534193515778,-0.13651742041111,0.053907431662083,36824,5347,-261,-3541,0.921270132064819 +23027,-0.839359700679779,-0.148136332631111,0.052822843194008,36824,7396,806,-3231,0.932984232902527 +23029,-0.877019941806793,-0.150612279772758,0.053627636283636,36824,6010,-44,-3533,0.94111567735672 +23031,-0.904253900051117,-0.169360905885696,0.053712267428637,36824,7617,1755,-3205,0.939155399799347 +23033,-0.935131251811981,-0.170889362692833,0.0559515170753,36824,6727,266,-3506,0.941993892192841 +23035,-0.965815961360931,-0.170337930321693,0.058774292469025,36824,9247,484,-3138,0.941306531429291 +23037,-0.990581810474396,-0.163256913423538,0.056805588304997,36824,7485,-369,-3489,0.939235389232636 +23039,-1.00679516792297,-0.156374499201775,0.056115597486496,36824,9274,-115,-3165,0.943765759468079 +23041,-1.01465809345245,-0.157094866037369,0.057416494935751,36824,7040,184,-3474,0.944828569889069 +23043,-1.01980030536652,-0.152719587087631,0.057569578289986,36824,9108,79,-3141,0.945633709430695 +23045,-1.01857078075409,-0.147613927721977,0.057022593915463,36824,6873,-287,-3466,0.94339656829834 +23047,-1.01397252082825,-0.127902060747147,0.057339783757925,36824,8742,-1347,-3144,0.93786746263504 +23049,-1.00157785415649,-0.124396190047264,0.059633798897266,36824,6257,-436,-3437,0.937596261501312 +23051,-0.9859299659729,-0.102860800921917,0.059742413461208,36824,7912,-1823,-3114,0.938317179679871 +23053,-0.959723830223084,-0.104661703109741,0.059744227677584,36824,5085,-280,-3426,0.939617574214935 +23055,-0.940005242824554,-0.091617725789547,0.059932805597782,36824,7274,-1345,-3105,0.950549840927124 +23057,-0.912853598594666,-0.079249396920204,0.060957625508309,36913,4743,-1607,-3407,0.960485398769379 +23059,-0.884564995765686,-0.063206806778908,0.05910137295723,36913,6151,-1964,-3113,0.96111923456192 +23061,-0.850431680679321,-0.040385972708464,0.061142969876528,36913,3723,-2872,-3396,0.96153450012207 +23063,-0.81733763217926,-0.023587699979544,0.062577642500401,36913,5079,-2624,-3071,0.95342618227005 +23065,-0.779614508152008,-0.00578924966976,0.057552061975002,36913,2798,-2985,-3410,0.948758721351624 +23067,-0.733930885791779,0.004731800872833,0.055225372314453,36913,3143,-2624,-3153,0.947490632534027 +23069,-0.690246343612671,0.023463914170861,0.056707818061113,36913,1400,-3462,-3407,0.946766138076782 +23071,-0.640076160430908,0.031588923186064,0.060360498726368,36913,1581,-2890,-3088,0.948045015335083 +23073,-0.590559184551239,0.061644818633795,0.061870645731688,36913,-178,-4825,-3362,0.946404695510864 +23075,-0.533746242523193,0.075068488717079,0.060387797653675,36913,-378,-3988,-3085,0.947282195091248 +23077,-0.489615619182587,0.103431522846222,0.059002932161093,36913,-1020,-5327,-3372,0.94893479347229 +23079,-0.442149221897125,0.118389800190926,0.060492806136608,36913,-999,-4837,-3080,0.948447227478027 +23081,-0.396982401609421,0.139849960803986,0.06055798754096,36913,-2243,-5399,-3352,0.948762595653534 +23083,-0.345487743616104,0.157920554280281,0.058232862502337,36913,-2701,-5757,-3102,0.950450778007507 +23085,-0.29325458407402,0.163251161575317,0.056139674037695,36913,-4102,-4642,-3374,0.949119687080383 +23087,-0.251137733459473,0.17286404967308,0.056184269487858,36913,-3439,-5448,-3119,0.957637369632721 +23089,-0.207048639655113,0.172768697142601,0.059126943349838,36913,-4660,-4458,-3345,0.959782421588898 +23091,-0.166725501418114,0.178182139992714,0.05763104185462,36913,32767,-28733,-3094,0.958051741123199 +23093,-0.134022429585457,0.182304188609123,0.057844895869494,37145,25614,-8925,-3345,0.961954176425934 +23095,-0.10608396679163,0.198437809944153,0.058744303882122,37145,25936,-10446,-3074,0.961282014846802 +23097,-0.069889463484287,0.198252871632576,0.058787520974875,37145,24773,-8964,-3330,0.959432065486908 +23099,-0.037549298256636,0.211819112300873,0.056368824094534,37145,24823,-10603,-3095,0.951693713665008 +23101,0.010286081582308,0.204851284623146,0.052425380796194,37145,23087,-8699,-3365,0.945317327976227 +23103,0.062063690274954,0.198937952518463,0.046207454055548,37145,22085,-9123,-3205,0.947965621948242 +23105,0.126353695988655,0.185036063194275,0.043185595422983,37145,20495,-8039,-3422,0.946406185626983 +23107,0.192700818181038,0.182799637317658,0.036723054945469,37145,19139,-9249,-3309,0.946493089199066 +23109,0.278891712427139,0.170144096016884,0.033477101475,37145,16929,-8030,-3484,0.94885128736496 +23111,0.372394293546677,0.156945079565048,0.034062534570694,37145,14427,-8159,-3333,0.948988795280456 +23113,0.469964474439621,0.150791823863983,0.034026451408863,37145,13480,-8323,-3475,0.955178499221802 +23115,0.577159583568573,0.129389613866806,0.035028412938118,37145,10184,-7215,-3314,0.952585101127624 +23117,0.693208813667297,0.111492417752743,0.037893690168858,37145,8966,-7010,-3443,0.9617680311203 +23119,0.824974358081818,0.086984656751156,0.039011962711811,37145,4354,-6389,-3256,0.969117403030396 +23121,0.95472377538681,0.06914072483778,0.039592459797859,37145,4128,-6479,-3426,0.981882512569428 +23123,1.09205043315887,0.050473026931286,0.041736725717783,37145,-536,-6279,-3213,0.990764796733856 +23125,1.23084628582001,0.032427459955216,0.045605089515448,37145,-709,-5994,-3378,0.995307981967926 +23127,1.36633443832397,0.000156877504196,0.048120219260454,37145,-5151,-4528,-3122,0.99255096912384 +23129,1.4902982711792,-0.011149172671139,0.047904301434755,37145,-3728,-5885,-3354,0.995460629463196 +23131,1.62209534645081,-0.031235288828611,0.050762042403221,37145,-9461,-4908,-3075,0.98922324180603 +23133,1.7497900724411,-0.039876624941826,0.054150775074959,37145,-8199,-5680,-3303,0.987979710102081 +23135,1.87298309803009,-0.066839478909969,0.057472821325064,37145,-13454,-3853,-2976,0.986038327217102 +23137,1.98658883571625,-0.09296391159296,0.062083050608635,37145,-11189,-3668,-3238,0.990906417369842 +23153,2.64832401275635,-0.238745778799057,0.062042854726315,37145,-19509,-2370,-3186,0.985714614391327 +23155,2.69319891929626,-0.264058798551559,0.059490207582712,37145,-25322,-578,-2778,0.980637013912201 +23157,2.71671175956726,-0.274611979722977,0.054097756743431,37145,-19603,-1912,-3227,0.975434184074402 +23159,2.73577833175659,-0.281991064548492,0.051964033395052,37145,-25195,-1469,-2829,0.972389817237854 +23161,2.74275755882263,-0.292365878820419,0.046942725777626,37145,-19833,-1572,-3262,0.962183356285095 +23163,2.74048137664795,-0.306848347187042,0.041843365877867,37145,-24778,-447,-2905,0.96147358417511 +23165,2.72875952720642,-0.323118925094604,0.036933220922947,37145,-19343,-598,-3318,0.95424622297287 +23167,2.70943570137024,-0.337744385004044,0.033007435500622,37145,-24076,179,-2961,0.952431499958038 +23169,2.67910575866699,-0.349528551101685,0.030209984630346,37288,-18338,-414,-3352,0.953597247600555 +23171,2.62826800346375,-0.353060334920883,0.026274720206857,37288,-21515,-231,-3000,0.956754684448242 +23173,2.57492637634277,-0.355874419212341,0.018734036013484,37288,-16204,-831,-3418,0.962450623512268 +23175,2.51344132423401,-0.348105996847153,0.012197693809867,37288,-19864,-984,-3141,0.965965330600738 +23177,2.44417524337769,-0.351212531328201,0.005445752758533,37288,-14150,-743,-3498,0.958764493465424 +23179,2.36096286773682,-0.354272812604904,0.000429892766988,37288,-16753,22,-3249,0.951898276805878 +23181,2.26700878143311,-0.355487823486328,-0.002341581508517,37288,-10738,-680,-3542,0.950208246707916 +23183,2.17782187461853,-0.353384554386139,-0.001801064354368,37288,-14195,-232,-3252,0.950451016426086 +23185,2.07622623443604,-0.34743458032608,-0.001636424800381,37288,-8272,-1172,-3528,0.94852614402771 +23187,1.96811068058014,-0.352459251880646,-0.002480128547177,37288,-10195,393,-3239,0.945331394672394 +23189,1.86092805862427,-0.348127543926239,-0.005076657049358,37288,-5509,-910,-3542,0.943546950817108 +23191,1.75609064102173,-0.358087509870529,-0.00900743342936,37288,-7660,977,-3289,0.941945850849152 +23193,1.64197826385498,-0.355728417634964,-0.01238327100873,37288,-2503,-520,-3583,0.936062216758728 +23195,1.52015483379364,-0.343653172254562,-0.014696462079883,37288,-3183,-678,-3350,0.937495052814483 +23197,1.40085339546204,-0.336677968502045,-0.012345368973911,37288,800,-986,-3574,0.94264143705368 +23199,1.28223216533661,-0.314545780420303,-0.011834805831313,37288,-22,-1754,-3329,0.945813894271851 +23201,1.16974127292633,-0.307348936796188,-0.012347511947155,37288,3206,-1300,-3566,0.943723261356354 +23203,1.05973553657532,-0.297786891460419,-0.012566816993058,37288,2612,-1009,-3340,0.94192498922348 +23205,0.940223753452301,-0.306169748306274,-0.014207823202014,37288,6682,-85,-3571,0.943826079368591 +23207,0.825714409351349,-0.308485805988312,-0.016088644042611,37288,6463,126,-3359,0.941443681716919 +23209,0.723278701305389,-0.294026225805283,-0.01359179802239,37288,8355,-1775,-3559,0.941217124462128 +23211,0.636575698852539,-0.285508781671524,-0.010637739673257,37288,7364,-906,-3307,0.942773818969727 +23213,0.551136314868927,-0.269446521997452,-0.010750574059785,37288,9476,-2132,-3532,0.940579652786255 +23215,0.465609669685364,-0.262303709983826,-0.011182573623955,37288,9959,-1078,-3327,0.946181535720825 +23217,0.383742988109589,-0.239680871367455,-0.010959344916046,37288,11566,-2928,-3526,0.945757627487183 +23219,0.314960688352585,-0.223727479577064,-0.011703747324646,37288,11187,-2239,-3366,0.947649121284485 +23221,0.253365993499756,-0.216015130281448,-0.012928038835526,37288,11999,-2115,-3534,0.949605047702789 +23223,0.190894722938538,-0.205145746469498,-0.014715214259923,37288,12794,-2087,-3415,0.952905178070068 +23225,0.138098478317261,-0.205054610967636,-0.016590235754848,37288,13093,-1648,-3555,0.954639732837677 +23227,0.094545982778072,-0.189945533871651,-0.014178700745106,37288,13095,-2559,-3420,0.954809904098511 +23229,0.058410812169314,-0.176049247384071,-0.011618686839938,37288,13158,-2980,-3517,0.952319741249084 +23231,0.026463102549315,-0.15132212638855,-0.015719609335065,37288,13499,-3811,-3475,0.957701325416565 +23233,0.010721059516072,-0.133113041520119,-0.014499015174806,37288,12527,-3850,-3534,0.969833791255951 +23235,-0.001857931143604,-0.109957359731197,-0.013618561439216,37288,12726,-4331,-3492,0.979239702224731 +23237,-0.00378790916875,-0.088932879269123,-0.015643998980522,37288,11906,-4650,-3541,0.988885164260864 +23239,0.005828948225826,-0.073883272707462,-0.017985554412007,37288,11165,-4304,-3580,0.986275196075439 +23241,0.018918160349131,-0.061714194715023,-0.022246487438679,37288,10660,-4386,-3587,0.97875040769577 +23243,0.035108104348183,-0.049959752708674,-0.022662632167339,37288,10362,-4426,-3660,0.973125159740448 +23245,0.052506972104311,-0.023465495556593,-0.018079731613398,37288,10011,-5950,-3560,0.968504071235657 +23247,0.082186408340931,-0.0116813974455,-0.015028579160571,37288,8756,-5049,-3613,0.969933927059174 +23249,0.117864541709423,0.003466079011559,-0.019364604726434,37288,7882,-5530,-3571,0.969458401203156 +23251,0.162198722362518,0.003791105700657,-0.023144757375121,37288,6510,-4494,-3726,0.973654627799988 +23253,0.204649537801742,0.021322617307305,-0.023539494723082,37288,6234,-5972,-3604,0.98157125711441 +23255,0.251281410455704,0.03301552683115,-0.02011395804584,37288,4955,-5794,-3725,0.984417974948883 +23257,0.3062544465065,0.042918510735035,-0.016455117613077,37288,3919,-5761,-3560,0.978760421276092 +23259,0.362227886915207,0.063723310828209,-0.013353701680899,37288,2500,-6983,-3683,0.979797124862671 +23261,0.410800725221634,0.06781742721796,-0.014524788595736,37288,2866,-5743,-3551,0.981956422328949 +23263,0.461627215147018,0.066924020648003,-0.020240586251021,37288,1230,-5519,-3773,0.988485991954803 +23265,0.525355398654938,0.057815924286842,-0.022529065608978,37288,80,-4696,-3612,0.992410123348236 +23267,0.585400342941284,0.070382162928581,-0.01854657009244,37288,-1519,-6582,-3764,0.990937113761902 +23269,0.642986416816711,0.077485248446465,-0.013446140103042,37288,-1281,-6183,-3556,0.991409838199616 +23271,0.695151805877685,0.092882670462132,-0.011487120762467,37288,-2881,-7196,-3712,0.986058533191681 +23273,0.755497455596924,0.087164372205734,-0.009584887884557,37288,-3261,-5457,-3535,0.982331991195679 +23275,0.808947026729584,0.098531939089298,-0.006962185259908,37288,-5024,-7068,-3671,0.980747640132904 +23277,0.865432560443878,0.101164594292641,-0.00470909383148,37288,-4785,-6316,-3506,0.976993083953857 +23279,0.910054385662079,0.112350828945637,-0.005487187765539,37288,-6283,-7352,-3675,0.976800918579102 +23281,0.95001631975174,0.109943896532059,-0.003253868315369,37288,-5087,17290,-3501,0.97086489200592 +23283,0.986380875110626,0.100760743021965,-0.00047628255561,37288,-7217,-1811,-3611,0.960107028484344 +23285,1.02302360534668,0.089848875999451,0.004200305324048,37288,-6207,-1335,-3454,0.955492436885834 +23287,1.05664002895355,0.076837651431561,0.009293155744672,37288,-8488,-1171,-3475,0.949127793312073 +23307,1.16591370105743,0.093510448932648,-0.000814321043435,37288,-9238,-2325,-3639,0.977031767368317 +23309,1.15179622173309,0.101870715618134,-0.002172993030399,37288,-6752,-2973,-3518,0.975876927375793 +23311,1.12385821342468,0.116749934852123,-0.000233072903939,37288,-7498,-3890,-3668,0.973823606967926 +23313,1.09490966796875,0.117875754833221,-0.002017103601247,37288,-5264,-2715,-3523,0.965921223163605 +23315,1.06975507736206,0.118668891489506,-0.007674214895815,37288,-7201,-2940,-3764,0.965993225574493 +23317,1.04550755023956,0.117500565946102,-0.008264399133623,37288,-32767,-2576,-3572,0.968180179595947 +23319,1.01624286174774,0.128919988870621,-0.005201469175518,37288,-18564,-3901,-3758,0.967802882194519 +23321,0.983096599578857,0.123246431350708,-0.004428380168974,37288,-16315,-2371,-3553,0.967817842960358 +23323,0.939864575862884,0.127521127462387,-0.008308738470078,37288,-16762,-3399,-3802,0.961065649986267 +23325,0.902670919895172,0.112768121063709,-0.011411557905376,37288,-15303,-1605,-3608,0.957642555236816 +23327,0.849286437034607,0.110160768032074,-0.012190928682685,37288,-14978,-2651,-3833,0.95830762386322 +23329,0.786153554916382,0.113787889480591,-0.013200718909502,37288,-12166,-2963,-3627,0.961107730865478 +23331,0.722283124923706,0.10944177210331,-0.017494227737188,37288,-12538,-2541,-3902,0.959303975105285 +23333,0.649419069290161,0.116817183792591,-0.019387219101191,37288,-9845,-3302,-3678,0.955743372440338 +23335,0.565242469310761,0.126719415187836,-0.018872145563364,37288,-8834,-3872,-3950,0.954417765140533 +23337,0.478082031011581,0.125713378190994,-0.022879391908646,37288,-6629,-2864,-3711,0.94764107465744 +23339,0.390809029340744,0.114634342491627,-0.026381438598037,37288,-5995,-2200,-4032,0.941670119762421 +23341,0.292263776063919,0.11329098790884,-0.030398562550545,37288,-3333,-2690,-3773,0.936027705669403 +23343,0.195086136460304,0.116557471454144,-0.031549088656902,37288,-2254,-3279,-4104,0.935361564159393 +23345,0.101089313626289,0.115523494780064,-0.031858652830124,37288,-1013,-2773,-3793,0.934727728366852 +23347,0.004683751612902,0.10078913718462,-0.035765420645475,37288,726,-1755,-4142,0.932092726230621 +23349,-0.093950062990189,0.089903026819229,-0.037078339606524,37288,2107,-1721,-3840,0.924151539802551 +23351,-0.200116917490959,0.087263509631157,-0.03483833745122,37288,4795,-2424,-4123,0.926577508449554 +23353,-0.298562496900559,0.075647234916687,-0.034496653825045,37288,5116,-1479,-3832,0.931875705718994 +23355,-0.388064980506897,0.065479971468449,-0.033754598349333,37288,6783,-1547,-4090,0.935865759849548 +23357,-0.474492281675339,0.056170903146267,-0.032330695539713,37288,6953,-1372,-3826,0.936503350734711 +23359,-0.555391848087311,0.050407275557518,-0.031709719449282,37288,9099,-1623,-4054,0.928019464015961 +23361,-0.635887622833252,0.049499988555908,-0.029086610302329,37288,9098,-1878,-3811,0.923578381538391 +23363,-0.707734704017639,0.041333738714457,-0.025735430419445,37288,11206,-1312,-3978,0.919004261493683 +23365,-0.779472529888153,0.042456343770027,-0.02568112872541,37288,10856,-1920,-3794,0.92442661523819 +23367,-0.841995477676392,0.036685362458229,-0.025461016222835,37288,13071,-1403,-3975,0.93427163362503 +23369,-0.896928429603577,0.043927568942309,-0.024126889184117,37288,11726,-2376,-3789,0.941383957862854 +23371,-0.939313232898712,0.030729150399566,-0.022068219259381,37288,13621,-774,-3932,0.950205028057098 +23373,-0.980804204940796,0.032219242304564,-0.021990826353431,37288,12404,-1790,-3780,0.956431448459625 +23375,-1.01344132423401,0.031211487948895,-0.023492995649576,37288,14588,-1639,-3955,0.962565124034882 +23377,-1.04674184322357,0.031900700181723,-0.022834848612547,37288,13238,-1720,-3791,0.958347141742706 +23379,-1.0776686668396,0.038448721170426,-0.019766505807638,37288,16005,-2282,-3925,0.956384658813477 +23381,-1.08858597278595,0.039634138345718,-0.019104920327664,37288,12745,-1860,-3771,0.95174640417099 +23383,-1.08507704734802,0.053398936986923,-0.019879754632711,37288,14150,-3050,-3948,0.948648989200592 +23385,-1.07457280158997,0.066302359104157,-0.019021069630981,37288,11522,-3085,-3776,0.949960649013519 +23387,-1.06581449508667,0.073647677898407,-0.018572490662336,37288,13959,-2933,-3961,0.95267254114151 +23389,-1.0475435256958,0.065984860062599,-0.019992876797915,37288,11084,-1621,-3789,0.953685700893402 +23391,-1.02607607841492,0.076664194464684,-0.021123016253114,37288,12900,-3230,-3999,0.952533960342407 +23393,-0.9910808801651,0.07418754696846,-0.018704351037741,37288,-26493,-2124,-3786,0.955645442008972 +23395,-0.957582116127014,0.082931637763977,-0.019893465563655,37271,5309,-3207,-3997,0.959797263145447 +23397,-0.917654991149902,0.079376213252544,-0.021249439567328,37271,2501,-2138,-3811,0.963525772094727 +23399,-0.873876631259918,0.087199918925762,-0.022259341552854,37271,3587,-3234,-4034,0.962608277797699 +23401,-0.81939959526062,0.092684790492058,-0.02385762706399,37271,414,-2997,-3836,0.965581059455872 +23403,-0.768778681755066,0.10125295817852,-0.021664286032319,37271,1728,-3539,-4048,0.970751643180847 +23405,-0.725547969341278,0.117090925574303,-0.02063575387001,37271,192,-4116,-3821,0.97788280248642 +23407,-0.681105375289917,0.119710214436054,-0.022410172969103,37271,1045,-3440,-4084,0.971432089805603 +23409,-0.638919711112976,0.131048679351807,-0.021400207653642,37271,-695,-4029,-3835,0.964282333850861 +23411,-0.600275456905365,0.136348694562912,-0.018101595342159,37271,405,-3945,-4058,0.963232219219208 +23413,-0.567281126976013,0.144720926880837,-0.01767411082983,37271,-820,-4057,-3817,0.961832225322723 +23415,-0.532358467578888,0.138998106122017,-0.017373412847519,37271,-203,-3244,-4058,0.961040794849396 +23417,-0.500081419944763,0.153577983379364,-0.018564963713288,37271,-1517,-4675,-3832,0.96048241853714 +23419,-0.45892721414566,0.149130463600159,-0.018768744543195,37271,-1639,-3541,-4092,0.954929232597351 +23421,-0.437714576721191,0.158361077308655,-0.01940044015646,37271,-1436,-4410,-3846,0.955492377281189 +23423,-0.407514929771423,0.154509216547012,-0.016318023204804,37271,-1520,-3721,-4076,0.95409744977951 +23425,-0.379330039024353,0.16185288131237,-0.013222548179329,37271,-2612,-4377,-3812,0.950620412826538 +23427,-0.348393768072128,0.162875205278397,-0.012159855104983,37271,-2392,-4268,-4042,0.952399551868439 +23429,-0.324620217084885,0.168838754296303,-0.012781373225153,37271,-32767,-4436,-3817,0.958026111125946 +23431,-0.306259334087372,0.175424739718437,-0.014469652436674,37271,-8134,-4925,-4090,0.967104136943817 +23433,-0.288143455982208,0.169188514351845,-0.013828048482537,37271,-9068,-3630,-3833,0.965351760387421 +23435,-0.268834292888641,0.173226878046989,-0.013596951030195,37271,-8752,-4765,-4085,0.965441823005676 +23437,-0.250318437814712,0.174988970160484,-0.013546622358263,37271,-9597,-4348,-3839,0.96176940202713 +23439,-0.249127134680748,0.177422061562538,-0.013306050561369,37271,-7733,-4779,-4093,0.961334407329559 +23441,-0.25698110461235,0.162969216704369,-0.013886042870581,37271,-7578,-3078,-3850,0.956350207328796 +23443,-0.269301295280457,0.162946835160255,-0.01506076194346,37271,-6404,-4433,-4105,0.954413056373596 +23445,-0.279699862003326,0.154609888792038,-0.013659561984241,37271,-7026,-3454,-3857,0.956579208374023 +23447,-0.300654977560043,0.159698888659477,-0.013037267141044,37271,-5232,-4807,-4085,0.959550321102142 +23449,-0.319626122713089,0.150190636515617,-0.011658283881843,37271,-5781,-3365,-3851,0.962082505226135 +23451,-0.351331651210785,0.144355624914169,-0.012400718405843,37271,-3565,-3830,-4068,0.959237039089203 +23453,-0.384223461151123,0.141949266195297,-0.011100558564067,37271,-3773,-3807,-3854,0.956716954708099 +23455,-0.411170154809952,0.13074791431427,-0.010863435454667,37271,-2848,-3279,-4042,0.948434591293335 +23457,-0.445337563753128,0.12051148712635,-0.011602421291173,37271,-2694,-2985,-3864,0.948413610458374 +23459,-0.478045761585236,0.102466478943825,-0.008589002303779,37271,-1214,-2370,-3992,0.94598913192749 +23461,-0.51573634147644,0.092266328632832,-0.006690067239106,37271,-1287,-2616,-3835,0.943231046199799 +23463,-0.548174262046814,0.071341499686241,-0.00719266757369,37271,71,-1687,-3949,0.936921715736389 +23465,-0.587176203727722,0.064823500812054,-0.010083138011396,37271,11,-2506,-3862,0.938033640384674 +23467,-0.63029009103775,0.046687930822373,-0.012950384989381,37271,-32767,-1497,-3995,0.934781432151794 +23469,-0.686520099639893,0.047754351049662,-0.013764132745564,37396,-3199,-2813,-3891,0.936565577983856 +23471,-0.728245794773102,0.034169748425484,-0.014456622302532,37396,-2030,-1629,-4004,0.937961161136627 +23473,-0.764102578163147,0.02328891120851,-0.016614522784948,37396,-3340,-1609,-3915,0.940964341163635 +23475,-0.804227232933044,0.018733844161034,-0.019115995615721,37396,-690,-2026,-4047,0.951016426086426 +23477,-0.84742546081543,0.016233520582318,-0.022569920867682,37396,-1377,-2105,-3959,0.948074638843536 +23479,-0.898653984069824,0.013186199590564,-0.024965872988105,37396,1906,-2030,-4114,0.941142380237579 +23481,-0.947894632816315,-0.003051766660064,-0.023577304556966,37396,785,-836,-3971,0.929929316043854 +23483,-0.998752474784851,-0.012391784228385,-0.022578435018659,37396,3816,-1148,-4068,0.919032096862793 +23485,-1.0490916967392,-0.030094394460321,-0.023651879280806,37396,2654,-323,-3975,0.914330065250397 +23487,-1.09587514400482,-0.029918070882559,-0.02536615729332,37396,5449,-1532,-4088,0.914289057254791 +23489,-1.13372576236725,-0.04433174058795,-0.02619774453342,37396,3358,-328,-3996,0.917764782905579 +23491,-1.17763209342957,-0.043666772544384,-0.026769755408168,37396,6975,-1318,-4097,0.923427402973175 +23493,-1.21750867366791,-0.049140725284815,-0.024945395067334,37396,5131,-867,-3991,0.92651903629303 +23495,-1.26125705242157,-0.047168619930744,-0.022400960326195,37396,8782,-1308,-4048,0.927676439285278 +23497,-1.30166673660278,-0.037303231656551,-0.019571930170059,37396,6847,-2099,-3957,0.93177318572998 +23499,-1.33224928379059,-0.037940923124552,-0.017174370586872,37396,9487,-1226,-3998,0.933663427829742 +23501,-1.36046707630157,-0.03475347161293,-0.014715034514666,37396,7326,-1624,-3925,0.937010884284973 +23503,-1.38438761234283,-0.03737386316061,-0.012608721852303,37396,10365,-1061,-3948,0.942109882831574 +23505,-1.4007385969162,-0.034512162208557,-0.013481101952493,37396,7589,-1571,-3918,0.948394536972046 +23507,-1.41065979003906,-0.034901332110167,-0.017533736303449,37664,10316,-1238,-4010,0.94646418094635 +23509,-1.42305290699005,-0.02249089628458,-0.018567005172372,37664,8174,-2397,-3955,0.944464564323425 +23511,-1.42266762256622,-0.026926718652248,-0.014130930416286,37664,10317,-1057,-3978,0.942998468875885 +23513,-1.42539310455322,-0.01722133345902,-0.012404439039528,37664,8073,-2253,-3915,0.941720962524414 +23515,-1.42396795749664,-0.019792314618826,-0.013909827917814,37664,10814,-1280,-3983,0.942287445068359 +23517,-1.41827857494354,-0.013110788539052,-0.017292538657785,37664,7930,-2072,-3950,0.937312841415405 +23519,-1.4032027721405,-0.005349006038159,-0.017518455162644,37664,10047,-2235,-4037,0.940939128398895 +23537,-1.10129070281982,0.052735708653927,-0.024835800752044,37664,3131,-2548,-4021,0.972761869430542 +23539,-1.06071376800537,0.073211953043938,-0.0243538338691,37664,5136,-4438,-4180,0.981839299201965 +23541,-1.00359535217285,0.087834000587463,-0.023441251367331,37664,1264,-4093,-4017,0.982618808746338 +23543,-0.953420221805572,0.109725758433342,-0.024338399991393,37664,3075,-5164,-4202,0.976050019264221 +23545,-0.897893905639648,0.122580870985985,-0.021745329722762,38540,227,-4505,-4011,0.971590638160706 +23547,-0.845920026302338,0.139756232500076,-0.019729113206267,38540,1524,-5352,-4165,0.964670121669769 +23549,-0.789931416511535,0.140032947063446,-0.017913641408086,38540,-1038,-3907,-3991,0.961571872234344 +23551,-0.742308080196381,0.139438167214394,-0.016963366419077,38540,456,-4127,-4136,0.953250288963318 +23553,-0.697760999202728,0.136412143707275,-0.016919273883104,38540,-1268,-3672,-3989,0.955059468746185 +23555,-0.651034712791443,0.142942637205124,-0.020979898050428,38540,-702,-4760,-4189,0.95296573638916 +23557,-0.610627412796021,0.157686784863472,-0.026101466268301,38540,-1987,-5307,-4058,0.954800367355347 +23559,-0.565147995948792,0.159576535224915,-0.025093343108893,38540,-1790,-4749,-4249,0.954075932502747 +23561,-0.520832896232605,0.1749317497015,-0.021346153691411,38540,-3359,-5663,-4032,0.956195890903473 +23563,-0.478238195180893,0.186988517642021,-0.016386656090617,38540,-2815,-5989,-4163,0.963351607322693 +23565,-0.440650314092636,0.198198154568672,-0.015807228162885,38540,-3869,-5776,-4000,0.973156154155731 +23567,-0.401305824518204,0.188270300626755,-0.020153617486358,38540,-3679,-4503,-4213,0.981920540332794 +23569,-0.374023407697678,0.191049471497536,-0.019635746255517,38540,-3960,-5146,-4032,0.981764614582062 +23571,-0.342519968748093,0.185062557458878,-0.020326236262918,38540,-3970,-4808,-4218,0.980169773101806 +23573,-0.310674011707306,0.199504435062408,-0.021409338340163,38540,-5097,-6178,-4050,0.980476379394531 +23575,-0.271991491317749,0.193259060382843,-0.019927425310016,38540,-5559,-4996,-4221,0.976386249065399 +23577,-0.253597795963287,0.188439786434174,-0.019009351730347,38540,-4886,-4718,-4040,0.973006784915924 +23579,-0.23843552172184,0.172479540109634,-0.017627492547035,38540,-4362,-4037,-4190,0.970440626144409 +23581,-0.230728834867477,0.176978453993797,-0.02052241191268,38540,-4398,-5291,-4056,0.968283414840698 +23583,-0.217815414071083,0.176971942186356,-0.023586370050907,39255,-4488,-5324,-4267,0.966700375080108 +23585,-0.205712825059891,0.16878554224968,-0.023985423147678,39255,-5030,-4337,-4086,0.95879465341568 +23587,-0.199895232915878,0.159076005220413,-0.021790103986859,39255,-4238,-4408,-4244,0.954798817634582 +23589,-0.192355990409851,0.145351842045784,-0.020134765654802,39255,-4861,-3669,-4066,0.947348654270172 +23591,-0.182850956916809,0.144717186689377,-0.019974417984486,39255,-4752,-4887,-4222,0.949571669101715 +23593,-0.17387954890728,0.13831727206707,-0.022290950641036,39255,-5203,-4151,-4086,0.949428081512451 +23595,-0.173872441053391,0.134517341852188,-0.026070414111018,39255,-4187,-4556,-4295,0.946702241897583 +23597,-0.17994137108326,0.11437352001667,-0.026419680565596,39255,-4015,-2878,-4121,0.945444285869598 +23599,-0.193788975477219,0.108879938721657,-0.027466896921396,39255,-2837,-4068,-4307,0.949618458747864 +23601,-0.203226417303085,0.095578886568546,-0.028901537880302,39255,-3406,-3142,-4144,0.954391121864319 +23603,-0.221681207418442,0.09815177321434,-0.029553484171629,39255,-2006,-4505,-4334,0.958009481430054 +23605,-0.236350446939468,0.097421407699585,-0.027635257691145,39255,-2507,-4107,-4141,0.962527394294739 +23607,-0.254567176103592,0.095066286623478,-0.027053410187364,39255,-1435,-4132,-4309,0.960314393043518 +23609,-0.269199132919311,0.080538481473923,-0.027454655617476,39255,-1974,-2912,-4146,0.959972262382507 +23611,-0.291022479534149,0.062031220644713,-0.028415085747838,39255,-516,-2467,-4318,0.956475913524628 +23613,-0.317790925502777,0.054339714348316,-0.029724275693297,39255,-326,-3046,-4167,0.959293842315674 +23615,-0.339000135660171,0.0496576577425,-0.032627526670694,39255,304,-3288,-4368,0.959291756153107 +23617,-0.363823056221008,0.057473000138998,-0.034683275967836,39255,298,-4220,-4208,0.967033565044403 +23619,-0.380916208028793,0.04623506963253,-0.03553444519639,39916,798,-2788,-4407,0.968761205673218 +23621,-0.39999857544899,0.042869921773672,-0.033678635954857,39916,529,-3227,-4207,0.967017292976379 +23623,-0.416744440793991,0.032189600169659,-0.026276333257556,39916,1474,-2614,-4299,0.967639088630676 +23625,-0.427282810211182,0.034515786916018,-0.02704012952745,39916,447,-3526,-4167,0.968715250492096 +23627,-0.43182560801506,0.029537934809923,-0.027030179277063,39916,1006,-2985,-4311,0.974786698818207 +23629,-0.450221925973892,0.03299155831337,-0.027328362688422,39916,1490,-3594,-4174,0.979479134082794 +23631,-0.471669256687164,0.028733940795064,-0.026272648945451,39916,3045,-3018,-4307,0.985736608505249 +23633,-0.487497925758362,0.022796040400863,-0.025153560563922,39916,2014,-2781,-4164,0.982281506061554 +23635,-0.503448188304901,0.027684627100825,-0.02393158711493,39916,3346,-3653,-4284,0.98402601480484 +23637,-0.515600621700287,0.024984182789922,-0.025375332683325,39916,2343,-3049,-4170,0.979745090007782 +23639,-0.529827296733856,0.040064163506031,-0.02577786333859,39916,3836,-4592,-4313,0.984294772148132 +23641,-0.535048723220825,0.043575778603554,-0.027253672480583,39916,2327,-3771,-4187,0.98479163646698 +23643,-0.54159939289093,0.044087000191212,-0.030514458194375,39916,3660,-3642,-4375,0.979568421840668 +23645,-0.545966446399689,0.034190200269222,-0.028052991256118,39916,2627,-2690,-4199,0.977961421012878 +23647,-0.558347761631012,0.041175939142704,-0.028761960566044,39916,4553,-4079,-4359,0.981154024600983 +23649,-0.561046123504639,0.040641240775585,-0.032269664108753,39916,2937,-3468,-4233,0.980151653289795 +23651,-0.562266290187836,0.0524892359972,-0.034541826695204,39916,4036,-4631,-4435,0.97615385055542 +23653,-0.563183724880219,0.059295490384102,-0.03220421820879,39916,3058,-4283,-4239,0.975342452526092 +23655,-0.566124677658081,0.061032872647047,-0.02916463650763,39916,4442,-4069,-4380,0.970314383506775 +23657,-0.570150852203369,0.064427301287651,-0.027522059157491,40274,3602,-4137,-4212,0.974971055984497 +23659,-0.569489717483521,0.065156735479832,-0.029242865741253,40274,4464,-4076,-4387,0.975339710712433 +23661,-0.567475020885468,0.073874995112419,-0.030951242893934,40274,3356,-4679,-4242,0.982575297355652 +23663,-0.561251163482666,0.076149515807629,-0.029747353866696,40274,4155,-4392,-4400,0.992739677429199 +23665,-0.551285326480866,0.083651132881641,-0.029086818918586,40274,2778,-4762,-4234,0.998768270015717 +23667,-0.530274033546448,0.087079681456089,-0.029608011245728,40274,2805,-4688,-4406,1.00594389438629 +23669,-0.511533141136169,0.107344061136246,-0.030024144798517,40274,1788,-6052,-4247,1.00843560695648 +23693,-0.274742186069488,0.150197386741638,9.37127115321346E-05,40274,-1301,-5620,-4063,1.01144874095917 +23695,-0.262707263231277,0.160120531916618,0.006473181769252,40953,146,-6767,-4016,1.01418304443359 +23697,-0.252880781888962,0.150728642940521,0.006430209614337,40953,-284,-5012,-4019,1.01391363143921 +23699,-0.245956674218178,0.155282452702522,0.004232713021338,40953,325,-6383,-4041,1.01286959648132 +23701,-0.231247618794441,0.161398231983185,0.007657609414309,40953,-859,-6346,-4011,1.01948773860931 +23703,-0.211589813232422,0.156285986304283,0.012445799075067,40953,-1071,-5787,-3944,1.02181386947632 +23705,-0.20374022424221,0.154473289847374,0.015204745344818,40953,-693,-5751,-3959,1.02432918548584 +23707,-0.193820640444756,0.147219210863113,0.015436452813447,40953,-605,-5560,-3906,1.02067792415619 +23709,-0.181866750121117,0.145218759775162,0.017300156876445,40953,-1241,-5674,-3943,1.02688229084015 +23711,-0.178024992346764,0.132995262742043,0.022156512364745,40953,-372,-5042,-3822,1.02265667915344 +23713,-0.182473570108414,0.127802312374115,0.025514338165522,40953,-4,-5259,-3884,1.01794099807739 +23715,-0.18067467212677,0.108294203877449,0.021081041544676,40953,-123,-4171,-3827,1.01718485355377 +23717,-0.179717287421227,0.098738394677639,0.014967820607126,40953,-375,-4581,-3954,1.01187944412231 +23719,-0.175003364682198,0.085839726030827,0.014025950804353,40953,-358,-4327,-3904,1.01608622074127 +23721,-0.172454163432121,0.07294787466526,0.013980029150844,40953,-537,-4013,-3959,1.01564514636993 +23723,-0.177140131592751,0.068362288177013,0.018650958314538,40953,414,-4672,-3845,1.01857113838196 +23725,-0.177767410874367,0.0599943138659,0.024630155414343,40953,-175,-4184,-3883,1.01876068115234 +23727,-0.173407316207886,0.054441124200821,0.026519298553467,40953,-236,-4400,-3747,1.02110767364502 +23729,-0.174054384231567,0.042519126087427,0.027142282575369,40953,-169,-3704,-3862,1.01713478565216 +23731,-0.18367312848568,0.041732631623745,0.031210489571095,40953,986,-4560,-3685,1.0128208398819 +23733,-0.194627568125725,0.03059527464211,0.037736989557743,41400,925,-3609,-3784,1.00759553909302 +23735,-0.210248827934265,0.029979137703776,0.039489470422268,41400,1900,-4407,-3581,1.00555574893951 +23737,-0.212964400649071,0.012930785305798,0.039681479334831,41400,670,-2948,-3765,1.00547194480896 +23739,-0.216952696442604,0.00305287935771,0.039010420441628,41400,1248,-3313,-3576,1.01096749305725 +23741,-0.220838159322739,-0.009942929260433,0.039766725152731,41400,942,-2914,-3758,1.02021872997284 +23743,-0.22785872220993,-0.01955096796155,0.042333580553532,41400,1731,-2966,-3528,1.01794719696045 +23745,-0.239100053906441,-0.022342782467604,0.048772349953652,41400,1814,-3460,-3690,1.0265508890152 +23747,-0.2547248005867,-0.02315884642303,0.05552776530385,41400,2877,-3524,-3364,1.03507852554321 +23749,-0.262818664312363,-0.019938759505749,0.055374469608069,41400,2026,-3916,-3635,1.04138326644897 +23751,-0.266192674636841,-0.033833846449852,0.051767356693745,41400,2285,-2399,-3398,1.036536693573 +23753,-0.269176810979843,-0.037908792495728,0.051790446043015,41400,1854,-3121,-3651,1.02290284633636 +23755,-0.275153964757919,-0.03864223882556,0.05859062820673,41400,2718,-3252,-3309,1.01616168022156 +23757,-0.290540277957916,-0.034444320946932,0.061590604484081,41400,3157,-3747,-3574,1.00947999954224 +23759,-0.295153707265854,-0.044238686561585,0.066135868430138,41400,3051,-2488,-3209,1.01208770275116 +23761,-0.29519322514534,-0.046530995517969,0.068779177963734,41400,2240,-3089,-3514,1.01152300834656 +23763,-0.29666668176651,-0.041606575250626,0.07269562035799,41400,2969,-3568,-3121,1.01855826377869 +23765,-0.29685166478157,-0.043535217642784,0.075866475701332,41400,2393,-3139,-3453,1.01911330223084 +23767,-0.297741562128067,-0.039941407740116,0.076272636651993,41400,3070,-3483,-3067,1.02405691146851 +23769,-0.293149322271347,-0.037848748266697,0.078834369778633,41757,2118,-3490,-3420,1.03190219402313 +23771,-0.284683734178543,-0.032267462462187,0.081730589270592,41757,2309,-3730,-2991,1.03359746932983 +23773,-0.275598585605621,-0.033348277211189,0.082475513219833,41757,1660,-3312,-3382,1.03212928771973 +23775,-0.271871030330658,-0.024621704593301,0.084832981228829,41757,2542,-4067,-2942,1.03136241436005 +23777,-0.263303518295288,-0.019926989451051,0.086997225880623,41757,1630,-3907,-3337,1.03252732753754 +23779,-0.257810980081558,-0.01298519782722,0.08589955419302,41757,2288,-4123,-2916,1.03235793113709 +23781,-0.257220149040222,-0.007731874473393,0.084369733929634,41757,2216,-4116,-3341,1.0345801115036 +23783,-0.250888705253601,-0.009006103500724,0.083795890212059,41757,2219,-3607,-2928,1.03591120243073 +23785,-0.248340025544167,0.002694697119296,0.085488297045231,41757,2049,-4727,-3320,1.0448135137558 +23787,-0.244648873806,0.004069882445037,0.084309659898281,41757,2406,-4015,-2909,1.04899144172668 +23789,-0.237658202648163,0.012368542142212,0.080613501369953,41757,1676,-4627,-3340,1.05190706253052 +23791,-0.224338501691818,0.015026792883873,0.079302199184895,41757,1478,-4297,-2955,1.05244541168213 +23793,-0.215350404381752,0.032370738685131,0.077141501009464,41757,1302,-5573,-3350,1.04999017715454 +23795,-0.203691452741623,0.041944790631533,0.077493250370026,41757,1340,-5246,-2966,1.05334222316742 +23797,-0.190022230148315,0.046332199126482,0.079960949718952,41757,683,-4869,-3319,1.0524924993515 +23799,-0.178462535142899,0.052673522382975,0.07900620251894,41757,1007,-5211,-2936,1.05607187747955 +23801,-0.165182992815971,0.051561456173658,0.077644504606724,41757,422,-4577,-3322,1.05534303188324 +23803,-0.154596671462059,0.063425488770008,0.07902692258358,41757,749,-5812,-2923,1.05942094326019 +23805,-0.144139781594276,0.062348276376724,0.082363776862621,41757,379,-4767,-3276,1.06432664394379 +23807,-0.138985633850098,0.076330475509167,0.08486433327198,41757,945,-6207,-2842,1.06446361541748 +23809,-0.131905123591423,0.083496794104576,0.084200419485569,41757,496,-5700,-3250,1.06171607971191 +23811,-0.13086661696434,0.094120442867279,0.081448115408421,41757,1148,-6293,-2870,1.05655837059021 +23813,-0.125652998685837,0.09093189239502,0.082121178507805,41757,586,-5111,-3251,1.05756819248199 +23815,-0.111010506749153,0.081545770168305,0.078829132020474,41757,-120,-4698,-2887,1.05458068847656 +23817,-0.10649811476469,0.082344830036163,0.073138162493706,41757,397,-5315,-3300,1.05502104759216 +23819,-0.107190668582916,0.079238377511501,0.071030892431736,41757,955,-5148,-2967,1.05924391746521 +23821,-0.108894169330597,0.082101449370384,0.071450226008892,41757,911,-5499,-3300,1.05893516540527 +23823,-0.106703028082848,0.065606437623501,0.072554923593998,41757,791,-4001,-2936,1.05387198925018 +23825,-0.108090758323669,0.059460360556841,0.075665764510632,41757,914,-4561,-3260,1.05172741413116 +23841,-0.11735574901104,0.024484425783157,0.069962292909622,41757,837,-3726,-3253,1.03292405605316 +23843,-0.111212469637394,0.015584297478199,0.067859925329685,41757,806,-3859,-2931,1.03852701187134 +23845,-0.114761628210545,0.004795081913471,0.070625349879265,41757,1384,-3560,-3237,1.04980874061584 +23847,-0.124498970806599,-0.001819460070692,0.07023249566555,41757,2207,-3742,-2891,1.05957794189453 +23849,-0.133889555931091,-1.83127922355197E-05,0.066972233355045,41757,2126,-4394,-3251,1.06674492359161 +23851,-0.135806798934937,-0.008671496063471,0.068795144557953,41757,1878,-3486,-2896,1.06770741939545 +23853,-0.13594688475132,-0.018653830513358,0.073528617620468,41757,1547,-3282,-3194,1.06486642360687 +23855,-0.134134262800217,-0.040732681751251,0.076344974339008,41757,1630,-2003,-2794,1.05831599235535 +23857,-0.140883013606072,-0.053692553192377,0.076452724635601,41757,2144,-2551,-3162,1.05263555049896 +23859,-0.148325473070145,-0.067281991243363,0.080904684960842,41757,2577,-2164,-2727,1.05239629745483 +23861,-0.147461488842964,-0.081816911697388,0.083552524447441,41757,1752,-2008,-3100,1.050985455513 +23863,-0.143628269433975,-0.091300867497921,0.081101469695568,41757,1753,-2043,-2711,1.05108857154846 +23865,-0.144306749105454,-0.103608973324299,0.077236458659172,41757,1875,-1818,-3130,1.05179357528687 +23867,-0.153880327939987,-0.113645747303963,0.076998434960842,41757,2940,-1600,-2745,1.05920743942261 +23869,-0.157820209860802,-0.127250626683235,0.079533763229847,41757,2365,-1338,-3101,1.06677615642548 +23871,-0.158824354410172,-0.124426521360874,0.081991694867611,41757,2473,-2285,-2673,1.06666254997253 +23873,-0.157132223248482,-0.127279803156853,0.082443960011005,41757,2018,-2054,-3067,1.06546199321747 +23875,-0.151251718401909,-0.144868150353432,0.081204950809479,41757,1921,-435,-2669,1.05706560611725 +23877,-0.148758068680763,-0.157152697443962,0.079724334180355,41757,1903,-886,-3072,1.0498161315918 +23879,-0.141340687870979,-0.168274849653244,0.082167573273182,41757,1707,-450,-2644,1.04591429233551 +23881,-0.133634924888611,-0.166301414370537,0.087253049015999,41757,1371,-1702,-3007,1.0481390953064 +23883,-0.125209450721741,-0.17423003911972,0.091312594711781,41936,1426,-507,-2522,1.05130577087402 +23885,-0.120158612728119,-0.168070167303085,0.094708904623985,41936,1418,-1898,-2941,1.05476379394531 +23887,-0.110850661993027,-0.171152159571648,0.09692158550024,41936,1189,-820,-2440,1.06113958358765 +23889,-0.101992025971413,-0.169067546725273,0.09613648056984,41936,931,-1514,-2915,1.06226682662964 +23891,-0.096608698368073,-0.159909293055534,0.096440523862839,41936,1288,-1796,-2430,1.06671798229218 +23893,-0.090792581439018,-0.15396611392498,0.09637164324522,41936,1030,-1932,-2897,1.06562209129334 +23895,-0.086151197552681,-0.144140720367432,0.094047084450722,41936,1206,-2036,-2443,1.05813002586365 +23897,-0.078492499887943,-0.142143830657005,0.092340901494026,41936,757,-1752,-2909,1.05000138282776 +23899,-0.075487293303013,-0.137437269091606,0.092145495116711,41936,1177,-1717,-2450,1.04363131523132 +23901,-0.07279359549284,-0.140393048524857,0.093173697590828,41936,1061,-1359,-2888,1.04511499404907 +23903,-0.068314671516419,-0.140327051281929,0.095368340611458,41936,985,-1276,-2396,1.04564547538757 +23905,-0.062304966151714,-0.134070128202438,0.09790300577879,41936,700,-2045,-2839,1.04897546768188 +23907,-0.056434594094753,-0.133858129382133,0.099257051944733,41936,724,-1322,-2335,1.05363976955414 +23909,-0.050604626536369,-0.126333594322205,0.098774880170822,41936,569,-2184,-2817,1.0586576461792 +23911,-0.049729969352484,-0.126306533813477,0.097305469214916,41936,996,-1358,-2341,1.06603193283081 +23913,-0.05252030864358,-0.117841899394989,0.095520675182343,41936,1234,-2311,-2823,1.07371020317078 +23915,-0.04697198420763,-0.111224390566349,0.094900853931904,41936,632,-2008,-2353,1.07897329330444 +23917,-0.03882172331214,-0.107132710516453,0.096012026071549,41936,272,-2094,-2803,1.07241916656494 +23919,-0.039414923638105,-0.100794710218906,0.099610455334187,41936,962,-2109,-2282,1.06321859359741 +23921,-0.039730455726385,-0.094893679022789,0.099945783615112,41936,906,-2348,-2759,1.06362950801849 +23923,-0.040378604084253,-0.08348997682333,0.097402729094029,41936,1000,-2710,-2291,1.06553554534912 +23925,-0.035989575088024,-0.087220758199692,0.095561146736145,41936,531,-1724,-2773,1.06800508499146 +23927,-0.033704556524754,-0.083723418414593,0.094787478446961,41936,697,-2100,-2306,1.0685350894928 +23929,-0.032891023904085,-0.070350006222725,0.095688939094544,41936,756,-3149,-2756,1.07173609733582 +23931,-0.029505556449294,-0.064403720200062,0.095920987427235,41936,551,-2547,-2277,1.07762503623962 +23933,-0.025910127907992,-0.058654274791479,0.097333580255509,41936,465,-2736,-2729,1.08121275901794 +23935,-0.02219002135098,-0.05742184817791,0.096109881997109,41936,411,-2294,-2258,1.0816376209259 +23937,-0.019886080175638,-0.045215684920549,0.092749610543251,41936,476,-3360,-2744,1.0771369934082 +23939,-0.018245123326778,-0.031821165233851,0.092231802642346,41936,500,-3568,-2288,1.07330536842346 +23941,-0.021806970238686,-0.02135705575347,0.090797804296017,41936,927,-3560,-2742,1.06916689872742 +23943,-0.026868555694819,-0.009479676373303,0.08733843266964,41936,1128,-3814,-2331,1.06992185115814 +23945,-0.028736280277372,0.001427507027984,0.089874170720577,41936,913,-3913,-2734,1.07848858833313 +23947,-0.028225611895323,0.012768721207976,0.09538895636797,41936,760,-4131,-2221,1.0823780298233 +23949,-0.019169149920344,0.019316209480167,0.097638159990311,41936,2,-3860,-2664,1.08023309707642 +23951,-0.00573042826727,0.028764326125383,0.095072686672211,41936,-527,-4260,-2208,1.07530498504639 +23953,0.002754486864433,0.040723036974669,0.090657375752926,41936,-273,-4565,-2696,1.07034540176392 +23955,0.009051997214556,0.047938499599695,0.088698752224445,41936,-262,-4423,-2268,1.06844651699066 +23957,0.017204847186804,0.058724291622639,0.090899266302586,41936,-465,-4758,-2679,1.0698469877243 +23959,0.026204543188214,0.059134494513273,0.091827094554901,41936,-747,-4143,-2216,1.07404851913452 +23961,0.029294608160853,0.069572053849697,0.091801926493645,41936,-293,-4914,-2657,1.07776272296906 +23963,0.034955956041813,0.076129540801048,0.09250295907259,41936,-666,-4892,-2192,1.08160638809204 +23965,0.046105429530144,0.074400000274181,0.092333637177944,41936,-1133,-4144,-2638,1.08309102058411 +23967,0.05641708150506,0.07575149089098,0.089836113154888,41936,-1369,-4539,-2208,1.08661222457886 +23969,0.059438928961754,0.075128607451916,0.08327741920948,41936,-772,-4266,-2685,1.09447908401489 +23971,0.053625818341971,0.075027346611023,0.07875007390976,41936,-197,-4449,-2325,1.09606695175171 +23973,0.054037068039179,0.069040432572365,0.079471431672573,41936,-536,-3826,-2698,1.08952534198761 +23989,0.085927069187164,0.038687262684107,0.064754866063595,41936,-991,-3212,-2748,1.09130036830902 +23991,0.085366144776344,0.028016125783324,0.058817055076361,41936,-1255,-3035,-2496,1.0968930721283 +23993,0.092092469334602,0.01937897503376,0.058049608021975,41936,-1723,-3031,-2784,1.09672248363495 +23995,0.097317732870579,0.014246109873057,0.05874290317297,41936,-1916,-3221,-2487,1.09128773212433 +23997,0.099891647696495,0.001360406284221,0.058927893638611,41936,-1587,-2471,-2768,1.09102261066437 +23999,0.107104681432247,-0.010380415245891,0.058219969272614,41936,-2267,-2348,-2482,1.09452450275421 +24001,0.114382393658161,-0.019144328311086,0.064884804189205,41936,-2185,-2464,-2717,1.10153841972351 +24003,0.12208317220211,-0.029966993257403,0.074184097349644,41936,-2596,-2080,-2282,1.10750806331635 +24005,0.12596769630909,-0.037216395139694,0.07708577811718,41936,-2168,-2296,-2620,1.11054027080536 +24007,0.135227084159851,-0.048176888376474,0.077108226716518,41936,-2986,-1753,-2234,1.10985732078552 +24009,0.150688886642456,-0.049663711339235,0.07633825391531,41936,-3419,-2504,-2612,1.11077797412872 +24011,0.168461009860039,-0.046452023088932,0.074370168149471,41936,-4219,-2770,-2253,1.11514365673065 +24013,0.185768812894821,-0.041357386857271,0.075799770653248,41936,-4139,-3069,-2603,1.11397528648376 +24015,0.192647010087967,-0.038977306336165,0.078508257865906,41936,-3926,-2818,-2192,1.11278831958771 +24017,0.196098521351814,-0.044217344373465,0.079362869262695,41936,-3392,-2267,-2565,1.10773801803589 +24019,0.196568563580513,-0.046342492103577,0.0812803581357,41936,-3631,-2365,-2145,1.10330379009247 +24021,0.198270261287689,-0.059013701975346,0.08088480681181,41936,-3397,-1500,-2540,1.11028730869293 +24023,0.200319573283195,-0.074684321880341,0.083507873117924,41936,-3896,-903,-2103,1.11918985843658 +24025,0.192168056964874,-0.086478397250176,0.086941607296467,41936,-2704,-1133,-2484,1.12834000587463 +24027,0.177630245685577,-0.096531078219414,0.087074525654316,41936,-2424,-904,-2045,1.13129019737244 +24029,0.162817418575287,-0.097011394798756,0.087557032704353,41936,-1894,-1745,-2464,1.13065433502197 +24031,0.150985971093178,-0.101660147309303,0.089695289731026,41936,-2264,-1154,-1998,1.1301246881485 +24033,0.137505665421486,-0.1097407117486,0.091014638543129,41936,-1703,-967,-2425,1.1254163980484 +24035,0.113910689949989,-0.114511832594872,0.089662194252014,41936,-888,-877,-1982,1.12119889259338 +24037,0.084593027830124,-0.124141067266464,0.087250538170338,41936,130,-591,-2435,1.11645996570587 +24039,0.057974580675364,-0.132430642843246,0.084789715707302,41936,188,-268,-2022,1.11540985107422 +24041,0.047827713191509,-0.145064204931259,0.083360053598881,41936,-749,-8,-2447,1.11324024200439 +24043,0.037681344896555,-0.153346136212349,0.084994666278362,41936,-689,134,-2004,1.10975956916809 +24045,0.010639938525856,-0.153969511389732,0.086447589099407,41936,969,-665,-2411,1.11092984676361 +24047,-0.028066862374544,-0.146793469786644,0.080439448356629,41936,2416,-1013,-2043,1.11217820644379 +24049,-0.066297665238381,-0.146177992224693,0.067158438265324,41936,2881,-793,-2529,1.11340117454529 +24051,-0.09347378462553,-0.15780483186245,0.056153014302254,41936,2668,585,-2316,1.11235344409943 +24053,-0.109930217266083,-0.161187708377838,0.050309762358666,41936,1983,-214,-2635,1.10959613323212 +24055,-0.121482424438,-0.161987066268921,0.047829579561949,41936,2044,-42,-2405,1.10316503047943 +24057,-0.131028980016708,-0.172459587454796,0.049012124538422,41936,1839,535,-2635,1.09863150119782 +24059,-0.142940208315849,-0.183582782745361,0.048431903123856,41936,2462,1134,-2388,1.09626662731171 +24061,-0.150815144181252,-0.193703383207321,0.045688029378653,41936,2060,905,-2649,1.09537541866303 +24063,-0.157553836703301,-0.19586643576622,0.039978075772524,41936,2390,778,-2480,1.09953939914703 +24065,-0.167022824287415,-0.191995516419411,0.033845108002424,41936,2471,-25,-2723,1.10414969921112 +24067,-0.173693031072617,-0.178886860609055,0.031910210847855,41936,2716,-509,-2569,1.10812640190125 +24069,-0.178919568657875,-0.156782180070877,0.031083226203919,41936,2410,-1749,-2736,1.11127209663391 +24071,-0.178385987877846,-0.144795253872871,0.02620704099536,41936,2346,-908,-2632,1.11509764194489 +24073,-0.176808461546898,-0.138391733169556,0.020217042416334,41936,1966,-818,-2805,1.11771738529205 +24075,-0.184079304337502,-0.126537531614304,0.017648654058576,41936,3069,-1120,-2730,1.12006962299347 +24077,-0.191091030836105,-0.108872182667255,0.020047189667821,41936,2863,-1984,-2803,1.12141871452332 +24079,-0.198478296399116,-0.086424633860588,0.019590899348259,41936,3392,-2467,-2705,1.12528765201569 +24081,-0.20086245238781,-0.075402498245239,0.015523685142398,41936,2756,-1941,-2830,1.12773621082306 +24083,-0.202524274587631,-0.062275037169457,0.014428301714361,41936,3145,-2141,-2764,1.12850272655487 +24085,-0.204396098852158,-0.042725652456284,0.013445592485368,41936,2859,-2983,-2842,1.13409674167633 +24087,-0.202462285757065,-0.027271691709757,0.012934683822095,41936,2986,-2836,-2780,1.14190304279327 +24089,-0.196530416607857,-0.019636068493128,0.01566425524652,41936,2278,-2437,-2824,1.14431846141815 +24091,-0.183053955435753,-0.015709957107902,0.018262784928084,41936,1927,-2174,-2714,1.14349377155304 +24093,-0.168603256344795,-0.010829588398337,0.014911724254489,41936,1349,-2347,-2825,1.14097106456757 +24095,-0.159970030188561,-0.008006012998521,0.014019097201526,41936,1964,-2202,-2761,1.13529348373413 +24097,-0.153581380844116,-0.00833510234952,0.021605445072055,41936,1781,-1994,-2777,1.13422238826752 +24099,-0.145315036177635,-0.005601028911769,0.025816598907113,41936,1825,-2223,-2619,1.13566505908966 +24101,-0.133126363158226,0.00011770297715,0.022882850840688,41936,1136,-2535,-2763,1.13872241973877 +24103,-0.130792379379272,0.009038456715643,0.020390568301082,41936,2080,-2898,-2678,1.14022743701935 +24105,-0.143851920962334,0.014198187738657,0.023350296542049,41936,3158,-2690,-2756,1.14303803443909 +24107,-0.162875428795815,0.014701194129884,0.030587377026677,41936,4184,-2378,-2553,1.14949345588684 +24109,-0.186381936073303,0.028847618028522,0.038288239389658,41936,4589,-3540,-2648,1.15507185459137 +24111,-0.204709574580193,0.048454970121384,0.045592166483402,41936,4889,-4299,-2370,1.1551376581192 +24113,-0.220303803682327,0.078838132321835,0.050282668322325,41936,4601,-5432,-2557,1.15398061275482 +24115,-0.226375117897987,0.097534619271755,0.052577894181013,41936,4461,-5067,-2279,1.15111601352692 +24117,-0.232686042785645,0.109061732888222,0.052911322563887,41936,4215,-4551,-2529,1.1473034620285 +24119,-0.238718152046204,0.121535860002041,0.054820824414492,41936,4765,-5059,-2242,1.15114593505859 +24121,-0.243799492716789,0.135858818888664,0.054531969130039,41936,4395,-5185,-2509,1.16188323497772 +24141,-0.086306065320969,0.235975444316864,0.032337423413992,41936,1412,-7168,-2631,1.20576500892639 +24143,-0.073624268174172,0.254755288362503,0.037024207413197,41936,1216,-8084,-2408,1.21287488937378 +24145,-0.063747189939022,0.262562602758408,0.045772314071655,41936,1176,-6993,-2531,1.21559393405914 +24147,-0.055940214544535,0.271032929420471,0.054573841392994,41936,1299,-7730,-2192,1.21754157543182 +24149,-0.128783658146858,0.325617581605911,0.076393261551857,41936,8062,-11369,-2311,1.3723019361496 +24151,-1.0654171705246,0.58689546585083,0.176721915602684,41936,32767,-31172,-720,1.96111822128296 +24153,-3.67139077186584,0.852392852306366,0.355954170227051,41936,32767,-32767,-357,2.78242087364197 +24155,-5.93662214279175,-0.048533160239458,0.503667533397675,41936,32767,32767,3162,3.67263007164001 +24157,-5.17809295654297,-1.69388699531555,0.596384465694428,41936,24167,32767,1381,4.83791637420654 +24159,-2.09558320045471,-1.42045629024506,0.697916030883789,41936,-32767,828,5300,5.51703023910522 +24161,0.844205617904663,0.253505557775497,0.89375650882721,41936,-32767,-32767,3537,5.20932340621948 +24163,2.23986887931824,1.55124855041504,1.09089946746826,41936,-32767,-32767,10600,4.55004835128784 +24165,2.53628158569336,2.05082631111145,1.16194081306458,41936,-32767,-32767,5577,3.85249900817871 +24167,2.49757313728333,2.05213975906372,1.15724241733551,41936,-32767,-32767,11566,3.18225359916687 +24169,2.31243944168091,1.82599461078644,1.09832906723022,41936,-16966,-14014,5346,2.55738735198975 +24171,2.15667700767517,1.73107075691223,0.998179316520691,41936,-21570,-25705,9761,1.97182309627533 +24173,2.18553566932678,1.80092656612396,0.969092845916748,41936,-31483,-32767,4633,1.59316623210907 +24175,2.20145630836487,1.79544770717621,0.987688302993774,41936,-32767,-32767,9739,1.35955417156219 +24177,2.12081003189087,1.67878937721252,0.94336861371994,41936,-23726,-21387,4628,1.1502331495285 +24179,2.08604454994202,1.63160836696625,0.863549113273621,41936,-30901,-29133,8368,1.05114614963532 +24181,2.10853600502014,1.65815842151642,0.832484304904938,41936,-31894,-32119,4014,1.03161597251892 +24183,2.07137989997864,1.62455582618713,0.826748907566071,41936,-31407,-30765,8016,1.03141045570374 +24185,1.98347735404968,1.54156684875488,0.790387451648712,41936,-23140,-23370,3865,1.03496503829956 +24187,1.92970538139343,1.50700783729553,0.733734309673309,41936,-28834,-29534,7001,1.04966771602631 +24189,1.90078842639923,1.50532186031342,0.698819875717163,41936,-27069,-29397,3358,1.08871603012085 +24191,1.82492387294769,1.45018899440765,0.68911623954773,41936,-26430,-27860,6546,1.10603618621826 +24193,1.70453679561615,1.3442268371582,0.66332745552063,41936,-18550,-20319,3227,1.10350358486176 +24195,1.58627283573151,1.25523281097412,0.609727203845978,41936,-20318,-22931,5701,1.11381030082703 +24197,1.4700129032135,1.19905471801758,0.56541633605957,41936,-16226,-22420,2653,1.11191463470459 +24199,1.33164393901825,1.11769449710846,0.539786636829376,41936,-15423,-21831,4963,1.09593749046326 +24201,1.17142140865326,1.00235402584076,0.507440626621246,41936,-9423,-15918,2342,1.09007334709167 +24203,1.00165176391602,0.902063727378845,0.460303425788879,41936,-8373,-17481,4128,1.09539139270782 +24205,0.83486545085907,0.849822580814362,0.422354966402054,41936,-4606,-18711,1832,1.10107004642487 +24207,0.680087506771088,0.77503913640976,0.399559706449509,41936,-4638,-17672,3497,1.10730624198914 +24209,0.536280035972595,0.671145975589752,0.373268753290176,41936,-2305,-12852,1559,1.11988294124603 +24211,0.40339794754982,0.581891596317291,0.335368514060974,41936,-1992,-13853,2839,1.12759470939636 +24213,0.284612834453583,0.518076777458191,0.302087098360062,41936,-699,-13844,1125,1.12635111808777 +24215,0.170431405305862,0.455066025257111,0.2769915163517,41936,284,-13960,2229,1.12356913089752 +24217,0.028293523937464,0.357872843742371,0.244035199284554,41936,4543,-9413,773,1.12071108818054 +24219,-0.126623019576073,0.255300134420395,0.202267646789551,41936,7986,-8086,1439,1.11392080783844 +24221,-0.277417659759521,0.163477405905724,0.164610981941223,41561,9580,-7176,262,1.10522532463074 +24223,-0.423743695020676,0.079076603055,0.137526318430901,41561,12293,-6638,750,1.0994416475296 +24225,-0.572679340839386,-0.008660890161991,0.111798234283924,41561,13851,-5082,-75,1.0958354473114 +24227,-0.717580199241638,-0.102125152945519,0.078014872968197,41561,17192,-3086,112,1.09962058067322 +24229,-0.853024959564209,-0.174758017063141,0.049795586615801,41561,17211,-3781,-484,1.10862243175507 +24231,-0.978243231773376,-0.257031828165054,0.03633052110672,41561,20373,-1341,-335,1.11611485481262 +24233,-1.08094394207001,-0.35185632109642,0.02569155022502,41561,18561,420,-639,1.11755216121674 +24235,-1.17892825603485,-0.456456422805786,0.007320981007069,41561,22141,3623,-639,1.12443447113037 +24237,-1.26824951171875,-0.565425872802734,-0.017456898465753,41561,20810,4664,-928,1.13096833229065 +24239,-1.34269404411316,-0.659117698669434,-0.035095635801554,41561,23650,6347,-1118,1.13331055641174 +24241,-1.40861833095551,-0.74200040102005,-0.039952583611012,41561,21743,5591,-1082,1.13913881778717 +24243,-1.46428608894348,-0.825189888477325,-0.047881979495287,41561,24888,8587,-1269,1.14263069629669 +24245,-1.50395309925079,-0.916293501853943,-0.058985214680433,41561,21883,9021,-1215,1.14494717121124 +24247,-1.522052526474,-1.01160168647766,-0.068597957491875,41561,23805,12867,-1521,1.14994645118713 +24249,-1.5326179265976,-1.09560990333557,-0.073724955320358,41561,20894,11515,-1322,1.1533842086792 +24251,-1.53510892391205,-1.16863143444061,-0.078084342181683,41561,23596,14292,-1658,1.15736842155457 +24253,-1.52117276191711,-1.23671782016754,-0.079723060131073,41561,19672,12905,-1371,1.15793347358704 +24255,-1.50277745723724,-1.2948694229126,-0.078394129872322,41561,22268,15812,-1699,1.15238201618195 +24257,-1.47939872741699,-1.34108376502991,-0.077545739710331,41561,19083,13404,-1365,1.14813935756683 +24259,-1.44279587268829,-1.37355864048004,-0.077704548835754,41024,20653,15833,-1738,1.1470388174057 +24261,-1.38833463191986,-1.38881170749664,-0.081299252808094,41024,16211,12478,-1401,1.14425706863403 +24263,-1.31978535652161,-1.4023265838623,-0.08453980088234,41024,16983,15549,-1868,1.14307403564453 +24265,-1.24210548400879,-1.4086856842041,-0.083953566849232,41024,13056,12750,-1431,1.14379417896271 +24267,-1.1593189239502,-1.39822542667389,-0.083202511072159,41024,13919,14374,-1899,1.14933943748474 +24269,-1.06482410430908,-1.3793488740921,-0.087004661560059,41024,9842,11145,-1466,1.15756833553314 +24271,-0.960800230503082,-1.35185980796814,-0.090208329260349,41024,9660,13006,-2021,1.16585624217987 +24273,-0.853205025196075,-1.32904267311096,-0.088081225752831,41024,6313,10746,-1488,1.1769642829895 +24297,0.427751958370209,-0.616723656654358,-0.162735387682915,40488,-9473,-2568,-2123,1.15661084651947 +24299,0.493026822805405,-0.517200708389282,-0.162174597382546,40488,-10536,-2321,-2967,1.15184223651886 +24301,0.546852588653564,-0.419343262910843,-0.165946707129478,40488,-9630,-4453,-2171,1.14702141284943 +24303,0.601977109909058,-0.325470387935638,-0.168415039777756,40488,-11818,-4824,-3048,1.14330780506134 +24305,0.656799256801605,-0.249233245849609,-0.169891998171806,40488,-11549,-5190,-2225,1.1401891708374 +24307,0.702513217926025,-0.172582298517227,-0.169341579079628,40488,-13068,-5950,-3073,1.13909733295441 +24309,0.744562566280365,-0.104139618575573,-0.167142882943153,40488,-12212,-6628,-2233,1.13643002510071 +24311,0.775073409080505,-0.03699267655611,-0.162301704287529,40488,-13480,-7417,-3008,1.13194954395294 +24313,0.795937657356262,0.028458388522267,-0.158584162592888,40488,-11784,-8293,-2200,1.12528681755066 +24315,0.807806134223938,0.090546116232872,-0.155311211943626,40488,-13024,-9127,-2947,1.11715972423553 +24317,0.81292724609375,0.148857116699219,-0.150819331407547,40488,-11267,-9543,-2170,1.10918343067169 +24319,0.814704239368439,0.201257362961769,-0.145431697368622,40488,-12784,-10288,-2854,1.1017609834671 +24321,0.808602035045624,0.246606677770615,-0.140220955014229,40488,-10774,-10103,-2119,1.09444749355316 +24323,0.797626256942749,0.292360544204712,-0.138980776071548,40488,-11964,-11398,-2804,1.0905659198761 +24325,0.787680447101593,0.331238150596619,-0.138982862234116,40488,-10567,-10982,-2132,1.08776533603668 +24327,0.774616956710815,0.362116128206253,-0.138431027531624,40488,-11805,-11610,-2824,1.08592212200165 +24329,0.756740272045136,0.390761524438858,-0.135834351181984,40488,-9915,-11264,-2132,1.08629584312439 +24331,0.734897315502167,0.41641840338707,-0.127636402845383,40488,-10884,-12291,-2725,1.08474934101105 +24333,0.703999400138855,0.439880073070526,-0.12438403069973,40488,-8570,-11785,-2073,1.08316171169281 +24335,0.665313541889191,0.461885452270508,-0.12766395509243,40488,-8879,-12963,-2754,1.08033156394959 +24337,0.626525342464447,0.480046540498733,-0.13105396926403,40488,-7208,-12191,-2139,1.07059001922607 +24339,0.585639119148254,0.493351846933365,-0.131491899490356,40488,-7725,-13068,-2827,1.05918574333191 +24341,0.541099727153778,0.49766993522644,-0.12937805056572,40488,-5851,-11678,-2149,1.04745602607727 +24343,0.491739749908447,0.506246209144592,-0.129885837435722,40488,-5854,-13165,-2835,1.03777551651001 +24345,0.438897043466568,0.512292265892029,-0.128640547394753,40488,-4028,-12244,-2165,1.03516328334808 +24347,0.381899982690811,0.51474142074585,-0.125911206007004,40488,-3732,-13100,-2815,1.03687727451324 +24349,0.323821574449539,0.522059440612793,-0.127223804593086,40488,-2191,-12713,-2176,1.03625392913818 +24351,0.276650458574295,0.524251639842987,-0.132485017180443,40488,-2892,-13476,-2917,1.03475821018219 +24353,0.231622248888016,0.514234125614166,-0.137296125292778,40488,-1944,-11603,-2267,1.03322958946228 +24355,0.179436281323433,0.491218060255051,-0.137307107448578,40488,-1084,-11366,-2996,1.0305392742157 +24357,0.123694971203804,0.46592253446579,-0.135850861668587,40488,272,-10045,-2280,1.03001773357391 +24359,0.06416167318821,0.444672733545303,-0.138652294874191,40488,1237,-10960,-3032,1.0313538312912 +24361,0.006261641159654,0.418832838535309,-0.143785700201988,40488,2064,-9540,-2357,1.03116965293884 +24363,-0.054772026836872,0.391037732362747,-0.14856331050396,40488,3258,-9826,-3167,1.02839314937592 +24365,-0.119153223931789,0.3537957072258,-0.151022002100945,40488,4336,-7978,-2431,1.02553451061249 +24367,-0.178688168525696,0.304995179176331,-0.15470527112484,40488,5210,-7082,-3255,1.02322494983673 +24369,-0.231059029698372,0.258496820926666,-0.160453990101814,40488,5149,-6096,-2521,1.01928114891052 +24371,-0.285750150680542,0.203878000378609,-0.166752770543098,40488,6702,-5142,-3412,1.0131049156189 +24373,-0.343096733093262,0.151705920696259,-0.169407188892365,40488,7232,-4257,-2610,1.00905787944794 +24375,-0.396066844463348,0.099385693669319,-0.167687579989433,40488,8500,-3685,-3441,1.01073348522186 +24377,-0.439228683710098,0.038210693746805,-0.165920823812485,40488,7764,-2036,-2613,1.01426982879639 +24379,-0.478154271841049,-0.020406495779753,-0.167954951524735,40488,9001,-1317,-3462,1.01508617401123 +24381,-0.512947618961334,-0.080981388688088,-0.171344488859177,40488,8427,-367,-2677,1.0134608745575 +24383,-0.546808302402496,-0.131779536604881,-0.170049488544464,40488,9973,-43,-3506,1.01299726963043 +24385,-0.570019543170929,-0.183422401547432,-0.163658961653709,40488,8655,515,-2651,1.01606166362762 +24387,-0.58620548248291,-0.233364924788475,-0.15930686891079,40488,9594,1620,-3402,1.0198267698288 +24389,-0.601252734661102,-0.278928875923157,-0.160649850964546,40488,8776,1551,-2655,1.02646994590759 +24391,-0.612072229385376,-0.322283565998077,-0.163933828473091,40488,9901,2717,-3480,1.02717900276184 +24393,-0.614973068237305,-0.357804775238037,-0.169501394033432,40488,8376,2106,-2741,1.0242760181427 +24395,-0.614740192890167,-0.398652166128159,-0.170335114002228,40488,9434,3932,-3583,1.01845300197601 +24397,-0.614262282848358,-0.42743319272995,-0.164178609848022,40488,8401,2800,-2731,1.01047396659851 +24399,-0.604204416275024,-0.450073450803757,-0.157545372843742,40488,8827,3648,-3462,1.01307487487793 +24401,-0.584326565265656,-0.480991929769516,-0.15530002117157,40488,6855,3925,-2695,1.02186572551727 +24403,-0.563045203685761,-0.509313821792603,-0.15716002881527,40488,7618,5228,-3487,1.02997219562531 +24405,-0.542074322700501,-0.531758785247803,-0.157185554504395,40488,6426,4277,-2733,1.03628659248352 +24407,-0.523163795471191,-0.53955864906311,-0.153957977890968,40488,7389,4488,-3479,1.03858375549316 +24409,-0.496959537267685,-0.551682770252228,-0.146786734461784,40488,5643,4070,-2686,1.04005837440491 +24411,-0.468551158905029,-0.561748325824737,-0.142996996641159,40488,6049,5262,-3379,1.03589856624603 +24413,-0.44083559513092,-0.565746366977692,-0.142495959997177,40488,4945,3947,-2679,1.03502523899078 +24415,-0.408089995384216,-0.560873866081238,-0.139411956071854,40488,4950,4434,-3364,1.03483498096466 +24417,-0.36581563949585,-0.54396253824234,-0.136783510446548,40488,3013,2396,-2662,1.03516471385956 +24419,-0.315885484218597,-0.535878539085388,-0.131577253341675,40488,2378,4044,-3297,1.03610503673553 +24421,-0.264862209558487,-0.524930775165558,-0.128487065434456,40488,1082,2798,-2627,1.04062116146088 +24423,-0.218434423208237,-0.517709851264954,-0.129046946763992,40488,1174,4054,-3290,1.0441757440567 +24425,-0.180463582277298,-0.498401880264282,-0.131065294146538,40488,907,2059,-2665,1.0460456609726 +24427,-0.142966791987419,-0.473356813192368,-0.131093293428421,40488,679,2288,-3335,1.05180871486664 +24429,-0.098264507949352,-0.455626666545868,-0.12807896733284,40488,-685,1781,-2666,1.05098617076874 +24431,-0.052516337484121,-0.440060973167419,-0.12852880358696,40488,-1333,2639,-3325,1.04621875286102 +24445,0.277232259511948,-0.224859148263931,-0.120107732713223,40488,-6247,-2591,-2692,1.03016746044159 +24447,0.318693071603775,-0.187932908535004,-0.116439707577229,40488,-7300,-2338,-3250,1.03142178058624 +24449,0.353307694196701,-0.148868396878243,-0.112114638090134,40488,-6744,-3362,-2655,1.02914297580719 +24451,0.377768874168396,-0.110744714736938,-0.111247986555099,40488,-7193,-3595,-3204,1.0269056558609 +24453,0.396436899900436,-0.081859663128853,-0.110200725495815,40488,-6395,-3531,-2660,1.02452600002289 +24455,0.414332002401352,-0.05097895860672,-0.109795100986958,40488,-7488,-4000,-3203,1.02388799190521 +24457,0.439281821250915,-0.023464364930987,-0.111592963337898,40488,-7650,-4235,-2686,1.02184402942657 +24459,0.458796054124832,0.003926155623049,-0.114060558378696,40488,-8525,-4616,-3270,1.01749587059021 +24461,0.46921044588089,0.023796273395419,-0.113708764314651,40488,-7250,-4354,-2719,1.01663541793823 +24463,0.474425762891769,0.044088784605265,-0.106812186539173,40488,-7975,-4761,-3202,1.01144814491272 +24465,0.47454047203064,0.069979630410671,-0.102710753679276,40488,-6810,-5456,-2660,1.00398671627045 +24467,0.471982955932617,0.092430397868157,-0.10478051006794,40488,-7609,-5726,-3196,0.996572494506836 +24469,0.462773859500885,0.112138733267784,-0.106983028352261,40488,-6197,-5650,-2706,0.991536676883698 +24471,0.44578692317009,0.128030940890312,-0.107302062213421,40488,-6373,-5880,-3244,0.99241554737091 +24473,0.42068949341774,0.145318314433098,-0.106884740293026,40488,-4668,-6002,-2722,0.994768321514129 +24475,0.38414141535759,0.163334250450134,-0.10456920415163,40488,-4167,-6677,-3231,0.995402693748474 +24477,0.346974045038223,0.175555437803268,-0.101383194327354,40488,-2932,-6142,-2701,0.998010754585266 +24479,0.313680619001389,0.191549077630043,-0.101590007543564,40488,-3425,-7065,-3215,0.998230695724487 +24481,0.287811905145645,0.196313381195068,-0.104071281850338,40488,-3047,-5987,-2736,0.999811112880707 +24483,0.262722223997116,0.194977775216103,-0.103753373026848,40488,-3329,-5943,-3258,1.00041246414185 +24485,0.232684329152107,0.192464664578438,-0.103754989802837,40488,-2089,-5491,-2750,0.998254418373108 +24487,0.192972049117088,0.189074143767357,-0.106043979525566,40488,-1257,-5768,-3303,0.998020112514496 +24489,0.147070929408073,0.194327607750893,-0.108289822936058,40488,176,-6151,-2798,0.996990323066711 +24491,0.110197149217129,0.187828749418259,-0.111626140773296,40488,-184,-5603,-3387,0.998582661151886 +24493,0.075414374470711,0.177336573600769,-0.117752633988857,40488,348,-4857,-2882,0.9988654255867 +24495,0.03270335495472,0.166429758071899,-0.118110105395317,40488,1451,-5012,-3481,1.00178027153015 +24497,-0.004139366559684,0.153596386313438,-0.116037428379059,40488,1613,-4416,-2889,1.00858926773071 +24499,-0.029825178906322,0.142661347985268,-0.120896443724632,40488,1230,-4686,-3532,1.01065754890442 +24501,-0.060363996773958,0.122332021594048,-0.125819191336632,40488,1972,-3487,-2976,1.00374352931976 +24503,-0.100872665643692,0.103093512356281,-0.125985041260719,40488,3461,-3500,-3609,0.995352864265442 +24505,-0.139005392789841,0.0889792740345,-0.124131433665752,40488,3680,-3494,-2985,0.995699524879456 +24507,-0.165799126029015,0.076951183378697,-0.123822011053562,40488,3587,-3629,-3602,0.996180176734924 +24509,-0.191248148679733,0.065105319023132,-0.126643344759941,40488,3588,-3342,-3022,0.99409294128418 +24511,-0.21988046169281,0.04250680655241,-0.127348870038986,40488,4682,-2344,-3662,0.991708278656006 +24513,-0.250107616186142,0.026574786752462,-0.125156745314598,40488,4868,-2511,-3032,0.991114437580108 +24515,-0.278837949037552,0.004940786398947,-0.122879460453987,40488,5754,-1800,-3628,0.994256675243378 +24517,-0.30748650431633,-0.007870538160205,-0.12507963180542,40488,5700,-2237,-3052,0.995466887950897 +24519,-0.322463721036911,-0.021146465092898,-0.129653826355934,40488,-32767,-1951,-3727,0.996978044509888 +24521,-0.331928431987762,-0.042345624417067,-0.128389969468117,40488,-25631,-1122,-3095,0.992319345474243 +24523,-0.346793979406357,-0.055480148643255,-0.12433448433876,40488,-24459,-1384,-3684,0.983425080776215 +24525,-0.361117005348206,-0.064461290836334,-0.122519366443157,40488,-25011,-1647,-3075,0.983414947986603 +24527,-0.376125872135162,-0.071877725422382,-0.124027863144875,40488,-24114,-1494,-3701,0.989109516143799 +24529,-0.400899589061737,-0.085503570735455,-0.127870976924896,40488,-23824,-971,-3132,0.99908047914505 +24531,-0.433146148920059,-0.106777809560299,-0.132966920733452,40488,-22077,110,-3826,1.00430369377136 +24533,-0.479051768779755,-0.11773406714201,-0.137682318687439,40488,-21295,-644,-3221,1.00319397449493 +24535,-0.540455937385559,-0.134642392396927,-0.143080025911331,40488,-18330,311,-3969,0.998566925525665 +24537,-0.62025785446167,-0.143085792660713,-0.147046238183975,40488,-16896,-391,-3308,0.994619965553284 +24539,-0.702845513820648,-0.151908487081528,-0.147851541638374,40488,-14201,93,-4050,0.993386507034302 +24541,-0.782381653785706,-0.152585059404373,-0.151450514793396,40488,-14569,-732,-3363,0.989570677280426 +24543,-0.871206402778626,-0.14692822098732,-0.156640738248825,40488,-10958,-950,-4181,0.980521321296692 +24545,-0.978030800819397,-0.141148969531059,-0.15703858435154,40488,-9707,-1282,-3427,0.972537994384766 +24547,-1.09568428993225,-0.134515032172203,-0.157548174262047,40488,-5090,-1154,-4220,0.97149246931076 +24549,-1.21637046337128,-0.137916818261147,-0.160148918628693,40488,-5086,-600,-3475,0.979510605335236 +24551,-1.33448278903961,-0.147041350603104,-0.160772860050201,40488,-909,248,-4288,0.984997510910034 +24553,-1.46074986457825,-0.153678372502327,-0.158735632896423,40488,-858,-66,-3492,0.990893661975861 +24555,-1.58911871910095,-0.158890649676323,-0.155163943767548,40488,4342,231,-4254,0.992859363555908 +24557,-1.71965658664703,-0.151676878333092,-0.1521065980196,40488,3607,-1007,-3472,0.9922194480896 +24559,-1.84570479393005,-0.142600804567337,-0.147718384861946,40488,8831,-982,-4194,0.992354750633239 +24561,-1.96861588954926,-0.132775485515594,-0.142260491847992,40488,7198,-1392,-3429,0.992357611656189 +24563,-2.09119462966919,-0.129469603300095,-0.138551667332649,40488,13177,-715,-4113,0.992357611656189 +24565,-2.20653343200684,-0.128331020474434,-0.136651694774628,40488,10751,-766,-3414,0.994251012802124 +24567,-2.31380105018616,-0.122790686786175,-0.133694127202034,40488,13732,-994,-3417,0.988781332969666 +24569,-2.50773119926453,-0.11133074015379,-0.133150160312653,40488,19205,-1469,-4102,0.98192834854126 +24571,-2.58650588989258,-0.102640226483345,-0.133262291550636,40488,15264,-1552,-3437,0.97793847322464 +24573,-2.65553307533264,-0.100463673472404,-0.131655812263489,40488,21010,-919,-4109,0.976313948631287 +24575,-2.65553307533264,-0.100463673472404,-0.131655812263489,40488,21010,-919,-4109,0.976313948631287 +24577,-2.76632237434387,-0.096233725547791,-0.126289516687393,40488,22637,-1095,-4071,0.984179794788361 +24579,-2.80888819694519,-0.091104909777641,-0.127779752016068,40488,17850,-1353,-3444,0.991068840026856 +24581,-2.84556984901428,-0.080779016017914,-0.12832148373127,40488,23799,-1715,-4115,0.996921479701996 +24583,-2.86973643302917,-0.079994156956673,-0.124560289084911,40488,18472,-1155,-3444,1.00148630142212 +24585,-2.86973643302917,-0.079994156956673,-0.124560289084911,40488,18472,-1155,-3444,1.00148630142212 +24587,-2.88335251808167,-0.086948059499264,-0.124703675508499,40488,17892,-742,-3466,1.01512777805328 +24589,-2.86550998687744,-0.084039323031902,-0.125501602888107,40488,22353,-1052,-4133,1.02285957336426 +24591,-2.84255504608154,-0.07245709002018,-0.127596959471703,40488,16885,-1943,-3508,1.02583360671997 +24593,-2.81396889686584,-0.056731931865215,-0.129935279488564,40488,21821,-2383,-4195,1.02860343456268 +24595,-2.81396889686584,-0.056731931865215,-0.129935279488564,40488,21821,-2383,-4195,1.02860343456268 +24597,-2.73342227935791,-0.031401269137859,-0.128812819719315,40488,20138,-1772,-4190,1.03500878810883 +24599,-2.67035222053528,-0.027608789503574,-0.124735005199909,40488,13655,-1976,-3532,1.03518867492676 +24601,-2.60092830657959,-0.02225492335856,-0.119807302951813,40488,17486,-2154,-4099,1.0354859828949 +24603,-2.53013229370117,-0.010838796384633,-0.115231193602085,40488,12077,-2746,-3487,1.03706204891205 +24605,-2.53013229370117,-0.010838796384633,-0.11403963714838,40488,15805,-3259,-4031,1.045290350914 +24607,-2.37540650367737,0.01309559121728,-0.110954485833645,40488,10028,-2916,-3476,1.05458390712738 +24609,-2.2850980758667,0.03005850315094,-0.106789827346802,40488,12689,-3834,-3943,1.06184065341949 +24611,-2.18399930000305,0.036484450101853,-0.102985747158527,40488,6720,-3073,-3438,1.06224989891052 +24613,-2.09184002876282,0.057808965444565,-0.100019499659538,40488,10214,-4614,-3854,1.05738747119904 +24615,-1.99978256225586,0.075504116714001,-0.098478049039841,40488,5492,-4462,-3421,1.05944228172302 +24617,-1.89793264865875,0.087978690862656,-0.096301071345806,40488,7098,-4492,-3796,1.05946552753448 +24619,-1.79324817657471,0.109904013574123,-0.09287578612566,40488,2310,-5294,-3396,1.06550419330597 +24621,-1.68826115131378,0.121598519384861,-0.086740978062153,40488,4116,-5011,-3664,1.06587934494019 +24623,-1.58724272251129,0.131288662552834,-0.082382582128048,40488,212,-4773,-3334,1.06662595272064 +24625,-1.48361587524414,0.129162043333054,-0.080297157168388,40488,1430,-4190,-3587,1.06728303432465 +24627,-1.38577270507813,0.140609979629517,-0.077985353767872,40488,-1946,-5085,-3312,1.06637525558472 +24629,-1.28244924545288,0.140737310051918,-0.068850666284561,40488,-1366,-4585,-3446,1.06384932994843 +24631,-1.18376863002777,0.154032751917839,-0.061022337526083,40488,-4491,-5466,-3202,1.05964481830597 +24633,-1.08082211017609,0.15277723968029,-0.055273607373238,40488,-4249,-4740,-3278,1.05661451816559 +24635,-0.986388206481934,0.148397728800774,-0.049907878041267,40488,-6696,-4182,-3130,1.05250489711761 +24637,-0.896433711051941,0.150111392140389,-0.046348333358765,40488,-6032,-4978,-3177,1.05540561676025 +24639,-0.807587146759033,0.146629422903061,-0.04519509896636,40488,-8620,-4283,-3099,1.05140328407288 +24641,-0.725218176841736,0.1484185308218,-0.045320443809033,40488,-8072,-5024,-3167,1.04448199272156 +24643,-0.649610638618469,0.142002284526825,-0.043272752314806,40488,-9776,-4069,-3088,1.03967237472534 +24645,-0.578911900520325,0.136468201875687,-0.042028367519379,40488,-9491,-4364,-3141,1.03703725337982 +24647,-0.514050304889679,0.119907446205616,-0.04225867241621,40488,-10855,-3083,-3083,1.03921246528625 +24649,-0.458564072847366,0.111459121108055,-0.04484236985445,40488,-10288,-3804,-3200,1.04071199893951 +24651,-0.399889349937439,0.10195255279541,-0.04614969715476,40488,-12008,-3378,-3113,1.04607331752777 +24653,-0.349463731050491,0.095626942813397,-0.047299735248089,40488,-11676,-3740,-3248,1.0460889339447 +24655,-0.313243746757507,0.093370273709297,-0.046772714704275,40488,-11650,-3814,-3121,1.04655623435974 +24657,-0.289445668458939,0.082621887326241,-0.046524707227945,40488,-10757,-3243,-3256,1.03906679153442 +24659,-0.280248671770096,0.076184213161469,-0.046569146215916,40488,-10220,-3301,-3124,1.0307457447052 +24661,-0.274456948041916,0.065997794270516,-0.044826056808233,40488,-9751,-3038,-3258,1.02268481254578 +24663,-0.273184925317764,0.066340573132038,-0.04387916252017,40488,-9794,-3671,-3110,1.01481795310974 +24665,-0.270479947328567,0.05471907928586,-0.042295020073652,40488,-9635,-2775,-3244,1.00974404811859 +24667,-0.272860109806061,0.047743201255798,-0.042244974523783,40488,26481,-2900,-3104,1.00663077831268 +24669,-0.284087002277374,0.044041801244021,-0.043201070278883,40488,-2345,-3180,-3271,1.01200973987579 +24671,-0.29895094037056,0.033748507499695,-0.044933833181858,40488,-2221,-2475,-3127,1.01754772663116 +24673,-0.322634547948837,0.032632075250149,-0.045818690210581,40488,-777,-3188,-3319,1.01555478572845 +24675,-0.34967777132988,0.030740488320589,-0.045554060488939,40488,-571,-3042,-3138,1.01030111312866 +24677,-0.375046074390411,0.031802169978619,-0.049495205283165,40488,247,-3340,-3369,1.00689446926117 +24679,-0.391753524541855,0.018824558705092,-0.050751872360706,40488,-635,-2085,-3180,1.0028064250946 +24681,-0.404679954051971,0.006165018770844,-0.049245160073042,40488,-90,-1962,-3399,0.995947897434235 +24683,-0.414710313081741,-0.000704311998561,-0.047143790870905,40488,-698,-2242,-3163,0.992398023605347 +24685,-0.425645291805267,-0.00588269950822,-0.043140199035406,40488,185,-2316,-3347,0.990782499313354 +24687,-0.439179122447968,-0.01317762862891,-0.039291750639677,40488,-1,-2030,-3116,0.991538763046265 +24689,-0.447083950042725,-0.029552368447185,-0.038952868431807,40488,408,-1127,-3330,0.996654272079468 +24691,-0.45040887594223,-0.036929298192263,-0.040561523288488,40488,-467,-1671,-3132,1.00236546993256 +24693,-0.451746642589569,-0.042842764407396,-0.044566288590431,40488,121,-1640,-3418,1.00968980789185 +24695,-0.453037053346634,-0.049994312226772,-0.04761965572834,40488,-468,-1479,-3189,1.01061415672302 +24697,-0.461516052484512,-0.052576206624508,-0.047273360192776,40488,897,-1693,-3469,1.00790750980377 +24699,-0.469481825828552,-0.05256213247776,-0.045686669647694,40488,358,-1931,-3185,1.00908029079437 +24701,-0.475621312856674,-0.050122924149037,-0.043837860226631,40488,1083,-2055,-3435,1.01416981220245 +24703,-0.477731347084045,-0.061489310115576,-0.039020411670208,40488,178,-960,-3148,1.01841390132904 +24705,-0.483153909444809,-0.06556198745966,-0.034337170422077,40488,32767,-1301,-3350,1.01604020595551 +24707,-0.487389296293259,-0.069908417761326,-0.031509451568127,40488,6689,-1308,-3104,1.01407790184021 +24709,-0.490982353687286,-0.075858570635319,-0.033022310584784,40488,7558,-954,-3354,1.01277029514313 +24711,-0.497838348150253,-0.074894391000271,-0.035415932536125,40488,7223,-1575,-3138,1.01596248149872 +24713,-0.50061959028244,-0.082908853888512,-0.037628926336765,40488,7853,-638,-3424,1.01753997802734 +24715,-0.495419293642044,-0.085133887827396,-0.041231852024794,40488,6527,-1154,-3187,1.01492345333099 +24717,-0.476812422275543,-0.082034096121788,-0.042671021074057,40488,6123,-1406,-3492,1.00734996795654 +24719,-0.452265709638596,-0.063738331198692,-0.041897084563971,40488,4713,-2885,-3202,0.999269962310791 +24721,-0.427095741033554,-0.054162703454495,-0.040765058249235,40488,5014,-2292,-3448,1.0030837059021 +24723,-0.398181408643723,-0.055942550301552,-0.041033379733563,40488,3791,-1528,-3204,1.00931906700134 +24725,-0.370484083890915,-0.051544211804867,-0.043254800140858,40488,4062,-1951,-3483,1.01444053649902 +24727,-0.341522246599197,-0.048960044980049,-0.044050831347704,40488,3115,-1913,-3234,1.0203138589859 +24729,-0.309071868658066,-0.035279363393784,-0.046004824340344,40488,2847,-2863,-3505,1.02329015731812 +24731,-0.268907606601715,-0.031466312706471,-0.048915144056082,40488,1383,-2233,-3276,1.02696001529694 +24733,-0.232372865080833,-0.022029673680663,-0.048404432833195,40488,1402,-2754,-3527,1.02419638633728 +24735,-0.197064384818077,-0.017824402078986,-0.043959464877844,40488,778,-2443,-3250,1.02724158763886 +24737,-0.163167282938957,-0.01976528391242,-0.036800365895033,40488,525,-1955,-3397,1.02825474739075 +24753,0.1479681879282,0.036160185933113,-0.037664730101824,40488,962,-3851,-3366,1.01979994773865 +24755,0.189344748854637,0.038291867822409,-0.036856986582279,40488,905,-3087,-3228,1.02187693119049 +24757,0.231543734669685,0.046320427209139,-0.033377144485712,40488,-431,-3742,-3309,1.02236139774323 +24759,0.288001954555511,0.041347738355398,-0.032018687576056,40488,-1668,-2638,-3198,1.02086091041565 +24761,0.33944046497345,0.048121698200703,-0.033705446869135,40488,-2944,-3699,-3315,1.02049469947815 +24763,0.38499841094017,0.049772944301367,-0.031212156638503,40488,-2408,-3251,-3196,1.01619160175323 +24765,0.43097186088562,0.047448545694351,-0.030091363936663,40488,-4184,-3048,-3278,1.00999999046326 +24767,0.478185892105103,0.050081063061953,-0.031599394977093,40488,-4035,-3342,-3202,1.0016360282898 +24769,0.51979398727417,0.052908662706614,-0.034800916910172,40488,-5501,-3521,-3331,0.997000217437744 +24771,0.56173574924469,0.065634824335575,-0.038996361196041,40488,-5069,-4308,-3256,0.99919980764389 +24773,0.600834906101227,0.073026709258556,-0.041307352483273,40488,-6862,-4198,-3390,1.00471162796021 +24775,0.631054997444153,0.075480476021767,-0.04248421266675,40488,-5476,-3741,-3284,1.01094818115234 +24777,0.661536276340485,0.073124222457409,-0.041328683495522,40488,-7493,-3523,-3395,1.01790249347687 +24779,0.693626880645752,0.072827391326428,-0.041205506771803,40488,-6789,-3534,-3280,1.01679456233978 +24781,0.721028685569763,0.076643824577332,-0.037256795912981,40488,27519,-4045,-3349,1.01480007171631 +24783,0.742589235305786,0.0762629956007,-0.033018130809069,40488,-959,-3605,-3226,1.01148653030396 +24785,0.761602997779846,0.082621857523918,-0.033519834280014,40488,-2804,-4350,-3303,1.00944602489471 +24787,0.775099158287048,0.076519519090653,-0.035351101309061,40488,-1121,-3230,-3245,1.00867068767548 +24789,0.775527775287628,0.075301587581635,-0.038677170872688,40488,-1981,-3731,-3376,1.00906467437744 +24791,0.78606915473938,0.064803086221218,-0.043454561382532,40488,-1351,-2776,-3304,1.00831151008606 +24793,0.808946371078491,0.056812811642885,-0.046148844063282,40488,-4422,-2990,-3488,1.00433599948883 +24795,0.826088786125183,0.059346172958613,-0.045183822512627,40488,-2699,-3656,-3322,1.01126194000244 +24797,0.841858685016632,0.057360198348761,-0.043557830154896,40488,-4756,-3449,-3463,1.02010464668274 +24799,0.853839218616486,0.058412987738848,-0.043865084648132,40488,-3047,-3561,-3318,1.01826322078705 +24801,0.865689814090729,0.052639927715063,-0.041580520570278,40488,-5182,-3117,-3451,1.01136493682861 +24803,0.869184911251068,0.058010797947645,-0.037123329937458,40488,-2991,-3886,-3276,1.00715386867523 +24805,0.880000829696655,0.043850805610418,-0.034414440393448,40488,-5673,-2374,-3382,1.00561606884003 +24807,0.89447546005249,0.025153543800116,-0.03536469116807,40488,-4482,-1705,-3269,1.00223565101624 +24809,0.908673882484436,0.01092123799026,-0.036878820508719,40488,-6720,-1844,-3447,0.998627841472626 +24811,0.917036116123199,0.008185621351004,-0.036949917674065,40488,-4724,-2604,-3285,0.997108221054077 +24813,0.914230942726135,0.022870572283864,-0.034645646810532,40488,-5944,-4113,-3416,1.00111258029938 +24815,0.907188177108765,0.019850987941027,-0.034122928977013,40488,-3839,-2756,-3271,1.00461542606354 +24817,0.89745157957077,0.01860467530787,-0.036434859037399,40488,-5529,-2902,-3446,1.0067549943924 +24819,0.886191427707672,0.013029493391514,-0.034813798964024,40488,-3591,-2478,-3281,1.01026856899261 +24821,0.872528553009033,0.009443496353924,-0.035292260348797,40488,-5191,-2590,-3447,1.00578832626343 +24823,0.860756933689117,0.005432382691652,-0.038904163986445,40488,-3536,-2480,-3314,1.00159728527069 +24825,0.851739764213562,-0.003181269159541,-0.042962778359652,40488,-5534,-2026,-3554,1.00126469135284 +24827,0.838736236095428,-0.006234616972506,-0.043544597923756,40488,-3472,-2375,-3353,1.00093483924866 +24829,0.823642671108246,-0.018608324229717,-0.041265834122896,40488,-4977,-1501,-3554,1.00117957592011 +24831,0.804188370704651,-0.027124239131808,-0.042376279830933,40488,-2845,-1672,-3353,0.998115479946136 +24833,0.782561719417572,-0.03254771232605,-0.04398875311017,40488,-4163,-1763,-3604,0.999797463417053 +24835,0.761939823627472,-0.035456422716379,-0.042504008859396,40488,-2469,-1937,-3362,1.00263214111328 +24837,0.739548087120056,-0.028979301452637,-0.040351681411266,40488,-3708,-2645,-3566,1.00578260421753 +24839,0.715219974517822,-0.034936185926199,-0.04248633235693,40488,-1829,-1707,-3369,1.00652635097504 +24841,0.689396500587463,-0.040840346366167,-0.045876067131758,40488,-2924,-1535,-3648,1.00248420238495 +24843,0.665283143520355,-0.055618949234486,-0.047137070447207,40488,-1401,-753,-3410,0.999175488948822 +24845,0.634233236312866,-0.049865789711475,-0.047280553728342,40488,-1907,-2196,-3680,0.996976613998413 +24847,0.60451078414917,-0.03665266558528,-0.045217521488667,40488,-377,-3001,-3406,0.994900166988373 +24849,0.580976366996765,-0.03816644474864,-0.043057586997748,40488,-1819,-1842,-3630,0.996853351593018 +24851,0.558621406555176,-0.049608774483204,-0.04217953979969,40488,-473,-1025,-3393,0.997135996818542 +24853,0.53351753950119,-0.062859602272511,-0.039581257849932,40488,-1147,-581,-3615,0.998376727104187 +24855,0.506526529788971,-0.060181081295014,-0.039271578192711,40488,32767,-1851,-3381,0.997130692005158 +24857,0.483264267444611,-0.044872112572193,-0.041139774024487,40488,5426,-2883,-3628,0.999371290206909 +24859,0.465609550476074,-0.034944925457239,-0.041112281382084,40488,6253,-2706,-3402,1.00420033931732 +24861,0.443898797035217,-0.026358909904957,-0.038247082382441,40488,5837,-2671,-3587,1.00767707824707 +24863,0.422799289226532,-0.029191778972745,-0.037113711237908,40488,7005,-1855,-3381,1.00890266895294 +24865,0.403836250305176,-0.023760346695781,-0.041158370673657,40488,6190,-2483,-3627,1.01292061805725 +24867,0.397631764411926,-0.026071920990944,-0.04596833884716,40488,6207,-1921,-3450,1.01587295532227 +24869,0.39676558971405,-0.017514349892736,-0.049015317112208,40488,4918,-2809,-3722,1.01753127574921 +24871,0.404056131839752,-0.011717842891812,-0.049305036664009,40488,5058,-2697,-3481,1.01895999908447 +24873,0.42096471786499,-0.007110863924026,-0.049090962857008,40488,3165,-2683,-3725,1.01866567134857 +24875,0.438323944807053,0.006658476311713,-0.049306239932776,40488,3744,-3526,-3490,1.01303648948669 +24877,0.453218817710876,0.015754740685225,-0.050767704844475,40488,2680,-3368,-3737,1.0085357427597 +24879,0.468446463346481,0.023482264950872,-0.054134860634804,40488,3348,-3337,-3531,1.00377762317657 +24881,0.49778026342392,0.026224531233311,-0.051625732332468,40488,788,-3082,-3748,1.00656020641327 +24883,0.535930752754211,0.035817790776491,-0.047672260552645,40488,597,-3655,-3495,1.00721371173859 +24885,0.563441038131714,0.055549833923578,-0.046255923807621,40488,-305,-4789,-3674,1.00872313976288 +24901,0.782297968864441,0.098577290773392,-0.0394491776824,40488,-4616,-4644,-3593,1.00879740715027 +24903,0.811812341213226,0.102438971400261,-0.040964838117361,40488,-3872,-4367,-3475,1.01247251033783 +24905,0.837476909160614,0.098989680409432,-0.039684113115072,40488,-5803,-4009,-3602,1.01575350761414 +24907,0.85516893863678,0.113039568066597,-0.038852315396071,40488,-3956,-5291,-3465,1.01544916629791 +24909,0.873658776283264,0.121606819331646,-0.038374669849873,40488,-6193,-5278,-3581,1.01635122299194 +24911,0.893031477928162,0.121144071221352,-0.039958383888006,40488,-4947,-4419,-3477,1.01163041591644 +24913,0.913010358810425,0.113914050161839,-0.041653089225292,40488,-7275,-4072,-3631,1.01118719577789 +24915,0.92750895023346,0.101184450089931,-0.039555076509714,40488,-5441,-3302,-3479,1.00796806812286 +24917,0.939867436885834,0.095848612487316,-0.03792641684413,40488,-7519,-3959,-3604,1.00728404521942 +24919,0.955663919448852,0.081523105502129,-0.034223910421133,40488,-6301,-2946,-3447,1.0106303691864 +24921,0.96365624666214,0.080232113599777,-0.033258136361837,40488,-7947,-4026,-3563,1.01289343833923 +24923,0.963513016700745,0.081900909543038,-0.037419725209475,40488,-5647,-4129,-3474,1.01437032222748 +24925,0.958306431770325,0.089023351669312,-0.043356593698263,40488,-7273,-4803,-3685,1.00978100299835 +24927,0.953008651733398,0.087508007884026,-0.044311188161373,40488,-5500,-4018,-3527,1.00592029094696 +24929,0.946697652339935,0.073634617030621,-0.045555215328932,40488,-7376,-3083,-3726,1.00113749504089 +24931,0.936993300914764,0.058352015912533,-0.055172376334667,40488,-5325,-2643,-3608,0.992965638637543 +24933,0.925584316253662,0.048317015171051,-0.064987637102604,40488,-7040,-2977,-3976,0.986812114715576 +24935,0.907717883586884,0.051742646843195,-0.063971616327763,40488,-4685,-3908,-3679,0.981168687343597 +24937,0.883829057216644,0.042526967823505,-0.055514678359032,40488,-5826,-2965,-3878,0.975833237171173 +24939,0.857025146484375,0.027408702298999,-0.052404031157494,40488,-3666,-2248,-3609,0.967055022716522 +24941,0.830222964286804,0.021148767322302,-0.052498385310173,40488,-5088,-2849,-3861,0.971864402294159 +24943,0.814244210720062,0.013703294098377,-0.054988790303469,40488,-4156,-2610,-3635,0.980421125888824 +24945,0.792847096920013,0.00933054368943,-0.056578684598208,40488,-5183,-2802,-3923,0.990048885345459 +24947,0.762440979480743,-0.000195888234884,-0.054828256368637,40488,-2691,-2266,-3644,0.996988594532013 +24949,0.728921294212341,0.000134133981192,-0.05567366629839,40488,-3566,-2993,-3926,0.999721050262451 +24951,0.703996896743774,-0.004798585083336,-0.056466031819582,40488,-2529,-2529,-3665,1.00320017337799 +24953,0.678813874721527,-0.009543867781758,-0.054865408688784,40488,-3633,-2469,-3930,1.00374674797058 +24955,0.64693820476532,-0.016394641250372,-0.055646721273661,40488,-1476,-2220,-3669,1.00388133525848 +24957,0.614135980606079,-0.026612550020218,-0.057082574814558,40488,-2286,-1793,-3972,1.00125157833099 +24959,0.581600308418274,-0.030709572136402,-0.0561553388834,40488,-728,-2200,-3682,0.996796548366547 +24961,0.551115036010742,-0.04028981551528,-0.054142590612173,40488,-1640,-1601,-3952,0.992492914199829 +24963,0.518009543418884,-0.047405850142241,-0.054035287350416,40488,16,-1726,-3678,0.987954676151276 +24965,0.480817794799805,-0.051987115293741,-0.055013455450535,40488,-201,-1735,-3975,0.98861175775528 +24967,0.448521584272385,-0.05982282012701,-0.054678305983543,40488,780,-1470,-3692,0.988170385360718 +24969,0.415457367897034,-0.060904070734978,-0.053564220666885,40488,408,-1810,-3971,0.984372079372406 +24971,0.382528305053711,-0.063063956797123,-0.05349450930953,40488,1626,-1799,-3694,0.984082400798798 +24973,0.349694699048996,-0.06165911257267,-0.052429083734751,40488,1319,-1944,-3967,0.980248391628265 +24975,0.323385715484619,-0.073606088757515,-0.051823407411575,40488,1882,-915,-3692,0.982472002506256 +24977,0.300683945417404,-0.085301958024502,-0.054239731281996,40488,1279,-588,-4005,0.985471844673157 +24979,0.280665695667267,-0.082135409116745,-0.052781518548727,40488,1947,-1833,-3709,0.987335979938507 +24981,0.260890156030655,-0.077353596687317,-0.050747383385897,40488,1626,-1860,-3971,0.988739550113678 +24983,0.244086965918541,-0.071371413767338,-0.053503081202507,40488,2162,-2151,-3724,0.994103491306305 +24985,0.230860844254494,-0.070258148014546,-0.054535117000342,40488,1571,-1681,-4023,1.00169849395752 +24987,0.217338189482689,-0.0682093501091,-0.054175492376089,40488,2243,-1881,-3739,1.01004672050476 +24989,0.208371311426163,-0.074846014380455,-0.053811617195606,40488,1569,-1014,-4026,1.01224005222321 +24991,0.202799454331398,-0.077236741781235,-0.051411438733339,40488,1825,-1396,-3730,1.00952577590942 +24993,0.190996825695038,-0.067189209163189,-0.047730725258589,40488,2007,-2296,-3962,1.0044881105423 +24995,0.182062268257141,-0.061306156218052,-0.041746824979782,40488,2314,-2184,-3673,1.00100123882294 +24997,0.176974564790726,-0.050993748009205,-0.041528355330229,40488,1707,-2545,-3892,0.9974325299263 +24999,0.182889550924301,-0.052278637886047,-0.043674662709236,40488,1195,-1772,-3694,0.997694909572601 +25001,0.191233083605766,-0.054420784115791,-0.046503383666277,40488,468,-1574,-3960,0.997291088104248 +25003,0.188016012310982,-0.050170317292214,-0.046018745750189,40488,1725,-2171,-3719,0.998043775558472 +25005,0.18621800839901,-0.043687846511602,-0.043679110705853,40488,1228,-2341,-3932,0.995167136192322 +25007,0.192961022257805,-0.032083727419376,-0.039701208472252,40488,892,-2934,-3683,0.9974045753479 +25009,0.207156181335449,-0.031528484076262,-0.035118766129017,40488,-308,-2088,-3835,0.998969256877899 +25011,0.216968193650246,-0.025156352669001,-0.034006014466286,40488,269,-2640,-3651,0.999729096889496 +25013,0.224744915962219,-0.031028484925628,-0.034683506935835,40488,-195,-1613,-3836,0.997751414775848 +25015,0.234548255801201,-0.029891634359956,-0.036344915628433,40488,-49,-2179,-3673,0.991931915283203 +25017,0.246953621506691,-0.017495857551694,-0.03943620249629,40488,-961,-3129,-3895,0.993080615997314 +25019,0.260635823011398,-0.011213984340429,-0.039513450115919,40488,-779,-2803,-3702,1.00042450428009 +25021,0.269937515258789,-0.006006049457937,-0.039157878607512,40488,-1198,-2792,-3896,1.00691390037537 +25023,0.288281172513962,-0.008973111398518,-0.037855390459299,40488,-1600,-2165,-3698,1.0128173828125 +25025,0.305014729499817,0.001098700915463,-0.038993012160063,40488,-2395,-3248,-3899,1.01531219482422 +25027,0.316224932670593,0.00485172867775,-0.038646187633276,40488,-1597,-2840,-3710,1.01706075668335 +25029,0.335340917110443,1.58612474479014E-05,-0.038949560374022,40488,-3168,-2157,-3906,1.01166307926178 +25031,0.349509030580521,0.001979713328183,-0.039407003670931,40488,-2407,-2666,-3723,1.01527237892151 +25033,0.358586668968201,0.005897995084524,-0.040230538696051,40488,-2963,-2873,-3927,1.01812100410461 +25051,0.438214838504791,0.030006965622306,-0.042100466787815,40184,-3534,-28926,-3777,1.01206648349762 +25053,0.440579324960709,0.018586799502373,-0.043602861464024,40184,-4605,-28648,-4001,1.00068926811218 +25055,0.44480311870575,0.00022665160941,-0.04213197901845,40184,-4029,-27982,-3785,0.997402667999268 +25057,0.450066804885864,-0.028105568140745,-0.046109106391668,40184,-5150,-26931,-4047,0.991702795028686 +25059,0.455870270729065,-0.053208351135254,-0.050911422818899,40184,-4483,-26975,-3854,0.987531781196594 +25061,0.460641235113144,-0.089568458497524,-0.052001982927322,40184,-5466,-25588,-4137,0.990280985832214 +25063,0.459288060665131,-0.135258629918098,-0.054549481719732,40184,-4208,-24537,-3889,0.998203217983246 +25065,0.457620978355408,-0.205019220709801,-0.057182312011719,40184,-5133,-21506,-4227,1.0096390247345 +25067,0.456354916095734,-0.282404989004135,-0.061753783375025,40184,-4358,-20315,-3950,1.01285970211029 +25069,0.459629446268082,-0.374634802341461,-0.062356397509575,40184,-5712,-17265,-4325,1.01477193832397 +25071,0.465237617492676,-0.472421199083328,-0.060185346752405,40184,-5168,-16208,-3952,1.01237690448761 +25073,0.460219711065292,-0.561064183712006,-0.062636911869049,40184,-5326,-14538,-4366,1.01318252086639 +25075,0.457871854305267,-0.663580417633057,-0.06723265349865,40184,-4685,-13121,-4015,1.00534093379974 +25077,0.456258624792099,-0.772544205188751,-0.070479810237885,40184,-5695,-9596,-4497,0.99653559923172 +25079,0.455899238586426,-0.899195313453674,-0.071226492524147,40184,-4991,-7907,-4058,0.986520171165466 +25081,0.442371755838394,-1.01540315151215,-0.066258944571018,40184,-4798,-4976,-4488,0.98320472240448 +25083,0.432376146316528,-1.14200675487518,-0.060623556375504,40184,-4149,-4208,-4002,0.983627438545227 +25085,0.425693720579147,-1.25390625,-0.055732842534781,40184,-5198,-1139,-4400,0.985288441181183 +25087,0.424062579870224,-1.37035310268402,-0.051971446722746,40184,-4808,-1328,-3957,0.993350744247436 +25089,0.417739927768707,-1.49714863300324,-0.051437769085169,40184,-5275,4265,-4382,0.998328566551208 +25091,0.398751050233841,-1.61759781837463,-0.050964597612619,40184,-3379,2953,-3966,1.01106595993042 +25093,0.379231572151184,-1.73677289485931,-0.050986662507057,40184,-3872,8108,-4405,1.0144077539444 +25095,0.36963626742363,-1.84245419502258,-0.052510004490614,40184,-3794,5684,-3992,1.01249325275421 +25097,0.362519472837448,-1.9420428276062,-0.051439419388771,40184,-4654,10640,-4432,1.0068416595459 +25099,0.35312956571579,-2.03117060661316,-0.054085444658995,40184,-3728,7867,-4018,1.00178861618042 +25101,0.356328845024109,-2.13132381439209,-0.059209238737822,40184,-5455,14450,-4541,0.998855710029602 +25103,0.350739151239395,-2.21023988723755,-0.064377523958683,40184,-4121,10457,-4106,0.993192791938782 +25105,0.340913385152817,-2.28785729408264,-0.06597501039505,40184,-4419,16163,-4636,0.991544723510742 +25107,0.328256160020828,-2.34614372253418,-0.065878234803677,40184,-3440,11759,-4135,0.989434838294983 +25109,0.328103542327881,-2.40202832221985,-0.065280467271805,40184,-5033,17311,-4641,0.992992222309112 +25111,0.322461545467377,-2.45059490203857,-0.064626783132553,40184,-4000,13451,-4144,0.999831676483154 +25113,0.310129195451736,-2.48772358894348,-0.068397462368012,40184,-3987,18262,-4690,1.00758576393127 +25115,0.298380047082901,-2.51533603668213,-0.073465801775456,40184,-3348,13814,-4223,1.01185858249664 +25117,0.293888658285141,-2.52864956855774,-0.076404176652432,40184,-4407,18166,-4792,1.01665437221527 +25119,0.294156074523926,-2.54677534103394,-0.077534012496471,40184,-4271,32767,-4270,1.02196252346039 +25121,0.296489924192429,-2.55777359008789,-0.077036641538143,40184,-5059,24676,-4807,1.02127408981323 +25123,0.286194920539856,-2.54680132865906,-0.078040741384029,40184,-3525,18707,-4293,1.02015221118927 +25125,0.271917223930359,-2.5304651260376,-0.07591737061739,40184,-3594,23298,-4796,1.01942563056946 +25127,0.264754235744476,-2.49393272399902,-0.072371833026409,40184,-3557,17145,-4272,1.02461206912994 +25129,0.26762330532074,-2.45424246788025,-0.07107774168253,40184,-4880,21389,-4736,1.02828323841095 +25131,0.267720431089401,-2.40191221237183,-0.072498999536038,40184,-4236,15691,-4290,1.02919721603394 +25133,0.255213230848312,-2.33837604522705,-0.071560144424439,40184,-3688,18766,-4742,1.03320229053497 +25135,0.242736741900444,-2.2609760761261,-0.069857060909271,40184,-3087,12824,-4288,1.03383505344391 +25137,0.238684266805649,-2.17562389373779,-0.069099493324757,40184,-4127,15471,-4713,1.03440833091736 +25139,0.241785332560539,-2.09235119819641,-0.069170780479908,40184,-4293,10866,-4299,1.03536701202393 +25141,0.237002685666084,-1.99579763412476,-0.066550299525261,40184,-4138,12586,-4686,1.03159558773041 +25143,0.225958794355392,-1.8867404460907,-0.06432493776083,40184,-3153,6873,-4280,1.02840137481689 +25145,0.210215181112289,-1.76090979576111,-0.064894884824753,40184,-3013,7424,-4665,1.02606308460236 +25147,0.196942359209061,-1.63724660873413,-0.063768185675144,40184,-2667,2948,-4290,1.02338230609894 +25149,0.181847959756851,-1.51773011684418,-0.062788851559162,40184,-2692,4570,-4638,1.02197217941284 +25151,0.172845467925072,-1.40110862255096,-0.058922436088324,40184,-2705,658,-4270,1.02284598350525 +25153,0.159285753965378,-1.28189337253571,-0.055253054946661,40184,-2514,1295,-4549,1.02655160427094 +25155,0.147040292620659,-1.16303050518036,-0.049716155976057,40184,-2172,-2430,-4218,1.03213882446289 +25157,0.133409574627876,-1.03514635562897,-0.043225288391113,40184,-2150,28278,-4411,1.03420925140381 +25159,0.117196291685104,-0.91155195236206,-0.039340857416391,40184,-1518,-734,-4155,1.03371846675873 +25161,0.107559263706207,-0.790207147598267,-0.031873662024736,40184,-2072,-801,-4278,1.03356111049652 +25163,0.09569589048624,-0.667798697948456,-0.023744197562337,40184,-1567,-3829,-4055,1.0296368598938 +25165,0.078027479350567,-0.551250755786896,-0.021219179034233,40184,-1062,-4067,-4152,1.03215706348419 +25167,0.058850787580013,-0.430897951126099,-0.02554096467793,40184,-549,-6870,-4072,1.03381645679474 +25169,0.04186237975955,-0.313557475805283,-0.027499232441187,40184,-542,-7836,-4229,1.03736925125122 +25171,0.029144397005439,-0.20186011493206,-0.024691650643945,40184,-602,-9435,-4072,1.04031789302826 +25173,0.015041925944388,-0.08826045691967,-0.019659535959363,40184,-327,-11182,-4138,1.04133224487305 +25175,0.001819119905122,0.01675028167665,-0.013627473264933,40184,-178,-12096,-4000,1.04431068897247 +25177,-0.007701435592026,0.116012863814831,-0.010477792471647,40184,-302,-13516,-4023,1.04438805580139 +25179,-0.018003368750215,0.212118744850159,-0.01088731829077,40184,-100,-14358,-3983,1.04522621631622 +25181,-0.034417185932398,0.300639122724533,-0.013918938115239,40184,628,-15880,-4061,1.04262089729309 +25183,-0.054383371025324,0.380212873220444,-0.018896060064435,40184,1128,-15768,-4040,1.04004979133606 +25185,-0.073122471570969,0.450249075889587,-0.02213797532022,40184,1455,-17198,-4160,1.03782415390015 +25201,-0.148979440331459,0.726323664188385,-0.021459795534611,40184,2252,-13169,-4159,1.00309658050537 +25203,-0.156650766730309,0.729263961315155,-0.022198304533959,40184,2003,-11599,-4080,1.00376057624817 +25205,-0.156024634838104,0.728356122970581,-0.027046237140894,40184,1746,-12958,-4230,1.00756061077118 +25207,-0.154374822974205,0.72766375541687,-0.028185723349452,40184,1381,-11650,-4125,1.01084971427917 +25209,-0.156293526291847,0.732958674430847,-0.029992388561368,40184,2025,-13810,-4272,1.01132142543793 +25211,-0.156341508030891,0.732676863670349,-0.03133399784565,40184,1612,-12089,-4152,1.01222229003906 +25213,-0.157053396105766,0.728010356426239,-0.030705662444234,40184,2030,-13344,-4282,1.01210045814514 +25215,-0.154023200273514,0.70901894569397,-0.027964808046818,40184,1440,-10747,-4133,1.00976276397705 +25217,-0.150817856192589,0.697304308414459,-0.025740927085281,40184,1710,-12680,-4220,1.000821352005 +25219,-0.144797697663307,0.674749493598938,-0.023785816505551,40184,1169,-10326,-4108,0.996101438999176 +25221,-0.134676590561867,0.635345160961151,-0.024856254458428,40184,1007,-10014,-4208,0.99384343624115 +25223,-0.123314209282398,0.5977703332901,-0.02861444093287,40184,544,-8448,-4145,0.995083928108215 +25225,-0.115744695067406,0.558385789394379,-0.030873764306307,40184,952,-9049,-4287,0.999665260314941 +25227,-0.112555854022503,0.528696835041046,-0.030076142400503,40184,1034,-8290,-4159,1.00425863265991 +25229,-0.101222738623619,0.486848950386047,-0.026340842247009,40184,501,-7959,-4239,1.0108687877655 +25231,-0.090867005288601,0.440681487321854,-0.02681901678443,40184,262,25108,-4141,1.01839601993561 +25233,-0.080114714801312,0.392807841300964,-0.027639586478472,40184,249,-941,-4263,1.02627050876617 +25235,-0.064464829862118,0.344180375337601,-0.023475948721171,40184,-452,577,-4122,1.02519726753235 +25237,-0.050105530768633,0.296788513660431,-0.022803349420428,40184,-463,465,-4213,1.02452445030212 +25239,-0.035550516098738,0.250532120466232,-0.025430381298065,40184,-759,1653,-4139,1.01991283893585 +25241,-0.017805863171816,0.218325689435005,-0.024334469810128,40184,-1215,564,-4236,1.01115894317627 +25243,0.002218699082732,0.186113551259041,-0.018572887405753,40184,-1680,1507,-4095,1.00690054893494 +25245,0.016362456604838,0.166213527321816,-0.017702374607325,40184,-1504,482,-4165,1.0067549943924 +25247,0.039529200643301,0.138206452131271,-0.020017128437758,40184,-2443,1854,-4108,1.01089823246002 +25249,0.064851738512516,0.103311352431774,-0.018905460834503,40184,-3095,2560,-4188,1.00782382488251 +25251,0.082817055284977,0.078804850578308,-0.011526538059116,40184,-2714,2445,-4053,1.01017796993256 +25253,0.096979752182961,0.058444499969483,-0.004562476184219,40184,-2848,2257,-4025,1.0145491361618 +25255,0.117244251072407,0.044438064098358,-0.001326815108769,40184,-3411,2198,-3984,1.01977372169495 +25257,0.142538651823998,0.027310989797115,-0.003632000647485,40184,-4432,2555,-4017,1.02656006813049 +25259,0.161450549960136,0.026872266083956,-0.006431953050196,40184,-4008,1504,-4020,1.02417325973511 +25261,0.177058219909668,0.031080700457096,-0.008550264872611,40184,-4371,982,-4074,1.02030313014984 +25263,0.195299118757248,0.037118501961231,-0.010102352127433,40184,-4522,917,-4047,1.01659107208252 +25265,0.207958459854126,0.045688338577747,-0.006672570016235,40184,-4751,446,-4052,1.01832139492035 +25267,0.21757797896862,0.040479842573404,-0.002609186572954,40184,-4316,1689,-3996,1.02332389354706 +25269,0.228016525506973,0.03851392865181,-0.004986281041056,40184,-5009,32349,-4035,1.02521395683289 +25271,0.2450090944767,0.032672252506018,-0.006384943146259,40184,-5339,7103,-4023,1.02144336700439 +25273,0.250627845525742,0.049047417938709,-0.005703315604478,40184,-5138,5131,-4045,1.02061426639557 +25275,0.252353727817535,0.069654077291489,-0.002243175636977,40184,-4464,4743,-3996,1.0234397649765 +25277,0.25661113858223,0.093727879226208,-0.001235838164575,40184,-5261,3910,-3990,1.01861548423767 +25279,0.263406842947006,0.119588769972324,-0.007166703231633,40184,-5103,3695,-4030,1.01113450527191 +25281,0.262002855539322,0.151740208268166,-0.012048955075443,40184,-5057,2410,-4119,1.00167739391327 +25283,0.259145170450211,0.194695368409157,-0.013140017166734,40184,-4470,1408,-4074,0.992708325386047 +25285,0.256946265697479,0.233602806925774,-0.014496210962534,40184,-5032,588,-4151,0.993767440319061 +25287,0.257370412349701,0.271240621805191,-0.014119266532362,40184,-4798,667,-4083,0.995188534259796 +25289,0.252233386039734,0.309816718101501,-0.013876866549254,40184,-4849,-661,-4151,0.999023973941803 +25291,0.248028755187988,0.34872779250145,-0.012417286634445,40184,-4446,-595,-4074,1.00205910205841 +25293,0.238589197397232,0.40011927485466,-0.010204162448645,40184,-4436,-3124,-4110,1.00388610363007 +25295,0.226273864507675,0.444713175296783,-0.010194914415479,40184,-3662,-2480,-4061,1.00443291664124 +25297,0.210743978619575,0.48702871799469,-0.012894552201033,40184,-3659,-4008,-4143,0.998432457447052 +25299,0.193228185176849,0.526791393756866,-0.014153575524688,40184,-2915,-3455,-4090,0.998404026031494 +25301,0.179281771183014,0.563764214515686,-0.013430413790047,40184,-3349,-5032,-4156,0.996388852596283 +25303,0.163181126117706,0.60936176776886,-0.010315649211407,40184,-2669,-5238,-4066,0.997909724712372 +25305,0.14936837553978,0.64875602722168,-0.006733653135598,40184,-2946,-6785,-4083,0.997077465057373 +25307,0.131533578038216,0.691155731678009,-0.005581519100815,40184,-2161,-6405,-4036,0.996035277843475 +25309,0.111410684883595,0.724741756916046,-0.002332100179046,40184,-1929,-7833,-4038,0.998679935932159 +25311,0.083674184978008,0.76652991771698,-0.000672045338433,40184,-816,-7700,-4003,1.00243675708771 +25313,0.051079038530588,0.807840824127197,-0.003711816621944,40184,-87,-10001,-4059,1.00779676437378 +25315,0.021279703825712,0.836466491222382,-0.004444749560207,40184,204,-8056,-4030,1.00873303413391 +25317,0.002065222943202,0.861117124557495,-0.003552123438567,40184,-274,-9985,-4056,1.00367844104767 +25319,-0.010776634328067,0.888379573822022,-0.002160649513826,40184,-553,-9027,-4016,1.00404298305511 +25321,-0.025521080940962,0.910570442676544,-0.003247873391956,40184,-148,-10950,-4052,1.00654065608978 +25323,-0.046099573373795,0.923295617103577,-0.007529383990914,40184,517,-8836,-4054,1.00941121578217 +25325,-0.062214743345976,0.925208449363708,-0.011254415847361,40184,561,-10086,-4147,1.01533758640289 +25327,-0.080679908394814,0.928681790828705,-0.014114512130618,40184,888,-8610,-4102,1.01781356334686 +25329,-0.09565045684576,0.92176765203476,-0.015770085155964,40184,1060,-9755,-4202,1.01484096050262 +25331,-0.120268240571022,0.924900233745575,-0.015876978635788,40184,1940,-8891,-4118,1.01650393009186 +25333,-0.147195547819138,0.930081784725189,-0.013881471939385,40184,2809,-11110,-4181,1.02223992347717 +25353,-0.201805055141449,0.755009829998016,-0.021331733092666,40184,2019,-7426,-4273,0.991995930671692 +25355,-0.202791452407837,0.735204458236694,-0.017660224810243,40184,1953,-6561,-4149,0.991047441959381 +25357,-0.200425073504448,0.697927713394165,-0.017086960375309,40184,2121,-6260,-4222,0.992750525474548 +25359,-0.196334198117256,0.66787314414978,-0.018062641844153,40184,1594,-5131,-4155,0.98886913061142 +25361,-0.189542353153229,0.638512969017029,-0.016020638868213,40184,1699,-6128,-4207,0.989276230335236 +25363,-0.181181490421295,0.599879920482636,-0.012944153510034,40184,1159,-3787,-4122,0.984869420528412 +25365,-0.172265365719795,0.563886046409607,-0.010981366969645,40184,1340,-4677,-4148,0.987731397151947 +25367,-0.153708100318909,0.517027795314789,-0.01007332932204,40184,113,-2224,-4104,0.992090344429016 +25369,-0.134362369775772,0.48020538687706,-0.009431464597583,40184,51,-3450,-4132,0.999453783035278 +25371,-0.120833404362202,0.439090847969055,-0.009153294377029,40184,65,-1694,-4099,1.00535213947296 +25373,-0.109066635370255,0.415783315896988,-0.008713814429939,40184,243,-3529,-4126,1.01235008239746 +25375,-0.088998965919018,0.390526980161667,-0.005817581899464,40184,-808,-2281,-4078,1.02516281604767 +25377,-0.069556042551994,0.363891303539276,-0.000634889816865,40184,-899,-2578,-4034,1.02436697483063 +25379,-0.05274460837245,0.331274092197418,0.004017147701234,40184,-1060,-1028,-4010,1.01977646350861 +25381,-0.030353346839547,0.288581550121307,0.00276949070394,40184,-1723,-315,-3995,1.01289486885071 +25383,-0.00922432448715,0.259069889783859,0.00153532391414,40184,-1977,-306,-4027,1.01086139678955 +25385,0.011009389534593,0.226308301091194,-0.000691630935762,40184,-2228,-90,-4038,1.0114666223526 +25387,0.026193642988801,0.2110885232687,-0.001527324086055,40184,-2061,-704,-4048,1.01166129112244 +25389,0.050442285835743,0.18233497440815,0.002319458173588,40184,-3161,288,-4005,1.00962293148041 +25391,0.064654320478439,0.163527995347977,0.003363678231835,40184,-2562,192,-4014,1.01162457466125 +25393,0.087471939623356,0.1433175355196,0.003462886437774,40184,-3686,278,-3993,1.01487255096436 +25395,0.110685035586357,0.13034600019455,0.001127580180764,40184,-3903,225,-4029,1.02007615566254 +25397,0.134159833192825,0.1158816665411,0.000298574304907,40184,-4541,296,-4031,1.02563285827637 +25399,0.148892745375633,0.110348932445049,0.003060292685404,40184,-3902,-32,-4016,1.02304244041443 +25401,0.158191412687302,0.115883752703667,0.002376081421971,40184,-3990,-1157,-4005,1.01177310943604 +25403,0.167300760746002,0.110786914825439,0.001976627623662,40184,-3835,-83,-4024,1.00908303260803 +25405,0.179901912808418,0.102865286171436,-0.002206340199336,40184,-4656,1,-4060,1.00948393344879 +25407,0.195779860019684,0.092194639146328,-0.003579107811674,40184,-4811,573,-4062,1.01334702968597 +25409,0.211415261030197,0.084723368287087,-0.00306922593154,40184,-5473,256,-4072,1.01454544067383 +25411,0.220953091979027,0.080979697406292,-0.00052759796381,40184,-4815,236,-4042,1.01595497131348 +25413,0.22857677936554,0.077650897204876,0.002404324710369,40184,-5273,75,-4009,1.014608502388 +25415,0.227412939071655,0.088758766651154,0.005446720402688,40184,-4245,-937,-4001,1.01854288578033 +25417,0.223293274641037,0.095786653459072,0.011115920729935,40184,-4445,-956,-3907,1.0206526517868 +25419,0.216709569096565,0.113929890096188,0.01037635281682,40184,-3806,-1808,-3966,1.0179078578949 +25421,0.215597167611122,0.124431125819683,0.001875251648016,40184,-4634,-1680,-4015,1.00854337215424 +25423,0.215611264109611,0.137109532952309,-0.00599473528564,40184,-4361,-1769,-4078,0.996539771556854 +25425,0.215921714901924,0.145350515842438,-0.007577206939459,40184,-4835,-1880,-4129,0.996414601802826 +25427,0.217812269926071,0.149283021688461,-0.006118624005467,40184,-4626,-1345,-4081,0.99681568145752 +25429,0.215249016880989,0.156850054860115,-0.007291168905795,40184,-4707,-2049,-4129,0.999282419681549 +25431,0.208202719688416,0.161370813846588,-0.006485136691481,40184,-3946,-1595,-4085,0.999642550945282 +25433,0.195804551243782,0.179701805114746,0.000396875635488,40184,-3773,-3232,-4041,0.996175765991211 +25435,0.181916743516922,0.190960183739662,0.005430113058537,40184,-3167,-2548,-4004,0.996087789535522 +25437,0.168483912944794,0.20335964858532,0.001467631431296,40184,-3340,-3240,-4029,0.995850324630737 +25439,0.151162177324295,0.223975345492363,-0.002444241661578,40184,-2556,-3749,-4058,1.00172221660614 +25441,0.1337059289217,0.237903967499733,-0.000435983849457,40184,-2566,-3975,-4052,0.999835312366486 +25443,0.114105455577373,0.257192879915237,0.001328125945292,40184,-1923,-4204,-4033,0.993620097637176 +25445,0.098877608776093,0.275861322879791,0.003851388813928,40184,-2224,-5020,-4002,0.993514895439148 +25447,0.088381074368954,0.299019664525986,0.007541095372289,40184,-2255,-5174,-3990,0.993812322616577 +25449,0.077765859663487,0.305847525596619,0.012032952159643,40184,-2255,-4760,-3906,1.00147795677185 +25451,0.063426494598389,0.306005388498306,0.013036726042628,40184,-1660,-3735,-3951,1.00664019584656 +25453,0.043146379292011,0.313559293746948,0.011699559167028,40184,-1031,-5051,-3909,1.01183462142944 +25455,0.02062725648284,0.316061198711395,0.011481702327728,40184,-483,-4160,-3960,1.01352035999298 +25457,-0.003341811709106,0.327176421880722,0.01176879554987,40184,-30,-5640,-3906,1.01499164104462 +25459,-0.017965750768781,0.323278367519379,0.014212442561984,40184,-498,-3924,-3940,1.02127182483673 +25461,-0.035720191895962,0.323006987571716,0.014590386301279,40184,49,-4868,-3871,1.01793074607849 +25463,-0.052935265004635,0.321991354227066,0.01424867566675,40184,200,-4230,-3938,1.00964736938477 +25465,-0.071483157575131,0.326534986495972,0.015341948717833,40184,713,-5390,-3860,0.996610701084137 +25467,-0.093509055674076,0.331292420625687,0.014818488620222,40184,1156,-4897,-3932,0.982114017009735 +25469,-0.110845021903515,0.330934256315231,0.011258350685239,40184,1311,-5233,-3907,0.975800812244415 +25471,-0.124035038053989,0.336374342441559,0.011984230950475,40184,1010,-5143,-3950,0.978156745433807 +25473,-0.134157836437225,0.337296843528748,0.018102860078216,40184,1231,-5549,-3824,0.983593702316284 +25475,-0.137393832206726,0.333309799432755,0.017886534333229,40184,549,-4550,-3907,0.982602477073669 +25477,-0.141350269317627,0.325145602226257,0.015115137211979,40184,970,-4819,-3856,0.984145402908325 +25479,-0.15038038790226,0.312575280666351,0.015316993929446,40184,1215,-3759,-3923,0.986840605735779 +25481,-0.159365266561508,0.314358830451965,0.01871888525784,40184,1687,-5470,-3810,0.992070198059082 +25483,-0.160316422581673,0.303697288036346,0.020891755819321,40184,852,-3885,-3882,0.993048131465912 +25485,-0.159943759441376,0.297819286584854,0.017735155299306,40184,1089,-4772,-3817,0.990938007831574 +25487,-0.15949684381485,0.286255717277527,0.014054033905268,40184,812,-3681,-3926,0.994280159473419 +25489,-0.166359588503838,0.28156989812851,0.012895997613669,40184,1784,-4700,-3871,0.997446298599243 +25491,-0.172385066747665,0.277642697095871,0.012641831301153,40184,1535,-4208,-3934,1.00594258308411 +25493,-0.168626487255096,0.27213579416275,0.013269917108119,40184,1142,-4588,-3864,1.01323711872101 +25495,-0.159062534570694,0.270078510046005,0.016466341912747,40184,305,-4334,-3906,1.01533567905426 +25497,-0.149927705526352,0.258943796157837,0.020869363099337,40184,525,-4065,-3771,1.01471769809723 +25499,-0.140424787998199,0.25408461689949,0.025330791249871,40184,111,-3998,-3842,1.01195335388184 +25501,-0.126701414585114,0.236820667982101,0.028145212680101,40184,-114,-3353,-3681,1.01409268379211 +25503,-0.118295632302761,0.227662578225136,0.027019144967198,40184,-67,-3396,-3826,1.00961267948151 +25505,-0.107637785375118,0.220838591456413,0.028350375592709,40184,-150,-3921,-3674,1.00480425357819 +25507,-0.095599427819252,0.208337530493736,0.032854046672583,40184,-603,-2957,-3781,0.997451663017273 +25509,-0.087093710899353,0.204537108540535,0.032426878809929,40184,-284,-3949,-3621,0.996465981006622 +25511,-0.074652127921581,0.198899909853935,0.027002131566405,40184,-891,-3384,-3817,1.00231122970581 +25513,-0.063901096582413,0.197040855884552,0.021352900192142,40184,-777,-4039,-3747,1.00513076782227 +25515,-0.046372763812542,0.183485224843025,0.016976190730929,40184,-1629,-2664,-3882,1.00733888149261 +25517,-0.033839482814074,0.179571777582169,0.013215177692473,40184,-1362,-3683,-3841,1.00582361221313 +25519,-0.01948275230825,0.173244699835777,0.014795996248722,40184,-1768,-3098,-3895,1.00727868080139 +25521,-0.004218324553221,0.163537308573723,0.016935786232352,40184,-2031,-3070,-3795,1.00604486465454 +25523,0.006214411463588,0.153357684612274,0.016462359577417,40184,-1850,-2594,-3881,1.00741243362427 +25525,0.014792153611779,0.142903476953507,0.017921682447195,40184,-1873,-2735,-3780,1.00729858875275 +25527,0.023428022861481,0.140118345618248,0.020377449691296,40184,-1974,-2981,-3852,1.00533843040466 +25529,0.038227386772633,0.126232579350472,0.022701594978571,40184,-2722,-2265,-3720,1.00183415412903 +25531,0.05157595127821,0.11596954613924,0.023166166618466,40184,-2734,-2140,-3829,1.00149512290955 +25533,0.067748695611954,0.105756439268589,0.025755671784282,40184,-3322,-2233,-3681,1.00171148777008 +25535,0.082051925361157,0.109607480466366,0.027796579524875,40184,-3272,-3092,-3793,1.0011157989502 +25537,0.088920965790749,0.121373623609543,0.025949709117413,40184,-3034,-4100,-3675,1.00175714492798 +25539,0.09246414154768,0.122730739414692,0.026565589010716,40184,-2692,-3142,-3798,1.00391614437103 +25541,0.091633178293705,0.128257885575295,0.031190758571029,40184,-2572,-3790,-3609,1.00883531570435 +25543,0.10037325322628,0.12143312394619,0.036851342767477,40184,-3221,-2578,-3722,1.01287567615509 +25545,0.105940453708172,0.121914155781269,0.036684982478619,40184,-3306,-3351,-3539,1.01095795631409 +25547,0.110125787556171,0.104127317667007,0.033282198011875,40184,-3085,-1581,-3741,1.00434243679047 +25549,0.106800280511379,0.092101946473122,0.027222823351622,40184,-2724,-2004,-3647,0.998403549194336 +25551,0.107063822448254,0.088161364197731,0.022289087995887,40184,-2809,-2367,-3812,1.00229287147522 +25553,0.114395759999752,0.084980003535748,0.021342722699046,40184,-3656,-2552,-3713,1.00454962253571 +25555,0.121835172176361,0.091037176549435,0.027358576655388,40184,-3587,-3146,-3774,1.00258994102478 +25557,0.122785195708275,0.089359566569328,0.028725646436215,40184,-3388,-2762,-3622,0.999527871608734 +25559,0.113861203193665,0.090227417647839,0.027263894677162,40184,-2357,-2788,-3770,1.00081408023834 +25561,0.109681978821754,0.078156188130379,0.0329096801579,40184,-2866,-1853,-3568,1.00366592407227 +25563,0.109625995159149,0.069580689072609,0.037118691951037,40184,-2982,-1835,-3697,1.00780951976776 +25565,0.105669997632504,0.066938914358616,0.035138126462698,40184,-2872,-2354,-3536,1.01084327697754 +25587,0.004805706441402,0.083698801696301,0.025243198499084,39684,-531,-3439,-3751,0.992230534553528 +25589,-0.000897074816749,0.083502754569054,0.029561832547188,39684,-1171,-2908,-3575,0.988669097423553 +25591,-0.003387060249224,0.091976039111614,0.0269670560956,39684,-1376,-3505,-3734,0.990504801273346 +25593,-0.008214797824621,0.101786471903324,0.025660322979093,39684,-1117,-3955,-3617,0.99642413854599 +25595,-0.008484407328069,0.099722363054752,0.026237063109875,39684,-1460,-2893,-3735,1.00299561023712 +25597,-0.010457798838616,0.098769381642342,0.023408815264702,39684,-1280,-3173,-3640,1.00379109382629 +25599,-0.01246986258775,0.094490855932236,0.023898579180241,39684,-1274,-2691,-3748,1.00352823734283 +25601,-0.020605497062206,0.095686450600624,0.026714256033301,39684,-671,-3307,-3597,1.00247240066528 +25603,-0.025741588324308,0.086730964481831,0.030156133696437,39684,-852,-2276,-3701,1.00486958026886 +25605,-0.029720440506935,0.084057167172432,0.030231829732657,39684,-816,-2859,-3551,1.00454449653625 +25607,-0.035484079271555,0.080352075397968,0.026617344468832,39684,-656,-2584,-3720,1.00955545902252 +25609,-0.034511394798756,0.078205242753029,0.0261613689363,39326,-1079,-2819,-3594,1.00431954860687 +25611,-0.037792008370161,0.09160277992487,0.030837344005704,39326,-787,-3992,-3687,1.0008864402771 +25613,-0.043255027383566,0.0962098762393,0.036741320043802,39326,-451,-3623,-3465,0.998235762119293 +25615,-0.050542820245028,0.103384248912334,0.03782269731164,39326,-297,-3745,-3633,0.997047781944275 +25617,-0.049237985163927,0.104220569133759,0.033293686807156,39326,-809,-3514,-3500,0.993371665477753 +25619,-0.047798871994019,0.108693964779377,0.030789151787758,39326,-938,-3661,-3677,0.984932363033295 +25621,-0.054118473082781,0.10539323091507,0.032822627574205,39326,-153,-3272,-3501,0.977881610393524 +25623,-0.053408727049828,0.091945178806782,0.035662703216076,39326,-778,-2172,-3638,0.971467018127441 +25625,-0.05104623734951,0.082277379930019,0.0337840244174,39326,-802,-2464,-3484,0.971166610717773 +25627,-0.049310989677906,0.072305031120777,0.028987489640713,39326,-885,-2162,-3679,0.971234500408173 +25629,-0.050633728504181,0.082620695233345,0.026974266394973,39326,-527,-3924,-3559,0.97211629152298 +25631,-0.051302969455719,0.083307154476643,0.030437421053648,39326,-660,-3107,-3664,0.976252019405365 +25633,-0.054322920739651,0.08994672447443,0.034987609833479,39326,-334,-3825,-3459,0.981636166572571 +25635,-0.051445879042149,0.090441785752773,0.036190360784531,39326,-888,-3226,-3619,0.991600632667542 +25637,-0.045657463371754,0.085136987268925,0.034940745681524,39326,-1093,-2928,-3454,0.998758614063263 +25639,-0.046404678374529,0.08502783626318,0.034624479711056,39326,-683,-3135,-3625,0.998170495033264 +25641,-0.04620073735714,0.085180327296257,0.036170762032271,39326,-668,-3347,-3434,1.00015914440155 +25643,-0.041085556149483,0.095535434782505,0.037044856697321,39326,-1161,-4066,-3602,0.997510194778442 +25645,-0.032131299376488,0.081736102700234,0.039666645228863,39326,-1501,-2315,-3387,0.996702432632446 +25647,-0.032352674752474,0.079821512103081,0.040660168975592,37968,-890,-2989,-3571,0.991790115833282 +25649,-0.029007866978645,0.086227603256703,0.038351442664862,37968,-1125,-3855,-3396,0.987310230731964 +25651,-0.024423783645034,0.091273926198483,0.034689549356699,37968,-1334,-3680,-3606,0.983080804347992 +25653,-0.020899968221784,0.09337443113327,0.03256656229496,37968,-1252,-3689,-3459,0.981175184249878 +25655,-0.021388068795204,0.094043143093586,0.032683715224266,37968,-1003,-3438,-3615,0.983264327049255 +25657,-0.019676992669702,0.097873330116272,0.033724658191204,37968,-1133,-3918,-3440,0.98852127790451 +25659,-0.015365356579423,0.091882824897766,0.034971009939909,37968,-1423,-2963,-3593,0.98949933052063 +25661,-0.014597721397877,0.08649330586195,0.035505659878254,37968,-1151,-3104,-3413,0.982875823974609 +25663,-0.015116671100259,0.080518402159214,0.033430401235819,37968,-1075,-2830,-3598,0.981361091136932 +25665,-0.01272707991302,0.072530351579189,0.029714556410909,37968,-1290,-2719,-3476,0.975457549095154 +25667,-0.010706065222621,0.067665599286556,0.031383693218231,37968,-1315,-2748,-3608,0.974148452281952 +25669,-0.001617971225642,0.055759087204933,0.032396655529738,37968,-1948,-2183,-3439,0.975017547607422 +25671,0.009551969356835,0.056185476481915,0.030955396592617,37968,-2260,-2977,-3606,0.975699365139008 +25673,0.018073214218021,0.047557033598423,0.032109882682562,37968,-2227,-2295,-3438,0.973147630691528 +25675,0.013032857328653,0.046973921358585,0.034172255545855,37968,-1157,-2783,-3578,0.973111987113952 +25677,0.006791841238737,0.035504959523678,0.038037300109863,37968,-983,-1897,-3363,0.974064469337463 +25679,-0.002207563025877,0.034889366477728,0.038317624479532,37968,-656,-2612,-3544,0.97168618440628 +25681,0.001890435349196,0.03242065012455,0.031553413718939,37968,-1646,-2498,-3433,0.968028664588928 +25683,0.010761280544102,0.035377252846956,0.028090391308069,37968,-2122,-2878,-3609,0.961428940296173 +25685,0.015977887436748,0.038777884095907,0.032987955957651,37485,-1961,-3030,-3411,0.963377356529236 +25687,0.01616714335978,0.034107148647308,0.038929127156735,37485,-1584,-2321,-3529,0.969282448291779 +25689,0.016107646748424,0.03042926825583,0.039939966052771,37485,-1590,-2393,-3324,0.975191116333008 +25691,0.016294764354825,0.021238094195724,0.037786494940519,37485,-1592,-1815,-3531,0.977307617664337 +25693,0.0111119505018,0.026099814102054,0.035472638905048,37485,-1147,-2938,-3370,0.975940763950348 +25695,0.00592937739566,0.028530577197671,0.035513766109943,37485,-1062,-2754,-3541,0.974909067153931 +25697,0.004645119886845,0.030431794002652,0.033207051455975,37485,-1325,-2793,-3391,0.971051752567291 +25699,0.00753862503916,0.032323520630598,0.030348263680935,37485,-1665,-2773,-3571,0.971357643604279 +25701,0.011606915853918,0.024213247001171,0.029800288379192,37485,-1827,-1975,-3426,0.962364196777344 +25703,0.012092380784452,0.021759985014796,0.032047212123871,37485,-1563,-2310,-3554,0.952292084693909 +25705,0.011243745684624,0.017874963581562,0.031681824475527,37485,-1478,-2182,-3399,0.952830135822296 +25707,0.010644171386957,0.025247164070606,0.027163995429874,37485,-1470,-3062,-3583,0.954288005828857 +25709,0.014769438654184,0.02239703387022,0.022363048046827,37485,-1901,-2338,-3505,0.961080610752106 +25711,0.019093723967671,0.026108074933291,0.019804839044809,37485,-1952,-2814,-3630,0.95878654718399 +25713,0.01875738427043,0.027742259204388,0.023908877745271,37485,-1655,-2751,-3483,0.959557592868805 +25715,0.015975534915924,0.025450402870774,0.026153476908803,37485,-1408,-2379,-3583,0.958685457706451 +25717,0.010246266610921,0.033346671611071,0.025436734780669,37485,-1140,-3278,-3461,0.959831357002258 +25719,0.009959915652871,0.033494740724564,0.025687675923109,37485,-1506,-2674,-3582,0.959108054637909 +25737,0.018325971439481,0.068350896239281,0.016234871000052,36949,-1926,-3000,-3549,0.964791119098663 +25739,0.011821519583464,0.074298121035099,0.016676586121321,36949,-1123,-3761,-3624,0.954378247261047 +25741,0.003536564763635,0.066715128719807,0.022877331823111,36949,-867,-2818,-3468,0.946300268173218 +25743,-0.008664106950164,0.071369521319866,0.028051601722837,36949,-420,-3649,-3542,0.94349330663681 +25745,-0.014043161645532,0.063326977193356,0.029997849836946,36949,-786,-2747,-3380,0.948198497295379 +25747,-0.017911989241839,0.061085749417543,0.027170574292541,36949,-876,-3028,-3543,0.946020483970642 +25749,-0.022794945165515,0.066222682595253,0.025768512859941,36949,-679,-3763,-3425,0.946280002593994 +25751,-0.018287902697921,0.059165302664042,0.024386916309595,36949,-1460,-2677,-3558,0.937413215637207 +25753,-0.015772009268403,0.056822322309017,0.0212557092309,36949,-1316,-3101,-3474,0.925888359546661 +25755,-0.019095797091723,0.04610875621438,0.019061280414462,36949,-880,-2247,-3591,0.9238201379776 +25757,-0.028407888486981,0.055810604244471,0.022369787096977,36949,-253,-3967,-3457,0.921304106712341 +25759,-0.02883124910295,0.0469652377069,0.027080997824669,36949,-935,-2411,-3533,0.921342194080353 +25761,-0.035955280065537,0.054878849536181,0.024384113028646,36949,-277,-3849,-3430,0.922394931316376 +25763,-0.033545587211847,0.051158003509045,0.022887730970979,36949,-1055,-2858,-3558,0.927209556102753 +25765,-0.033286947757006,0.047163791954517,0.021382080391049,36949,-837,-2885,-3462,0.928656339645386 +25767,-0.032159749418497,0.04065727442503,0.024028031155467,36949,-968,-2524,-3546,0.929334044456482 +25769,-0.040780823677778,0.038483202457428,0.027711231261492,36949,-60,-2878,-3383,0.926243245601654 +25771,-0.040584675967693,0.036276016384363,0.025135368108749,36949,-762,-2779,-3534,0.926312148571014 +25773,-0.034466914832592,0.029334012418985,0.022904057055712,36949,-1194,-2395,-3436,0.929643750190735 +25775,-0.036856297403574,0.032754506915808,0.021876983344555,36949,-614,-3138,-3553,0.932854175567627 +25777,-0.039243426173925,0.028421562165022,0.021702064201236,36949,-478,-2569,-3447,0.938381969928741 +25779,-0.03937878459692,0.02933382242918,0.020038248971105,36949,-718,-2914,-3562,0.940012395381928 +25781,-0.031703889369965,0.016943570226431,0.020501337945461,36949,-1302,-1807,-3457,0.936844110488892 +25783,-0.034073654562235,0.018168130889535,0.021027876064181,36949,-616,-2776,-3552,0.93207311630249 +25785,-0.035914424806833,0.020971242338419,0.023612793534994,36949,-543,-2965,-3417,0.928880453109741 +25787,-0.036201495677233,0.025692790746689,0.024407519027591,36949,-716,-3137,-3525,0.924279868602753 +25789,-0.028754692524672,0.029553778469563,0.024412678554654,36949,-1314,-3188,-3404,0.924791157245636 +25791,-0.020958276465535,0.020705908536911,0.026965025812388,36949,-1500,-2100,-3504,0.925811350345612 +25793,-0.022028436884284,0.023183884099126,0.029091520234943,36949,-797,-2986,-3344,0.936501324176788 +25795,-0.020130274817348,0.023685619235039,0.029004549607635,36949,-1078,-2815,-3485,0.944702446460724 +25797,-0.013546683825553,0.026437062770128,0.025489253923297,36770,-1474,-3055,-3382,0.940852344036102 +25799,-0.004290231969208,0.022692073136568,0.030288137495518,36770,-1825,-2500,-3472,0.935348153114319 +25801,-0.006468687206507,0.029364950954914,0.034143932163715,36770,-964,-3377,-3275,0.926434636116028 +25803,-0.005639596842229,0.022282032296062,0.031795784831047,36770,-1199,-2258,-3456,0.925871133804321 +25805,-0.003996542654932,0.022256590425968,0.026576582342386,36770,-1277,-2785,-3360,0.920841693878174 +25807,-0.000255861814367,0.032016985118389,0.025843093171716,36770,-1483,-3604,-3493,0.922718048095703 +25809,0.010087878443301,0.034463159739971,0.026423655450344,36770,-2136,-3187,-3357,0.924389243125916 +25811,0.018597127869725,0.040287543088198,0.024900833144784,36770,-2101,-3451,-3495,0.930543482303619 +25813,0.026354722678661,0.027623768895865,0.024182299152017,36770,-2229,-2011,-3379,0.92730325460434 +25815,0.023715805262327,0.029164729639888,0.028346177190542,36770,-1390,-2993,-3467,0.919100999832153 +25817,0.01960345543921,0.030912518501282,0.033532306551933,36770,-1279,-3098,-3264,0.914548993110657 +25819,0.017166797071695,0.044928498566151,0.031527258455753,36770,-1321,-4122,-3440,0.914074897766113 +25821,0.030431903898716,0.044909987598658,0.027827071025968,36770,-2684,-3211,-3327,0.916776955127716 +25823,0.034305263310671,0.052512470632792,0.023197880014777,36770,-2030,-3787,-3493,0.922249019145966 +25825,0.031127322465181,0.053604885935783,0.024654511362314,36770,-1518,-3449,-3360,0.930774927139282 +25827,0.037573542445898,0.051530998200178,0.024522250518203,36770,-2271,-3099,-3480,0.929670572280884 +25829,0.045514658093453,0.052108436822891,0.024050801992416,36770,-2584,-3402,-3363,0.93279242515564 +25831,0.055176295340061,0.048135682940483,0.026926342397928,36770,-2774,-2932,-3459,0.930082559585571 +25833,0.050959918648005,0.048549957573414,0.030537175014615,36770,-1835,-3331,-3282,0.930217623710632 +25835,0.046094484627247,0.032092962414026,0.030909262597561,36770,-1628,-1821,-3427,0.92561936378479 +25837,0.042808692902327,0.038433060050011,0.026244398206472,36770,-1790,-3620,-3328,0.924858570098877 +25839,0.046933475881815,0.03695035725832,0.021079920232296,36770,-2305,-2974,-3490,0.927468597888946 +25841,0.044265706092119,0.050124827772379,0.020301869139075,36770,-1879,-4315,-3394,0.928829908370972 +25843,0.0433169901371,0.051494400948286,0.024164108559489,36770,-1911,-3405,-3466,0.92682421207428 +25845,0.035388004034758,0.050458572804928,0.028704656288028,36770,-1380,-3313,-3291,0.919275403022766 +25847,0.030582023784518,0.042571995407343,0.033389300107956,36770,-1470,-2630,-3398,0.918106019496918 +25849,0.030079483985901,0.030163375660777,0.030220471322537,36770,-1837,-2181,-3269,0.913324594497681 +25851,0.028959782794118,0.032095644623041,0.028485698625445,36770,-1726,-3191,-3426,0.91717654466629 +25853,0.020310433581472,0.036117777228356,0.031628683209419,36770,-1099,-3466,-3247,0.91798996925354 +25855,0.016418689861894,0.041979480534792,0.031480100005865,36770,-1356,-3625,-3401,0.920315086841583 +25857,0.021648954600096,0.031180107966066,0.026457091793418,36770,-2122,-2330,-3304,0.923191547393799 +25859,0.018408929929137,0.030086943879724,0.023018900305033,36770,-1440,-2964,-3454,0.925969541072845 +25861,0.015091515146196,0.023224143311381,0.026454973965883,36770,-1413,-2487,-3299,0.921986043453217 +25863,0.004829885903746,0.024125823751092,0.03105047531426,36770,-749,-3026,-3395,0.916404485702515 +25865,-0.001124975271523,0.022414080798626,0.032207265496254,36770,-976,-2857,-3227,0.911074876785278 +25867,-0.003474231809378,0.022723713889718,0.03322695940733,36770,-1198,-2969,-3375,0.903806388378143 +25869,-0.008474067784846,0.019808482378721,0.033182915300131,36770,-928,-2738,-3210,0.90553468465805 +25871,-0.009733470156789,0.010344576090574,0.028696540743113,36770,-1185,-2096,-3400,0.905039250850678 +25873,-0.010034349747002,0.012684111483395,0.026486264541745,36770,-1232,-2999,-3284,0.907216846942902 +25875,-0.006197020877153,0.012216797098518,0.028099376708269,36770,-1597,-2768,-3400,0.90763783454895 +25877,-0.009448069147766,0.016254572197795,0.029501741752029,36770,-1021,-3172,-3244,0.908780753612518 +25879,-0.010419664904475,-0.001722284592688,0.027840174734593,36770,-1188,-1315,-3397,0.907679855823517 +25881,-0.017856761813164,-5.82101165491622E-05,0.026863852515817,36770,-577,-2726,-3270,0.910114467144012 +25883,-0.017579382285476,-0.007169609423727,0.027425918728113,36770,-1167,-2007,-3396,0.910714209079742 +25885,-0.019892692565918,-0.002319943858311,0.024117656052113,36770,-901,-2909,-3298,0.914162218570709 +25887,-0.021271232515574,0.001707302872092,0.025612471625209,36770,-986,-2924,-3404,0.922831833362579 +25889,-0.027924165129662,0.009382187388837,0.027923559769988,36770,-447,-3301,-3249,0.921372950077057 +25891,-0.030442606657744,0.007830565795302,0.025188891217113,36770,-759,-2610,-3402,0.921845555305481 +25893,-0.026906859129667,0.006066575180739,0.024829801172018,36770,-1193,-2576,-3281,0.915807068347931 +25895,-0.019588829949498,0.011801920831204,0.027070729061961,36770,-1609,-3187,-3385,0.909011840820312 +25897,-0.010730251669884,0.005992439109832,0.02675786614418,36770,-1836,-2280,-3254,0.906536996364594 +25899,-0.009758299216628,0.009642257355154,0.025814842432737,36770,-1293,-3004,-3390,0.902838587760925 +25901,-0.012008833698928,0.001834167866036,0.023534102365375,36770,-1002,-2068,-3288,0.901778817176819 +25903,-0.012702833861113,0.008640219457448,0.020605793222785,36770,-1126,-3211,-3422,0.90793365240097 +25905,-0.008141184225678,0.001692365854979,0.021411819383502,36770,-1560,-2122,-3309,0.919307768344879 +25907,-0.005826112814248,0.006713427603245,0.02196048013866,36770,-1438,-3051,-3409,0.927681982517242 +25909,0.0069803991355,0.00667930347845,0.025949923321605,36770,-2407,-2690,-3252,0.929052650928497 +25911,0.005221606697887,0.013616922311485,0.02903169952333,36770,-1311,-3285,-3356,0.930099487304688 +25913,0.002781349001452,0.021540563553572,0.025444405153394,36770,-1237,-3497,-3254,0.933379650115967 +25915,-0.000743454846088,0.024509904906154,0.022721076384187,36770,-1101,-3160,-3395,0.93454498052597 +25917,-0.003206152003258,0.028613021597266,0.027061488479376,36770,-1114,-3350,-3231,0.937123596668243 +25919,-0.001195874763653,0.031155968084931,0.030778812244535,36770,-1487,-3232,-3335,0.932658135890961 +25921,0.001757099875249,0.035239845514298,0.02913617156446,36770,-1598,-3472,-3201,0.928519308567047 +25923,0.009182153269649,0.033124707639217,0.025732558220625,36770,-2024,-2938,-3365,0.92337828874588 +25925,0.014517412520945,0.04265582934022,0.020651178434491,36770,-1977,-3996,-3297,0.917125165462494 +25927,0.021701462566853,0.036733962595463,0.021764896810055,36770,-2193,-2732,-3389,0.914413690567017 +25929,0.011143281124532,0.040967628359795,0.026070429012179,36770,-777,-3606,-3230,0.90940260887146 +25931,0.00566517515108,0.031585704535246,0.028183344751597,36770,-1059,-2425,-3341,0.912403881549835 +25933,0.004704075399786,0.039033390581608,0.026189599186182,36770,-1370,-3812,-3224,0.92039155960083 +25935,0.005709692370147,0.047259859740734,0.026187229901552,36770,-1525,-3924,-3350,0.927749693393707 +25937,0.011025041341782,0.036681436002255,0.024780489504337,36770,-1932,-2483,-3236,0.929277062416077 +25939,0.003286785213277,0.041286550462246,0.021632062271237,36770,-869,-3590,-3377,0.928312420845032 +25941,-0.009718297049403,0.04893808811903,0.021375089883804,36770,-285,-4002,-3272,0.929000198841095 +25943,-0.012113612145186,0.053322248160839,0.021928424015641,36770,-1027,-3762,-3372,0.927797496318817 +25945,-0.003855196293443,0.040552951395512,0.022146908566356,36770,-1900,-2424,-3260,0.926909267902374 +25947,-0.00362669210881,0.040865942835808,0.02460603043437,36770,-1335,-3306,-3350,0.925191700458527 +25949,-0.000878834514879,0.023696437478066,0.029848888516426,36770,-1554,-1843,-3165,0.920207679271698 +25951,-0.003962379414588,0.019393173977733,0.030986191704869,36770,-1093,-2672,-3301,0.916922807693481 +25965,-0.009924820624292,0.02129153162241,0.025253584608436,36770,-1009,-3487,-3199,0.90935891866684 +25967,-0.007922241464257,0.014492978341878,0.024878805503249,36770,-1388,-2450,-3323,0.910868942737579 +25969,-0.01120419986546,0.021012369543314,0.026146903634071,36770,-941,-3526,-3185,0.909509718418121 +25971,-0.006482865195721,0.010666699148715,0.030815361067653,36770,-1599,-2145,-3278,0.908773839473724 +25973,-0.012589841149747,0.017406899482012,0.0333506539464,36770,-708,-3483,-3095,0.910658001899719 +25975,-0.00798234064132,0.011958326213062,0.034713733941317,36770,-1564,-2516,-3246,0.913072049617767 +25977,-0.00746818818152,0.008549643680453,0.031644228845835,36770,-1259,-2619,-3109,0.914462625980377 +25979,-0.00468942290172,0.003806268097833,0.029102221131325,36770,-1477,-2448,-3279,0.919473171234131 +25981,-0.011522583663464,0.001593308872543,0.029743103310466,36770,-662,-2595,-3127,0.918635845184326 +25983,-0.0166997294873,0.00744820991531,0.028758699074388,36770,-729,-3257,-3277,0.917192876338959 +25985,-0.013677876442671,0.008966688998044,0.028436824679375,36770,-1339,-2984,-3137,0.909740269184112 +25987,-0.014297995716333,0.013843275606632,0.030434712767601,36770,-1085,-3279,-3260,0.900743663311004 +25989,-0.012349811382592,0.008510272949934,0.033687900751829,36770,-1281,-2483,-3070,0.898805916309357 +25991,-0.017468163743615,0.008510212413967,0.032255902886391,36770,-713,-2854,-3242,0.89935439825058 +25993,-0.013303403742611,-0.009444643743336,0.028612866997719,36770,-1409,-1292,-3125,0.908639907836914 +25995,-0.006690220441669,-0.005165064707398,0.026594435796142,36770,-1702,-2957,-3276,0.914425492286682 +25997,0.006113370880485,-0.004352190066129,0.029029408469796,36770,-2348,-2705,-3115,0.924258530139923 +25999,0.012865414842963,0.006346974056214,0.029895089566708,36770,-1996,-3577,-3249,0.92496782541275 +26001,0.014695812948048,0.011755428276956,0.033023670315743,36770,-1709,-3270,-3063,0.923906803131104 +26003,0.007684851065278,0.005592261441052,0.039829410612583,36770,-944,-2355,-3175,0.926182329654694 +26005,0.005528185982257,0.011594420298934,0.044335603713989,36770,-1274,-3311,-2923,0.933587372303009 +26007,0.013387758284807,0.003868806175888,0.045859590172768,36770,-2094,-2216,-3126,0.936615228652954 +26009,0.015337602235377,0.002731898799539,0.042300350964069,36770,-1745,-2659,-2940,0.933893322944641 +26011,0.015535220503807,0.000146272286656,0.043780833482742,36770,-1586,-2526,-3134,0.926200270652771 +26013,0.017035188153386,0.002648916328326,0.043767586350441,36770,-1776,-2916,-2915,0.91748970746994 +26015,0.025619674474001,-0.003830572357401,0.042712219059467,36770,-2346,-2186,-3134,0.913079917430878 +26017,0.023087076842785,0.002919408725575,0.036273807287216,36770,-1587,-3220,-2997,0.914250373840332 +26019,0.024810407310724,-0.000289809657261,0.032460726797581,36770,-1858,-2466,-3198,0.91634875535965 +26021,0.0264066234231,-0.001583395525813,0.029284154996276,36770,-1928,-2581,-3074,0.91350919008255 +26023,0.025920171290636,-0.004107870627195,0.025993390008807,37253,-1728,-2457,-3238,0.916818261146545 +26025,0.029098456725478,-0.001444810302928,0.026985853910446,37253,-2090,-2860,-3096,0.917993426322937 +26027,0.021632924675942,0.012458546087146,0.029738504439592,37253,-1179,-3867,-3207,0.92589682340622 +26029,0.01555335149169,0.007858941331506,0.031607501208782,37253,-1216,-2468,-3037,0.9278604388237 +26031,0.006985116750002,0.009850975126028,0.031813479959965,37253,-897,-2973,-3188,0.928376495838165 +26033,0.003600330092013,0.003802885534242,0.032129887491465,37253,-1223,-2294,-3026,0.933040380477905 +26035,0.001260680845007,0.00702966330573,0.031785756349564,37253,-1262,-3016,-3183,0.92974728345871 +26037,0.007749082054943,-0.009768896736205,0.031879913061857,37253,-1992,-1303,-3023,0.929680645465851 +26039,0.003142999252304,-0.009101957082748,0.031151562929154,37253,-1129,-2591,-3182,0.922941863536835 +26041,-0.001436992548406,-0.009483094327152,0.033816959708929,37253,-1051,-2479,-2995,0.917230904102325 +26043,-0.001587502541952,-0.01104823499918,0.034992262721062,37253,-1378,-2394,-3149,0.907958030700684 +26045,-0.001340141287074,-0.005282475613058,0.031875189393759,37253,-1405,-2985,-3012,0.9060218334198 +26047,0.001014796434902,-0.007653585635126,0.032695710659027,37253,-1595,-2379,-3160,0.903055965900421 +26049,0.00133245869074,-0.002266629366204,0.039132054895163,37253,-1455,-3006,-2921,0.902214050292969 +26051,-0.001465551322326,-0.006189393810928,0.038547269999981,37253,-1191,-2284,-3113,0.900458872318268 +26053,-0.002886364702135,0.000291661126539,0.032491441816092,37253,-1258,-3117,-2993,0.903760254383087 +26055,-0.000697346578818,-0.002220426686108,0.031201042234898,37253,-1558,-2438,-3158,0.908096611499786 +26057,-0.00834986846894,0.00527431955561,0.031930066645146,37253,-722,-3260,-2994,0.912772178649902 +26059,-0.011120399460197,0.001219821628183,0.034085664898157,37431,-1049,-2374,-3133,0.910227298736572 +26061,-0.018772391602397,0.000233716040384,0.034143749624491,37431,-553,-2572,-2963,0.91025185585022 +26063,-0.019855005666614,-0.000979158678092,0.035969868302345,37431,-1037,-2541,-3114,0.916254341602325 +26065,-0.013380437158048,-0.000310269824695,0.035737115889788,37431,-1650,-2680,-2938,0.916207313537598 +26067,-0.013177327811718,0.006653496995568,0.034446280449629,37431,-1220,-3232,-3119,0.918771088123322 +26069,-0.012685006484389,0.007185616064817,0.036802113056183,37431,-1226,-2788,-2919,0.915861248970032 +26071,-0.012699824757874,0.013274016790092,0.03874196484685,37431,-1207,-3264,-3083,0.915731966495514 +26073,-0.007307997439057,0.008178271353245,0.037823732942343,37431,-1657,-2398,-2901,0.912756621837616 +26075,-0.00530208228156,0.015467572025955,0.035176519304514,37431,-1455,-3381,-3101,0.907153069972992 +26077,0.002707764273509,0.006941676139832,0.033054903149605,37431,-2003,-2133,-2951,0.902129948139191 +26079,0.003563454607502,0.015847632661462,0.034277379512787,37431,-1501,-3501,-3102,0.906921982765198 +26081,0.008063706569374,0.016804303973913,0.033990327268839,37431,-1835,-2977,-2934,0.916778922080994 +26083,0.012706260196865,0.018318347632885,0.028006687760353,37431,-1906,-3011,-3139,0.922129333019257 +26085,0.015514047816396,0.027158562093973,0.027004392817617,37431,-1832,-3709,-3011,0.930792272090912 +26087,0.018880475312471,0.026504183188081,0.028356647118926,37431,-1908,-2981,-3132,0.927716016769409 +26089,0.017396748065949,0.01850544475019,0.027516098693013,37431,-1574,-2360,-3001,0.924537420272827 +26091,0.021799394860864,0.011106164194644,0.029691260308027,37431,-2032,-2279,-3118,0.921204805374146 +26093,0.024684114381671,0.018181154504418,0.03145444393158,37431,-2025,-3434,-2949,0.920575261116028 +26095,0.024007132276893,0.011161648668349,0.029018364846706,37431,-1713,-2308,-3118,0.923227787017822 +26097,0.022106537595391,0.020765643566847,0.025404380634427,37789,-1658,-3676,-3016,0.923558056354523 +26099,0.030466953292489,0.017350653186441,0.028909957036376,37789,-2467,-2661,-3114,0.921866714954376 +26101,0.034769382327795,0.034651704132557,0.033202428370714,37789,-2323,-4453,-2919,0.923647522926331 +26103,0.039811030030251,0.03426119685173,0.035433072596789,37789,-2382,-3131,-3063,0.922678649425507 +26105,0.034029703587294,0.025389859452844,0.033721584826708,37789,-1603,-2424,-2907,0.917946100234985 +26107,0.030158581212163,0.02556593157351,0.030330760404468,37789,-1623,-3051,-3093,0.919628381729126 +26109,0.03273943066597,0.022363690659404,0.028219319880009,37789,-2193,-2795,-2967,0.92241895198822 +26111,0.040202792733908,0.028895711526275,0.027227314189077,37789,-2595,-3560,-3109,0.928085744380951 +26113,0.044839888811112,0.028157470747829,0.024997480213642,37789,-2542,-3079,-3000,0.931577384471893 +26115,0.045834138989449,0.028468310832977,0.024952191859484,37789,-2232,-3117,-3121,0.932080507278442 +26117,0.046120181679726,0.02386892773211,0.026026425883174,37789,-2272,-2737,-2984,0.929584801197052 +26119,0.038162555545569,0.02648613601923,0.027948303148151,37789,-1501,-3260,-3096,0.928296685218811 +26121,0.037112392485142,0.018588123843074,0.031219271942973,37789,-2054,-2421,-2918,0.926162660121918 +26123,0.035689890384674,0.022286413237453,0.030069574713707,37789,-1951,-3281,-3076,0.922463119029999 +26125,0.036311138421297,0.024358086287975,0.032320834696293,37789,-2179,-3248,-2899,0.920493245124817 +26127,0.031443569809198,0.033374503254891,0.03240268304944,37789,-1661,-3831,-3054,0.9151970744133 +26129,0.027602851390839,0.034841623157263,0.030954634770751,37789,-1733,-3389,-2910,0.920087218284607 +26131,0.02408910728991,0.02231208793819,0.032780542969704,37789,-1666,-2143,-3046,0.923766672611237 +26133,0.017070274800062,0.017869023606181,0.035589952021837,37789,-1351,-2697,-2850,0.924829840660095 +26135,0.011321206577122,0.012214771471918,0.038270875811577,37914,-1332,-2496,-3003,0.926760315895081 +26137,0.009229645133019,0.016529221087694,0.037784237414599,37914,-1588,-3303,-2818,0.927914023399353 +26139,0.010155051015318,0.015322426334024,0.036357261240482,37914,-1800,-2864,-3009,0.934115529060364 +26141,0.004711565095931,0.012745503336191,0.037059310823679,37914,-1266,-2745,-2820,0.935681521892548 +26143,-0.001476456294768,0.003668968565762,0.040451895445585,37914,-1126,-2134,-2975,0.940250933170319 +26145,-0.006307676900178,0.00188362156041,0.040663190186024,37914,-1124,-2619,-2771,0.93563312292099 +26147,-0.009245433844626,0.000452819280326,0.038770698010922,37914,-1243,-2632,-2980,0.931498050689697 +26149,-0.004569810349494,-0.014540812000632,0.038757491856814,37914,-1834,-1400,-2787,0.928259432315826 +26151,0.000958490942139,-0.0161745660007,0.042521230876446,37914,-1994,-2368,-2947,0.927684247493744 +26153,0.000900537648704,-0.026061980053783,0.046962965279818,37914,-1590,-1570,-2683,0.923154890537262 +26155,-0.003717780578882,-0.025777690112591,0.045706398785114,37914,-1201,-2351,-2917,0.919419765472412 +26157,-0.007931323722005,-0.030579190701246,0.04388502985239,37914,-1149,-1848,-2711,0.921259820461273 +26159,-0.013234789483249,-0.022483214735985,0.043912123888731,37914,-1012,-2941,-2922,0.927016973495483 +26161,-0.008016193285584,-0.023136658594012,0.045390114188194,37914,-1818,-2245,-2686,0.935681998729706 +26163,-0.010259741917253,-0.020586771890521,0.043822225183249,37914,-1271,-2556,-2915,0.93706887960434 +26165,-0.014764897525311,-0.018024884164333,0.043711427599192,37914,-1006,-2540,-2698,0.93915581703186 +26167,-0.013267827220261,-0.020768903195858,0.045844614505768,37914,-1489,-2161,-2894,0.940806567668915 +26169,-0.010661985725165,-0.016588868573308,0.044672083109617,37914,-1583,-2669,-2679,0.942052781581879 +26171,-0.005508542060852,-0.020842069759965,0.040962778031826,37914,-1859,-2039,-2920,0.942385256290436 +26173,0.001386599382386,-0.017164742574096,0.040700633078814,38272,-2086,-2616,-2719,0.939604580402374 +26175,0.005699032917619,-0.024518227204681,0.044628415256739,38272,-1962,-1752,-2888,0.942214906215668 +26177,0.005540479440242,-0.022511662915349,0.045964445918799,38272,-1650,-2394,-2649,0.941796362400055 +26191,0.018690105527639,-0.005433908198029,0.047156266868115,38272,-1734,-3068,-2837,0.951373755931854 +26193,0.025242269039154,-0.007254115305841,0.048820447176695,38272,-2491,-2327,-2583,0.959775924682617 +26195,0.032633658498526,-0.003977038431913,0.046438556164503,38272,-2616,-2746,-2834,0.95689994096756 +26197,0.037378925830126,-0.003983845934272,0.044312831014395,38272,-2574,-2487,-2628,0.954901397228241 +26199,0.03748831152916,-1.79276084963931E-05,0.041131086647511,38272,-2183,-2845,-2863,0.953526556491852 +26201,0.036706283688545,0.004471344873309,0.036854848265648,38272,-2184,-2948,-2709,0.956323206424713 +26203,0.040044978260994,0.004819732625037,0.033580306917429,38272,-2470,-2653,-2908,0.954821884632111 +26205,0.036301121115685,0.020059341564775,0.037995111197233,38272,-1984,-3997,-2689,0.95202374458313 +26207,0.035607803612948,0.021298035979271,0.046011190861464,38272,-2136,-2962,-2816,0.950777173042297 +26209,0.034935723990202,0.028762754052878,0.047096408903599,38272,-2200,-3589,-2575,0.946297645568848 +26211,0.037722922861576,0.015947433188558,0.046489410102367,38701,-2433,-1890,-2805,0.945440828800201 +26213,0.032047815620899,0.017551558092237,0.045051749795675,38701,-1812,-2988,-2591,0.947592258453369 +26215,0.0237095952034,0.021432371810079,0.041018515825272,38701,-1452,-3171,-2835,0.953501403331757 +26217,0.018413728103042,0.022217364981771,0.036058012396097,38701,-1624,-3012,-2690,0.954744160175324 +26219,0.009177841246128,0.034964602440596,0.03493570163846,38701,-1188,-4008,-2870,0.953565716743469 +26221,-0.001064286916517,0.042864937335253,0.035662494599819,38701,-954,-3867,-2688,0.950352370738983 +26223,-0.005602479912341,0.048870597034693,0.039712660014629,38701,-1312,-3742,-2831,0.946894586086273 +26225,-0.002698618918657,0.045575488358736,0.042722061276436,38701,-1879,-3122,-2598,0.943157494068146 +26227,0.00066581799183,0.050855934619904,0.043134696781635,38701,-1969,-3737,-2801,0.940654814243317 +26229,0.00355175184086,0.043022189289332,0.045357409864664,38701,-1988,-2772,-2560,0.943104028701782 +26231,-0.003043808043003,0.031487490981817,0.045439250767231,38701,-1207,-2271,-2777,0.942174911499023 +26233,-0.016339395195246,0.025410553440452,0.043489519506693,38701,-505,-2627,-2574,0.946053862571716 +26235,-0.02412942238152,0.021009983494878,0.042387571185827,38701,-814,-2641,-2790,0.945956766605377 +26237,-0.029569648206234,0.027979588136077,0.042155135422945,38701,-836,-3603,-2582,0.950088798999786 +26239,-0.033412571996451,0.027324017137289,0.045334413647652,38701,-951,-3008,-2763,0.956168711185455 +26241,-0.037460587918758,0.032478861510754,0.048806507140398,38701,-790,-3545,-2496,0.961709141731262 +26243,-0.037043754011393,0.024661116302013,0.047655522823334,38701,-1187,-2465,-2738,0.965666472911835 +26245,-0.043128792196512,0.02435358799994,0.046061187982559,38701,-538,-3027,-2520,0.961000680923462 +26247,-0.044985178858042,0.023591944947839,0.045969117432833,38701,-892,-2961,-2742,0.958978593349457 +26249,-0.040942471474409,0.023647110909224,0.044723980128765,38701,-1287,-3050,-2528,0.958644688129425 +26251,-0.036009840667248,0.030015505850315,0.046287156641483,38701,-1490,-3569,-2732,0.9584521651268 +26253,-0.031825512647629,0.028782144188881,0.047982480376959,38701,-1434,-3054,-2481,0.957723438739777 +26255,-0.028878131881356,0.030125027522445,0.051331821829081,38701,-1438,-3220,-2689,0.957522869110107 +26257,-0.029282810166478,0.018970932811499,0.055799428373575,38701,-1137,-2187,-2380,0.959304571151733 +26259,-0.038654755800963,0.018484864383936,0.053898364305496,38701,-405,-2926,-2662,0.964682281017303 +26261,-0.041249088943005,0.010290431790054,0.05285232141614,38701,-776,-2258,-2406,0.965649306774139 +26263,-0.043503228574991,0.008319276385009,0.054458048194647,38701,-829,-2673,-2649,0.96642804145813 +26265,-0.04822164773941,0.021900586783886,0.055013176053763,38701,-484,-4005,-2371,0.970003426074982 +26267,-0.045539759099484,0.023852756246924,0.052508994936943,38701,-1133,-3181,-2653,0.97302234172821 +26269,-0.034993354231119,0.016891954466701,0.048805546015501,38701,-1761,-2458,-2435,0.976771056652069 +26271,-0.027966745197773,0.012967049144209,0.051654014736414,38701,-1679,-2606,-2650,0.977223098278046 +26273,-0.033332914113999,0.025302145630121,0.052569840103388,38701,-648,-3989,-2382,0.975125253200531 +26275,-0.033400386571884,0.027165355160832,0.051433030515909,38701,-1080,-3232,-2642,0.978432416915894 +26277,-0.027287723496556,0.027166211977601,0.051491376012564,38701,-1552,-3147,-2385,0.979884743690491 +26279,-0.022138623520732,0.020915970206261,0.051064506173134,38701,-1603,-2570,-2636,0.983290493488312 +26281,-0.017937103286386,0.01858776062727,0.051115363836289,38701,-1535,-2843,-2381,0.9812793135643 +26283,-0.021551627665758,0.028655968606472,0.050502862781286,38701,-973,-3855,-1914,0.975425839424133 +26285,-0.023105140775442,0.024221539497376,0.049447536468506,39898,-1031,-2788,-1651,0.972905278205872 +26287,-0.020409582182765,0.026182306930423,0.048937931656838,39898,-1428,-3245,-1868,0.972954511642456 +26289,-0.012235144153237,0.015567638911307,0.051286410540342,39898,-1916,-2218,-1572,0.976415574550629 +26291,-0.012988524511457,0.024632219225168,0.049280796200037,39898,-1283,-3737,-1808,0.979937732219696 +26293,-0.009664357639849,0.028441784903407,0.042819738388062,39898,-1610,-3473,-1615,0.979755461215973 +26295,0.004119849763811,0.019045444205403,0.038175739347935,39898,-2568,-2345,-1829,0.970072627067566 +26297,0.010238812305033,0.017182856798172,0.035880498588085,39898,-2119,-2899,-1642,0.963177800178528 +26299,0.006709553766996,0.01824177801609,0.034281738102436,39898,-1369,-3089,-1801,0.96466600894928 +26301,0.006399988662452,0.030543811619282,0.027903567999601,39898,-1596,-4139,-1682,0.966641783714294 +26303,0.015903759747744,0.035527940839529,0.02124915458262,39898,-2436,-3631,-1838,0.970059037208557 +26305,0.016550224274397,0.040729857981205,0.01327305752784,39898,-1840,-3806,-1802,0.972042798995972 +26307,0.00939798168838,0.033588889986277,0.006283637136221,39898,-1157,-2752,-1890,0.976412832736969 +26309,0.008675155229867,0.023931195959449,0.004744756966829,39898,-1623,-2477,-1852,0.976937115192413 +26311,0.012933874502778,0.016684869304299,0.008249747566879,39898,-2029,-2510,-1827,0.977022349834442 +26313,0.01173618901521,0.019505674019456,0.007784568704665,39898,-1641,-3303,-1767,0.975541055202484 +26315,0.00590523192659,0.026252284646034,0.001494942582212,39898,-1211,-3656,-1823,0.976798176765442 +26317,0.003996957559139,0.010736608877778,-0.004811173770577,39898,-1471,-1850,-1866,0.978946030139923 +26319,0.003600128926337,0.004130317363888,-0.010087692178786,39898,-1570,-2384,-1855,0.98386287689209 +26321,0.007693318184465,0.004673210438341,-0.013723304495216,39898,-1969,-2903,-1878,0.983522593975067 +26323,0.012603275477886,0.011933370493353,-0.017249193042517,40649,-2084,-3489,-1811,0.977625906467438 +26341,-0.009214420802891,0.006596333347261,-0.040185168385506,40649,-1587,-3220,-1951,0.984669089317322 +26343,-0.002235184656456,0.01558240968734,-0.045661386102438,40649,-2011,-3668,-1769,0.985576272010803 +26345,0.001993710175157,0.004514865577221,-0.046061459928751,40649,-1282,-2846,-1727,0.981253147125244 +26347,0.001993710175157,0.004514865577221,-0.047622609883547,40649,-1196,-3257,-1949,0.986503481864929 +26349,-0.000276515609585,0.011954475194216,-0.051838222891092,40649,-1683,-3204,-1723,0.992750406265259 +26351,0.005538950674236,0.011446229182184,-0.057745285332203,40649,-2045,-2951,-2025,0.996694624423981 +26353,0.005538950674236,0.011446229182184,-0.057745285332203,40649,-2045,-2951,-2025,0.996694624423981 +26355,0.003623279742897,0.016854155808687,-0.068295784294605,40649,-1467,-3762,-2108,0.990711092948914 +26357,0.005000901408494,0.021828155964613,-0.073139987885952,40649,-1719,-3484,-1786,0.988086640834808 +26359,0.006229832302779,0.016920881345868,-0.075802356004715,41292,-1739,-2734,-2156,0.982747614383698 +26361,0.004274384118617,0.008443355560303,-0.078582435846329,41292,-1473,-2334,-1784,0.986392140388489 +26363,0.004274384118617,0.008443355560303,-0.078582435846329,41292,-1473,-2334,-1784,0.986392140388489 +26365,0.006912895478308,0.015897031873465,-0.085084728896618,41292,-1817,-3682,-1791,0.997153699398041 +26367,0.01294600404799,0.015871450304985,-0.088663622736931,41292,-2208,-3076,-2231,0.999500751495361 +26369,0.015172474086285,0.020780446007848,-0.094724372029305,41292,-1940,-3477,-1819,0.996982038021088 +26371,0.011650046333671,0.025336340069771,-0.09632420539856,41292,-1518,-3547,-2284,0.997731268405914 +26373,0.011650046333671,0.025336340069771,-0.09632420539856,41292,-1518,-3547,-2284,0.997731268405914 +26375,0.009516417048872,0.031544119119644,-0.094003967940807,41292,-1676,-3511,-2220,0.996985554695129 +26377,0.008947872556746,0.022795855998993,-0.096016094088554,41292,-1665,-2544,-1756,1.00187563896179 +26379,0.006642959546298,0.021531378850341,-0.099225267767906,41292,-1509,-3103,-2246,1.00818872451782 +26381,0.011691118590534,0.011427793651819,-0.10297104716301,41292,-2109,-2292,-1768,1.01966559886932 +26383,0.011691118590534,0.011427793651819,-0.10297104716301,41292,-2109,-2292,-1768,1.01966559886932 +26385,0.017974870279431,0.020035792142153,-0.106256827712059,41292,-1926,-3667,-1756,1.02806413173676 +26387,0.016067460179329,0.020668182522059,-0.107385367155075,41292,-1716,-3243,-2272,1.02773439884186 +26389,0.014909652993083,0.023851256817579,-0.109809681773186,41292,-1727,-3437,-1746,1.02209103107452 +26391,0.015221105888486,0.016732020303607,-0.111888952553272,41292,-1860,-2630,-2291,1.01300799846649 +26393,0.015936996787787,0.013932703994215,-0.112675458192825,41292,-1882,-2873,-1732,1.00505936145782 +26395,0.017373405396938,0.018043337389827,-0.112313278019428,41292,-1974,-3459,-2262,1.00141334533691 +26397,0.022227834910154,0.022419171407819,-0.115734785795212,41292,-2275,-3515,-1719,1.00550973415375 +26399,0.026030037552118,0.028480587527156,-0.122254088521004,41292,-2296,-3776,-2346,1.01037800312042 +26401,0.025926085188985,0.025789706036449,-0.127522900700569,41292,-1984,-3069,-1768,1.01621699333191 +26403,0.021545376628637,0.027631163597107,-0.130504742264748,41292,-1655,-3470,-2412,1.02003920078278 +26405,0.015655424445868,0.029807517305017,-0.129202112555504,41292,-1432,-3486,-1749,1.02281546592712 +26407,0.012287026271224,0.033229447901249,-0.12919220328331,41292,-1590,-3681,-2366,1.02230727672577 +26409,0.013437736779451,0.037690494209528,-0.131795659661293,41292,-1912,-3775,-1736,1.01989114284515 +26411,0.015238447114825,0.036461494863033,-0.133252128958702,41292,-2009,-3421,-2383,1.01821637153625 +26413,0.015424508601427,0.03448897972703,-0.137838914990425,41292,-1878,-3284,-1747,1.01540756225586 +26415,0.019033333286643,0.023202057927847,-0.144011169672012,41292,-2208,-2500,-2481,1.01800119876862 +26417,0.019732987508178,0.015930958092213,-0.149378314614296,41292,-1986,-2648,-1798,1.02217245101929 +26419,0.017133176326752,0.011412044987083,-0.152724340558052,41292,-1747,-2796,-2556,1.02792513370514 +26421,0.010962416417897,0.008746112696826,-0.15309701859951,41292,-1377,-2879,-1797,1.03126704692841 +26423,0.007155064959079,0.012641537934542,-0.153342843055725,41292,-1508,-3422,-2536,1.03157830238342 +26425,0.005952080711722,0.016324216499925,-0.153732508420944,41292,-1666,-3446,-1774,1.02960169315338 +26427,0.000285577436443,0.019230913370848,-0.154022201895714,41292,-1268,-3464,-2517,1.02500379085541 +26429,-0.011098833754659,0.015219559893012,-0.156612828373909,41292,-694,-2886,-1767,1.02289760112762 +26431,-0.015733765438199,0.002914086915553,-0.158486619591713,41292,-1081,-2112,-2543,1.02310252189636 +26433,-0.011660563759506,-0.004118816927075,-0.161840736865997,41292,-1788,-2392,-1777,1.02448785305023 +26435,-0.003512338269502,-0.00923050288111,-0.16557565331459,41292,-2188,-2431,-2601,1.02825570106506 +26437,0.001349558937363,-0.004023282323033,-0.163960978388786,41292,-2030,-3265,-1767,1.02744841575623 +26439,0.001140668522567,0.00248487573117,-0.163810357451439,41292,-1671,-3442,-2555,1.02718055248261 +26441,0.001759444829077,-0.003407624084502,-0.172664701938629,41292,-1735,-2477,-1801,1.02967274188995 +26443,0.001269816304557,-0.008336760103703,-0.179517164826393,41292,-1658,-2432,-2716,1.03217482566834 +26445,0.001514035626315,-0.009837289340794,-0.178924486041069,41292,-1708,-2691,-1822,1.03317224979401 +26447,-0.009900095872581,0.00395101448521,-0.174783051013947,41292,-692,-3978,-2637,1.03343451023102 +26449,-0.021714471280575,0.012721376493573,-0.174617081880569,41292,-508,-3750,-1769,1.03653299808502 +26451,-0.025214519351721,0.020474944263697,-0.183734074234962,41292,-1004,-3826,-2720,1.03821647167206 +26453,-0.024368487298489,0.02012549340725,-0.193178877234459,41292,-1367,-3211,-1874,1.03887808322907 +26455,-0.025809766724706,0.013930930756033,-0.196429774165154,41292,-1124,-2722,-2849,1.03676068782806 +26457,-0.029753478243947,0.019508400931954,-0.19607275724411,41292,-936,-3632,-1875,1.03172504901886 +26459,-0.03169584646821,0.025081604719162,-0.197557836771011,41292,-977,-3752,-2842,1.02786862850189 +26461,-0.03163930401206,0.022184690460563,-0.200595587491989,41292,-1181,-3072,-1886,1.02148830890656 +26463,-0.033885754644871,0.016205413267016,-0.201084285974503,41292,-913,-2790,-2864,1.0164760351181 +26465,-0.033888261765242,0.017126154154539,-0.203977957367897,41292,-1130,-3279,-1890,1.01637995243073 +26467,-0.032166987657547,0.021652139723301,-0.209527879953384,41292,-1213,-3643,-2945,1.02108120918274 +26469,-0.028139242902398,0.018449135124683,-0.214371427893639,41292,-1488,-3012,-1944,1.02805840969086 +26471,-0.024448519572616,0.014527969062328,-0.21722012758255,41292,-1466,-2942,-3019,1.03370440006256 +26473,-0.025035452097654,0.012674012221396,-0.220313757658005,41292,-1191,-3033,-1969,1.03796195983887 +26475,-0.023810343816877,0.007201679982245,-0.220073103904724,41292,-1297,-2715,-3036,1.0410521030426 +26477,-0.023424671962857,0.012876249849796,-0.218163624405861,41292,-1275,-3580,-1938,1.04305922985077 +26479,-0.021118476986885,0.016305826604366,-0.219963237643242,41292,-1410,-3495,-3019,1.04083645343781 +26481,-0.023909330368042,0.013960608281195,-0.224777474999428,41292,-1033,-3027,-1967,1.03501105308533 +26483,-0.028404273092747,0.012900219298899,-0.229072213172913,41292,-776,-3125,-3111,1.02864122390747 +26485,-0.030977685004473,0.020731370896101,-0.230477079749107,41292,-933,-3859,-1992,1.02451586723328 +26487,-0.037177640944719,0.029095362871885,-0.231997400522232,41292,-487,-4074,-3131,1.03027307987213 +26489,-0.03833669796586,0.021576410159469,-0.235490903258324,41292,-909,-2784,-2013,1.04018151760101 +26491,-0.0342181250453,0.02000436000526,-0.238322079181671,41292,-1265,-3220,-3193,1.04828143119812 +26493,-0.032097682356835,0.02380814217031,-0.237477689981461,41292,-1217,-3635,-2014,1.05766224861145 +26495,-0.033894822001457,0.021452855318785,-0.234556496143341,41292,-842,-3193,-3135,1.05930864810944 +26497,-0.035753313452005,0.017910024151206,-0.235710933804512,41292,-865,-3033,-1988,1.05474972724915 +26499,-0.034350160509348,0.01517540961504,-0.242345198988914,41292,-1053,-3075,-3214,1.04683136940002 +26501,-0.032493218779564,0.019659655168653,-0.24894155561924,41292,-1163,-3639,-2067,1.03638505935669 +26503,-0.028447372838855,0.022625153884292,-0.246634870767593,41292,-1321,-3610,-3253,1.03223073482513 +26505,-0.023015411570668,0.015638327226043,-0.242277964949608,41292,-1543,-2769,-2009,1.03413236141205 +26507,-0.023427549749613,0.010934766381979,-0.244480445981026,41292,-1068,-2874,-3216,1.03441023826599 +26509,-0.023277433589101,0.005346319638193,-0.247214332222939,41292,-1150,-2724,-2032,1.03139400482178 +26511,-0.021604413166642,0.006739334668964,-0.250941634178162,41292,-1236,-3241,-3280,1.03055953979492 +26513,-0.019769275560975,0.006439693737775,-0.253836989402771,41292,-1311,-3119,-2066,1.03010284900665 +26515,-0.019404042512179,0.003703732509166,-0.253531396389008,41292,-1171,-2895,-3300,1.02871644496918 +26517,-0.022605152800679,0.005807467270643,-0.255242437124252,41292,-900,-3282,-2066,1.0318797826767 +26519,-0.023509504273534,0.003723734524101,-0.257577627897263,41292,-1011,-2951,-3338,1.03527820110321 +26521,-0.022892432287335,0.002091862494126,-0.262946546077728,41292,-1160,-2962,-2109,1.04109644889832 +26523,-0.018244972452521,-0.002358143450692,-0.264237821102142,41292,-1478,-2684,-3407,1.04609346389771 +26525,-0.014854862354696,-0.003193256445229,-0.261907458305359,41292,-1466,-2941,-2093,1.04866659641266 +26527,-0.015036230906844,-0.004427636507899,-0.26314902305603,41292,-1168,-2875,-3386,1.05313444137573 +26529,-0.018359312787652,-0.00982579216361,-0.265425324440002,41292,-926,-2516,-2109,1.05488550662994 +26531,-0.023158885538578,-0.011952301487327,-0.26581084728241,41292,-702,-2683,-3409,1.05181992053986 +26533,-0.020868545398116,-0.014832694083452,-0.26757749915123,41292,-1281,-2617,-2115,1.04873621463776 +26535,-0.012983994558454,-0.02141653560102,-0.270411908626556,41292,-1775,-2206,-3455,1.04419207572937 +26537,-0.012787746265531,-0.018604323267937,-0.268834382295609,41292,-1242,-2961,-2116,1.04074776172638 +26539,-0.013572212308645,-0.015010489150882,-0.268538743257523,41292,-1135,-3030,-3425,1.03891861438751 +26541,-0.011256606318057,-0.013236366212368,-0.271240413188934,41292,-1410,-2956,-2125,1.03937590122223 +26543,-0.001095813931897,-0.016801225021482,-0.270479321479797,41292,-2114,-2478,-3441,1.0397242307663 +26545,0.000786908261944,-0.019581085070968,-0.269987881183624,41292,-1550,-2530,-2109,1.0415745973587 +26547,-0.005618334747851,-0.020620282739401,-0.272404849529266,41292,-853,-2582,-3456,1.04497969150543 +26549,-0.001448864699341,-0.021744458004832,-0.273511439561844,41292,-1679,-2605,-2126,1.04850709438324 +26551,0.003489705966786,-0.012721669860184,-0.273845702409744,41292,-1813,-3417,-3466,1.05372488498688 +26553,0.007749643176794,-0.010913504287601,-0.275444030761719,41292,-1819,-2962,-2132,1.05259573459625 +26555,0.0085220746696,-0.002595672383904,-0.278479069471359,41292,-1607,-3533,-3514,1.04814922809601 +26557,0.010017782449722,0.003290254622698,-0.281966835260391,41292,-1658,-3455,-2171,1.05168879032135 +26559,0.017575055360794,0.000279215135379,-0.284350275993347,41292,-2246,-2768,-3577,1.05631864070892 +26561,0.021321656182408,-0.000663141021505,-0.286513030529022,41292,-1991,-2908,-2197,1.05989789962769 +26563,0.021167028695345,-8.07148535386659E-05,-0.288826555013657,41292,-1745,-3016,-3625,1.06122934818268 +26565,0.020386975258589,0.004324947483838,-0.289228320121765,41292,-1661,-3362,-2211,1.05930376052856 +26567,0.019204989075661,0.008530432358384,-0.28844878077507,41292,-1641,-3409,-3616,1.05619955062866 +26569,0.02277428470552,0.014380183070898,-0.289054572582245,41292,-2013,-3611,-2206,1.04911386966705 +26571,0.02912200987339,0.020285384729505,-0.29355400800705,41292,-2353,-3721,-3672,1.04310083389282 +26573,0.034003730863333,0.020604021847248,-0.299728870391846,41292,-2279,-3309,-2276,1.03727221488953 +26575,0.035589620471001,0.025732779875398,-0.301943004131317,41292,-2134,-3759,-3768,1.03119766712189 +26577,0.038131326436997,0.029671929776669,-0.298708081245422,41292,-2186,-3707,-2266,1.0290242433548 +26579,0.038443479686976,0.030712736770511,-0.29367670416832,41292,-2110,-3565,-3668,1.02978360652924 +26581,0.033727146685124,0.030205335468054,-0.290587604045868,41292,-1620,-3408,-2207,1.03655672073364 +26583,0.036818355321884,0.025533663108945,-0.289093613624573,41292,-2308,-3091,-3610,1.04418909549713 +26585,0.041175521910191,0.028852220624685,-0.289543360471725,41292,-2395,-3674,-2195,1.05338501930237 +26587,0.044870931655169,0.024119328707457,-0.292136579751968,41292,-2507,-3077,-3641,1.05743634700775 +26589,0.041854418814182,0.023888783529401,-0.297429889440536,41292,-1899,-3360,-2246,1.05578577518463 +26591,0.032684452831745,0.033507697284222,-0.301753401756287,41292,-1405,-4274,-3752,1.05493116378784 +26593,0.030745243653655,0.036319520324469,-0.306317150592804,41292,-1834,-3772,-2304,1.05525517463684 +26595,0.038008105009794,0.03444841504097,-0.310685813426971,41292,-2695,-3475,-3855,1.05779159069061 +26597,0.050947293639183,0.029765848070383,-0.311869323253632,41292,-3210,-3156,-2342,1.06297445297241 +26599,0.056123036891222,0.029421906918287,-0.310330182313919,41292,-2860,-3518,-3850,1.062948346138 +26601,0.044079169631004,0.031900644302368,-0.309395134449005,41292,-1351,-3713,-2324,1.06069040298462 +26603,0.0307433065027,0.035151705145836,-0.309432566165924,41292,-1135,-3882,-3839,1.05323266983032 +26605,0.021356295794249,0.038679137825966,-0.30840939283371,41292,-1230,-3901,-2316,1.04627513885498 +26607,0.017825556918979,0.031704381108284,-0.309269368648529,41292,-1632,-3102,-3836,1.04249930381775 +26609,0.016911763697863,0.023187762126327,-0.313497513532639,41292,-1782,-2829,-2350,1.03958106040955 +26611,0.01676013879478,0.019121075049043,-0.31376126408577,41292,-1865,-3109,-3888,1.04223918914795 +26613,0.020875891670585,0.018803087994456,-0.310939460992813,41292,-2207,-3359,-2333,1.04054868221283 +26615,0.01493130158633,0.022682266309857,-0.309131354093552,41292,-1430,-3753,-3833,1.03645145893097 +26617,0.006610099226236,0.017926434054971,-0.309845417737961,41292,-1119,-3038,-2324,1.03333389759064 +26619,0.000104550104879,0.01974412240088,-0.311057507991791,41292,-1159,-3573,-3855,1.03281366825104 +26621,5.98845108470414E-05,0.020457670092583,-0.311947673559189,41292,-1619,-3476,-2338,1.03723394870758 +26623,0.002024612855166,0.017771415412426,-0.310851156711578,41292,-1800,-3229,-3852,1.04316055774689 +26625,-0.002324531320483,0.012429188936949,-0.311164438724518,41292,-1279,-2936,-2332,1.04735434055328 +26627,-0.006513044238091,0.009475083090365,-0.314181059598923,41292,-1218,-3087,-3891,1.04980158805847 +26629,-0.007251354400069,0.014840238727629,-0.316926658153534,41292,-1465,-3743,-2371,1.05137073993683 +26631,-0.004303732421249,0.007616357877851,-0.315373659133911,41292,-1768,-2746,-3905,1.05317986011505 +26633,-0.00362152652815,0.000761003058869,-0.312421560287476,41292,-1619,-2669,-2340,1.04951536655426 +26635,-0.005665300413966,-0.000743950309698,-0.31054362654686,41292,-1381,-3017,-3848,1.04539132118225 +26651,0.016173247247934,-0.003759822342545,-0.320079445838928,41292,-2065,-2440,-3960,1.05116736888886 +26653,0.016317371279001,-0.00812734849751,-0.317563384771347,41292,-1884,-2708,-2376,1.0432550907135 +26655,0.011107210069895,-0.012700048275292,-0.313750028610229,41292,-1466,-2582,-3886,1.03932774066925 +26657,0.010280776768923,-0.015359615907073,-0.3120097219944,41292,-1737,-2718,-2338,1.03714275360107 +26659,0.010177073068917,-0.007802263833582,-0.312456041574478,41292,-1820,-3528,-3871,1.03807556629181 +26661,0.012013142928481,-0.008894533850253,-0.3126460313797,41292,-1960,-2918,-2342,1.04137051105499 +26663,0.011171701364219,-0.006091111339629,-0.310485363006592,41292,-1782,-3212,-3847,1.04349219799042 +26665,0.010339288972318,-0.010799686424434,-0.312279731035233,41292,-1752,-2628,-2339,1.05077695846558 +26667,0.011857584118843,-0.011931867338717,-0.319112539291382,41292,-1959,-2820,-3948,1.05134868621826 +26669,0.011576640419662,-0.001987141324207,-0.325638115406036,41292,-1815,-3795,-2431,1.05184316635132 +26671,0.010918594896793,0.008332195691764,-0.326942145824432,41292,-1791,-3962,-4042,1.0469057559967 +26673,0.016383867710829,0.013635152950883,-0.324310153722763,41292,-2300,-3687,-2424,1.04026961326599 +26675,0.02613534219563,0.011168197728694,-0.320821791887283,41292,-2802,-3098,-3972,1.03707015514374 +26677,0.032560750842095,0.010192836634815,-0.316182821989059,41292,-2614,-3191,-2369,1.02931177616119 +26679,0.029536724090576,0.007886739447713,-0.315211176872253,41292,-1958,-3059,-3906,1.028076171875 +26681,0.023086592555046,0.004506994504482,-0.320276468992233,41292,-1571,-2938,-2398,1.0310959815979 +26683,0.015020817518234,0.010261570103467,-0.326205551624298,41292,-1362,-3678,-4036,1.03267359733582 +26685,0.010734026320279,0.012484320439398,-0.328717201948166,41292,-1555,-3456,-2458,1.03623306751251 +26687,0.009742718189955,0.021602736786008,-0.328988522291184,41292,-1802,-4114,-4072,1.03711998462677 +26689,0.012035182677209,0.027113690972328,-0.329804211854935,41292,-2052,-3910,-2467,1.0436418056488 +26691,0.016473036259413,0.025319539010525,-0.331649363040924,41292,-2326,-3406,-4106,1.04567921161652 +26693,0.016080437228084,0.019343947991729,-0.331486046314239,41292,-1930,-2987,-2482,1.04308104515076 +26695,0.006905289832503,0.010647339746356,-0.330977290868759,41292,-1209,-2690,-4100,1.04034459590912 +26697,-0.011419490911067,0.019291484728456,-0.329744189977646,41292,-260,-4039,-2473,1.03227865695953 +26699,-0.029290670529008,0.031065262854099,-0.321212410926819,41292,5,-4501,-3987,1.03394401073456 +26701,-0.034724604338408,0.035662792623043,-0.316064298152924,41292,-840,-4000,-2380,1.0357027053833 +26703,-0.033240888267756,0.036391686648131,-0.320669829845428,41292,-1286,-3809,-3982,1.03426766395569 +26705,-0.033197864890099,0.0255834069103,-0.326181411743164,41292,-1241,-2769,-2450,1.03505003452301 +26707,-0.040080297738314,0.019921146333218,-0.328947961330414,41292,-548,-3089,-4081,1.03488147258759 +26709,-0.046880014240742,0.012213797308505,-0.329674929380417,41292,-535,-2808,-2477,1.03690123558044 +26711,-0.053157597780228,0.012374436482787,-0.328922271728516,41292,-360,-3388,-4083,1.03408086299896 +26713,-0.05598496645689,0.015949251130223,-0.324818968772888,41292,-664,-3675,-2446,1.03221607208252 +26715,-0.059187140315771,0.016210082918406,-0.321936637163162,41292,-458,-3461,-4003,1.03137540817261 +26717,-0.063847362995148,0.020008381456137,-0.324443757534027,41292,-392,-3755,-2444,1.03206539154053 +26719,-0.06292174756527,0.015125058591366,-0.325914293527603,41292,-668,-3082,-4051,1.03212416172028 +26721,-0.061344020068646,0.010874945670366,-0.324239522218704,41292,-846,-3054,-2445,1.03567922115326 +26723,-0.061607703566551,0.003419112181291,-0.322939336299896,41292,-580,-2713,-4018,1.04432487487793 +26725,-0.060877729207277,0.001856668619439,-0.323943018913269,41292,-764,-3118,-2444,1.04679238796234 +26727,-0.057427022606135,0.002059739548713,-0.327052026987076,41292,-888,-3241,-4068,1.04638779163361 +26729,-0.055572647601366,0.004532785154879,-0.329727709293365,41292,-895,-3446,-2486,1.0454648733139 +26731,-0.053022220730782,0.010124813765287,-0.330296814441681,41292,-874,-3756,-4109,1.04240417480469 +26733,-0.053976271301508,0.0074143265374,-0.330506920814514,41292,-693,-3119,-2494,1.04341244697571 +26735,-0.046642452478409,-0.00408989796415,-0.330658465623856,40989,-1296,-2305,-4116,1.03950381278992 +26737,-0.035683777183294,-0.008794223889709,-0.330377399921417,40989,-1788,-2741,-2496,1.03731215000153 +26739,-0.024715596809983,-0.015754461288452,-0.328733921051025,40989,-1895,-2442,-4096,1.03604900836945 +26741,-0.02256366610527,-0.003650788217783,-0.327596455812454,40989,-1334,-4013,-2479,1.03743314743042 +26743,-0.021327245980501,-0.001268647960387,-0.32760214805603,40989,-1246,-3344,-4084,1.04340124130249 +26745,-0.019654164090753,0.001441785949282,-0.3311667740345,40989,-1333,-3413,-2506,1.04503762722015 +26747,-0.014239706099033,0.001213982701302,-0.331208020448685,40989,-1650,-3194,-4129,1.04454040527344 +26749,-0.010159146040678,0.005515073891729,-0.328145653009415,40989,-1635,-3586,-2488,1.04129076004028 +26751,-0.000983871286735,0.01521157938987,-0.331165790557861,40989,-2127,-4134,-4132,1.03551602363586 +26753,0.010656413622201,0.019668405875564,-0.333718031644821,40989,-2474,-3807,-2529,1.0336697101593 +26755,0.016291966661811,0.024762488901615,-0.33166316151619,40989,-2159,-3965,-4140,1.02831208705902 +26757,0.016078343614936,0.02342108078301,-0.330938518047333,40989,-1710,-3456,-2513,1.02737009525299 +26759,0.01333839725703,0.019261837005615,-0.33486145734787,40989,-1524,-3225,-4181,1.02926158905029 +26761,0.014679784886539,0.018134342506528,-0.337014585733414,40989,-1809,-3404,-2558,1.02950203418732 +26763,0.022362807765603,0.010855288244784,-0.337353736162186,40989,-2428,-2877,-4214,1.03200840950012 +26765,0.029505826532841,0.010456043295562,-0.336067765951157,40989,-2449,-3351,-2556,1.03239488601685 +26767,0.033072993159294,0.005036687944084,-0.333595007658005,40989,-2318,-2922,-4174,1.03930497169495 +26769,0.034380577504635,0.005581458099186,-0.332884967327118,40989,-2117,-3352,-2537,1.04588460922241 +26771,0.033887919038534,0.014071334153414,-0.332222700119019,40792,-2060,-4069,-4161,1.05232775211334 +26773,0.031495410948992,0.016818078234792,-0.328660607337952,40792,-1827,-3678,-2511,1.05448925495148 +26775,0.030302092432976,0.0236986130476,-0.326046675443649,40792,-1973,-4124,-4091,1.05414438247681 +26777,0.03462627530098,0.025281587615609,-0.327894777059555,40792,-2370,-3729,-2508,1.05548238754272 +26779,0.032563976943493,0.035636276006699,-0.331163972616196,40792,-1971,-4578,-4153,1.05572164058685 +26781,0.026414204388857,0.036177977919579,-0.329804390668869,40792,-1520,-3828,-2524,1.0559948682785 +26783,0.025326577946544,0.033182762563229,-0.326909124851227,40792,-1940,-3596,-4106,1.05494010448456 +26785,0.03177060186863,0.034644335508347,-0.330711275339127,40792,-2515,-3888,-2532,1.05253994464874 +26787,0.036941763013601,0.033989109098911,-0.337965101003647,40792,-2584,-3796,-4239,1.0489456653595 +26789,0.03703036904335,0.035485211759806,-0.342369496822357,40792,-2154,-3919,-2616,1.04258012771606 +26791,0.033760469406843,0.032645959407091,-0.340958833694458,40792,-1939,-3633,-4278,1.04144895076752 +26793,0.026859378442168,0.034797128289938,-0.338060230016708,40792,-1524,-3973,-2591,1.04108476638794 +26795,0.023560790345073,0.032809901982546,-0.337378531694412,40792,-1785,-3699,-4240,1.04145741462708 +26797,0.029207453131676,0.018947131931782,-0.338992178440094,40792,-2468,-2612,-2602,1.03751444816589 +26799,0.02557416446507,0.017297137528658,-0.341903686523437,40792,-1795,-3487,-4298,1.03236818313599 +26801,0.017352852970362,0.017894592136145,-0.343332290649414,40792,-1316,-3640,-2636,1.02903139591217 +26803,0.005621198099107,0.032526958733797,-0.344010055065155,40792,-895,-4917,-4328,1.02959966659546 +26805,0.002464399673045,0.035203389823437,-0.34561875462532,40792,-1466,-4053,-2657,1.03206503391266 +26807,0.008003707975149,0.021343845874071,-0.345554441213608,40792,-2181,-2706,-4351,1.03690052032471 +26809,0.010263789445162,0.009913977235556,-0.344157487154007,40077,-1970,-2690,-2652,1.03889083862305 +26811,0.006364561151713,0.00683178473264,-0.344295918941498,40077,-1483,-3253,-4342,1.04214870929718 +26813,-0.002345215529203,0.015210583806038,-0.343704730272293,40077,-1007,-4190,-2654,1.04223358631134 +26815,-0.006267513614148,0.018194034695625,-0.338854223489761,40077,-1285,-3873,-4282,1.04472804069519 +26817,-0.008274032734334,0.016072556376457,-0.337740868330002,40077,-1401,-3458,-2618,1.04410433769226 +26819,-0.009357220493257,0.009764934889972,-0.341101706027985,40077,-1439,-3079,-4313,1.04407596588135 +26821,-0.008045435883105,-0.003675608662888,-0.343298673629761,40077,-1640,-2369,-2661,1.03986752033234 +26823,-0.012059507891536,-0.009747234173119,-0.342253774404526,40077,-1182,-2786,-4331,1.03391349315643 +26825,-0.018091473728418,-0.009479351341724,-0.342773407697678,40077,-966,-3265,-2662,1.0315808057785 +26827,-0.02597770281136,-0.008749075233936,-0.344406366348267,40077,-668,-3284,-4362,1.03277111053467 +26829,-0.028949119150639,-0.020363381132484,-0.345125794410706,40077,-1019,-2255,-2683,1.03522527217865 +26831,-0.026440959423781,-0.027366233989596,-0.34439554810524,40077,-1391,-2419,-4367,1.03932499885559 +26833,-0.023186944425106,-0.019962897524238,-0.345172137022018,40077,-1536,-3611,-2689,1.03667306900024 +26835,-0.022576868534088,-0.022044567391276,-0.346954673528671,40077,-1310,-2842,-4402,1.03497898578644 +26837,-0.029539369046688,-0.020926166325808,-0.345594763755798,40077,-704,-3137,-2697,1.0305210351944 +26839,-0.026644764468074,-0.02937144972384,-0.338795244693756,40077,-1396,-2252,-4311,1.02644276618958 +26841,-0.025146508589387,-0.032703541219235,-0.335649043321609,40077,-1361,-2635,-2633,1.02374744415283 +26843,-0.026098497211933,-0.03447612375021,-0.335535228252411,40077,-1114,-2639,-4277,1.02393245697021 +26845,-0.027135806158185,-0.032274752855301,-0.336181670427322,40077,-1139,-3022,-2640,1.02465879917145 +26847,-0.020363805815578,-0.029383540153504,-0.340308278799057,39719,-1753,-3044,-4337,1.02924537658691 +26849,-0.013954882510007,-0.027851287275553,-0.341394811868668,39719,-1853,-3024,-2681,1.03425276279449 +26851,-0.012155163101852,-0.022459700703621,-0.337481915950775,39719,-1524,-3322,-4308,1.03958344459534 +26853,-0.008996743708849,-0.025016393512488,-0.333657026290894,39719,-1686,-2762,-2632,1.04367506504059 +26855,-0.002575099235401,-0.027850903570652,-0.330823689699173,39719,-2009,-2632,-4233,1.0403573513031 +26857,0.00286775524728,-0.031290501356125,-0.330638766288757,39719,-2020,-2596,-2614,1.03340435028076 +26859,0.006452781148255,-0.035641834139824,-0.330569624900818,39719,-1960,-2371,-4233,1.029296875 +26861,0.006844281684607,-0.025144511833787,-0.327004313468933,39719,-1720,-3664,-2592,1.02299892902374 +26863,0.013642163015902,-0.024560401216149,-0.322929888963699,39719,-2309,-2885,-4146,1.01916301250458 +26879,0.034610103815794,-0.006889461539686,-0.333448976278305,39719,-2193,-3442,-4282,1.00126814842224 +26881,0.038159959018231,-0.004558275919408,-0.337421506643295,39719,-2461,-3325,-2679,0.999629735946655 +26883,0.044466774910688,-0.007049137726426,-0.336806178092957,39719,-2849,-2908,-4325,1.00210797786713 +26885,0.046018566936255,-0.008783331140876,-0.33771687746048,39183,-2453,-2967,-2685,1.00351452827454 +26887,0.046143610030413,-0.014029249548912,-0.33817121386528,39183,-2459,-2610,-4346,1.00793218612671 +26889,0.038616694509983,-0.005401858594269,-0.335843563079834,39183,-1720,-3752,-2676,1.01645565032959 +26891,0.037219058722258,-0.005437063984573,-0.332658231258392,39183,-2234,-3113,-4284,1.02491545677185 +26893,0.037322521209717,-0.003735483856872,-0.332623153924942,39183,-2269,-3278,-2657,1.02956557273865 +26895,0.036514479666948,-0.009242701344192,-0.334700286388397,39183,-2285,-2643,-4311,1.03203785419464 +26897,0.037075657397509,-0.01345547940582,-0.336500346660614,39183,-2319,-2708,-2687,1.02641153335571 +26899,0.031396809965372,-0.006559890694916,-0.334895998239517,39183,-1862,-3571,-4317,1.01801776885986 +26901,0.023456359282136,-0.002948106499389,-0.33223482966423,39183,-1532,-3414,-2661,1.00975322723389 +26903,0.017900796607137,-0.003381533315405,-0.331373125314712,39183,-1661,-3094,-4278,1.00602984428406 +26905,0.020520882681012,-0.014526035636664,-0.330907225608826,39183,-2256,-2187,-2654,1.00671052932739 +26907,0.024558566510677,-0.02013754285872,-0.333510011434555,39183,-2466,-2453,-4306,1.00670611858368 +26909,0.021809795871377,-0.014046601951122,-0.333533853292465,39183,-1902,-3418,-2675,1.005047082901 +26911,0.014280247502029,-0.014162972569466,-0.328765869140625,39183,-1484,-2945,-4253,1.00464355945587 +26913,0.005970093421638,-0.010347547009587,-0.327251374721527,39183,-1285,-3303,-2635,1.0086350440979 +26915,0.007881118915975,-0.01366126164794,-0.328707993030548,39183,-2065,-2709,-4255,1.01197135448456 +26917,0.006755758542568,-0.010534698143602,-0.329776406288147,39183,-1817,-3244,-2654,1.01048946380615 +26919,0.004019720479846,-0.020697597414255,-0.329569667577744,39183,-1671,-2095,-4267,1.00606834888458 +26921,-0.001771848532371,-0.025234393775463,-0.327469378709793,39183,-1364,-2474,-2641,1.0010906457901 +26923,-0.002363762352616,-0.028973186388612,-0.328059375286102,38808,-1722,-2407,-4252,0.998026192188263 +26925,-0.004181598313153,-0.035017229616642,-0.32953879237175,38808,-1615,-2211,-2657,0.997808277606964 +26927,-0.00951259676367,-0.033990483731032,-0.331030488014221,38808,-1263,-2653,-4289,0.997300744056702 +26929,-0.011401477269828,-0.028942808508873,-0.333261519670486,38808,-1503,-3076,-2685,0.996440351009369 +26931,-0.012936166487634,-0.020900391042233,-0.333474218845367,38808,-1473,-3350,-4321,0.996359825134277 +26933,-0.019688883796334,-0.023709705099464,-0.329581141471863,38808,-1030,-2577,-2663,0.999790370464325 +26935,-0.026067486032844,-0.033613182604313,-0.325916975736618,38808,-904,-1835,-4234,1.00017929077148 +26937,-0.029553009197116,-0.042795054614544,-0.326200306415558,38808,-1111,-1828,-2642,1.00380659103394 +26939,-0.024070614948869,-0.055631320923567,-0.324845969676971,38808,-1776,-1246,-4223,1.0036609172821 +26941,-0.023293741047382,-0.042737629264593,-0.321673691272736,38808,-1496,-3382,-2612,1.00659108161926 +26943,-0.025338757783175,-0.042834103107452,-0.321398586034775,38808,-1210,-2349,-4184,1.01150548458099 +26945,-0.03113910369575,-0.036761801689863,-0.324225783348083,38808,-902,-2957,-2631,1.01232147216797 +26947,-0.031164469197393,-0.033259216696024,-0.323173135519028,38808,-1243,-2744,-4206,1.01111352443695 +26949,-0.032471846789122,-0.024160092696548,-0.321357160806656,38808,-1190,-3338,-2612,1.0029034614563 +26951,-0.034335430711508,-0.013730245642364,-0.323498666286468,38808,-1040,-3543,-4211,0.994136095046997 +26953,-0.029126757755876,-0.010227959603071,-0.322701394557953,38808,-1689,-3128,-2623,0.987941265106201 +26955,-0.026354540139437,-0.000108344371256,-0.320692986249924,38808,-1490,-3735,-4180,0.9848712682724 +26957,-0.023110177367926,0.000279187661363,-0.321276813745499,38808,-1622,-3053,-2614,0.982491970062256 +26959,-0.021686399355531,0.00317515921779,-0.321952313184738,38629,-1464,-3271,-4195,0.979720056056976 +26961,-0.017253864556551,-0.004023635294288,-0.320494711399078,38629,-1782,-2447,-2610,0.98427826166153 +26963,-0.012526237405837,-0.009943902492523,-0.319928765296936,38629,-1852,-2429,-4173,0.988183856010437 +26965,-0.01130180247128,-0.00286222435534,-0.320494323968887,38629,-1634,-3481,-2611,0.996046006679535 +26967,-0.006802971009165,-0.002584958914667,-0.318206608295441,38629,-1928,-2989,-4153,0.997981190681458 +26969,-0.006258365698159,0.001444592489861,-0.317323684692383,38629,-1657,-3322,-2590,0.993623197078705 +26971,-0.00927194301039,0.000880778126884,-0.318693101406097,38629,-1350,-2982,-4159,0.992109596729279 +26973,-0.016060037538409,0.011963157914579,-0.317589908838272,38629,-990,-3978,-2592,0.9878830909729 +26975,-0.010777209885419,0.007841582410038,-0.314206928014755,38629,-1923,-2839,-4107,0.987507045269012 +26977,-0.000899644161109,0.00048221994075,-0.315414816141129,38629,-2400,-2494,-2577,0.984196484088898 +26979,0.004523204639554,0.005270722322166,-0.318333923816681,38629,-2167,-3434,-4156,0.986562609672546 +26981,0.008132280781865,0.006272059399635,-0.321551471948624,38629,-2083,-3176,-2620,0.988604187965393 +26983,0.007839928381145,0.000945137522649,-0.3216512799263,38629,-1820,-2643,-4196,0.991958200931549 +26985,0.007719023153186,-0.010774389840663,-0.318940728902817,38629,-1815,-2019,-2603,0.996060371398926 +26987,0.003029246814549,-0.000711720553227,-0.315530627965927,38629,-1441,-3716,-4124,0.99937105178833 +26989,0.004472822882235,0.006020744796842,-0.315334260463715,38629,-1886,-3579,-2578,0.995201766490936 +26991,0.001569844083861,0.018475979566574,-0.317569434642792,38629,-1548,-4204,-4148,0.985295534133911 +26993,-0.001519977697171,0.020331660285592,-0.32010143995285,38629,-1479,-3443,-2611,0.980341196060181 +26995,0.00193617597688,0.006448911968619,-0.317567020654678,38629,-2008,-2134,-4208,0.972937405109406 +26997,-0.003717795480043,-0.001652751117945,-0.312132060527802,38272,-1267,-2417,-2618,0.974442064762116 +26999,-0.008424727246165,-0.012309532612562,-0.306697756052017,38272,-1246,-2049,-4083,0.983264923095703 +27001,-0.009736941196024,-0.009129692800343,-0.304963737726212,38272,-1488,-3111,-2571,0.98390257358551 +27003,-0.005955325905234,-0.009642461314797,-0.305012315511703,38272,-1893,-2811,-4066,0.981471240520477 +27005,-0.006875305902213,-0.006068104878068,-0.307152807712555,38272,-1555,-3177,-2588,0.981317937374115 +27007,-0.004371274728328,-0.00602268660441,-0.307294219732285,38272,-1835,-2902,-4095,0.982965290546417 +27009,-0.000157258502441,-0.010908858850598,-0.307749330997467,38272,-2020,-2496,-2595,0.984835863113403 +27011,-0.000533045851626,-0.004690476693213,-0.310765117406845,38272,-1693,-3357,-4139,0.986231744289398 +27013,-0.002060780767351,-0.000170748578967,-0.314790278673172,38272,-1583,-3319,-2647,0.980828881263733 +27015,-0.00417516939342,0.005351246800274,-0.315117955207825,38272,-1505,-3471,-4194,0.976088583469391 +27017,-0.003301381133497,-0.007373705971986,-0.310593485832214,38272,-1737,-1980,-2622,0.973440825939178 +27019,-0.005752109456807,-0.009126184508204,-0.308048099279404,38272,-1451,-2711,-4114,0.978930950164795 +27021,-0.005219171289355,-0.011394577100873,-0.309538900852203,38272,-1683,-2665,-2617,0.980085790157318 +27023,-0.00134668906685,-0.016275176778436,-0.311597228050232,38272,-1975,-2359,-4159,0.974214375019074 +27025,-0.00404593301937,-0.015713918954134,-0.308562755584717,38272,-1469,-2795,-2614,0.969686090946198 +27027,-0.006531570106745,-0.02149367518723,-0.303319364786148,38272,-1437,-2194,-4064,0.96747350692749 +27029,-0.006191032007337,-0.024962451308966,-0.302158385515213,38272,-1654,-2360,-2572,0.966386437416077 +27031,0.000938654702622,-0.031528197228909,-0.305958539247513,38272,-2246,-1960,-4097,0.966562807559967 +27033,0.002875230275095,-0.019832219928503,-0.307802408933639,38272,-1900,-3502,-3317,0.967886626720428 +27035,0.004039132967591,-0.02659834548831,-0.306387782096863,38200,-1865,-2022,-4832,0.966122984886169 +27037,-0.005915121175349,-0.027948327362537,-0.306933999061584,38200,-924,-2437,-3360,0.970399796962738 +27039,-0.013013051822782,-0.028302308171988,-0.305638194084167,38200,-996,-2448,-4872,0.975268185138702 +27041,-0.004370116163045,-0.034685987979174,-0.305368214845657,38200,-2273,-1966,-3399,0.974413335323334 +27043,0.006918187253177,-0.032468408346176,-0.303331404924393,38200,-2640,-2550,-4894,0.979761481285095 +27045,0.01386241056025,-0.025239376351237,-0.299653619527817,38200,-2417,-3061,-3408,0.986602246761322 +27047,0.012805190868676,-0.018508397042751,-0.29709604382515,38200,-1858,-3079,-4869,0.99167275428772 +27049,0.014967601746321,-0.026475807651877,-0.291605859994888,38200,-2098,-1944,-3401,0.996411204338074 +27051,0.012284966185689,-0.022135926410556,-0.286393165588379,38200,-1728,-2830,-4790,0.990945398807526 +27053,0.012218438088894,-0.023258486762643,-0.284417778253555,38200,-1904,-2467,-3397,0.98192709684372 +27055,0.019860502332449,-0.026359718292952,-0.284807205200195,38200,-2593,-2206,-4817,0.967110753059387 +27057,0.023870823904872,-0.022848710417748,-0.282247424125671,38200,-2371,-2788,-3428,0.95923638343811 +27059,0.030466485768557,-0.022753108292818,-0.273453176021576,38200,-2712,-2476,-4728,0.953626155853272 +27061,0.031414948403835,-0.015882546082139,-0.264017909765244,38200,-2274,-3114,-3347,0.949549674987793 +27063,0.031264539808035,-0.020890025421977,-0.257413297891617,38200,-2274,-2141,-4582,0.946691036224365 +27065,0.029758239164949,-0.01428644079715,-0.251426219940186,38200,-2093,-3105,-3302,0.949371099472046 +27067,0.031157094985247,-0.019271632656455,-0.25000849366188,38200,-2403,-2167,-4536,0.951465725898743 +27069,0.028326634317637,-0.019487328827381,-0.252120733261108,38200,-1996,-2533,-3347,0.950509309768677 +27071,0.022563250735402,-0.01484827324748,-0.248875766992569,38200,-1751,-2910,-4563,0.954087972640991 +27073,0.021203404292464,-0.01914387755096,-0.243431448936462,38200,-2011,-2235,-3327,0.950841248035431 +27075,0.022608509287238,-0.019708314910531,-0.23778061568737,38200,-2276,-2445,-4471,0.948873937129974 +27077,0.021839588880539,-0.017533183097839,-0.236387312412262,38200,-2074,-2710,-3317,0.948993980884552 +27079,0.01749424263835,-0.008061207830906,-0.23691388964653,38200,-1798,-3336,-4499,0.953328788280487 +27081,0.014794036746025,-0.010085992515087,-0.233563452959061,38200,-1845,-2507,-3335,0.955953419208527 +27083,0.011198305524886,-0.005047185346484,-0.229084655642509,38200,-1758,-3067,-4444,0.95450633764267 +27085,0.013225661590695,-0.01380873285234,-0.224876537919044,38200,-2169,-1966,-3312,0.952415645122528 +27087,0.008694997988641,-0.018719553947449,-0.220012754201889,38200,-1652,-2129,-4373,0.948701977729797 +27089,-0.003871402470395,-0.017157232388854,-0.217406302690506,38200,-884,-2646,-3296,0.951528668403626 +27091,-0.009705903939903,-0.020829759538174,-0.219042807817459,38200,-1251,-2170,-4397,0.951707243919373 +27093,-0.01430204603821,-0.015418265014887,-0.222011685371399,38200,-1300,-2935,-3363,0.952853322029114 +27105,-0.025922205299139,-0.031135808676481,-0.190201058983803,38200,-1099,-2611,-3243,0.959523975849152 +27107,-0.026191448792815,-0.020351603627205,-0.190354809165001,38200,-1365,-3155,-4191,0.962933540344238 +27109,-0.030443403869867,-0.017154097557068,-0.186987981200218,38200,-1064,-2688,-3251,0.961800575256348 +27111,-0.031923893839121,-0.013656783849001,-0.183827057480812,38200,-1174,-2728,-4144,0.957268834114075 +27113,-0.031408481299877,-0.009657050482929,-0.183687463402748,38200,-1378,-2844,-3258,0.953184962272644 +27115,-0.033648461103439,-0.001826705876738,-0.181381523609161,38200,-1086,-3225,-4145,0.945713400840759 +27117,-0.034776717424393,-0.004414557013661,-0.178668633103371,38200,-1199,-2443,-3253,0.946315944194794 +27119,-0.034403346478939,-0.002989033702761,-0.179216668009758,38200,-1245,-2735,-4148,0.950609982013702 +27121,-0.035740703344345,-0.003395810723305,-0.177739471197128,38200,-1157,-2609,-3275,0.95572692155838 +27123,-0.037880569696426,-0.006369813811034,-0.174824476242065,38200,-986,-2352,-4125,0.955556213855743 +27125,-0.044974610209465,-0.00478096306324,-0.168910324573517,38200,-595,-2724,-3243,0.955649793148041 +27127,-0.049697034060955,-0.012673475779593,-0.16383507847786,38200,-589,-1882,-4023,0.956833600997925 +27129,-0.0518803820014,-0.011009018868208,-0.162484437227249,38200,-825,-2628,-3225,0.958480715751648 +27131,-0.052692823112011,-0.011433062143624,-0.162668436765671,38200,-800,-2428,-4035,0.95563417673111 +27133,-0.055620469152927,-0.00395080819726,-0.161351695656776,38200,-695,-3134,-3243,0.954335153102875 +27135,-0.054475769400597,-0.009099171496928,-0.161918967962265,38200,-901,-2133,-4052,0.953947365283966 +27137,-0.054915729910135,-0.007485402282327,-0.163720905780792,38200,-860,-2656,-3285,0.950506269931793 +27139,-0.053240228444338,0.004581845831126,-0.16164992749691,38200,-941,-3592,-4075,0.95221608877182 +27141,-0.043420679867268,0.019154762849212,-0.160196602344513,38200,-1739,-3967,-3287,0.953350245952606 +27143,-0.036638658493757,0.022759471088648,-0.158424660563469,38200,-1551,-3281,-4063,0.953206121921539 +27145,-0.034720934927464,0.014373104088008,-0.15658038854599,38200,-1283,-2261,-3288,0.952893197536468 +27147,-0.036114573478699,0.011103074066341,-0.155932813882828,39076,-952,-2587,-4059,0.951543152332306 +27149,-0.035410515964031,0.002663398860022,-0.153592064976692,39076,-1170,-2089,-3292,0.951465606689453 +27151,-0.042383670806885,0.016230739653111,-0.15183612704277,39076,-426,-3868,-4036,0.957288444042206 +27153,-0.041161622852087,0.012035217136145,-0.148925498127937,39076,-1105,-2527,-3285,0.960355579853058 +27155,-0.036431051790714,0.013362175785005,-0.144360944628716,39076,-1340,-2964,-3971,0.967347204685211 +27157,-0.027822146192193,0.018212243914604,-0.138196736574173,39076,-1807,-3266,-3234,0.974096059799194 +27159,-0.019805574789643,0.029483642429113,-0.136827275156975,39076,-1835,-3957,-3905,0.974031209945679 +27161,-0.012126429006457,0.036440670490265,-0.138431638479233,39076,-1956,-3691,-3258,0.973887085914612 +27163,-0.008210188709199,0.025239069014788,-0.138887166976929,39076,-1736,-2287,-3952,0.968638777732849 +27165,-0.004534632433206,0.019266730174422,-0.1362015157938,39076,-1776,-2528,-3264,0.966095685958862 +27167,-0.001309340936132,0.020979512482882,-0.132186874747276,39076,-1804,-3147,-3894,0.964174807071686 +27169,-0.005547051783651,0.039932258427143,-0.12795627117157,39076,-1197,-4618,-3229,0.963333904743195 +27171,-0.00693968590349,0.035535912960768,-0.12099289894104,39076,-1368,-2949,-3783,0.965333759784698 +27173,-0.003178717335686,0.027719067409635,-0.120387211441994,39076,-1801,-2538,-3196,0.966236710548401 +27175,0.005564640741795,0.022483127191663,-0.120235741138458,39076,-2296,-2685,-3793,0.974768877029419 +27177,0.006007264368236,0.03126135841012,-0.119204334914684,39076,-1697,-3784,-3208,0.982436299324035 +27179,0.003227524459362,0.04030067846179,-0.118261232972145,39076,-1442,-4001,-3789,0.990692853927612 +27181,0.001479399506934,0.036312397569418,-0.115764081478119,39076,-1478,-2955,-3203,0.985982418060303 +27183,0.002297104569152,0.032168921083212,-0.114468239247799,39076,-1682,-2939,-4786,0.972019493579864 +27185,0.002236592350528,0.02396315895021,-0.111725367605686,39791,-1611,-2486,-4250,0.969447374343872 +27187,0.003638594411314,0.023808054625988,-0.107351899147034,39791,-1742,-3102,-4788,0.972230792045593 +27189,0.010850802063942,0.013232166878879,-0.104298584163189,39791,-2257,-2170,-4284,0.975459575653076 +27191,0.016546672210097,0.006317663472146,-0.101740077137947,39791,-2263,-2345,-4807,0.975365161895752 +27193,0.021085640415549,0.003045643214136,-0.095942340791226,39791,-2220,-2547,-4311,0.976239264011383 +27195,0.01994888857007,-0.00052967236843,-0.087146438658238,39791,-1841,-2469,-4718,0.978554844856262 +27197,0.017084611579776,0.002289266325533,-0.075329698622227,39791,-1642,-2970,-4251,0.982702195644379 +27199,0.020692124962807,-0.004710640292615,-0.067722462117672,39791,-2206,-2144,-4570,0.983722269535065 +27201,0.02463367022574,-0.002266078488901,-0.063244752585888,39791,-2248,-2872,-4247,0.981358647346497 +27203,0.024044033139944,-0.000438993592979,-0.057042188942432,39791,-1969,-2836,-4522,0.98213118314743 +27205,0.019468335434795,0.009864619933069,-0.053648762404919,39791,-1575,-3604,-4258,0.980204284191132 +27207,0.023906717076898,0.006503166165203,-0.046978000551462,39791,-2335,-2573,-4480,0.980959832668304 +27209,0.020788060501218,0.012505485676229,-0.043331746011973,39791,-1709,-3332,-4262,0.97648012638092 +27211,0.02140449732542,0.015678515657783,-0.038891166448593,39791,-2030,-3187,-4459,0.974314391613007 +27213,0.031989514827728,0.012812570668757,-0.034201696515083,39791,-2862,-2703,-4274,0.970756471157074 +27215,0.043613694608212,0.017617283388972,-0.030026601627469,39791,-3195,-3336,-4428,0.969875037670136 +27217,0.054431941360235,0.017130762338638,-0.024524118751288,39791,-3221,-2938,-4280,0.967856228351593 +27219,0.057361155748367,0.028445484116674,-0.017079466953874,39791,-2822,-3992,-4348,0.967624008655548 +27221,0.055815167725086,0.02637655287981,-0.006526515353471,39791,-2383,-2965,-4957,0.969560861587524 +27223,0.046942960470915,0.031901393085718,0.001669071614742,40184,-1832,-3648,-4950,0.973932862281799 +27225,0.045890834182501,0.028359642252326,0.006518446840346,40184,-2298,-2900,-4983,0.979806363582611 +27227,0.043848425149918,0.034381896257401,0.011233183555305,40184,-2282,-3734,-4953,0.980359733104706 +27229,0.041379723697901,0.03767779096961,0.015381743200123,40184,-2152,-3536,-5036,0.980593800544739 +27231,0.042138125747442,0.030839443206787,0.021552050486207,40184,-2481,-2771,-4945,0.976886212825775 +27233,0.046868443489075,0.031055929139257,0.028758658096194,40184,-2766,-3232,-5057,0.969598710536957 +27235,0.05639012157917,0.031365413218737,0.036997530609369,40184,-3374,-3308,-4875,0.96886271238327 +27237,0.061432775110006,0.039633084088564,0.045624118298292,40184,-3026,-3944,-5052,0.971050024032593 +27239,0.060730461031199,0.034600123763085,0.054012782871723,40184,-2744,-2998,-4784,0.975305438041687 +27241,0.049580715596676,0.040960110723972,0.0612902790308,40184,-1727,-3842,-5052,0.97802346944809 +27243,0.044532239437103,0.037503827363253,0.067706644535065,40184,-2197,-3177,-4729,0.985902428627014 +27245,0.046959564089775,0.027283925563097,0.073981925845146,40184,-2686,-2475,-5070,0.988515734672546 +27247,0.042502291500568,0.030594231560826,0.082793556153774,40184,-2219,-3557,-4656,0.995934724807739 +27249,0.036874327808619,0.038077689707279,0.093652933835983,40184,-1985,-3911,-5038,0.995219826698303 +27251,0.040969558060169,0.043140217661858,0.100638672709465,40184,-2826,-3898,-4547,0.985918283462524 +27253,0.047361202538014,0.038445252925158,0.105601944029331,40184,-3017,-3062,-5056,0.980183720588684 +27255,0.045011084526777,0.04352555051446,0.110085152089596,40184,-2452,-3911,-4536,0.972924709320068 +27257,0.042038574814797,0.039640728384256,0.117485493421555,40184,-2293,-3153,-5073,0.973984777927399 +27259,0.039872754365206,0.041849728673697,0.122833505272865,40184,-2395,-3692,-4731,0.973278820514679 +27261,0.03846375644207,0.048058517277241,0.125371664762497,40184,-2372,-4012,-5371,0.977378129959106 +27263,0.038347467780113,0.046314287930727,0.129073962569237,40184,-2525,-3509,-4770,0.979683995246887 +27265,0.033509187400341,0.055073212832213,0.138981744647026,40184,-2072,-4315,-5390,0.99243426322937 +27267,0.0330527164042,0.05136363953352,0.151452109217644,40184,-2442,-3468,-4617,1.00947296619415 +27269,0.033347584307194,0.047410350292921,0.158074945211411,40184,-2453,-3316,-5367,1.01942551136017 +27271,0.034202605485916,0.033892244100571,0.165169164538383,40184,-2579,-2503,-4563,1.02803504467011 +27273,0.02110899053514,0.043611541390419,0.171167477965355,40184,-1337,-4256,-5383,1.02568554878235 +27275,0.009688033722341,0.047032926231623,0.179604321718216,40184,-1320,-3940,-4498,1.02683019638062 +27277,0.009618405252695,0.043857768177986,0.187796831130981,40184,-2113,-3355,-5373,1.02086234092712 +27279,0.01461454294622,0.043160919100046,0.194663882255554,40184,-2582,-3601,-4424,1.01504325866699 +27281,0.012280613183975,0.038984578102827,0.201124250888824,40184,-1998,-3230,-5383,1.00605177879334 +27283,-0.000418583338615,0.039499271661043,0.207965493202209,40184,-1069,-3650,-4368,0.996872425079346 +27285,-0.010270928964019,0.03452654927969,0.212587609887123,40184,-1138,-3126,-5403,0.995311319828033 +27287,-0.015615501441062,0.036582663655281,0.218726992607117,40184,-1340,-3730,-4339,0.996643364429474 +27289,-0.013704623095691,0.020300617441535,0.225970864295959,40184,-1925,-2127,-5409,0.996553897857666 +27291,-0.0191332064569,0.016220523044467,0.232198655605316,40184,-1268,-2970,-4277,0.995147526264191 +27293,-0.019456630572677,0.018833994865418,0.242910444736481,40184,-1674,-3466,-5388,0.997341394424438 +27295,-0.015337767079473,0.014211036264896,0.25120747089386,40184,-2005,-2901,-4148,0.995579779148102 +27297,-0.018921885639429,0.010892719961703,0.256134897470474,40184,-1440,-2932,-5689,0.998800039291382 +27299,-0.027845244854689,0.009158261120319,0.261572122573853,40184,-859,-3030,-4427,0.998695850372314 +27301,-0.029126457870007,0.012449081987143,0.268496245145798,40184,-1446,-3430,-5715,1.00411927700043 +27303,-0.025724058970809,-0.00255329022184,0.276940077543259,40184,-1766,-1898,-4355,1.00883769989014 +27305,-0.029713770374656,-0.008967498317361,0.284420996904373,40184,-1232,-2427,-5714,1.01505601406097 +27307,-0.030746459960938,-0.016831383109093,0.287620395421982,40184,-1356,-2174,-4337,1.01708519458771 +27309,-0.030667776241899,-0.017013415694237,0.29096457362175,40184,-1496,-2750,-5775,1.01792693138123 +27311,-0.033629082143307,-0.012809175997973,0.298128098249435,40184,-1159,-3093,-4319,1.01925992965698 +27313,-0.03354786336422,-0.017126055434346,0.309479355812073,40184,-1441,-2445,-5753,1.01807522773743 +27315,-0.029614778235555,-0.015986079350114,0.32081264257431,40184,-1707,-2807,-4155,1.01871633529663 +27317,-0.02123766951263,-0.018148286268115,0.329901307821274,40184,-2199,-2575,-5714,1.01805531978607 +27335,0.005577844567597,-0.018593035638332,0.383552998304367,40184,-2971,-2272,-4034,1.00521123409271 +27337,0.010382117703557,-0.003997997380793,0.392182558774948,40184,-2360,-3937,-5902,1.00333189964294 +27339,0.007710192818195,0.002670096699148,0.401610791683197,40184,-1797,-3452,-3920,0.999636352062225 +27341,0.00040779428673,0.011467318981886,0.408249348402023,40184,-1354,-3741,-5889,1.00755703449249 +27343,-0.00402166089043,0.011882898397744,0.413265436887741,40184,-1486,-3158,-3879,1.01831650733948 +27345,2.99531311611645E-05,0.007234878372401,0.414681375026703,40184,-2161,-2720,-5940,1.02465105056763 +27347,0.012238027527928,0.009269670583308,0.415494531393051,40184,-2937,-3234,-3948,1.02837479114532 +27349,0.018713498488069,0.009963054209948,0.424974530935288,40184,-2608,-3143,-5964,1.03201746940613 +27351,0.014316828921437,0.026596046984196,0.439800143241882,40184,-1794,-4571,-3754,1.03066551685333 +27353,0.016837451606989,0.029137147590518,0.45112806558609,40184,-2306,-3561,-5875,1.03006231784821 +27355,0.014477238059044,0.037109926342964,0.45374408364296,40184,-1958,-4138,-3680,1.03023147583008 +27357,0.015976270660758,0.033844906836748,0.456758111715317,40184,-2229,-3228,-5925,1.02592074871063 +27359,0.018311945721507,0.028245598077774,0.460253179073334,40184,-2373,-3042,-3691,1.01841330528259 +27361,0.017899783328176,0.024582015350461,0.468999713659287,40184,-2132,-3080,-5928,1.01502072811127 +27363,0.014432244002819,0.027283577248454,0.480324029922485,40184,-1896,-3631,-3541,1.01223623752594 +27365,0.00702908821404,0.039087552577257,0.488065391778946,40184,-1484,-4408,-5881,1.0104466676712 +27367,0.004094156436622,0.035571899265051,0.493745267391205,40184,-1753,-3324,-3466,1.00638997554779 +27369,-0.002916590310633,0.043738212436438,0.495664894580841,40184,-1369,-4229,-5911,1.00878834724426 +27371,0.00122338172514,0.037541594356299,0.497060835361481,40184,-2207,-3171,-3639,1.0111495256424 +27373,0.002649463480338,0.039936795830727,0.497348546981811,40184,-2052,-3775,-6116,1.0115612745285 +27375,0.002662544604391,0.034213986247778,0.505153775215149,40184,-1935,-3159,-3634,1.01606154441834 +27377,-0.005888477899134,0.030814524739981,0.514935374259949,40184,-1214,-3241,-6084,1.0134938955307 +27379,-0.009957276284695,0.028751917183399,0.520872592926025,40184,-1441,-3350,-3536,1.00988495349884 +27381,-0.018652660772204,0.027639769017696,0.527282118797302,40184,-1014,-3370,-6085,1.00272107124329 +27383,-0.027853772044182,0.035898577421904,0.529257774353027,40184,-783,-4232,-3523,0.994742155075073 +27385,-0.031067043542862,0.036924976855517,0.532170295715332,40184,-1217,-3672,-6137,0.993131279945374 +27387,-0.034899573773146,0.03732917830348,0.538407266139984,40184,-1042,-3709,-3500,0.999646365642548 +27389,-0.033368248492479,0.019902277737856,0.542004406452179,40184,-1509,-2123,-6153,1.00529408454895 +27391,-0.029505144804716,0.010696171782911,0.548242688179016,40184,-1665,-2593,-3467,1.00454163551331 +27393,-0.026829779148102,0.01617581397295,0.558924198150635,40184,-1671,-3714,-6119,1.012251496315 +27395,-0.038626726716757,0.023247981444001,0.568601012229919,40184,-380,-3959,-3308,1.02423334121704 +27397,-0.045746292918921,0.029853379353881,0.573974370956421,40184,-681,-3999,-6094,1.03117489814758 +27399,-0.0450061224401,0.021426793187857,0.575986504554749,40184,-1160,-2827,-3299,1.03061783313751 +27401,-0.038679528981447,0.019134234637022,0.579746186733246,40184,-1726,-3215,-6132,1.02271926403046 +27403,-0.033174928277731,0.019865749403834,0.587766945362091,40184,-1685,-3476,-3237,1.01479160785675 +27405,-0.036925293505192,0.022076223045588,0.592424154281616,40184,-1016,-3588,-6120,1.00761985778809 +27407,-0.039577975869179,0.016542043536902,0.595619857311249,40184,-984,-2983,-3220,1.00703155994415 +27409,-0.034524779766798,0.007808062247932,0.599666237831116,40184,-1666,-2607,-6145,1.0061868429184 +27411,-0.034535188227892,0.005461868364364,0.604103744029999,40184,-1231,-3039,-3194,1.00887191295624 +27413,-0.039091411978006,0.00036196410656,0.61141049861908,40184,-897,-2763,-6137,1.01568520069122 +27415,-0.046308610588312,0.009724636562169,0.615850031375885,40184,-495,-3937,-3128,1.02467489242554 +27417,-0.044205266982317,0.005275148432702,0.615889966487885,40184,-1278,-2882,-6178,1.03252005577087 +27419,-0.039688318967819,0.003822437254712,0.616529822349548,40184,-1420,-3060,-3191,1.03028619289398 +27421,-0.035824570804834,-0.000589209026657,0.627099335193634,40184,-1505,-2799,-6172,1.02298617362976 +27423,-0.038722891360521,0.003099830821157,0.634354770183563,40184,-894,-3415,-3051,1.0151435136795 +27425,-0.039793681353331,0.005868398584425,0.637470364570618,40184,-1076,-3404,-6169,1.01197922229767 +27427,-0.034284546971321,-0.001024611992762,0.641809940338135,40184,-1559,-2585,-3031,1.00491964817047 +27429,-0.033684335649014,-0.001745560090058,0.644939601421356,40184,-1269,-3041,-6184,1.00084495544434 +27431,-0.030613861978054,-0.011725949123502,0.649040639400482,40184,-1421,-2190,-3012,0.993488907814026 +27433,-0.037358745932579,1.31873875943711E-05,0.656566083431244,40184,-675,-3951,-6170,0.99621057510376 +27435,-0.044084887951613,-0.000877839280292,0.664757072925568,40184,-473,-3005,-2892,1.00210309028625 +27437,-0.048594120889902,-0.000731781066861,0.671990394592285,40184,-651,-3106,-6128,1.00813007354736 +27439,-0.039543688297272,-0.012066274881363,0.677845239639282,40184,-1651,-2067,-2800,1.01514065265656 +27441,-0.035527188330889,-0.012383362278342,0.678690135478973,40184,-1428,-2896,-6143,1.01097619533539 +27443,-0.037481654435396,-0.004102609120309,0.681495606899262,40184,-888,-3589,-2818,1.00972235202789 +27445,-0.032332222908735,-0.006021396722645,0.685291528701782,40184,-1536,-2865,-6158,1.01053297519684 +27447,-0.030474634841085,-0.000830591481645,0.687130689620972,40184,-1264,-3408,-2812,1.01265871524811 +27449,-0.028140023350716,-0.006910390220582,0.688872873783112,40184,-1381,-2547,-6193,1.00935137271881 +27451,-0.031700376421213,-0.002674075542018,0.690343677997589,40184,-840,-3320,-2834,1.00508093833923 +27453,-0.031124101951718,-0.013960207812488,0.692886471748352,40184,-1197,-2068,-6225,1.01102101802826 +27455,-0.039512928575277,-0.013840992935002,0.698103904724121,40184,-353,-2843,-2801,1.02383780479431 +27457,-0.043432723730803,-0.017256572842598,0.706534147262573,40184,-680,-2576,-6189,1.03219079971313 +27459,-0.039534509181976,-0.019171366468072,0.709934115409851,40184,-1213,-2609,-2719,1.03495562076569 +27461,-0.038078930228949,-0.012183638289571,0.71038556098938,40184,-1122,-3384,-6219,1.03655076026917 +27463,-0.037410072982311,-0.009373215027154,0.715036451816559,40184,-1001,-3095,-2714,1.03659045696259 +27465,-0.027437059208751,-0.004489574115723,0.723027527332306,40184,-1868,-3338,-6187,1.04061996936798 +27467,-0.01621768809855,-0.010531114414334,0.729740560054779,40184,-2089,-2429,-2595,1.03935050964355 +27469,-0.018328942358494,-0.008232831023633,0.733112096786499,40184,-1125,-3092,-6171,1.03694474697113 +27471,-0.018262168392539,-0.010934984311462,0.735328733921051,40184,-1246,-2657,-2582,1.02971744537354 +27473,-0.01778956502676,-0.008369286544621,0.738470137119293,40184,-1309,-3102,-6186,1.02099549770355 +27475,-0.021009722724557,-0.002899260958657,0.742619872093201,40184,-956,-3373,-2548,1.01742458343506 +27477,-0.013208731077612,-0.010080394335091,0.745210707187653,40184,-1889,-2376,-6191,1.0153032541275 +27479,-0.006040702573955,-0.008916939608753,0.744671523571014,40184,-1937,-2967,-2574,1.00971412658691 +27481,0.000584747060202,-0.011216226033866,0.751305878162384,40184,-2000,-2704,-6199,1.00988781452179 +27483,-0.00101438339334,-0.002909778850153,0.759539306163788,40184,-1388,-3569,-2449,1.00999128818512 +27485,0.007091726642102,-0.00902951695025,0.76498156785965,40184,-2198,-2459,-6153,1.00707936286926 +27487,0.008414691314101,-0.000845002534334,0.767591118812561,40184,-1742,-3580,-2401,1.00746297836304 +27489,0.007835297845304,-0.001693038386293,0.77172189950943,40184,-1588,-2938,-6154,1.00597786903381 +27491,0.012194611132145,-0.002362398896366,0.776221811771393,40184,-2019,-2912,-2346,1.00209438800812 +27493,0.011810701340437,0.000143276993185,0.779424488544464,40184,-1662,-3199,-6146,1.00522458553314 +27495,0.010136224329472,0.001676286221482,0.781312465667725,40184,-1557,-3137,-2331,1.00669538974762 +27497,0.011979283764958,0.011189830489457,0.78514963388443,40184,-1826,-3857,-6152,1.00728273391724 +27499,0.015219086781144,0.004441586323082,0.786834359169006,40184,-1999,-2589,-2310,1.01278781890869 +27501,0.016065193340182,0.008407996036112,0.788188338279724,40184,-1818,-3420,-6175,1.01463878154755 +27503,0.024352373555303,0.004443738143891,0.794973611831665,40184,-2519,-2788,-2257,1.01731383800507 +27505,0.02831700257957,0.006949068978429,0.801642835140228,40184,-2227,-3293,-6124,1.0141509771347 +27507,0.029200008139014,0.00638604676351,0.80675595998764,40184,-2083,-3059,-2160,1.01897442340851 +27509,0.02259068749845,-0.000448186765425,0.807846486568451,40184,-1400,-2517,-6122,1.02041614055634 +27511,0.024017443880439,-0.00499930139631,0.808505058288574,40184,-2059,-2587,-2180,1.02057206630707 +27513,0.028356900438666,0.001390268094838,0.813731193542481,40184,-2279,-3486,-6122,1.0249354839325 +27515,0.030866479501128,0.012146349996328,0.816257357597351,40184,-2262,-3966,-2128,1.02671492099762 +27517,0.029526147991419,0.009600833058357,0.815936028957367,40184,-1904,-2967,-6146,1.03039491176605 +27519,0.027689969167113,0.008500379510224,0.818312704563141,40184,-1908,-3063,-2143,1.03085589408875 +27521,0.027927845716477,0.010138243436813,0.824751734733581,40184,-2008,-3276,-6124,1.03384447097778 +27523,0.031292237341404,0.014982746914029,0.827120840549469,40184,-2348,-3598,-2077,1.02952694892883 +27525,0.030722400173545,0.027089722454548,0.830634534358978,40184,-2004,-4275,-6121,1.02569699287415 +27527,0.028969068080187,0.0235709939152,0.833686709403992,40184,-1954,-3146,-2036,1.0202933549881 +27529,0.026831308379769,0.023520277813077,0.833868503570556,40184,-1848,-3362,-6135,1.01586282253265 +27531,0.029162706807256,0.015268168412149,0.833439946174622,40184,-2265,-2675,-2076,1.01075541973114 +27533,0.031077146530151,0.01644267514348,0.832906901836395,40184,-2213,-3353,-6178,1.00926077365875 +27535,0.036319673061371,0.016217280179262,0.839211225509644,40184,-2594,-3270,-2043,1.01323306560516 +27537,0.03672706335783,0.026811398565769,0.844646096229553,40184,-2201,-4182,-6132,1.01543784141541 +27539,0.030149035155773,0.036161575466395,0.846785962581635,40184,-1650,-4288,-1989,1.01927030086517 +27541,0.026390874758363,0.035756435245276,0.845420718193054,40184,-1764,-3536,-6161,1.01626920700073 +27543,0.022920325398445,0.041333101689816,0.845022082328796,40184,-1760,-4111,-2044,1.0127694606781 +27545,0.022742789238691,0.039068881422281,0.849871158599854,40184,-1975,-3466,-6165,1.00681364536285 +27547,0.019108194857836,0.051276791840792,0.853288114070892,40184,-1696,-4766,-1980,1.00261843204498 +27563,-0.004107533954084,0.002150529529899,0.855148792266846,40184,-1544,-3152,-2086,1.02466404438019 +27565,-0.008704469539225,0.011982418596745,0.858009457588196,40184,-1216,-3995,-6269,1.02557229995728 +27567,-0.015484476462007,0.016955371946097,0.864212214946747,40184,-926,-3743,-2011,1.02210783958435 +27569,-0.019523117691279,0.015732718631625,0.870347857475281,40184,-1093,-3264,-6216,1.01526856422424 +27571,-0.02555044926703,0.013401751406491,0.873264074325562,40184,-809,-3169,-1935,1.01137459278107 +27573,-0.030840512365103,0.008950585499406,0.877990067005158,40184,-828,-2940,-6193,1.0042427778244 +27575,-0.030919117853046,0.00853833463043,0.879668116569519,40184,-1134,-3235,-1889,0.993596971035004 +27577,-0.031080693006516,-0.001543652266264,0.882717251777649,40184,-1177,-2389,-6189,0.993530213832855 +27579,-0.038732726126909,-0.000242721725954,0.886841297149658,40184,-443,-3212,-1833,0.995500445365906 +27581,-0.037378527224064,-0.010856501758099,0.889565050601959,40184,-1177,-2216,-6170,1.00111591815948 +27583,-0.035246506333351,-0.021891200914979,0.885567128658295,40184,-1178,-1965,-1876,1.00395345687866 +27585,-0.037417568266392,-0.026649111881852,0.885335028171539,40184,-905,-2396,-6227,1.00980114936829 +27587,-0.040213134139776,-0.036654088646174,0.888427555561066,40184,-725,-1777,-1870,1.00884652137756 +27589,-0.041471090167761,-0.033616442233324,0.893801391124725,40184,-891,-2835,-6196,1.00487267971039 +27591,-0.039516679942608,-0.032498467713595,0.897367298603058,40184,-1066,-2629,-1792,1.00241053104401 +27593,-0.039789233356714,-0.022572733461857,0.897126197814941,40184,-967,-3469,-6199,1.00143206119537 +27595,-0.038558848202229,-0.0228405687958,0.899602830410004,40184,-1018,-2680,-1791,1.00391280651093 +27597,-0.042636208236218,-0.019042156636715,0.90305769443512,40184,-636,-3070,-6184,1.00750017166138 +27599,-0.042892921715975,-0.013173417188227,0.907620489597321,40184,-816,-3261,-1722,1.01596367359161 +27601,-0.036815825849772,-0.009057749994099,0.913576126098633,40184,-1426,-3228,-6136,1.02444922924042 +27603,-0.032535299658775,0.001637843670324,0.917198836803436,40184,-1284,-3838,-1632,1.02881813049316 +27605,-0.027004469186068,0.001772244926542,0.918669521808624,40184,-1511,-3095,-6124,1.03506183624268 +27607,-0.025100270286203,0.005980943329632,0.918600261211395,40184,-1222,-3436,-1638,1.0401291847229 +27609,-0.016810541972518,-0.004708904307336,0.920344352722168,40184,-1841,-2225,-6135,1.03479933738709 +27611,-0.013857113197446,-0.001184552209452,0.921121537685394,40184,-1471,-3272,-1631,1.02286684513092 +27613,-0.015842895954847,0.004897252190858,0.922111749649048,40184,-1111,-3561,-6145,1.01632010936737 +27615,-0.012650156393647,0.007309935521334,0.922658383846283,40184,-1502,-3332,-1635,1.00802946090698 +27617,-0.008245942182839,0.006084594409913,0.923405170440674,40184,-1671,-3055,-6158,1.00615251064301 +27619,0.001067473785952,-0.003365606302395,0.924996316432953,40184,-2149,-2304,-1629,1.00990605354309 +27621,0.014061463996768,0.004032962024212,0.921570181846619,40184,-2604,-3639,-6192,1.0125275850296 +27623,0.032871566712856,0.001277957926504,0.920598983764648,40184,-3338,-2854,-1703,1.01661229133606 +27625,0.039382170885801,0.002883460838348,0.926486134529114,40184,-2513,-3204,-6180,1.0193088054657 +27627,0.042062867432833,0.00194637675304,0.933437764644623,40184,-2347,-2984,-1573,1.02334928512573 +27629,0.048975933343172,0.004700161051005,0.934838473796844,40184,-2694,-3309,-6143,1.02166843414307 +27631,0.056443031877279,0.005112228449434,0.937987089157104,40184,-2942,-3126,-1539,1.02128970623016 +27633,0.058666441589594,0.004036320839077,0.942080795764923,40184,-2519,-3022,-6112,1.01785242557526 +27635,0.054651163518429,0.012077121064067,0.94085031747818,40184,-2128,-3793,-1524,1.01383972167969 +27637,0.051045503467321,0.009025981649756,0.938210546970367,40184,-2016,-2953,-6158,1.01134848594666 +27639,0.05130473151803,0.009170347824693,0.937935352325439,40184,-2408,-3190,-1578,1.01350343227386 +27641,0.049414552748203,0.003541365033016,0.938476920127869,40184,-2138,-2691,-6176,1.01799356937408 +27643,0.047554887831211,0.002953714458272,0.937782049179077,40184,-2214,-3051,-1599,1.01996922492981 +27645,0.046419613063336,0.013623578473926,0.934354066848755,40184,-2171,-4005,-6223,1.02545428276062 +27647,0.050565514713526,0.023574041202664,0.93634432554245,40184,-2723,-4147,-1635,1.03291988372803 +27649,0.054202117025852,0.040756620466709,0.943683922290802,40184,-2648,-4872,-6179,1.0365504026413 +27651,0.059116244316101,0.033632729202509,0.948773562908173,40184,-2946,-3096,-1508,1.03346657752991 +27653,0.055932570248842,0.028159776702523,0.950009047985077,40184,-2213,-3083,-6153,1.0254420042038 +27655,0.046552654355764,0.020950254052878,0.950115442276001,40184,-1735,-2899,-1509,1.01910543441772 +27657,0.033445872366428,0.024447649717331,0.949517846107483,40184,-1201,-3682,-6174,1.00775468349457 +27659,0.030255626887083,0.028010368347168,0.950825214385986,40184,-1923,-3792,-1518,1.0057784318924 +27661,0.04023852199316,0.016791248694062,0.950943231582642,40184,-2965,-2530,-6181,1.00849390029907 +27663,0.045988772064447,0.012360587716103,0.94996577501297,40184,-2831,-2973,-1546,1.00921738147736 +27665,0.038564577698708,0.009707821533084,0.953515946865082,40184,-1714,-3047,-6181,1.01046562194824 +27667,0.022472154349089,0.024978270754218,0.955180525779724,40184,-900,-4592,-1502,1.01170337200165 +27669,0.020628893747926,0.027505975216627,0.953300714492798,40184,-1865,-3683,-6199,1.01571249961853 +27671,0.022631024941802,0.02644737623632,0.951986491680145,40184,-2210,-3444,-1556,1.01962041854858 +27673,0.02446635812521,0.020184991881251,0.953193962574005,40184,-2193,-2957,-6217,1.02175056934357 +27675,0.024211246520281,0.014438554644585,0.956025183200836,40184,-2086,-2918,-1525,1.01904916763306 +27677,0.019762078300119,0.015151184052229,0.958028137683868,40184,-1686,-3387,-6200,1.01487278938293 +27679,0.008343608118594,0.017057228833437,0.961238026618958,40184,-1041,-3519,-1480,1.01353085041046 +27681,0.001031136140227,0.024177502840757,0.96558690071106,40184,-1216,-3981,-6164,1.0109691619873 +27683,0.005208442453295,0.019186187535524,0.967968642711639,40184,-2114,-3072,-1416,1.01112544536591 +27685,0.00595083180815,0.006187388207763,0.967865943908691,40184,-1867,-2289,-6163,1.01142060756683 +27687,-0.000525368435774,0.00253135478124,0.968940377235413,40184,-1258,-2907,-1419,1.01311695575714 +27689,-0.002837393665686,-0.006080631632358,0.971350431442261,40184,-1523,-2428,-6153,1.01726353168488 +27691,-0.00621441937983,-0.005385769531131,0.970396459102631,40184,-1385,-3080,-1416,1.0222806930542 +27693,-0.004028401803225,-0.010330340825021,0.969428956508636,40184,-1825,-2625,-6181,1.02385175228119 +27695,-0.005297432187945,-0.003381315851584,0.969442248344421,40184,-1543,-3547,-1442,1.02146458625793 +27715,-0.007153727579862,-0.022951729595661,0.978472828865051,40184,-1549,-2709,-1403,1.03452408313751 +27717,-0.008263778872788,-0.021576069295406,0.982551753520966,40184,-1490,-2863,-6172,1.03192389011383 +27719,-0.010851683095098,-0.008103501051664,0.988760948181152,40184,-1329,-3897,-1294,1.03025305271149 +27721,-0.00861540902406,-0.009477556683123,0.995012879371643,40184,-1721,-2834,-6097,1.02992391586304 +27723,-0.005732745397836,-0.010504584759474,0.993086218833923,40184,-1797,-2814,-1254,1.02764844894409 +27725,-0.000559478532523,-0.020121656358242,0.987334489822388,40184,-2044,-2084,-6161,1.0246102809906 +27727,0.000227539247135,-0.018942059949041,0.98417741060257,40184,-1728,-2830,-1370,1.01722514629364 +27729,-0.005593542475253,-0.012746113352478,0.987267255783081,40184,-1182,-3313,-6173,1.01195299625397 +27731,-0.000836949679069,-0.016936410218477,0.993724524974823,40184,-1990,-2468,-1269,1.00896000862122 +27733,0.012770542874932,-0.016774158924818,0.997905492782593,40184,-2834,-2814,-6110,1.00971555709839 +27735,0.025867689400911,-0.023919135332108,0.995774567127228,40184,-3023,-2116,-1255,1.01036107540131 +27737,0.024053344503045,-0.016966816037893,0.991660475730896,40184,-1900,-3283,-6163,1.01161134243011 +27739,0.019977571442723,-0.015041999518871,0.991584837436676,40184,-1701,-2902,-1314,1.01246964931488 +27741,0.017358424142003,-0.002089035464451,0.998757183551788,40184,-1752,-3917,-6125,1.01470100879669 +27743,0.017393134534359,0.009008937515318,1.00592601299286,40184,-1963,-3952,-1155,1.0219441652298 +27745,0.02354515530169,-0.000495234678965,1.00440275669098,40184,-2474,-2333,-6095,1.02823960781097 +27747,0.02671860717237,-0.004262437578291,0.996627867221832,40184,-2352,-2677,-922,1.02667486667633 +27749,0.025002017617226,0.004571754019707,0.99756646156311,40184,-1942,-3716,-5788,1.02551114559174 +27751,0.020082455128431,0.020463159307838,1.00413227081299,40184,-1682,-4487,-819,1.02471017837524 +27753,0.024082079529762,0.01734103448689,1.00666677951813,40184,-2347,-3051,-5711,1.02847945690155 +27755,0.029467415064573,0.010734804905951,1.00152468681335,40184,-2587,-2719,-835,1.02822518348694 +27757,0.025896659120917,0.012301683425903,1.00001978874207,40184,-1845,-3317,-5742,1.02725958824158 +27759,0.028997743502259,0.01798602938652,1.00080609321594,40184,-2429,-3722,-830,1.02109336853027 +27761,0.028413152322173,0.027844274416566,1.00096070766449,40184,-2108,-4141,-5721,1.01741921901703 +27763,0.025545286014676,0.017874186858535,0.998671472072601,40184,-1955,-2609,-841,1.01515567302704 +27765,0.020088223740459,0.018251748755574,0.995612978935242,40184,-1651,-3331,-5744,1.016037940979 +27767,0.020269019529224,0.022755261510611,0.99402642250061,40184,-2091,-3728,-882,1.0146940946579 +27769,0.019633330404759,0.027820967137814,0.994453489780426,40184,-1998,-3813,-5739,1.01190912723541 +27771,0.009631374850869,0.02418078109622,0.99872761964798,40184,-1189,-3177,-813,1.01256573200226 +27773,0.002440345939249,0.011362102814019,0.996901869773865,40184,-1284,-2304,-5708,1.01404619216919 +27775,-0.000270258722594,0.010630840435624,0.990644931793213,40184,-1553,-3167,-895,1.01624572277069 +27777,0.001455330871977,0.013959798030555,0.987304925918579,40184,-1907,-3501,-5762,1.01549816131592 +27779,-0.001389193465002,0.021157298237085,0.983643352985382,40184,-1524,-3909,-966,1.01620388031006 +27781,-0.00307083572261,0.013143312186003,0.985674977302551,40184,-1596,-2683,-5762,1.02144908905029 +27783,-0.001059566391632,0.004644870292395,0.98915958404541,40184,-1882,-2532,-889,1.02400207519531 +27785,-0.004692408721894,0.009061843156815,0.98931235074997,40184,-1432,-3516,-5242,1.03193354606628 +27787,-0.009085785597563,0.013550677336753,0.98811262845993,40434,-1297,-3616,-391,1.0344580411911 +27789,-0.016039788722992,0.016294628381729,0.987185120582581,40434,-1027,-3507,-5213,1.03305757045746 +27791,-0.018164619803429,0.013567997142673,0.986763000488281,40434,-1301,-3102,-362,1.02850198745728 +27793,-0.019153591245413,0.01542045082897,0.986525595188141,40434,-1401,-3436,-5173,1.02307212352753 +27795,-0.018937958404422,0.011578479781747,0.984986543655396,40434,-1450,-2990,-339,1.01964139938355 +27797,-0.013684649020434,0.006481813266873,0.978360891342163,40434,-1918,-2814,-5186,1.01642549037933 +27799,-0.01415104418993,0.008228912949562,0.968066155910492,40434,-1471,-3335,-496,1.0154412984848 +27801,-0.012273936532438,0.008296892978251,0.965621769428253,40434,-1690,-3212,-5232,1.0154949426651 +27803,-0.011861574836075,0.015675563365221,0.967005550861358,40434,-1562,-3865,-468,1.01580929756165 +27805,-0.009308438748121,0.001476784003899,0.967147767543793,40434,-1775,-2098,-5181,1.01291346549988 +27807,-0.010913392528892,-0.003124278504401,0.963564336299896,40434,-1421,-2709,-468,1.01315951347351 +27809,-0.014607850462198,-3.48706671502441E-05,0.960679113864899,40434,-1245,-3312,-5185,1.01948404312134 +27811,-0.0105109680444,0.004276062361896,0.960997700691223,40434,-1835,-3467,-458,1.02077901363373 +27813,-0.004915132187307,0.007211917079985,0.961461305618286,40434,-2044,-3407,-5140,1.02478635311127 +27815,-0.002391334623098,0.007285234052688,0.959011852741241,40434,-1859,-3214,-442,1.02795004844666 +27817,-0.005843459162861,0.009863131679595,0.955943405628204,40434,-1382,-3422,-5138,1.02971458435059 +27819,-0.005950650665909,0.007395637687296,0.949311971664429,40434,-1619,-3034,-517,1.03432536125183 +27821,-0.003046451602131,0.004755340516567,0.94219833612442,40434,-1877,-2977,-5195,1.03526198863983 +27823,-0.002797563560307,-0.000961038749665,0.940440535545349,40434,-1693,-2665,-284,1.03400695323944 +27825,-0.003104452043772,-0.004932855255902,0.940630078315735,40917,-1646,-2741,-4859,1.02868056297302 +27827,-0.003736593062058,-0.001354099367745,0.938359200954437,40917,-1604,-3322,-253,1.02369070053101 +27829,1.85008884727722E-05,-0.005754525773227,0.938126802444458,40917,-1980,-2697,-4820,1.02152585983276 +27831,0.000405687605962,0.000210347672692,0.936465442180634,40917,-1737,-3504,-219,1.02225577831268 +27833,-0.000187595549505,-0.000833496509586,0.934313297271728,40917,-1665,-3004,-4790,1.02214622497559 +27835,0.001773507567123,9.17017241590656E-05,0.931915163993835,40917,-1867,-3130,-217,1.01921105384827 +27837,0.00491383485496,0.005707189440727,0.929103374481201,40917,-2004,-3570,-4771,1.02237415313721 +27839,0.006192726548761,0.009684255346656,0.921934545040131,40917,-1892,-3507,-280,1.02729880809784 +27841,0.004460497293621,0.01181904040277,0.917546093463898,40917,-1650,-3409,-4797,1.03173732757568 +27843,0.007715839892626,0.008821600116789,0.916892349720001,40917,-2063,-3003,-286,1.03512918949127 +27845,0.015173865482211,0.013983407057822,0.913021445274353,40917,-2464,-3659,-4775,1.03513991832733 +27847,0.016768243163824,0.01758181117475,0.909493446350098,40917,-2105,-3625,-320,1.0368732213974 +27849,0.011691498570144,0.015724558383226,0.910996913909912,40917,-1524,-3187,-4737,1.03956985473633 +27851,0.007602201309055,0.013747131451964,0.908108949661255,40917,-1561,-3169,-285,1.03919768333435 +27853,0.008986314758658,0.012443652376533,0.902296125888824,40917,-1953,-3185,-4745,1.03392541408539 +27855,0.004569003824145,0.017847131937742,0.900852024555206,40917,-1485,-3769,-320,1.02807140350342 +27857,-0.002241153735667,0.009823220781982,0.900327980518341,40917,-1208,-2672,-4709,1.02289795875549 +27859,-0.010209529660642,0.004811448976398,0.896367132663727,40917,-980,-2811,257,1.01407992839813 +27861,-0.014241070486605,-0.002404159400612,0.89168906211853,41239,-1228,-2554,-4119,1.01098847389221 +27863,-0.015726832672954,-0.002784146694466,0.887111127376556,41239,-1343,-3015,236,1.01162457466125 +27865,-0.017753938212991,0.003157310420647,0.884453356266022,41239,-1312,-3572,-4082,1.01185262203217 +27867,-0.021078169345856,0.006161452736706,0.879783928394318,41239,-1113,-3402,236,1.01207304000855 +27869,-0.020464319735766,0.009164938703179,0.872712910175324,41239,-1450,-3448,-4076,1.01234459877014 +27871,-0.018437206745148,0.01244115177542,0.866871058940887,41239,-1534,-3524,169,1.01400566101074 +27873,-0.019985063001514,0.008102314546704,0.86396062374115,41239,-1292,-2910,-4053,1.01612186431885 +27875,-0.03017875738442,0.007160938810557,0.860172986984253,41239,-457,-3144,173,1.01829504966736 +27877,-0.031725324690342,0.003180251922458,0.853309452533722,41239,-1109,-2866,-4043,1.02183949947357 +27879,-0.033941127359867,0.008164304308593,0.845718860626221,41239,-959,-3592,84,1.02796256542206 +27881,-0.036022461950779,0.001084586954676,0.841131269931793,41239,-993,-2617,-4047,1.03690052032471 +27883,-0.035517312586308,-0.003871921915561,0.837154865264893,41239,-1117,-2685,63,1.04051887989044 +27885,-0.035049311816692,-0.003125118091702,0.832511901855469,41239,-1174,-3115,-4027,1.04146349430084 +27887,-0.036346293985844,-0.001696570776403,0.828594446182251,41239,-952,-3172,41,1.03763616085053 +27889,-0.034488268196583,-0.000395976996515,0.822097837924957,41239,-1265,-3192,-4021,1.03447616100311 +27891,-0.031085172668099,-0.005279126577079,0.814292013645172,41239,-1355,-2657,-50,1.03089618682861 +27893,-0.033886071294546,-0.002391670597717,0.806850433349609,41239,-924,-3273,-4051,1.02874970436096 +27895,-0.032931875437498,-0.006417108234018,0.802621781826019,41239,-1138,-2695,-113,1.03142106533051 +27897,-0.029897160828114,-0.010164455510676,0.800323665142059,41239,32767,25445,-3175,1.03472816944122 +27899,-0.032449558377266,-0.006292020436376,0.797907650470733,41239,29574,1491,779,1.03575623035431 +27901,-0.032512784004212,-0.001724651316181,0.792482852935791,41239,29492,1380,-3099,1.0371789932251 +27903,-0.027309123426676,0.003924251068383,0.784460008144379,41239,29262,1249,749,1.0385901927948 +27905,-0.023621490225196,0.009391040541232,0.776587128639221,41239,29413,1203,-3081,1.04136765003204 +27907,-0.009513002820313,0.013856929726899,0.765376448631287,41239,28643,1225,650,1.04482591152191 +27909,0.017316585406661,0.028139101341367,0.757072031497955,41239,27476,346,-3091,1.0472651720047 +27911,0.05928985029459,0.043939642608166,0.751864671707153,41239,25814,-34,614,1.04801869392395 +27913,0.109425149857998,0.073732852935791,0.74623030424118,41239,24760,-1388,-3044,1.05083310604095 +27915,0.180072411894798,0.093796119093895,0.74131578207016,41239,22050,-1137,612,1.05345559120178 +27917,0.263982594013214,0.117641471326351,0.734657168388367,41239,20343,-1585,-3003,1.057732462883 +27919,0.359559237957001,0.146032676100731,0.727513909339905,41239,17530,-2589,568,1.06737244129181 +27921,0.469199866056442,0.173059493303299,0.719658136367798,41239,15691,-2627,-2988,1.071364402771 +27923,0.587132215499878,0.201532378792763,0.712956666946411,41239,12315,-3532,512,1.07094764709473 +27925,0.712718069553375,0.225988015532494,0.706594467163086,41239,11085,-3247,-2962,1.07023501396179 +27927,0.839161515235901,0.255328744649887,0.698610901832581,41239,7583,-4531,454,1.0699622631073 +27929,0.978972017765045,0.277715981006622,0.690572142601013,41239,6157,-3913,-2959,1.07585918903351 +27931,1.12578737735748,0.302545428276062,0.682585835456848,41239,1327,-5057,371,1.07877576351166 +27933,1.26707661151886,0.33330637216568,0.675701081752777,41239,1695,-5405,-2951,1.08476173877716 +27935,1.41692185401917,0.361086994409561,0.671465516090393,41239,-3901,-6333,1074,1.0820050239563 +27937,1.5655689239502,0.389451444149017,0.667058706283569,41239,-3472,-6162,-2140,1.07607674598694 +27939,1.71121144294739,0.411031574010849,0.663057625293732,41239,-8817,-6844,1116,1.07078802585602 +27941,1.85282158851624,0.442569106817246,0.65683650970459,41239,-7591,-7301,-2055,1.06772756576538 +27943,1.99849104881287,0.451514422893524,0.649205148220062,41239,-14050,-6761,1087,1.06463265419006 +27945,2.14059853553772,0.466789364814758,0.639915704727173,41239,-12394,-6654,-2018,1.06499791145325 +27947,2.26770663261414,0.486357390880585,0.630669474601746,41239,-17783,-8284,995,1.06972420215607 +27949,2.38324069976807,0.504172921180725,0.625626862049103,41239,-14740,-7563,-1967,1.07583010196686 +27951,2.48984360694885,0.530575394630432,0.620777249336243,41239,-20748,-9704,993,1.09101164340973 +27953,2.59348106384277,0.537820637226105,0.611389636993408,41239,-17782,-7502,-1919,1.10198986530304 +27955,2.68657493591309,0.544142067432404,0.600651562213898,41239,-23906,-8708,868,1.10757672786713 +27957,2.77287626266479,0.545017838478088,0.591965734958649,41239,-20093,-7372,-1910,1.10440289974213 +27959,2.84480214118958,0.561635375022888,0.583832085132599,41239,-25957,-9970,775,1.09712731838226 +27961,2.90176939964294,0.586317002773285,0.575473129749298,41239,-20897,-9906,-1885,1.09371888637543 +27963,2.94368743896484,0.601299047470093,0.567314207553864,41239,-26470,-10750,670,1.08421623706818 +27965,2.97513198852539,0.601931273937225,0.556895017623901,41239,-21227,-8664,-1879,1.07208228111267 +27967,2.99942421913147,0.600438356399536,0.544217526912689,41239,-27210,-9816,495,1.06365263462067 +27969,3.01027178764343,0.610340476036072,0.533015966415405,41239,-21393,-9708,-1914,1.05227243900299 +27971,3.00483632087708,0.615596115589142,0.522972941398621,41239,-26304,-10804,328,1.04266953468323 +27973,2.98856163024902,0.611664056777954,0.512810587882996,41239,-20286,-9003,-1668,1.03512561321259 +27975,2.95928645133972,0.603531658649445,0.500493288040161,41239,-24993,-9911,425,1.02910912036896 +27977,2.9191107749939,0.591786682605743,0.488284051418304,41239,-18713,-8421,-1700,1.02827203273773 +27979,2.87232065200806,0.590697109699249,0.478874444961548,41239,-23434,-10488,278,1.0284503698349 +27981,2.81409573554993,0.589361548423767,0.472981572151184,41239,-17015,-9394,-1672,1.03153169155121 +27983,2.7465124130249,0.581862151622772,0.462838470935822,41239,-20970,-10168,193,1.0347146987915 +27985,2.67001461982727,0.57107949256897,0.447175294160843,41239,-14691,-8720,-1721,1.03597474098206 +27987,2.58989191055298,0.552439153194428,0.431616097688675,41239,-18538,-9137,-56,1.03803789615631 +27989,2.4937379360199,0.536916971206665,0.421847283840179,41239,-11739,-8140,-1771,1.03965413570404 +27991,2.39171576499939,0.517165660858154,0.416006863117218,41239,-14685,-8718,-117,1.04137909412384 +27993,2.28934955596924,0.505091845989227,0.410583049058914,41239,-9263,-8165,-1728,1.03665316104889 +27995,2.18067216873169,0.487337172031403,0.402837574481964,41239,-11633,-8605,-151,1.0310230255127 +27997,2.06622171401978,0.462167531251907,0.392452567815781,41239,-6005,-6834,-1734,1.03056812286377 +27999,1.94843006134033,0.432007998228073,0.383765459060669,41239,-7957,-7024,-229,1.03148686885834 +28001,1.82359111309052,0.402629464864731,0.376439929008484,41239,-2487,-5876,-1727,1.03428816795349 +28003,1.69996643066406,0.371740460395813,0.367111057043076,41239,-4139,-6175,-269,1.03839385509491 +28005,1.5848343372345,0.339451134204864,0.353835016489029,41239,-352,-4931,-1767,1.03589701652527 +28007,1.46570539474487,0.301955074071884,0.338828444480896,41239,-1189,-4719,-434,1.03428733348846 +28009,1.33925187587738,0.274001806974411,0.328466057777405,41239,3492,-4442,-1698,1.03617191314697 +28025,0.496823877096176,0.004917332902551,0.256262898445129,41239,11638,-1321,-1718,1.02010953426361 +28027,0.424372345209122,-0.017586836591363,0.249931454658508,41239,11184,-915,-465,1.0279952287674 +28029,0.363491386175156,-0.053462583571673,0.245595887303352,41239,11841,584,-1674,1.03610944747925 +28031,0.310540825128555,-0.093238666653633,0.239602476358414,41239,11636,1573,-395,1.04118120670319 +28033,0.262560278177261,-0.12080904096365,0.231312066316605,41239,12393,996,-1654,1.04372119903564 +28035,0.223581209778786,-0.134116053581238,0.220909222960472,41239,12092,400,-456,1.04417037963867 +28037,0.193608120083809,-0.146646127104759,0.212190791964531,41239,12159,351,-1670,1.04263854026794 +28039,0.168194651603699,-0.163945376873016,0.206456035375595,41239,12091,1249,-480,1.0386803150177 +28041,0.148478358983994,-0.184976503252983,0.199791878461838,41239,12162,1587,-1640,1.03931772708893 +28043,0.139322623610497,-0.195235878229141,0.195845723152161,41239,11486,1343,-460,1.04159009456635 +28045,0.147440358996391,-0.20033298432827,0.193790003657341,41239,10286,759,-1567,1.04390633106232 +28047,0.163060113787651,-0.201709434390068,0.187453746795654,41239,-26628,-2883,-436,1.04927682876587 +28049,0.180011957883835,-0.198871999979019,0.1814024746418,41239,3188,-373,-1539,1.0549328327179 +28051,0.199310690164566,-0.200389489531517,0.177512541413307,41239,2538,343,-442,1.06176316738129 +28053,0.223416104912758,-0.20830711722374,0.171906247735024,41239,2068,621,-1492,1.06861019134521 +28055,0.252843737602234,-0.21865938603878,0.162858992815018,41239,939,1372,-484,1.07458186149597 +28057,0.281203240156174,-0.214033871889114,0.153649464249611,41239,923,-95,-1508,1.07788681983948 +28059,0.306622087955475,-0.207441106438637,0.147662281990051,41239,326,82,-564,1.07680344581604 +28061,0.333853453397751,-0.205841183662414,0.141161754727364,41239,211,100,-1486,1.07079458236694 +28063,0.359902173280716,-0.202006742358208,0.133761361241341,41239,-624,290,-624,1.06500971317291 +28065,0.380844682455063,-0.196696490049362,0.128110155463219,41239,-73,-201,-1471,1.06039643287659 +28067,0.398640692234039,-0.181314215064049,0.11969518661499,41239,-723,-773,-703,1.05693161487579 +28069,0.421374768018723,-0.165977954864502,0.1076405569911,41239,-861,-1273,-1510,1.05582165718079 +28071,0.445942133665085,-0.150917395949364,0.099507391452789,41239,-2068,-1150,-869,1.05737364292145 +28073,0.468022435903549,-0.128917530179024,0.096589855849743,41239,-1585,-2206,-1488,1.05849719047546 +28075,0.490234851837158,-0.107402928173542,0.093206360936165,41239,-2735,-2250,-890,1.05941331386566 +28077,0.509059309959412,-0.087595596909523,0.088988803327084,41239,-2064,-2585,-1445,1.05726110935211 +28079,0.524862289428711,-0.065774016082287,0.079978346824646,41239,-2976,-2899,-994,1.05398869514465 +28081,0.540225446224213,-0.048576049506664,0.07163754850626,41239,-2406,-2919,-1473,1.05551207065582 +28083,0.555804193019867,-0.029525576159358,0.065881550312042,41239,-3618,-3252,-1106,1.05886495113373 +28085,0.575144648551941,-0.009852756746113,0.061652421951294,41239,-3351,-3630,-1453,1.0626802444458 +28087,0.593866884708405,0.006937595549971,0.059699647128582,41239,-4627,-3665,-1129,1.0650577545166 +28089,0.608824014663696,0.021229095757008,0.055633809417486,41239,-3697,-3683,-1408,1.06276702880859 +28091,0.6210657954216,0.033580709248781,0.047078128904104,41239,-4785,-3767,-1219,1.0586371421814 +28093,0.627712965011597,0.050797328352928,0.037248369306326,41239,-3564,-4321,-1452,1.05269134044647 +28095,0.631595849990845,0.064772419631481,0.032539028674364,41239,-4554,-4383,-1341,1.047034740448 +28097,0.634701311588287,0.081765726208687,0.031465373933315,41239,-3608,-4765,-1412,1.0443195104599 +28099,0.634002566337585,0.10404808819294,0.025195645168424,41239,-4459,-5637,-1391,1.04270374774933 +28101,0.63606458902359,0.123051829636097,0.016168193891645,41239,-3753,-5534,-1440,1.04225933551788 +28103,0.636455059051514,0.133581340312958,0.011088941246271,41239,-4778,-5312,-1513,1.04516971111298 +28105,0.628438651561737,0.135462746024132,0.00768450461328,41239,-3125,-4532,-1424,1.0483615398407 +28107,0.618876993656158,0.142703518271446,0.003305251244456,41239,-3991,-5268,-1543,1.05235958099365 +28109,0.609884142875671,0.156671851873398,-0.001159125356935,41239,-2987,-5752,-1413,1.0561238527298 +28111,0.599792182445526,0.158452242612839,-0.004848122131079,41239,-3840,-5185,-1585,1.0549236536026 +28113,0.585662245750427,0.15496127307415,-0.011447844095528,41239,-2463,-4534,-1414,1.05267298221588 +28115,0.573296368122101,0.15383692085743,-0.018736984580755,41239,-3429,-4956,-1674,1.0507230758667 +28117,0.562078177928925,0.152507871389389,-0.02221629396081,41239,-2513,-4709,-1420,1.04738259315491 +28119,0.546525359153748,0.152153208851814,-0.023900605738163,41239,-2932,-5036,-1664,1.04643428325653 +28121,0.531419992446899,0.147257596254349,-0.028187490999699,41239,-1963,-4433,-1393,1.04587125778198 +28123,0.513702750205994,0.141761973500252,-0.031697079539299,41239,-32767,-10676,-1703,1.04159700870514 +28125,0.493373423814774,0.139337912201881,-0.036065757274628,41060,-7286,-5581,-1755,1.03686141967773 +28127,0.447409749031067,0.138573944568634,-0.047911643981934,41060,-6547,-5787,-1426,1.03371322154999 +28129,0.418297916650772,0.131836220622063,-0.054701078683138,41060,-6497,-5430,-1835,1.0349428653717 +28131,0.418297916650772,0.131836220622063,-0.054701078683138,41060,-6497,-5430,-1835,1.0349428653717 +28133,0.350904762744904,0.110246181488037,-0.066217891871929,41060,-5188,-4854,-1883,1.03885447978973 +28135,0.310019284486771,0.101252526044846,-0.066904097795487,41060,-3696,-4717,-1435,1.04420518875122 +28137,0.263928025960922,0.094641275703907,-0.071683123707771,41060,-3032,-4907,-1866,1.04214644432068 +28139,0.217034265398979,0.078898578882218,-0.077832885086537,41060,-2032,-3947,-1449,1.03692924976349 +28141,0.217034265398979,0.078898578882218,-0.077832885086537,41060,-2032,-3947,-1449,1.03692924976349 +28143,0.1331667304039,0.040554765611887,-0.087535284459591,41060,-1327,-3381,-1456,1.02352452278137 +28145,0.087535634636879,0.021955018863082,-0.094446793198586,41060,-316,-2884,-1927,1.0192323923111 +28147,0.040214151144028,0.00486640445888,-0.101650662720203,41060,457,-2802,-1493,1.01556134223938 +28149,-0.009175810031593,-0.011255228891969,-0.108242876827717,41060,1510,-2516,-1991,1.01545441150665 +28151,-0.009175810031593,-0.011255228891969,-0.108242876827717,41060,1510,-2516,-1991,1.01545441150665 +28153,-0.105524197220802,-0.027723781764507,-0.116571716964245,41060,2986,-2932,-2011,1.01613998413086 +28155,-0.149344235658646,-0.048356868326664,-0.11774431169033,41060,3016,-1745,-1488,1.01803779602051 +28157,-0.189593553543091,-0.061502516269684,-0.119721181690693,41060,3917,-1873,-1950,1.0186026096344 +28179,-0.572186231613159,-0.235171407461166,-0.169926553964615,41060,3284,-1752,-1500,1.03642451763153 +28181,-0.601521849632263,-0.261811941862106,-0.173631265759468,41060,4646,-378,-2021,1.03228425979614 +28183,-0.628542602062225,-0.280676573514938,-0.177842244505882,41060,3699,-1197,-1497,1.02767014503479 +28185,-0.650909125804901,-0.306095898151398,-0.181255429983139,41060,5202,376,-2009,1.0217981338501 +28187,-0.667246580123901,-0.338516920804977,-0.184704661369324,41060,3758,732,-1487,1.01801824569702 +28189,-0.682975709438324,-0.362977206707001,-0.189263746142387,41060,5519,1370,-1989,1.02099597454071 +28191,-0.693974435329437,-0.369989305734634,-0.195106372237206,41060,4043,-481,-1500,1.02462017536163 +28193,-0.705521583557129,-0.366662204265594,-0.197706013917923,41060,5868,-412,-2033,1.03014826774597 +28195,-0.71325421333313,-0.382151693105698,-0.19739693403244,41060,4382,457,-1459,1.03398609161377 +28197,-0.722787320613861,-0.40192648768425,-0.197975635528564,41060,-32767,1974,-2033,1.03453385829926 +28199,-0.730960130691528,-0.411202311515808,-0.201317504048347,41006,-7205,602,-1515,1.0388970375061 +28201,-0.732349812984467,-0.414707809686661,-0.207466065883636,41006,-6046,1202,-2087,1.03870093822479 +28203,-0.732999682426453,-0.412375539541245,-0.214178934693336,41006,-7520,-29,-1553,1.03493762016296 +28205,-0.733208119869232,-0.409469455480576,-0.217019304633141,41006,-5925,850,-2162,1.02958142757416 +28207,-0.734458148479462,-0.405025571584702,-0.221447616815567,41006,-7260,-103,-1554,1.02254390716553 +28209,-0.736435055732727,-0.399146556854248,-0.229611918330193,41006,-5545,657,-2279,1.02248132228851 +28211,-0.747134387493133,-0.388177961111069,-0.23796346783638,41006,-6200,-631,-1621,1.02743721008301 +28213,-0.771173238754272,-0.380751043558121,-0.244428738951683,41006,-3189,423,-2433,1.0298957824707 +28215,-0.794682443141937,-0.382822126150131,-0.25022691488266,41006,-4380,399,-1662,1.03492391109467 +28217,-0.81640899181366,-0.384078204631805,-0.253970384597778,41006,-2407,1268,-2508,1.03973937034607 +28219,-0.841164767742157,-0.37544721364975,-0.258014470338821,41006,-3384,-297,-1675,1.04195654392242 +28221,-0.872687578201294,-0.357895165681839,-0.260636806488037,41006,-554,-335,-2579,1.04533934593201 +28223,-0.906091570854187,-0.335423499345779,-0.263360649347305,41006,-1567,-1698,-1672,1.04525816440582 +28225,-0.935320079326629,-0.319705098867416,-0.267764061689377,41006,590,-665,-2668,1.04454910755157 +28227,-0.961968660354614,-0.314987927675247,-0.270201742649078,41006,-949,-571,-1683,1.0426310300827 +28229,-0.991264820098877,-0.311458796262741,-0.268902212381363,41006,1833,224,-2659,1.03658199310303 +28231,-1.02387511730194,-0.305660873651505,-0.26624396443367,41006,697,-635,-1620,1.02969896793365 +28233,-1.05585563182831,-0.284374982118607,-0.266873627901077,41006,3426,-1333,-2678,1.02208757400513 +28235,-1.08362400531769,-0.265308141708374,-0.268808156251907,41006,1573,-2027,-1649,1.01839351654053 +28237,-1.1118221282959,-0.252290278673172,-0.268113404512405,41006,4432,-1140,-2697,1.01505446434021 +28239,-1.14081037044525,-0.235635355114937,-0.268152683973312,41006,2874,-2158,-1614,1.01550710201263 +28241,-1.16671824455261,-0.218658730387688,-0.273811817169189,41006,5548,-1867,-2771,1.01894319057465 +28243,-1.1894017457962,-0.19606976211071,-0.280853867530823,41006,3539,-3045,-1673,1.01993596553803 +28245,-1.20772290229797,-0.173954367637634,-0.28119882941246,41006,6089,-2871,-2874,1.02341818809509 +28247,-1.22612500190735,-0.158012464642525,-0.281393080949783,41006,4199,-3030,-1651,1.02695822715759 +28249,-1.24908423423767,-0.144502997398376,-0.281966358423233,41006,7546,-2654,-2886,1.02917838096619 +28251,-1.26771223545074,-0.130331456661224,-0.281178176403046,41006,5275,-3229,-1625,1.03093123435974 +28253,-1.27835726737976,-0.113282434642315,-0.282278150320053,41006,7614,-3347,-2895,1.03078544139862 +28255,-1.28678119182587,-0.097522743046284,-0.282940655946732,41006,5299,-3755,-1613,1.03326654434204 +28257,-1.2887544631958,-0.093062557280064,-0.282930761575699,41006,7645,-2718,-2898,1.03761184215546 +28259,-1.28617739677429,-0.088456749916077,-0.285289704799652,41006,4993,-3036,-1606,1.04302597045898 +28261,-1.27599847316742,-0.077132277190685,-0.289893835783005,41006,7052,-3420,-2973,1.04903936386108 +28263,-1.26392340660095,-0.060604970902205,-0.294539600610733,41006,4481,-4246,-1649,1.05205881595612 +28265,-1.25646781921387,-0.046971794217825,-0.300651609897613,41006,7415,-4038,-3103,1.05033826828003 +28267,-1.24899852275848,-0.045487347990275,-0.30668830871582,41006,5080,-3355,-1713,1.04738521575928 +28269,-1.23888576030731,-0.047188155353069,-0.306033104658127,41006,7415,-2902,-3150,1.04445922374725 +28271,-1.21930384635925,-0.044973742216826,-0.302475601434708,41006,4264,-3384,-1667,1.0447291135788 +28273,-1.19146835803986,-0.03961743041873,-0.302689075469971,41006,5831,-3506,-3101,1.04570758342743 +28275,-1.16427040100098,-0.040449861437082,-0.303959786891937,41006,3387,-3203,-1659,1.04632365703583 +28277,-1.13727021217346,-0.043433893471956,-0.305231928825378,41006,5449,-2828,-3112,1.04452466964722 +28279,-1.11033225059509,-0.03788872435689,-0.307041645050049,41006,3067,-3670,-1662,1.04351353645325 +28281,-1.07833564281464,-0.038274701684713,-0.306891590356827,41006,4557,-3078,-3119,1.04394435882568 +28283,-1.04626679420471,-0.034601997584105,-0.30997097492218,41006,2192,-3558,-1665,1.04502820968628 +28285,-1.01214170455933,-0.029777515679598,-0.312298834323883,41006,3728,-3562,-3173,1.0460342168808 +28287,-0.975735902786255,-0.026220263913274,-0.311613380908966,41006,1254,-3649,-1660,1.04349720478058 +28289,-0.937151670455933,-0.020571406930685,-0.309122800827026,41006,2564,-3757,-3125,1.03694629669189 +28291,-0.893452048301697,-0.018051013350487,-0.310288071632385,41006,-94,-3675,-1635,1.03229975700378 +28293,-0.859067022800446,-0.009090662933886,-0.314213335514069,41006,1930,-4167,-3177,1.03411567211151 +28295,-0.827671885490418,-0.006722950842232,-0.317161619663238,41006,163,-3816,-1667,1.04172384738922 +28297,-0.794249653816223,-0.007519523613155,-0.32054677605629,41006,1258,-3479,-3238,1.04932916164398 +28299,-0.755558550357819,-0.006845131516457,-0.321214914321899,41006,-1100,-3681,-1680,1.05328512191772 +28301,-0.718736290931702,-0.009188654832542,-0.319021642208099,41006,66,-3332,-3205,1.05257022380829 +28303,-0.686430752277374,-0.008801373653114,-0.318882346153259,41006,-1372,-3621,-1650,1.04656600952148 +28305,-0.64721816778183,-0.011709264479578,-0.323073714971542,41006,-1037,-3244,-3238,1.04698395729065 +28307,-0.608958423137665,-0.008967766538262,-0.32867294549942,41006,-2682,-3775,-1703,1.04865789413452 +28309,-0.579775929450989,-0.00036699543125,-0.331132650375366,41006,-1213,-4247,-3463,1.0536013841629 +28311,-0.552443981170654,0.000840040796902,-0.332164317369461,41006,-2513,-3799,-1856,1.05978214740753 +28331,-0.36125585436821,-0.049676429480314,-0.343225032091141,41006,-3437,-2720,-1920,1.03991651535034 +28333,-0.358279913663864,-0.04917972907424,-0.343187481164932,41006,-2076,-2764,-3570,1.04106962680817 +28335,-0.357738792896271,-0.052819546312094,-0.345664530992508,41006,-2598,-2561,-1935,1.04071891307831 +28337,-0.354704916477203,-0.062193460762501,-0.350720345973968,41006,-2047,-1819,-3653,1.03865730762482 +28339,-0.350771099328995,-0.078183688223362,-0.354018270969391,41006,-2836,-1277,-1991,1.03697991371155 +28341,-0.352884978055954,-0.079921565949917,-0.354295372962952,41006,-1629,-2048,-3689,1.03257429599762 +28343,-0.359481185674667,-0.075928777456284,-0.352254778146744,41006,-1856,-2698,-1979,1.03572523593903 +28345,-0.35866767168045,-0.076335176825523,-0.350931018590927,41006,-1648,-2164,-3651,1.04151356220245 +28347,-0.356107443571091,-0.078183263540268,-0.3485446870327,41006,-2457,-2207,-2005,1.04477345943451 +28349,-0.358088612556458,-0.088559195399284,-0.348066985607147,41006,-1344,-1213,-3666,1.04574418067932 +28351,-0.36932498216629,-0.089170552790165,-0.351205796003342,41006,-1173,-2093,-2025,1.04472208023071 +28353,-0.381940215826035,-0.099295094609261,-0.353141695261002,41006,-69,-996,-3725,1.04553496837616 +28355,-0.393481135368347,-0.11355934292078,-0.357314884662628,41006,-684,-712,-2070,1.03923964500427 +28357,-0.403614729642868,-0.122138157486916,-0.361440449953079,41006,236,-669,-3818,1.03018736839294 +28359,-0.414973556995392,-0.124248467385769,-0.364713579416275,41006,-255,-1364,-2125,1.0213440656662 +28361,-0.426207661628723,-0.117488786578178,-0.368227511644363,41006,814,-1778,-3906,1.01196277141571 +28363,-0.43654215335846,-0.116771556437016,-0.371704936027527,41006,123,-1610,-2178,1.01279807090759 +28365,-0.446091771125794,-0.118692792952061,-0.375008851289749,41006,1168,-1078,-3992,1.01606369018555 +28367,-0.461874127388001,-0.118415251374245,-0.375819742679596,41006,1032,-1491,-2213,1.02146077156067 +28369,-0.47875714302063,-0.116603247821331,-0.37394055724144,41006,2383,-1321,-3988,1.02573704719543 +28371,-0.491678446531296,-0.108008503913879,-0.371166169643402,41006,1426,-2173,-2188,1.03028726577759 +28373,-0.498678475618362,-0.103359393775463,-0.367215991020203,41006,2156,-1685,-3921,1.03586030006409 +28375,-0.501130998134613,-0.096528150141239,-0.364610075950623,41006,990,-2156,-2148,1.03686487674713 +28377,-0.506611585617065,-0.087409377098084,-0.365397453308106,41006,2346,-2218,-3912,1.04008162021637 +28379,-0.515344023704529,-0.085100769996643,-0.369521945714951,41006,1825,-1948,-2187,1.04392004013062 +28381,-0.529477536678314,-0.08154309540987,-0.371980726718903,41006,3525,-1875,-3998,1.04814577102661 +28383,-0.538690686225891,-0.080691523849964,-0.371805459260941,41006,2389,-1862,-2294,1.04883432388306 +28385,-0.543868839740753,-0.077648587524891,-0.37442147731781,41006,3326,-1855,-4124,1.04638922214508 +28387,-0.54552561044693,-0.08486520498991,-0.376148611307144,41006,2150,-1181,-2337,1.04397654533386 +28389,-0.549771666526794,-0.080192945897579,-0.375062584877014,41006,3576,-1879,-4144,1.03522109985352 +28391,-0.557125687599182,-0.059754639863968,-0.373086541891098,41006,2936,-3476,-2329,1.02940464019775 +28393,-0.558929622173309,-0.043276805430651,-0.37177911400795,41006,3754,-3282,-4130,1.02391064167023 +28395,-0.557166755199432,-0.033947367221117,-0.375462859869003,41006,2499,-3020,-2358,1.01992750167847 +28397,-0.548842549324035,-0.036166787147522,-0.377610832452774,41006,3068,-2028,-4215,1.01747190952301 +28399,-0.537326455116272,-0.035880699753761,-0.375423073768616,41006,1726,-2318,-2371,1.01314234733582 +28401,-0.532776772975922,-0.035044107586145,-0.373059570789337,41006,3287,-2240,-4176,1.01525104045868 +28403,-0.527879953384399,-0.029915692284703,-0.373335093259811,41006,2270,-2723,-2370,1.02059042453766 +28405,-0.519844770431519,-0.018660234287381,-0.377736419439316,41006,3041,-3233,-4249,1.02463388442993 +28407,-0.507502377033234,-0.015485659241676,-0.379958868026733,41006,1648,-2771,-2430,1.02878737449646 +28409,-0.496317118406296,-0.010377431288362,-0.377295345067978,41006,2621,-2916,-4261,1.03172397613525 +28411,-0.484106123447418,-0.012471265159547,-0.375588834285736,41006,1514,-2423,-2414,1.03481650352478 +28413,-0.468979597091675,-0.014216607436538,-0.373241603374481,41006,2072,-2361,-4226,1.03632509708405 +28415,-0.461229741573334,0.000191383602214,-0.370920211076736,41006,1685,-3774,-2395,1.03637909889221 +28417,-0.451043367385864,0.004269648343325,-0.369457513093948,41006,2304,-3084,-4199,1.03700864315033 +28419,-0.441539913415909,0.011040471494198,-0.36977681517601,41006,1448,-3380,-2400,1.04321956634521 +28421,-0.424263507127762,0.005996032152325,-0.370942741632462,41006,1535,-2448,-4928,1.05051469802856 +28423,-0.407916039228439,0.011653100140393,-0.372833371162415,41006,637,-3305,-3155,1.05209898948669 +28425,-0.394652009010315,0.022336250171065,-0.372179687023163,41006,1506,-3831,-5006,1.05319201946259 +28427,-0.380989879369736,0.023753892630339,-0.367345184087753,41006,594,-3178,-3178,1.04720592498779 +28429,-0.364516794681549,0.024316439405084,-0.367687523365021,41006,926,-3139,-5014,1.0390841960907 +28431,-0.346018821001053,0.027493545785546,-0.370137929916382,41006,-115,-3361,-3257,1.0321569442749 +28433,-0.33122855424881,0.037203714251518,-0.366981744766235,41006,630,-4005,-5068,1.02743494510651 +28435,-0.316021680831909,0.040061317384243,-0.362260371446609,41006,-188,-3526,-3262,1.02723670005798 +28437,-0.298594266176224,0.036597039550543,-0.357001066207886,41006,35,-3062,-5009,1.02644467353821 +28439,-0.289627403020859,0.036159094423056,-0.352145791053772,41006,-10,-3243,-3251,1.02871251106262 +28441,-0.282548636198044,0.032600145787001,-0.346080124378204,41006,629,-2999,-4936,1.02955675125122 +28443,-0.275008916854858,0.03688869997859,-0.341993361711502,41006,-13,-3599,-3237,1.03124344348907 +28445,-0.258323520421982,0.029410595074296,-0.341312706470489,41006,-350,-2669,-4935,1.03383803367615 +28447,-0.249439015984535,0.028654536232352,-0.341941446065903,41006,-381,-3124,-3292,1.03599059581757 +28449,-0.239915862679481,0.021413533017039,-0.342896044254303,41006,-56,-2565,-5008,1.03689563274384 +28451,-0.224588245153427,0.020613446831703,-0.339314371347427,41006,-1114,-3008,-3330,1.02850186824799 +28453,-0.217122435569763,0.028888005763292,-0.333048611879349,41006,-209,-3815,-4948,1.02004504203796 +28455,-0.215329095721245,0.025269253179431,-0.327177315950394,41006,-204,-2881,-3301,1.01771903038025 +28457,-0.212581127882004,0.017166135832667,-0.322637528181076,41006,127,-2462,-4877,1.02076780796051 +28459,-0.201074317097664,0.007572580128908,-0.318424671888351,41006,-1033,-2202,-3293,1.02799999713898 +28461,-0.189406737685204,0.010491346009076,-0.315607070922852,41006,-824,-3144,-4845,1.03204798698425 +28463,-0.18346731364727,0.005020676646382,-0.314107567071915,41006,-825,-2461,-3314,1.03783547878265 +28481,-0.163648962974548,-0.008890241384506,-0.289131164550781,41006,-231,-2916,-4775,1.04484152793884 +28483,-0.166158616542816,-0.011861398816109,-0.285602539777756,41006,-207,-2363,-3361,1.03958511352539 +28485,-0.169346004724503,-0.012502588331699,-0.280365735292435,41006,232,-2464,-4718,1.0341545343399 +28487,-0.172317251563072,-0.016665497794747,-0.275021821260452,41006,-30,-2196,-3334,1.03552055358887 +28489,-0.176098525524139,-0.014651429839432,-0.271878600120544,41006,441,-2601,-4663,1.03391110897064 +28491,-0.178788751363754,-0.012731217779219,-0.270678579807281,41006,100,-2673,-3348,1.03399205207825 +28493,-0.17689922451973,-0.013490179553628,-0.272910237312317,41006,121,-2415,-4719,1.02924990653992 +28495,-0.185506656765938,-0.00192925077863,-0.270922601222992,41006,683,-3507,-3394,1.02986943721771 +28497,-0.192062735557556,-0.007642131764442,-0.265400469303131,41006,1050,-2151,-4675,1.03078186511993 +28499,-0.194811567664146,-0.014960242435336,-0.263927459716797,41006,469,-1958,-3389,1.03228259086609 +28501,-0.198036819696426,-0.024553421884775,-0.264253914356232,41006,982,-1585,-4703,1.03227245807648 +28503,-0.206297606229782,-0.017181972041726,-0.261718273162842,41006,1104,-2962,-3416,1.0288405418396 +28505,-0.214650511741638,-0.003789544571191,-0.256088674068451,41006,1693,-3555,-4652,1.02424359321594 +28507,-0.21501886844635,-0.002590751508251,-0.252864599227905,41006,746,-2721,-3397,1.02301621437073 +28509,-0.211871966719627,-0.008658467791975,-0.254445970058441,41006,896,-2074,-4673,1.02278017997742 +28511,-0.212806671857834,-0.027555041015148,-0.253499358892441,41006,835,-914,-3443,1.02492868900299 +28513,-0.221419438719749,-0.031080026179552,-0.252626746892929,41006,1968,-1882,-4691,1.02786600589752 +28515,-0.225911632180214,-0.037252236157656,-0.252539962530136,41006,1362,-1666,-3478,1.03294277191162 +28517,-0.233012527227402,-0.027922423556447,-0.251188039779663,41006,2139,-2842,-4715,1.03252625465393 +28519,-0.231159090995789,-0.018746579065919,-0.246408939361572,41006,1074,-3014,-3476,1.03386735916138 +28521,-0.233132541179657,-0.013667846098542,-0.241911053657532,41006,1861,-2757,-4648,1.03560435771942 +28523,-0.238411128520966,-0.007706954609603,-0.239446476101875,41006,1780,-2932,-3468,1.03718495368958 +28525,-0.238664656877518,-0.01175494864583,-0.237185686826706,41006,1911,-2123,-4631,1.04031157493591 +28527,-0.232062891125679,-0.015728324651718,-0.236785367131233,41006,930,-2096,-3488,1.0424075126648 +28529,-0.225731268525124,-0.021967319771648,-0.235264703631401,41006,1317,-1791,-4646,1.04505920410156 +28531,-0.22296541929245,-0.022615080699325,-0.233512490987778,41006,1162,-2221,-3504,1.04328763484955 +28533,-0.222247585654259,-0.014131991192699,-0.226021781563759,41006,1749,-2960,-4576,1.04413044452667 +28535,-0.219962880015373,-0.00970749091357,-0.215982988476753,41006,1239,-2760,-3420,1.04356670379639 +28537,-0.222690746188164,-0.000597502570599,-0.21523942053318,41006,2090,-3219,-4486,1.04335641860962 +28539,-0.22108855843544,0.002028390299529,-0.218590930104256,41006,1391,-2795,-3473,1.04336166381836 +28541,-0.226531341671944,0.019166268408299,-0.218239113688469,41006,2436,-4115,-4559,1.04291117191315 +28543,-0.224977448582649,0.021206062287092,-0.214637085795403,41006,1540,-3033,-3482,1.03769814968109 +28545,-0.220899790525436,0.021005246788263,-0.212430521845818,41006,1748,-2911,-4526,1.04057812690735 +28547,-0.217468291521072,0.018040522933006,-0.210094556212425,41006,1385,-2635,-3485,1.04782915115356 +28549,-0.204744279384613,0.012867363169789,-0.211137324571609,41006,949,-2423,-4544,1.05670177936554 +28551,-0.194448664784431,0.012032805010676,-0.21213299036026,41006,644,-2704,-3534,1.06206905841827 +28553,-0.190426662564278,0.008273637853563,-0.206865429878235,41006,1426,-2447,-4528,1.06370210647583 +28555,-0.190762624144554,0.020423706620932,-0.202156141400337,41006,1428,-3754,-3499,1.062704205513 +28557,-0.185183987021446,0.018081856891513,-0.197662994265556,41006,1309,-2709,-4453,1.05599737167358 +28559,-0.183297947049141,0.016681669279933,-0.194718942046165,41006,1237,-2734,-3481,1.04827129840851 +28561,-0.179141253232956,0.018791247159243,-0.193040460348129,41006,1381,-3044,-4431,1.04714179039001 +28563,-0.171594902873039,0.020489035174251,-0.191568911075592,41006,735,-3014,-3491,1.04216051101685 +28565,-0.156960636377335,0.016414573416114,-0.189454436302185,41006,328,-2572,-4420,1.03684294223785 +28567,-0.15003676712513,0.011501547880471,-0.186862155795097,41006,531,-2416,-3489,1.03091728687286 +28569,-0.150482282042503,0.021037554368377,-0.185043081641197,41006,1359,-3630,-4399,1.02911448478699 +28571,-0.147935524582863,0.023502007126808,-0.184805795550346,41006,872,-3123,-3505,1.03250527381897 +28573,-0.145411416888237,0.025429151952267,-0.184738919138908,40899,1125,-3160,-4426,1.0313640832901 +28575,-0.144495368003845,0.022119857370854,-0.179284363985062,40899,996,-2698,-3498,1.03404366970062 +28577,-0.135063216090202,0.015278916805983,-0.176883175969124,40899,516,-2372,-4362,1.0283008813858 +28579,-0.12573330104351,0.012087885290384,-0.176475122570992,40899,176,-2566,-3507,1.0255389213562 +28581,-0.118001200258732,-0.003364760894328,-0.174655884504318,40899,407,-1452,-4364,1.02349257469177 +28583,-0.115761749446392,-0.003818126861006,-0.172156095504761,40899,585,-2529,-3506,1.02101457118988 +28585,-0.116347819566727,-0.010773082263768,-0.169409140944481,40899,1018,-1944,-4330,1.01822102069855 +28587,-0.121156319975853,-0.001932910177857,-0.168085008859634,40899,1210,-3215,-3506,1.01657724380493 +28589,-0.119164608418942,-0.002040334511548,-0.165810093283653,40899,921,-2576,-4316,1.02068912982941 +28591,-0.112653620541096,-0.009389182552695,-0.163766846060753,40899,322,-1947,-3504,1.0208512544632 +28593,-0.10833964496851,-0.00820351857692,-0.162640824913979,40899,628,-2559,-4305,1.02435147762299 +28595,-0.106651574373245,-0.008885278366506,-0.158835723996162,40899,623,-2425,-3496,1.02468693256378 +28597,-0.107019059360027,-0.005226473789662,-0.154982268810272,40899,980,-2782,-4241,1.02125120162964 +28599,-0.103929601609707,-0.015683848410845,-0.152912080287933,40899,524,-1623,-3481,1.01832759380341 +28601,-0.108135424554348,-0.012826666235924,-0.149746879935265,40899,1306,-2592,-4204,1.01753222942352 +28603,-0.102072045207024,-0.017122104763985,-0.145800411701202,40899,324,-2036,-3457,1.02626299858093 +28605,-0.094765454530716,-0.021224908530712,-0.143480747938156,40899,297,-1939,-4154,1.02926993370056 +28607,-0.092826426029205,-0.021638503298164,-0.140224203467369,40899,520,-2235,-3442,1.02735686302185 +28609,-0.09926038980484,-0.025965075939894,-0.140162363648415,40899,-32767,-32767,-4138,1.02667820453644 +28611,-0.100698843598366,-0.023387882858515,-0.142371907830238,40774,-24544,-9962,-3480,1.02929365634918 +28613,-0.100235976278782,-0.021064871922135,-0.141137897968292,40774,-24622,-9959,-4173,1.03560554981232 +28615,-0.098211273550987,-0.019253129139543,-0.142234593629837,40774,-25041,-10027,-3502,1.0339777469635 +28631,-0.395756125450134,-0.165311828255653,-0.163490206003189,40774,-15845,-5585,-3748,0.993393182754517 +28633,-0.479865312576294,-0.197269380092621,-0.164072588086128,40774,-13199,-4812,-4565,0.99729311466217 +28635,-0.57495242357254,-0.22763903439045,-0.168677821755409,40774,-11964,-4853,-3811,1.00747764110565 +28637,-0.671133756637573,-0.26094052195549,-0.172903954982758,40774,-9221,-3641,-4699,1.01951205730438 +28639,-0.770580947399139,-0.290674537420273,-0.173923492431641,40774,-8789,-3943,-3875,1.01866543292999 +28641,-0.876858115196228,-0.325676411390305,-0.171381965279579,40774,-5061,-2406,-4714,1.01377606391907 +28643,-0.996537566184998,-0.357144504785538,-0.170083880424499,40774,-3946,-2783,-3878,1.00607979297638 +28645,-1.11913871765137,-0.391372829675674,-0.16834282875061,40774,244,-1305,-4715,1.00512051582336 +28647,-1.23131918907166,-0.438715547323227,-0.169754341244698,40774,-849,-364,-3904,1.00892269611359 +28649,-1.34486055374146,-0.478379100561142,-0.174031913280487,40774,3578,622,-4825,1.01090204715729 +28651,-1.46066999435425,-0.521212518215179,-0.173208490014076,40774,3074,648,-3958,1.01124513149261 +28653,-1.58183693885803,-0.550198435783386,-0.170879289507866,40774,8411,1191,-4837,1.01021337509155 +28655,-1.69401895999908,-0.587143898010254,-0.169782653450966,40774,6651,1359,-3964,1.0108140707016 +28657,-1.80385637283325,-0.621146261692047,-0.166553124785423,40774,11757,2913,-4843,1.0132657289505 +28659,-1.90871679782867,-0.647620320320129,-0.159890234470367,40774,9805,1699,-3926,1.01494550704956 +28661,-2.0042622089386,-0.67660790681839,-0.158627614378929,40774,14635,3691,-4811,1.01528584957123 +28663,-2.09393191337585,-0.698569715023041,-0.157618090510368,40774,12071,2357,-3941,1.01518380641937 +28665,-2.17322826385498,-0.717179596424103,-0.150645241141319,40774,16938,3863,-4781,1.01502120494843 +28667,-2.23747324943542,-0.73966109752655,-0.143723517656326,40774,13088,3254,-3875,1.01418495178223 +28669,-2.29360938072205,-0.764118611812592,-0.14326785504818,40774,18037,5316,-4766,1.01289308071136 +28671,-2.35077691078186,-0.789817035198212,-0.1438118070364,40774,15047,4497,-3906,1.01333487033844 +28673,-2.40098023414612,-0.801824152469635,-0.143543809652329,40774,20213,5331,-4844,1.01906478404999 +28675,-2.43452000617981,-0.813184201717377,-0.140413388609886,40774,15451,4117,-3914,1.02336692810059 +28677,-2.45708441734314,-0.812023639678955,-0.134455606341362,40774,20048,4854,-4808,1.02816569805145 +28679,-2.47401714324951,-0.808585524559021,-0.128669038414955,40774,15755,3307,-3865,1.03729140758514 +28681,-2.4795446395874,-0.815052628517151,-0.128932431340218,40774,20121,5760,-4813,1.04595232009888 +28683,-2.47826170921326,-0.813016951084137,-0.130348488688469,40774,15456,3789,-3908,1.05047345161438 +28685,-2.46810841560364,-0.805694222450256,-0.126440793275833,40774,19750,4937,-4849,1.05412268638611 +28687,-2.4510190486908,-0.788531243801117,-0.120390959084034,40774,14878,2671,-3872,1.05373692512512 +28689,-2.421053647995,-0.778488397598267,-0.113994538784027,40774,18493,4612,-4757,1.05610489845276 +28691,-2.37369108200073,-0.773271977901459,-0.110437832772732,40774,12529,3614,-3835,1.05428552627563 +28693,-2.32164931297302,-0.754618406295776,-0.108855865895748,40774,16203,3903,-4750,1.0544912815094 +28695,-2.27069330215454,-0.729311645030975,-0.106543958187103,40774,11685,1841,-3839,1.05707168579102 +28697,-2.21026635169983,-0.695929527282715,-0.103137776255608,40774,14651,2174,-4711,1.0619603395462 +28699,-2.13325119018555,-0.673831224441528,-0.099851094186306,40774,8690,1546,-3824,1.06596624851227 +28701,-2.0567831993103,-0.638258397579193,-0.092967122793198,40774,11819,1341,-4613,1.0664290189743 +28703,-1.97691237926483,-0.606111466884613,-0.081888027489185,40774,7022,102,-3728,1.06380522251129 +28705,-1.89555633068085,-0.570180416107178,-0.076212011277676,40774,9580,442,-4420,1.05624532699585 +28707,-1.81073033809662,-0.536145329475403,-0.074146077036858,40774,4992,-819,-3700,1.05571854114532 +28709,-1.71505165100098,-0.508289575576782,-0.072110772132874,40774,6273,219,-4370,1.0516209602356 +28711,-1.61918294429779,-0.469956755638123,-0.070433244109154,40774,2080,-1886,-3697,1.05422449111938 +28713,-1.5243479013443,-0.429645836353302,-0.070540681481361,40774,3831,-1775,-4335,1.05852508544922 +28715,-1.42870557308197,-0.386031895875931,-0.069665350019932,40774,-90,-3313,-3714,1.06227087974548 +28717,-1.32116436958313,-0.347635269165039,-0.065572828054428,40774,114,-2836,-4246,1.06393003463745 +28719,-1.21862852573395,-0.301841706037521,-0.06206127256155,40774,-3142,-4559,-3680,1.06066071987152 +28721,-1.12689065933228,-0.263726413249969,-0.055661015212536,40774,-1521,-4074,-4089,1.06756711006165 +28723,-1.03396165370941,-0.226536199450493,-0.047088224440813,40774,-4738,-4942,-3593,1.06989920139313 +28725,-0.941252887248993,-0.18967978656292,-0.037887260317803,40774,-4280,-5119,-3841,1.06698417663574 +28727,-0.854211270809174,-0.159984171390533,-0.033593259751797,40774,-6613,-5312,-3511,1.06183838844299 +28729,-0.771673083305359,-0.119473032653332,-0.035861115902662,40774,-6052,-6497,-3776,1.05936026573181 +28731,-0.690412163734436,-0.088312603533268,-0.036253333091736,40774,-8340,-6430,-3537,1.06090569496155 +28733,-0.617062389850616,-0.055516064167023,-0.036071185022593,40774,-7731,-6977,-3737,1.06311309337616 +28735,-0.548071682453156,-0.035976245999336,-0.032835971564055,40774,-9365,-6362,-3521,1.06507921218872 +28737,-0.493524461984634,-0.016293108463287,-0.028487859293819,40774,-8282,-6688,-3623,1.0618497133255 +28739,-0.452795505523682,0.002462936099619,-0.024567691609264,40774,-8624,-6887,-3469,1.06225001811981 +28741,-0.412221252918243,0.019752310588956,-0.02576818689704,40774,-8542,-7133,-3565,1.06072783470154 +28743,-0.365772187709808,0.038927141577005,-0.030819850042462,40774,-10236,-7486,-3515,1.06108331680298 +28745,-0.319162875413895,0.048192039132118,-0.033131595700979,40774,-10460,-7077,-3631,1.05887973308563 +28747,-0.286076098680496,0.059487652033568,-0.029924366623163,40774,-10418,-7276,-3512,1.05434322357178 +28749,-0.262411534786224,0.055994942784309,-0.026228189468384,40774,-9744,-6352,-3547,1.05083012580872 +28751,-0.248286858201027,0.055163774639368,-0.028653861954808,40774,-9623,-6409,-3506,1.04343116283417 +28753,-0.242711618542671,0.061856381595135,-0.032107386738062,40774,-8791,-7239,-3614,1.0420628786087 +28755,-0.243784070014954,0.064294308423996,-0.035398487001658,40774,-8628,-6840,-3555,1.0380973815918 +28757,-0.249113380908966,0.065275050699711,-0.041434105485678,40774,-7937,-6953,-3724,1.02838099002838 +28759,-0.260395288467407,0.060588601976633,-0.044387750327587,40774,-7684,-6345,-3621,1.02420198917389 +28761,-0.28004252910614,0.062597572803497,-0.041680835187435,40667,-6426,-7051,-3733,1.02372562885284 +28763,-0.294260442256927,0.048137027770281,-0.0398991368711,40667,-6999,-5533,-3595,1.02707755565643 +28765,-0.309308052062988,0.031405165791512,-0.040546573698521,40667,-6274,-5260,-3752,1.02844798564911 +28767,-0.329791367053986,0.017440157011151,-0.040272012352944,40667,-6035,-5180,-3603,1.02851474285126 +28769,-0.35292860865593,0.003463553730398,-0.039338879287243,40667,-4967,-5046,-3768,1.02789008617401 +28771,-0.384762406349182,-0.005733064841479,-0.042804270982742,40667,-4407,-5229,-3626,1.02144587039948 +28773,-0.420159250497818,-0.030882934108377,-0.046110417693853,40667,-2949,-3720,-3884,1.01616287231445 +28775,-0.462058424949646,-0.050929892808199,-0.045474737882614,40667,-2517,-3827,-3653,1.01426720619202 +28777,-0.497205853462219,-0.082933813333511,-0.042356487363577,40667,-1642,-2396,-3892,1.01026606559753 +28779,-0.533955514431,-0.108212970197201,-0.042215995490551,40667,-1759,-2630,-3640,1.01114010810852 +28781,-0.5746950507164,-0.127345234155655,-0.046250015497208,40667,123,-2596,-3986,1.01632261276245 +28783,-0.614259362220764,-0.149576380848885,-0.048427481204271,40667,-274,-2235,-3693,1.02213537693024 +28785,-0.653615713119507,-0.17046582698822,-0.046106949448586,40667,1458,-1751,-4035,1.02741169929504 +28787,-0.694918751716614,-0.196329891681671,-0.043699640780687,40667,1178,-1266,-3673,1.03013753890991 +28789,-0.737493872642517,-0.214863672852516,-0.042941886931658,40667,3234,-1152,-4050,1.03259611129761 +28791,-0.775311529636383,-0.232687249779701,-0.044085048139095,40667,2291,-1261,-3689,1.03860914707184 +28793,-0.808742880821228,-0.254787385463715,-0.04447178542614,40667,3952,-184,-4119,1.0407942533493 +28795,-0.847015738487244,-0.271772891283035,-0.044104639440775,40667,3595,-683,-3704,1.03927898406982 +28797,-0.881969749927521,-0.292572945356369,-0.043936297297478,40667,32767,9440,-4165,1.03602266311646 +28799,-0.914581179618835,-0.30397829413414,-0.041267294436693,40434,9523,996,-3700,1.03158009052277 +28801,-0.939542651176452,-0.326092302799225,-0.039866458624601,40434,11136,2698,-4169,1.02726495265961 +28803,-0.96473240852356,-0.337055891752243,-0.040110114961863,40434,10070,1566,-3708,1.02616274356842 +28805,-0.976881325244904,-0.349108159542084,-0.036829005926848,40434,11192,2486,-4177,1.02964913845062 +28807,-0.978874325752258,-0.366631865501404,-0.035257022827864,40434,8990,2600,-3692,1.03331756591797 +28809,-0.984429717063904,-0.373222172260284,-0.033564858138561,40434,11233,2625,-4186,1.03407871723175 +28811,-0.978613197803497,-0.378034949302673,-0.031258326023817,40434,8813,2003,-3682,1.03540396690369 +28813,-0.958751857280731,-0.380498260259628,-0.030939470976591,40434,9371,2598,-4184,1.03910064697266 +28815,-0.929406404495239,-0.37790122628212,-0.028950650244951,40434,6798,1625,-3683,1.03927266597748 +28817,-0.89991682767868,-0.354920566082001,-0.028443457558751,40434,8085,514,-4151,1.03884470462799 +28819,-0.867376863956451,-0.333563029766083,-0.026249434798956,40434,6030,-210,-3681,1.03866052627563 +28821,-0.826644003391266,-0.322501540184021,-0.025794059038162,40434,6424,983,-4107,1.03428220748901 +28823,-0.791781365871429,-0.308287888765335,-0.02750570140779,40434,5098,70,-3704,1.03530645370483 +28825,-0.753455936908722,-0.296702206134796,-0.024930378422141,40434,5712,653,-4089,1.03786742687225 +28827,-0.707522809505463,-0.278942227363586,-0.019354231655598,40434,3384,-484,-3662,1.03986024856567 +28829,-0.653059303760529,-0.265697211027145,-0.014413464814425,40434,3190,148,-3950,1.03957009315491 +28831,-0.603457868099213,-0.238602474331856,-0.012457830831409,40434,1872,-1624,-3626,1.03335523605347 +28833,-0.55165821313858,-0.218504562973976,-0.008171571418643,40434,1937,-1008,-3837,1.03450012207031 +28835,-0.497213393449783,-0.206727027893066,-0.003858824493364,40434,30486,7936,-3575,1.03401350975037 +28837,-0.441188156604767,-0.189979687333107,-0.002150735119358,40417,5116,340,-3744,1.03772783279419 +28839,-0.386019676923752,-0.166026622056961,-0.001190738170408,40417,3834,-780,-3563,1.04408955574036 +28841,-0.330452442169189,-0.13463619351387,0.002271465025842,40417,3529,-1523,-3641,1.0493243932724 +28843,-0.267441242933273,-0.119001522660255,0.002768275560811,40417,1716,-793,-3539,1.05364263057709 +28859,0.243486508727074,0.117573864758015,0.00322953145951,40417,-5170,-5707,-3531,1.00360751152039 +28861,0.301107823848724,0.141476646065712,0.000690216722433,40417,-6884,-5445,-3361,1.0072877407074 +28863,0.352846205234528,0.16190604865551,-0.000771212158725,40417,-6525,-5206,-3552,1.00956511497498 +28865,0.398018568754196,0.180111318826675,0.003190224757418,40417,-7740,-5732,-3285,1.01479768753052 +28867,0.443772703409195,0.192193478345871,0.004355984274298,40417,-7596,-5123,-3509,1.01944744586945 +28869,0.482797622680664,0.211106717586517,0.003996262326837,40417,-8883,-6361,-3239,1.02347934246063 +28871,0.515800893306732,0.230708763003349,0.008021671324968,40417,-7950,-6307,-3475,1.02690243721008 +28873,0.540346384048462,0.266750484704971,0.012993218377233,40417,21082,18273,-3070,1.02985680103302 +28875,0.565934956073761,0.280527204275131,0.011992332525551,40131,-3316,-2186,-3435,1.03427338600159 +28877,0.588360786437988,0.29274794459343,0.007704865653068,40131,-4815,-2871,-3098,1.03687989711761 +28879,0.609849333763123,0.299320340156555,0.004511681851,40131,-3888,-2026,-3474,1.03657913208008 +28881,0.628331363201141,0.305925369262695,0.005265619140118,40131,-5424,-2772,-3106,1.0323680639267 +28883,0.639974057674408,0.320266991853714,0.007681459188461,40131,-3870,-2976,-3440,1.02677547931671 +28885,0.648416578769684,0.334172755479813,0.009236779995263,40131,-5296,-3847,-3023,1.02460861206055 +28887,0.654304802417755,0.349045783281326,0.00872731115669,40131,-3932,-3534,-3420,1.02310681343079 +28889,0.669375419616699,0.35570427775383,0.005950045306236,40131,-6381,-3792,-3033,1.02241599559784 +28891,0.683476746082306,0.376154392957687,0.001224487903528,40131,-5218,-4440,-3458,1.02173638343811 +28893,0.697901666164398,0.40046027302742,-0.002000025473535,40131,-7086,-5920,-3076,1.02358555793762 +28895,0.707805752754211,0.415341109037399,-0.004166862461716,40131,-5562,-4744,-3481,1.02635824680328 +28897,0.705980718135834,0.426647365093231,-0.003900766372681,40131,-6357,-5567,-3066,1.02991783618927 +28899,0.701220691204071,0.435399979352951,-0.002912143711001,40131,-4719,-4749,-3459,1.0288645029068 +28901,0.689213991165161,0.451972126960754,-4.15805734519381E-05,40131,-5651,-6514,-2991,1.02611243724823 +28903,0.678256869316101,0.456980705261231,0.002278376137838,40131,-4242,-4958,-3408,1.01890790462494 +28905,0.664956986904144,0.465836346149445,-0.001712451339699,40131,-5454,-6358,-2991,1.01084733009338 +28907,0.655334115028381,0.470996081829071,-0.008028081618249,40131,-4296,-5346,-3464,1.01122176647186 +28909,0.645577013492584,0.473894774913788,-0.011450815945864,40131,-5667,-6241,-3092,1.0119309425354 +28911,0.622544348239899,0.481884658336639,-0.014039092697203,40131,-3144,-5886,-3492,1.01238071918488 +28913,0.598775207996368,0.484589815139771,-0.017055485397577,40131,-4159,-6583,-3144,1.01353693008423 +28915,0.573600888252258,0.489360600709915,-0.017671879380941,40131,-2546,-5950,-3505,1.01520490646362 +28917,0.553077936172485,0.485704839229584,-0.016458358615637,40131,-3892,-6330,-3131,1.01441657543182 +28919,0.531559467315674,0.47760072350502,-0.019519975408912,40131,-2442,-5048,-3505,1.01073920726776 +28921,0.502776801586151,0.468967586755753,-0.025812348350883,40131,-2705,-5883,-3251,1.00891757011414 +28923,0.477791696786881,0.453428000211716,-0.028627691790462,40131,-1638,-4350,-3558,1.00213980674744 +28925,0.452842831611633,0.444406181573868,-0.027478886768222,40131,-2367,-5633,-3288,0.99499523639679 +28927,0.428826421499252,0.42909899353981,-0.027410654351115,40131,-1198,-4190,-3541,0.988072037696838 +28929,0.395216405391693,0.425695836544037,-0.029274364933372,40131,-996,-5902,-3320,0.992477059364319 +28931,0.363573759794235,0.417967617511749,-0.031582269817591,40131,115,-4738,-3561,1.00481784343719 +28933,0.33971831202507,0.405460178852081,-0.032239250838757,40131,-944,-5085,-3369,1.0116069316864 +28935,0.309435486793518,0.388032495975494,-0.035948675125837,40131,651,-3771,-3585,1.01643049716949 +28937,0.280943334102631,0.364947110414505,-0.03863874450326,40131,216,-3820,-3476,1.01805293560028 +28939,0.2548568546772,0.350475460290909,-0.03779486566782,40131,1017,-3585,-3593,1.01715791225433 +28941,0.235360398888588,0.326108276844025,-0.037987772375345,40131,202,-3227,-3498,1.01408970355988 +28943,0.217237949371338,0.312321841716766,-0.041389215737581,40131,889,-3210,-3614,1.0099675655365 +28945,0.200202196836472,0.29859870672226,-0.041775159537792,40131,507,-3653,-3565,1.00715780258179 +28947,0.182854786515236,0.282562285661697,-0.041554402559996,40131,1244,-2732,-3613,0.996726393699646 +28949,0.158174589276314,0.26889955997467,-0.043110884726048,40131,32767,-3280,-3605,0.995605885982513 +28951,0.135862454771996,0.248246923089027,-0.045555472373962,39773,12382,-2007,-3640,1.00115609169006 +28953,0.118524432182312,0.233637452125549,-0.048069145530462,39773,11960,-2731,-3693,1.00879049301147 +28955,0.114418767392635,0.218089491128921,-0.048583257943392,39773,11442,-2023,-3662,1.01839292049408 +28957,0.113973550498486,0.210484251379967,-0.051269620656967,39773,10888,-2936,-3752,1.01991128921509 +28959,0.110480144619942,0.197284236550331,-0.052904948592186,39773,11514,-1965,-3694,1.01897358894348 +28961,0.117135882377625,0.180306494235992,-0.049495443701744,39773,10380,-1843,-3758,1.01107096672058 +28963,0.135953798890114,0.166269555687904,-0.050939068198204,39773,9606,-1520,-3683,1.00364565849304 +28965,0.165795594453812,0.147352576255798,-0.055772434920073,39773,7963,-1228,-3861,1.00132644176483 +28967,0.194147497415543,0.145660474896431,-0.057410310953856,39773,8119,-2156,-3732,1.00304758548737 +28969,0.228978365659714,0.128367319703102,-0.05657134577632,39773,6580,-1089,-3891,1.00614798069 +28971,0.265915125608444,0.131002262234688,-0.054868128150702,39773,6473,-2296,-3720,1.0125013589859 +28973,0.315870523452759,0.128470703959465,-0.051925987005234,39773,4069,-2191,-3843,1.02204096317291 +28975,0.365447819232941,0.126299604773521,-0.049792319536209,39773,4098,-1925,-3690,1.02795052528381 +28977,0.414916455745697,0.125070005655289,-0.049665220081806,39773,2436,-2265,-3825,1.03668558597565 +28979,0.470707505941391,0.120963633060455,-0.048986833542585,39773,2055,-1749,-3688,1.03539836406708 +28981,0.531165778636932,0.125717580318451,-0.047282285988331,39773,-355,-2738,-3802,1.02823853492737 +28983,0.596335291862488,0.12847912311554,-0.045836143195629,39773,-562,-2388,-3671,1.02853012084961 +28985,0.656007170677185,0.137704268097878,-0.044781737029553,39773,-2489,-3289,-3770,1.02516174316406 +28987,0.718940913677216,0.130445376038551,-0.040743578225374,38718,-2363,-1742,-3639,1.02213084697723 +28989,0.781752109527588,0.136431112885475,-0.036652773618698,38718,-4975,-3079,-3682,1.01808702945709 +28991,0.844884276390076,0.141887336969376,-0.032842416316271,38718,-4444,-2861,-3587,1.01890623569489 +29009,1.24122738838196,0.191149234771728,-0.039618294686079,38718,-11830,-4615,-3706,0.9991455078125 +29011,1.26514852046967,0.187815755605698,-0.038232255727053,38718,-9698,-3178,-3632,0.997573733329773 +29013,1.2784116268158,0.187987476587296,-0.041766185313463,38718,-11902,-3850,-3742,0.999247908592224 +29015,1.28449082374573,0.190184757113457,-0.048529826104641,38718,-9207,-3680,-3705,1.00132942199707 +29017,1.28656268119812,0.208842977881432,-0.048439431935549,38718,-11743,-5590,-3817,1.00108790397644 +29019,1.29468214511871,0.213808864355087,-0.039130140095949,38718,-10017,-4299,-3644,0.999319612979889 +29021,1.29337739944458,0.213058471679687,-0.034318804740906,38718,-12125,-4345,-3657,1.00365042686462 +29023,1.28390002250671,0.209173873066902,-0.036234814673662,38718,-9125,-3682,-3626,1.00993144512177 +29025,1.27498006820679,0.209048241376877,-0.037812247872353,38003,-11788,-4400,-3708,1.01363658905029 +29027,1.25959730148315,0.213463723659515,-0.03939063474536,38003,-8870,-4420,-3649,1.01499176025391 +29029,1.24104845523834,0.205374881625175,-0.04063132032752,38003,-11043,-3845,-3752,1.01037800312042 +29031,1.21219158172607,0.204727038741112,-0.041095342487097,38003,-7727,-4011,-3664,0.99994832277298 +29033,1.18053925037384,0.19812573492527,-0.044330626726151,38003,-9606,-3908,-3808,0.991116106510162 +29035,1.14524245262146,0.195892497897148,-0.049965355545282,38003,-6783,-3847,-3729,0.985903978347778 +29037,1.10822176933289,0.183005794882774,-0.052873525768519,38003,-8515,-3288,-3925,0.980639696121216 +29039,1.0677011013031,0.171708852052689,-0.052221186459065,38003,-5745,-2921,-3750,0.972446620464325 +29041,1.02091693878174,0.167466953396797,-0.049065854400396,38003,-6833,-3731,-3896,0.973057568073273 +29043,0.975597739219666,0.159481003880501,-0.047492902725935,38003,-4493,-3047,-3723,0.97869473695755 +29045,0.931499779224396,0.153260380029678,-0.04876683652401,38003,-5960,-3422,-3908,0.982890367507935 +29047,0.887852847576141,0.137270390987396,-0.051521431654692,38003,-3727,-2214,-3757,0.983045041561127 +29049,0.833362996578217,0.130183398723602,-0.053725920617581,38003,-3958,-3037,-3985,0.979291498661041 +29051,0.776711642742157,0.123054385185242,-0.051109347492457,38003,-1530,-2694,-3761,0.978952765464783 +29053,0.728730380535126,0.109819620847702,-0.050033692270517,38003,-3031,-2307,-3958,0.97284996509552 +29055,0.684169113636017,0.099032878875733,-0.050317976623774,38003,-1351,-2126,-3762,0.970447719097137 +29057,0.632902383804321,0.091340154409409,-0.051791530102491,38003,-1500,-2437,-3994,0.966025829315186 +29059,0.576923906803131,0.084559410810471,-0.052612580358982,38003,764,-2236,-3785,0.963723957538605 +29061,0.525908827781677,0.062272731214762,-0.049681566655636,37396,0,-950,-3987,0.959562838077545 +29063,0.478389978408814,0.050470504909754,-0.047791294753552,37396,1378,-1406,-3759,0.952639579772949 +29065,0.432188957929611,0.046325284987688,-0.050123896449804,37396,997,-2009,-4006,0.954536557197571 +29067,0.395142048597336,0.037889529019594,-0.054611135274172,37396,1668,-1479,-3813,0.957346856594086 +29069,0.355973392724991,0.028895016759634,-0.058207899332047,37396,1610,-1380,-4116,0.96006852388382 +29071,0.313660115003586,0.010058465413749,-0.05748738348484,37396,3098,-337,-3842,0.960999250411987 +29073,0.27033594250679,0.003257774049416,-0.057800374925137,37396,3197,-1116,-4129,0.957887530326843 +29075,0.242438033223152,-0.0074263503775,-0.060587648302317,37396,3008,-661,-3873,0.957156121730804 +29077,0.215376555919647,-0.009242491796613,-0.063362471759319,37396,2854,-1258,-4208,0.956502318382263 +29079,0.184061735868454,-0.012367037124932,-0.060641340911388,37396,4035,-1117,-3884,0.959641396999359 +29081,0.158951044082642,-0.020183628425002,-0.058758188039065,37396,3581,-642,-4167,0.958712577819824 +29083,0.13611912727356,-0.017074279487133,-0.058447550982237,37396,4084,-1478,-3878,0.965396046638489 +29085,0.119906283915043,-0.01996055431664,-0.055792510509491,37396,3560,-980,-4142,0.969766676425934 +29087,0.100272282958031,-0.011346117593348,-0.052933938801289,37396,4357,-1936,-3850,0.972418010234833 +29089,0.08539728820324,-0.007822442799807,-0.04961758106947,37396,4039,-1610,-4075,0.975720405578613 +29091,0.068099819123745,-0.001366447540931,-0.049349397420883,37396,4657,-1910,-3833,0.973460495471954 +29093,0.063333943486214,-0.009730626828969,-0.048454452306032,37396,3685,-709,-4069,0.965165257453918 +29095,0.071204461157322,-0.014532955363393,-0.049433384090662,37396,2825,-899,-3842,0.952829003334045 +29097,0.075729466974735,-0.005822903476655,-0.05470085516572,37396,2821,-1973,-4150,0.944825232028961 +29099,0.081077955663204,0.004816232714802,-0.057659611105919,37038,2872,-2267,-3907,0.941687285900116 +29101,0.087603129446507,0.012888263911009,-0.058733511716127,37038,2487,-2226,-4201,0.943300127983093 +29103,0.095639169216156,0.007138509303331,-0.057677444070578,37038,2473,-1120,-3917,0.949637115001678 +29105,0.099999748170376,0.020486492663622,-0.053893312811852,37038,2433,-2735,-4150,0.959594547748566 +29107,0.114254668354988,0.025781167671085,-0.050746511667967,37038,1755,-2178,-3878,0.970671832561493 +29109,0.12720875442028,0.046825740486384,-0.049986802041531,37038,1349,-3709,-4104,0.981412172317505 +29111,0.146754652261734,0.053150445222855,-0.049697443842888,37038,889,-2655,-3878,0.982258141040802 +29113,0.169045120477676,0.055592723190785,-0.049711745232344,37038,-29,-2524,-4106,0.982059478759766 +29115,0.185638874769211,0.07076608389616,-0.048440378159285,37038,501,-3555,-3877,0.983134388923645 +29117,0.203527212142944,0.075306594371796,-0.047267962247133,37038,-310,-3012,-4080,0.985483646392822 +29119,0.223454713821411,0.084955930709839,-0.04835457354784,37038,-334,-3385,-3883,0.985864043235779 +29121,0.244433954358101,0.096556477248669,-0.048913571983576,37038,-1246,-3891,-4101,0.979046642780304 +29123,0.263344258069992,0.113337785005569,-0.04673270881176,37038,-906,-4336,-3879,0.972169756889343 +29125,0.287304908037186,0.113066680729389,-0.043930854648352,37038,-2244,-3348,-4045,0.967759609222412 +29127,0.308258354663849,0.122767053544521,-0.044442135840654,37038,-1791,-4005,-3870,0.965547800064087 +29129,0.329687714576721,0.125706151127815,-0.043673135340214,37038,-2862,-3836,-4045,0.962702572345733 +29131,0.344903290271759,0.133775115013123,-0.041799947619438,37038,-2021,-4095,-3857,0.955015301704407 +29133,0.359467297792435,0.1478501111269,-0.039909452199936,37038,-2974,-5051,-4001,0.953732073307037 +29135,0.376656383275986,0.153908833861351,-0.03845950961113,37038,-2748,-4300,-3840,0.947781264781952 +29137,0.385495781898499,0.158511281013489,-0.037666898220778,37038,-3105,-4596,-3979,0.945303022861481 +29139,0.395139276981354,0.14834226667881,-0.037035189568997,37038,-2613,-3121,-3835,0.944482564926147 +29141,0.40451791882515,0.147819817066193,-0.034860298037529,37038,-3593,-4103,-3955,0.941829144954681 +29163,0.456152677536011,0.093538969755173,-0.028730319812894,37038,-3619,-2835,-3804,0.926712036132812 +29165,0.451669216156006,0.07597278803587,-0.030645022168756,37038,-4442,-2020,-3954,0.929571151733398 +29167,0.443540692329407,0.07354973256588,-0.031823866069317,37038,-3269,-2938,-3830,0.932327151298523 +29169,0.442674517631531,0.064731419086456,-0.027514699846506,37038,-4725,-2484,-3925,0.935081958770752 +29171,0.438523828983307,0.060022320598364,-0.027405025437474,37038,-3660,-2602,-3804,0.933733522891998 +29173,0.433458507061005,0.048574909567833,-0.028471978381276,37038,-4443,-2046,-3944,0.935456454753876 +29175,0.421834468841553,0.036278232932091,-0.02813408151269,37038,-3058,-1732,-3813,0.932794034481049 +29177,0.40768313407898,0.030487110838294,-0.027687337249518,37038,-3548,-2172,-3942,0.930086374282837 +29179,0.397169321775436,0.020064061507583,-0.028195412829518,37038,-2948,-1640,-3818,0.922249734401703 +29181,0.386397778987884,0.015499481000006,-0.028069796040654,37038,-3612,-2029,-3954,0.912579417228699 +29183,0.366228610277176,0.007139326073229,-0.024961762130261,37038,-1969,-1603,-3800,0.914375603199005 +29185,0.344845712184906,-0.003685302799568,-0.026489464566112,37038,-2323,-1270,-3943,0.916413247585297 +29187,0.333894163370132,-0.023757519200444,-0.028206409886479,37038,-2304,-314,-3827,0.92121285200119 +29189,0.325042009353638,-0.031434901058674,-0.030060889199376,37038,-3027,-1032,-3994,0.919915735721588 +29191,0.3135666847229,-0.037606775760651,-0.028805032372475,37038,-2104,-1091,-3836,0.923899114131928 +29193,0.292674362659454,-0.036133125424385,-0.026232056319714,37038,-1761,-1580,-3954,0.92682957649231 +29195,0.274823486804962,-0.038603384047747,-0.026681488379836,37038,-1207,-1318,-3826,0.929473340511322 +29197,0.264110952615738,-0.05317896977067,-0.0289352145046,37038,-2133,-120,-3993,0.932283878326416 +29199,0.252084344625473,-0.054768279194832,-0.026541531085968,37038,-1400,-1117,-3830,0.936930537223816 +29201,0.243172526359558,-0.059188567101956,-0.02060011588037,37038,-2007,-711,-3900,0.936956703662872 +29203,0.230555474758148,-0.060042392462492,-0.01942727342248,37038,-1141,-1058,-3785,0.938521683216095 +29205,0.216130763292313,-0.066386535763741,-0.020356277003884,37038,-1256,-421,-3901,0.936866343021393 +29207,0.201509594917297,-0.064522422850132,-0.023476170375943,37038,-660,-1149,-3817,0.928924858570099 +29209,0.191732063889504,-0.062338888645172,-0.023370923474431,37038,-1291,-1071,-3939,0.927690207958221 +29211,0.180189579725266,-0.047781612724066,-0.023525755852461,37038,-648,-2262,-3821,0.923837959766388 +29213,0.169824525713921,-0.04161424189806,-0.023965030908585,37038,-972,-1669,-3948,0.929027080535889 +29215,0.165325909852982,-0.045222010463476,-0.02402525395155,37038,-1004,-973,-3829,0.931565523147583 +29217,0.160368800163269,-0.04591541364789,-0.023142226040363,37038,-1249,-1074,-3943,0.931007027626038 +29219,0.155336305499077,-0.053104478865862,-0.020688423886895,37038,-881,-574,-3810,0.923347055912018 +29221,0.140906929969788,-0.038031663745642,-0.01772984303534,37038,-295,-2298,-3882,0.922801673412323 +29223,0.126592054963112,-0.031425189226866,-0.015074267052114,37038,148,-1847,-3774,0.926891267299652 +29225,0.120577149093151,-0.024914521723986,-0.015172246843577,37038,-622,-1871,-3853,0.928656160831451 +29227,0.122918508946896,-0.028140522539616,-0.014330714009702,37038,-1032,-1169,-3772,0.931046545505524 +29229,0.112305626273155,-0.02449593693018,-0.01411824952811,37038,-208,-1655,-3843,0.928309440612793 +29231,0.104906089603901,-0.020772740244866,-0.013874334283173,37038,-115,-1752,-3771,0.933547616004944 +29233,0.103760309517384,-0.01136161480099,-0.016824249178171,37038,-780,-2265,-3876,0.930774211883545 +29235,0.101137638092041,0.005790466908365,-0.016504809260368,37038,-438,-3081,-3792,0.926020920276642 +29237,0.096981070935726,0.020703434944153,-0.013198760338128,37038,-479,-3166,-3833,0.922291457653046 +29239,0.094265639781952,0.031993113458157,-0.009978478774428,37038,-363,-3037,-3749,0.91868793964386 +29241,0.095350116491318,0.026708843186498,-0.007562986575067,37038,-861,-1816,-3767,0.917620241641998 +29243,0.090228520333767,0.042426705360413,-0.01190762128681,37038,-163,-3506,-3764,0.917396605014801 +29245,0.09308061003685,0.049568630754948,-0.013100947253406,37038,-987,-3091,-3832,0.918373465538025 +29247,0.094691418111324,0.05749174207449,-0.011583202518523,37038,-740,-3178,-3764,0.918842434883118 +29249,0.098069317638874,0.047026909887791,-0.011239121668041,37038,-1121,-1805,-3813,0.921244561672211 +29251,0.091573916375637,0.043957069516182,-0.013443073257804,37038,-145,-2210,-3778,0.922732293605804 +29253,0.087382294237614,0.046711333096027,-0.012017675675452,37038,-426,-2757,-3824,0.931286215782166 +29255,0.088625982403755,0.050327956676483,-0.010396419093013,37038,-682,-2793,-3759,0.927952885627747 +29257,0.088873989880085,0.063713230192661,-0.009780914522707,37038,-803,-3812,-3797,0.925146758556366 +29259,0.089554235339165,0.067202672362328,-0.008249720558524,37038,-682,-3047,-3746,0.92525440454483 +29261,0.088847361505032,0.071764037013054,-0.009713163599372,37038,-770,-3328,-3797,0.925765693187714 +29263,0.093792073428631,0.065867513418198,-0.009677872993052,37038,-1078,-2379,-3757,0.921585202217102 +29265,0.096204727888107,0.069124162197113,-0.006801948416978,37038,-1141,-3219,-3765,0.919544458389282 +29267,0.098556093871594,0.062518946826458,-0.004217526875436,37038,-992,-2303,-3720,0.920178532600403 +29269,0.095271423459053,0.072273395955563,-0.006093214266002,37038,-749,-3763,-3757,0.918866574764252 +29271,0.104049377143383,0.073567599058151,-0.00750758452341,37038,-1564,-3053,-3744,0.922759592533112 +29273,0.106574587523937,0.081109933555126,-0.006597112864256,37038,-1391,-3777,-3763,0.921453952789306 +29275,0.109548822045326,0.083801835775375,-0.00408594077453,37038,-1266,-3330,-3721,0.924842953681946 +29277,0.117304995656013,0.077281259000301,-0.003995287697762,37038,-1976,-2738,-3734,0.925926387310028 +29279,0.121515445411205,0.073770344257355,-0.005376195069402,37038,-1569,-2771,-3731,0.932274341583252 +29281,0.123106382787228,0.070420943200588,-0.005451741628349,37038,-1658,-2876,-3753,0.935561001300812 +29283,0.12314572930336,0.072669960558415,-0.000798642344307,37038,-1338,-3193,-3700,0.936049163341522 +29285,0.126218035817146,0.058591030538082,0.0016227128217,37038,-1859,-1933,-3671,0.933864772319794 +29287,0.129903540015221,0.055098447948694,-0.002737387083471,37038,-1741,-2549,-3713,0.929602086544037 +29289,0.137865260243416,0.044123064726591,-0.003974579740316,37038,-2458,-1940,-3738,0.928429067134857 +29291,0.142140835523605,0.051774740219116,-0.00135141517967,37038,-2012,-3313,-3704,0.923792839050293 +29293,0.153662174940109,0.054026860743761,-0.000419469928602,37038,-3031,-3073,-3696,0.917239129543304 +29295,0.156961932778358,0.052392832934857,-0.000542846799362,37038,-2217,-2676,-3698,0.912938833236694 +29313,0.159642994403839,0.031704138964415,-0.010489732027054,37038,-2223,-2787,-3818,0.930109679698944 +29315,0.158911988139153,0.028713105246425,-0.00874643959105,37038,-2270,-2322,-3757,0.935427606105804 +29317,0.163458585739136,0.024627882987261,-0.004194980487227,37038,-3057,-2232,-3745,0.935650408267975 +29319,0.163761019706726,0.024992428719998,-0.002632543211803,37038,-2480,-2515,-3716,0.941670119762421 +29321,0.161445796489716,0.019649554044008,-0.00587782682851,37038,-2597,-2065,-3766,0.935647964477539 +29323,0.158028483390808,0.015304015018046,-0.008272618986666,37038,-2198,-2042,-3756,0.923393666744232 +29325,0.152509614825249,0.009560121223331,-0.006514398846775,37038,-2288,-1869,-3776,0.920385479927063 +29327,0.142871826887131,0.01836302690208,-0.006849151104689,37038,-1598,-3026,-3747,0.917694687843323 +29329,0.138791605830193,0.010794128291309,-0.007906761951745,37038,-2225,-1768,-3793,0.923025965690613 +29331,0.138012409210205,0.013737600296736,-0.010005140677095,37038,-2219,-2540,-3770,0.925798058509827 +29333,0.143534928560257,0.002060399390757,-0.010588510893285,37038,-3051,-1341,-3827,0.932533025741577 +29335,0.137970745563507,0.006868602707982,-0.010201765224338,37038,-1936,-2574,-3773,0.941790342330933 +29337,0.130880147218704,0.007851763628423,-0.006714725866914,37038,-2011,-2326,-3782,0.943639516830444 +29339,0.128022819757462,0.001361400354654,-0.005423961207271,37038,-2043,-1684,-3741,0.943297684192658 +29341,0.123459875583649,0.000567198439967,-0.006895422004163,37038,-2118,-2067,-3786,0.948135435581207 +29343,0.118884392082691,-0.009656853042543,-0.007487086579204,37038,-1841,-1251,-3757,0.951439559459686 +29345,0.118735179305077,-0.011611368507147,-0.007592386100441,37038,-2391,-1780,-3796,0.953043818473816 +29347,0.116560012102127,-0.011282861232758,-0.007790304720402,37038,-2027,-1972,-3760,0.952165603637695 +29349,0.109133780002594,-0.002897693775594,-0.009698588401079,37038,-1780,-2658,-3822,0.947330236434936 +29351,0.103325173258781,-0.007994963787496,-0.011570706032217,37038,-1624,-1623,-3788,0.944985628128052 +29353,0.096128314733505,0.002355546923354,-0.016409393399954,37038,-1653,-2883,-3902,0.938746511936188 +29355,0.098976515233517,0.004027569666505,-0.017553798854351,37038,-2226,-2277,-3832,0.933010995388031 +29357,0.093615807592869,0.006793918088079,-0.016236903145909,37038,-1771,-2409,-3903,0.923424005508423 +29359,0.081627279520035,0.007574589457363,-0.012845924124122,37038,-956,-2262,-3802,0.922595202922821 +29361,0.077259078621864,0.002341218525544,-0.012247424572706,37038,-1608,-1761,-3859,0.922816157341003 +29363,0.072726458311081,0.012110545299947,-0.0154286948964,37038,-1395,-2968,-3822,0.931356489658356 +29365,0.069793753325939,0.013402176089585,-0.016757868230343,37038,-1631,-2396,-3914,0.944131731987 +29367,0.064747147262096,0.017725808545947,-0.016962986439467,37038,-1276,-2658,-3835,0.942794919013977 +29369,0.056100022047758,0.013417622074485,-0.012311799451709,37038,-1027,-1992,-3864,0.942181825637817 +29371,0.042072251439095,0.022842219099403,-0.009510472416878,37038,-332,-3097,-3786,0.936809420585632 +29373,0.04386618360877,0.016964837908745,-0.009709198959172,37038,-1584,-1946,-3836,0.935971081256866 +29375,0.038125231862068,0.019275134429336,-0.012426606379449,37038,-886,-2538,-3808,0.932970881462097 +29377,0.030964698642492,0.019141372293234,-0.009422994218767,37038,-744,-2400,-3834,0.931903302669525 +29379,0.024665487930179,0.020261853933334,-0.009741563349962,37038,-664,-2471,-3791,0.932012617588043 +29381,0.022153157740831,0.022377526387572,-0.011401302181184,37038,-947,-2613,-3859,0.934159815311432 +29383,0.025168308988214,0.021606437861919,-0.012563779018819,37038,-1346,-2360,-3812,0.928666889667511 +29385,0.021915476769209,0.022414786741138,-0.012393100187183,37038,-898,-2523,-3873,0.925764143466949 +29387,0.01509493868798,0.012024437077344,-0.010658307932317,37038,-505,-1537,-3801,0.920889854431152 +29389,0.004217635374516,0.016728144139052,-0.008154049515724,37038,-67,-2715,-3825,0.921629428863525 +29391,0.003547555767,0.008751320652664,-0.002622094238177,37038,-780,-1665,-3748,0.929281949996948 +29393,4.9568057875149E-05,0.012873940169811,-0.002854763530195,37038,-523,-2611,-3763,0.93826425075531 +29395,0.001590265776031,0.00630546733737,-0.007964381016791,37038,-907,-1731,-3785,0.947424113750458 +29397,-0.001456866040826,0.01371955126524,-0.009960368275642,37038,-529,-2858,-3848,0.945554316043854 +29399,-0.00205073482357,0.014622356742621,-0.005962754134089,37038,-698,-2386,-3773,0.947524905204773 +29401,0.001006308593787,0.016893954947591,-0.005833487026393,37038,-1000,-2534,-3801,0.942372381687164 +29403,0.002811860758811,0.022196605801582,-0.006226831115782,37038,-937,-2810,-3776,0.940269231796265 +29405,0.00182849005796,0.010184522718191,-0.00844837538898,37038,-718,-1404,-3833,0.937664866447449 +29407,0.001217061653733,0.008020075038075,-0.011415549553931,37038,-738,-2070,-3813,0.938235521316528 +29409,-0.000363464845577,0.004413763061166,-0.009447672404349,37038,-637,-1919,-3846,0.936367332935333 +29411,0.002287952927873,0.01465938705951,-0.007484960369766,37038,-983,-3052,-3787,0.928162395954132 +29413,0.012748504057527,0.017062265425921,-0.007694335188717,37038,-1715,-2560,-3827,0.923087120056152 +29415,0.011847566813231,0.028307884931564,-0.010245651938021,37038,-868,-3323,-3808,0.915617406368256 +29417,0.017209116369486,0.023167572915554,-0.010112283751369,37038,-1441,-2128,-3857,0.910813927650452 +29419,0.022005531936884,0.025149276480079,-0.010511925444007,37038,-1429,-2621,-3811,0.90530788898468 +29421,0.028670227155089,0.028809757903218,-0.010518122464419,37038,-1731,-2856,-3863,0.909310877323151 +29423,0.03653483837843,0.031517684459686,-0.009987026453018,37038,-1871,-2774,-3810,0.911082446575165 +29425,0.040725897997618,0.035576526075602,-0.006474306806922,37038,-1756,-3004,-3817,0.916358649730682 +29427,0.043712660670281,0.030096301808953,-0.008509369567037,37038,-1641,-2179,-3800,0.917600870132446 +29429,0.048309616744518,0.036648284643889,-0.013054431416094,37038,-1922,-3208,-3896,0.921122491359711 +29431,0.051136799156666,0.040643125772476,-0.01321189198643,37038,-1756,-3022,-3835,0.921298861503601 +29433,0.050130449235439,0.050750631839037,-0.013541427440941,37038,-1573,-3713,-3904,0.923368453979492 +29435,0.057231109589338,0.042555935680866,-0.013259688392282,37038,-2171,-2195,-3838,0.924459993839264 +29437,0.057047922164202,0.048013765364885,-0.013987567275763,37038,-1773,-3360,-3912,0.926794469356537 +29439,0.065227076411247,0.049670148640871,-0.01223627012223,37038,-2388,-3023,-3833,0.925804257392883 +29441,0.072280570864678,0.055442295968533,-0.012729501351714,37038,-2563,-3519,-3899,0.921912610530853 +29443,0.075601108372212,0.050052426755428,-0.013643603771925,37038,-2221,-2546,-3845,0.919178307056427 +29445,0.074366293847561,0.040721192955971,-0.012845636345446,37038,-2032,-2211,-3903,0.911094427108765 +29447,0.06869176030159,0.040487550199032,-0.010550384409726,37038,-1510,-2793,-3826,0.914375185966492 +29449,0.070086367428303,0.035231247544289,-0.011493997648358,37038,-2190,-2429,-3889,0.912810385227203 +29451,0.072200931608677,0.043709456920624,-0.013714076019824,37038,-2151,-3476,-3850,0.912273705005646 +29453,0.068827584385872,0.036516200751066,-0.01212034933269,37038,-1872,-2338,-3899,0.914996027946472 +29455,0.062082007527351,0.043141651898623,-0.011376499198377,37038,-1404,-3351,-3836,0.9167041182518 +29457,0.069684937596321,0.036898020654917,-0.009477527812123,37038,-2686,-2423,-3870,0.916883587837219 +29459,0.066577605903149,0.050280563533306,-0.005795304197818,37038,-1760,-3953,-3799,0.915064096450806 +29461,0.066507272422314,0.054080970585346,-0.001529075670987,37038,-2108,-3432,-3777,0.91158938407898 +29463,0.06384863704443,0.051662340760231,-0.004027885850519,37038,-1782,-2863,-3787,0.90924596786499 +29465,0.065564282238484,0.042536526918411,-0.006884901318699,37038,-2259,-2332,-3841,0.911526501178741 +29467,0.066004954278469,0.044192619621754,-0.008436650969088,37038,-2065,-3063,-3819,0.912333428859711 +29469,0.065132543444634,0.048879999667406,-0.012280669994652,37038,-2108,-3449,-3906,0.917427539825439 +29471,0.070516295731068,0.044390443712473,-0.01495604403317,37038,-2516,-2645,-3866,0.916156053543091 +29473,0.076542727649212,0.049057491123676,-0.01185963023454,37038,-2814,-3477,-3903,0.916551649570465 +29475,0.076330922544003,0.035560689866543,-0.008019488304853,37038,-2234,-1894,-3820,0.915209949016571 +29477,0.066313773393631,0.039539899677038,-0.007348161190748,37038,-1525,-3285,-3852,0.913613319396973 +29479,0.062465444207192,0.024723844602704,-0.002916465513408,37038,-1805,-1659,-3786,0.914358019828796 +29481,0.053215499967337,0.025144848972559,0.000928296940401,37038,-1393,-2809,-3755,0.915884912014008 +29483,0.048781160265207,0.025560000911355,0.00086140766507,37038,-1591,-2772,-3760,0.922924339771271 +29485,0.038577910512686,0.027997419238091,-0.005415168125182,37038,-1094,-3008,-3830,0.92320305109024 +29487,0.036276742815971,0.025581995025277,-0.006997393909842,37038,-1580,-2580,-3815,0.924524366855621 +29489,0.029140561819077,0.014557407237589,-0.00448662834242,37038,-1171,-1829,-3820,0.922044813632965 +29491,0.023306461051107,0.006684297230095,-0.005898211617023,37038,-1152,-1921,-3808,0.921820819377899 +29493,0.015508393757045,0.007473073434085,-0.005648328457028,37038,-919,-2551,-3835,0.924966931343079 +29495,0.012131549417973,0.010704345069826,-0.004399854224175,37038,-1173,-2773,-3799,0.928292334079742 +29497,0.016922630369663,0.004874381702393,-0.004941088147461,37038,-1858,-2032,-3828,0.925956547260284 +29499,0.010434811934829,0.015445231460035,-0.00556213548407,37038,-934,-3364,-3808,0.926633656024933 +29501,0.004009406082332,0.008796771988273,-0.006598338019103,37038,-853,-2047,-3848,0.922428667545319 +29503,-0.005704022012651,0.007219975348562,-0.009951391257346,37038,-473,-2377,-3839,0.920448899269104 +29505,-0.007753088138998,-0.001481263549067,-0.012664496898651,37038,-972,-1735,-3921,0.921415686607361 +29507,-0.01309250574559,-0.003435285529122,-0.015238839201629,37038,-677,-2194,-3878,0.916394710540772 +29509,-0.016614789143205,-0.012871773913503,-0.009898135438561,37038,-721,-1491,-3891,0.918115198612213 +29511,-0.019038878381252,-0.024069793522358,-0.005239314865321,37038,-794,-1227,-3811,0.915404856204987 +29513,-0.018506100401282,-0.026807336136699,-0.006566676776856,37038,-971,-1734,-3853,0.921581983566284 +29515,-0.01980628632009,-0.025751577690244,-0.006348096765578,37163,-855,-2066,-3820,0.925025880336762 +29517,-0.022981626912952,-0.017953475937247,-0.003852161578834,37163,-619,-2617,-3822,0.92908126115799 +29519,-0.024717781692743,-0.030200267210603,-0.001659502740949,37163,-742,-1037,-3788,0.934517562389374 +29521,-0.028606263920665,-0.025030387565494,-0.002313304692507,37163,-456,-2290,-3804,0.939502537250519 +29523,-0.024242678657174,-0.027711333706975,-0.003444016445428,37163,-1171,-1742,-3801,0.942134618759155 +29525,-0.023983607068658,-0.02116621658206,-0.000898744328879,37163,-817,-2429,-3788,0.940800607204437 +29527,-0.018824001774192,-0.026689624413848,0.002049474511296,37163,-1293,-1537,-3764,0.938971519470215 +29541,-0.010472827591002,-0.018123941496015,0.003462663618848,37163,-1430,-1743,-3738,0.924663305282593 +29543,-0.012280839495361,-0.002178780036047,0.002479595365003,37163,-859,-3372,-3761,0.926496922969818 +29545,-0.005386644974351,-0.006323578767478,0.002054061507806,37163,-1578,-1854,-3754,0.924899637699127 +29547,-0.000679389399011,-0.004493298474699,-0.000205704927794,37163,-1491,-2322,-3780,0.92871767282486 +29549,0.002131674205884,-0.009472963400185,0.001009843312204,37163,32767,-27515,-3766,0.935271978378296 +29551,-0.005661250092089,8.12524231150746E-05,0.001511804759502,37914,29925,-7287,-3768,0.934360861778259 +29553,-0.002442153869197,0.006032291799784,-0.000276053644484,37914,29247,-7144,-3781,0.9329714179039 +29555,0.002588874660432,0.010504580102861,-0.00383373000659,37914,29190,-7115,-3805,0.927115440368652 +29557,0.009034509770572,0.012014113366604,-0.005378573667258,37914,29114,-6962,-3842,0.928442656993866 +29559,0.025433575734496,0.005036539863795,-0.00851736869663,37914,28342,-6260,-3838,0.926717936992645 +29561,0.050513219088316,0.007781696505845,-0.013033671304584,37914,27396,-7023,-3934,0.930630505084991 +29563,0.092077426612377,-0.004933349322528,-0.016575120389462,37914,25859,-5748,-3895,0.929687917232513 +29565,0.142349421977997,-0.003467271337286,-0.017979701980949,37914,24360,-6802,-3995,0.937279045581818 +29567,0.210776105523109,-0.018342316150665,-0.018476502969861,37914,22466,-5440,-3912,0.943397879600525 +29569,0.291394531726837,-0.022563392296434,-0.024138195440173,37914,19967,-6123,-4071,0.942258894443512 +29571,0.38662987947464,-0.036144725978375,-0.02430603466928,37914,18188,-5308,-3956,0.943673014640808 +29573,0.487718164920807,-0.037497330456972,-0.02515160664916,37914,15422,-6114,-4086,0.943088054656982 +29575,0.608249127864838,-0.044450972229242,-0.024765715003014,37914,13268,-5688,-3963,0.951324462890625 +29577,0.72464257478714,-0.047241546213627,-0.023910336196423,37914,10497,-5869,-4075,0.959342122077942 +29579,0.853224754333496,-0.068709537386894,-0.025500455871224,37914,9137,-4319,-3972,0.972169935703278 +29581,0.987262964248657,-0.066486403346062,-0.025999214500189,37914,4873,-5925,-4102,0.979188919067383 +29583,1.13150429725647,-0.076295144855976,-0.025516225025058,37914,3860,-5054,-3977,0.979637563228607 +29585,1.27045810222626,-0.077683724462986,-0.025873890146613,37914,-303,-5478,-4103,0.981965720653534 +29587,1.41616535186768,-0.092620670795441,-0.019574141129851,37914,-624,-4453,-3940,0.981137990951538 +29589,1.5627555847168,-0.096753157675266,-0.012380449101329,38093,-5957,-4966,-3943,0.980906188488007 +29591,1.71198427677155,-0.100937210023403,-0.001361990929581,38093,-5555,-5096,-3817,0.987878441810608 +29593,1.84866166114807,-0.108477368950844,0.006738126277924,38093,-10380,-4530,-3714,0.993767023086548 +29595,1.98092675209045,-0.119227789342403,0.008379442617297,38093,-8768,-4352,-3748,1.00164031982422 +29597,2.11215114593506,-0.13080196082592,0.006485024001449,38093,-14897,-3864,-3707,1.00303030014038 +29599,2.24584054946899,-0.142674520611763,0.012192468158901,38093,-13367,-3912,-3720,1.00632226467133 +29601,2.36251544952393,-0.142699852585793,0.012580348178744,38093,-18679,-4476,-3625,1.00401282310486 +29603,2.47414922714233,-0.147321626543999,0.009914491325617,38093,-15882,-4338,-3733,1.00006747245789 +29605,2.58452582359314,-0.146992206573486,0.011554013937712,38093,-22698,-4407,-3626,0.993242383003235 +29607,2.68279790878296,-0.15028814971447,0.012917165644467,38093,-18847,-4361,-3709,0.991113185882568 +29609,2.76608180999756,-0.16818955540657,0.009340520016849,38093,-24663,-2720,-3635,0.980355322360992 +29611,2.83452820777893,-0.173890352249146,0.007959093898535,38093,-19905,-3810,-3740,0.977056324481964 +29613,2.89242577552795,-0.181811109185219,0.011411061510444,38093,-25947,-3170,-3593,0.968396127223968 +29615,2.93546867370605,-0.181614607572556,0.011745367199183,38093,-20618,-4075,-3710,0.963643252849579 +29617,2.97706842422485,-0.187118723988533,0.008302944712341,38093,-27261,-3212,-3614,0.960523366928101 +29619,3.00922346115112,-0.177486851811409,0.003683884628117,38093,-22029,-4761,-3762,0.957616090774536 +29621,3.03037333488464,-0.180990040302277,-0.000382379279472,38093,-27799,-3418,-3705,0.955003023147583 +29623,3.03309631347656,-0.174056604504585,-0.007234250660986,38093,-21428,-4572,-3834,0.953581094741821 +29625,3.03453588485718,-0.184388786554337,-0.012706416659057,38093,-27607,-2828,-3836,0.957578539848327 +29627,3.01411914825439,-0.182878211140633,-0.016082156449556,38093,-20671,-4010,-3894,0.960469186306 +29629,2.98622059822083,-0.199887931346893,-0.015640806406736,38093,-25866,-2039,-3850,0.965542614459991 +29631,2.93984150886536,-0.203272566199303,-0.018414257094264,38093,-18903,-3311,-3909,0.967066705226898 +29633,2.88839793205261,-0.200893476605415,-0.025732081383467,38093,-23719,-3348,-3956,0.969829142093658 +29635,2.83958292007446,-0.208078444004059,-0.03297683596611,38093,-18409,-2911,-4009,0.970254957675934 +29637,2.7751317024231,-0.210692256689072,-0.034431077539921,38093,-22025,-2771,-4041,0.969482839107513 +29639,2.69234895706177,-0.221659928560257,-0.033738195896149,38093,-14936,-2381,-4015,0.96629524230957 +29641,2.59906554222107,-0.219862431287765,-0.034485768526793,38093,-18132,-2872,-4025,0.96504819393158 +29643,2.51019263267517,-0.231508746743202,-0.035090945661068,38093,-12885,-2122,-4025,0.961461424827576 +29645,2.41442823410034,-0.233338430523872,-0.038686983287335,38093,-15909,-2319,-4054,0.954944670200348 +29647,2.31014847755432,-0.229164466261864,-0.038687076419592,38093,-9831,-3213,-4050,0.956814706325531 +29649,2.19071388244629,-0.229252874851227,-0.039629817008972,38093,-11458,-2428,-4058,0.956864774227142 +29651,2.07898306846619,-0.233535677194595,-0.039309326559305,38093,-6806,-2469,-4054,0.953901350498199 +29653,1.96515882015228,-0.240348190069199,-0.039779048413038,38093,-8962,-1686,-4041,0.958100318908691 +29655,1.83668541908264,-0.240997314453125,-0.042537741363049,38093,-2856,-2540,-4076,0.964495003223419 +29657,1.71503365039825,-0.24812924861908,-0.047949481755495,38093,-4994,-1452,-4122,0.965868234634399 +29659,1.59191167354584,-0.254426538944244,-0.05052250251174,38093,-341,-1857,-4131,0.969336152076721 +29661,1.46734368801117,-0.261017322540283,-0.048035863786936,38093,-1316,-1195,-4104,0.966309487819672 +29663,1.33959186077118,-0.265009313821793,-0.0463309250772,38272,3107,-1777,-4102,0.962002873420715 +29665,1.21234059333801,-0.270327091217041,-0.04622919857502,38272,2566,-1034,-4067,0.959603190422058 +29667,1.09266591072083,-0.279008239507675,-0.047700490802527,38272,5681,-1142,-4110,0.952960968017578 +29669,0.976318836212158,-0.2891885638237,-0.049781303852797,38272,5285,-278,-4084,0.946316361427307 +29671,0.864658296108246,-0.291387885808945,-0.044799707829952,38272,8095,-1320,-4089,0.947317898273468 +29673,0.759948313236237,-0.291786521673203,-0.040468744933605,38272,7726,-835,-3967,0.946867763996124 +29675,0.670864105224609,-0.293862074613571,-0.036906268447638,38272,9071,-1185,-4032,0.95127147436142 +29677,0.583864748477936,-0.290776520967484,-0.035159301012755,38272,9170,-1000,-3900,0.95660799741745 +29679,0.494578450918198,-0.280154824256897,-0.038674145936966,38272,11507,-2183,-4040,0.964712560176849 +29681,0.411354213953018,-0.283529311418533,-0.040439534932375,38272,11641,-546,-3964,0.962592244148254 +29683,0.339303076267242,-0.291852205991745,-0.04034186899662,38272,12473,-552,-4049,0.95774894952774 +29685,0.27397209405899,-0.28921040892601,-0.043575067073107,38272,12602,-777,-3991,0.953882038593292 +29687,0.21898789703846,-0.280971169471741,-0.044624235481024,38272,13012,-1785,-4076,0.949932038784027 +29689,0.173058152198792,-0.273257046937942,-0.046346910297871,38272,12903,-1292,-4037,0.951050102710724 +29691,0.141502469778061,-0.274781614542007,-0.048741225153208,38272,12526,-1071,-4103,0.954427778720856 +29693,0.11140550673008,-0.260599702596664,-0.047727696597576,38272,12856,-1868,-4065,0.958647012710571 +29695,0.088544204831123,-0.25397065281868,-0.043953742831946,38272,12771,-1857,-4069,0.963031828403473 +29697,0.072121307253838,-0.23851378262043,-0.042965602129698,38272,12629,-2230,-4031,0.965071141719818 +29699,0.063740111887455,-0.219891667366028,-0.045339986681938,38272,-23844,22664,-4077,0.973505318164825 +29701,0.065780222415924,-0.209229931235313,-0.045407965779305,38272,5456,2081,-4091,0.973053634166718 +29703,0.068734310567379,-0.189827442169189,-0.043446782976389,38272,5341,845,-4065,0.973904848098755 +29705,0.081069111824036,-0.175318449735641,-0.042225506156683,38272,4522,1370,-4089,0.974946200847626 +29707,0.096506468951702,-0.157659232616425,-0.04589406400919,38272,4109,612,-4083,0.971698343753815 +29709,0.11651536077261,-0.141828209161758,-0.048717871308327,38272,3439,826,-4201,0.971545875072479 +29711,0.12941937148571,-0.10761634260416,-0.052096344530583,38272,3860,-1202,-4129,0.976052403450012 +29713,0.140854746103287,-0.082769021391869,-0.04900511726737,38272,3702,-699,-4271,0.983937978744507 +29715,0.158063933253288,-0.059255890548229,-0.046306911855936,38272,3173,-1067,-4095,0.987646043300629 +29717,0.17755588889122,-0.027179384604097,-0.0456089861691,38272,2543,-2070,-4294,0.992887496948242 +29719,0.208715796470642,0.001522565376945,-0.043906934559345,38272,1460,-2273,-4085,0.998062193393707 +29721,0.237485736608505,0.040532287210226,-0.042910605669022,38272,899,-3636,-4340,1.00439500808716 +29723,0.263836711645126,0.061410050839186,-0.038790754973888,38272,998,-2565,-4059,1.00874364376068 +29725,0.282646507024765,0.096237674355507,-0.031571079045534,38272,856,-4236,-4275,1.00764560699463 +29727,0.308322072029114,0.121694259345531,-0.02561154961586,38272,372,-3774,-3977,0.999687194824219 +29729,0.32615253329277,0.163795754313469,-0.022299226373434,38272,190,-5891,-4249,0.997591137886047 +29731,0.343987286090851,0.201642423868179,-0.021607980132103,38272,367,-5858,-3959,0.993914902210236 +29733,0.369686424732208,0.225068286061287,-0.025092203170061,38272,-1132,-5617,-4358,0.982245743274689 +29735,0.396674424409866,0.256187558174133,-0.026720171794295,38272,-1116,-6238,-4007,0.973204374313354 +29737,0.426705241203308,0.284891217947006,-0.025513377040625,38272,-32767,-7060,-4440,0.966913342475891 +29739,0.456648766994476,0.311389863491058,-0.025992957875133,38272,-8380,-6806,-4017,0.968066513538361 +29741,0.486203700304031,0.325284481048584,-0.026161851361394,38272,-9636,-6774,-4508,0.973886966705322 +29743,0.503834247589111,0.34848415851593,-0.024855270981789,38272,-8366,-7230,-4025,0.976177632808685 +29745,0.516694664955139,0.357244908809662,-0.023081805557013,38272,-9133,-7057,-4525,0.979668974876404 +29747,0.519012987613678,0.3760866522789,-0.020089562982321,38272,-7694,-7456,-4010,0.984365284442902 +29749,0.518920183181763,0.387910962104797,-0.01453965716064,38272,-8436,-7913,-4479,0.992402195930481 +29751,0.51702344417572,0.398816615343094,-0.011877487413585,38272,-7570,-7370,-3970,0.987846076488495 +29753,0.50771576166153,0.414842844009399,-0.011526104062796,38272,-7799,-8805,-4493,0.983193039894104 +29771,0.266570806503296,0.374386161565781,0.003433126257733,38272,-2146,-6357,-3948,0.981939375400543 +29773,0.220224633812904,0.351432055234909,0.003646581433713,38272,-1243,-5808,-4334,0.981744587421417 +29775,0.175164774060249,0.334052175283432,0.001138063147664,38272,-32767,-5402,-3977,0.978046238422394 +29777,0.136383548378944,0.310658097267151,0.000220467714826,38272,-6569,-5252,-4341,0.978716671466827 +29779,0.094218671321869,0.294807940721512,-0.000332031951984,38272,-5676,-5075,-3999,0.976301968097687 +29781,0.063110873103142,0.258952349424362,-0.00275278557092,38272,-6010,-3648,-4329,0.97284597158432 +29783,0.020525082945824,0.233058422803879,-0.004898909013718,38272,-4652,-3575,-4041,0.966670870780945 +29785,-0.027660073712468,0.206748023629189,-0.003711394267157,38272,-3358,-3585,-4290,0.967154026031494 +29787,-0.079859182238579,0.178693860769272,-0.004689992871135,38272,-2546,-2724,-4048,0.959278762340546 +29789,-0.132715627551079,0.151659920811653,-0.006476430222392,38272,-1304,-2707,-4268,0.954595625400543 +29791,-0.1947962641716,0.119239591062069,-0.008913472294807,38272,-160,-1616,-4084,0.950506865978241 +29793,-0.258045047521591,0.092438146471977,-0.010485373437405,38272,1535,-1805,-4255,0.952415823936462 +29795,-0.320389568805695,0.066010043025017,-0.010458323173225,38272,1747,-1312,-4101,0.95815521478653 +29797,-0.379029273986816,0.047417942434549,-0.011054173111916,38272,3282,-1692,-4216,0.964468955993652 +29799,-0.43045637011528,0.026932993903756,-0.010984832420945,38272,2688,-1189,-4108,0.972169160842896 +29801,-0.477963089942932,0.005818406119943,-0.011492662131786,38272,4255,-842,-4178,0.974448800086975 +29803,-0.528862833976746,-0.025630341842771,-0.010220704600215,38272,4254,356,-4105,0.973441243171692 +29805,-0.577400088310242,-0.059536300599575,-0.008143863640726,38272,6159,1151,-4069,0.964508891105652 +29807,-0.623827993869782,-0.082890346646309,-0.007248386275023,38272,5534,634,-4084,0.96385669708252 +29809,-0.664411962032318,-0.112337119877338,-0.009572482667863,38272,7263,1741,-4029,0.957762956619263 +29811,-0.701416969299316,-0.127868756651878,-0.011130949482322,38272,-29805,780,-4109,0.949914336204529 +29813,-0.738807737827301,-0.147055745124817,-0.00943293236196,38272,2445,1636,-3990,0.944469749927521 +29815,-0.775438129901886,-0.149298503994942,-0.008589173667133,38272,1486,212,-4088,0.946668446063995 +29817,-0.799995481967926,-0.154937356710434,-0.009129852056503,38272,2791,865,-3978,0.957097053527832 +29819,-0.822792172431946,-0.161250904202461,-0.012828569859266,38272,1462,755,-4114,0.964024603366852 +29821,-0.845654845237732,-0.166267976164818,-0.009397094137967,38272,3710,1082,-3969,0.972997903823852 +29823,-0.872861623764038,-0.169063061475754,-0.008031935431063,38272,2808,700,-4077,0.976277649402618 +29825,-0.900969624519348,-0.170957818627357,-0.013551518321037,38272,5293,1024,-4012,0.977998733520508 +29827,-0.921437501907349,-0.173292905092239,-0.017768627032638,38272,3360,816,-4141,0.980702698230743 +29829,-0.935634255409241,-0.166422188282013,-0.016211975365877,38272,5194,423,-4048,0.980972588062286 +29831,-0.950396418571472,-0.166699290275574,-0.012331988662481,38272,3721,663,-4101,0.978546559810638 +29833,-0.973455011844635,-0.149110034108162,-0.012004103511572,38272,6810,-547,-4017,0.974660098552704 +29835,-0.996500372886658,-0.141234949231148,-0.011886294931173,38272,5351,-205,-4096,0.975718379020691 +29837,-1.01727902889252,-0.13374887406826,-0.011169194243848,38272,7742,4,-4022,0.982782959938049 +29839,-1.0270768404007,-0.129340887069702,-0.0092180268839,38272,5239,-53,-4075,0.989607155323029 +29841,-1.02759158611298,-0.124217785894871,-0.008583125658333,38272,6856,89,-4002,0.990532875061035 +29843,-1.02557480335236,-0.108563549816608,-0.005056205671281,38272,4778,-1088,-4045,0.990707039833069 +29845,-1.02531635761261,-0.098237760365009,0.00105184817221,38272,7165,-645,-3913,0.991893529891968 +29847,-1.02542471885681,-0.081480167806149,-0.00066439632792,38272,5335,-1499,-4012,0.992239713668823 +29849,-1.01920187473297,-0.068149238824844,-0.005749087315053,38272,-29015,-1299,-4019,0.989816784858704 +29851,-1.00938355922699,-0.036822251975536,-0.010357324965298,38272,-1287,-3140,-4078,0.98633486032486 +29853,-0.9910968542099,-0.018777389079332,-0.011884061619639,38272,9,-2401,-4135,0.982556700706482 +29855,-0.98051518201828,0.000804834184237,-0.0105538694188,38272,-1417,-2817,-4081,0.975146174430847 +29857,-0.970603346824646,0.003435765393078,-0.010291188023985,38272,613,-1638,-4137,0.97018039226532 +29859,-0.970827698707581,0.02065509930253,-0.011723740957677,38272,-450,-2921,-4091,0.962563574314117 +29861,-0.970522999763489,0.044026896357536,-0.009641996584833,38272,1617,-3778,-4165,0.958836555480957 +29863,-0.96784120798111,0.064399883151054,-0.010186670348048,38272,-367,-3781,-4084,0.954025030136108 +29865,-0.966857969760895,0.087353654205799,-0.013115596957505,38272,1835,-4470,-4243,0.959186553955078 +29867,-0.966039419174194,0.101545207202435,-0.013090196996927,38272,73,-3898,-4108,0.966412663459778 +29869,-0.963033318519592,0.114671595394611,-0.013471012935042,38272,1966,-4251,-4272,0.97541743516922 +29871,-0.963173568248749,0.12252576649189,-0.012223163619638,38272,436,-3786,-4108,0.981299996376038 +29873,-0.969105005264282,0.145080462098122,-0.008005138486624,38272,3044,-5471,-4234,0.983207166194916 +29875,-0.971142590045929,0.152447834610939,-0.005415759980679,38272,1028,-4236,-4067,0.987875998020172 +29877,-0.975454270839691,0.161621376872063,-0.008156443946064,38272,3368,-4821,-4250,0.99118435382843 +29879,-0.971728205680847,0.16323147714138,-0.008089841343462,38272,970,-4039,-4091,0.993996143341064 +29881,-0.967516541481018,0.163706168532372,-0.00672542816028,38272,2974,-4284,-4237,0.992856562137604 +29883,-0.975473880767822,0.173373356461525,-0.004480242263526,38272,2207,-4822,-4071,0.996387720108032 +29885,-0.979254007339478,0.17569899559021,-0.003577629569918,38272,4088,-4678,-4211,0.99763023853302 +29887,-0.976161181926727,0.185339123010635,-0.009319766424596,38272,1780,-5059,-4110,0.992457926273346 +29889,-0.973518669605255,0.195633262395859,-0.011789987795055,38272,3882,-5649,-4322,0.988764405250549 +29891,-0.970928609371185,0.209204807877541,-0.010823220014572,38272,2096,-5761,-4127,0.983776271343231 +29893,-0.962887465953827,0.199054017663002,-0.012218772433698,38272,3659,-4327,-4332,0.983558237552643 +29895,-0.95740807056427,0.201740846037865,-0.01624071598053,38272,2044,-4956,-4171,0.985044360160827 +29897,-0.945919871330261,0.200644135475159,-0.01663083396852,38272,3484,-5087,-4388,0.985678613185883 +29899,-0.938652694225311,0.20477919280529,-0.016343703493476,38272,1992,-5187,-4179,0.980171859264374 +29901,-0.935316264629364,0.201404079794884,-0.014325842261314,38272,4251,-5020,-4365,0.97854483127594 +29903,-0.938060879707336,0.189579799771309,-0.014882079325616,38272,3046,-3909,-4176,0.970988273620606 +29921,-0.791913270950317,0.119401849806309,-0.009022332727909,38272,1094,-3371,-4164,0.96766060590744 +29923,-0.775683999061585,0.103140950202942,-0.003228086978197,38272,2646,-2912,-4195,0.960408627986908 +29925,-0.764950215816498,0.089469417929649,0.000918053265195,38272,1504,-2720,-4098,0.959819138050079 +29927,-0.749271512031555,0.076836712658405,-0.000439098919742,38272,2529,-2770,-4150,0.958733201026916 +29929,-0.749271512031555,0.076836712658405,-0.000439098919742,38272,2529,-2770,-4150,0.958733201026916 +29931,-0.705631017684937,0.065941572189331,-0.008543186821043,38272,1777,-2893,-4241,0.968875169754028 +29933,-0.69292676448822,0.060411270707846,-0.002704415703192,38272,862,-2940,-4128,0.975813448429108 +29935,-0.671718060970306,0.035816270858049,0.000503528513946,38272,1400,-1286,-4121,0.985534965991974 +29937,-0.650755345821381,0.023212620988488,-0.002839532447979,38272,-90,-1910,-4129,0.995389044284821 +29939,-0.650755345821381,0.023212620988488,-0.002839532447979,38272,-90,-1910,-4129,0.995389044284821 +29941,-0.608508050441742,0.014365478418768,-0.001547737978399,38272,-306,-3338,-4122,1.00692188739777 +29943,-0.580970823764801,0.003186531830579,0.000136644986924,38272,-105,-1720,-4111,1.0018345117569 +29945,-0.566252827644348,-0.003827639389783,-0.00039988028584,38272,-430,-1916,-4114,0.9974564909935 +29947,-0.54656982421875,-0.01045960560441,0.001774034230039,38272,101,-1816,-4086,0.990070998668671 +29949,-0.522526204586029,-0.018640834838152,-0.000163694014191,38272,-1537,-1609,-4112,0.978380680084228 +29951,-0.509330868721008,-0.023475909605622,0.000832578632981,38272,153,-1714,-4092,0.971316695213318 +29953,-0.498709082603455,-0.023100413382053,0.006909884978086,38272,-741,-2141,-4064,0.96272337436676 +29955,-0.485523372888565,-0.024809192866087,0.010768583975732,38272,-60,-1896,-3974,0.96395480632782 +29957,-0.467446476221085,-0.043673932552338,0.0061798193492,38272,-1557,-448,-4067,0.960714638233185 +29959,-0.455668359994888,-0.041290432214737,0.004562843590975,38272,-300,-1910,-4039,0.960114061832428 +29961,-0.44316503405571,-0.05086674913764,0.007874455302954,38272,-1355,-986,-4054,0.957068502902985 +29963,-0.433608502149582,-0.049360524863005,0.006996688898653,38272,-361,-1701,-4006,0.961136341094971 +29965,-0.415396511554718,-0.057044327259064,0.005202839151025,38272,-2021,-1006,-4071,0.969932377338409 +29967,-0.397546976804733,-0.055724509060383,0.002413420472294,38272,-1394,-1552,-4057,0.972094297409058 +29969,-0.381710916757584,-0.058845993131399,0.002455596113577,38272,-2206,-1276,-4089,0.976095139980316 +29971,-0.377824693918228,-0.049965962767601,0.000418134295614,38272,-583,-2149,-4083,0.9758061170578 +29973,-0.370554506778717,-0.051598418504,0.000276899343589,38272,-1631,-1458,-4104,0.97730427980423 +29975,-0.363314777612686,-0.059389255940914,-0.000745277502574,38272,-936,-751,-4093,0.975777566432953 +29977,-0.358706831932068,-0.058981973677874,-0.000661322905216,38272,-1493,-1461,-4110,0.977978527545929 +29979,-0.354934245347977,-0.064005233347416,-0.00068404932972,38272,-709,-837,-4091,0.977587461471558 +29981,-0.357073605060577,-0.052829425781965,-0.001564711797982,38272,-919,-2282,-4116,0.985794901847839 +29983,-0.350440472364426,-0.047271050512791,-0.002500734524801,38272,-883,-1846,-4119,0.986495852470398 +29985,-0.342950642108917,-0.039665184915066,-0.006222442723811,38272,-1699,-2185,-4148,0.978575766086578 +29987,-0.340293616056442,-0.042700376361609,-0.004668124485761,38272,-666,-1288,-4146,0.976386070251465 +29989,-0.347099125385284,-0.034662902355194,-0.001512649701908,38272,-510,-2263,-4116,0.97267210483551 +29991,-0.343822509050369,-0.040221739560366,-0.003172306576744,38272,-561,-1126,-4130,0.972155392169952 +29993,-0.340068966150284,-0.037270706146956,-0.007836724631488,38272,-1261,-1838,-4160,0.972447872161865 +29995,-0.333075404167175,-0.033745590597391,-0.009694324806333,38272,-876,-1849,-4210,0.972566723823547 +29997,-0.331872433423996,-0.027558738365769,-0.008340804837644,38272,-1090,-2186,-4165,0.970202207565308 +29999,-0.334680527448654,-0.020648062229157,-0.004379368852824,38272,-36,-2277,-4154,0.972168326377869 +30001,-0.336576908826828,-0.017783492803574,-0.00164731964469,38272,-692,-2070,-4120,0.968618094921112 +30003,-0.342661529779434,-0.01008718367666,-0.001082978677005,38272,432,-2487,-4119,0.972492635250092 +30005,-0.351180076599121,-0.008202242664993,-0.000969495042227,38272,104,-2124,-4116,0.971904397010803 +30007,-0.35897308588028,-0.002799920039251,-0.001183799700812,38272,921,-2442,-4123,0.969995021820068 +30009,-0.362534254789352,-0.004403396975249,0.0001524425752,38272,30,-1920,-4109,0.972313523292542 +30011,-0.367311060428619,0.004883871413767,5.47839081264101E-05,38272,951,-2847,-4111,0.972453773021698 +30013,-0.368708610534668,0.005718716885895,-0.001948637655005,38272,85,-2237,-4123,0.969789981842041 +30015,-0.375337988138199,0.019664028659463,-0.002808855380863,38272,1347,-3418,-4150,0.966040194034576 +30017,-0.383463799953461,0.025510327890515,0.000340929051163,38272,907,-2883,-4109,0.965112626552582 +30019,-0.393728941679001,0.03072190284729,0.001430675038137,38272,2051,-2966,-4104,0.961236417293549 +30021,-0.397798359394073,0.027436448261142,0.000446989637567,38272,962,-2262,-4108,0.962482750415802 +30023,-0.398191601037979,0.025398369878531,-0.003337570931762,38272,1561,-2362,-4159,0.954189419746399 +30025,-0.401985049247742,0.039599593728781,-0.00816254876554,38272,1147,-3693,-4169,0.953606486320496 +30027,-0.402579337358475,0.041373059153557,-0.00940069463104,38272,1776,-2902,-4236,0.951121747493744 +30029,-0.400302946567535,0.042450081557036,-0.010356436483562,38272,832,-2805,-4186,0.954249680042267 +30031,-0.401997357606888,0.042032849043608,-0.010446331463754,38272,1993,-2774,-4250,0.963896572589874 +30033,-0.406455159187317,0.053534332662821,-0.011954352259636,38272,1549,-3724,-4199,0.967882394790649 +30035,-0.407499253749847,0.049944341182709,-0.013059351593256,38272,2179,-2690,-4285,0.970136761665344 +30037,-0.413867622613907,0.056542593985796,-0.013826955109835,38272,1941,-3432,-4215,0.968201637268066 +30039,-0.4136743247509,0.055987797677517,-0.009967164136469,38272,2337,-3012,-4253,0.969769835472107 +30041,-0.409161239862442,0.059257555752993,-0.010205008089542,38272,1247,-3250,-4193,0.965476751327515 +30043,-0.407735586166382,0.065627463161945,-0.010220021940768,38272,2314,-3683,-4260,0.967153429985046 +30045,-0.409984111785889,0.069671086966992,-0.009691209532321,38272,1896,-3477,-4192,0.965103387832642 +30047,-0.407445579767227,0.077373117208481,-0.010346626862884,38272,2388,-4002,-4266,0.971076667308807 +30049,-0.396339684724808,0.078799940645695,-0.007636384107172,38272,898,-3449,-4180,0.979435980319977 +30051,-0.387799799442291,0.090202987194061,-0.009243392385542,38272,1775,-4508,-4258,0.979887843132019 +30053,-0.381239265203476,0.094946101307869,-0.008166298270226,38272,1152,-3953,-4186,0.979816138744354 +30071,-0.304594308137894,0.087209045886994,0.007423298899084,38272,266,-3185,-4062,0.96233457326889 +30073,-0.285155802965164,0.090000316500664,0.005666435230523,38272,-501,-3939,-4094,0.955022811889648 +30075,-0.274603307247162,0.096184298396111,0.005960481707007,38272,548,-4476,-4080,0.953440308570862 +30077,-0.267680436372757,0.100656904280186,0.007011158857495,38272,241,-4254,-4085,0.957665622234344 +30079,-0.250273376703262,0.09212052822113,0.005571202374995,38272,-251,-3400,-4084,0.962351322174072 +30081,-0.239443942904472,0.098201416432858,0.004539410118014,38272,-358,-4375,-4102,0.962471067905426 +30083,-0.227100223302841,0.084989175200462,0.005529302638024,38272,-180,-2987,-4082,0.964103817939758 +30085,-0.21992439031601,0.08383971452713,0.006124980282038,38272,-300,-3689,-4091,0.966244876384735 +30087,-0.207458481192589,0.070347160100937,0.011113661341369,38272,-423,-2746,-4013,0.96614670753479 +30089,-0.201724037528038,0.064426124095917,0.014458958990872,38272,-387,-3096,-4032,0.972898721694946 +30091,-0.191225752234459,0.060130707919598,0.015241424553096,38272,-465,-3268,-3961,0.980321288108826 +30093,-0.181907653808594,0.054359123110771,0.015498104505241,38272,-863,-2986,-4023,0.983876526355743 +30095,-0.169641926884651,0.059109564870596,0.012752994894981,38272,-871,-3928,-3989,0.991471409797668 +30097,-0.151594802737236,0.056672621518374,0.01236688811332,38272,-1865,-3283,-4043,0.98725837469101 +30099,-0.134133473038673,0.050764214247465,0.013864283449948,38272,-1788,-3059,-3972,0.986144781112671 +30101,-0.119615040719509,0.035910736769438,0.01222974807024,38272,-2033,-2117,-4043,0.986883342266083 +30103,-0.112265266478062,0.037289842963219,0.010933662764728,38272,-1404,-3382,-4003,0.985243558883667 +30105,-0.105569735169411,0.021163174882531,0.013636196032167,38272,-1648,-1830,-4032,0.980516314506531 +30107,-0.108157284557819,0.021679513156414,0.015808155760169,38272,-727,-3079,-3942,0.971363425254822 +30109,-0.10547836124897,0.007918540388346,0.018460310995579,38272,-1336,-1818,-3996,0.962486624717712 +30111,-0.111473374068737,0.009978480637074,0.020135326310992,38272,-398,-2996,-3886,0.966532647609711 +30113,-0.107984393835068,0.010656667873263,0.02143538929522,38272,-1330,-2894,-3973,0.966295897960663 +30115,-0.109209388494492,0.012523599900305,0.017756896093488,38272,-749,-3020,-3912,0.962206304073334 +30117,-0.109814420342445,0.010889708995819,0.017363876104355,38272,-983,-2734,-3998,0.964348375797272 +30119,-0.109366402029991,0.007228156551719,0.019734231755138,38272,-841,-2540,-3885,0.963635325431824 +30121,-0.112337440252304,0.001303624245338,0.019946129992604,38272,-750,-2289,-3978,0.968409717082977 +30123,-0.114020422101021,-0.009687436744571,0.01901738345623,38272,-590,-1743,-3888,0.970783472061157 +30125,-0.11814047396183,0.00026803475339,0.017997000366449,38272,-555,-3405,-3988,0.972261250019074 +30127,-0.117688611149788,-0.005666182376444,0.019160706549883,38272,-643,-2167,-3884,0.970783293247223 +30129,-0.126515179872513,-0.008805459365249,0.019289808347821,38272,-65,-2333,-3976,0.970236480236053 +30131,-0.134417667984962,-0.020831853151322,0.020321981981397,38272,285,-1466,-3865,0.968161940574646 +30133,-0.145391836762428,-0.022985979914665,0.018008507788181,38272,404,-2187,-3982,0.962729454040527 +30135,-0.140563726425171,-0.033257108181715,0.017850318923593,38272,-485,-1374,-3890,0.956993222236633 +30137,-0.139085382223129,-0.035141807049513,0.015273850411177,38272,-530,-2012,-3998,0.94951856136322 +30139,-0.142408415675163,-0.031956490129233,0.011955857276917,38272,166,-2344,-3957,0.949425518512726 +30141,-0.146102353930473,-0.03343902528286,0.011594783514738,38272,-13,-2048,-4022,0.947364926338196 +30143,-0.152376428246498,-0.031117402017117,0.011670976877213,38272,586,-2289,-3959,0.949441730976105 +30145,-0.149927765130997,-0.03842642903328,0.011791829951108,38272,-346,-1543,-4018,0.94955587387085 +30147,-0.150637179613113,-0.030524257570505,0.0112399822101,38272,207,-2684,-3962,0.957274436950684 +30149,-0.153402894735336,-0.033883687108755,0.011932397261262,38272,127,-1875,-4016,0.964233875274658 +30151,-0.163904562592506,-0.029292616993189,0.009630592539907,38272,1178,-2439,-3980,0.964344680309296 +30153,-0.169702142477036,-0.036314837634564,0.009878098033369,38272,635,-1560,-4028,0.964209854602814 +30155,-0.183341577649116,-0.025493750348687,0.011557743884623,38272,1780,-2926,-3956,0.965534508228302 +30157,-0.18656525015831,-0.028936088085175,0.013828345574439,38272,759,-1906,-4000,0.970745503902435 +30159,-0.192217364907265,-0.027714552357793,0.014529191888869,38272,1421,-2191,-3919,0.968020915985107 +30161,-0.19777475297451,-0.029338309541345,0.016006829217076,38272,1158,-2014,-3982,0.974465787410736 +30163,-0.196139454841614,-0.03749381005764,0.016060527414084,38272,1024,-1349,-3898,0.974032163619995 +30165,-0.1926289498806,-0.036471661180258,0.017451480031014,38272,507,-2082,-3970,0.980280339717865 +30167,-0.195970103144646,-0.037639480084181,0.019638933241367,38272,1442,-1827,-3853,0.981375098228455 +30169,-0.20033960044384,-0.029654216021299,0.019543047994375,38272,1253,-2659,-3953,0.97222775220871 +30171,-0.201085835695267,-0.02812285348773,0.016485560685396,38272,1418,-2154,-3889,0.962244510650635 +30173,-0.204660266637802,-0.022048717364669,0.018158974125981,38272,1334,-2615,-3960,0.951858758926392 +30175,-0.208092838525772,-0.026461679488421,0.022434260696173,38272,1804,-1742,-3816,0.948673069477081 +30177,-0.21301594376564,-0.024668518453837,0.022277876734734,38272,1630,-2256,-3928,0.95451146364212 +30179,-0.204192146658897,-0.026767974719405,0.019574528560042,38272,949,-1879,-3846,0.958982765674591 +30181,-0.194629400968552,-0.022721946239472,0.018511243164539,38272,408,-2428,-3951,0.960600674152374 +30183,-0.18770195543766,-0.017786104232073,0.022480128332973,38272,896,-2514,-3810,0.964920043945312 +30185,-0.186241328716278,-0.012103558517993,0.02493236400187,38272,-32767,-2685,-3903,0.968742907047272 +30187,-0.183947175741196,-0.001762501429766,0.025637101382017,38272,-23432,-3148,-3770,0.97553151845932 +30189,-0.177489548921585,-0.00170536688529,0.024145379662514,38272,-24257,-2425,-3904,0.973740518093109 +30191,-0.17350922524929,0.007942396216095,0.020524451509118,38272,-23896,-3256,-3828,0.973657369613647 +30193,-0.173514559864998,0.007761393673718,0.018005950376391,38272,-24029,-2542,-3943,0.975752234458923 +30195,-0.181734949350357,0.014675355516374,0.012165041640401,38272,-23059,-3170,-3925,0.971833407878876 +30197,-0.203118458390236,0.009180376306176,0.009160497225821,38272,-22244,-2184,-4003,0.971906363964081 +30199,-0.242971673607826,0.017255960032344,0.00873345322907,38272,-19960,-3296,-3964,0.964863359928131 +30201,-0.286293685436249,0.021133534610272,0.008461808785796,38272,-19623,-3030,-4006,0.96412843465805 +30203,-0.335425347089767,0.024585153907538,0.002734597539529,38272,-17918,-3090,-4034,0.959970653057098 +30225,-1.38334834575653,0.011407350189984,-0.024894254282117,38272,2108,-2247,-4253,0.949117124080658 +30227,-1.49603235721588,0.00651343818754,-0.023876709863544,38272,6323,-2250,-4365,0.950584232807159 +30229,-1.59985017776489,-0.008152459748089,-0.023152515292168,38272,4594,-1324,-4245,0.957087755203247 +30231,-1.69938540458679,-0.020768016576767,-0.026351826265454,38272,9190,-1245,-4400,0.955600023269653 +30233,-1.80527532100678,-0.024110991507769,-0.027164809405804,38272,8238,-1894,-4278,0.959280610084534 +30235,-1.90156888961792,-0.04006939008832,-0.02547019906342,38272,12842,-668,-4397,0.96470046043396 +30237,-1.99976587295532,-0.042446535080671,-0.023868098855019,38272,11124,-1678,-4259,0.96866649389267 +30239,-2.09146404266357,-0.053652592003346,-0.02050737477839,38272,16279,-763,-4346,0.971760153770447 +30241,-2.18084073066711,-0.052009455859661,-0.0164461620152,38272,13830,-1800,-4212,0.966040551662445 +30243,-2.24675464630127,-0.06591123342514,-0.013572637923062,38272,17714,-348,-4272,0.96297299861908 +30245,-2.29632091522217,-0.081549294292927,-0.013894077390432,38272,13450,-105,-4198,0.954571425914764 +30247,-2.3473048210144,-0.081610351800919,-0.017235416918993,38272,19108,-1050,-4324,0.956212282180786 +30249,-2.3902542591095,-0.088748402893543,-0.016626866534352,38272,15190,-570,-4220,0.961084067821503 +30251,-2.42610883712769,-0.085713684558869,-0.014267960563302,38272,20190,-1156,-4298,0.963823080062866 +30253,-2.45040225982666,-0.093418747186661,-0.012671860866249,38272,15627,-418,-4196,0.966041445732117 +30255,-2.47294735908508,-0.081546239554882,-0.011975046247244,38272,20922,-1804,-4277,0.970572888851166 +30257,-2.48043394088745,-0.07562530785799,-0.007474932819605,38272,15793,-1606,-4164,0.977924108505249 +30259,-2.48151159286499,-0.066342763602734,-0.004198129288852,38272,20461,-1820,-4186,0.982464611530304 +30261,-2.47164511680603,-0.065735675394535,-0.00431506941095,38272,15374,-1329,-4144,0.983332097530365 +30263,-2.45105218887329,-0.069174364209175,-0.001869041123427,38450,19343,-838,-4164,0.981363892555237 +30265,-2.42949748039246,-0.055123999714851,-3.42376551998313E-05,38450,14873,-2408,-4116,0.979181587696075 +30267,-2.39873576164246,-0.050036977976561,0.002353463089094,38450,18679,-1738,-4110,0.982214868068695 +30269,-2.35153579711914,-0.047856789082289,0.00338987656869,38450,12839,-1635,-4093,0.986336946487427 +30271,-2.28375601768494,-0.050435159355402,0.002635687822476,38450,15049,-1162,-4110,0.991480946540832 +30273,-2.22170615196228,-0.029118292033672,0.001928578014486,38450,10786,-3250,-4104,0.995532751083374 +30275,-2.15172386169434,-0.02010471187532,0.004443188663572,38450,13592,-2457,-4074,0.998855292797089 +30277,-2.08070397377014,-0.007331223227084,0.006296744570136,38450,8940,-2937,-4074,1.0031601190567 +30279,-1.99768948554993,-0.004354188684374,0.010456681251526,38450,10941,-2260,-3995,1.00540542602539 +30281,-1.90522599220276,0.008462972939014,0.00928355474025,38450,5641,-3159,-4052,1.00392055511475 +30283,-1.80715417861938,0.027326494455338,0.007574780844152,38450,7478,-3910,-4008,1.01072132587433 +30285,-1.71437251567841,0.042663112282753,0.008504559285939,38450,3551,-3837,-4056,1.0082631111145 +30287,-1.62644803524017,0.062663890421391,0.012077764607966,38450,5905,-4574,-3929,1.01285088062286 +30289,-1.53245389461517,0.068558134138584,0.019841803237796,38450,1449,-3553,-3975,1.00700032711029 +30291,-1.43456709384918,0.075552225112915,0.024959562346339,38450,2618,-3871,-3763,1.00062966346741 +30293,-1.33247041702271,0.075158283114433,0.029638435691595,38450,-1492,-3224,-3902,0.998387813568115 +30295,-1.23695433139801,0.089777804911137,0.032448951154947,38450,35,-4672,-3657,0.995960474014282 +30297,-1.13246059417725,0.093529425561428,0.029166251420975,38450,-4113,-3817,-3898,1.00129652023315 +30299,-1.0400630235672,0.11473436653614,0.023477256298065,38450,-2572,-5600,-3736,1.00389587879181 +30301,-0.945098519325256,0.11454925686121,0.023799177259207,38450,-5788,-3883,-3928,1.00288248062134 +30303,-0.860082685947418,0.130099311470985,0.030025018379092,38450,-4680,-5494,-3639,1.00211346149445 +30305,-0.770000636577606,0.133311733603477,0.037488732486963,38450,-7700,-4449,-3826,0.994627356529236 +30307,-0.690710246562958,0.148431003093719,0.041264940053225,38450,-6820,-5811,-3483,0.992134094238281 +30309,-0.612957894802094,0.163181409239769,0.04265446215868,38450,-8898,-5766,-3780,0.997070372104645 +30311,-0.539680182933807,0.169137552380562,0.04152699187398,38450,-8697,-5554,-3452,0.998712062835693 +30313,-0.476656466722488,0.168865561485291,0.04557066783309,38450,-9693,-4843,-3750,1.00993776321411 +30315,-0.416356205940247,0.158704310655594,0.047615732997656,38450,-9676,-4298,-3377,1.00911259651184 +30317,-0.359751254320145,0.15533247590065,0.047214139252901,38450,-10858,-4493,-3727,1.01370692253113 +30319,-0.303560048341751,0.149254530668259,0.047128088772297,38450,-11189,-4500,-3378,1.0164680480957 +30321,-0.257466584444046,0.153578147292137,0.049680441617966,38450,-11571,-5082,-3698,1.01490473747253 +30323,-0.223032116889954,0.142320111393929,0.052959617227316,38450,-10957,-4072,-3303,1.00613415241241 +30325,-0.200313687324524,0.14180052280426,0.052084613591433,38450,-10753,-4625,-3670,0.996411800384522 +30327,-0.180459141731262,0.128828749060631,0.051656648516655,38450,-10647,-3789,-3316,0.992442488670349 +30329,-0.170717135071754,0.124028645455837,0.053065769374371,38450,-10302,-4117,-3651,0.990369558334351 +30331,-0.159176617860794,0.107183404266834,0.053607698529959,38450,-10450,-3210,-3299,0.992715656757355 +30333,-0.157147124409676,0.099251821637154,0.048485528677702,38450,-10007,-3581,-3671,0.988363564014435 +30335,-0.158712670207024,0.086960762739182,0.045703873038292,38450,19624,-3249,-3397,0.986521422863007 +30337,-0.161198392510414,0.072978489100933,0.040237441658974,38647,-4756,-2805,-3719,0.979483306407928 +30339,-0.16874948143959,0.067819878458977,0.038027133792639,38647,-4103,-3483,-3493,0.982342600822449 +30341,-0.185906663537025,0.059209689497948,0.039685759693384,38647,-3361,-3020,-3715,0.980157494544983 +30343,-0.208414152264595,0.055363461375237,0.041768882423639,38647,-2395,-3401,-3451,0.980366170406342 +30345,-0.230682656168938,0.034353632479906,0.04352317750454,38647,-2346,-1796,-3680,0.986137568950653 +30347,-0.249194145202637,0.02551456913352,0.040027473121882,38647,-1996,-2566,-3488,0.990562081336975 +30349,-0.259762078523636,0.013749232515693,0.035446174442768,38647,-2739,-2170,-3729,0.99662697315216 +30351,-0.275966674089432,0.007550346665084,0.033435251563788,38647,-1689,-2466,-3573,0.994327247142791 +30353,-0.290897011756897,-0.002182079013437,0.033746264874935,38647,-1939,-2085,-3735,0.989230334758758 +30355,-0.305378764867783,-0.014078976586461,0.031998224556446,38647,-1297,-1709,-3602,0.981099903583527 +30357,-0.321731120347977,-0.021430043503642,0.029192447662354,38647,-1342,-1970,-3762,0.974482178688049 +30375,-0.48558896780014,-0.110819131135941,0.043997615575791,38647,2591,-435,-3521,0.981616020202637 +30377,-0.496629863977432,-0.123476170003414,0.042869687080383,38647,1319,77,-3647,0.984166204929352 +30379,-0.506283044815064,-0.123178787529469,0.045645788311958,38647,2247,-573,-3509,0.986741721630096 +30381,-0.511864244937897,-0.117937296628952,0.050044149160385,38647,1298,-1222,-3594,0.987943708896637 +30383,-0.520012974739075,-0.100287355482578,0.050054498016834,38647,2512,-2138,-3435,0.9892538189888 +30385,-0.522758305072784,-0.103377960622311,0.048567559570074,38647,1409,-783,-3599,0.991151094436646 +30387,-0.525363266468048,-0.095151647925377,0.048503331840038,38647,2362,-1497,-3444,0.991336405277252 +30389,-0.524198353290558,-0.091451674699783,0.047981195151806,38647,1312,-1392,-3598,0.98758453130722 +30391,-0.526205718517303,-0.089570105075836,0.049722820520401,38647,2501,-1085,-3421,0.975701570510864 +30393,-0.533629834651947,-0.082045421004295,0.052411630749703,38647,2227,-1755,-3562,0.977994620800018 +30395,-0.53581166267395,-0.083802498877049,0.05582644790411,38647,2848,-870,-3339,0.981171250343323 +30397,-0.532034814357758,-0.078256346285343,0.057823069393635,38647,1574,-1623,-3519,0.986030340194702 +30399,-0.524366021156311,-0.069295518100262,0.058403484523296,38647,2146,-1830,-3290,0.992152154445648 +30401,-0.521088123321533,-0.048424828797579,0.057004071772099,38647,1625,-3111,-3517,0.994730949401856 +30403,-0.514447331428528,-0.046824779361487,0.052308432757855,38647,2212,-1640,-3335,0.995043694972992 +30405,-0.506238758563995,-0.044808216392994,0.049056965857744,38647,1225,-1785,-3565,0.993408501148224 +30407,-0.494157582521439,-0.03788723051548,0.049615569412708,38647,1628,-2142,-3352,0.997604250907898 +30409,-0.477798074483871,-0.028230780735612,0.049191050231457,38647,386,-2547,-3557,0.99632316827774 +30411,-0.464960932731628,-0.016961306333542,0.048572741448879,38647,30451,-2769,-3338,0.999133169651032 +30413,-0.454182654619217,-0.021423045545817,0.049427699297667,38969,5520,-1619,-3548,0.993032932281494 +30415,-0.448282778263092,-0.012717430479825,0.053730510175228,38969,6574,-2631,-3266,0.987441718578339 +30417,-0.434518307447434,-0.007273936178535,0.059526838362217,38969,5209,-2517,-3470,0.983875751495361 +30419,-0.414979726076126,0.005779865663499,0.058805197477341,38969,5238,-3219,-3181,0.98204904794693 +30421,-0.384464085102081,0.009371166117489,0.052328355610371,38969,3462,-2615,-3510,0.981507062911987 +30423,-0.349332004785538,0.017564535140991,0.0498385168612,38969,3205,-3062,-3266,0.981588423252106 +30425,-0.308266520500183,0.02385806851089,0.051594711840153,38969,1753,-3014,-3507,0.986050069332123 +30427,-0.26620951294899,0.035034921020269,0.053572162985802,38969,1475,-3571,-3197,0.989006161689758 +30429,-0.226977035403252,0.052086174488068,0.054691087454558,38969,820,-4198,-3476,0.994212329387665 +30431,-0.186272278428078,0.064395077526569,0.054039228707552,38969,356,-4147,-3154,0.994600653648376 +30433,-0.147678360342979,0.079635933041573,0.052784129977226,38969,-206,-4486,-3478,0.996317744255066 +30435,-0.10282276570797,0.07508572191,0.049039673060179,38969,-1244,-3134,-3192,0.997847557067871 +30437,-0.061009895056486,0.08151488006115,0.047202553600073,38969,-1652,-3908,-3506,1.00195467472076 +30439,-0.016911581158638,0.077063404023647,0.052219983190298,38969,-2573,-3194,-3142,0.997710168361664 +30441,0.024452237412334,0.087850108742714,0.053679503500462,38969,-2857,-4338,-3451,0.992962658405304 +30443,0.074366644024849,0.08691231161356,0.054460808634758,38969,-4505,-3637,-3096,0.991639256477356 +30445,0.118909083306789,0.095840707421303,0.053800702095032,38969,-4494,-4352,-3439,0.99141538143158 +30447,0.151034981012344,0.105131819844246,0.053893949836493,38969,-4546,-4703,-3074,0.997854113578796 +30449,0.178712084889412,0.108377255499363,0.052436366677284,38969,32767,-4165,-3436,0.99930465221405 +30451,0.209620699286461,0.122021779417992,0.049455732107163,43706,4351,-5336,-3099,0.999961197376251 +30453,0.244330942630768,0.126176238059998,0.049550872296095,43706,4118,-4534,-3444,0.99937117099762 +30455,0.274240732192993,0.132822796702385,0.04983850568533,43706,3342,-5051,-3074,0.997096598148346 +30457,0.306773513555527,0.126859739422798,0.049056254327297,43706,3328,-3872,-3435,0.99428403377533 +30459,0.333770841360092,0.145960047841072,0.048360455781221,43706,2522,-6209,-3068,0.99641352891922 +30461,0.371890097856522,0.1490218937397,0.04937856644392,43706,1915,-4895,-3421,1.0024082660675 +30463,0.405690729618073,0.157962635159493,0.050069943070412,43706,770,-5738,-3026,1.0078090429306 +30465,0.447552353143692,0.148229569196701,0.050311826169491,43706,448,-4031,-3402,1.00666725635529 +30467,0.488696783781052,0.141993686556816,0.050369244068861,43706,-1240,-4457,-3026,1.00058972835541 +30469,0.53062516450882,0.144447207450867,0.049369525164366,43706,-901,-4908,-3396,1.00059473514557 +30471,0.581614494323731,0.136663556098938,0.04699656739831,43706,-3642,-4323,-3060,1.00012028217316 +30473,0.632523596286774,0.131424799561501,0.045967794954777,43706,-3207,-4228,-3407,1.00639462471008 +30475,0.677994906902313,0.127805605530739,0.046182457357645,43706,-5024,-4531,-3067,1.01238083839417 +30477,0.717085063457489,0.137567490339279,0.044901050627232,43706,-3819,-5444,-3404,1.01772010326386 +30479,0.765788435935974,0.129105105996132,0.041669249534607,43706,-6928,-4258,-3110,1.01986479759216 +30481,0.803472280502319,0.133753761649132,0.042089801281691,43706,-5243,-5078,-3412,1.02616739273071 +30483,0.839674592018127,0.128397822380066,0.047421749681234,43706,-7536,-4517,-3035,1.03528797626495 +30485,0.86972177028656,0.123160757124424,0.046477448195219,43706,-5968,-4271,-3371,1.04263603687286 +30487,0.901712238788605,0.119605451822281,0.043356217443943,43706,20626,-4552,-3081,1.04967212677002 +30489,0.927765846252441,0.12325794249773,0.04372039064765,44063,-1936,-4958,-3380,1.04545664787292 +30491,0.946254193782806,0.126803562045097,0.040154531598091,44063,-3744,-5235,-3105,1.03731024265289 +30493,0.964878857135773,0.118806533515453,0.037706445902586,44063,-2265,-4113,-3411,1.0361750125885 +30495,0.990539133548737,0.115230813622475,0.038559049367905,44063,-5315,-4597,-3126,1.03645002841949 +30497,1.01460552215576,0.105185434222221,0.042067337781191,44063,-3720,-3821,-3372,1.04299819469452 +30499,1.03481984138489,0.104733377695084,0.040220327675343,44063,-6003,-4706,-3107,1.0451785326004 +30501,1.05639481544495,0.111720256507397,0.038428090512753,44063,-4517,-5182,-3388,1.04905271530151 +30503,1.08702063560486,0.113169997930527,0.038631368428469,44063,-7980,-5028,-3113,1.04847753047943 +30505,1.11494171619415,0.113413125276566,0.037899594753981,44063,-6213,-4775,-3382,1.0499312877655 +30507,1.13371694087982,0.101140670478344,0.037585083395243,44063,-8299,-3895,-3127,1.05019199848175 +30509,1.14594423770905,0.097614951431751,0.037775814533234,44063,-5960,-4324,-3374,1.0506374835968 +30511,1.16081357002258,0.091777421534062,0.036470483988524,44063,-8891,-4252,-3141,1.04740655422211 +30513,1.17163920402527,0.098993808031082,0.034326530992985,44063,-6671,-5156,-3390,1.04470467567444 +30515,1.17372786998749,0.107470504939556,0.034078177064657,44063,-8630,-5583,-3152,1.0513710975647 +30517,1.17452383041382,0.108202569186687,0.036777783185244,44063,-6446,-4874,-3365,1.05804777145386 +30519,1.17681920528412,0.10707750916481,0.038139522075653,44063,-9143,-4945,-3099,1.06228649616241 +30521,1.17677044868469,0.100094459950924,0.037086062133312,44063,-6874,-4256,-3355,1.06864523887634 +30523,1.16761326789856,0.09895882755518,0.034842159599066,44063,-8629,-4861,-3137,1.07176768779755 +30525,1.15575861930847,0.087231785058975,0.031768698245287,44063,-6182,-3780,-3383,1.07800912857056 +30527,1.14197111129761,0.080819770693779,0.030155776068568,44063,-8335,-4223,-3198,1.08395576477051 +30529,1.12072193622589,0.087714537978172,0.030611148104072,44063,-5455,-5159,-3385,1.08956062793732 +30531,1.09206926822662,0.090297900140286,0.031869485974312,44063,-6896,-5061,-3168,1.09037411212921 +30533,1.06035840511322,0.098755478858948,0.027465602383018,44063,-4268,-5473,-3400,1.08707249164581 +30535,1.03722989559174,0.093464441597462,0.022279864177108,44063,-6812,-4603,-3274,1.08406674861908 +30537,1.01386117935181,0.082848250865936,0.021254925057292,44063,-4604,-3925,-3437,1.07755672931671 +30539,0.981230199337006,0.073181487619877,0.023833893239498,44063,-5611,-4002,-3263,1.07723355293274 +30541,0.945931851863861,0.073512136936188,0.02505168132484,44063,-3157,-4612,-3405,1.08192980289459 +30543,0.91560024023056,0.071479737758637,0.023635415360332,44063,-5070,-4555,-3263,1.08304715156555 +30545,0.878302931785584,0.066952645778656,0.019631689414382,44063,-2397,-4206,-3438,1.08355617523193 +30547,0.83648031949997,0.065976887941361,0.017600998282433,44063,-3301,-4577,-3333,1.08147788047791 +30549,0.79506915807724,0.066889986395836,0.0192716922611,44063,-1229,-4629,-3436,1.08418476581573 +30551,0.759279847145081,0.063503108918667,0.02001628279686,44063,-2783,-4395,-3303,1.08545362949371 +30553,0.714972615242004,0.06791327893734,0.020789934322238,44063,-160,-4927,-3421,1.083052277565 +30555,0.675073802471161,0.063237652182579,0.021893806755543,44063,-1382,-4330,-3277,1.08284664154053 +30557,0.640023767948151,0.06415455788374,0.021555190905929,44063,2,-4656,-3412,1.08510315418243 +30559,0.60455709695816,0.06019227206707,0.020397901535034,44063,-778,-4357,-3292,1.0911066532135 +30561,0.564078629016876,0.05398565530777,0.020415907725692,44063,1263,-4030,-3415,1.09663331508636 +30563,0.526998102664948,0.049164045602083,0.017923165112734,44063,406,-4141,-3323,1.09911870956421 +30565,0.491936653852463,0.03936966881156,0.014889992773533,44063,1728,-3587,-3449,1.1019275188446 +30567,0.457996070384979,0.029708025977016,0.017757741734386,44063,1142,-3503,-3330,1.10185301303864 +30569,0.421791136264801,0.027353797107935,0.020813845098019,44063,2666,-3965,-3405,1.10110867023468 +30571,0.389455288648605,0.021337401121855,0.019911991432309,44063,2002,-3648,-3305,1.1034334897995 +30573,0.365639507770538,0.022103631868959,0.01858526468277,44063,2463,-4127,-3417,1.106072306633 +30575,0.35021236538887,0.017417868599296,0.016095528379083,44063,1309,-3686,-3348,1.11133241653442 +30577,0.332327634096146,0.007976036518812,0.015933830291033,44063,2411,-3203,-3432,1.11066401004791 +30579,0.307273119688034,0.006677895784378,0.016882969066501,44063,2599,-3764,-3341,1.10977363586426 +30581,0.290185511112213,0.007197984028608,0.014599270187318,44063,2871,-3912,-3439,1.10504174232483 +30583,0.283961951732635,0.011332353577018,0.013331476598978,44063,1550,-4246,-3378,1.09647023677826 +30585,0.281975895166397,0.004330258350819,0.016893468797207,44063,1831,-3342,-3420,1.08922517299652 +30587,0.271753877401352,0.000925579864997,0.017983598634601,44063,1966,-3549,-3324,1.08462154865265 +30589,0.259694486856461,-0.003884022356942,0.012538077309728,44063,2801,-3387,-3447,1.09098660945892 +30603,0.313247919082642,-0.0127147519961,0.01020990870893,44063,-579,-3722,-3414,1.12699198722839 +30605,0.325024783611298,-0.01228498108685,0.010637669824064,44063,-154,-3631,-3454,1.12379038333893 +30607,0.337166786193848,-0.006349891424179,0.009376804344356,44063,-1095,-4077,-3420,1.1214851140976 +30609,0.350405007600784,0.001460496685468,0.00877945497632,44063,-729,-4357,-3466,1.12379062175751 +30611,0.363154947757721,0.005951537285,0.011138601228595,44063,-1677,-4179,-3393,1.12621283531189 +30613,0.372422933578491,0.010148905217648,0.013242463581264,44063,-880,-4228,-3433,1.12883687019348 +30615,0.388050854206085,0.004898506216705,0.011724738404155,44063,-2417,-3475,-3385,1.13335204124451 +30617,0.410382449626923,0.003035880858079,0.01061986759305,44063,-2494,-3699,-3449,1.13939940929413 +30619,0.423915386199951,0.007970075123012,0.011546963825822,44063,-2986,-4272,-3384,1.14474213123322 +30621,0.440276294946671,0.014067488722503,0.011207827366889,44063,-2645,-4436,-3443,1.14702665805817 +30623,0.458977699279785,0.019280940294266,0.011123484000564,44063,-4089,-4490,-3383,1.15078055858612 +30625,0.4718998670578,0.01689319126308,0.012796157971025,44063,-3021,-3884,-3430,1.15782749652863 +30627,0.485517472028732,0.019983172416687,0.012757868506014,44063,-4339,-4359,-3362,1.15367460250855 +30629,0.496716678142548,0.022670956328511,0.013651517219842,44063,-3438,-4345,-3422,1.14845764636993 +30631,0.49786901473999,0.017352655529976,0.019132053479552,44063,-3832,-3728,-3285,1.13919425010681 +30633,0.497169524431229,0.019367868080735,0.019438756629825,44063,-2783,-4263,-3379,1.12910354137421 +30635,0.506548762321472,0.029809769243002,0.016676506027579,44063,-4751,-5072,-3307,1.1211348772049 +30637,0.521986722946167,0.039795625954867,0.018131988123059,44063,-4490,-5146,-3384,1.11282229423523 +30639,0.534551680088043,0.031703088432551,0.018903445452452,44063,-5630,-3792,-3277,1.11295413970947 +30641,0.540414392948151,0.024752097204328,0.017850259318948,44063,-4278,-3736,-3383,1.11439347267151 +30643,0.539587378501892,0.029573576524854,0.017668250948191,44063,-4955,-4700,-3289,1.12196862697601 +30645,0.532861351966858,0.031593486666679,0.017529940232635,44063,-3480,-4495,-3382,1.13196980953217 +30647,0.52106237411499,0.030888793990016,0.016679530963302,44063,-4077,-4342,-3297,1.13694643974304 +30649,0.507624924182892,0.03279384970665,0.016696294769645,44063,-2842,-4522,-3384,1.14181101322174 +30651,0.501987338066101,0.033766977488995,0.015301552601159,44063,-4411,-4526,-3310,1.14220547676086 +30653,0.497009009122849,0.035569731146097,0.012953760102391,44063,-3494,-4574,-3407,1.1413311958313 +30655,0.492405533790588,0.03258453309536,0.013213968835771,44063,-4523,-4244,-3333,1.13972949981689 +30657,0.480946928262711,0.037602286785841,0.014211483299732,44063,-2994,-4853,-3396,1.1354718208313 +30659,0.460259348154068,0.044980209320784,0.014084441587329,44063,-3036,-5208,-3317,1.12748801708221 +30661,0.440507352352142,0.050581194460392,0.012584682554007,44063,-2001,-5106,-3404,1.12116408348084 +30663,0.424221605062485,0.055076193064451,0.007543744985014,44063,-2941,-5185,-3390,1.11835658550262 +30665,0.414662599563599,0.051749929785729,0.004112551920116,44063,-2527,-4511,-3461,1.12067902088165 +30667,0.405756056308746,0.050963986665011,0.003730751341209,44063,-3324,-4771,-3435,1.12387561798096 +30669,0.388322651386261,0.054310653358698,0.003197590820491,44063,-1743,-5053,-3466,1.12936007976532 +30671,0.367949962615967,0.060449033975601,0.000720866082702,44063,-2034,-5451,-3468,1.13480615615845 +30673,0.35113388299942,0.062173079699278,-0.000313932570862,44063,-1394,-5082,-3490,1.14083468914032 +30675,0.33594998717308,0.055207192897797,-0.000655392184854,44063,-2020,-4452,-3485,1.14871835708618 +30677,0.321620166301727,0.051408521831036,-0.001281539094634,44063,-1276,-4560,-3496,1.14910292625427 +30679,0.306673854589462,0.045343209058046,-0.0017695564311,44063,-1683,-4387,-3500,1.14602601528168 +30681,0.291467100381851,0.037436831742525,-0.002114075701684,44063,-896,-4090,-3502,1.13978469371796 +30683,0.270843148231506,0.034811351448298,-0.003129661548883,44063,-802,-4490,-3518,1.13408696651459 +30685,0.256213843822479,0.024808306246996,-0.003350411076099,44063,-531,-3780,-3510,1.12630772590637 +30687,0.251119673252106,0.01494465675205,-0.001128874020651,44063,-1686,-3663,-3498,1.12132585048676 +30689,0.241876542568207,0.014480112120509,0.001172212301753,44063,-802,-4326,-3479,1.11757552623749 +30691,0.231165736913681,0.016833068802953,0.000499001645949,44063,-1040,-4576,-3479,1.11383211612701 +30693,0.219894513487816,0.019736122339964,-0.004760885145515,44063,-423,-4655,-3520,1.11388516426086 +30695,0.206399008631706,0.018692020326853,-0.006610720418394,44063,-507,-4378,-3562,1.11693692207336 +30697,0.192037746310234,0.019021620973945,-0.002712759422138,44063,128,-4473,-3507,1.11980831623077 +30699,0.178755804896355,0.02208624407649,0.001106322859414,44063,-134,-4741,-3471,1.12711977958679 +30701,0.17632257938385,0.017548516392708,0.003829161403701,44063,-557,-4118,-3461,1.13400340080261 +30703,0.175614237785339,0.015127466060221,0.005340261384845,44063,-1035,-4247,-3422,1.13776862621307 +30705,0.169604107737541,0.012835361994803,0.005728005431592,44063,-260,-4222,-3447,1.14246785640717 +30707,0.162361145019531,0.012129816226661,0.006076974328607,44063,-409,-4333,-3413,1.14216268062592 +30709,0.160759463906288,0.004151701461524,0.005639810115099,44063,-499,-3701,-3446,1.14149284362793 +30711,0.161564394831657,-0.005811502691358,0.007055466994643,44063,-1036,-3391,-3403,1.14082825183868 +30713,0.157792314887047,-0.013425615616143,0.010695297271013,44063,-354,-3477,-3410,1.14148128032684 +30715,0.151813074946404,-0.017127616330981,0.012608440592885,44063,-450,-3658,-3338,1.13978564739227 +30717,0.15406896173954,-0.02022098004818,0.010605749674141,44063,-782,-3702,-3409,1.13561046123505 +30719,0.154806330800056,-0.021522028371692,0.012051051482558,44063,-1029,-3758,-3343,1.13566768169403 +30721,0.154275327920914,-0.029852762818337,0.016127459704876,44063,-637,-3184,-3369,1.13585805892944 +30723,0.147149190306663,-0.030803635716438,0.015772046521306,44063,-389,-3626,-3298,1.13597822189331 +30725,0.146120503544807,-0.030375750735402,0.016165193170309,44063,-533,-3796,-3366,1.1362646818161 +30727,0.151769295334816,-0.030563946813345,0.018327141180635,44063,-1431,-3673,-3265,1.14092218875885 +30729,0.154806241393089,-0.032412953674793,0.017495721578598,44063,-1000,-3595,-3354,1.14700651168823 +30731,0.152690038084984,-0.028507579118013,0.016690038144589,44063,-939,-3995,-3281,1.15425395965576 +30733,0.146724551916122,-0.017915509641171,0.01052909437567,44063,-291,-4687,-3399,1.15869069099426 +30735,0.148924931883812,-0.013421799987555,0.00666263513267,44063,-1232,-4285,-3395,1.15897703170776 +30737,0.158128261566162,-0.024081207811833,0.008667419664562,44063,-1591,-3077,-3411,1.15790557861328 +30739,0.166794091463089,-0.030953258275986,0.009301503188908,44063,-2045,-3176,-3365,1.1559727191925 +30741,0.173120751976967,-0.035050757229328,0.010469008237124,44063,-1659,-3381,-3397,1.15785157680511 +30743,0.175319761037827,-0.038272455334663,0.013534761033952,44063,-1786,-3302,-3314,1.1534743309021 +30745,0.169758692383766,-0.031133988872171,0.01710868999362,44063,-824,-4229,-3349,1.14817774295807 +30747,0.168716490268707,-0.02326718531549,0.017515569925308,44063,-1512,-4335,-3263,1.14251828193665 +30749,0.177590176463127,-0.010846473276615,0.015308463014662,44063,-2033,-4893,-3359,1.14293086528778 +30751,0.191657543182373,-0.005579852964729,0.011545755900443,44063,-3034,-4438,-3328,1.14987945556641 +30753,0.203025862574577,-0.011105863377452,0.009018183685839,44063,-2650,-3607,-3400,1.15379285812378 +30755,0.208328410983086,-0.017717391252518,0.00972718000412,44063,-2748,-3394,-3349,1.1544406414032 +30757,0.205995485186577,-0.026126973330975,0.01023814547807,44063,-1792,-3183,-3390,1.15877389907837 +30759,0.195028811693192,-0.027733961120248,0.01105706486851,44063,-1443,-3584,-3333,1.16070759296417 +30761,0.190030634403229,-0.027196412906051,0.01647536829114,44063,-1447,-3802,-3345,1.16304707527161 +30763,0.19945316016674,-0.020751217380166,0.017463112249971,44063,-3050,-4263,-3254,1.16036939620972 +30765,0.212163910269737,-0.013394687324762,0.013973571360111,44063,-3111,-4484,-3359,1.15608811378479 +30767,0.213328257203102,-0.011601435951889,0.014936740510166,44063,-2757,-4073,-3280,1.15178692340851 +30769,0.206150233745575,-0.010756350122392,0.017577642574906,44063,-1683,-4054,-3332,1.14208340644836 +30771,0.198380351066589,-0.018506364896894,0.016920261085034,44063,-1950,-3273,-3254,1.13280832767487 +30773,0.193435207009316,-0.023934612050653,0.014926184900105,44063,-1737,-3411,-3347,1.12203872203827 +30775,0.193915650248528,-0.026026448234916,0.015218066051602,44063,-2545,-3549,-3273,1.11215472221375 +30777,0.197860777378082,-0.025185925886035,0.01665086299181,44063,-2512,-3834,-3333,1.10890436172485 +30779,0.199556156992912,-0.026555044576526,0.021076759323478,44063,-2799,-3583,-3200,1.11303782463074 +30781,0.189228028059006,-0.029126517474651,0.023324530571699,44063,-1444,-3524,-3284,1.12236166000366 +30783,0.176294162869453,-0.030508307740092,0.022830536589027,44063,-1446,-3507,-3176,1.13066852092743 +30785,0.167858645319939,-0.024479530751705,0.020197529345751,44063,-1341,-4196,-3301,1.13797247409821 +30787,0.174369752407074,-0.02292869053781,0.017019459977746,44063,-2875,-3833,-3241,1.14273238182068 +30789,0.181289866566658,-0.019753707572818,0.015492856502533,44063,-2701,-4052,-3331,1.1444696187973 +30791,0.174578309059143,-0.021695939823985,0.015962608158588,44063,-1994,-3597,-3250,1.14792823791504 +30793,0.159207850694656,-0.017214369028807,0.01916896365583,44063,-855,-4176,-3303,1.14775848388672 +30795,0.150112301111221,-0.009494369849563,0.024733966216445,44063,-1486,-4488,-3142,1.14576685428619 +30797,0.151243776082993,-0.009493924677372,0.025740027427673,44063,-1979,-3965,-3253,1.14282059669495 +30799,0.152335911989212,-0.007694459985942,0.020098747685552,44063,-2313,-4094,-3193,1.13644576072693 +30801,0.143871366977692,-0.003475909354165,0.020167486742139,44063,-1244,-4355,-3288,1.13011157512665 +30803,0.128244817256928,0.002825299277902,0.025217700749636,44063,-787,-4583,-3128,1.12623333930969 +30805,0.1205178424716,0.003129040822387,0.028194921091199,44063,-1011,-4173,-3229,1.12552440166473 +30807,0.119891621172428,-0.000728988205083,0.027386214584112,44063,-1781,-3800,-3098,1.12733149528503 +30809,0.111106663942337,-0.003208079608157,0.025494234636426,44063,-848,-3885,-3243,1.13075411319733 +30811,0.091981701552868,0.002303078537807,0.025618890300393,44063,-43,-4530,-3114,1.139031291008 +30813,0.079818308353424,0.005524053703994,0.025267897173762,44063,-192,-4424,-3240,1.14743828773499 +30815,0.076058395206928,0.006721607875079,0.024935211986303,44063,-911,-4301,-3118,1.15517246723175 +30831,0.04779139533639,-0.023768797516823,0.020610122010112,44063,-573,-3277,-3155,1.13864731788635 +30833,0.0498559884727,-0.031169541180134,0.0203413721174,44063,-879,-3122,-3254,1.13679921627045 +30835,0.053581438958645,-0.034533504396677,0.020087940618396,44063,-1167,-3283,-3158,1.13473212718964 +30837,0.057650879025459,-0.036624204367399,0.022964900359511,44063,-1151,-3413,-3233,1.13416230678558 +30839,0.057649739086628,-0.037506449967623,0.026928653940559,44063,-984,-3402,-3074,1.13183760643005 +30841,0.053401205688715,-0.036983452737331,0.028050411492586,44063,-512,-3582,-3193,1.12559175491333 +30843,0.051370844244957,-0.036396071314812,0.026391671970487,44063,-751,-3509,-3076,1.12590444087982 +30845,0.054292652755976,-0.033300515264273,0.025396458804607,44063,-1054,-3806,-3207,1.12984323501587 +30847,0.06249188631773,-0.039999689906836,0.024124555289745,44063,-1677,-2911,-3098,1.13443303108215 +30849,0.075809195637703,-0.054249972105026,0.022300371900201,44063,-2127,-2248,-3224,1.1336042881012 +30851,0.087909430265427,-0.057999040931463,0.023020263761282,44063,-2394,-2810,-3108,1.13124191761017 +30853,0.0948800817132,-0.061202265322209,0.024685312062502,44063,-1977,-2915,-3204,1.12835991382599 +30855,0.09729015827179,-0.062801666557789,0.024426819756627,44063,-1886,-2859,-3088,1.12273395061493 +30857,0.101389996707439,-0.066195376217365,0.022528119385243,44063,-1901,-2803,-3215,1.11988592147827 +30859,0.106405720114708,-0.071218296885491,0.024599242955446,44063,-2262,-2448,-3082,1.11609733104706 +30861,0.107175387442112,-0.067564025521278,0.027710627764464,44063,-1786,-3257,-3175,1.11634123325348 +30863,0.108511857688427,-0.06708811968565,0.028728039935231,44063,-2078,-2878,-3028,1.1204000711441 +30865,0.109514646232128,-0.061752513051033,0.029162807390094,44063,-1879,-3432,-3160,1.12493050098419 +30867,0.109923377633095,-0.058720659464598,0.030708469450474,44063,-2082,-3168,-3000,1.13234853744507 +30869,0.108982861042023,-0.052583523094654,0.028389783576131,44063,-1777,-3595,-3160,1.13834404945374 +30871,0.109762378036976,-0.051434986293316,0.024591332301498,44063,-2147,-3135,-3066,1.14229738712311 +30873,0.112372264266014,-0.049870222806931,0.023308580741286,44063,-2125,-3285,-3191,1.14696729183197 +30875,0.110606640577316,-0.047018688172102,0.02320989407599,44063,-2011,-3321,-3078,1.14885950088501 +30877,0.102813214063644,-0.05239100009203,0.023574877530336,44063,-1285,-2734,-3185,1.14883232116699 +30879,0.103783667087555,-0.062826812267304,0.025002360343933,44063,-2143,-2094,-3054,1.1492475271225 +30881,0.111081935465336,-0.060103617608547,0.026317112147808,44063,-2526,-3179,-3162,1.15096759796143 +30883,0.118255503475666,-0.056249808520079,0.028043868020177,44063,-2879,-3198,-3013,1.14900946617126 +30885,0.126555025577545,-0.057439848780632,0.029456108808518,44063,-2870,-2915,-3136,1.1421400308609 +30887,0.13286928832531,-0.059983376413584,0.030027188360691,44063,-3119,-2657,-2985,1.13754570484161 +30889,0.138805851340294,-0.068831279873848,0.029927659779787,44063,-2936,-2179,-3127,1.13368105888367 +30891,0.140533491969109,-0.074558682739735,0.032143779098988,44063,-2980,-2162,-2955,1.1340594291687 +30893,0.140735760331154,-0.076810672879219,0.035015720874071,44063,-2617,-2505,-3087,1.13770270347595 +30895,0.140731170773506,-0.073157340288162,0.034435600042343,44063,-2910,-2826,-2922,1.14108085632324 +30897,0.142060786485672,-0.06690214574337,0.033961765468121,44063,-2779,-3226,-3088,1.14091861248016 +30899,0.135972380638123,-0.057760290801525,0.034312400966883,44063,32767,-32767,-2917,1.14157891273499 +30901,0.121458068490028,-0.047313820570707,0.033184815198183,43759,6540,-32767,-3088,1.1433881521225 +30903,0.107107684016228,-0.044839318841696,0.035048067569733,43759,6553,-32767,-2902,1.14208841323853 +30905,0.099858395755291,-0.049542054533959,0.03969369083643,43759,6364,-32767,-3037,1.14104795455933 +30907,0.098560564219952,-0.053304247558117,0.04037207365036,43759,5784,-32767,-2833,1.14173972606659 +30909,0.105374783277512,-0.0654571428895,0.035256955772638,43759,5313,-32294,-3061,1.14261615276337 +30911,0.121349520981312,-0.090194217860699,0.028281798586249,43759,4205,-30981,-2970,1.13961815834045 +30913,0.139772444963455,-0.125407814979553,0.023934405297041,43759,4013,-30035,-3134,1.1358186006546 +30915,0.158542603254318,-0.177561640739441,0.02101381123066,43759,3413,-27840,-3053,1.13030529022217 +30917,0.178628280758858,-0.24401430785656,0.018251467496157,43759,3343,-26310,-3169,1.12006103992462 +30919,0.205366492271423,-0.325088202953339,0.016154004260898,43759,2076,-23563,-3109,1.11714053153992 +30921,0.232041627168655,-0.410019487142563,0.015117282047868,43759,2088,-22752,-3188,1.11661767959595 +30923,0.260613918304443,-0.501650154590607,0.012713991105557,43759,1021,-20043,-3148,1.11797285079956 +30925,0.301436990499496,-0.611341416835785,0.009274584241211,43759,37,-18153,-3226,1.12027668952942 +30927,0.337537050247192,-0.729776561260223,0.008234714157879,43759,-821,-14428,-3198,1.1274482011795 +30929,0.370117247104645,-0.859383165836334,0.00874453317374,43759,-434,-13125,-3229,1.1338312625885 +30931,0.401061236858368,-0.977431654930115,0.006981723941863,43759,-1570,-10330,-3206,1.14492928981781 +30933,0.444937616586685,-1.10403633117676,0.005974838044494,43759,-2424,-9669,-3246,1.15054988861084 +30935,0.49001482129097,-1.22614300251007,0.00638064974919,43759,-4157,-5784,-3201,1.15069282054901 +30937,0.532182812690735,-1.35630488395691,0.008673896081746,43759,-3703,-5516,-3226,1.14938056468964 +30939,0.578047156333923,-1.5027357339859,0.014585958793759,43759,-5817,789,-3083,1.14833188056946 +30941,0.614143908023834,-1.63985931873322,0.020466020330787,43759,-4636,-539,-3141,1.14675331115723 +30943,0.65094780921936,-1.77314460277557,0.022459195926786,43759,-6562,4706,-2959,1.13823914527893 +30945,0.684693574905396,-1.89369988441467,0.024157915264368,43759,-5708,2453,-3110,1.13279581069946 +30947,0.724133610725403,-2.02516889572144,0.024433726444841,43759,-8186,9258,-2894,1.1294116973877 +30949,0.758774399757385,-2.1410186290741,0.022790795192123,43759,-7100,6323,-3112,1.1250331401825 +30951,0.779502689838409,-2.2425549030304,0.020501159131527,43759,-8029,11351,-2889,1.11922442913055 +30953,0.801105082035065,-2.34711360931396,0.022382948547602,43759,-7066,9237,-3107,1.11704123020172 +30955,0.829320192337036,-2.44336533546448,0.024079840630293,43759,-9676,15035,-2788,1.11511921882629 +30957,0.859157264232636,-2.54079532623291,0.024200802668929,43759,-8807,12368,-3084,1.11500561237335 +30959,0.873433232307434,-2.61580324172974,0.026827557012439,43759,-9713,17195,-2689,1.1107292175293 +30961,0.882632493972778,-2.67858076095581,0.030304776504636,43759,-8005,12809,-3029,1.1175811290741 +30963,0.894795000553131,-2.72969079017639,0.030568048357964,43759,-10250,18297,-2575,1.13080930709839 +30983,0.8199542760849,-2.70203685760498,0.014794292859733,43563,-9106,16672,-2447,1.1266154050827 +30985,0.805279970169067,-2.6487123966217,0.011817320249975,43563,-7304,10368,-3051,1.12373566627502 +30987,0.776043474674225,-2.58287596702576,0.008450545370579,43563,-7454,13793,-2488,1.1244387626648 +30989,0.742234528064728,-2.50516796112061,0.008514660410583,43563,-5342,7545,-3054,1.12567865848541 +30991,0.71001809835434,-2.42184591293335,0.010788506828249,43563,-6463,10864,-2442,1.12953221797943 +30993,0.675000965595245,-2.33209109306335,0.01177690923214,43563,-4575,5114,-3011,1.13283932209015 +30995,0.638713240623474,-2.2414824962616,0.012521477416158,43563,-5274,8284,-2417,1.13419485092163 +30997,0.599316716194153,-2.14531540870666,0.012789070606232,43563,-3428,2812,-2984,1.13286375999451 +30999,0.554741978645325,-2.04896259307861,0.013903699815273,43563,-3551,5538,-2405,1.13442599773407 +31001,0.50755649805069,-1.95015144348145,0.017405066639185,43563,-1768,578,-2933,1.13491714000702 +31003,0.462890714406967,-1.84443712234497,0.022922333329916,43563,-2260,2250,-2309,1.13397622108459 +31005,0.418598920106888,-1.72672855854034,0.022010689601302,43563,-876,-3315,-2882,1.13309466838837 +31007,0.379733711481094,-1.61532700061798,0.020043095573783,43563,-1486,-1270,-2369,1.13022744655609 +31009,0.339381366968155,-1.50978255271912,0.019355760887265,43563,-162,-4993,-2882,1.12641727924347 +31011,0.296339631080627,-1.40829634666443,0.020689763128758,43563,44,-3409,-2390,1.12823939323425 +31013,0.248102381825447,-1.3019232749939,0.028420401737094,43563,-7765,27776,-2803,1.13204598426819 +31015,0.200804531574249,-1.2000287771225,0.031951125711203,43563,241,-431,-2295,1.13539719581604 +31017,0.160591080784798,-1.10597348213196,0.026287861168385,43563,640,-3114,-2801,1.14000761508942 +31019,0.127975091338158,-1.01657676696777,0.022688137367368,43563,329,-2119,-2442,1.14369380474091 +31021,0.091853775084019,-0.925474584102631,0.024115141481161,43563,1295,-5136,-2803,1.14505076408386 +31023,0.051659535616636,-0.829460382461548,0.025979844853282,43563,2096,-5319,-2445,1.14651906490326 +31025,0.011295028030872,-0.727547228336334,0.025815984234214,43563,2752,-8478,-2779,1.13999235630035 +31027,-0.020341308787465,-0.634010374546051,0.025676049292088,43563,2667,-8084,-2493,1.13118302822113 +31029,-0.047323998063803,-0.546549379825592,0.02477678284049,43563,2665,-9854,-2776,1.12210083007813 +31031,-0.073640733957291,-0.457888036966324,0.024366967380047,43563,3194,-10447,-2549,1.11377513408661 +31033,-0.095904126763344,-0.369931489229202,0.02345946803689,43563,3079,-12318,-2777,1.11114609241486 +31035,-0.117466427385807,-0.293580770492554,0.022021427750588,43563,3643,-12166,-2620,1.11328101158142 +31037,-0.140104711055756,-0.224633827805519,0.021272741258144,43563,3818,-13011,-2786,1.11497414112091 +31039,-0.160116747021675,-0.16781148314476,0.022170485928655,43563,4321,-12807,-2653,1.11784553527832 +31041,-0.174202725291252,-0.12211561948061,0.023348778486252,43563,3794,-12842,-2767,1.11999428272247 +31043,-0.182835951447487,-0.079399608075619,0.024307547137141,43563,3981,-13274,-2648,1.12305104732513 +31045,-0.191039502620697,-0.035845194011927,0.021112175658345,43563,3725,-13993,-2778,1.1250616312027 +31047,-0.194837242364883,0.003102174261585,0.015177763067186,43563,3944,-14423,-2774,1.12456858158112 +31049,-0.198550671339035,0.04108564928174,0.010778379626572,43563,-5926,20536,-2847,1.12600195407867 +31051,-0.196087419986725,0.064474761486054,0.007729443721473,43563,2017,-8446,-2873,1.1284521818161 +31053,-0.192183911800384,0.071801885962486,0.006796846631914,43563,1488,-7179,-2875,1.1268105506897 +31055,-0.18921959400177,0.074449077248573,0.007363344077021,43563,1967,-7197,-2878,1.1254814863205 +31057,-0.18670628964901,0.082258120179176,0.006384427193552,43563,1608,-7440,-2877,1.1220475435257 +31059,-0.184952706098556,0.096841156482697,0.005083604715765,43563,2082,-8503,-2910,1.11652743816376 +31061,-0.18182210624218,0.107312701642513,0.007084754761308,43563,1591,-8079,-2873,1.11510539054871 +31063,-0.17515917122364,0.111797884106636,0.006135558709502,43563,1677,-8119,-2906,1.11507189273834 +31065,-0.164408192038536,0.111920535564423,0.004318121820688,43563,891,-7500,-2892,1.11785447597504 +31067,-0.149850249290466,0.110648833215237,0.004144528880715,43563,792,-7782,-2930,1.1209831237793 +31069,-0.130631059408188,0.115820042788982,0.005197801161557,43563,-115,-8015,-2887,1.12427353858948 +31071,-0.113518863916397,0.121637761592865,0.012358053587377,43563,77,-8563,-2827,1.12939321994782 +31073,-0.097607150673866,0.115894682705402,0.018655950203538,43563,-287,-7335,-2794,1.13378143310547 +31075,-0.082836754620075,0.098287656903267,0.018011601641774,43563,-208,-6600,-2748,1.13596034049988 +31077,-0.064880341291428,0.081046417355538,0.013858871534467,43563,-854,-6102,-2824,1.13644480705261 +31079,-0.04425198212266,0.067554011940956,0.013231935910881,43563,-1211,-6478,-2795,1.13640606403351 +31081,-0.02789174951613,0.053540859371424,0.016303325071931,43563,-1238,-6015,-2806,1.13499510288239 +31083,-0.006744367070496,0.035917699337006,0.016911573708057,43563,-1834,-5740,-2743,1.12919700145721 +31085,0.01502993144095,0.017774228006601,0.015794822946191,43563,-2227,-5269,-2807,1.12459540367126 +31087,0.034281507134438,-0.005126252304763,0.01743184402585,43563,-11734,30583,-2725,1.11978983879089 +31089,0.051477245986462,-0.023759899660945,0.019584234803915,43563,-4009,1284,-2778,1.11438369750977 +31091,0.070176117122173,-0.042765326797962,0.020748129114509,43563,-4505,1535,-2674,1.11461555957794 +31093,0.086875826120377,-0.068318270146847,0.01893856190145,43563,-4518,2450,-2779,1.12049508094788 +31095,0.097768813371658,-0.086816221475601,0.017119096592069,43563,-4432,2263,-2705,1.12778067588806 +31097,0.110802136361599,-0.101569533348084,0.016993004828692,43563,-4647,2205,-2789,1.1346298456192 +31099,0.125181436538696,-0.109034895896912,0.013389436528087,43563,-5179,1895,-2741,1.13457071781158 +31101,0.130502879619598,-0.095051325857639,0.011483340524137,43563,-4438,116,-2824,1.13087558746338 +31103,0.129189237952232,-0.075246922671795,0.014788773842156,43563,-4184,-554,-2729,1.12472093105316 +31105,0.133627265691757,-0.06463423371315,0.015607153065503,43563,-4483,-31,-2793,1.11758959293365 +31107,0.143988862633705,-0.062966659665108,0.01360559463501,43563,-5330,583,-2741,1.1145396232605 +31109,0.150414288043976,-0.056410994380713,0.009930917993188,43563,-4937,181,-2829,1.11151731014252 +31111,0.14857816696167,-0.044007744640112,0.007089389953762,43563,-4605,-459,-2819,1.11196255683899 +31113,0.138860329985619,-0.023717844858766,0.007644830271602,43563,-3688,-1239,-2843,1.11415791511536 +31115,0.129368096590042,0.00918451230973,0.009311656467617,43563,-3815,-2774,-2805,1.11455273628235 +31117,0.121232770383358,0.039247892796993,0.011139775626361,43563,-3614,-2837,-2818,1.11939060688019 +31119,0.113541789352894,0.055136546492577,0.010396724566817,43563,-3744,-2303,-2804,1.12383043766022 +31121,0.104079745709896,0.068786226212978,0.008025711402297,43563,-3331,-2100,-2838,1.12694072723389 +31123,0.093246906995773,0.098674573004246,0.009149654768407,43563,-3236,-4031,-2832,1.13015174865723 +31125,0.080502167344093,0.129509717226028,0.011009299196303,43563,-21556,31102,-2817,1.12785267829895 +31127,0.06500655412674,0.14740389585495,0.010032116435468,43563,-5659,1958,-2830,1.12218153476715 +31129,0.048381596803665,0.154870718717575,0.007352120243013,43563,-5285,3013,-2842,1.11616969108582 +31131,0.032768175005913,0.170681029558182,0.00466811703518,43563,-5192,1723,-2897,1.10961210727692 +31133,0.012182862497866,0.203460454940796,0.001900890725665,43563,-4535,493,-2881,1.10619258880615 +31135,-0.01341619156301,0.245794534683228,0.002539243781939,43563,-3760,-1427,-2946,1.10398769378662 +31137,-0.039241503924131,0.289378494024277,0.005007937550545,43563,-3452,-1559,-2861,1.10178303718567 +31139,-0.064265608787537,0.322460263967514,0.005867214407772,43563,-2988,-2075,-2931,1.1033581495285 +31141,-0.091919705271721,0.352172195911408,0.00126730685588,43563,-2571,-1550,-2889,1.10716426372528 +31143,-0.123278692364693,0.396398663520813,-0.002182939322665,43563,-1558,-4171,-3050,1.10949730873108 +31145,-0.154726296663284,0.44408118724823,-0.005730572622269,43563,-1374,-4274,-2941,1.11080253124237 +31147,-0.183150425553322,0.487386763095856,-0.007537674624473,43563,-750,-5715,-3142,1.11181437969208 +31149,-0.219066008925438,0.532419621944428,-0.008034269325435,43563,-78,-5512,-2963,1.11489641666412 +31151,-0.259080737829208,0.577235579490662,-0.005184749606997,43563,1385,-7451,-3141,1.11716938018799 +31153,-0.296097934246063,0.627409279346466,0.000451649335446,43563,1195,-7444,-2911,1.11132109165192 +31155,-0.323457092046738,0.663224518299103,0.001475184457377,43563,1627,-8422,-3084,1.10346174240112 +31157,-0.343294233083725,0.688505589962006,-0.002734370995313,43563,761,-6781,-2938,1.0936963558197 +31159,-0.36476793885231,0.716693341732025,-0.005391384940594,43563,2005,-8999,-3177,1.08216118812561 +31161,-0.391896635293961,0.750511109828949,-0.005991346668452,43563,2120,-8551,-2968,1.07988405227661 +31163,-0.421902239322662,0.782611966133118,-0.004046802874655,43563,3694,24708,-3175,1.08495628833771 +31165,-0.446415364742279,0.803724348545074,-0.002708696760237,43563,2882,-2738,-2952,1.09276151657105 +31167,-0.459693282842636,0.8112832903862,-0.006054105702788,43563,3288,-3646,-3205,1.09999990463257 +31169,-0.471679240465164,0.825603187084198,-0.008124686777592,43563,2533,-2823,-2996,1.10500454902649 +31171,-0.484462022781372,0.8484006524086,-0.007044953294098,43563,3851,-5608,-3225,1.10745131969452 +31173,-0.497819751501083,0.871572911739349,-0.006324044428766,43563,3207,-4395,-2991,1.11152684688568 +31175,-0.508549213409424,0.896571338176727,-0.008150541223586,43563,4299,-6836,-3244,1.109454870224 +31177,-0.514238715171814,0.918056130409241,-0.009975480847061,43563,3105,-5244,-3024,1.10767209529877 +31179,-0.518224895000458,0.940271377563477,-0.010012989863753,43563,4173,-7652,-3266,1.10680735111237 +31181,-0.521513164043427,0.969922244548798,-0.010672421194613,43563,3253,-6898,-3036,1.10727167129517 +31183,-0.520248055458069,0.995718955993652,-0.012445344589651,43563,4038,-9143,-3298,1.10783588886261 +31185,-0.514348566532135,1.01223230361938,-0.014437047764659,43563,2710,-6916,-3070,1.1052953004837 +31187,-0.505877315998077,1.02430701255798,-0.014462080784142,43563,3503,-8983,-3323,1.10856878757477 +31189,-0.49421563744545,1.02923238277435,-0.014980494044721,43563,2220,-6699,-3082,1.11226058006287 +31191,-0.48489448428154,1.03347742557526,-0.013688518665731,43563,3314,-8937,-3315,1.1142646074295 +31193,-0.472157537937164,1.03877604007721,-0.008240377530456,43563,2031,-7238,-3043,1.11775708198547 +31195,-0.458500921726227,1.04760384559631,-0.005742646288127,43563,2785,-9871,-3224,1.11838269233704 +31197,-0.444192111492157,1.05280756950378,-0.006346101872623,43563,1714,-7817,-3036,1.11727368831635 +31213,-0.275111645460129,0.999150454998016,-0.008445254527032,43563,-666,-7108,-3072,1.11161530017853 +31215,-0.249662801623344,0.983305037021637,-0.013974070549011,43563,-724,-8987,-3290,1.11281704902649 +31217,-0.226238548755646,0.969568371772766,-0.018448857590556,43563,-1356,-7183,-3146,1.12038946151733 +31219,-0.206253975629806,0.950136184692383,-0.016527857631445,43563,-953,-8549,-3316,1.13040995597839 +31221,-0.187021538615227,0.930374979972839,-0.01195006351918,43563,-1538,-6548,-3107,1.13837039470673 +31223,-0.165356338024139,0.906191885471344,-0.007827350869775,43563,-1674,-7833,-3209,1.14315032958984 +31225,-0.145562902092934,0.876858294010162,-0.006902778055519,43563,-2113,-5435,-3076,1.13665568828583 +31227,-0.122573830187321,0.845474123954773,-0.010176364332438,43563,-2414,-6654,-3232,1.12476527690887 +31229,-0.0942607447505,0.811585247516632,-0.012065645307303,43563,-3419,-4486,-3116,1.11144554615021 +31231,-0.075288631021977,0.78390097618103,-0.011785295791924,43563,-2864,-6215,-3248,1.10208261013031 +31233,-0.066991247236729,0.754880011081696,-0.011936799623072,43563,-2357,-4309,-3119,1.0997622013092 +31235,-0.058252941817045,0.719836056232452,-0.011077100411058,43563,-2392,-4922,-3236,1.09857070446014 +31237,-0.041296567767859,0.683377802371979,-0.009693251922727,43563,-3334,-3011,-3107,1.10068678855896 +31239,-0.021724056452513,0.646975994110107,-0.012663918547332,43563,-3754,-3887,-3252,1.10598063468933 +31241,-0.007470637559891,0.620575368404388,-0.015482145361602,43563,-3630,-3060,-3151,1.11283648014069 +31243,0.003293981542811,0.59379118680954,-0.013025027699769,43563,-3533,-3930,-3257,1.12045812606812 +31245,0.00750266527757,0.570868611335754,-0.009984822012484,43563,-3140,-2803,-3117,1.12340247631073 +31247,0.007972474209964,0.549949645996094,-0.009895426221192,43563,-2883,-3833,-3220,1.12186932563782 +31249,0.006661317776889,0.530828714370728,-0.008021323010325,43563,-2748,-2689,-3106,1.12072336673737 +31251,0.009506981819868,0.514761686325073,-0.008966936729848,43563,-3090,-3784,-3210,1.11625599861145 +31253,0.016961202025414,0.498008996248245,-0.013752902857959,43563,-3540,-2560,-3149,1.11307406425476 +31255,0.025734951719642,0.475014537572861,-0.018857479095459,43563,-3803,-2799,-3325,1.11073911190033 +31257,0.029755275696516,0.458050847053528,-0.019601251929998,43563,-3502,-2126,-3193,1.11086213588715 +31259,0.037086311727762,0.438560158014298,-0.019127435982227,43563,-3917,-2607,-3328,1.11165010929108 +31261,0.045384999364615,0.419421702623367,-0.021563351154327,43563,-4063,-1556,-3211,1.10841107368469 +31263,0.052342686802149,0.395994961261749,-0.022070368751884,43563,-4176,-1773,-3363,1.10755717754364 +31265,0.049383897334337,0.382955014705658,-0.019360048696399,43563,-3353,-1593,-3200,1.10334718227386 +31267,0.039653219282627,0.379380881786346,-0.015207746997476,43563,-2808,-3050,-3285,1.10285127162933 +31269,0.032140824943781,0.37541139125824,-0.01656593196094,43563,-2811,-2252,-3185,1.10449981689453 +31271,0.024959072470665,0.374349802732468,-0.019125794991851,43563,-2770,-3259,-3337,1.10668408870697 +31273,0.01655562967062,0.372605681419373,-0.020102564245463,43563,-2548,-2487,-3213,1.11043930053711 +31275,0.003391962964088,0.37441274523735,-0.02468122728169,43563,-2002,-3575,-3408,1.10782968997955 +31277,-0.013348212465644,0.377528220415115,-0.029739271849394,43563,-1534,-3021,-3284,1.10330760478973 +31279,-0.030905799940229,0.377101868391037,-0.031853269785643,43563,-1135,-3570,-3498,1.09986245632172 +31281,-0.047550138086081,0.377799153327942,-0.03170507401228,43563,-1047,-2969,-3304,1.09498524665833 +31283,-0.060556221753359,0.380944907665253,-0.034591775387526,43563,-977,-4002,-3535,1.09277868270874 +31285,-0.066652581095696,0.384317398071289,-0.039297204464674,43563,-1512,-3373,-3363,1.08948814868927 +31287,-0.071049734950066,0.387196660041809,-0.04023827239871,43563,-1410,-4205,-3608,1.08922302722931 +31289,-0.07221457362175,0.380886763334274,-0.04115566238761,43563,-1766,-2754,-3383,1.08833909034729 +31291,-0.074844680726528,0.38137412071228,-0.043470695614815,43563,-1451,-4067,-3653,1.08477091789246 +31293,-0.081292435526848,0.389466911554337,-0.043677002191544,43563,-1235,-4032,-3409,1.08365392684937 +31295,-0.090550631284714,0.397236764431,-0.043581262230873,43563,-691,-4974,-3664,1.08734679222107 +31297,-0.101315625011921,0.406560689210892,-0.043340034782887,43563,-607,-4497,-3415,1.09224140644073 +31299,-0.114189423620701,0.411506742238998,-0.040970083326101,43563,-9,-5139,-3642,1.09761381149292 +31301,-0.126372992992401,0.415774166584015,-0.042131084948778,43563,-103,-4406,-3414,1.1008814573288 +31303,-0.141092538833618,0.423569530248642,-0.042944874614477,43563,613,-5681,-3673,1.09949910640717 +31305,-0.15689180791378,0.426459461450577,-0.039322923868895,43563,649,-4607,-3403,1.09572541713715 +31307,-0.170144364237785,0.432848006486893,-0.036062777042389,43563,1039,-5871,-3599,1.09327971935272 +31309,-0.175873130559921,0.436112195253372,-0.037443161010742,43563,269,-4923,-3397,1.09145045280457 +31311,-0.179794877767563,0.44410514831543,-0.04203625023365,43563,592,-6322,-3674,1.08802711963654 +31313,-0.184488564729691,0.450941622257233,-0.044012997299433,43563,392,-5549,-3450,1.08803987503052 +31315,-0.187464669346809,0.452392935752869,-0.046129740774632,43259,717,-6148,-3728,1.08675360679626 +31317,-0.188514351844788,0.456402599811554,-0.049537308514118,43259,265,-5587,-3496,1.0875301361084 +31319,-0.190875992178917,0.459673494100571,-0.046925973147154,43259,809,-6561,-3745,1.09062397480011 +31321,-0.193893775343895,0.458019405603409,-0.043080147355795,43259,562,-5372,-3460,1.09095776081085 +31323,-0.200053453445435,0.455425173044205,-0.046367276459932,43259,1317,-6241,-3746,1.09088671207428 +31325,-0.201193377375603,0.456265956163406,-0.048960506916046,43259,617,-5693,-3509,1.09178030490875 +31327,-0.195922046899796,0.45797598361969,-0.047731004655361,43259,516,-6760,-3768,1.09430050849915 +31329,-0.189535453915596,0.453166127204895,-0.048201709985733,43259,-4,-5413,-3513,1.10001564025879 +31331,-0.180550590157509,0.438650369644165,-0.04824884980917,43259,75,-5443,-3779,1.10393500328064 +31333,-0.17014217376709,0.435039907693863,-0.049589239060879,43259,-495,-5401,-3531,1.10802388191223 +31335,-0.158163040876389,0.441124081611633,-0.051577419042587,43259,-433,-7111,-3826,1.11245965957642 +31337,-0.147467568516731,0.45726490020752,-0.051208887249231,43259,-774,-7297,-3551,1.10945534706116 +31339,-0.1322021484375,0.456443101167679,-0.051269471645355,43259,-1033,-7030,-3830,1.1042640209198 +31341,-0.120396219193935,0.44783017039299,-0.052386574447155,43259,-1188,-5559,-3568,1.09466946125031 +31343,-0.112940788269043,0.445441126823425,-0.054356213659048,43259,-746,-6911,-3873,1.08154809474945 +31345,-0.101927153766155,0.434321016073227,-0.05534853041172,43259,-1353,-5353,-3598,1.07748556137085 +31347,-0.088676549494267,0.421626955270767,-0.04852607101202,43259,-1516,-5949,-3811,1.08022081851959 +31349,-0.069780752062798,0.411617070436478,-0.043287757784128,43259,-2345,-5264,-3523,1.08809995651245 +31351,-0.045700617134571,0.402506291866303,-0.045674480497837,43259,-2964,-6049,-3785,1.09481406211853 +31353,-0.022702548652887,0.400232315063477,-0.048144318163395,40417,-3301,-5806,-3564,1.10130274295807 +31355,-0.001150866388343,0.38609191775322,-0.047620914876461,40417,-3499,-5574,-3815,1.10510683059692 +31357,0.008193624205887,0.373781025409698,-0.0457808598876,40417,-2772,-4852,-3556,1.10699355602264 +31359,0.010867554694414,0.36041983962059,-0.044727005064488,40417,-2351,-5354,-3788,1.10653102397919 +31361,0.007647653110325,0.359506845474243,-0.043246358633041,40417,-1875,-5599,-3547,1.10226213932037 +31363,0.008893704041839,0.355142116546631,-0.041608620435,40417,-2235,-6046,-3758,1.09700357913971 +31365,0.01375437527895,0.343965828418732,-0.042216755449772,40417,-2553,-4773,-3547,1.09152615070343 +31367,0.025047326460481,0.329016327857971,-0.045607514679432,40417,-3237,-4987,-3811,1.08610463142395 +31369,0.041122402995825,0.317130595445633,-0.05121910199523,40417,-3770,-4459,-3616,1.08293950557709 +31371,0.055857215076685,0.31284961104393,-0.053652130067349,40417,-4010,-5603,-3913,1.0798397064209 +31373,0.060983806848526,0.312989264726639,-0.051643077284098,40417,-3305,-5376,-3628,1.07937705516815 +31375,0.063329473137856,0.30295130610466,-0.049037985503674,40417,-3273,-5150,-3868,1.07685017585754 +31377,0.058499399572611,0.288984447717667,-0.04423650354147,40417,-2592,-4133,-3586,1.07482576370239 +31379,0.04970270767808,0.274241268634796,-0.039666466414929,40417,-2284,-4458,-3765,1.07896792888641 +31381,0.037285607308149,0.271663665771484,-0.041128356009722,40417,-1774,-4801,-3571,1.08395659923553 +31383,0.026946488767862,0.268842071294785,-0.044582094997168,40417,-1829,-5313,-3830,1.09328484535217 +31385,0.023286299780011,0.251338601112366,-0.044355846941471,40417,-2221,-3537,-3601,1.10325729846954 +31387,0.021184226498008,0.232730180025101,-0.044177614152432,40417,-2345,-3678,-3831,1.10085308551788 +31389,0.024837600067258,0.209857076406479,-0.043342407792807,39344,-2784,-2638,-3601,1.088862657547 +31391,0.022585973143578,0.201229393482208,-0.042247567325831,39344,-2375,-3952,-3814,1.07782077789307 +31393,0.016505101695657,0.195246085524559,-0.042169816792011,39344,-1985,-3704,-3600,1.07168292999268 +31395,0.00685639725998,0.188864439725876,-0.043244034051895,39344,-1612,-3979,-3832,1.06619596481323 +31397,-0.00046728271991,0.184057623147965,-0.044147174805403,39344,-1665,-3689,-3621,1.05922758579254 +31399,-0.004194713197649,0.179749071598053,-0.045126132667065,39344,-1873,-4048,-3860,1.05077159404755 +31401,-0.011759029701352,0.177422538399696,-0.048424020409584,39344,-1494,-3831,-3658,1.04062867164612 +31403,-0.017058713361621,0.162539973855019,-0.048970699310303,39344,-1557,-3072,-3913,1.03574800491333 +31405,-0.020264785736799,0.1522436439991,-0.048222698271275,39344,-1687,-2952,-3665,1.03539061546326 +31407,-0.028687715530396,0.147142291069031,-0.047001730650663,39344,-1136,-3569,-3897,1.03767871856689 +31409,-0.036939024925232,0.136715948581696,-0.046555988490582,39344,-1081,-2765,-3661,1.039555311203 +31411,-0.040209367871285,0.127155631780624,-0.044960297644138,39344,-1305,-2959,-3880,1.04343163967133 +31413,-0.04737101495266,0.122805893421173,-0.041068136692047,39344,-999,-3037,-3631,1.04866075515747 +31415,-0.059732720255852,0.121009700000286,-0.038223005831242,39344,-322,-3447,-3807,1.05120265483856 +31417,-0.070828072726727,0.121093787252903,-0.038276832550764,39344,-361,-3363,-3618,1.0513014793396 +31419,-0.071932129561901,0.114770904183388,-0.042230855673552,39344,-906,-3048,-3861,1.04567849636078 +31421,-0.074236012995243,0.113124124705791,-0.049119554460049,39344,-915,-3154,-3700,1.04040277004242 +31423,-0.080156587064266,0.102697394788265,-0.052883516997099,39344,-398,-2582,-3994,1.03738367557526 +31425,-0.090712681412697,0.102146603167057,-0.054561566561461,39344,-57,-3099,-3746,1.03417181968689 +31441,-0.110512539744377,0.118480443954468,-0.047286681830883,37807,-419,-3734,-3728,1.00788986682892 +31443,-0.106013715267181,0.115850739181042,-0.048352394253016,37807,-505,-3481,-3981,1.00315678119659 +31445,-0.103708922863007,0.120390377938747,-0.0470952950418,37807,-574,-3859,-3735,0.996475398540497 +31447,-0.101595342159271,0.121170371770859,-0.043968267738819,37807,-373,-3841,-3936,0.996876239776611 +31449,-0.101048707962036,0.131507903337479,-0.040431380271912,37807,-444,-4467,-3696,0.9945188164711 +31451,-0.094192676246166,0.128279596567154,-0.040756419301033,37807,-793,-3705,-3905,0.992511689662933 +31453,-0.095429696142674,0.136068418622017,-0.044457536190748,37807,-358,-4387,-3731,0.991268217563629 +31455,-0.09515967965126,0.147709563374519,-0.041567150503397,37807,-262,-5137,-3922,0.995361864566803 +31457,-0.093511454761028,0.1454057097435,-0.040619861334562,37807,-552,-3846,-3711,1.00244665145874 +31459,-0.085723474621773,0.130738392472267,-0.042617831379175,37807,-919,-3024,-3940,1.00780951976776 +31461,-0.076611161231995,0.121170572936535,-0.042552143335343,37807,-1294,-3019,-3731,1.01227915287018 +31463,-0.07523113489151,0.134764015674591,-0.042631629854441,37807,-593,-5150,-3948,1.00895667076111 +31465,-0.076801538467407,0.144603788852692,-0.041329260915518,37306,-494,-4788,-3730,0.99985259771347 +31467,-0.075471363961697,0.144808903336525,-0.041091948747635,37306,-553,-4389,-3937,0.987578392028809 +31469,-0.066703379154205,0.134275153279305,-0.039915695786476,37306,-1348,-3226,-3727,0.981334745883942 +31471,-0.057049613445997,0.128374457359314,-0.037667170166969,37306,-1423,-3720,-3902,0.976439952850342 +31473,-0.05857103317976,0.135695219039917,-0.037564743310213,37306,-704,-4563,-3717,0.972341954708099 +31475,-0.059242513030768,0.132862895727158,-0.038632612675428,37306,-614,-4058,-3920,0.966928720474243 +31477,-0.058355741202831,0.136182516813278,-0.036330714821816,37306,-853,-4325,-3715,0.963730871677399 +31479,-0.055149763822556,0.133633881807327,-0.036876056343317,37306,-926,-4140,-3906,0.966566741466522 +31481,-0.054158445447683,0.140975624322891,-0.040911760181189,37306,-895,-4725,-3753,0.975606918334961 +31483,-0.038915332406759,0.132245033979416,-0.040522586554289,37306,-2043,-3719,-3954,0.978030204772949 +31485,-0.03128132596612,0.129744917154312,-0.03796124830842,37306,-1683,-3902,-3739,0.980833470821381 +31487,-0.034005660563707,0.142767488956451,-0.035480733960867,37306,-836,-5491,-3900,0.982306838035584 +31489,-0.034618429839611,0.15261135995388,-0.034543834626675,37306,-1032,-5162,-3721,0.982750773429871 +31491,-0.034008160233498,0.152291685342789,-0.034470655024052,37306,-1071,-4741,-3894,0.98034018278122 +31493,-0.028275078162551,0.140874817967415,-0.032913826406002,37306,-1568,-3523,-3716,0.975088655948639 +31495,-0.023925175890327,0.140735656023025,-0.035101298242807,37306,-1490,-4618,-3907,0.968891680240631 +31497,-0.015206578187645,0.129025474190712,-0.035745456814766,37306,-1963,-3380,-3741,0.960089027881622 +31499,-0.017217867076397,0.128290072083473,-0.033065013587475,37306,-1121,-4415,-3889,0.954630255699158 +31501,-0.022739756852388,0.119196601212025,-0.029771041125059,37306,-828,-3469,-3705,0.952667772769928 +31503,-0.02655322663486,0.113307826220989,-0.030243156477809,37306,-831,-3840,-3861,0.947600483894348 +31505,-0.028583368286491,0.118453241884708,-0.030933056026697,37306,-983,-4514,-3718,0.945791780948639 +31507,-0.022698540240526,0.118197880685329,-0.029253559187055,37306,-1589,-4365,-3854,0.944519281387329 +31509,-0.019700163975358,0.123545177280903,-0.029047418385744,37306,-1464,-4640,-3710,0.943327367305756 +31511,-0.016424246132374,0.111001037061214,-0.028339620679617,37306,-1494,-3405,-3848,0.942343294620514 +31513,-0.0165149345994,0.113029435276985,-0.027577374130488,37306,-1283,-4288,-3705,0.944290518760681 +31515,-0.005230464041233,0.102007307112217,-0.026079177856445,37306,-2246,-3399,-3826,0.946418225765228 +31517,-0.004582126159221,0.104808390140533,-0.02728776820004,37306,-1506,-4257,-3707,0.950581192970276 +31519,-0.008472500368953,0.098274022340775,-0.026117969304323,37306,-1092,-3684,-3831,0.955016672611237 +31521,-0.017195908352733,0.08942086994648,-0.022459207102656,37306,-650,-3231,-3678,0.951232850551605 +31523,-0.019766181707382,0.083454757928848,-0.021927356719971,37306,-1005,-3509,-3785,0.951720714569092 +31525,-0.009323571808636,0.071483537554741,-0.022820305079222,37306,-2128,-2772,-3684,0.9463050365448 +31527,0.000385590130463,0.066048130393028,-0.025745950639248,37306,-2225,-3293,-3833,0.935337722301483 +31529,0.004031552933156,0.062996357679367,-0.025996871292591,37306,-1837,-3305,-3710,0.934934735298157 +31531,6.47535198368132E-05,0.071945108473301,-0.024964708834887,37306,-1243,-4436,-3828,0.935049414634705 +31533,0.001516244956292,0.061487626284361,-0.022934246808291,37306,-1648,-2772,-3693,0.937896251678467 +31535,0.000717874092516,0.055928688496351,-0.02286727540195,37306,-1475,-3148,-3808,0.941461622714996 +31537,0.001708016963676,0.049450188875198,-0.023230915889144,37306,-1620,-2895,-3699,0.943763256072998 +31539,-0.002673431998119,0.045237813144922,-0.023930128663778,37306,-1151,-3068,-3824,0.941338002681732 +31541,-0.013543943874538,0.046786118298769,-0.021023955196142,36985,-550,-3436,-3688,0.942216157913208 +31543,-0.021702881902456,0.048986487090588,-0.018950145691633,36985,-566,-3592,-3769,0.936040103435516 +31545,-0.02504312992096,0.053137104958296,-0.019071221351624,36985,-914,-3720,-3678,0.931629717350006 +31547,-0.024020668119192,0.047923181205988,-0.017329677939415,36985,-1191,-3059,-3753,0.930674016475678 +31549,-0.025380846112967,0.046029444783926,-0.015010811388493,36985,-1043,-3192,-3653,0.931195497512817 +31551,-0.016765080392361,0.033306822180748,-0.015572275035083,36985,-1857,-2296,-3734,0.932731032371521 +31553,-0.015650991350412,0.046395607292652,-0.018527988344431,36985,-1356,-4273,-3679,0.931794464588165 +31555,-0.015971347689629,0.048223808407784,-0.017940394580364,36985,-1225,-3591,-3765,0.929017663002014 +31557,-0.016876677051187,0.041585676372051,-0.017118638381362,36985,-1190,-2801,-3673,0.923431038856506 +31559,-0.015259957872331,0.027798410505056,-0.017931492999196,36985,-1362,-2140,-3768,0.925274729728699 +31561,-0.016426766291261,0.031656384468079,-0.018086649477482,36985,-1173,-3410,-3682,0.923777043819428 +31563,-0.021400917321444,0.044008735567331,-0.015796119347215,36985,-783,-4275,-3746,0.926805436611176 +31565,-0.021739654242992,0.041355066001415,-0.013592555187643,36985,-1148,-3089,-3654,0.930201649665832 +31567,-0.018671775236726,0.042877722531557,-0.011420404538512,36985,-1386,-3492,-3697,0.931527554988861 +31569,-0.015661250799894,0.037781000137329,-0.009281144477427,36985,-1467,-2869,-3626,0.932333707809448 +31571,-0.017351221293211,0.047066695988178,-0.00699544698,36985,-1051,-4120,-3646,0.932393789291382 +31573,-0.014587401412428,0.04644088819623,-0.00284486496821,36985,-1456,-3322,-3583,0.930087864398956 +31591,-0.01206888910383,0.043396588414908,0.009446199983358,36985,-1505,-3035,-3450,0.933046281337738 +31593,-0.012488429434598,0.055436290800572,0.013086432591081,36985,-1238,-4397,-3470,0.932467401027679 +31595,-0.00772769190371,0.054830480366945,0.015810405835509,36985,-1658,-3584,-3373,0.932079255580902 +31597,-0.009142184630036,0.064515084028244,0.014978675171733,36985,-1212,-4371,-3455,0.933110117912292 +31599,-0.003672687103972,0.063842654228211,0.013409674167633,36985,-1771,-3740,-3399,0.931652426719666 +31601,0.002576714148745,0.063968755304813,0.011790322139859,36985,-1929,-3695,-3474,0.930903196334839 +31603,0.002989102853462,0.067660100758076,0.014285940676928,36985,-1510,-4130,-3387,0.936139464378357 +31605,0.000775609514676,0.070047549903393,0.014095112681389,36985,-1297,-3962,-3456,0.940773189067841 +31607,-7.6640943007078E-05,0.080571658909321,0.009827594272792,36985,-1357,-4840,-3438,0.943041324615478 +31609,0.004080893471837,0.080356299877167,0.009934313595295,36985,-1799,-3946,-3483,0.938301086425781 +31611,0.001953826984391,0.090053535997868,0.013946086168289,36985,-1308,-4964,-3387,0.929797768592834 +31613,0.002014411380515,0.083718612790108,0.017165223136544,36985,-1476,-3583,-3431,0.929334700107574 +31615,-0.003174426266924,0.09397554397583,0.018954688683152,36985,-1022,-5106,-3325,0.93231338262558 +31617,0.00130337907467,0.089653335511685,0.021495051681995,36985,-1783,-3844,-3398,0.935552179813385 +31619,0.003327134763822,0.097549423575401,0.021483924239874,36985,-1648,-5035,-3292,0.931138217449188 +31621,0.007707089185715,0.092771269381046,0.022871874272823,36985,-1872,-3891,-3385,0.926480889320374 +31623,0.001999854343012,0.088766522705555,0.020310400053859,36985,-1069,-4058,-3302,0.924665153026581 +31625,-0.001397288171574,0.092036254703999,0.01513375621289,36985,-1186,-4485,-3435,0.92290997505188 +31627,0.000940838828683,0.089564763009548,0.014999181032181,36985,-1634,-4203,-3362,0.917035520076752 +31629,-0.000154399604071,0.100437350571156,0.01669885031879,36985,-1371,-5179,-3422,0.914501249790192 +31631,-0.0017796108732,0.094763517379761,0.019934384152293,36985,-1315,-4086,-3301,0.914018750190735 +31633,-0.003982660360634,0.09300247579813,0.023803448304534,36985,-1239,-4198,-3370,0.915386438369751 +31635,-0.000275861239061,0.081883005797863,0.026872754096985,36985,-1721,-3517,-3215,0.912262439727783 +31637,-0.004372930619866,0.086902633309364,0.024594793096185,36985,-1100,-4621,-3360,0.914389491081238 +31639,-0.0015156455338,0.085852406919003,0.020805461332202,36985,-1646,-4338,-3282,0.917019426822662 +31641,-0.001679315115325,0.090033173561096,0.017242193222046,36985,-1423,-4635,-3407,0.921190679073334 +31643,0.002654205076396,0.080772295594215,0.017632301896811,36985,-1824,-3700,-3317,0.92233681678772 +31645,0.000910039641894,0.079692207276821,0.021448915824294,36985,-1352,-4138,-3375,0.913673460483551 +31647,-0.008484785445035,0.08337264508009,0.024390254169703,36985,-655,-4697,-3234,0.916137337684631 +31649,-0.014887068420649,0.073779322206974,0.022519489750266,36985,-790,-3472,-3363,0.916139423847198 +31651,-0.018503854051232,0.071940936148167,0.020417990162969,36985,-890,-4139,-3277,0.922145128250122 +31653,-0.012281451374292,0.065982960164547,0.021599004045129,36985,-1723,-3643,-3366,0.927923917770386 +31655,-0.011262715794146,0.068666681647301,0.023817636072636,36985,-1320,-4424,-3233,0.927348375320435 +31657,-0.015391275286675,0.05457716435194,0.023976087570191,36985,-930,-2917,-3346,0.92638236284256 +31659,-0.0246443413198,0.05707598477602,0.023231510072947,36985,-354,-4236,-3236,0.927361249923706 +31661,-0.016974991187453,0.045657522976399,0.021321015432477,36985,-1739,-2995,-3360,0.924928784370422 +31663,-0.012978743761778,0.047835569828749,0.018214583396912,36985,-1486,-4073,-3292,0.92040354013443 +31665,-0.01099388115108,0.047863334417343,0.01986700296402,36985,-1410,-3857,-3367,0.91747123003006 +31667,-0.012074595317245,0.044795870780945,0.023181326687336,36985,-1147,-3665,-3229,0.911010086536408 +31669,-0.015779798850417,0.037964534014464,0.025427581742406,36985,-929,-3233,-3325,0.913872003555298 +31671,-0.01356082316488,0.032034412026405,0.023162858560681,36985,-1353,-3265,-3226,0.914154887199402 +31673,-0.013953682035208,0.040306124836207,0.022557524964213,36985,-1187,-4354,-3341,0.916063785552978 +31675,-0.011958084069193,0.038029529154301,0.022886557504535,36985,-1356,-3631,-3225,0.917542040348053 +31677,-0.00941292848438,0.039583716541529,0.020802088081837,36985,-1457,-3871,-3349,0.918883562088013 +31679,-0.00803254917264,0.019936079159379,0.018872791901231,36985,-1369,-2084,-3269,0.917508184909821 +31681,-0.012277572415769,0.025608660653234,0.023959228768945,36985,-926,-3964,-3324,0.91740757226944 +31683,-0.011084766127169,0.019545130431652,0.031333521008492,36985,-1309,-3044,-3118,0.917942762374878 +31685,0.001192406751215,0.024871038272977,0.025006355717778,36985,-2070,-3641,-3188,0.920637965202332 +31687,0.001192406751215,0.024871038272977,0.025006355717778,36985,-2070,-3641,-3188,0.920637965202332 +31689,-0.006533708423376,0.025591650977731,0.023167319595814,36985,10301,24413,-3206,0.924268245697022 +31691,-0.006261825095862,0.010731265880168,0.025430457666516,36985,10056,25719,-3301,0.918874204158783 +31693,-0.00588034838438,0.002954438328743,0.029610592871904,36985,10121,25475,-3125,0.918953716754913 +31695,-0.005835998803377,0.005398692563176,0.031756643205881,36985,10182,24841,-3253,0.916252732276916 +31697,-0.005835998803377,0.005398692563176,0.031756643205881,36985,10182,24841,-3253,0.916252732276916 +31699,0.026927491649985,0.05137288197875,0.034761007875204,36985,8266,22715,-3227,0.911502301692963 +31701,0.046119391918182,0.101060882210731,0.03683703020215,36985,8134,20291,-3029,0.909935116767883 +31703,0.071504794061184,0.145162984728813,0.039083730429411,36985,7456,20363,-3191,0.91107302904129 +31705,0.091576538980007,0.204969704151154,0.044839214533568,36985,7411,18097,-2929,0.916594445705414 +31707,0.091576538980007,0.204969704151154,0.044839214533568,36985,7411,18097,-2929,0.916594445705414 +31709,0.165718913078308,0.354031622409821,0.053712949156761,36985,5000,13931,-2817,0.920555233955383 +31711,0.203556135296822,0.457208961248398,0.057021733373404,36985,4771,11964,-3051,0.928564786911011 +31713,0.245521128177643,0.556621909141541,0.055072400718927,36985,3410,9779,-2796,0.93473744392395 +31715,0.289735317230225,0.652811288833618,0.049930971115828,36985,3074,9683,-3091,0.94268935918808 +31717,0.289735317230225,0.652811288833618,0.049930971115828,36985,3074,9683,-3091,0.94268935918808 +31719,0.385283052921295,0.871977806091309,0.053632322698832,36985,1197,5097,-3057,0.94789719581604 +31721,0.442282557487488,0.987405359745026,0.058563701808453,36985,-967,1496,-2756,0.946683406829834 +31723,0.489110976457596,1.1192409992218,0.060881417244673,36985,-115,191,-2999,0.943389058113098 +31725,0.52848082780838,1.24670016765594,0.061782889068127,36985,-1222,-3803,-2727,0.946743965148926 +31727,0.577408134937286,1.38568902015686,0.062727108597756,36985,-1672,-4442,-2977,0.95068484544754 +31729,0.628838896751404,1.51666033267975,0.062421761453152,36985,-3867,-8813,-2737,0.95304811000824 +31731,0.678646624088287,1.64518368244171,0.06152767688036,36985,-3373,-7845,-2977,0.952826857566834 +31733,0.726097404956818,1.78147733211517,0.0633904337883,36985,-5360,-13982,-2753,0.95179271697998 +31735,0.777292251586914,1.89047729969025,0.063885092735291,36985,-5118,-10521,-2954,0.950779557228088 +31737,0.821115732192993,2.00906825065613,0.064527034759522,36985,-6891,-17006,-2776,0.950768887996674 +31739,0.857021391391754,2.11642050743103,0.068602442741394,36985,-5443,-14309,-2915,0.952681839466095 +31741,0.889323651790619,2.22637915611267,0.067782312631607,36985,-7468,-20628,-2785,0.9512038230896 +31743,0.917740762233734,2.32358884811401,0.067383602261543,36985,-6088,-17325,-2919,0.952687680721283 +31745,0.940760433673858,2.41167640686035,0.07041385024786,36985,-7959,-22871,-2809,0.947496592998504 +31747,0.961088836193085,2.49994969367981,0.074484452605248,36985,-6467,-20076,-2867,0.937824308872223 +31749,0.973529994487762,2.56878590583801,0.075933441519737,36985,-8074,-24935,-2805,0.930393517017364 +31751,0.979764759540558,2.63773703575134,0.077082425355911,36985,-6079,-21608,-2848,0.923804402351379 +31753,0.984055817127228,2.6970374584198,0.079118348658085,36985,-8021,-27304,-2833,0.925383150577545 +31755,0.992509186267853,2.74551677703857,0.079299792647362,36985,-6783,-22694,-2832,0.92979222536087 +31757,0.995906591415405,2.78528332710266,0.081813909113407,36985,-8516,-28351,-2867,0.936997950077057 +31759,0.995733201503754,2.80855059623718,0.084517270326614,36985,-6582,-22845,-2798,0.93948233127594 +31761,0.988139927387238,2.82653617858887,0.084825657308102,36985,-7967,-28511,-2893,0.939791023731232 +31763,0.983681857585907,2.82662463188171,0.084799505770207,36985,-6471,-22522,-2799,0.939199030399322 +31765,0.977601289749146,2.82681393623352,0.08440662920475,36985,-8269,-28307,-2953,0.936940431594849 +31767,0.965698480606079,2.80611681938171,0.085362553596497,36985,-6047,-21822,-2800,0.936312556266785 +31769,0.94359564781189,2.79523539543152,0.08697309345007,36985,-6935,-28078,-2974,0.939662456512451 +31771,0.928640127182007,2.77297949790955,0.087215639650822,36985,-5652,-22313,-2793,0.944835245609283 +31773,0.911005258560181,2.75261259078979,0.085546009242535,36985,-7077,-27774,-3037,0.947972238063812 +31775,0.897117853164673,2.70346355438232,0.086558394134045,36985,-5620,-20455,-2805,0.947045803070068 +31777,0.874937653541565,2.64935040473938,0.087439261376858,36985,-6504,-24716,-3042,0.94025444984436 +31779,0.850444674491882,2.58720946311951,0.084638133645058,36985,-4520,-18882,-2826,0.942692637443542 +31781,0.82452118396759,2.52176570892334,0.080971598625183,36985,-5741,-22825,-3136,0.945023477077484 +31783,0.79810231924057,2.45221209526062,0.083044618368149,36985,-3941,-17387,-2847,0.952226042747498 +31785,0.77151757478714,2.355952501297,0.084410920739174,36985,-5126,-18861,-3093,0.953000903129577 +31787,0.739900469779968,2.26857256889343,0.084110662341118,36985,-3021,-14380,-2848,0.956086277961731 +31789,0.707180261611939,2.17418122291565,0.080715008080006,36985,-3905,-16895,-3118,0.954217731952667 +31791,0.670481503009796,2.0892436504364,0.073027797043324,36985,-1919,-12807,-2932,0.960085034370422 +31793,0.634096562862396,1.98098015785217,0.068155221641064,36985,-2704,-13531,-3243,0.968285501003265 +31795,0.605175733566284,1.88045454025269,0.062989793717861,36985,-1767,-9434,-3010,0.961320757865906 +31797,0.579394102096558,1.77229809761047,0.06631500273943,36985,-2787,-10836,-3226,0.953666508197784 +31799,0.542965948581696,1.67396759986877,0.068596012890339,36985,-540,-7277,-2979,0.94311398267746 +31801,0.52062463760376,1.55435180664063,0.067013420164585,36985,-2266,-7077,-3168,0.937373042106628 +31803,0.488219261169434,1.44796395301819,0.066652067005634,37324,-219,-4010,-2999,0.935438096523285 +31805,0.459257990121841,1.33518087863922,0.070584893226624,37324,-962,-4516,-3072,0.931252121925354 +31807,0.424667626619339,1.22606205940247,0.067848369479179,37324,697,-1086,-2994,0.933193862438202 +31809,0.396506607532501,1.11965417861938,0.064254023134708,37324,-132,-1884,-3081,0.936735510826111 +31811,0.366132348775864,1.01326310634613,0.057971529662609,37324,1112,1409,-3063,0.930086731910706 +31813,0.336564689874649,0.909672439098358,0.057981364428997,37324,835,1007,-3087,0.936282753944397 +31815,0.312070786952972,0.81409764289856,0.059677321463823,37324,1371,3225,-3052,0.936609625816345 +31817,0.292716264724731,0.715491533279419,0.059873767197132,37324,739,3584,-2995,0.93621152639389 +31819,0.2749243080616,0.624330639839172,0.058713033795357,37324,1349,5452,-3057,0.927024185657501 +31821,0.254230916500092,0.540721118450165,0.053949497640133,37324,1408,5213,-2994,0.922406315803528 +31823,0.242820829153061,0.455155164003372,0.050598870962858,37324,1297,7379,-3110,0.921441316604614 +31825,0.228639334440231,0.385935992002487,0.049501109868288,37324,1313,6627,-2985,0.926072359085083 +31827,0.226283416152,0.307250589132309,0.051303669810295,37324,842,8978,-3100,0.934184908866882 +31829,0.224225267767906,0.251647859811783,0.052039504051209,37324,479,7834,-2898,0.943480908870697 +31831,0.225825533270836,0.189878776669502,0.05218318477273,37324,524,9482,-3088,0.949615955352783 +31833,0.22070623934269,0.15374381840229,0.050054360181093,37324,731,8088,-2871,0.953127682209015 +31835,0.219600766897202,0.106940887868404,0.049645740538836,37324,770,9677,-3097,0.944582045078278 +31837,0.21310131251812,0.082349866628647,0.050791710615158,37324,-25937,-32767,-2823,0.941683650016785 +31839,0.219463527202606,0.068043895065785,0.051605336368084,37324,-4332,-3127,-3075,0.938695192337036 +31841,0.223499044775963,0.051785714924336,0.047270752489567,37324,-4611,-2679,-2854,0.932191908359528 +31843,0.222507312893867,0.043493676930666,0.04594911634922,37324,-3935,-3194,-3105,0.935263633728027 +31845,0.22301772236824,0.03159886226058,0.044306103140116,37324,-4448,-2656,-2878,0.931061387062073 +31847,0.222761824727058,0.021685060113669,0.039312962442637,37324,-4080,-2745,-3143,0.927899599075317 +31849,0.217701509594917,0.007393579930067,0.039609376341105,37324,-4049,-2065,-2915,0.925350844860077 +31851,0.210481941699982,-0.00754982791841,0.043530616909266,37324,-3491,-1934,-3106,0.930022060871124 +31853,0.211059615015984,-0.029401209205389,0.043352201581001,37324,-4424,-885,-2846,0.93608021736145 +31855,0.199507102370262,-0.035091139376164,0.041394032537937,37324,-3106,-2153,-3112,0.937327802181244 +31857,0.188686728477478,-0.049942720681429,0.040846507996321,37324,-3316,-997,-2856,0.937344431877136 +31859,0.175592452287674,-0.055571109056473,0.040661010891199,37324,-2724,-1805,-3108,0.930913805961609 +31861,0.16326105594635,-0.072169326245785,0.042332068085671,37324,-2858,-446,-2819,0.932504713535309 +31863,0.146820366382599,-0.079344570636749,0.041029538959265,37324,-2132,-1283,-3097,0.933585464954376 +31865,0.128193631768227,-0.084265448153019,0.03782057389617,37324,-1888,-1014,-2857,0.941111743450165 +31867,0.115449383854866,-0.09318271279335,0.032641444355249,37324,-1991,-884,-3145,0.941002786159515 +31869,0.103132233023644,-0.093218222260475,0.032505102455616,37324,-1973,-1140,-2907,0.943670034408569 +31871,0.08766283094883,-0.102905228734016,0.0353710539639,37324,-1430,-608,-3119,0.939090609550476 +31873,0.073266737163067,-0.099256128072739,0.034543089568615,37324,-1366,-1229,-2873,0.932263016700745 +31875,0.063184194266796,-0.103768892586231,0.033295191824436,37324,-14826,-32767,-3124,0.92765998840332 +31877,0.044768113642931,-0.098076745867729,0.031073400750756,37324,-2895,-6889,-2912,0.921593070030212 +31879,0.033131949603558,-0.103378660976887,0.030318589881063,37324,-3215,-6350,-3137,0.922949135303497 +31881,0.015674013644457,-0.098031260073185,0.029249222949147,37324,-2517,-6842,-2927,0.928982853889465 +31883,-0.004139186814427,-0.089173525571823,0.031728968024254,37324,-2112,-7541,-3120,0.937840461730957 +31885,-0.016250755637884,-0.091084778308868,0.033285893499851,37324,-2385,-6414,-2872,0.943034529685974 +31901,-0.1645637601614,-0.229852229356766,0.023957453668118,37324,982,-2387,-2894,0.932189047336578 +31903,-0.18460014462471,-0.254753619432449,0.020615575835109,37324,651,-2462,-3158,0.926950335502624 +31905,-0.204926565289497,-0.268878221511841,0.020467642694712,37324,1471,-2325,-2916,0.92763739824295 +31907,-0.215941518545151,-0.294096082448959,0.022193999961019,37324,542,-1765,-3139,0.926361978054047 +31909,-0.223797470331192,-0.304380148649216,0.021000772714615,37324,971,-1904,-2892,0.924825310707092 +31911,-0.230258077383041,-0.326255708932877,0.018487585708499,37324,518,-1416,-3156,0.92431116104126 +31913,-0.24633577466011,-0.32775616645813,0.017378740012646,37324,-24838,-32767,-2919,0.928309857845306 +31915,-0.256086349487305,-0.351412445306778,0.017611242830753,37324,-3305,-6359,-3153,0.929431617259979 +31917,-0.272631287574768,-0.366465538740158,0.015614310279489,37324,-1955,-5869,-2918,0.934280335903168 +31919,-0.278730601072311,-0.387896835803986,0.017966607585549,37324,-3166,-5891,-3142,0.941911935806274 +31921,-0.289822310209274,-0.397313475608826,0.019821062684059,37324,-1979,-5659,-2848,0.94271731376648 +31923,-0.294071763753891,-0.413093626499176,0.015679493546486,37324,-2992,-5815,-3149,0.936505258083344 +31925,-0.298151135444641,-0.437126129865646,0.013856311328709,37324,-2261,-3839,-2898,0.924934506416321 +31927,-0.311186820268631,-0.45598840713501,0.017629977315664,37324,-2026,-4839,-3126,0.915712058544159 +31929,-0.324058890342712,-0.482673406600952,0.01955053023994,37324,-1114,-2759,-2810,0.913965940475464 +31931,-0.340993285179138,-0.5047407746315,0.015082953497768,37324,-1215,-3748,-3133,0.914600789546967 +31933,-0.353491395711899,-0.534702837467194,0.008605318143964,37324,-555,-1525,-2915,0.917690932750702 +31935,-0.369014859199524,-0.545751631259918,0.006904577370733,37324,-797,-3765,-3181,0.920128107070923 +31937,-0.379897594451904,-0.575138568878174,0.011934068985283,37324,-122,-731,-2860,0.923931300640106 +31939,-0.39568218588829,-0.590530395507813,0.013934816233814,37324,-265,-2610,-3123,0.928833603858948 +31941,-0.412806272506714,-0.619828760623932,0.012125592678785,37324,996,219,-2839,0.931577682495117 +31943,-0.426560372114182,-0.65103280544281,0.012427871115506,37324,179,-381,-3123,0.939280986785889 +31945,-0.442564129829407,-0.663435757160187,0.015201191417873,37324,1553,-44,-2784,0.946934282779694 +31947,-0.45250591635704,-0.684463262557983,0.015694778412581,37324,440,-380,-3090,0.949431657791138 +31949,-0.463979423046112,-0.695431232452393,0.013459412381053,37324,1750,626,-2788,0.948791027069092 +31951,-0.472223073244095,-0.716279447078705,0.011032656766474,37324,776,330,-3111,0.944276213645935 +31953,-0.476888239383698,-0.726283848285675,0.01068202778697,37324,1645,1333,-2810,0.940203964710236 +31955,-0.472888857126236,-0.745975375175476,0.012431330047548,37324,89,957,-3091,0.934241235256195 +31957,-0.481522083282471,-0.750389039516449,0.014153009280562,37324,2182,1616,-2761,0.935205280780792 +31959,-0.48566597700119,-0.764389395713806,0.016255529597402,37324,1040,1111,-3054,0.929948985576629 +31961,-0.48824805021286,-0.770874917507172,0.014115534722805,37324,2037,2394,-2756,0.922185480594635 +31963,-0.485179901123047,-0.772570371627808,0.012299742549658,37324,704,655,-3070,0.918416261672974 +31965,-0.483342736959457,-0.76990669965744,0.013427219353616,37324,1823,2025,-2763,0.91506838798523 +31967,-0.479917466640472,-0.772100150585175,0.013077326118946,37324,789,993,-3055,0.921250581741333 +31969,-0.470676213502884,-0.785188019275665,0.013956752605736,37324,1276,3718,-2749,0.925249874591827 +31971,-0.459137588739395,-0.785183548927307,0.014959040097892,37324,92,1343,-3032,0.927712738513946 +31973,-0.447614371776581,-0.775818765163422,0.016846496611834,37324,912,2283,-2716,0.932355165481567 +31975,-0.440740346908569,-0.752731561660767,0.017414459958673,37324,335,-457,-3004,0.93462485074997 +31977,-0.430050700902939,-0.745568692684174,0.015738815069199,37324,848,2264,-2737,0.938184440135956 +31979,-0.41592463850975,-0.729439556598663,0.013017479330301,37324,-374,14,-3025,0.938061892986298 +31981,-0.401128202676773,-0.71900749206543,0.01148540712893,37324,238,1896,-2792,0.940809369087219 +31983,-0.392328590154648,-0.70431661605835,0.010281409136951,37324,-179,54,-3036,0.941469192504883 +31985,-0.378909766674042,-0.690824270248413,0.012670611962676,37324,122,1505,-2783,0.941663026809692 +31987,-0.36513477563858,-0.676865577697754,0.016435652971268,37324,-783,-32767,-2985,0.938936769962311 +31989,-0.350544989109039,-0.648997366428375,0.019039260223508,37324,-293,-5503,-2717,0.939305245876312 +31991,-0.32979553937912,-0.629302322864533,0.014677709899843,37324,-1660,-6426,-2989,0.936012029647827 +31993,-0.310125350952148,-0.610120177268982,0.007560598198324,37324,-1192,-5308,-2857,0.937492430210114 +31995,-0.295772463083267,-0.591153562068939,0.005180140957236,37324,-1578,-6724,-3048,0.944311201572418 +31997,-0.284456461668014,-0.566693186759949,0.004209069069475,37324,-892,-6206,-2900,0.950091302394867 +31999,-0.266384601593018,-0.56672465801239,0.00568797532469,37324,-2162,-5534,-3039,0.960095882415772 +32001,-0.248430609703064,-0.560945749282837,0.005455158185214,37324,-1857,-4786,-2884,0.95902407169342 +32003,-0.233438611030579,-0.547889351844788,0.006702042650431,37324,-2327,-6565,-3026,0.958056330680847 +32005,-0.221197694540024,-0.539292693138123,0.009308277629316,37324,-1815,-5158,-2843,0.953826665878296 +32007,-0.215181097388268,-0.527596890926361,0.013894299045205,37324,-1871,-6588,-2971,0.952462494373322 +32009,-0.206367179751396,-0.536213517189026,0.016348853707314,37324,-1737,-3804,-2756,0.944122731685638 +32011,-0.195021107792854,-0.535751163959503,0.015716964378953,37324,-2473,-5495,-2951,0.939477443695068 +32013,-0.184999659657478,-0.538685977458954,0.013978745788336,37324,-2097,-4011,-2777,0.942371428012848 +32015,-0.179455727338791,-0.531121611595154,0.011038861237466,37324,-2219,-5898,-2977,0.947483777999878 +32017,-0.162756010890007,-0.543076038360596,0.011403540149331,37324,-2887,-3130,-2804,0.948291540145874 +32019,-0.15844339132309,-0.551811575889587,0.011445570737124,37324,-2382,-4259,-2968,0.940533995628357 +32021,-0.154582589864731,-0.560642898082733,0.013186438940466,37324,-2062,-2892,-2779,0.939380347728729 +32023,-0.145603150129318,-0.563893258571625,0.009920543991029,37324,-2855,-4295,-2972,0.935494780540466 +32025,-0.138465687632561,-0.565207719802856,0.005328380037099,37324,-2499,-3162,-2862,0.934995234012604 +32027,-0.134813591837883,-0.572209000587463,0.008345675654709,37324,-2587,-3718,-2978,0.934430718421936 +32029,-0.13441202044487,-0.580190658569336,0.013382131233811,37324,-2030,-2252,-2758,0.936075747013092 +32031,-0.128077745437622,-0.596025824546814,0.014825920574367,37324,-2833,-2546,-2927,0.945876121520996 +32033,-0.128179550170898,-0.58728551864624,0.009905870072544,37324,-2078,-3136,-2799,0.95201826095581 +32051,-0.158848389983177,-0.674036502838135,0.007098672445863,37324,-1619,-793,-2952,0.930074214935303 +32053,-0.157575130462646,-0.690139532089233,0.005830196198076,37324,-1489,1456,-2815,0.929351925849915 +32055,-0.163678333163261,-0.688670456409454,0.003979725763202,37324,-1170,-1075,-2968,0.933028936386108 +32057,-0.164432197809219,-0.694786190986633,0.009802338667214,37324,-1181,1077,-2765,0.937803983688354 +32059,-0.174087136983871,-0.69164103269577,0.009441233240068,37324,-712,-889,-2925,0.942415177822113 +32061,-0.177480891346931,-0.701683402061462,0.00253156456165,37324,-718,1741,-2846,0.946507513523102 +32063,-0.180070400238037,-0.705102801322937,0.005119172856212,37324,-1071,44,-2950,0.944040238857269 +32065,-0.186085164546967,-0.698803663253784,0.011651557870209,37628,-315,799,-2734,0.948163628578186 +32067,-0.183168143033981,-0.702225983142853,0.014943744987249,37628,-1353,275,-2877,0.940740823745728 +32069,-0.180988997220993,-0.698563992977142,0.011694028042257,37628,-921,1246,-2731,0.928723454475403 +32071,-0.183816730976105,-0.696425020694733,0.006668854039162,37628,-867,66,-2928,0.925900399684906 +32073,-0.191878601908684,-0.686663210391998,0.003475881181657,37628,49,875,-2829,0.926745414733887 +32075,-0.192786380648613,-0.686251759529114,0.004172745160759,37628,-806,312,-2940,0.930622756481171 +32077,-0.194318264722824,-0.667688846588135,0.005276348441839,37628,-312,196,-2810,0.931219458580017 +32079,-0.19093431532383,-0.650892436504364,0.006982534192503,37628,-1069,-1108,-2916,0.936270654201508 +32081,-0.187417924404144,-0.639469087123871,0.006640957202762,37628,-714,514,-2795,0.937110185623169 +32083,-0.194231271743774,-0.625370621681213,0.005932703614235,37628,-222,-1030,-2919,0.941358387470245 +32085,-0.196661859750748,-0.619402647018433,0.005818231962621,37628,-68,824,-2806,0.942118287086487 +32087,-0.195296674966812,-0.601008534431458,0.006744702812284,37628,-719,-1444,-2909,0.945792853832245 +32089,-0.195003867149353,-0.587066471576691,0.009087409824133,37628,-220,-42,-2771,0.952565431594849 +32091,-0.198679193854332,-0.559457421302795,0.010476096533239,37628,-236,-2471,-2879,0.957006216049194 +32093,-0.19224314391613,-0.547341108322144,0.011695095337927,37628,-635,-341,-2743,0.955237686634064 +32095,-0.1874870210886,-0.526228666305542,0.011750251986086,37628,-929,-2271,-2866,0.948098301887512 +32097,-0.188238501548767,-0.503724932670593,0.011501035653055,37628,-133,-1598,-2751,0.945858418941498 +32099,-0.18352122604847,-0.491353392601013,0.012279238551855,37628,-916,-1952,-2858,0.93780928850174 +32101,-0.177241712808609,-0.476742774248123,0.010311044752598,37628,-752,-1284,-2766,0.939803421497345 +32103,-0.168637007474899,-0.459324866533279,0.009379890747368,37628,-1346,-2592,-2874,0.944519698619842 +32105,-0.164380609989166,-0.435840278863907,0.008693699724972,37628,-748,-2410,-2786,0.944441676139832 +32107,-0.162180289626122,-0.427189886569977,0.003845901228488,37628,-921,-2260,-2909,0.944566667079926 +32109,-0.160339564085007,-0.403581500053406,0.002178266178817,37628,-586,-2782,-2865,0.942607522010803 +32111,-0.153825908899307,-0.393572092056274,0.003579377895221,37628,-1293,-2688,-2908,0.946158230304718 +32113,-0.150183588266373,-0.371863007545471,0.004323214292526,37628,-824,-3011,-2842,0.944878458976746 +32115,-0.144420221447945,-0.357444196939468,0.007710742764175,37628,-1322,-3383,-2877,0.943271696567535 +32117,-0.134288534522057,-0.355092614889145,0.012340802699328,37628,-1488,-1775,-2746,0.939744412899017 +32119,-0.12985135614872,-0.341680735349655,0.013912399299443,37628,-1388,-3407,-2831,0.941444337368012 +32121,-0.129743561148644,-0.332676708698273,0.014914485625923,37628,-793,-2499,-2714,0.94053840637207 +32123,-0.127024576067925,-0.314841151237488,0.013627717271447,37628,-1259,-3989,-2829,0.934905171394348 +32125,-0.118686214089394,-0.305369555950165,0.012076916173101,37628,-1523,-2871,-2748,0.934076130390167 +32127,-0.118006706237793,-0.287242531776428,0.012208258733153,37628,-1201,-4300,-2835,0.937264621257782 +32129,-0.112917207181454,-0.27561017870903,0.013720201328397,37628,-1336,-3401,-2728,0.945856153964996 +32131,-0.104904145002365,-0.26323214173317,0.008494921959937,37628,-1875,-4137,-2857,0.949127674102783 +32133,-0.104495748877525,-0.251529693603516,0.001753648510203,37628,-1082,-3694,-2867,0.952816843986511 +32135,-0.106487177312374,-0.239248558878899,0.003022553864867,37628,-1096,-4387,-2893,0.948306977748871 +32137,-0.110061056911945,-0.224062755703926,0.006512845400721,37628,-686,-4311,-2814,0.944202303886414 +32139,-0.104722209274769,-0.228231489658356,0.004331351723522,37628,-1607,-3292,-2882,0.946592390537262 +32141,-0.099873781204224,-0.224591329693794,0.002791859209538,37628,-1446,-3408,-2860,0.951027631759644 +32143,-0.092119835317135,-0.232638359069824,0.005640482064337,37628,-1931,-2876,-2871,0.953184545040131 +32145,-0.091496877372265,-0.222182080149651,0.007421396672726,37628,-1243,-3858,-2803,0.9506476521492 +32147,-0.086533986032009,-0.227889254689217,0.008883534930646,37628,-1784,-3037,-2847,0.942207753658295 +32149,-0.08751030266285,-0.22694855928421,0.008846388198435,37628,-1162,-3020,-2784,0.939383924007416 +32151,-0.090791121125221,-0.2148677110672,0.012722270563245,37628,-1105,-4420,-2818,0.943186104297638 +32153,-0.086163893342018,-0.211700275540352,0.015785995870829,37628,-1569,-3351,-2701,0.945277452468872 +32155,-0.08109924197197,-0.207695141434669,0.011395066976547,37628,-1817,-3872,-2823,0.950089931488037 +32157,-0.080515176057816,-0.206713482737541,0.00838933698833,37628,-1348,-3206,-2786,0.957219839096069 +32159,-0.080794587731361,-0.203465789556503,0.006459924392402,37628,-1417,-3809,-2855,0.96324634552002 +32161,-0.073778100311756,-0.206501871347427,0.005931003950536,37628,-1874,-2846,-2811,0.966980814933777 +32163,-0.07341942191124,-0.198789909482002,0.006932811345905,37628,-1544,-4124,-2850,0.9608353972435 +32165,-0.073225446045399,-0.204992726445198,0.008591583929956,37628,-1366,-2571,-2778,0.95531564950943 +32167,-0.07548987865448,-0.218366771936417,0.008057340979576,37628,-1303,-2261,-2839,0.951025366783142 +32169,-0.07595406472683,-0.235612377524376,0.005477124359459,37628,-1281,-1214,-2813,0.954685628414154 +32171,-0.069236159324646,-0.242096170783043,0.000810071185697,37628,-2015,-2329,-2887,0.953091084957123 +32173,-0.074142709374428,-0.235678434371948,-0.002307047136128,37628,-972,-2826,-2904,0.947654128074646 +32175,-0.08569673448801,-0.242024704813957,-0.000788843375631,37628,-450,-2254,-2898,0.940980732440948 +32177,-0.093268662691116,-0.240391448140144,0.002794952364638,37628,-435,-2320,-2842,0.941164374351501 +32179,-0.094598010182381,-0.248558655381203,0.005116163287312,37628,-1024,-1941,-2856,0.945885479450226 +32181,-0.097580015659332,-0.249981760978699,0.009051474742591,37628,-664,-1847,-2766,0.955561578273773 +32183,-0.096866466104984,-0.259025245904922,0.012191439978778,37628,-1105,-1633,-2804,0.960898995399475 +32203,-0.107742644846439,-0.303140968084335,0.013210792094469,37628,-185,-1198,-2783,0.93160218000412 +32205,-0.10844437032938,-0.306678056716919,0.013114255852997,37628,-437,-94,-2700,0.933483600616455 +32207,-0.111160442233086,-0.304239273071289,0.015978367999196,37628,-447,-1100,-2761,0.938388228416443 +32209,-0.113141387701035,-0.294550120830536,0.01530862506479,37628,-227,-1116,-2672,0.94783091545105 +32211,-0.112231001257896,-0.293082743883133,0.011284730397165,37628,-647,-1070,-2790,0.957464218139648 +32213,-0.107849337160587,-0.294470906257629,0.010591197758913,37628,-729,-201,-2725,0.958320140838623 +32215,-0.101100601255894,-0.299734979867935,0.013543893583119,37628,-1184,-371,-2771,0.952349424362183 +32217,-0.099788725376129,-0.288522154092789,0.017272055149078,37628,-601,-1078,-2644,0.945560991764069 +32219,-0.099780976772308,-0.28029727935791,0.017498912289739,37628,-682,-1496,-2740,0.944652795791626 +32221,-0.096266686916351,-0.275758028030395,0.016071375459433,37628,-778,-688,-2656,0.942902445793152 +32223,-0.091492600739002,-0.271178692579269,0.01845059171319,37628,-1106,-1250,-2730,0.944132149219513 +32225,-0.090174145996571,-0.269131571054459,0.019534135237336,37628,-687,-514,-2612,0.945246040821075 +32227,-0.087287418544293,-0.258605092763901,0.018832225352526,37628,-997,-1745,-2723,0.944841682910919 +32229,-0.082458302378655,-0.260655552148819,0.017521677538753,37628,-1030,-245,-2633,0.942628443241119 +32231,-0.078633591532707,-0.251300573348999,0.01836471632123,37628,-1158,-1657,-2723,0.938279807567596 +32233,-0.072417572140694,-0.248486891388893,0.019592018797994,37628,-1262,-682,-2605,0.938154816627502 +32235,-0.070275671780109,-0.236522004008293,0.016712907701731,37628,-1130,-1952,-2730,0.94190925359726 +32237,-0.06742586940527,-0.230277195572853,0.016356248408556,37628,-1069,-1128,-2640,0.949283123016357 +32239,-0.071031175553799,-0.220724523067474,0.018653452396393,37628,-682,-1910,-2713,0.947194218635559 +32241,-0.070111244916916,-0.209765449166298,0.01785190962255,37628,-867,-1710,-2620,0.944806456565857 +32243,-0.062525518238545,-0.20245349407196,0.013886645436287,37628,-1579,-1924,-2742,0.939799427986145 +32245,-0.055251520127058,-0.190247312188149,0.013047811575234,37628,-1552,-2037,-2675,0.931802868843079 +32247,-0.050817370414734,-0.183635413646698,0.015628956258297,37628,-1504,-2066,-2727,0.931275725364685 +32249,-0.049200020730496,-0.168068259954453,0.017022389918566,37628,-1225,-2562,-2626,0.936931252479553 +32251,-0.046622842550278,-0.166315481066704,0.016463050618768,37628,-1415,-1897,-2718,0.943848133087158 +32253,-0.044510163366795,-0.163134917616844,0.013458632864058,37914,-1315,-1691,-2665,0.947515249252319 +32255,-0.040563270449638,-0.155535250902176,0.014012759551406,37914,-1586,-2404,-2732,0.95091050863266 +32257,-0.040479145944119,-0.142523109912872,0.013612881302834,37914,-1224,-2667,-2661,0.953428328037262 +32259,-0.0394626557827,-0.123792000114918,0.011572531424463,37914,-1379,-3600,-2746,0.954091906547546 +32261,-0.036286525428295,-0.122296452522278,0.01465083565563,37914,-1504,-2108,-2647,0.951435446739197 +32263,-0.036884386092424,-0.117524191737175,0.020193396136165,37914,-1290,-2639,-2683,0.951805472373962 +32265,-0.037843246012926,-0.11530215293169,0.021187353879213,37914,-1173,-2223,-2566,0.95557165145874 +32267,-0.040542352944613,-0.096528328955174,0.018482306972146,37914,-1076,-3896,-2691,0.958701491355896 +32269,-0.036218862980604,-0.085667543113232,0.016000116243959,37914,-1559,-3285,-2625,0.964206218719482 +32271,-0.035009223967791,-0.080400690436363,0.014653983525932,37914,-1423,-3126,-2714,0.960231006145477 +32273,-0.035474896430969,-0.0801050812006,0.017224125564098,37914,-1218,-2590,-2607,0.955841600894928 +32275,-0.033931143581867,-0.075532294809818,0.017227271571756,37914,-1451,-3115,-2692,0.949250519275665 +32277,-0.031131437048316,-0.06492380797863,0.013230843469501,37914,-1518,-3553,-2652,0.94981724023819 +32279,-0.028821522369981,-0.059082929044962,0.008339396677911,37914,-1571,-3418,-2751,0.954657018184662 +32281,-0.029867110773921,-0.046854745596647,0.007310498971492,37914,-1248,-3941,-2719,0.960824012756348 +32283,-0.033165473490954,-0.052559576928616,0.009887740947306,37914,-1098,-2669,-2738,0.966276407241821 +32285,-0.037991248071194,-0.050710815936327,0.010882736183703,37914,-828,-3115,-2675,0.962373912334442 +32287,-0.037406656891108,-0.050298478454352,0.015610718168318,37914,-1301,-3121,-2697,0.95923775434494 +32289,-0.041355237364769,-0.042933061718941,0.013513187877834,38272,-824,-3620,-2642,0.95437079668045 +32291,-0.043535023927689,-0.035772744566202,0.007854074239731,38272,-1000,-3798,-2747,0.952826797962189 +32293,-0.040321353822947,-0.050023805350065,0.007507670205086,38272,-1352,-1955,-2710,0.949409186840057 +32295,-0.040618564933539,-0.056218732148409,0.010708461515606,38272,-1164,-2533,-2726,0.949361026287079 +32297,-0.044185768812895,-0.05456006526947,0.012724267318845,38272,-792,-3011,-2647,0.951375007629394 +32299,-0.050206795334816,-0.044480744749308,0.009496160782874,38272,-602,-3850,-2731,0.949998378753662 +32301,-0.04784594848752,-0.045070730149746,0.007064901292324,38272,-1129,-2980,-2711,0.946562767028809 +32303,-0.048145573586226,-0.041709877550602,0.004892533645034,38272,-1023,-3395,-2761,0.937484264373779 +32305,-0.048072077333927,-0.048225369304419,0.002512353239581,38272,-944,-2482,-2763,0.936815083026886 +32307,-0.043134890496731,-0.056119121611118,0.001096409512684,38272,-1452,-2365,-2786,0.940518796443939 +32309,-0.041164170950651,-0.06121788546443,0.001059716218151,38272,-1189,-2355,-2780,0.949035942554474 +32311,-0.037246011197567,-0.064628854393959,0.002140696858987,38272,-1450,-2541,-2778,0.951419591903686 +32313,-0.035123977810145,-0.053246777504683,0.002727056387812,38272,-1280,-3639,-2759,0.949692606925964 +32315,-0.035399753600359,-0.057887375354767,0.003560738172382,38272,-1165,-2529,-2768,0.947203159332275 +32317,-0.04121495038271,-0.049860276281834,0.000835961604025,38272,-586,-3417,-2780,0.93926352262497 +32319,-0.042033437639475,-0.053852804005146,-0.000328777736286,38272,-1014,-2612,-2794,0.932574331760406 +32321,-0.04588458314538,-0.050265893340111,0.001106139388867,38272,-636,-3071,-2777,0.928152740001678 +32323,-0.047854475677013,-0.046894188970327,0.005562372505665,38272,-830,-3217,-2752,0.935953140258789 +32325,-0.041104692965746,-0.060551352798939,0.005966573487967,38272,-1471,-1664,-2718,0.937760949134827 +32327,-0.039864517748356,-0.068216390907765,0.006215020082891,38272,-1160,-2097,-2746,0.941939949989319 +32329,-0.050183229148388,-0.068578355014324,0.006372388917953,38272,-83,-2456,-2712,0.947247385978699 +32331,-0.0612703114748,-0.059732485562563,0.003146517090499,38272,47,-3373,-2766,0.951200664043426 +32333,-0.055931687355042,-0.063628882169724,0.002418507123366,38272,-1085,-2253,-2757,0.955184042453766 +32335,-0.053200293332338,-0.065516769886017,0.001593881752342,38272,-1035,-2495,-2775,0.956624984741211 +32353,-0.065454758703709,-0.093944318592548,-0.001711280317977,38272,-235,-2354,-2802,0.943289339542389 +32355,-0.070827387273312,-0.099377699196339,0.000905333494302,38272,-78,-1561,-2777,0.944068074226379 +32357,-0.069757021963596,-0.111642226576805,0.002329610986635,38272,-408,-656,-2753,0.942620933055878 +32359,-0.069374240934849,-0.110205180943012,0.00139355531428,38272,-481,-1849,-2772,0.94498747587204 +32361,-0.070560492575169,-0.116345293819904,0.002406228100881,38272,-201,-966,-2752,0.948396325111389 +32363,-0.07198328524828,-0.113367885351181,0.005174895748496,38272,-284,-1863,-2745,0.948624491691589 +32365,-0.065332673490048,-0.11963527649641,0.005046754609793,38272,-826,-857,-2720,0.946086943149567 +32367,-0.06663266569376,-0.103998966515064,0.000632408249658,38272,-343,-2852,-2775,0.94841057062149 +32369,-0.061225589364767,-0.097959659993649,0.000196894732653,38272,-780,-2044,-2776,0.949653685092926 +32371,-0.049926068633795,-0.101392693817616,0.00198459229432,38272,-1460,-1481,-2765,0.949144780635834 +32373,-0.041896678507328,-0.103579707443714,0.005761887412518,38272,-1251,-1322,-2709,0.950980722904205 +32375,-0.048612773418427,-0.105598852038383,0.008658543229103,38272,-171,-1477,-2718,0.951544106006622 +32377,-0.053359732031822,-0.104047894477844,0.007853610441089,38272,-125,-1536,-2683,0.954051077365875 +32379,-0.049968175590038,-0.105458572506905,0.006175338290632,38272,-851,-1477,-2733,0.959230840206146 +32381,-0.043761160224676,-0.097638435661793,0.003426720853895,38272,-1049,-2043,-2734,0.962778508663178 +32383,-0.036482881754637,-0.10170241445303,0.001295697991736,38272,-1304,-1297,-2766,0.961324572563171 +32385,-0.035044670104981,-0.100277937948704,-0.000604112108704,38272,-835,-1498,-2781,0.960577666759491 +32387,-0.033029247075319,-0.093399450182915,-0.003450083779171,38272,-963,-2155,-2798,0.963442265987396 +32389,-0.0264524333179,-0.08562158793211,-0.004772588610649,38272,-1327,-2146,-2830,0.964427351951599 +32391,-0.023701328784227,-0.075739495456219,-0.005125492345542,38272,-1138,-2585,-2810,0.962414979934692 +32393,-0.024263529106975,-0.079507768154144,-0.004877486266196,38272,-841,-1374,-2831,0.96108478307724 +32395,-0.026644079014659,-0.07537267357111,-0.005664375144988,38272,-718,-2141,-2814,0.960151016712189 +32397,-0.012617276981473,-0.08155120164156,-0.006433863658458,38272,-2071,-1131,-2850,0.957918524742126 +32399,-0.00436723837629,-0.067800767719746,-0.004109213128686,38272,-1795,-2900,-2803,0.962443888187408 +32401,-0.000475039472803,-0.065681323409081,-0.000161509422469,38272,-1551,-1952,-2777,0.966463446617126 +32403,-0.004189385101199,-0.067897439002991,0.000969112850726,38272,-944,-1724,-2768,0.967775106430054 +32405,-0.003786698216572,-0.071861580014229,0.001438472419977,38272,-1239,-1381,-2757,0.969437599182129 +32407,-0.004710455425084,-0.066901288926601,-0.000366884021787,38272,-1136,-2218,-2776,0.973736047744751 +32409,-0.000789075100329,-0.05257834866643,-0.001655627391301,38272,-1532,-2965,-2793,0.978172242641449 +32411,0.010359897278249,-0.049459166824818,-0.000862060347572,38272,-2217,-2309,-2780,0.976070761680603 +32413,0.01692178286612,-0.046359900385141,-0.001385611481965,38272,-2018,-2244,-2790,0.970502197742462 +32415,0.018803514540196,-0.050854884088039,0.000179008478881,38272,-1683,-1720,-2772,0.963274240493774 +32417,0.018009644001722,-0.050676304847002,-0.003259402001277,38272,-1523,-1946,-2811,0.956142723560333 +32419,0.01877942122519,-0.053041882812977,-0.008474420756102,38272,-1613,-1817,-2832,0.957968652248383 +32421,0.019472090527415,-0.052977975457907,-0.008886346593499,38272,-1663,-1884,-2878,0.958553552627564 +32423,0.020645875483751,-0.040883470326662,-0.007789227645844,38272,-1680,-3003,-2828,0.9575315117836 +32425,0.022317364811897,-0.033536035567522,-0.008194762282074,38272,-1792,-2708,-2871,0.959912180900574 +32427,0.01939469575882,-0.016369538381696,-0.008656454272568,38272,-1381,-3704,-2835,0.96046245098114 +32429,0.024506388232112,-0.018468119204044,-0.009434812702239,38272,-2084,-2254,-2887,0.960431456565857 +32431,0.018200973048806,-0.014583978801966,-0.010657229460776,38272,-1134,-2769,-2850,0.962681591510773 +32433,0.009860040619969,-0.017434479668737,-0.008092707954347,38272,-888,-2202,-2872,0.966496348381042 +32435,0.000975715229288,-0.013723383657634,-0.008528114296496,38272,-708,-2759,-2836,0.968396663665772 +32437,0.002234412590042,-0.017376100644469,-0.012544464319944,38272,-1444,-2136,-2926,0.970312297344208 +32439,0.004004346206784,-0.021873310208321,-0.012882522307336,38272,-1515,-2044,-2867,0.968728959560394 +32441,-5.96895042690448E-05,-0.015019436366856,-0.012062638998032,38272,-1039,-2923,-2922,0.970171332359314 +32443,0.00149769464042,-0.016216808930039,-0.015566983260214,38272,-1465,-2353,-2887,0.968042135238647 +32445,0.008889485150576,-0.014270313084126,-0.019696423783898,38272,-2018,-2577,-3014,0.969460427761078 +32447,0.010794630274177,-0.015586665831506,-0.01884158141911,38272,-1631,-2346,-2913,0.977095603942871 +32449,0.001904140342958,-0.007136104628444,-0.013350772671402,38272,-725,-3141,-2941,0.979076266288757 +32451,-0.007911455817521,-0.002024616580457,-0.009003954008222,38272,-524,-2995,-2847,0.981442213058472 +32453,-0.012168164364994,-0.002712812274694,-0.00957338232547,38272,-819,-2549,-2898,0.973457515239716 +32455,-0.012201763689518,-0.0019628952723,-0.009348749183118,38272,-1156,-2679,-2850,0.965854346752167 +32457,-0.014161962084472,-0.007078990340233,-0.009222669526935,38272,-965,-2163,-2895,0.966963648796082 +32459,-0.022913092747331,0.006097296718508,-0.010339153930545,38272,-373,-3679,-2858,0.972951292991638 +32461,-0.02022048085928,-0.002697112737224,-0.011635105125606,38272,-1208,-1974,-2925,0.976389706134796 +32463,-0.018813349306583,-0.005933301988989,-0.013933738693595,38272,-1155,-2329,-2884,0.97558331489563 +32465,-0.020541103556752,-0.018113670870662,-0.011913481168449,38272,-869,-1482,-2930,0.972712576389313 +32467,-0.032848842442036,-0.024204513058066,-0.009301907382905,38272,35,-1854,-2854,0.967005908489227 +32469,-0.040940281003714,-0.017886565998197,-0.007917786948383,38272,-59,-2798,-2884,0.965376377105713 +32471,-0.037541583180428,-0.017401544377208,-0.004619554616511,38272,-1003,-2413,-2823,0.963524341583252 +32473,-0.029831577092409,-0.012695943005383,-0.003366695949808,38272,-1359,-2756,-2831,0.961773216724396 +32475,-0.02665594406426,-0.016415225341916,-0.003733207704499,38272,-1131,-2119,-2817,0.961067736148834 +32477,-0.028958216309548,-0.019076492637396,-0.006466715130955,38272,-656,-2115,-2867,0.962773382663727 +32479,-0.028231965377927,-0.020886227488518,-0.011151051148772,38272,-922,-2181,-2868,0.970748901367188 +32481,-0.027927093207836,-0.010345251299441,-0.012205816805363,38272,-845,-3195,-2936,0.970808863639832 +32483,-0.024440713226795,-0.012590063735843,-0.007183644454926,38272,-1164,-2263,-2843,0.970349013805389 +32485,-0.024094259366393,-0.02911327406764,-0.004482042975724,38272,-895,-935,-2846,0.967833876609802 +32487,-0.03028373606503,-0.039741273969412,-0.005574098788202,38272,-377,-1257,-2832,0.966253638267517 +32489,-0.034577060490847,-0.050192765891552,-0.004956192336977,38272,-381,-1001,-2852,0.964743673801422 +32491,-0.036999102681875,-0.037845216691494,-0.003503889078274,38272,-536,-2904,-2818,0.963492214679718 +32493,-0.03259089589119,-0.039802171289921,-0.00608088914305,38272,-1033,-1764,-2866,0.96326732635498 +32495,-0.030882865190506,-0.041582524776459,-0.010926789604127,38272,-907,-1817,-2870,0.962861120700836 +32497,-0.02931653521955,-0.05144539102912,-0.009361684322357,38272,-853,-986,-2905,0.964324831962585 +32499,-0.037916030734778,-0.052280079573393,-0.00736438203603,38272,-54,-1706,-2846,0.963805735111237 +32501,-0.048811249434948,-0.050696607679129,-0.005898250732571,38272,383,-1782,-2865,0.970083713531494 +32503,-0.047256488353014,-0.063226312398911,-0.005356916226447,38272,-623,-683,-2833,0.967732131481171 +32505,-0.04035734757781,-0.065224140882492,-0.007054150570184,38272,-1015,-1265,-2880,0.963576793670654 +32507,-0.034811563789845,-0.065252482891083,-0.011045835912228,38272,-1069,-1516,-2873,0.961192607879639 +32509,-0.037164848297834,-0.056976862251759,-0.013925286009908,38272,-397,-2099,-2962,0.958463072776794 +32511,-0.033933468163014,-0.066455647349358,-0.013058289885521,38272,-900,-791,-2889,0.956937611103058 +32513,-0.031031815335155,-0.066334053874016,-0.013997562229633,38272,-858,-1336,-2965,0.954942882061004 +32515,-0.024871015921235,-0.06277110427618,-0.015461631119251,38272,-1227,-1744,-2907,0.95573216676712 +32517,-0.020852990448475,-0.064664393663406,-0.015534495934844,38272,-1094,-1184,-2985,0.960545063018799 +32519,-0.025103580206633,-0.060571365058422,-0.012200582772493,38272,-469,-1781,-2887,0.970480024814606 +32521,-0.023599196225405,-0.063755758106709,-0.007057272363454,38272,-863,-1065,-2886,0.977381706237793 +32523,-0.023185532540083,-0.059634324163199,-0.002300709486008,38272,-821,-1761,-2819,0.978518545627594 +32525,-0.020109985023737,-0.064918167889118,0.00093638227554,38272,-1022,-864,-2792,0.977833151817322 +32527,-0.022461973130703,-0.05861746892333,-0.003998167347163,38272,-626,-1897,-2830,0.977057218551636 +32529,-0.017324902117252,-0.059320535510779,-0.013734011910856,38272,-1199,-1253,-2966,0.98262494802475 +32531,-0.010574208572507,-0.062828436493874,-0.018310563638806,38272,-1440,-1102,-2931,0.980653047561646 +32533,-0.01333065982908,-0.06095789372921,-0.014404375106096,38272,-691,-1378,-2976,0.978808522224426 +32535,-0.012198575772345,-0.064302116632462,-0.009425950236619,38272,-1008,-1060,-2871,0.973716735839844 +32537,-0.009790170006454,-0.062454469501972,-0.008566332049668,38272,-1118,-1321,-2908,0.973986089229584 +32539,-0.00541077926755,-0.061171405017376,-0.008454542607069,38272,-1334,-1402,-2866,0.974610567092896 +32541,-0.003711690660566,-0.045031942427158,-0.009369858540595,38272,-1167,-2602,-2919,0.97766125202179 +32543,0.005459994077683,-0.044662855565548,-0.010187127627432,38272,-1833,-1549,-2879,0.979471445083618 +32545,0.011089138686657,-0.03981364890933,-0.008271236903965,38272,-1688,-1855,-2907,0.981538891792297 +32547,0.011109855957329,-0.037527203559876,-0.005560909863561,38272,-1264,-1766,-2848,0.984280228614807 +32549,0.013628753833473,-0.047412902116776,-0.007654022891074,38272,-1501,-643,-2900,0.980995416641235 +32551,0.011137147434056,-0.048717673867941,-0.009210196323693,38272,-1090,-1320,-2874,0.983312666416168 +32553,0.008222218602896,-0.048021096736193,-0.00729998247698,38272,-1030,-1361,-2897,0.98039984703064 +32555,0.005779783241451,-0.03790993988514,-0.008205040358007,38272,-1019,-2265,-2868,0.973596751689911 +32557,0.010248959995806,-0.035880886018276,-0.011998147703707,38272,-1602,-1638,-2953,0.971014618873596 +32559,0.007861602120101,-0.025036981329322,-0.012175492011011,38272,-1058,-2481,-2896,0.974633097648621 +32561,0.006756609305739,-0.023556465283036,-0.009536437690258,38272,-1152,-1780,-2925,0.980050981044769 +32563,0.010993093252182,-0.025314563885331,-0.010573209263384,38272,-1581,-1558,-2886,0.98078864812851 +32565,0.009141025133431,-0.018952496349812,-0.012549671344459,38272,-1140,-2189,-2962,0.980967879295349 +32567,0.010611622594297,-0.016012582927942,-0.013400629162788,38272,-1382,-2014,-2907,0.980207622051239 +32583,0.006653385702521,-0.009991647675633,-0.008897834457457,38272,-1115,-1816,-2882,0.979546010494232 +32585,0.002176787704229,-0.008291216567159,-0.011991359293461,38272,-872,-1994,-2963,0.975931644439697 +32587,-0.001308329752646,0.000169418184669,-0.012821270152927,38272,-880,-2607,-2911,0.973874986171722 +32589,0.004468555096537,-0.004165803082287,-0.012488526292145,38272,-1635,-1621,-2971,0.976762115955353 +32591,0.007381961680949,0.001791065442376,-0.01291102450341,38272,-1465,-2445,-2913,0.977993488311768 +32593,0.003814354306087,0.00833554752171,-0.013577508740127,38272,-941,-2590,-2985,0.981904804706574 +32595,0.001314119785093,0.012321851216257,-0.015520610846579,38272,-989,-2452,-2933,0.976392507553101 +32597,-0.001738672377542,0.017915148288012,-0.0188297778368,38272,-895,-2678,-3049,0.969874978065491 +32599,0.00079877168173,0.009393201209605,-0.018990030512214,38272,-1341,-1516,-2959,0.967421591281891 +32601,0.000476307526696,0.009274038486183,-0.01536952983588,38272,-1143,-2133,-3011,0.969034671783447 +32603,-0.003727155504748,-0.000756812398322,-0.01376408804208,38272,-795,-1261,-2926,0.971347570419312 +32605,-0.008598814718425,0.004487689118832,-0.013560649007559,38272,-677,-2442,-2991,0.975461661815643 +32607,-0.002262837952003,0.004147995263338,-0.013388998806477,38272,-1571,-2023,-2925,0.977258861064911 +32609,-0.00156744022388,0.007767912466079,-0.014566307887435,38272,-1181,-2368,-3005,0.975706994533539 +32611,-0.009535986930132,0.015643818303943,-0.013900854624808,38272,-442,-2774,-2930,0.978314161300659 +32613,-0.006254049483687,0.014671336859465,-0.013786677271128,38272,-1281,-2137,-2998,0.975320994853973 +32615,0.004905974958092,0.014487813226879,-0.013298287056387,38272,-2017,-2179,-2928,0.970488667488098 +32617,0.008843176066875,0.010148842819035,-0.012510457076132,38272,-1580,-1824,-2984,0.971243143081665 +32619,0.001038351561874,0.010702267289162,-0.011030577123165,38272,-608,-2174,-2914,0.973568499088287 +32621,0.00185496325139,0.006943944841623,-0.011505133472383,38272,-1260,-1818,-2974,0.982421398162842 +32623,0.008268371224403,0.012996543198824,-0.0170933958143,38272,-1734,-2598,-2957,0.981743395328522 +32625,0.013761312700808,0.013586382381618,-0.021879650652409,38272,-1791,-2240,-3098,0.979013979434967 +32627,0.017771737650037,0.008413476869464,-0.02125814370811,38272,-1708,-1729,-2989,0.972763419151306 +32629,0.010300249792636,0.005891885142773,-0.018859770148993,38272,-800,-1885,-3066,0.966670274734497 +32631,0.008326357230544,-0.00525314360857,-0.018552662804723,38272,-1149,-1101,-2973,0.958402216434479 +32633,0.009774507023394,0.00586781417951,-0.020639030262828,38272,-1435,-2863,-3090,0.951706171035767 +32635,0.013099301606417,0.008149116300046,-0.022060327231884,38272,-1601,-2252,-3000,0.951277792453766 +32637,0.012200028635562,0.024890720844269,-0.019359443336725,38272,-1321,-3586,-3077,0.954844236373901 +32639,0.020991381257773,0.025998190045357,-0.014332851395011,38272,-2114,-2431,-2950,0.96280699968338 +32641,0.021780973300338,0.016679501160979,-0.01246939972043,38272,-1587,-1591,-2999,0.963637113571167 +32643,0.01446560677141,0.016299234703183,-0.01336311455816,38272,-875,-2190,-2945,0.968005061149597 +32645,0.013444754295051,0.014909357763827,-0.01511241029948,38272,-1322,-2126,-3032,0.965641736984253 +32647,0.014156738296151,0.019744340330362,-0.017000731080771,38272,-1449,-2614,-2972,0.958853900432587 +32649,0.012511072680354,0.024162607267499,-0.017142562195659,38272,-1270,-2696,-3058,0.958062767982483 +32651,0.007240019273013,0.032466281205416,-0.016290217638016,38272,-925,-3052,-2969,0.961819231510162 +32653,0.008356356993318,0.022074833512306,-0.015287875197828,38272,-1407,-1618,-3038,0.964536666870117 +32655,0.011445177718997,0.012880152091384,-0.020181886851788,38272,-1587,-1524,-2998,0.964580118656158 +32657,0.015798760578036,0.008658675476909,-0.02291901409626,38272,-1770,-1854,-3131,0.967260837554931 +32659,0.019779674708843,0.007398024201393,-0.021123850718141,38272,-1778,-2016,-3008,0.966772973537445 +32661,0.012008887715638,0.009096261113882,-0.01892501115799,38272,-849,-2268,-3087,0.972616076469421 +32663,0.006611101329327,-0.005540857557207,-0.018218418583274,38272,-923,-871,-2990,0.976196229457855 +32665,0.000846805458423,-0.011758601292968,-0.019366137683392,38272,-816,-1344,-3095,0.977729797363281 +32667,-0.000807192118373,-0.021832291036844,-0.019967395812273,38272,-1086,-951,-3005,0.97913271188736 +32669,-0.007448472548276,-0.015519523993135,-0.020388927310705,38272,-624,-2173,-3109,0.98069417476654 +32671,-0.008715938776731,-0.02027714625001,-0.019420050084591,38272,-998,-1341,-3004,0.985641479492188 +32673,-0.008661625906825,-0.025727745145559,-0.018630357459188,38272,-1077,-1157,-3092,0.981834650039673 +32675,-0.015997979789972,-0.025649322196841,-0.015009371563792,38272,-456,-1594,-2977,0.980208396911621 +32677,-0.017184108495712,-0.03230844065547,-0.015032226219773,38272,-854,-947,-3051,0.976290106773376 +32679,-0.012871160171926,-0.034512054175139,-0.016943365335465,38272,-1329,-1284,-2992,0.971141159534454 +32681,-0.009155369363725,-0.03843242675066,-0.018586719408631,38272,-1339,-1027,-3096,0.967408537864685 +32683,-0.013411170803011,-0.030030436813831,-0.02175541035831,38272,-707,-2086,-3028,0.969883322715759 +32685,-0.018630836158991,-0.037186220288277,-0.021765097975731,38272,-538,-795,-3136,0.970606446266174 +32687,-0.02528578415513,-0.036670085042715,-0.020050806924701,38272,-359,-1405,-3019,0.971441984176636 +32689,-0.027848478406668,-0.032563768327236,-0.017206527292729,38272,-565,-1644,-3085,0.977429389953613 +32691,-0.023962361738086,-0.030005903914571,-0.018347369506955,38272,-1122,-1625,-3010,0.976082265377045 +32693,-0.024827880784869,-0.030223850160837,-0.022826008498669,38272,-716,-1341,-3154,0.978553950786591 +32695,-0.02773947454989,-0.043264679610729,-0.022315390408039,38272,-570,-295,-3041,0.978070676326752 +32697,-0.03237509727478,-0.040923677384853,-0.01934758760035,38272,-317,-1338,-3116,0.973335087299347 +32699,-0.026983363553882,-0.040442127734423,-0.017969265580177,38272,-1162,-1279,-3014,0.972380995750427 +32701,-0.025698272511363,-0.031548149883747,-0.018161810934544,38272,-838,-1941,-3105,0.976355731487274 +32703,-0.025744158774614,-0.035870086401701,-0.018181324005127,38272,-779,-980,-3018,0.980435788631439 +32705,-0.025787921622396,-0.039195708930492,-0.019949587062001,38272,-729,-925,-3129,0.978317558765411 +32707,-0.028708273544908,-0.032758623361588,-0.02046968229115,38272,-520,-1773,-3036,0.978037655353546 +32709,-0.024054935202003,-0.029825501143932,-0.018732884898782,38272,-1079,-1498,-3117,0.977228820323944 +32711,-0.017462324351072,-0.02570234797895,-0.017395066097379,38272,-1352,-1689,-3018,0.976340651512146 +32713,-0.014781214296818,-0.03148939460516,-0.01954603381455,38272,-1072,-814,-3130,0.973977744579315 +32715,-0.019283402711153,-0.018405605107546,-0.021323550492525,38272,-523,-2413,-3048,0.977483630180359 +32717,-0.018398262560368,-0.019049655646086,-0.020481681451202,38272,-878,-1373,-3144,0.979540944099426 +32719,-0.01650963164866,-0.016849158331752,-0.018150053918362,38272,-1011,-1640,-3029,0.982344448566437 +32721,-0.015126058831811,-0.01042325142771,-0.014433989301324,38272,-963,-2011,-3075,0.979926466941834 +32723,-0.009578729979694,-0.007876239717007,-0.016419799998403,38272,-1365,-1783,-3019,0.971255481243134 +32725,-0.003649570513517,-0.004955648910254,-0.022044636309147,38272,-1472,-1841,-3167,0.962862193584442 +32727,0.001473207725212,-0.008605311624706,-0.021117441356182,38272,-1492,-1320,-3054,0.958436191082001 +32729,-0.000343291147146,-0.000961950921919,-0.020289296284318,38272,-983,-2242,-3149,0.955343663692474 +32731,0.001511601381935,-0.005332812201232,-0.023854998871684,38272,-1261,-1310,-3076,0.958316326141357 +32733,0.005814731121063,-0.000610923452768,-0.024860195815563,38272,-1520,-2027,-3206,0.963359713554382 +32735,0.015452617779374,-0.000705091515556,-0.022110149264336,38272,-2023,-1676,-3068,0.970886468887329 +32737,0.019293017685413,-0.000513622304425,-0.022054878994823,38272,-1709,-1695,-3177,0.973454535007477 +32739,0.009828098118305,0.002853617304936,-0.019268192350864,38272,-583,-32767,-3052,0.976364374160767 +32741,0.003807740053162,0.000283394532744,-0.019010620191693,38272,-763,-31954,-3144,0.975597977638245 +32743,0.006319146603346,0.004043326247484,-0.016473924741149,38272,-1394,-32608,-3035,0.97376412153244 +32745,0.010081777349115,-0.001391031546518,-0.01498113013804,38272,-1566,-32020,-3099,0.972015261650085 +32747,0.01062638591975,-0.000557508319616,-0.016928629949689,38272,-1321,-32627,-3040,0.97428947687149 +32749,0.013834002427757,-0.01736949570477,-0.019034512341023,38272,-1589,-31240,-3149,0.975050389766693 +32751,0.013750124722719,-0.037228275090456,-0.021891459822655,38272,-1327,-30907,-3077,0.979091048240662 +32753,0.016515146940947,-0.068480849266052,-0.026837147772312,38272,-1602,-29643,-3245,0.982634603977203 +32755,0.026216758415103,-0.115555860102177,-0.035334628075361,38272,-2214,-28097,-3174,0.980305194854736 +32757,0.026546342298389,-0.177172735333443,-0.043508611619473,38272,-1599,-25933,-3447,0.979389786720276 +32759,0.022212078794837,-0.259579122066498,-0.043505121022463,38272,-1163,-23710,-3237,0.976496517658233 +32761,0.013500801287592,-0.3373122215271,-0.041154719889164,38272,-751,-22354,-3426,0.97541880607605 +32763,0.012820092961192,-0.437837719917297,-0.043168228119612,38272,-1296,-19991,-3241,0.974120616912842 +32765,0.01921059563756,-0.536937952041626,-0.045422248542309,38272,-1939,-17678,-3483,0.976115584373474 +32767,0.031120171770454,-0.665957093238831,-0.046549890190363,38272,-2470,-14721,-3271,0.980692028999329 +32769,0.034989450126886,-0.777333319187164,-0.047951061278582,38272,-2026,-12885,-3520,0.983425617218018 +32771,0.035551898181439,-0.905867218971252,-0.048999443650246,38272,-1738,-11245,-3296,0.984705090522766 +32773,0.029070852324367,-1.02076685428619,-0.054826617240906,38272,-1216,-8560,-3608,0.982451915740967 +32775,0.032508652657271,-1.1432056427002,-0.054978478699923,38272,-1917,-8094,-3345,0.980224430561066 +32777,0.041947610676289,-1.27787005901337,-0.05797166749835,38272,-2598,-2741,-3652,0.974830210208893 +32779,0.063128508627415,-1.41375112533569,-0.059674348682165,38272,-3652,-2948,-3387,0.973008453845978 +32781,0.073833853006363,-1.55377244949341,-0.055248737335205,38272,-3234,2483,-3626,0.96047306060791 +32783,0.07981850206852,-1.68844616413116,-0.052800089120865,38272,-2841,1338,-3348,0.959852397441864 +32785,0.082400307059288,-1.82787001132965,-0.054710283875465,38272,-2830,7384,-3624,0.957916498184204 +32787,0.080348677933216,-1.95558905601501,-0.057873398065567,38272,-2316,5236,-3391,0.961219549179077 +32789,0.082869924604893,-2.07494592666626,-0.058101668953896,38272,-2855,10576,-3669,0.972080528736114 +32791,0.087065733969212,-2.18178486824036,-0.058215089142323,38272,-2899,7668,-3403,0.97962498664856 +32793,0.101805403828621,-2.29488658905029,-0.059970367699862,38272,-4086,14433,-3694,0.984679579734802 +32795,0.110430985689163,-2.39082193374634,-0.062762454152107,38272,-3601,10677,-3443,0.990252494812012 +32813,0.159850433468819,-2.898597240448,-0.077825836837292,38272,-4889,21943,-3911,0.988007009029388 +32815,0.166406214237213,-2.90649461746216,-0.080655172467232,38272,-4595,16862,-3615,0.98578804731369 +32817,0.167319685220718,-2.89009189605713,-0.082505993545055,38272,-4550,20818,-3969,0.98533695936203 +32819,0.172745570540428,-2.8775007724762,-0.08544684201479,38272,-4685,16087,-3659,0.988562107086181 +32821,0.178326070308685,-2.84559035301208,-0.086144641041756,38272,-5145,20077,-4015,0.995220065116882 +32823,0.181265085935593,-2.80326342582703,-0.081735342741013,38272,-4715,13987,-3645,1.00630867481232 +32825,0.182205498218536,-2.7643129825592,-0.079918161034584,38272,-4961,19327,-3946,1.01324880123138 +32827,0.178636968135834,-2.71158051490784,-0.084622301161289,38272,-4298,12991,-3675,1.01688504219055 +32829,0.170694604516029,-2.64202189445496,-0.087126582860947,38272,-4215,16178,-4038,1.01764011383057 +32831,0.159732013940811,-2.55413746833801,-0.0864722058177,38272,-3579,9229,-3699,1.01106035709381 +32833,0.15407158434391,-2.46901655197144,-0.08798561245203,38272,-4186,13222,-4059,1.00779545307159 +32835,0.144708082079887,-2.38402318954468,-0.090358011424542,38272,-3552,7937,-3737,1.00061643123627 +32837,0.133812248706818,-2.29727840423584,-0.091602049767971,38272,-3546,11213,-4115,1.00076067447662 +32839,0.120554007589817,-2.19925880432129,-0.092392779886723,38272,-2991,5222,-3763,1.00634849071503 +32841,0.109694331884384,-2.08613324165344,-0.086776413023472,38272,-3212,6711,-4076,1.00835597515106 +32843,0.09951101988554,-1.97120034694672,-0.076703891158104,38272,-2962,1515,-3667,1.01079988479614 +32845,0.090296722948551,-1.86202597618103,-0.068177193403244,38272,-3075,4072,-3870,1.00773990154266 +32847,0.071495182812214,-1.75185513496399,-0.067281298339367,38272,-1989,-613,-3610,1.00359535217285 +32849,0.052355654537678,-1.64397692680359,-0.068204633891583,38272,-1787,1249,-3885,1.00199162960053 +32851,0.03484794870019,-1.5253050327301,-0.060032248497009,38272,-1585,-3891,-3569,1.00298488140106 +32853,0.019763622432947,-1.41228270530701,-0.049955081194639,38272,-1568,-2353,-3690,1.00807082653046 +32855,0.004941598977894,-1.3004252910614,-0.044496204704046,38272,-1362,-6150,-3468,1.01233279705048 +32857,-0.009588832966983,-1.19464147090912,-0.04052098095417,38272,-1138,-4944,-3595,1.01100611686707 +32859,-0.026175322011113,-1.09315669536591,-0.036452651023865,38272,-790,-8000,-3418,1.00863516330719 +32861,-0.046519719064236,-0.991790890693665,-0.033627938479185,38272,-118,-7574,-3527,1.00080847740173 +32863,-0.067543543875218,-0.899554073810577,-0.03032286837697,38272,137,-9822,-3380,0.999470412731171 +32865,-0.084648758172989,-0.798600018024445,-0.025965373963118,38272,299,-10434,-3453,1.00235044956207 +32867,-0.098573736846447,-0.7015500664711,-0.025710217654705,38272,108,-12801,-3351,1.00374567508698 +32869,-0.11041758954525,-0.621078550815582,-0.024432208389044,38272,389,-11701,-3451,1.01000010967255 +32871,-0.131140753626823,-0.541362404823303,-0.02186812646687,38272,1111,-13735,-3328,1.01598727703094 +32873,-0.156060799956322,-0.472960859537125,-0.021021421998739,38272,2107,-13153,-3412,1.02197587490082 +32875,-0.175317645072937,-0.416404545307159,-0.021029060706496,38272,1706,-13812,-3325,1.02362036705017 +32877,-0.196789741516113,-0.360220670700073,-0.022391393780708,38272,2583,-14069,-3429,1.02351140975952 +32879,-0.213343992829323,-0.315469563007355,-0.024253638461232,38272,2142,-14407,-3350,1.01531100273132 +32881,-0.230468660593033,-0.274888783693314,-0.028378440067172,38272,2925,-14347,-3513,1.00595390796661 +32883,-0.242139875888824,-0.242392018437386,-0.029131826013327,38272,2308,-14609,-3388,0.993724226951599 +32885,-0.258120208978653,-0.202069535851479,-0.028576876968145,38272,3419,-15561,-3532,0.990673005580902 +32887,-0.271859854459763,-0.167736500501633,-0.029308632016182,38272,3001,-15877,-3394,0.99075323343277 +32889,-0.276850342750549,-0.154089108109474,-0.028162300586701,38272,3060,-14506,-3534,0.990656971931458 +32891,-0.283047527074814,-0.145713806152344,-0.028477970510721,38272,2750,-14420,-3393,0.991863965988159 +32893,-0.293405592441559,-0.14340578019619,-0.029283717274666,38272,3833,-13953,-3547,0.99633401632309 +32895,-0.303120195865631,-0.147252216935158,-0.032421860843897,38272,3425,-13613,-3425,1.0016303062439 +32897,-0.300810486078262,-0.165011301636696,-0.035466384142637,38272,3175,-12251,-3620,1.00711584091187 +32899,-0.296147018671036,-0.171992957592011,-0.035342592746019,38272,2433,-13115,-3451,1.00302875041962 +32901,-0.296031147241592,-0.184732794761658,-0.034186150878668,38272,3393,-12360,-3612,0.998439431190491 +32903,-0.295409381389618,-0.209167703986168,-0.035003062337637,38272,2849,-11401,-3454,0.990467369556427 +32905,-0.297160387039185,-0.236815229058266,-0.034670226275921,38272,3682,-10499,-3624,0.991989076137543 +32907,-0.287823408842087,-0.281502783298492,-0.035998247563839,38272,2254,-8957,-3466,0.989997446537018 +32909,-0.283552408218384,-0.319794684648514,-0.037462178617716,38272,3163,-8417,-3663,0.986177146434784 +32911,-0.280936390161514,-0.364957541227341,-0.037030309438706,38272,2770,-7732,-3479,0.982034504413605 +32913,-0.274532198905945,-0.401822507381439,-0.035767029970884,38272,2994,-7179,-3652,0.978111088275909 +32915,-0.253781110048294,-0.452976733446121,-0.034313075244427,38272,1210,-6009,-3466,0.981504857540131 +32917,-0.241065934300423,-0.501375734806061,-0.032521937042475,38272,2131,-4677,-3630,0.984763979911804 +32919,-0.227948263287544,-0.561897873878479,-0.026755567640066,38272,1503,-3695,-3420,0.990980863571167 +32921,-0.206843078136444,-0.619794428348541,-0.021159380674362,38272,1082,-1964,-3506,0.989420652389526 +32923,-0.179464504122734,-0.667078375816345,-0.016582239419222,38272,-112,-2999,-3354,0.989015161991119 +32925,-0.157839894294739,-0.715083301067352,-0.013780660927296,38272,327,-971,-3422,0.984843313694 +32927,-0.137449935078621,-0.752290785312653,-0.013126508332789,38272,-137,-2317,-3333,0.984617650508881 +32929,-0.115079015493393,-0.802636742591858,-0.014030326157808,38272,-363,811,-3427,0.977516710758209 +32931,-0.092520713806152,-0.844324886798858,-0.015503260307014,38272,-881,-454,-3352,0.970930457115173 +32933,-0.065739519894123,-0.893307328224182,-0.01213629450649,38272,-1436,2422,-3410,0.966767907142639 +32935,-0.046200357377529,-0.930799067020416,-0.011345580220223,38272,-1296,750,-3326,0.964285969734192 +32937,-0.019927551969886,-0.97748214006424,-0.009843984618783,38272,-2122,3906,-3389,0.969499170780182 +32939,0.005048764869571,-1.01039826869965,-0.009412406012416,38272,-2408,1870,-3315,0.971153318881988 +32941,0.033720746636391,-1.03987240791321,-0.004312073346227,38272,-3166,4008,-3327,0.980104446411133 +32943,0.060131765902042,-1.07139444351196,-0.001660929294303,38272,-3314,2982,-3263,0.983295023441315 +32945,0.080331347882748,-1.09738206863403,-0.000519233464729,38272,-3335,5047,-3288,0.987220942974091 +32961,0.22855843603611,-1.17005145549774,-0.007427480071783,38272,-5826,6048,-3349,0.986790478229523 +32963,0.237296491861343,-1.15451467037201,-0.006140757352114,38272,-4930,2779,-3300,0.991900444030762 +32965,0.246452763676643,-1.13662505149841,-0.001262024044991,38272,-5639,4501,-3273,0.996278882026672 +32967,0.253998309373856,-1.10762071609497,0.002403040416539,38272,-5200,1539,-3241,0.9996297955513 +32969,0.258430153131485,-1.08948242664337,0.002617553342134,38272,-5598,4109,-3232,0.997974932193756 +32971,0.250974744558334,-1.05411994457245,0.001031520427205,38272,-4202,694,-3250,0.992237329483032 +32973,0.248202949762344,-1.02401280403137,-5.04195850226097E-05,38272,-5014,2564,-3269,0.987832367420196 +32975,0.245645388960838,-0.980442821979523,-0.000676721800119,38272,-4589,-596,-3262,0.98129665851593 +32977,0.246219679713249,-0.944214165210724,-0.002785262651742,38272,-5339,1156,-3293,0.978264629840851 +32979,0.246308833360672,-0.917887270450592,-0.003359220921993,38272,-4901,59,-3281,0.975776076316834 +32981,0.238134518265724,-0.876089036464691,-0.001167599344626,38272,-4710,-62,-3259,0.973715126514435 +32983,0.224924132227898,-0.833477377891541,0.002152391942218,38272,-3755,-2032,-3243,0.973639130592346 +32985,0.210965931415558,-0.793046176433563,0.003862382145599,38272,-3966,-1047,-3195,0.974907159805298 +32987,0.201203137636185,-0.762962281703949,0.00422614812851,38272,-3764,-1896,-3227,0.974335551261902 +32989,0.184383228421211,-0.722803473472595,0.000905259046704,38272,-3408,-1930,-3237,0.970551490783691 +32991,0.163252338767052,-0.683584749698639,0.001457132282667,38272,-2492,-3469,-3246,0.96979022026062 +32993,0.147187456488609,-0.653251349925995,0.006074375007302,38272,-2932,-2137,-3179,0.96875411272049 +32995,0.133662790060043,-0.625837743282318,0.005668762605637,38272,-2683,-3260,-3215,0.969903111457825 +32997,0.122110404074192,-0.598469793796539,-0.000217517328565,38272,-2914,-2635,-3249,0.975695669651032 +32999,0.104145869612694,-0.543597340583801,-0.004660806618631,38272,-2000,-6239,-3286,0.979783058166504 +33001,0.089843273162842,-0.499213606119156,-0.003287894884124,38272,-2251,-5336,-3281,0.9795281291008 +33003,0.074450306594372,-0.457687973976135,-0.00223651714623,38272,-1804,-6394,-3269,0.977766692638397 +33005,0.049150642007589,-0.417528480291367,-0.00067794858478,38272,-842,-6257,-3250,0.981482207775116 +33007,0.017757335677743,-0.387859046459198,0.002311553573236,38272,127,-6462,-3238,0.980719923973084 +33009,-0.014922585338354,-0.356582909822464,0.003240067744628,38272,712,-6534,-3204,0.974310040473938 +33011,-0.042207680642605,-0.327554136514664,0.003630359889939,38272,695,-7223,-3227,0.972012162208557 +33013,-0.067700542509556,-0.28742703795433,0.006522936746478,38272,1065,-8244,-3164,0.969935417175293 +33015,-0.080061234533787,-0.268397986888885,0.008883764967322,38272,194,-7327,-3190,0.972704589366913 +33017,-0.095904566347599,-0.254336804151535,0.007974918931723,38272,872,-6895,-3152,0.972606956958771 +33019,-0.123339079320431,-0.240218833088875,0.008640707470477,38272,1935,-7367,-3190,0.974323570728302 +33021,-0.148296922445297,-0.230519503355026,0.00538971228525,38272,2420,-6955,-3176,0.971738696098327 +33023,-0.161257565021515,-0.218663677573204,0.002313003409654,38272,1506,-7511,-3232,0.969511330127716 +33025,-0.169575452804565,-0.206292778253555,0.003604768542573,38272,1638,-7541,-3193,0.9680997133255 +33027,-0.183977454900742,-0.189147040247917,0.002642072970048,38272,2008,-8320,-3229,0.964733242988586 +33029,-0.200979694724083,-0.187972858548164,0.001750475727022,38272,2856,-7055,-3218,0.963309168815613 +33031,-0.218425184488296,-0.181651458144188,0.000646666216198,38272,2810,-7670,-3242,0.95958662033081 +33033,-0.228420540690422,-0.175248131155968,6.72437963658012E-05,38272,2899,-7663,-3241,0.964847564697266 +33035,-0.23290903866291,-0.172007128596306,-0.002050878712907,38272,2192,-7611,-3260,0.965961158275604 +33037,-0.240707516670227,-0.166516855359077,-0.004741929005831,38272,3055,-7754,-3302,0.970044553279877 +33039,-0.244406625628471,-0.169653132557869,-0.005142007488757,38272,2411,28846,-3282,0.976592659950256 +33041,-0.248649567365646,-0.165684074163437,-0.005790117196739,38272,3044,-1586,-3317,0.97503674030304 +33043,-0.250496327877045,-0.181255877017975,-0.009187220595777,38272,2481,-60,-3310,0.971051812171936 +33045,-0.25381550192833,-0.184726819396019,-0.010751255787909,38272,3178,-697,-3376,0.966432213783264 +33047,-0.249285355210304,-0.193109676241875,-0.00895709451288,38272,2126,-359,-3310,0.965664863586426 +33049,-0.24203959107399,-0.191374972462654,-0.009201620705426,38272,2343,-925,-3359,0.964231491088867 +33051,-0.229434475302696,-0.180624514818192,-0.005972619634122,38272,1376,-1861,-3291,0.970885157585144 +33053,-0.217671275138855,-0.169002488255501,-0.005109437741339,38272,1718,-1964,-3303,0.976857602596283 +33055,-0.201524168252945,-0.152083739638329,-0.005577553529292,38272,822,-2677,-3289,0.979475736618042 +33057,-0.188724771142006,-0.139920949935913,-0.003104728879407,38272,1268,-2443,-3280,0.976553976535797 +33059,-0.177091121673584,-0.112994834780693,-0.000541210465599,38272,883,-3932,-3255,0.975482523441315 +33061,-0.161675319075584,-0.098024368286133,-0.000616153760348,38272,724,-3309,-3252,0.977831780910492 +33063,-0.148608908057213,-0.081445582211018,-0.000796876673121,38272,448,-3640,-3256,0.980688750743866 +33065,-0.129716843366623,-0.065456688404083,0.00296900072135,38272,34,-3915,-3215,0.987945020198822 +33067,-0.111614584922791,-0.042188137769699,0.004390833899379,38272,-380,-4694,-3220,0.987382054328918 +33069,-0.094341583549976,-0.015694612637162,0.006448512896895,38272,-372,-5494,-3170,0.988441467285156 +33071,-0.076417170464993,0.000388188025681,0.008817879483104,38272,-825,-4824,-3188,0.983974158763886 +33073,-0.063507482409477,0.019153885543346,0.010784379206598,38272,-533,-5549,-3109,0.977305233478546 +33075,-0.04410969093442,0.028832031413913,0.012441734783352,38272,-1364,-4823,-3161,0.97267872095108 +33077,-0.027690200135112,0.056668490171433,0.015400561504066,38272,-1352,29189,-3046,0.970020174980164 +33079,-0.006473938468844,0.070843651890755,0.01767997816205,38272,-2022,273,-3121,0.96697998046875 +33081,0.009221312589943,0.089376293122768,0.014373156242073,38272,-1903,-697,-3049,0.964261174201965 +33083,0.031699940562248,0.090771079063416,0.012277976609767,38272,-2665,877,-3155,0.965561807155609 +33085,0.047422435134649,0.107825823128223,0.010659889318049,38272,-2534,-913,-3092,0.972527623176575 +33087,0.059640228748322,0.142533794045448,0.009979421272874,38272,-2353,-2284,-3168,0.983716130256653 +33089,0.078908935189247,0.178325220942497,0.009127210825682,38272,-3320,-3438,-3112,0.990523219108582 +33091,0.092503525316715,0.220397770404816,0.007758099585772,38272,-2959,-3994,-3181,0.989486157894134 +33093,0.097875237464905,0.259367614984512,0.006488945800811,38272,-2668,-5057,-3142,0.987734973430634 +33111,0.148625165224075,0.562673509120941,0.015300809405744,38272,-2956,-8413,-3120,0.979358971118927 +33113,0.143662989139557,0.59493762254715,0.009686022996902,38272,-2971,-10972,-3098,0.985067188739777 +33115,0.144889250397682,0.617598354816437,0.005484418943524,38272,-3184,26623,-3185,0.991045415401459 +33117,0.144665688276291,0.641280353069305,0.005084392614663,38272,-3378,-5290,-3161,0.987338483333588 +33119,0.137742355465889,0.657592833042145,0.009095877408981,38272,-2563,-3722,-3159,0.984382510185242 +33121,0.126518428325653,0.673523902893066,0.011967522092164,38272,-2378,-5499,-3067,0.978791773319244 +33123,0.113408707082272,0.696667492389679,0.011099064722657,38272,-1831,-5017,-3143,0.9775310754776 +33125,0.109968304634094,0.714638769626617,0.006298611871898,38272,-2742,-6575,-3120,0.977165699005127 +33127,0.107302024960518,0.748308598995209,0.000911291514058,38272,-2547,-6780,-3211,0.975877165794373 +33129,0.103862188756466,0.774219632148743,-0.000648352492135,38272,-2680,-8391,-3213,0.973620295524597 +33131,0.092135332524777,0.816913366317749,-0.000936571508646,38272,-1731,-8708,-3223,0.970874190330505 +33133,0.085017800331116,0.842178523540497,0.001201879815198,38272,-2143,-9750,-3201,0.970232665538788 +33135,0.077705100178719,0.861854493618012,0.004215236287564,38272,-1881,-8034,-3187,0.970184206962585 +33137,0.067358084022999,0.881719648838043,0.007623845245689,38272,-1662,-10331,-3126,0.980153560638428 +33139,0.058502029627562,0.893981337547302,0.011625984683633,38272,-1527,-8312,-3135,0.987183928489685 +33141,0.045369248837233,0.912694752216339,0.014313735067844,38272,-1140,-11102,-3043,0.985983729362488 +33143,0.026862053200603,0.922750890254974,0.01521659642458,38272,-405,-8931,-3107,0.985846281051636 +33145,0.009946397505701,0.937565326690674,0.012200807221234,38272,-312,-11594,-3064,0.982793152332306 +33147,0.003739289939404,0.932956993579864,0.007164799142629,38272,-962,-8405,-3160,0.976684033870697 +33149,-0.011626673862338,0.941760122776032,0.003417644416913,38272,-67,-11615,-3170,0.968123257160187 +33151,-0.023902134969831,0.942614555358887,0.007011116482317,38272,-128,26740,-3161,0.967714250087738 +33153,-0.033055976033211,0.942053437232971,0.007629458326846,38272,-159,-5247,-3118,0.969916224479675 +33155,-0.034631460905075,0.933742225170136,0.004292137455195,38272,-727,-2803,-3178,0.972660183906555 +33157,-0.045688726007938,0.932686686515808,0.002841129200533,38272,205,-5385,-3176,0.971200048923492 +33159,-0.062809348106384,0.94025319814682,0.000417554285377,38272,810,-4361,-3204,0.971209585666656 +33161,-0.074785873293877,0.939841687679291,-0.000424177385867,38272,772,-5876,-3213,0.973232209682465 +33163,-0.081025309860706,0.940412700176239,-0.001988585107028,38272,326,-4195,-3221,0.973646819591522 +33165,-0.086902268230915,0.939009606838226,-0.00023736373987,38272,567,-6126,-3209,0.979906737804413 +33167,-0.090915679931641,0.950879156589508,0.001826206804253,38272,348,-5491,-3194,0.978593230247498 +33169,-0.086307413876057,0.952124357223511,0.003808354958892,38272,-154,-6865,-3159,0.978120148181915 +33171,-0.086056381464005,0.959448277950287,0.00377714401111,38272,12,-5633,-3180,0.979913473129272 +33173,-0.086406044661999,0.967730462551117,0.006492720451206,38272,241,-7966,-3125,0.97550755739212 +33175,-0.086011365056038,0.971543908119202,0.009454965591431,38272,41,-5909,-3139,0.964330732822418 +33177,-0.089850775897503,0.985044181346893,0.010690634138882,38272,584,-8976,-3070,0.954494774341583 +33179,-0.092302061617375,0.99726665019989,0.012884229421616,38272,376,-7245,-3114,0.949017286300659 +33181,-0.096137292683125,1.0130866765976,0.014027290046215,38272,727,-9965,-3026,0.953733146190643 +33183,-0.092219561338425,1.01458406448364,0.015528378076851,38272,-37,-7105,-3093,0.959725081920624 +33185,-0.090671062469483,1.01961696147919,0.017315320670605,38272,307,-9681,-2989,0.96833735704422 +33187,-0.087625168263912,1.01303422451019,0.016817264258862,38272,2,-6890,-3081,0.97866028547287 +33189,-0.087429039180279,1.01548886299133,0.015413190238178,38272,390,26241,-3004,0.985377192497253 +33191,-0.079160414636135,1.00885450839996,0.017057163640857,38272,-450,-1125,-3076,0.995928108692169 +33193,-0.067710086703301,1.00174307823181,0.016913674771786,38272,-715,-3160,-2974,0.998779773712158 +33195,-0.05778194963932,0.997819483280182,0.016132418066263,38272,-846,-1483,-3079,1.00272536277771 +33197,-0.050631288439036,0.99138069152832,0.019734494388104,38272,-663,-3352,-2934,0.999350428581238 +33199,-0.051393564790487,1.0040168762207,0.022093024104834,38272,-150,-3078,-3033,0.994706451892853 +33201,-0.050606735050678,1.01489984989166,0.020219530910254,38272,-187,-5308,-2923,0.998022794723511 +33203,-0.049043387174606,1.02891457080841,0.015602455474436,38272,-329,-3870,-3074,0.995983481407166 +33205,-0.037374719977379,1.03184711933136,0.016527209430933,38272,-1156,-5357,-2964,0.994738698005676 +33207,-0.032365705817938,1.05528855323792,0.019789446145296,38272,-798,-5271,-3041,0.987670004367828 +33209,-0.027414483949542,1.07357215881348,0.024773357436061,38272,-825,-7486,-2861,0.98688417673111 +33211,-0.018874598667026,1.08199203014374,0.026420164853335,38272,-1233,-4946,-2991,0.981740891933441 +33213,-0.012624981813133,1.09379160404205,0.02563776448369,38272,-1141,-7712,-2849,0.980200290679931 +33215,-0.009253180585802,1.1054345369339,0.023347996175289,38272,-995,-5893,-3007,0.976972818374634 +33217,-0.008340979926288,1.12614274024963,0.024391124024987,38272,-819,-9258,-2860,0.980329096317291 +33219,-0.000860742526129,1.13441550731659,0.027007890865207,38272,-1405,-6464,-2977,0.98774117231369 +33221,0.006549153011292,1.14501976966858,0.02818326279521,38272,-1529,-9244,-2808,0.995298206806183 +33223,0.013794980943203,1.15225493907928,0.02877183444798,38272,-1601,-7055,-2959,0.994863510131836 +33225,0.017003336921334,1.16568899154663,0.027637019753456,38272,-1409,-10196,-2807,0.987706959247589 +33227,0.021063270047307,1.17303359508514,0.028064157813788,38272,-1485,-7783,-2958,0.980990290641785 +33229,0.028056120499969,1.18007397651672,0.029685076326132,38272,-1877,-10402,-2775,0.971515595912933 +33231,0.03119263984263,1.18173515796661,0.031587466597557,38272,-1579,-7934,-2928,0.973923921585083 +33233,0.035114619880915,1.17635929584503,0.032402385026217,38272,-1795,-9885,-2736,0.974888205528259 +33235,0.041637718677521,1.18143272399902,0.032751195132732,38272,-1991,-8610,-2914,0.980192124843597 +33237,0.050374012440443,1.17384243011475,0.031220551580191,38272,-2413,-10125,-2744,0.981786072254181 +33239,0.050665978342295,1.17719221115112,0.031543422490358,38272,-1701,-8865,-2916,0.985319674015045 +33241,0.041918095201254,1.17560887336731,0.036784391850233,38272,-1037,-11009,-2678,0.988943219184876 +33243,0.029881363734603,1.18086493015289,0.0394391939044,38272,-541,-9495,-2855,0.991976976394653 +33263,0.026229722425342,1.04018831253052,0.038850143551827,38272,-1195,-7921,-2823,0.978966534137726 +33265,0.01463324483484,1.0274600982666,0.038620267063379,38272,-464,-10328,-2622,0.97995913028717 +33267,0.00285474024713,0.995066285133362,0.0428646504879,38272,-247,-6653,-2788,0.982942640781403 +33269,-0.006562649272382,0.971875429153442,0.042163260281086,38272,-279,-9049,-2574,0.982090353965759 +33271,-0.006127084139735,0.944229662418366,0.044212270528078,38272,-991,-6630,-2771,0.982598841190338 +33273,-0.007900238037109,0.913901329040527,0.045404866337776,38272,-806,-7949,-2528,0.987351298332214 +33275,-0.017032608389855,0.895572483539581,0.045700125396252,38272,-147,-6943,-2753,0.996016025543213 +33277,-0.020549766719341,0.873645126819611,0.043108649551869,38272,-472,-8234,-2547,1.00394856929779 +33279,-0.020711157470942,0.848817348480225,0.042489055544138,38272,-730,-6135,-2767,1.00880396366119 +33281,-0.028862314298749,0.823383510112762,0.046617068350315,38272,1,-7484,-2497,1.00307440757751 +33283,-0.04318281263113,0.799996733665466,0.048482391983271,38272,617,-5845,-2718,0.995055079460144 +33285,-0.044087719172239,0.765802025794983,0.046308796852827,38272,-260,-6215,-2491,0.986541509628296 +33287,-0.046043738722801,0.74659651517868,0.042617455124855,38272,-209,-5662,-2750,0.986005544662476 +33289,-0.045389488339424,0.713054776191711,0.044062126427889,38272,-327,-5679,-2511,0.985897541046143 +33291,-0.052903823554516,0.69022661447525,0.04738050326705,38272,306,-4855,-2709,0.98134034872055 +33293,-0.055040143430233,0.662560403347015,0.046819925308228,38272,55,-5536,-2471,0.975897133350372 +33295,-0.058312732726336,0.642510533332825,0.045811466872692,38272,104,-4611,-2711,0.971411287784576 +33297,-0.062641978263855,0.614451587200165,0.046445861458778,38272,365,-4955,-2468,0.976609408855438 +33299,-0.064723946154118,0.589879214763641,0.044874384999275,38272,139,-3753,-2709,0.979364991188049 +33301,-0.068607784807682,0.579724073410034,0.044677454978228,38272,459,-5881,-2480,0.982761383056641 +33303,-0.071240819990635,0.557433187961578,0.049774039536715,38272,304,-3657,-2668,0.986134171485901 +33305,-0.076270490884781,0.543294727802277,0.053072851151228,38272,698,-5187,-2372,0.990151584148407 +33307,-0.07518095523119,0.514273881912231,0.052554544061422,38272,129,-2743,-2639,0.986553013324738 +33309,-0.074291922152042,0.504901826381683,0.05048805847764,38272,281,-5086,-2394,0.988195776939392 +33311,-0.070214785635471,0.481212943792343,0.04918996989727,38272,-121,-2823,-2653,0.991765320301056 +33313,-0.080220296978951,0.468153864145279,0.050560858100653,38272,1192,-4387,-2383,0.995936095714569 +33315,-0.075677379965782,0.446879655122757,0.055379290133715,38272,-38,-2660,-2601,0.999003350734711 +33317,-0.071328356862068,0.436583966016769,0.054506953805685,38272,42,-4223,-2325,0.994032502174377 +33319,-0.06569167226553,0.42744767665863,0.055979315191507,38272,-228,-3394,-2587,0.993666052818298 +33321,-0.056327316910029,0.415389955043793,0.057150237262249,38272,-554,-3895,-2279,0.989980161190033 +33323,-0.055174022912979,0.407431185245514,0.058568239212036,38272,-36,-3327,-2559,0.991991817951202 +33325,-0.052171092480421,0.405872911214829,0.060945939272642,38272,-135,-4624,-2226,0.987730741500854 +33327,-0.048908360302448,0.40055650472641,0.061465870589018,38272,-256,-3550,-2528,0.9832563996315 +33329,-0.041798532009125,0.38321003317833,0.059790853410959,38272,-561,-3258,-2232,0.980354368686676 +33331,-0.044268183410168,0.386579841375351,0.058541536331177,38272,106,-4097,-2538,0.988520741462708 +33333,-0.045933071523905,0.381902694702148,0.058494597673416,38272,155,-4258,-2236,0.999631881713867 +33335,-0.046011060476303,0.385515570640564,0.057195879518986,38272,-17,-4222,-2536,0.998677253723144 +33337,-0.03896226733923,0.369667917490005,0.057393189519644,38272,-564,-3376,-2238,0.994270026683807 +33339,-0.043379079550505,0.374153286218643,0.057439025491476,38272,273,-4240,-2524,0.98941707611084 +33341,-0.045215647667647,0.383482158184052,0.05978587269783,38272,190,-5518,-2199,0.989670872688293 +33343,-0.03674840554595,0.388962507247925,0.057023286819458,38272,-724,-4648,-2516,0.986588656902313 +33345,-0.029394339770079,0.393225640058518,0.053573753684759,38272,-705,-5443,-2261,0.992309629917145 +33347,-0.028134401887655,0.395043611526489,0.050459962338209,38272,-317,-4603,-2551,0.995698094367981 +33349,-0.023809844627977,0.403877794742584,0.048494707792997,38272,-569,-6081,-2311,1.00325441360474 +33351,-0.01936705596745,0.40105801820755,0.048675417900086,38272,-660,-4494,-2555,1.00431895256042 +33353,-0.019706418737769,0.409700751304626,0.047413971275091,38272,-286,-6300,-2316,0.998555600643158 +33355,-0.020919000729919,0.416469842195511,0.048067323863506,38272,-223,-5543,-2550,0.994620263576508 +33357,-0.024826632812619,0.426140427589417,0.043895706534386,38272,57,-6787,-2347,0.992534518241882 +33359,-0.018393153324723,0.423403441905975,0.041547242552042,38272,-796,-5112,-2587,0.997225821018219 +33361,-0.011318235658109,0.435667544603348,0.040946666151285,38272,-941,-7286,-2373,1.00110185146332 +33363,-0.008649568073452,0.447181165218353,0.042694624513388,38272,-661,-6631,-2571,1.00952172279358 +33365,-0.005228279158473,0.452382206916809,0.039908323436976,38272,-767,-7209,-2379,1.00748193264008 +33367,-0.006214492022991,0.461499601602554,0.039102952927351,38272,-431,-6831,-2588,1.00785624980927 +33369,-0.009641028009355,0.457881212234497,0.038680586963892,38272,-190,-6819,-2387,1.00386142730713 +33371,-0.012196968309581,0.461852461099625,0.038874510675669,38272,-225,-6634,-2582,1.00075972080231 +33373,-0.01271219085902,0.460922628641129,0.038786258548498,38272,-343,-7228,-2378,0.998261451721191 +33375,-0.010913932695985,0.469622164964676,0.034858636558056,38272,-547,-7254,-2603,0.991725921630859 +33377,-0.010279851965606,0.467173248529434,0.031307987868786,38272,22976,32767,-2458,0.989415884017944 +33379,-0.015817174687982,0.472263634204865,0.030199887230992,38414,4013,13405,-2629,0.98946225643158 +33381,-0.014733228832483,0.47142505645752,0.034199848771095,38414,3565,12958,-2418,0.989805221557617 +33383,-0.015245351009071,0.477776825428009,0.037594962865114,38414,3693,13261,-2571,0.987687647342682 +33385,-0.008035935461521,0.485105931758881,0.03845002874732,38414,3064,12171,-2361,0.990798234939575 +33387,0.003293507965282,0.487900733947754,0.036092404276133,38414,2623,13388,-2574,0.994040846824646 +33389,0.018250407651067,0.505970358848572,0.035337615758181,38414,2123,11080,-2390,0.999832093715668 +33391,0.03349744156003,0.535301685333252,0.033966518938542,38414,1942,10815,-2582,1.0034693479538 +33393,0.047354087233543,0.579184591770172,0.029932010918856,38414,1755,8039,-2446,1.00612902641296 +33395,0.059217229485512,0.626744568347931,0.028992369771004,38414,1835,8170,-2610,1.00936985015869 +33415,0.240114167332649,1.43181669712067,0.029535681009293,38414,-1219,-943,-2578,1.01731693744659 +33417,0.25491526722908,1.51026964187622,0.02981735393405,38414,-1842,-9761,-2419,1.01810872554779 +33419,0.263707011938095,1.60111248493195,0.029042871668935,38414,-1087,-9356,-2575,1.01553678512573 +33421,0.282925397157669,1.69353556632996,0.029026975855231,38414,-2704,-14245,-2431,1.01498305797577 +33423,0.306658923625946,1.77415287494659,0.028705721721053,38414,-2868,-11656,-2572,1.01142752170563 +33425,0.321975409984589,1.85273408889771,0.025512602180243,38414,-3162,-16434,-2479,1.01070177555084 +33427,0.330079704523087,1.92736113071442,0.022626779973507,38414,-2197,-14056,-2609,1.01140451431274 +33429,0.337731838226318,2.00675797462463,0.019309615716338,38414,-2977,-19653,-2563,1.00921094417572 +33431,0.342447698116302,2.07666993141174,0.016296995803714,38414,-2251,-16566,-2650,1.00907671451569 +33433,0.339299529790878,2.14276933670044,0.015551737509668,38414,-2346,-21633,-2621,1.00131368637085 +33435,0.337110161781311,2.19777870178223,0.019558096304536,38414,-1801,-18008,-2626,1.00248956680298 +33437,0.339903086423874,2.24581623077393,0.021289488300681,38414,-2902,-22802,-2568,1.00205886363983 +33439,0.338857710361481,2.29534816741943,0.01936393417418,38414,-2029,-19841,-2625,1.00453329086304 +33441,0.336002647876739,2.32316017150879,0.016796432435513,38414,-2559,-23454,-2637,1.00369596481323 +33443,0.331208527088165,2.35549879074097,0.014536580070853,38414,-1773,-20341,-2658,1.00428223609924 +33445,0.328352570533752,2.37226104736328,0.014953934587538,38414,-2553,-24333,-2676,1.00654518604279 +33447,0.318007469177246,2.39665150642395,0.014769128523767,38414,-1305,-21258,-2656,1.01144564151764 +33449,0.308726668357849,2.39855766296387,0.011656696908176,38414,-1881,-24585,-2730,1.01785945892334 +33451,0.296039223670959,2.39497089385986,0.00431742426008,38414,-931,-20143,-2729,1.01510381698608 +33453,0.285999864339828,2.38949394226074,0.000499760615639,38414,-1567,-19409,-2878,1.01088917255402 +33455,0.277930527925491,2.38141584396362,0.001581370248459,38557,-1103,-19629,-2752,1.00183200836182 +33457,0.268110990524292,2.36482119560242,0.002090621273965,38557,-1390,-23607,-2874,1.00247097015381 +33459,0.260635584592819,2.32679390907288,-0.000388339423807,38557,-991,-17601,-2769,1.00361430644989 +33461,0.252152770757675,2.28831958770752,-0.002543105743825,38557,-1302,-21671,-2938,1.00347697734833 +33463,0.245470508933067,2.23065114021301,-0.001983339199796,38557,-915,-15685,-2785,1.00312769412994 +33465,0.233127772808075,2.19748854637146,-0.004263168666512,38557,-797,-21426,-2967,1.01157689094543 +33467,0.200240567326546,2.09356832504272,-0.013305463828147,38557,221,-19279,-3083,1.0196293592453 +33469,0.183014065027237,2.0243546962738,-0.01777864061296,38557,595,-13526,-2905,1.01886940002441 +33471,0.169247210025787,1.95913767814636,-0.01882640644908,38557,193,-16830,-3155,1.0137894153595 +33473,0.164754286408424,1.88703501224518,-0.015505712479353,38557,-106,-12086,-2898,1.01468539237976 +33475,0.164754286408424,1.88703501224518,-0.015505712479353,38557,-106,-12086,-2898,1.01468539237976 +33477,0.149610951542854,1.75075221061707,-0.014507614076138,38557,124,-10788,-2898,1.00922453403473 +33479,0.14024643599987,1.67025685310364,-0.019247218966484,38557,257,-12399,-3163,1.01194274425507 +33481,0.137007206678391,1.58688569068909,-0.021297555416823,38557,116,-8267,-2952,1.01439428329468 +33483,0.126932308077812,1.5052193403244,-0.024499360471964,38557,494,-10205,-3221,1.01251101493835 +33485,0.126932308077812,1.5052193403244,-0.024499360471964,38557,494,-10205,-3221,1.01251101493835 +33487,0.100422993302345,1.31768643856049,-0.028900295495987,38557,910,-6611,-3271,1.01025927066803 +33489,0.090132772922516,1.23751103878021,-0.029146743938327,38557,1238,-879,-3022,1.00893020629883 +33491,0.094542026519775,1.15455627441406,-0.027257511392236,38557,-77,-4725,-3249,1.00307881832123 +33493,0.086748026311398,1.0849906206131,-0.023150129243732,38557,1088,-2832,-2989,0.999485373497009 +33495,0.086748026311398,1.0849906206131,-0.023150129243732,38557,1088,-2832,-2989,0.999485373497009 +33497,0.076793424785137,0.931575059890747,-0.025986233726144,38557,1098,-791,-3014,0.974964499473572 +33499,0.073862098157406,0.847266256809235,-0.026223458349705,38557,762,-276,-3224,0.97862708568573 +33501,0.067940331995487,0.793301999568939,-0.021803490817547,38557,1199,-327,-2992,0.979628384113312 +33503,0.075268179178238,0.723580300807953,-0.016326393932104,38557,8,473,-3099,0.987695693969727 +33505,0.074436999857426,0.672507107257843,-0.010563942603767,38557,733,1007,-2920,0.99496591091156 +33507,0.083279393613339,0.610622823238373,-0.006303118076175,38557,-229,1590,-2972,1.00072085857391 +33509,0.082563675940037,0.557418763637543,-0.006805636454374,38557,597,2671,-2896,1.00708878040314 +33511,0.085226342082024,0.501586139202118,-0.007882249541581,38557,161,2812,-2986,1.0059118270874 +33513,0.081551045179367,0.460504233837128,-0.009319718927145,38557,811,3103,-2916,1.00535464286804 +33515,0.079245395958424,0.423379778862,-0.006664280313998,38557,589,2664,-2971,1.00751984119415 +33517,0.085979722440243,0.398169547319412,-0.009968836791813,38557,-11,2804,-2923,1.00302290916443 +33519,0.100185133516788,0.383643746376038,-0.014092507772148,38557,-958,1639,-3061,1.00420355796814 +33521,0.115744657814503,0.367902189493179,-0.015580529347062,38557,-1094,2520,-2964,0.99842244386673 +33523,0.119542807340622,0.360733360052109,-0.015195971354842,38557,-556,1452,-3076,1.00400066375732 +33525,0.127809211611748,0.345985412597656,-0.010189244523645,38557,-779,8143,-2931,1.00566101074219 +33527,0.132192894816399,0.34817162156105,-0.008060093037784,38557,-835,1874,-2993,1.00272417068481 +33529,0.14330992102623,0.346917062997818,-0.009314312599599,38557,-1244,2648,-2927,1.0049010515213 +33531,0.14694932103157,0.365929901599884,-0.011338444426656,38557,-1062,363,-3036,1.00296664237976 +33533,0.159529626369476,0.367285251617432,-0.010069009847939,38557,-1628,2144,-2935,1.00552654266357 +33535,0.170896396040916,0.388895958662033,-0.007094754837453,38557,-2048,-221,-2989,1.01207864284515 +33537,0.191542372107506,0.40985107421875,-0.003244923893362,38557,-2721,95,-2890,1.01761984825134 +33539,0.201560243964195,0.435091823339462,-0.000110537592263,38557,-2507,-1273,-2913,1.02013993263245 +33541,0.207684174180031,0.455286026000977,0.004137319978327,38557,-1983,-559,-2841,1.01973009109497 +33543,0.205526202917099,0.476496040821075,0.00411462970078,38557,-1766,-1721,-2870,1.0185923576355 +33545,0.206692934036255,0.515024125576019,0.000341759965522,38557,-1685,-2806,-2868,1.02265894412994 +33547,0.216444671154022,0.552048623561859,-0.000241210029344,38557,-2874,-4176,-2934,1.01589787006378 +33549,0.224849656224251,0.590775728225708,-0.002058455720544,38557,-2541,-4020,-2886,1.00621628761292 +33551,0.227374151349068,0.625700056552887,-0.001284730038606,38557,-2618,-5354,-2961,0.997953832149506 +33553,0.222960874438286,0.674550354480743,-0.000995849259198,38557,-1680,-6097,-2881,0.989240050315857 +33555,0.225446701049805,0.708134949207306,-0.000808325887192,38557,-2674,-6769,-2973,0.989596307277679 +33557,0.22670590877533,0.747441232204437,-0.001156411948614,38557,-2225,-6648,-2885,0.988349616527557 +33559,0.226900488138199,0.78654944896698,0.002820945344865,38557,-2621,-8649,-2947,0.994404554367065 +33561,0.223164394497871,0.818573415279388,0.004463859368116,38557,-1903,-7375,-2849,0.996779382228851 +33563,0.216677203774452,0.851289689540863,0.004701948724687,38557,-2062,-6235,-2940,1.00186741352081 +33565,0.209025889635086,0.878611862659454,0.007441684603691,38557,-1502,-7611,-2831,1.00435483455658 +33567,0.197986334562302,0.917603254318237,0.011508408002555,38557,-1512,-10721,-2876,1.00710594654083 +33569,0.187313705682754,0.948007702827454,0.012019677087665,38557,-1049,-9112,-2802,1.01145362854004 +33571,0.175793692469597,0.980786979198456,0.009883359074593,38557,-1170,-11596,-2903,1.01375734806061 +33573,0.171519324183464,1.00288355350494,0.010534936562181,38557,-1344,-9621,-2814,1.01690578460693 +33575,0.163051307201386,1.03273701667786,0.012127763591707,38557,-1224,-12557,-2882,1.01567280292511 +33577,0.156382754445076,1.04897725582123,0.013152450323105,38557,-1009,-10205,-2799,1.0160847902298 +33579,0.150375321507454,1.05700135231018,0.009632419794798,38557,-1265,-11741,-2928,1.00995516777039 +33581,0.133929044008255,1.07114160060883,0.007955812849104,38557,-38,-10730,-2838,1.00875234603882 +33583,0.120119646191597,1.08262014389038,0.009911777451634,38557,-263,-12770,-2936,1.00064635276794 +33585,0.103376992046833,1.09529495239258,0.008806169964373,38557,381,-11344,-2835,0.991761267185211 +33587,0.090264268219471,1.09168720245361,0.004280566703528,38557,143,-12213,-3007,0.981594383716583 +33589,0.073458470404148,1.09530353546143,0.004010464996099,38557,791,-11076,-2873,0.982137560844421 +33591,0.061927884817124,1.08259570598602,0.004379738122225,38557,468,-11785,-3011,0.992117464542389 +33593,0.047751571983099,1.07697451114655,0.004155251197517,38557,959,-10529,-2876,1.00214374065399 +33595,0.039692435413599,1.0603266954422,0.004333276301622,38557,573,-11501,-3014,1.01266705989838 +33597,0.033064179122448,1.04412722587585,0.002369834342971,38557,626,-9668,-2893,1.01340270042419 +33599,0.023708023130894,1.02792823314667,0.002346734981984,38557,919,-11366,-3040,1.01403856277466 +33601,0.014074187725782,1.00905311107636,0.004277961794287,38557,1118,-9328,-2884,1.00919616222382 +33603,0.002190532861277,0.995776414871216,0.002469440223649,38557,1457,-11398,-3039,1.01144134998322 +33605,-0.009893198497593,0.969551920890808,0.001266117324121,38557,1651,-8578,-2909,1.00720882415771 +33607,-0.022185802459717,0.949837923049927,0.002228986937553,38557,1896,-10534,-3041,1.00474143028259 +33609,-0.024459538981319,0.916457772254944,0.003882055403665,38557,1180,-7629,-2896,1.00430130958557 +33611,-0.026752900332213,0.891207695007324,3.4293709177291E-05,38557,1281,-9500,-3060,1.00287508964539 +33613,-0.029794836416841,0.857964217662811,-0.002829782199115,38557,1338,-7101,-2946,1.00260055065155 +33615,-0.036389097571373,0.834360778331757,-0.002774221589789,38557,1779,-8974,-3086,0.995724320411682 +33617,-0.035361241549254,0.790428519248962,-0.002260111505166,38557,1158,-5642,-2947,0.995312929153442 +33619,-0.035815410315991,0.758696615695953,-0.000773564213887,38557,1365,-7414,-3053,0.995916247367859 +33621,-0.034835640341044,0.720290064811706,0.002678260672838,38557,1186,-5274,-2916,1.00091230869293 +33623,-0.033766243606806,0.687372267246246,0.0029204019811,38557,1254,-6400,-3001,1.00373888015747 +33625,-0.03371212631464,0.661053061485291,0.005038139410317,38557,1268,-5502,-2903,1.00852370262146 +33627,-0.029168071225286,0.633764743804932,0.004191027022898,38557,969,-6134,-2976,1.00749158859253 +33629,-0.02580969594419,0.611339092254639,0.003129734657705,38557,949,-5256,-2918,1.00880265235901 +33649,0.070728965103626,0.31803947687149,-0.001032008556649,38557,-1201,-1721,-2947,1.00133883953094 +33651,0.082179293036461,0.299520611763,0.00468316487968,38557,-1301,-2000,-2924,1.00386452674866 +33653,0.095316708087921,0.28156703710556,0.012983087450266,38557,-1479,-1419,-2851,1.00209176540375 +33655,0.108226239681244,0.273105770349503,0.014751505106688,38557,-1854,-2326,-2801,1.0057065486908 +33657,0.1256413012743,0.250018447637558,0.011904386803508,38557,-2255,-631,-2857,1.00198173522949 +33659,0.135575875639915,0.241347089409828,0.011061243712902,38557,-2121,-1808,-2836,1.0041047334671 +33661,0.13996222615242,0.231185287237167,0.011388448998332,38557,-1573,-1303,-2859,1.01313984394073 +33663,0.140915676951408,0.229396790266037,0.006789156235754,38557,-1608,-2124,-2881,1.01588368415833 +33665,0.150874465703964,0.229343190789223,0.002443968085572,38557,-2177,-2013,-2920,1.01846921443939 +33667,0.15659399330616,0.239785209298134,0.002978882752359,38557,-2253,-3184,-2926,1.01725137233734 +33669,0.166297778487206,0.225241348147392,0.00972041580826,38557,-2435,-933,-2870,1.01285362243652 +33671,0.164128705859184,0.2170200496912,0.011403665877879,38557,-1871,-1491,-2826,1.00684320926666 +33673,0.16308231651783,0.215663388371468,0.008499622344971,38557,-1679,-1747,-2877,0.999882638454437 +33675,0.166464626789093,0.222789198160171,0.005088405683637,38557,-2374,-2697,-2904,0.99096542596817 +33677,0.168871313333511,0.237139701843262,0.005863102618605,38557,-2072,-3192,-2895,0.991137802600861 +33679,0.170475333929062,0.24366295337677,0.010310539975762,38557,-2379,-3015,-2849,0.985819876194 +33681,0.165553510189056,0.251621156930923,0.011144767515361,38557,-1565,-2964,-2858,0.988156974315643 +33683,0.15938076376915,0.257015287876129,0.015230320394039,38557,-1697,-3167,-2789,0.993932664394379 +33685,0.153754681348801,0.273112386465073,0.017546381801367,38557,-1404,-3883,-2812,0.997249603271484 +33687,0.159167781472206,0.267148464918137,0.016095329076052,38557,-2577,-2548,-2776,0.999779939651489 +33689,0.156255692243576,0.275604873895645,0.015127236954868,38557,-1693,-3404,-2827,0.998775243759155 +33691,0.158093899488449,0.273743063211441,0.014748565852642,38557,-2362,-2970,-2792,1.00235664844513 +33693,0.15482322871685,0.276953756809235,0.014203033410013,38557,-1706,-3082,-2832,0.999597191810608 +33695,0.148938402533531,0.284917682409286,0.018020614981651,38557,-1715,-3895,-2754,1.00105333328247 +33697,0.136220946907997,0.2938551902771,0.01944413036108,38557,-817,-3774,-2794,1.00426757335663 +33699,0.125291049480438,0.310342639684677,0.016064707189798,38557,-1026,-4969,-2784,1.00978982448578 +33701,0.123924538493156,0.317943692207336,0.016173366457224,38557,-1499,-4077,-2815,1.01535749435425 +33703,0.12700742483139,0.333023607730865,0.014758614823222,38557,-2093,-5291,-2796,1.01766228675842 +33705,0.126721605658531,0.346076637506485,0.014266136102378,38557,-1661,-4935,-2827,1.01461517810822 +33707,0.115396626293659,0.364720612764358,0.013331188820303,38557,-923,-6129,-2823,1.00362980365753 +33709,0.104465648531914,0.364877432584763,0.014352432452142,38557,-620,-4359,-2826,1.00212180614471 +33711,0.093460060656071,0.373161256313324,0.012591477483511,38557,-638,-5610,-2840,1.00185656547546 +33713,0.080626055598259,0.387067764997482,0.014020782895386,38557,-175,-5746,-2828,1.00511038303375 +33715,0.071303106844425,0.39833527803421,0.017120074480772,38557,-424,-6325,-2791,1.00137865543365 +33717,0.060858711600304,0.411959648132324,0.01976159773767,38557,-86,-6180,-2787,1.00213801860809 +33719,0.054810617119074,0.407860428094864,0.019552296027541,38557,-394,-5469,-2755,1.00158298015594 +33721,0.0506921261549,0.413105607032776,0.017637738958001,38557,-406,-5697,-2800,0.998978793621063 +33723,0.038249395787716,0.416743755340576,0.018405819311738,38557,322,-6267,-2769,0.996562242507935 +33725,0.022223804146052,0.428264915943146,0.019788984209299,38557,849,-6469,-2784,0.991945683956146 +33727,0.020826714113355,0.424417614936829,0.023011965677142,38557,-195,-5973,-2721,0.984286487102508 +33729,0.020839085802436,0.423003435134888,0.023430524393916,38557,-277,-5579,-2758,0.975328862667084 +33731,0.014313970692456,0.422691285610199,0.025319905951619,38557,279,-6313,-2692,0.9721559882164 +33733,0.000678457960021,0.419129490852356,0.026602737605572,38557,993,-5481,-2734,0.9703608751297 +33735,-0.00730859907344,0.418543636798859,0.02647159062326,38557,753,-6338,-2670,0.969488024711609 +33737,-0.01592530310154,0.409060329198837,0.025735525414348,38557,887,-5023,-2737,0.96942126750946 +33739,-0.02360817976296,0.408236503601074,0.023822521790862,38557,1015,-6260,-2696,0.977814257144928 +33741,-0.02592496201396,0.400390416383743,0.021114086732268,38557,602,-5123,-2767,0.987090170383453 +33743,-0.028679402545095,0.396403133869171,0.017099816352129,38557,763,-5938,-2774,0.991420209407806 +33745,-0.028486100956798,0.379170387983322,0.015970047563315,38557,484,-4247,-2801,0.991275787353516 +33747,-0.037395022809506,0.374586701393127,0.014867073856294,38557,1368,-5636,-2797,0.989422082901001 +33749,-0.041036959737539,0.365043252706528,0.016818640753627,38557,967,-4687,-2795,0.992709696292877 +33751,-0.039895717054606,0.355926364660263,0.018312545493245,38557,718,-5098,-2751,0.992093443870544 +33753,-0.029623940587044,0.341673582792282,0.018523532897234,38557,-163,-4098,-2781,0.996515572071075 +33755,-0.018903601914644,0.322823971509934,0.018369242548943,38557,-283,-3941,-2742,0.994792819023132 +33757,-0.014833305031061,0.317193239927292,0.018568562343717,38557,88,-4435,-2779,0.996534466743469 +33759,-0.012581048533321,0.308373719453812,0.019553054124117,38557,243,-4491,-2721,0.990940093994141 +33761,-0.016763590276241,0.309966653585434,0.018798729404807,38557,725,-4913,-2776,0.985199749469757 +33763,-0.01621650159359,0.292103052139282,0.021958366036415,38557,438,-3634,-2691,0.979067265987396 +33765,-0.012659071944654,0.274269223213196,0.022312868386507,38557,130,-3065,-2749,0.977995157241821 +33767,-0.001146125490777,0.254920184612274,0.020680900663138,38557,-555,-2974,-2684,0.981917321681976 +33769,0.000502281764057,0.254685312509537,0.017807701602578,38557,94,-4084,-2777,0.988333642482758 +33771,0.003163577523083,0.245756730437279,0.017895188182592,38557,28,-3611,-2708,0.996741473674774 +33773,0.012376872822642,0.236837923526764,0.018649227917194,38557,-603,-3243,-2769,0.997942090034485 +33775,0.019522875547409,0.229681566357613,0.020266175270081,38557,-566,-3507,-2686,1.00180196762085 +33777,0.027024803683162,0.222761884331703,0.023975159972906,38557,-687,-3213,-2729,0.998612225055695 +33779,0.028826590627432,0.217513710260391,0.027956100180745,38557,-338,-3463,-2594,0.999742746353149 +33781,0.032773450016975,0.199955672025681,0.034425139427185,38557,-517,-2145,-2654,0.996611475944519 +33783,0.035745620727539,0.195424512028694,0.041165109723806,38557,-528,-3185,-2426,0.994318544864654 +33785,0.039883796125651,0.179081380367279,0.039163839071989,38557,-635,-1946,-2614,0.997469902038574 +33787,0.04634889960289,0.180449292063713,0.033848218619824,38557,-956,-3377,-2502,0.997612595558166 +33789,0.053187910467386,0.17633181810379,0.030889336019755,38557,-1028,-2790,-2666,0.999578893184662 +33791,0.053517770022154,0.170526176691055,0.031860552728176,38557,-640,-2702,-2516,0.992981255054474 +33793,0.05524479970336,0.158802330493927,0.037764351814985,38557,-702,-1996,-2613,0.991463661193848 +33795,0.065024517476559,0.145584598183632,0.03641876205802,38557,-1512,-1762,-2450,0.986766397953033 +33797,0.076410293579102,0.141880825161934,0.031830452382565,38557,-1713,-2319,-2648,0.987022519111633 +33799,0.083402648568153,0.13229513168335,0.030123775824905,38557,-1635,-1795,-2517,0.983444035053253 +33801,0.089245662093163,0.128855556249619,0.033510569483042,38557,-1525,-2136,-2631,0.984653770923614 +33803,0.094679765403271,0.118706949055195,0.038172475993633,38557,-1731,-1519,-2413,0.988751828670502 +33805,0.094609618186951,0.127146646380425,0.037369180470705,38557,-1208,-2942,-2598,0.991226196289062 +33807,0.092775352299213,0.129160940647125,0.034010194242001,38557,-1205,-2538,-2455,0.997193217277527 +33809,0.085499003529549,0.129979014396667,0.031941413879395,38557,-590,-2420,-2629,0.993069708347321 +33811,0.082687273621559,0.125737175345421,0.030313912779093,38557,-1000,-2021,-2494,0.987285733222961 +33813,0.084703624248505,0.122914247214794,0.02783389762044,38557,-1269,-2041,-2652,0.979035377502441 +33815,0.09056481719017,0.125979140400887,0.026838250458241,38557,-1779,-2532,-2531,0.979158878326416 +33817,0.093348875641823,0.118097983300686,0.028072956949473,38557,-1477,-1592,-2646,0.981742560863495 +33819,0.088271453976631,0.116469107568264,0.03273119777441,38557,-976,-2025,-2449,0.981998980045319 +33821,0.088730394840241,0.1065668836236,0.036066088825464,38557,-1270,-1261,-2585,0.981088817119598 +33823,0.088461220264435,0.12069445848465,0.035740558058024,38557,-1346,-3204,-2406,0.984610617160797 +33825,0.08923003077507,0.128339543938637,0.034806311130524,38557,-1325,-2811,-2587,0.98637181520462 +33827,0.079565718770027,0.141907781362534,0.034481141716242,38557,-558,-3484,-2423,0.98963326215744 +33829,0.080827549099922,0.132847562432289,0.03683577850461,38557,-1263,-1668,-2567,0.991584897041321 +33831,0.082364715635777,0.125191733241081,0.038659136742354,38557,-1437,-1680,-2369,0.992340445518494 +33833,0.074069261550903,0.136383339762688,0.037944175302982,38557,-507,-3152,-2553,0.998870611190796 +33835,0.069454088807106,0.151198178529739,0.035811007022858,38557,-817,-3700,-2406,0.998648583889008 +33837,0.067966125905514,0.161481156945229,0.03537955135107,38557,-928,-3441,-2564,0.99109011888504 +33839,0.065446212887764,0.156988173723221,0.036885570734739,38557,-908,-2407,-2380,0.980703055858612 +33841,0.058900617063046,0.158958360552788,0.034729108214378,38557,-453,-2807,-2562,0.967331528663635 +33843,0.057784143835306,0.150668486952782,0.033806785941124,38557,-895,-2025,-2406,0.962607383728027 +33845,0.057917419821024,0.153167471289635,0.037264380604029,38557,-930,-2756,-2539,0.964284658432007 +33847,0.059190958738327,0.155319824814796,0.040103618055582,38557,-1113,-2855,-2334,0.96875673532486 +33849,0.060564693063498,0.159553244709969,0.035804711282253,38557,-1073,-2969,-2542,0.970386147499084 +33851,0.059488255530596,0.168040096759796,0.030939307063818,38557,-975,-3528,-2443,0.97500342130661 +33853,0.05787829682231,0.172150567173958,0.033648174256086,38557,-838,-3147,-2552,0.978436648845673 +33855,0.052804343402386,0.176319926977158,0.037596508860588,38557,-577,-3351,-2350,0.980002522468567 +33857,0.043699290603399,0.171180009841919,0.037449382245541,38557,-109,-2479,-2520,0.980808138847351 +33859,0.034650228917599,0.182213082909584,0.037646777927876,38557,-1,-3935,-2342,0.978374123573303 +33861,0.033543914556503,0.187333986163139,0.038216017186642,38557,-538,-3454,-2508,0.973627030849457 +33875,0.005304201040417,0.194389879703522,0.036877423524857,38557,-96,-3106,-2333,0.977688729763031 +33877,0.002412303583696,0.190748766064644,0.036340285092592,38557,58,-2928,-2496,0.981285154819488 +33879,0.003180698025972,0.177436098456383,0.036686278879643,38557,-175,-2187,-2327,0.979112088680267 +33881,-0.004002605099231,0.176149502396584,0.037488952279091,38557,469,-2897,-2482,0.977002441883087 +33883,-0.012205845676363,0.177715212106705,0.040588539093733,38557,732,-3263,-2274,0.980860710144043 +33885,-0.016459967941046,0.175614938139915,0.043326664716005,38557,455,-2841,-2435,0.98023796081543 +33887,-0.02187329530716,0.172670528292656,0.041813008487225,38557,711,-2862,-2251,0.978232502937317 +33889,-0.025243923068047,0.15889336168766,0.040667451918125,38557,541,-1771,-2446,0.976431846618652 +33891,-0.026910269632936,0.155969440937042,0.043213285505772,38557,549,-2594,-2224,0.97322428226471 +33893,-0.02216218598187,0.150035053491592,0.046138186007738,38557,-58,-2205,-2401,0.971858501434326 +33895,-0.025127522647381,0.159279316663742,0.044323243200779,38557,632,-3522,-2208,0.976301312446594 +33897,-0.02580832503736,0.155816942453384,0.042715474963188,38557,406,-2466,-2417,0.979373812675476 +33899,-0.025277430191636,0.147425502538681,0.039703492075205,38557,406,-2068,-2253,0.978695809841156 +33901,-0.026080414652824,0.1438277810812,0.041957400739193,38557,2245,-1740,-2415,0.984107494354248 +33903,-0.031695786863566,0.134153440594673,0.045135319232941,38557,1288,-1658,-2174,0.99142861366272 +33905,-0.035053823143244,0.127801612019539,0.04300919175148,38557,1088,-1751,-2400,0.997592210769653 +33907,-0.031996339559555,0.120765201747417,0.043355274945498,38557,707,-1609,-2182,1.00258755683899 +33909,-0.027155408635736,0.126586392521858,0.046565417200327,38557,419,-2587,-2368,0.997488379478455 +33911,-0.021744946017861,0.128651022911072,0.052201088517904,38557,406,-2373,-2070,0.990339636802673 +33913,-0.02218727208674,0.13310980796814,0.053207233548164,38557,755,-2569,-2313,0.981028437614441 +33915,-0.017803151160479,0.12959785759449,0.054563704878092,38557,443,-1981,-2033,0.978144824504852 +33917,-0.003931999672204,0.118995398283005,0.055706441402435,38557,-505,-1274,-2286,0.976934790611267 +33919,0.005115047562867,0.114539295434952,0.052132602781057,38557,-239,-1671,-2047,0.976050794124603 +33921,0.010326016694307,0.108682714402676,0.051109865307808,38557,-73,-1449,-2308,0.978340566158295 +33923,0.012358347885311,0.119055010378361,0.05435385927558,38557,158,-2794,-2014,0.982725262641907 +33925,0.019796742126346,0.117932572960854,0.056023295968771,38557,-355,-1906,-2264,0.983942627906799 +33927,0.026010997593403,0.129166543483734,0.055525224655867,38557,-354,-2995,-1993,0.98338770866394 +33929,0.034570261836052,0.123037576675415,0.059656862169504,38557,-641,-1609,-2229,0.979408442974091 +33931,0.036618132144213,0.118394620716572,0.063805304467678,38557,-210,-1672,-1875,0.981148898601532 +33933,0.036880251020193,0.121941573917866,0.063218228518963,38557,-76,-2270,-2193,0.992239356040955 +33935,0.044948432594538,0.112875044345856,0.05969650298357,38557,-777,-1250,-1912,0.9950070977211 +33937,0.05535688623786,0.107844658195972,0.059239476919174,38557,-1069,-1436,-2209,0.993021488189697 +33939,0.062202729284763,0.111091323196888,0.060529552400112,38557,-5501,-31478,-1903,0.991149365901947 +33941,0.067395955324173,0.118855059146881,0.061678986996412,38557,-1641,-7455,-2182,0.988171637058258 +33943,0.0773915797472,0.112510874867439,0.058412194252014,38557,-2264,-6392,-1928,0.988856136798858 +33945,0.08090191334486,0.111958757042885,0.052618741989136,38557,-1743,-6792,-2234,0.985373020172119 +33947,0.081499248743057,0.10738355666399,0.052883423864842,38557,-1665,-6454,-1968,0.982240974903107 +33949,0.083111099898815,0.098895497620106,0.058797314763069,38557,-1667,-6062,-2182,0.978474140167236 +33951,0.077990844845772,0.084958493709564,0.062163677066565,38557,-1231,-5444,-1848,0.980032444000244 +33953,0.078908681869507,0.063668496906757,0.061222556978464,38557,-1584,-4656,-2154,0.988493800163269 +33955,0.08422626554966,0.057029701769352,0.058445740491152,38557,-2130,-5527,-1889,0.997990190982819 +33957,0.092324189841747,0.031678203493357,0.055745016783476,38557,-2325,-3910,-2181,1.00346398353577 +33959,0.093068949878216,0.010188168846071,0.054484855383635,38557,-1985,-3694,-1917,1.00012493133545 +33961,0.085624366998673,-0.024776792153716,0.055713724344969,38557,-1154,-2394,-2171,0.99360603094101 +33963,0.070437364280224,-0.051411963999271,0.054077498614788,38557,-491,-2297,-1887,0.989497244358063 +33965,0.064249604940415,-0.074605762958527,0.052135787904263,38557,-963,-2476,-2185,0.990903675556183 +33967,0.066012725234032,-0.101511672139168,0.05400250479579,38557,-1647,-1408,-1861,0.992490231990814 +33969,0.064664483070374,-0.124536119401455,0.055062279105187,38557,-1337,-1702,-2154,0.990413069725037 +33971,0.060283225029707,-0.155227288603783,0.053765542805195,38557,-1126,-180,-1835,0.98808616399765 +33973,0.056912485510111,-0.179370567202568,0.05580160394311,38557,-1098,-740,-2137,0.986875593662262 +33975,0.052920836955309,-0.211681753396988,0.060684982687235,38557,-1037,957,-1723,0.983973264694214 +33977,0.037050686776638,-0.239906087517738,0.059357061982155,38557,-20664,-28847,-2099,0.9814293384552 +33979,0.02243877761066,-0.271607518196106,0.058878514915705,38557,-3289,-2946,-1718,0.979838490486145 +33981,0.014404029585421,-0.291636645793915,0.059185180813074,38557,-3684,-4141,-2086,0.980792582035065 +33983,0.008246056735516,-0.302962839603424,0.060688994824886,38557,-3698,-3789,-1680,0.986386656761169 +33985,0.000740377057809,-0.322080820798874,0.060898050665856,38557,-3552,-3653,-2060,0.983320951461792 +33987,-0.010217152535915,-0.351128876209259,0.057027187198401,38557,-3080,-1612,-1700,0.977126896381378 +33989,-0.024633729830384,-0.39382603764534,0.053347282111645,38557,-2712,-796,-2098,0.972834229469299 +33991,-0.044849239289761,-0.422470808029175,0.052822064608336,38557,-1865,-329,-1721,0.973200559616089 +33993,-0.059083111584187,-0.454497039318085,0.051495432853699,38557,-2233,-516,-2097,0.978580296039581 +33995,-0.075968585908413,-0.479466170072556,0.049778871238232,38557,-1583,524,-1726,0.982775270938873 +33997,-0.100992746651173,-0.510435879230499,0.050363067537546,38557,-845,412,-2091,0.987161815166473 +33999,-0.124074801802635,-0.552274167537689,0.050077021121979,38557,-329,3135,-1694,0.981754183769226 +34001,-0.142908349633217,-0.586411416530609,0.045936908572912,38557,-650,1967,-2107,0.974486827850342 +34003,-0.163558885455132,-0.615267932415008,0.04432237893343,38557,169,3478,-1744,0.971289038658142 +34005,-0.188426658511162,-0.624125957489014,0.04583990201354,38557,488,965,-2095,0.972779273986816 +34007,-0.201728612184525,-0.649878919124603,0.04623905941844,38557,317,4089,-1710,0.973589062690735 +34025,-0.317531496286392,-0.762201130390167,0.041901994496584,38557,978,-76,-2053,0.993740320205688 +34027,-0.315350592136383,-0.773062169551849,0.044386953115463,38557,1594,1493,-1664,0.994368135929108 +34029,-0.323103815317154,-0.774671614170074,0.045926436781883,38557,1837,-612,-2011,0.988535344600678 +34031,-0.330210626125336,-0.780713856220245,0.047236990183592,38557,2637,1583,-1618,0.981763482093811 +34033,-0.33677339553833,-0.788335144519806,0.049009952694178,38557,2084,324,-1976,0.975000739097595 +34035,-0.3386609852314,-0.799714088439941,0.048841092735529,38557,2529,2588,-1593,0.974148035049438 +34037,-0.334759265184402,-0.797002851963043,0.046811949461699,38557,1445,29,-1977,0.978581428527832 +34039,-0.326157540082932,-0.805185556411743,0.046986822038889,38557,1705,2759,-1609,0.988096237182617 +34041,-0.316342055797577,-0.810999870300293,0.048631239682436,38557,890,1166,-1951,0.988225162029266 +34043,-0.310343086719513,-0.815003216266632,0.051366914063692,38557,1780,2953,-1541,0.98793613910675 +34045,-0.303636223077774,-0.830527603626251,0.052501015365124,38557,1061,2475,-1911,0.984049379825592 +34047,-0.299732595682144,-0.828001260757446,0.052984599024057,38557,1894,3036,-1507,0.980303227901459 +34049,-0.292368322610855,-0.831367969512939,0.052359368652105,38557,979,1959,-1897,0.981474995613098 +34051,-0.280416071414948,-0.825688481330872,0.049657937139273,38557,1099,-26284,-1551,0.985470652580261 +34053,-0.256935328245163,-0.821095049381256,0.051461856812239,39004,-568,-3379,-1890,0.990041255950928 +34055,-0.234414637088776,-0.812531173229218,0.055892128497362,39004,-304,-1980,-1473,0.987204074859619 +34057,-0.225702181458473,-0.785918593406677,0.056953676044941,39004,135,-5174,-1838,0.991486430168152 +34059,-0.215908020734787,-0.767844557762146,0.05530433729291,39004,401,-3100,-1472,0.994816601276398 +34061,-0.195970788598061,-0.759511470794678,0.052473850548267,39004,-1009,-3973,-1855,0.996251881122589 +34063,-0.17017987370491,-0.766346156597137,0.05140870064497,39004,-1404,-1062,-1505,0.995790839195251 +34065,-0.158585220575333,-0.77098274230957,0.049724269658327,39004,-880,-2605,-1861,0.994592905044556 +34067,-0.153577715158463,-0.780949950218201,0.049943845719099,39004,-134,-324,-1516,1.00075685977936 +34069,-0.138970658183098,-0.791719496250153,0.049560379236937,39004,-1319,-1585,-1849,1.0019246339798 +34071,-0.122177474200726,-0.790120780467987,0.048956204205752,39004,-1436,-722,-1516,0.995993256568909 +34073,-0.105099141597748,-0.790169477462769,0.048553515225649,39004,-1938,-2086,-1843,0.988600492477417 +34075,-0.092618376016617,-0.799606263637543,0.048064183443785,39004,-1558,515,-1509,0.979885995388031 +34077,-0.081753358244896,-0.821941137313843,0.050086639821529,39004,-1795,262,-1820,0.977463841438293 +34079,-0.066755212843418,-0.826042830944061,0.052468985319138,39004,-2135,862,-1445,0.980121970176697 +34081,-0.051118403673172,-0.828046202659607,0.053197506815195,39004,-2555,-795,-1785,0.986457109451294 +34083,-0.036040779203177,-0.829834640026093,0.055224571377039,39004,-2630,1060,-1402,0.984131276607513 +34085,-0.02713736332953,-0.837344288825989,0.061742328107357,39004,-2411,46,-1713,0.983381927013397 +34087,-0.02034123800695,-0.856784403324127,0.064908981323242,39004,-2276,3089,-1267,0.985921025276184 +34089,-0.010936416685581,-0.857364237308502,0.060733910650015,39004,-2678,-29222,-1704,0.987461149692535 +34091,-0.001592274638824,-0.864386320114136,0.057292751967907,40667,-2770,-2308,-1343,0.988698840141296 +34093,-0.000684798927978,-0.859705209732056,0.059684384614229,40667,-2225,-4828,-1697,0.986300647258758 +34095,-0.00137379928492,-0.849347770214081,0.061702139675617,40667,-2080,-3527,-1285,0.99090564250946 +34097,0.004051959142089,-0.855323195457459,0.060528807342053,40667,-2627,-3847,-1677,0.991533815860748 +34099,0.007928172126412,-0.864189922809601,0.06239327788353,40667,-2571,-1633,-1261,0.990029215812683 +34101,0.013061026111245,-0.881518006324768,0.067869573831558,40667,-2751,-2369,-1611,0.992692112922668 +34103,0.015936799347401,-0.887004315853119,0.070840701460838,40667,-2633,-1203,-1139,0.999432444572449 +34105,0.020049231126905,-0.898422122001648,0.070832036435604,40667,-2795,-2246,-1575,1.00548160076141 +34107,0.020245460793376,-0.913062751293182,0.070550821721554,40667,-2527,187,-1123,1.00561797618866 +34109,0.016860231757164,-0.925904750823975,0.073950476944447,40667,-2230,-1431,-1536,1.00475859642029 +34111,0.012583980336785,-0.945164799690247,0.076434999704361,40667,-2104,1370,-1036,1.00815618038178 +34113,0.011484509333968,-0.974481821060181,0.073653370141983,40667,-2333,783,-1521,1.00928783416748 +34115,0.011708822101355,-1.00501239299774,0.072823725640774,40667,-2427,3495,-1054,1.00936484336853 +34117,0.007949648424983,-1.01794064044952,0.074362941086292,40667,-2106,599,-1499,1.00731921195984 +34119,0.003547086380422,-1.03239631652832,0.07600312680006,40667,-1975,3153,-997,1.01133632659912 +34121,-0.000959689088631,-1.04341185092926,0.078401409089565,40667,-1936,1209,-1453,1.01561641693115 +34123,-0.003730485914275,-1.05037820339203,0.082002714276314,40667,-1984,3290,-907,1.01744735240936 +34125,-0.006180012598634,-1.05586016178131,0.083681486546993,40667,-2016,1384,-1397,1.01875746250153 +34127,-0.009645614773035,-1.06426572799683,0.085712268948555,40667,-1841,4012,-842,1.01809513568878 +34129,-0.013003756292164,-1.07920718193054,0.091267958283424,41972,-1858,2798,-1326,1.01632356643677 +34131,-0.01684052310884,-1.08341002464294,0.094372309744358,41972,-1694,4423,-717,1.01650607585907 +34133,-0.02412723377347,-1.07547855377197,0.093899510800839,41972,-1417,1519,-1286,1.02033269405365 +34135,-0.029145762324333,-1.06667053699493,0.09310132265091,41972,-1411,3625,-715,1.02337348461151 +34137,-0.03315107524395,-1.05793416500092,0.091127254068852,41972,-1517,1617,-1284,1.02487993240356 +34139,-0.039299942553043,-1.05247783660889,0.090088166296482,41972,-1158,4036,-732,1.02566540241241 +34141,-0.045098062604666,-1.04128730297089,0.092688657343388,41972,-1208,1607,-1253,1.02600789070129 +34143,-0.048598639667034,-1.02281713485718,0.09434300661087,41972,-1185,3019,-666,1.03037071228027 +34145,-0.047879151999951,-1.00531542301178,0.096391029655933,41972,-1621,1032,-1206,1.03630256652832 +34147,-0.047237910330296,-0.98397558927536,0.096577405929566,41972,-1487,2565,-622,1.04077577590942 +34149,-0.051825806498528,-0.969796895980835,0.091683007776737,41972,-1169,1139,-1218,1.04268014431 +34151,-0.062924928963184,-0.954019248485565,0.089594095945358,41972,-379,2846,-690,1.03771460056305 +34153,-0.06889995187521,-0.934587836265564,0.091271474957466,41972,-804,625,-1200,1.03712666034698 +34155,-0.065299198031426,-0.913688063621521,0.094540387392044,41972,-1376,2178,-618,1.04167759418488 +34157,-0.058887649327517,-0.891450881958008,0.097766555845738,41972,-1814,155,-1135,1.04704988002777 +34175,-0.010718381032348,-0.664214611053467,0.069842755794525,43151,-2428,-357,-842,1.0555168390274 +34177,-0.007183096371591,-0.645683705806732,0.070793054997921,43151,-2302,-1667,-1229,1.05942213535309 +34179,-0.002299525076523,-0.62939977645874,0.068958558142185,43151,-2447,-384,-841,1.06175470352173 +34181,-0.00057830644073,-0.603678643703461,0.064529098570347,43151,-2275,-2551,-1257,1.06240689754486 +34183,-0.00200072163716,-0.574136674404144,0.057746976613999,43151,-2010,-2006,-963,1.06214666366577 +34185,0.003144268179312,-0.550479650497437,0.052961733192206,43151,-2583,-2956,-1323,1.06090569496155 +34187,0.009538293816149,-0.535481214523315,0.052429553121328,43151,-2772,-1399,-1017,1.06399405002594 +34189,0.016528176143766,-0.531655013561249,0.054255627095699,43151,-2922,-1612,-1302,1.06861627101898 +34191,0.023544503375888,-0.527768492698669,0.051842946559191,43151,-3067,-544,-1013,1.07348275184631 +34193,0.024921797215939,-0.516039669513702,0.048254676163197,43151,-2662,-2212,-1331,1.07716822624207 +34195,0.020887946709991,-0.501056492328644,0.046128034591675,43151,-2254,-1588,-1071,1.0789840221405 +34197,0.011793958023191,-0.482380986213684,0.041975077241659,43151,-1745,-3013,-1363,1.08230817317963 +34199,0.006720891688019,-0.4696084856987,0.037338752299547,43151,-1965,-1763,-1167,1.08337759971619 +34201,0.007484279107302,-0.463423907756805,0.032817404717207,43151,-2403,-2223,-1417,1.08258414268494 +34203,0.007277116645128,-0.452391773462296,0.026945646852255,43545,-2332,-1752,-1281,1.08300399780273 +34205,0.004985532257706,-0.444839805364609,0.023315016180277,43545,-2162,-2426,-1475,1.08477079868317 +34207,-0.002235233318061,-0.440360635519028,0.024026285856962,43545,-1682,-1326,-1308,1.0886458158493 +34209,-0.009897604584694,-0.436036080121994,0.022077782079578,43545,-1572,-2165,-1476,1.09395062923431 +34211,-0.014910054393113,-0.433605641126633,0.01574419438839,43545,-1644,-1136,-1401,1.09940814971924 +34213,-0.018257951363921,-0.429576277732849,0.008347999304533,43545,-1764,-2083,-1565,1.103147149086 +34215,-0.019399024546146,-0.427227973937988,0.000887003028765,43545,-1860,-1079,-1573,1.1059684753418 +34217,-0.028617499396205,-0.421296954154968,-0.002644576830789,43545,-1198,-2185,-1637,1.10624933242798 +34219,-0.042991597205401,-0.415271669626236,-0.006037909071893,43545,-530,-1389,-1654,1.10344254970551 +34221,-0.055333774536848,-0.41788974404335,-0.013660671189427,43545,-583,-1473,-1711,1.10056412220001 +34223,-0.066392563283444,-0.42015552520752,-0.020077051594853,43545,-373,-567,-1818,1.09683990478516 +34225,-0.076115854084492,-0.415066629648209,-0.021965727210045,43545,-453,-1914,-1769,1.09757173061371 +34227,-0.080237410962582,-0.411253035068512,-0.022963734343648,43545,-622,-993,-1854,1.10052275657654 +34229,-0.082971334457398,-0.416108995676041,-0.026973802596331,43545,-830,-1037,-1804,1.10312592983246 +34231,-0.087316416203976,-0.420672863721848,-0.034482769668102,43545,-464,-84,-1992,1.10628175735474 +34233,-0.091127172112465,-0.421577870845795,-0.041060395538807,43545,-606,-1086,-1904,1.10445988178253 +34235,-0.10077016800642,-0.419257640838623,-0.044224381446838,43545,161,-448,-2112,1.09926116466522 +34237,-0.113457709550858,-0.417055308818817,-0.044117644429207,43545,384,-1217,-1930,1.09417355060577 +34239,-0.123099036514759,-0.415214687585831,-0.045835293829441,43545,561,-329,-2138,1.09038877487183 +34241,-0.125161752104759,-0.414407283067703,-0.049728408455849,43866,-163,-1001,-1973,1.09331750869751 +34243,-0.120359316468239,-0.415880888700485,-0.050834465771914,43866,-466,73,-2202,1.10068500041962 +34245,-0.118425779044628,-0.413301706314087,-0.050151135772467,43866,-501,-988,-1982,1.10518431663513 +34247,-0.119879610836506,-0.408924609422684,-0.051161233335734,43866,17,-305,-2214,1.11026084423065 +34249,-0.117401950061321,-0.412200838327408,-0.055539984256029,43866,-509,-430,-2025,1.11501812934875 +34251,-0.112942405045033,-0.420524299144745,-0.062036603689194,43866,-486,946,-2350,1.11671936511993 +34253,-0.110604368150234,-0.42179661989212,-0.065595880150795,43866,-557,-276,-2102,1.12093913555145 +34255,-0.107061773538589,-0.417943954467773,-0.065643392503262,43866,-478,187,-2402,1.12337267398834 +34257,-0.099988199770451,-0.418529778718948,-0.065124087035656,43866,-1010,-212,-2108,1.12455177307129 +34259,-0.094296723604202,-0.422545611858368,-0.064487554132938,43866,-799,982,-2397,1.12686312198639 +34261,-0.091510072350502,-0.421751797199249,-0.062293164432049,43866,-792,-103,-2097,1.12579703330994 +34263,-0.091452442109585,-0.418752163648605,-0.061729248613119,43866,-404,580,-2373,1.12492787837982 +34265,-0.091307893395424,-0.418780475854874,-0.063059568405151,43866,-573,75,-2110,1.12515294551849 +34267,-0.090467341244221,-0.419106304645538,-0.067285612225533,43866,-442,989,-2448,1.12644267082214 +34269,-0.089148476719856,-0.419696569442749,-0.070792198181152,43866,-655,292,-2172,1.12641787528992 +34271,-0.087350629270077,-0.415501475334168,-0.072960659861565,43866,-526,778,-2525,1.12676155567169 +34273,-0.079483553767204,-0.409991919994354,-0.073836468160153,43866,-1230,-118,-2203,1.12716686725616 +34275,-0.063537880778313,-0.406274199485779,-0.070962138473988,43866,-1896,826,-2512,1.1254631280899 +34277,-0.054498881101608,-0.401590913534164,-0.067035637795925,43866,-1650,-18,-2166,1.12507903575897 +34279,-0.049702879041433,-0.40050020813942,-0.068621449172497,43866,-1302,1070,-2494,1.12413644790649 +34281,-0.042328536510468,-0.399703979492187,-0.071515016257763,43866,-1690,391,-2206,1.1242344379425 +34283,-0.035687800496817,-0.398264914751053,-0.073876202106476,43866,-1652,1163,-2567,1.13018190860748 +34285,-0.025547659024596,-0.400415122509003,-0.076310761272907,43866,-2119,771,-2249,1.13748931884766 +34287,-0.016325611621142,-0.400677800178528,-0.08022040873766,43866,-2153,1490,-2653,1.14417278766632 +34289,-0.014208216220141,-0.400393724441528,-0.084732592105866,43866,-1708,758,-2318,1.14802718162537 +34291,-0.012417292222381,-0.399034291505814,-0.08838777244091,43866,-1691,1512,-2762,1.14699065685272 +34293,-0.005698979366571,-0.390969008207321,-0.090015359222889,43866,-2163,228,-2367,1.14184737205505 +34295,0.001333459280431,-0.38433575630188,-0.087142676115036,43866,-2298,1050,-2761,1.14188861846924 +34297,0.004900383297354,-0.382574945688248,-0.084361955523491,43866,-2099,716,-2341,1.14476895332336 +34299,0.004392892122269,-0.372322678565979,-0.085121154785156,43866,-1817,748,-2750,1.14925968647003 +34301,-0.000564925489016,-0.362633228302002,-0.086221821606159,43866,-1421,14,-2366,1.15703785419464 +34303,-0.00716850021854,-0.357964396476746,-0.086132906377316,43866,-1196,1063,-2775,1.15984058380127 +34305,-0.011553445830941,-0.351945579051971,-0.085711516439915,43866,-1310,270,-2375,1.15826368331909 +34307,-0.009915567934513,-0.345437586307526,-0.085318617522717,43866,-1743,870,-2778,1.15616822242737 +34309,-0.004540333990008,-0.336021542549133,-0.083860084414482,43866,-2113,-60,-2375,1.15093386173248 +34329,-0.034308977425099,-0.228822201490402,-0.066701591014862,43866,-1162,-942,-2311,1.13700771331787 +34331,-0.033231668174267,-0.216818273067474,-0.065021403133869,43866,-1327,-922,-2612,1.13483333587646 +34333,-0.030217528343201,-0.203973144292831,-0.064232043921948,43866,-1568,-1532,-2304,1.13621437549591 +34335,-0.02932083979249,-0.196816220879555,-0.060791570693255,43866,-1371,-822,-2572,1.13849341869354 +34337,-0.025324368849397,-0.188014999032021,-0.060408189892769,43866,-1703,-1394,-2286,1.14551091194153 +34339,-0.015511500649154,-0.179947003722191,-0.06128129735589,43866,-2234,-1090,-2588,1.15113747119904 +34341,-0.013533155433834,-0.173534110188484,-0.061213247478008,43866,-1729,-1361,-2300,1.15572118759155 +34343,-0.020799934864044,-0.165007814764977,-0.060766585171223,43866,-927,-1299,-2591,1.15864586830139 +34345,-0.025672307237983,-0.154982969164848,-0.05800262466073,43866,-1063,-1823,-2287,1.15939426422119 +34347,-0.026009907945991,-0.144203409552574,-0.057417668402195,43866,-1336,-1737,-2561,1.15890944004059 +34349,-0.028589220717549,-0.134600207209587,-0.058210913091898,43866,-1182,-2030,-2296,1.15716326236725 +34351,-0.029021536931396,-0.130560621619225,-0.059023268520832,43866,-1276,-1417,-2589,1.15610134601593 +34353,-0.025577647611499,-0.124478556215763,-0.060630641877651,43866,-1652,-1874,-2322,1.15308630466461 +34355,-0.024222718551755,-0.119255371391773,-0.061789009720087,43866,-1477,-1641,-2631,1.14901566505432 +34357,-0.029141215607524,-0.114371448755264,-0.063716724514961,43866,-999,-1888,-2352,1.14497470855713 +34359,-0.034121423959732,-0.109406299889088,-0.067835450172424,43866,-853,-1746,-2712,1.14602053165436 +34361,-0.038157053291798,-0.104400709271431,-0.071559742093086,43866,-925,-2000,-2416,1.15227353572845 +34363,-0.042266495525837,-0.102787010371685,-0.073170334100723,43866,-767,-1575,-2786,1.1574832201004 +34365,-0.045172907412052,-0.098990820348263,-0.074054874479771,43866,-892,-1955,-2444,1.16240131855011 +34367,-0.046052504330874,-0.093702733516693,-0.076538018882275,43866,-919,-1949,-2837,1.16644620895386 +34369,-0.044742923229933,-0.085990749299526,-0.079707019031048,43866,-1184,-2389,-2494,1.16333556175232 +34371,-0.049326680600643,-0.078899867832661,-0.080810770392418,43866,-590,-2286,-2900,1.15788960456848 +34373,-0.0537532530725,-0.073140248656273,-0.079947046935558,43866,-628,-2406,-2508,1.15068638324738 +34375,-0.056653127074242,-0.06529937684536,-0.077528968453407,43866,-580,-2534,-2874,1.14475870132446 +34377,-0.056595999747515,-0.067716971039772,-0.073417894542217,43866,-889,-1877,-2475,1.14033246040344 +34379,-0.052767887711525,-0.076026052236557,-0.06874593347311,43866,-1103,-1183,-2782,1.13712990283966 +34381,-0.046329386532307,-0.088436551392078,-0.067997232079506,43866,-1476,-837,-2448,1.13530814647675 +34383,-0.03558549284935,-0.101749375462532,-0.068817436695099,43866,-1858,-381,-2792,1.13485944271088 +34385,-0.025899332016707,-0.109769880771637,-0.070215590298176,43866,-1991,-809,-2474,1.13566339015961 +34387,-0.019288687035441,-0.121787279844284,-0.074216090142727,43866,-1818,-106,-2865,1.13590037822723 +34389,-0.011479218490422,-0.135313004255295,-0.078673079609871,43866,-2060,-1,-2543,1.13432550430298 +34391,-0.004910442512482,-0.143861085176468,-0.081747442483902,43866,-2056,64,-2965,1.13291013240814 +34393,0.000933764618821,-0.152154579758644,-0.084977857768536,43866,-2101,-75,-2599,1.13120520114899 +34395,0.00515525508672,-0.164567604660988,-0.087025389075279,43866,-2060,745,-3040,1.12842285633087 +34397,0.007468030322343,-0.172623351216316,-0.089266903698444,43866,-1951,270,-2642,1.12529897689819 +34399,0.010373114608228,-0.176441624760628,-0.091267794370651,43866,-2059,389,-3103,1.12157130241394 +34401,0.011785676702857,-0.180100560188293,-0.091626197099686,43866,-1960,137,-2672,1.11869549751282 +34403,0.008817340247333,-0.184485644102097,-0.093135438859463,43866,-1622,634,-3139,1.12107241153717 +34405,0.003558170516044,-0.187435567378998,-0.094645790755749,43866,-1374,270,-2708,1.12646532058716 +34407,-0.002300473861396,-0.184643477201462,-0.095210149884224,43866,-1237,204,-3177,1.13150441646576 +34409,-0.009226102381945,-0.184549108147621,-0.097847819328308,43866,-1075,90,-2744,1.13345038890839 +34411,-0.018496718257666,-0.183639138936996,-0.103460796177387,43866,-727,400,-3290,1.13160157203674 +34413,-0.025868562981486,-0.177423164248467,-0.110616728663445,43866,-801,-370,-2848,1.12997531890869 +34415,-0.034799516201019,-0.171269834041595,-0.115092441439629,43866,-480,-100,-3445,1.1308479309082 +34417,-0.045596219599247,-0.167929321527481,-0.117689795792103,43866,-261,-226,-2915,1.12928307056427 +34419,-0.055673606693745,-0.16763336956501,-0.11976271122694,43866,-44,332,-3519,1.12734341621399 +34421,-0.062502086162567,-0.166842818260193,-0.123051218688488,43866,-282,12,-2971,1.12582850456238 +34423,-0.063449293375015,-0.156980529427528,-0.126368969678879,43866,-554,-452,-3617,1.1246771812439 +34425,-0.066512674093247,-0.150876417756081,-0.128523319959641,43866,-471,-527,-3029,1.13134109973907 +34427,-0.071072049438953,-0.15538364648819,-0.127535179257393,43866,-144,620,-3651,1.13806676864624 +34429,-0.07698654383421,-0.160554707050324,-0.126008093357086,43616,-88,487,-3032,1.14035081863403 +34431,-0.083978362381458,-0.163310945034027,-0.124664731323719,43616,271,692,-3638,1.13970136642456 +34433,-0.09009113907814,-0.156663715839386,-0.123494930565357,43616,147,-342,-3035,1.13789331912994 +34435,-0.09247288107872,-0.151932492852211,-0.122550621628761,43616,113,40,-3634,1.13786947727203 +34437,-0.093151181936264,-0.15432271361351,-0.123151555657387,43616,-159,338,-3052,1.13749527931213 +34439,-0.097259379923344,-0.159974753856659,-0.124990433454514,43616,354,981,-3682,1.1390917301178 +34441,-0.104450240731239,-0.164789617061615,-0.127456188201904,43616,509,734,-3102,1.13903546333313 +34443,-0.110108613967896,-0.166522264480591,-0.129571542143822,43616,716,878,-3757,1.13611733913422 +34445,-0.118179447948933,-0.161025360226631,-0.130143016576767,43616,816,16,-3142,1.13494443893433 +34447,-0.12997955083847,-0.155726507306099,-0.129982218146324,43616,1529,267,-3784,1.13457989692688 +34449,-0.137221410870552,-0.150928422808647,-0.128872632980347,43616,1086,-9,-3154,1.13518893718719 +34451,-0.140348508954048,-0.137298405170441,-0.128472596406937,43616,1133,-563,-3788,1.13918793201447 +34453,-0.147031396627426,-0.127972707152367,-0.127596497535706,43616,1248,-601,-3166,1.1477609872818 +34455,-0.15886963903904,-0.118257708847523,-0.125047996640205,43616,2117,-530,-3769,1.1575665473938 +34457,-0.166223242878914,-0.115055568516254,-0.122836522758007,43616,1640,-294,-3154,1.16565871238709 +34459,-0.172120854258537,-0.119973264634609,-0.118915654718876,43616,1975,601,-3717,1.16319632530212 +34461,-0.176977261900902,-0.125892743468285,-0.116432070732117,43616,1691,569,-3129,1.15480136871338 +34463,-0.179494425654411,-0.131666913628578,-0.117202788591385,43616,1928,909,-3716,1.14554035663605 +34465,-0.184281721711159,-0.135403200984001,-0.115520246326923,43616,1870,610,-3142,1.13433468341827 +34467,-0.19027853012085,-0.135421961545944,-0.111724801361561,43223,2437,618,-3671,1.12869560718536 +34469,-0.189758196473122,-0.134813264012337,-0.109736137092114,43223,1653,353,-3120,1.12644553184509 +34471,-0.187521755695343,-0.129010438919067,-0.106359668076038,43223,1896,157,-3626,1.12722158432007 +34473,-0.186872288584709,-0.129628971219063,-0.101642839610577,43223,1688,426,-3082,1.13040852546692 +34475,-0.182524636387825,-0.133969113230705,-0.09835895895958,43223,1754,1028,-3549,1.13306081295013 +34477,-0.179013878107071,-0.12846240401268,-0.096694275736809,43223,1455,34,-3064,1.13599252700806 +34479,-0.17262502014637,-0.125465855002403,-0.094293512403965,43223,1530,430,-3517,1.13476729393005 +34481,-0.165816009044647,-0.124560706317425,-0.092560730874539,43223,1110,368,-3051,1.1317595243454 +34483,-0.159006431698799,-0.122626923024654,-0.088873460888863,43223,1353,522,-3468,1.12862408161163 +34485,-0.145786002278328,-0.117781542241573,-0.08449037373066,43223,438,48,-3010,1.12478232383728 +34487,-0.130398899316788,-0.108202934265137,-0.080925583839417,43223,338,-205,-3389,1.12488615512848 +34489,-0.116724707186222,-0.096383228898048,-0.07667388767004,43223,50,-705,-2969,1.1266667842865 +34491,-0.101134248077869,-0.084030851721764,-0.074125818908215,43223,-99,-753,-3321,1.12721645832062 +34493,-0.082947239279747,-0.071944363415241,-0.07361401617527,43223,-710,-1033,-2960,1.12752139568329 +34495,-0.064724251627922,-0.062658160924912,-0.067231521010399,43223,-840,-847,-3251,1.13042414188385 +34497,-0.046681001782417,-0.051036637276411,-0.056585233658552,43223,-1189,-1269,-2854,1.13511765003204 +34499,-0.026814553886652,-0.042787827551365,-0.047683846205473,43223,-1552,-1071,-3030,1.13871443271637 +34501,-0.008201233111322,-0.044628854840994,-0.045717034488916,43223,-1768,-374,-2786,1.13734900951386 +34503,0.006595987826586,-0.050448782742024,-0.04684117436409,43223,-1732,-32767,-3028,1.1326949596405 +34505,0.014888315461576,-0.052117761224508,-0.044313039630652,42901,-1363,-25101,-2784,1.12730062007904 +34507,0.018656920641661,-0.051147192716599,-0.039450358599424,42901,-1152,-25335,-2947,1.12224507331848 +34509,0.023311806842685,-0.047006212174893,-0.034147035330534,42901,-1234,-25811,-2720,1.12377429008484 +34511,0.02982266061008,-0.046887557953596,-0.030312111601234,42901,-1539,-25564,-2845,1.12909150123596 +34513,0.037763752043247,-0.05498917773366,-0.033351968973875,42901,-1691,-25041,-2719,1.13186872005463 +34515,0.047682587057352,-0.079646497964859,-0.037150856107473,42901,-2090,-23472,-2931,1.13480234146118 +34517,0.052618607878685,-0.115241281688213,-0.038367375731468,42901,-1712,-22413,-2760,1.13429701328278 +34519,0.05430618673563,-0.162280023097992,-0.038357116281986,42901,-1626,-20714,-2952,1.13381230831146 +34521,0.063307411968708,-0.227440401911736,-0.038179080933333,42901,-2181,-18853,-2764,1.13210463523865 +34523,0.075035817921162,-0.294915527105331,-0.037355583161116,42901,-2705,-17231,-2947,1.13028490543365 +34525,0.085037678480148,-0.375607371330261,-0.034467913210392,42901,-2598,-15720,-2745,1.12871038913727 +34527,0.092433154582977,-0.467312514781952,-0.032692510634661,42901,-2721,-12768,-2898,1.12350225448608 +34529,0.096239328384399,-0.565551698207855,-0.036861963570118,42901,-2358,-11764,-2766,1.1217474937439 +34531,0.099435642361641,-0.663531243801117,-0.039724510163069,42901,-2590,-9113,-2986,1.12244176864624 +34533,0.104493759572506,-0.76331090927124,-0.040664508938789,42901,-2615,-8750,-2799,1.12201821804047 +34535,0.109805919229984,-0.873701810836792,-0.042038589715958,42901,-2965,-4694,-3018,1.12332165241241 +34537,0.110233150422573,-0.987129688262939,-0.041837807744742,42901,-2420,-4396,-2813,1.1220794916153 +34539,0.104270152747631,-1.09809708595276,-0.043607603758574,42901,-2114,-799,-3041,1.12262392044067 +34541,0.105037949979305,-1.22168803215027,-0.047292232513428,42901,-2420,-31,-2858,1.12487697601318 +34561,0.076325878500939,-2.18378233909607,-0.041356943547726,42579,-1660,12034,-2849,1.09441697597504 +34563,0.074013523757458,-2.23173594474792,-0.042868200689554,42579,-2193,16547,-3041,1.09434974193573 +34565,0.073205053806305,-2.28245544433594,-0.043101452291012,42579,-2159,13733,-2867,1.09833931922913 +34567,0.066909700632095,-2.32189917564392,-0.041807476431131,42579,-1832,18237,-3028,1.1074253320694 +34569,0.055061660706997,-2.34995079040527,-0.042175132781267,42579,-1143,13944,-2866,1.12246918678284 +34571,0.043869968503714,-2.36188101768494,-0.046071588993073,42579,-1132,17793,-3081,1.13474094867706 +34573,0.029167626053095,-2.36362075805664,-0.048326697200537,42579,-592,13148,-2914,1.14174687862396 +34575,0.012478237040341,-2.35983848571777,-0.050216738134623,42579,-234,17524,-3137,1.14253401756287 +34577,-0.00363323208876,-2.34663510322571,-0.054140344262123,42579,-28,12731,-2961,1.13941717147827 +34579,-0.0225147921592,-2.32978701591492,-0.059729240834713,42579,499,16987,-3259,1.13227880001068 +34581,-0.047864593565464,-2.29946255683899,-0.060190286487341,42579,1277,11718,-3011,1.1227114200592 +34583,-0.073279388248921,-2.25898766517639,-0.05723562836647,42579,1807,15017,-3240,1.11359572410584 +34585,-0.093433775007725,-2.20567774772644,-0.056690752506256,42579,1591,9589,-2995,1.10618185997009 +34587,-0.106190726161003,-2.15447592735291,-0.057200323790312,42579,1470,13390,-3252,1.10587418079376 +34589,-0.122042179107666,-2.092942237854,-0.058413870632649,42579,1741,8204,-3015,1.10859906673431 +34591,-0.130236089229584,-2.01902747154236,-0.057478938251734,42579,1593,10352,-3271,1.11169028282166 +34593,-0.13281661272049,-1.94327902793884,-0.053101599216461,42579,1004,5803,-2987,1.11297106742859 +34595,-0.135251566767693,-1.87504577636719,-0.046654667705298,42579,1319,9146,-3158,1.10921680927277 +34597,-0.142877444624901,-1.80398976802826,-0.039544612169266,42579,1572,4844,-2901,1.10699534416199 +34599,-0.153208494186401,-1.72842764854431,-0.03342305123806,42579,2235,6905,-3012,1.1073579788208 +34601,-0.166271612048149,-1.64905917644501,-0.026999523863196,42579,2366,2665,-2819,1.1090259552002 +34603,-0.181092455983162,-1.56635987758636,-0.019602676853538,42579,3094,4359,-2862,1.11330080032349 +34605,-0.196872279047966,-1.48117554187775,-0.010771731846035,42579,3084,409,-2711,1.11791813373566 +34607,-0.207658842206001,-1.39976763725281,-0.004884569440037,42579,3334,2273,-2700,1.12218832969666 +34609,-0.215122565627098,-1.3152346611023,-0.006229312159121,42579,2848,-1429,-2680,1.12633299827576 +34611,-0.220561996102333,-1.22631621360779,-0.005669613368809,42579,3266,-621,-2716,1.12888777256012 +34613,-0.223675057291985,-1.13668990135193,0.00022202868422,42579,2765,-3936,-2636,1.1291081905365 +34615,-0.223457396030426,-1.05229687690735,0.006022042129189,42579,3004,-2739,-2579,1.12828195095062 +34617,-0.222303822636604,-0.98266726732254,0.009444771334529,42383,2545,-4370,-2572,1.12839865684509 +34619,-0.219974219799042,-0.921452581882477,0.011774855665863,42383,2884,-2888,-2507,1.13155496120453 +34621,-0.218335852026939,-0.856934368610382,0.011754260398448,42383,2556,-5521,-2554,1.13586914539337 +34623,-0.211775735020637,-0.795555055141449,0.012241496704519,42383,2538,-4691,-2496,1.13945150375366 +34625,-0.207422390580177,-0.740021169185638,0.015379416756332,42383,2302,-6325,-2527,1.14010870456696 +34627,-0.210639134049416,-0.681595087051392,0.023072527721524,42383,3315,-6139,-2366,1.14174652099609 +34629,-0.205900490283966,-0.633462309837341,0.030827201902866,42383,2349,-7146,-2416,1.14335072040558 +34631,-0.191942274570465,-0.593375980854034,0.032242957502604,42383,1867,-6101,-2251,1.14622271060944 +34633,-0.174822121858597,-0.554696619510651,0.031947027891874,42383,1104,-7461,-2403,1.14940762519836 +34635,-0.159054383635521,-0.514680683612824,0.031738124787808,42383,1283,-7253,-2250,1.14768528938293 +34637,-0.150062337517738,-0.480441808700561,0.030436122789979,42383,1405,-8105,-2408,1.14261245727539 +34639,-0.146789595484734,-0.455265313386917,0.030304070562124,42383,2058,-7073,-2264,1.13641655445099 +34641,-0.143138825893402,-0.426392018795013,0.028068795800209,42383,1757,-8420,-2418,1.13108170032501 +34643,-0.132228434085846,-0.393959879875183,0.024382999166846,42383,1345,-8528,-2329,1.13040268421173 +34645,-0.118991583585739,-0.369686335325241,0.023373464122415,42383,788,-8856,-2446,1.13353645801544 +34647,-0.108876258134842,-0.360537320375442,0.023567356169224,42383,1080,-7358,-2333,1.13567781448364 +34649,-0.099530033767223,-0.349580138921738,0.021804470568895,42383,840,-8156,-2453,1.13536906242371 +34651,-0.088386245071888,-0.339350789785385,0.017347682267428,42383,720,-7743,-2401,1.13039195537567 +34653,-0.075584962964058,-0.333077132701874,0.011602086015046,42383,293,-8031,-2520,1.12120747566223 +34655,-0.054577618837357,-0.333260208368301,0.007454458624125,42383,-501,-7069,-2514,1.11820650100708 +34657,-0.032927598804236,-0.335923999547958,0.004217993002385,42383,-924,-7325,-2569,1.11785507202148 +34659,-0.010790476575494,-0.337410151958466,-0.000455702946056,42383,-1261,-6886,-2612,1.11671102046967 +34661,0.00524982996285,-0.338678628206253,-0.001524139544927,42383,-1060,-7358,-2608,1.1174224615097 +34663,0.013399094343186,-0.343520700931549,0.001452681026421,42383,-638,-6517,-2593,1.11479330062866 +34665,0.022467564791441,-0.358527272939682,-0.00029712106334,42383,-807,-6058,-2599,1.11336123943329 +34667,0.037753097712994,-0.372297912836075,-0.008048969320953,42383,-1554,-5369,-2704,1.11263203620911 +34669,0.05062272772193,-0.382304906845093,-0.013839196413756,42383,-1495,-6030,-2694,1.1081634759903 +34671,0.063709780573845,-0.399872601032257,-0.016582576557994,42383,-1843,-4596,-2803,1.10550773143768 +34673,0.079729840159416,-0.415552139282227,-0.019107164815068,42383,-2163,-5087,-2733,1.10138475894928 +34675,0.098846517503262,-0.427338123321533,-0.014518979936838,42383,-2884,-4505,-2780,1.09778392314911 +34677,0.113212265074253,-0.443945109844208,-0.010113941505551,42383,-2567,-4541,-2673,1.09275698661804 +34679,0.116256132721901,-0.465568453073502,-0.009991250932217,42383,-2067,-3105,-2727,1.09134638309479 +34681,0.115584552288055,-0.497415781021118,-0.009188814088702,42383,-1576,-2593,-2668,1.09572064876556 +34683,0.117289580404758,-0.527243554592133,-0.006630693096668,42383,-2043,-1407,-2688,1.10317361354828 +34685,0.126940175890923,-0.558717131614685,-0.00469673005864,42383,-2531,-1620,-2638,1.10753357410431 +34687,0.138127610087395,-0.584727346897125,-0.004127715248615,42383,-3113,-615,-2662,1.10675466060638 +34689,0.145060122013092,-0.603599071502685,-0.002526064403355,42383,-2659,-1731,-2624,1.10316407680511 +34691,0.147402480244637,-0.622044920921326,-0.00033061040449,42383,-2689,-397,-2619,1.10067236423492 +34693,0.148369550704956,-0.643243730068207,-0.002684961771593,42383,-2345,-830,-2625,1.09739124774933 +34711,0.070446990430355,-0.851229548454285,-0.008138853125274,42383,-673,4343,-2711,1.12176513671875 +34713,0.061273828148842,-0.863233685493469,-0.007339561823756,42383,-645,2873,-2665,1.11972045898438 +34715,0.045614633709192,-0.867099404335022,-0.009814463555813,42383,-65,3968,-2733,1.11793899536133 +34717,0.025816360488534,-0.866779565811157,-0.011769593693316,42383,603,2333,-2697,1.11249399185181 +34719,0.005111649632454,-0.868718266487122,-0.012567182071507,42383,948,4143,-2769,1.1038064956665 +34721,-0.010759015567601,-0.874354839324951,-0.010294132865965,42383,845,3162,-2688,1.09562504291534 +34723,-0.02957683056593,-0.87211400270462,-0.006592496763915,42383,1393,4191,-2706,1.0868227481842 +34725,-0.049238339066506,-0.862138390541077,-0.004446972161531,42383,1685,2165,-2649,1.08110249042511 +34727,-0.065372794866562,-0.850138187408447,-0.004314304329455,42383,1812,3426,-2683,1.08128786087036 +34729,-0.081462293863297,-0.839711606502533,-0.007195063401014,42383,1926,31490,-2669,1.08166682720184 +34731,-0.09020296484232,-0.826483428478241,-0.009973352774978,42383,1718,8201,-2748,1.08183479309082 +34733,-0.09246776252985,-0.806221723556519,-0.012104263529182,42383,1138,6184,-2704,1.08282947540283 +34735,-0.094885066151619,-0.785670578479767,-0.013425463810563,42383,1381,7331,-2787,1.08269274234772 +34737,-0.099400661885738,-0.764723896980285,-0.01298910100013,42383,1444,5851,-2712,1.08431994915009 +34739,-0.100208528339863,-0.740792453289032,-0.01239790674299,42383,1400,6655,-2778,1.08719038963318 +34741,-0.092024274170399,-0.709692060947418,-0.011100873351097,42383,477,4627,-2701,1.087029337883 +34743,-0.083456717431545,-0.669686138629913,-0.009972940199077,42383,505,4624,-2753,1.08752059936523 +34745,-0.076431073248386,-0.619206607341766,-0.009498698636889,42383,378,2201,-2692,1.08817720413208 +34747,-0.066811889410019,-0.564605414867401,-0.00761799281463,42383,198,2116,-2727,1.08823359012604 +34749,-0.059732396155596,-0.501850783824921,-0.004658562131226,42383,170,-146,-2660,1.08891570568085 +34751,-0.052995797246695,-0.437094479799271,0.002848325762898,42383,203,-489,-2599,1.08767855167389 +34753,-0.042595483362675,-0.375113725662231,0.009586901403964,42383,-286,-1750,-2561,1.08558857440948 +34755,-0.031856760382652,-0.312546521425247,0.009989432990551,42383,-407,-2224,-2510,1.08637154102325 +34757,-0.017754783853889,-0.250629961490631,0.011472030542791,42383,-891,-3429,-2546,1.08909320831299 +34759,-0.000339564518072,-0.18478474020958,0.013572690077126,42383,-1384,-4460,-2465,1.09316265583038 +34761,0.013424634933472,-0.121073618531227,0.013737912289798,42383,-1312,-5373,-2528,1.09952616691589 +34763,0.022201247513294,-0.066264562308788,0.014141122810543,42383,-1132,-5575,-2454,1.10225641727448 +34765,0.027577131986618,-0.009623457677662,0.013562093488872,42383,-921,22912,-2526,1.10116052627563 +34767,0.034170188009739,0.048296246677637,0.013294068165124,42383,-1181,-2729,-2458,1.10051226615906 +34769,0.044846553355455,0.105043724179268,0.013913988135755,42383,-1562,-3204,-2521,1.09564018249512 +34771,0.052631378173828,0.160808205604553,0.01370707154274,42383,-1588,-4445,-2445,1.08820343017578 +34773,0.058520808815956,0.210603833198547,0.010155484080315,42383,-1438,-4287,-2544,1.08104491233826 +34775,0.065146885812283,0.259355396032333,0.006343975197524,42383,-1737,-5637,-2525,1.07464075088501 +34777,0.070507846772671,0.315712511539459,0.001691421028227,42383,-1601,-6379,-2600,1.06770396232605 +34779,0.071551717817783,0.359728842973709,-0.003663619980216,42383,-1471,-7067,-2640,1.06765639781952 +34781,0.070673361420631,0.390269488096237,-0.007825179025531,42383,-1188,-5762,-2665,1.07090675830841 +34783,0.0775131508708,0.421601325273514,-0.009872023016214,42383,-2011,-7336,-2715,1.07821249961853 +34785,0.089356012642384,0.456013411283493,-0.010107468813658,42383,-2402,-7173,-2681,1.08616805076599 +34787,0.092317573726177,0.489528238773346,-0.009749928489327,42383,-2018,-8802,-2711,1.08895695209503 +34789,0.086879000067711,0.512121081352234,-0.011250257492066,42383,-1171,-7356,-2690,1.09083986282349 +34791,0.077329009771347,0.527713775634766,-0.015333791263402,42383,-912,-8369,-2781,1.09201896190643 +34793,0.070476196706295,0.542139291763306,-0.017952529713512,42383,-869,-7445,-2738,1.09345972537994 +34795,0.069762796163559,0.552063703536987,-0.019273182377219,42383,-1445,-8604,-2834,1.09512531757355 +34797,0.069079846143723,0.561401605606079,-0.020012004300952,42383,-1321,-7612,-2754,1.09563338756561 +34799,0.063587695360184,0.57284015417099,-0.020829487591982,42383,-1027,-9305,-2858,1.09571015834808 +34801,0.054393548518419,0.586232602596283,-0.026394862681627,42383,-527,-8525,-2801,1.09417760372162 +34803,0.042123161256313,0.59480744600296,-0.030268747359514,42383,-211,-9723,-2974,1.09572553634644 +34805,0.034950952976942,0.590290248394012,-0.030762474983931,42383,-409,-7578,-2836,1.09408831596375 +34807,0.030633222311735,0.582884550094605,-0.031503353267908,42383,-606,-8655,-2994,1.09005963802338 +34809,0.026618033647537,0.57440048456192,-0.033252973109484,42383,-526,-7339,-2858,1.08460450172424 +34811,0.021466728299856,0.575343012809753,-0.03355061635375,42383,-403,-9403,-3025,1.08026850223541 +34813,0.010536690242589,0.57806932926178,-0.037049852311611,42383,193,-8467,-2889,1.0791916847229 +34815,-0.000503363145981,0.573756158351898,-0.045096602290869,42383,373,-9275,-3166,1.07956480979919 +34817,-0.012165968306363,0.563858568668366,-0.049007587134838,42383,575,-7632,-2978,1.08092260360718 +34819,-0.021052449941635,0.547541737556458,-0.046972066164017,42383,557,-8258,-3193,1.08439254760742 +34821,-0.023725099861622,0.533319413661957,-0.042805057018995,42383,110,-7148,-2943,1.0873692035675 +34823,-0.03014206327498,0.517991602420807,-0.041998170316219,42383,545,-8111,-3143,1.08793413639069 +34825,-0.035701915621758,0.492572247982025,-0.049653977155686,42383,506,-6014,-2997,1.08728790283203 +34827,-0.041874665766955,0.470672398805618,-0.056391853839159,42383,743,-7109,-3321,1.08586537837982 +34829,-0.048003096133471,0.442587673664093,-0.051164843142033,42383,747,-5338,-3016,1.08537971973419 +34831,-0.05732150003314,0.412066042423248,-0.043518714606762,42383,1238,-5749,-3175,1.08300876617432 +34833,-0.067700892686844,0.388538748025894,-0.03950721770525,42383,1364,-5094,-2943,1.08123540878296 +34835,-0.077715843915939,0.369124501943588,-0.036348480731249,42383,1654,-6041,-3097,1.0778557062149 +34837,-0.094119571149349,0.354998111724854,-0.034844245761633,42383,2214,-5472,-2917,1.07439732551575 +34839,-0.108149647712708,0.328207939863205,-0.031460143625736,42383,2477,-5029,-3043,1.07847952842712 +34841,-0.124961256980896,0.304034560918808,-0.027051560580731,42383,2739,25378,-2868,1.08427309989929 +34843,-0.139596834778786,0.27971163392067,-0.023661840707064,42383,3085,417,-2953,1.09404349327087 +34861,-0.162738785147667,0.124048888683319,-0.003633440006524,42383,2154,1085,-2717,1.08701038360596 +34863,-0.159284368157387,0.128214731812477,0.001079807640053,42383,2468,586,-2661,1.09881556034088 +34865,-0.148995608091354,0.138075053691864,0.000764536380302,42383,1596,406,-2686,1.11095583438873 +34867,-0.13215072453022,0.154585942625999,-0.000960246194154,42383,1145,-762,-2686,1.11854422092438 +34869,-0.116971231997013,0.169422641396523,0.001959302695468,42383,849,-445,-2677,1.11747062206268 +34871,-0.109573192894459,0.188313364982605,0.00779837416485,42383,1507,-1535,-2578,1.1107017993927 +34873,-0.0985292121768,0.202130183577538,0.009324795566499,42383,933,-903,-2624,1.10233271121979 +34875,-0.077610492706299,0.211384654045105,0.009130020625889,42383,57,-1289,-2556,1.09780621528625 +34877,-0.054862603545189,0.22191746532917,0.009434799663723,42383,-495,-1026,-2621,1.09603023529053 +34879,-0.031545847654343,0.22979211807251,0.011328857392073,42383,-838,27821,-2526,1.09368991851807 +34881,-0.012854173779488,0.237960398197174,0.012578899040818,42383,-792,3793,-2596,1.09292352199554 +34883,0.00113603414502,0.245942205190659,0.013246014714241,42383,-694,3064,-2500,1.09465515613556 +34885,0.015419295988977,0.252393990755081,0.016023375093937,42383,-882,3666,-2569,1.09656238555908 +34887,0.031238630414009,0.267429977655411,0.016117621213198,42383,-1319,2165,-2463,1.09946846961975 +34889,0.050589796155691,0.293742895126343,0.011355926282704,42383,-1764,1598,-2597,1.1005996465683 +34891,0.063929684460163,0.334136158227921,0.006547328550369,42383,-1688,-799,-2572,1.10140991210938 +34893,0.078872837126255,0.36566224694252,0.00599763635546,42383,-1882,108,-2631,1.10149741172791 +34895,0.084598533809185,0.397673100233078,0.007325939834118,42383,-1513,-1333,-2559,1.09987008571625 +34897,0.083301186561585,0.437435537576675,0.00662673311308,42383,-820,-1627,-2624,1.1000394821167 +34899,0.085523329675198,0.479375958442688,0.004059011582285,42383,-1315,-3502,-2593,1.1019823551178 +34901,0.093559443950653,0.522164940834045,0.007329632993788,42383,-1675,-3213,-2618,1.10544168949127 +34903,0.097009114921093,0.567331790924072,0.011271880939603,42383,-1631,-5327,-2504,1.10786557197571 +34905,0.093234546482563,0.610771000385284,0.008748118765652,42383,-869,-4726,-2604,1.10869526863098 +34907,0.086122065782547,0.649543464183807,0.005662444978952,42383,-726,-6415,-2572,1.1065731048584 +34909,0.075731538236141,0.681051075458527,0.010097288526595,42383,-181,-5114,-2593,1.10369050502777 +34911,0.063814252614975,0.70658016204834,0.017038414254785,42383,-49,-6636,-2436,1.09528136253357 +34913,0.054443575441837,0.738594233989716,0.020298346877098,42383,24,-6239,-2519,1.08748042583466 +34915,0.04837004840374,0.770919620990753,0.022818814963102,42383,-250,-8433,-2360,1.0836147069931 +34917,0.041764602065086,0.801397025585175,0.027011880651116,42383,-13,22066,-2467,1.07976377010345 +34919,0.038199618458748,0.820298075675964,0.033198397606611,42383,-289,-3609,-2230,1.07815563678741 +34921,0.03104192763567,0.83184540271759,0.037743128836155,42383,162,-1731,-2387,1.07639467716217 +34923,0.02103010751307,0.844129502773285,0.038261264562607,42383,442,-3802,-2165,1.0778079032898 +34925,0.007965874858201,0.861200273036957,0.039463594555855,42383,907,-2831,-2367,1.07926607131958 +34927,-0.002993312897161,0.886029601097107,0.042583860456944,42383,894,-5673,-2105,1.08172273635864 +34929,-0.009691000916064,0.909912586212158,0.041206724941731,42383,705,-4322,-2346,1.08830094337463 +34931,-0.0218053329736,0.938055694103241,0.037401281297207,42383,1287,-7067,-2156,1.09337317943573 +34933,-0.034853748977184,0.967172622680664,0.036774072796106,42383,1531,-5849,-2369,1.09959483146667 +34935,-0.041879080235958,0.99541312456131,0.038774259388447,42383,1260,-8347,-2130,1.09784030914307 +34937,-0.044044032692909,1.01627945899963,0.043665830045939,42383,902,-6323,-2313,1.09056460857391 +34939,-0.047511171549559,1.02603983879089,0.04261165484786,42383,1116,-7890,-2075,1.09002256393433 +34941,-0.05638137832284,1.03535413742065,0.037380639463663,42383,1581,-6146,-2348,1.08929252624512 +34943,-0.068849600851536,1.04556477069855,0.035068932920694,42383,2145,-8619,-2157,1.09056460857391 +34945,-0.07773707062006,1.04578506946564,0.03639317303896,42383,1922,-6033,-2347,1.09373569488525 +34947,-0.087368488311768,1.03775572776794,0.035229507833719,42383,2276,-7568,-2146,1.09311032295227 +34949,-0.095945134758949,1.02234363555908,0.034601405262947,42383,2202,-4965,-2352,1.09297478199005 +34951,-0.098589681088924,1.01062047481537,0.0337626747787,42383,1996,-7243,-2153,1.08940005302429 +34953,-0.101431235671043,1.00722289085388,0.033526327461004,42383,1916,-5987,-2352,1.08908951282501 +34955,-0.107504107058048,0.998192608356476,0.035442247986794,42383,2428,-7609,-2123,1.09016597270966 +34957,-0.117407880723476,0.993418991565704,0.038501761853695,42383,2700,-6066,-2310,1.09137177467346 +34959,-0.119939714670181,0.979623734951019,0.041198529303074,42383,2425,-7343,-2045,1.09149539470673 +34961,-0.116292007267475,0.96179735660553,0.041214346885681,42383,1768,-5048,-2282,1.09231579303741 +34963,-0.112848199903965,0.935889422893524,0.040144123136997,42383,1939,-6127,-2049,1.09650409221649 +34965,-0.107895113527775,0.9083571434021,0.037588674575091,42383,1606,-3940,-2298,1.09757781028748 +34967,-0.103437066078186,0.882676064968109,0.035248719155789,42383,1772,-5616,-2101,1.09602570533752 +34969,-0.098079137504101,0.851433753967285,0.03256556764245,42383,1486,-3189,-2325,1.09419095516205 +34971,-0.090367928147316,0.823804914951324,0.031765516847372,42383,1382,-4832,-2137,1.08994233608246 +34973,-0.080985486507416,0.794124722480774,0.033681776374579,42383,998,-2784,-2310,1.0872597694397 +34975,-0.065837353467941,0.753264784812927,0.034696966409683,42383,487,-3025,-2096,1.08615159988403 +34977,-0.051941338926554,0.714787781238556,0.035082433372736,42383,291,-1291,-2293,1.08531630039215 +34979,-0.040243826806545,0.684075236320496,0.036231406033039,42383,341,-2890,-2072,1.08654117584229 +34981,-0.027615563943982,0.659247219562531,0.037065282464028,42383,54,-1717,-2272,1.08487272262573 +34983,-0.008747864514589,0.618981301784515,0.037875760346651,42383,-671,-1383,-2047,1.08658838272095 +34985,0.011095033958554,0.577258586883545,0.038610827177763,42383,-1011,450,-2253,1.08644688129425 +34987,0.022268569096923,0.550476849079132,0.04057402163744,42383,-618,-1442,-2011,1.08839893341064 +34989,0.03399183601141,0.521243333816528,0.041535507887602,42383,-765,170,-2225,1.08930730819702 +34991,0.04569561034441,0.49976173043251,0.041750445961952,42383,-1046,-1168,-1992,1.091468334198 +34993,0.061869867146015,0.475606381893158,0.041911821812391,42383,-1502,295,-2214,1.09110867977142 +35013,0.196769058704376,0.396242737770081,0.02512695081532,42383,-3795,-1376,-2294,1.07466173171997 +35015,0.202459946274757,0.406536638736725,0.025832518935204,42383,-3512,-2720,-2149,1.07411658763886 +35017,0.193617716431618,0.416723847389221,0.025777734816074,42383,-1991,-2098,-2284,1.07358717918396 +35019,0.189735800027847,0.422110021114349,0.025149043649435,42383,-2711,-2758,-2153,1.07028448581696 +35021,0.192029610276222,0.426106750965118,0.025180755183101,42383,-2853,-1929,-2283,1.06521081924438 +35023,0.195945248007774,0.426444083452225,0.025563655421138,42383,-3458,-2614,-2145,1.06151413917542 +35025,0.194133162498474,0.434446692466736,0.025272831320763,42383,-2679,-2480,-2277,1.05999910831451 +35027,0.186273336410522,0.443926125764847,0.022649584338069,42383,-2541,-3700,-2176,1.06492865085602 +35029,0.176398068666458,0.447168111801147,0.02263168618083,42383,-1933,-2475,-2291,1.07306170463562 +35031,0.163373991847038,0.450289815664291,0.025215612724424,42383,-1881,-3498,-2143,1.07651233673096 +35033,0.152471989393234,0.45209401845932,0.023323696106672,42383,-1592,-2600,-2281,1.07658040523529 +35035,0.146084174513817,0.453194141387939,0.020846640691161,42383,-2158,-3558,-2189,1.07387816905975 +35037,0.138708099722862,0.454741835594177,0.023792190477252,42383,-1718,-2779,-2273,1.06769871711731 +35039,0.127935379743576,0.45796462893486,0.023893443867564,42383,-1624,-3948,-2149,1.06582248210907 +35041,0.116320364177227,0.463631600141525,0.018530692905188,42383,-1157,-3365,-2305,1.06570672988892 +35043,0.099906913936138,0.469652324914932,0.01488303206861,42383,-816,-4505,-2253,1.06826913356781 +35045,0.082907274365425,0.473901122808456,0.013642647303641,42383,-342,-3581,-2335,1.06955051422119 +35047,0.0689537525177,0.480424106121063,0.01664556004107,42383,-529,-4887,-2230,1.07237029075623 +35049,0.057726629078388,0.48088926076889,0.020801225677133,42383,-430,-3587,-2282,1.0747150182724 +35051,0.043924860656262,0.481498748064041,0.020329549908638,42383,-165,-4655,-2184,1.07670092582703 +35053,0.025791415944696,0.484161615371704,0.018858768045902,42383,498,-3969,-2292,1.07928788661957 +35055,0.011092014610767,0.479278653860092,0.016873234882951,42383,416,-4398,-2221,1.07708537578583 +35057,-0.00374617963098,0.470382213592529,0.014547129161656,42383,676,-3121,-2318,1.07396018505096 +35059,-0.020176339894533,0.46057465672493,0.013239584863186,42383,1055,-3915,-2262,1.06939911842346 +35061,-0.033179637044668,0.459579348564148,0.011804703623057,42383,974,-3703,-2334,1.06632232666016 +35063,-0.046229653060436,0.454703807830811,0.010131563059986,42383,1252,-4341,-2296,1.06714868545532 +35065,-0.059120919555426,0.443419992923737,0.010396836325526,42383,1357,-2903,-2341,1.06746864318848 +35067,-0.072078846395016,0.436531037092209,0.011400987394154,42383,1690,-4061,-2278,1.06898057460785 +35069,-0.085704818367958,0.434744387865067,0.010520871728659,42383,1823,-3620,-2338,1.0718160867691 +35071,-0.095724500715733,0.436811476945877,0.007630848325789,42383,1908,-4869,-2321,1.07362270355225 +35073,-0.10543729364872,0.432274281978607,0.005119441542774,42383,1869,-3550,-2373,1.0722975730896 +35075,-0.112735129892826,0.423476606607437,0.005639357026666,42383,2035,-4029,-2341,1.06852984428406 +35077,-0.121820993721485,0.417232722043991,0.004761026706547,42383,2111,-3369,-2374,1.06455278396606 +35079,-0.128551080822945,0.405353933572769,0.001219271915033,42383,2306,-3659,-2391,1.06238126754761 +35081,-0.128598272800446,0.395554006099701,0.000295600155368,42383,1620,-2952,-2403,1.05789256095886 +35083,-0.131417274475098,0.385712832212448,0.003512681694701,42383,2146,-3634,-2363,1.0547080039978 +35085,-0.138017013669014,0.372087121009827,0.007016650866717,42383,2287,-2483,-2356,1.05242550373077 +35087,-0.143385469913483,0.357827961444855,0.007048161700368,42383,2594,-3004,-2320,1.04992592334747 +35089,-0.136595651507378,0.342015027999878,0.004976019728929,42383,1378,-2025,-2368,1.05381762981415 +35091,-0.125093892216682,0.338997423648834,0.002889331663027,42383,1153,-3627,-2366,1.05818581581116 +35093,-0.116400197148323,0.339360952377319,0.000272989127552,42383,1013,-3268,-2399,1.06188011169434 +35095,-0.110445402562618,0.334075272083283,0.000185761236935,42383,1360,-3503,-2395,1.06241345405579 +35097,-0.104510568082333,0.323986381292343,0.001647530472837,42383,1094,-2420,-2389,1.05875754356384 +35099,-0.099164180457592,0.30728867650032,0.002092291368172,42383,1255,-2365,-2369,1.05676925182343 +35101,-0.093025915324688,0.291210204362869,-0.001655603875406,42383,960,-1630,-2410,1.05543422698975 +35103,-0.087500736117363,0.284011125564575,-0.002888756571338,42383,1093,-2773,-2427,1.05549705028534 +35105,-0.080302655696869,0.271808117628098,0.000703518220689,42383,742,-1728,-2394,1.05721747875214 +35107,-0.072198063135147,0.25288450717926,0.002041466301307,42383,702,-1520,-2369,1.06004011631012 +35109,-0.063733108341694,0.231987237930298,-0.000939731253311,42383,448,-620,-2404,1.06436288356781 +35111,-0.052856501191855,0.216907784342766,-0.006108032539487,42383,220,-1285,-2464,1.06719648838043 +35113,-0.041680410504341,0.204562067985535,-0.010431854985654,42383,-36,-909,-2469,1.06988871097565 +35115,-0.027278136461973,0.191279381513596,-0.01019702386111,42383,-430,-1057,-2513,1.07065308094025 +35117,-0.01418920326978,0.191084325313568,-0.009471830911934,42383,-554,-1644,-2464,1.06917583942413 +35119,0.000843988033012,0.193224832415581,-0.010931622236967,42383,-926,-2259,-2523,1.06570446491241 +35121,0.012606101110578,0.196805357933044,-0.015205356292427,42383,-843,-2057,-2504,1.05842757225037 +35123,0.017864434048534,0.196915239095688,-0.013589849695563,42383,-508,-2244,-2555,1.0559024810791 +35125,0.021514670923352,0.183880105614662,-0.008442691527307,42383,-398,-746,-2459,1.05990743637085 +35127,0.025597013533115,0.168142899870873,-0.009032129310071,42383,-564,-696,-2503,1.06443166732788 +35129,0.033456735312939,0.157726407051086,-0.014523378573358,42383,-883,-609,-2501,1.06820797920227 +35131,0.04376320168376,0.16248694062233,-0.01744582131505,42383,-1317,-2123,-2604,1.06980884075165 +35133,0.051011264324188,0.171522781252861,-0.017983298748732,42383,-1111,-2250,-2527,1.06966936588287 +35135,0.053079832345247,0.172408550977707,-0.018887577578425,42383,-896,-2059,-2623,1.0692275762558 +35137,0.05326022952795,0.177965581417084,-0.021594822406769,42383,-661,-2148,-2555,1.06824958324432 +35139,0.057433187961578,0.184588521718979,-0.024977052584291,42383,-1144,-2718,-2698,1.06903302669525 +35141,0.0651725679636,0.192123338580132,-0.030366282910109,42383,-1400,-2552,-2618,1.06893169879913 +35143,0.069222033023834,0.199680283665657,-0.033825132995844,42383,-1356,-3088,-2806,1.06939446926117 +35145,0.067539513111115,0.201691329479218,-0.033518053591251,42383,-791,-2360,-2645,1.06867098808289 +35147,0.062830843031406,0.207169890403748,-0.03179968520999,42383,-654,-3137,-2788,1.06812655925751 +35149,0.062536850571632,0.214237838983536,-0.029047166928649,42383,-848,-2974,-2619,1.0716153383255 +35151,0.06653206795454,0.221153095364571,-0.028182983398438,42383,-1371,-3542,-2750,1.07604026794434 +35153,0.067661806941032,0.226530387997627,-0.032331623136997,42383,-1055,-3108,-2646,1.0829017162323 +35155,0.06293872743845,0.227713674306869,-0.037176433950663,42383,-723,-3312,-2860,1.09028780460358 +35157,0.053897086530924,0.222990870475769,-0.039412349462509,42383,-159,-2415,-2700,1.08991241455078 +35159,0.045773301273584,0.217241942882538,-0.042964477092028,42383,-226,-2723,-2935,1.0847030878067 +35161,0.03970717638731,0.22085639834404,-0.045270938426256,42383,-192,-3059,-2747,1.07501375675201 +35163,0.033528625965119,0.233301267027855,-0.046167582273483,42383,-183,-4371,-2980,1.06289279460907 +35165,0.030064964666963,0.242503732442856,-0.047487415373325,42383,-257,-3855,-2769,1.05600917339325 +35167,0.030578313395381,0.244463533163071,-0.049128733575344,42383,-624,-3888,-3023,1.05473828315735 +35169,0.033556450158358,0.238500475883484,-0.048293232917786,42383,-783,-2803,-2782,1.05820631980896 +35171,0.032927479594946,0.233346208930016,-0.047728233039379,42383,-593,-3285,-3014,1.06190621852875 +35173,0.032573442906141,0.227964371442795,-0.049941260367632,42383,-545,-2780,-2801,1.06619155406952 +35175,0.034535191953182,0.217913299798965,-0.050898373126984,42383,-825,-2762,-3059,1.07094955444336 +35177,0.03320425003767,0.21265372633934,-0.052366018295288,42383,-501,-2649,-2826,1.0744047164917 +35179,0.030375374481082,0.204812347888947,-0.055957034230232,42383,-428,-2781,-3128,1.07274103164673 +35181,0.029490048065782,0.198553279042244,-0.057928919792175,42383,-494,-2448,-2873,1.06606137752533 +35183,0.031208533793688,0.198065370321274,-0.056510534137487,42383,-777,-3278,-3144,1.05782401561737 +35185,0.030501490458846,0.191601157188416,-0.055909216403961,42383,-536,-2406,-2868,1.05281352996826 +35187,0.023506361991167,0.184513404965401,-0.058223810046911,42383,-42,-2657,-3173,1.05250930786133 +35189,0.017370482906699,0.175884008407593,-0.060921266674996,42383,29,-2092,-2912,1.05895006656647 +35191,0.014989723451436,0.163763403892517,-0.063688166439533,42383,-240,-2022,-3247,1.06538772583008 +35193,0.012615378014743,0.153325855731964,-0.065819725394249,42383,-178,-1697,-2956,1.06874585151672 +35195,0.012658541090787,0.151078224182129,-0.066078156232834,42383,-375,-2579,-3287,1.07217609882355 +35197,0.01342595834285,0.161540061235428,-0.063888289034367,42383,-419,-3365,-2953,1.07252407073975 +35199,0.013139123097062,0.163552522659302,-0.061073292046785,42383,-370,-3138,-3238,1.07297348976135 +35201,0.012790609151125,0.158987119793892,-0.064706727862358,42383,-336,-2311,-2969,1.07331156730652 +35203,0.014823963865638,0.160808682441711,-0.068774625658989,42383,-568,-3133,-3339,1.07182335853577 +35205,0.016525940969586,0.160496965050697,-0.067685373127461,42383,-543,-2694,-3000,1.06847667694092 +35207,0.016365872696042,0.155250504612923,-0.066157832741737,42383,-440,-2590,-3319,1.06289649009705 +35209,0.017109904438257,0.146229401230812,-0.068468563258648,42383,-489,-1920,-3017,1.05959045886993 +35211,0.023557219654322,0.14792862534523,-0.069907553493977,42383,-1035,-3022,-3375,1.05457448959351 +35213,0.027798606082797,0.15391381084919,-0.067865706980229,42383,-902,-3156,-3024,1.05107843875885 +35215,0.026673536747694,0.14946785569191,-0.064323469996452,42383,-554,-2662,-3320,1.05054843425751 +35217,0.022832103073597,0.143316179513931,-0.064604856073856,42383,-263,-2188,-3012,1.05262565612793 +35219,0.022739795967937,0.138122364878654,-0.066967017948628,42383,-577,-2472,-3362,1.05831062793732 +35221,0.030355203896761,0.135520339012146,-0.070043914020062,42383,-1202,-2379,-3060,1.05763983726501 +35223,0.034243911504746,0.134952753782272,-0.071450874209404,42383,-1070,-2805,-3426,1.05224096775055 +35225,0.038072548806667,0.125851333141327,-0.069552138447762,42383,-1058,-1822,-3069,1.04759037494659 +35227,0.044402413070202,0.119793497025967,-0.068233676254749,42383,-1438,-2212,-3399,1.04618620872498 +35229,0.05359148234129,0.118799529969692,-0.066006392240524,42383,-1688,-2344,-3055,1.04996573925018 +35231,0.06166010722518,0.118513688445091,-0.065625444054604,42383,-1867,-2642,-3379,1.05482876300812 +35233,0.06669719517231,0.11090312153101,-0.067853480577469,42383,-1609,-1797,-3079,1.05747449398041 +35235,0.073315158486366,0.096680089831352,-0.068114146590233,42383,-1975,-1326,-3420,1.05751502513886 +35237,0.078554257750511,0.100217282772064,-0.067524813115597,42383,-1828,-2474,-3088,1.06140053272247 +35239,0.083775371313095,0.094668760895729,-0.070144169032574,42383,-1575,-1621,-3117,1.06545615196228 +35241,0.080266334116459,0.084609106183052,-0.073600582778454,42383,-1429,-1476,-3508,1.06949782371521 +35243,0.080266334116459,0.084609106183052,-0.073600582778454,42383,-1429,-1476,-3508,1.06949782371521 +35245,0.082986436784268,0.092512033879757,-0.077130138874054,42383,-1929,-2820,-3562,1.06427276134491 +35247,0.082061305642128,0.092238418757916,-0.07469929754734,42383,-1551,-2171,-3173,1.06193244457245 +35249,0.084321074187756,0.090431377291679,-0.075461953878403,42383,-1994,-2225,-3555,1.06188809871674 +35251,0.085628807544708,0.095132946968079,-0.075551256537438,42383,-1803,-2598,-3192,1.06051504611969 +35253,0.085628807544708,0.095132946968079,-0.075551256537438,42383,-1803,-2598,-3192,1.06051504611969 +35255,0.07429264485836,0.086632892489433,-0.076322011649609,42383,-1041,-1531,-3209,1.05892777442932 +35257,0.066731475293636,0.078334502875805,-0.073381654918194,42383,-1084,-1631,-3556,1.06156957149506 +35259,0.064870111644268,0.078455932438374,-0.069204546511173,42383,-1351,-2089,-3173,1.06646168231964 +35261,0.062806241214275,0.091290652751923,-0.069346033036709,42383,-1447,-3376,-3520,1.06853950023651 +35263,0.062806241214275,0.091290652751923,-0.069346033036709,42383,-1447,-3376,-3520,1.06853950023651 +35265,0.058974415063858,0.100109696388245,-0.072926394641399,42383,-1283,-2908,-3575,1.0670417547226 +35267,0.054790809750557,0.097763270139694,-0.075632631778717,42383,-1102,-2253,-3241,1.0643824338913 +35269,0.046117536723614,0.102160051465034,-0.072009280323982,42383,-748,-3007,-3576,1.05822646617889 +35271,0.036328408867121,0.108035534620285,-0.068584851920605,42383,-458,-3024,-3204,1.04987955093384 +35273,0.036328408867121,0.108035534620285,-0.068584851920605,42383,-458,-3024,-3204,1.04987955093384 +35275,0.027587495744228,0.127753928303719,-0.071836858987808,42383,-895,-3653,-3238,1.03689503669739 +35277,0.021444484591484,0.128606259822845,-0.070500753819943,42383,-568,-3264,-3583,1.04047238826752 +35287,-0.004709629807621,0.155523955821991,-0.064270950853825,42383,-81,-4059,-3221,1.05994510650635 +35289,-0.014157565310598,0.160748302936554,-0.064045749604702,42383,243,-4256,-3542,1.05875897407532 +35291,-0.023312319070101,0.170666873455048,-0.062995903193951,42383,322,-4468,-3223,1.05859804153442 +35293,-0.022959919646382,0.160231426358223,-0.061611972749233,42383,-314,-3186,-3523,1.05395376682282 +35295,-0.022689692676067,0.155696764588356,-0.06142794713378,42383,-353,-3281,-3222,1.04704630374908 +35297,-0.020547302439809,0.161002174019814,-0.062185101211071,42383,-475,-4391,-3541,1.04618299007416 +35299,-0.020184816792607,0.176546543836594,-0.062341958284378,42383,-388,-5083,-3239,1.04760825634003 +35301,-0.024230415001512,0.190088614821434,-0.060138013213873,42383,42,-5523,-3527,1.05171024799347 +35303,-0.028301887214184,0.187595218420029,-0.05987935513258,42383,54,-4027,-3233,1.05616366863251 +35305,-0.027485352009535,0.173144951462746,-0.060674920678139,42383,-235,-3318,-3544,1.05789136886597 +35307,-0.0298817679286,0.164101734757423,-0.05949454754591,42383,-29,-3291,-3240,1.05941164493561 +35309,-0.027690580114722,0.16557964682579,-0.056986592710018,42383,-318,-4401,-3510,1.0579696893692 +35311,-0.024436688050628,0.170983955264092,-0.055668376386166,42383,-499,-4492,-3224,1.05533075332642 +35313,-0.020507382228971,0.168978780508041,-0.055090643465519,42383,-557,-4272,-3497,1.05329191684723 +35315,-0.022348450496793,0.166646495461464,-0.054778538644314,42383,-156,-3944,-3227,1.04998314380646 +35351,-0.372927218675613,0.17997895181179,-0.110325418412685,42383,-13806,-1335,-3719,1.03995764255524 +35353,-0.464009523391724,0.189736396074295,-0.117613576352596,42383,-10818,-1932,-4355,1.04198265075684 +35355,-0.568045735359192,0.207405522465706,-0.121737308800221,42383,-9286,-2425,-3817,1.04281890392303 +35357,-0.678805291652679,0.229370474815369,-0.118368811905384,42383,-5881,-3507,-4381,1.04357588291168 +35359,-0.796693086624146,0.243058621883392,-0.115534171462059,42383,-4927,-2716,-3795,1.04463028907776 +35361,-0.909177958965302,0.250668406486511,-0.117123804986477,42383,-1878,-2898,-4382,1.03994071483612 +35363,-1.01878595352173,0.259222805500031,-0.119440041482449,42383,-2138,-2656,-3842,1.02997410297394 +35365,-1.12927424907684,0.257075667381287,-0.121163457632065,42383,1785,-2382,-4445,1.02131950855255 +35367,-1.24575293064117,0.260114967823029,-0.118666186928749,42383,1907,-2354,-3857,1.01578569412231 +35369,-1.35849356651306,0.273706555366516,-0.113428771495819,42383,6005,-3864,-4366,1.01904928684235 +35371,-1.46027064323425,0.282620400190353,-0.107431940734386,42383,4336,-3185,-3798,1.02350401878357 +35373,-1.56273674964905,0.28414711356163,-0.104273483157158,42383,9025,-3262,-4267,1.0323406457901 +35375,-1.65600073337555,0.277402311563492,-0.103600114583969,42383,7035,-2083,-3789,1.04132091999054 +35377,-1.74947559833527,0.280102491378784,-0.103908635675907,42383,11956,-3377,-4271,1.04589569568634 +35379,-1.84277498722076,0.290162563323975,-0.101528137922287,42383,10309,-3563,-3791,1.05187010765076 +35381,-1.92339742183685,0.302709072828293,-0.097756467759609,42383,14497,-4550,-4201,1.06002998352051 +35383,-1.98807334899902,0.3111791908741,-0.095093533396721,42383,11022,-3856,-3762,1.07118630409241 +35385,-2.04321837425232,0.313407897949219,-0.095310613512993,42383,15318,-4085,-4173,1.08004903793335 +35387,-2.09190273284912,0.310677886009216,-0.096840620040894,42383,12104,-3157,-3788,1.09207224845886 +35389,-2.14106202125549,0.31451803445816,-0.098347060382366,42383,17234,-4325,-4211,1.09199118614197 +35391,-2.18310976028442,0.316029608249664,-0.099531538784504,42383,13726,-3648,-3821,1.08492529392242 +35393,-2.20868515968323,0.313841342926025,-0.102425135672092,42383,17445,-3991,-4260,1.07234644889832 +35395,-2.21876215934753,0.309323668479919,-0.104528613388538,42383,12772,-3231,-3870,1.06112420558929 +35397,-2.2247953414917,0.303470104932785,-0.104760780930519,42383,17131,-3667,-4293,1.05560100078583 +35399,-2.22338795661926,0.297694891691208,-0.103170543909073,42383,12855,-3081,-3875,1.05446624755859 +35401,-2.21477317810059,0.286058843135834,-0.100563958287239,42383,16751,-3079,-4251,1.05913472175598 +35403,-2.19906044006348,0.271681874990463,-0.096554718911648,42383,12321,-2192,-3844,1.06840133666992 +35405,-2.17458724975586,0.265247792005539,-0.094042167067528,42383,15786,-3210,-4184,1.08121311664581 +35407,-2.13793420791626,0.25987121462822,-0.093010365962982,42383,10770,-2759,-3832,1.09362256526947 +35409,-2.09268879890442,0.260403603315353,-0.095618717372418,42383,13776,-3720,-4207,1.10192346572876 +35411,-2.04019212722778,0.253843784332275,-0.095244854688644,42383,9027,-2678,-3860,1.1020233631134 +35413,-1.98459529876709,0.255391806364059,-0.089593380689621,42383,12045,-3803,-4141,1.09450435638428 +35415,-1.92500495910645,0.258689671754837,-0.084985852241516,42383,7616,-3543,-3800,1.08823704719543 +35417,-1.85685205459595,0.253208309412003,-0.081895358860493,42383,9782,-3350,-4053,1.08656656742096 +35419,-1.77992212772369,0.250895529985428,-0.081279382109642,42383,4988,-3118,-3785,1.0850031375885 +35421,-1.69161629676819,0.237244561314583,-0.081772051751614,42383,6318,-2596,-4062,1.08448934555054 +35423,-1.60729289054871,0.232537925243378,-0.082579664885998,42383,2606,-2766,-3803,1.08187019824982 +35425,-1.52890849113464,0.230719923973083,-0.079466715455055,42383,4975,-3420,-4041,1.08201992511749 +35427,-1.44784259796143,0.23342627286911,-0.076028071343899,42383,1106,-3391,-3768,1.08328115940094 +35429,-1.35957431793213,0.23939648270607,-0.072923883795738,42383,2032,-4196,-3961,1.08588099479675 +35431,-1.2664065361023,0.236427307128906,-0.069669023156166,42383,-1883,-3112,-3732,1.08765017986298 +35433,-1.17409074306488,0.238808944821358,-0.069804146885872,42383,-831,-4009,-3927,1.08800423145294 +35435,-1.09034895896912,0.241855949163437,-0.066698990762234,42383,-3335,-3704,-3718,1.08660650253296 +35437,-1.01260995864868,0.245175704360008,-0.061624530702829,42383,-2047,-4269,-3828,1.08087944984436 +35439,-0.933799028396606,0.243375644087791,-0.057248312979937,42383,-4901,-3467,-3659,1.08284938335419 +35441,-0.853127777576447,0.235776007175446,-0.052299700677395,42383,-4568,-3418,-3727,1.08574891090393 +35443,-0.771764874458313,0.235515385866165,-0.048112578690052,42383,-7154,-3549,-3600,1.08867824077606 +35445,-0.689979255199432,0.234090030193329,-0.048508021980524,42383,-7087,-3917,-3684,1.09295725822449 +35447,-0.619656443595886,0.235746294260025,-0.04837629199028,42383,-8366,-3774,-3605,1.09263098239899 +35449,-0.559099435806274,0.233869597315788,-0.044496338814497,42383,-7548,-3968,-3638,1.09658980369568 +35451,-0.500969111919403,0.230782881379127,-0.043420001864433,42383,-9075,-3449,-3573,1.09711790084839 +35453,-0.446058332920074,0.231395095586777,-0.044371843338013,42383,-8887,-4191,-3640,1.09566760063171 +35455,-0.400332123041153,0.224614143371582,-0.041532546281815,42383,-9561,-3180,-3563,1.09343707561493 +35457,-0.362960010766983,0.225420251488686,-0.037980396300554,42383,-8930,-4190,-3570,1.08917534351349 +35459,-0.32337099313736,0.220390990376472,-0.036556992679834,42383,-10194,-3328,-3530,1.08876574039459 +35461,-0.292759478092194,0.223467960953712,-0.038717664778233,42383,-9569,-4403,-3581,1.08614385128021 +35463,-0.271123200654984,0.223522752523422,-0.040115691721439,42383,-9657,-3819,-3557,1.08173537254334 +35465,-0.251415967941284,0.221450015902519,-0.039475128054619,42383,-9474,-4075,-3592,1.0807158946991 +35467,-0.233363911509514,0.219830259680748,-0.044320501387119,42383,-9961,-3727,-3587,1.07531833648682 +35469,-0.224517092108726,0.212499096989632,-0.050930138677359,42383,-9156,-3633,-3736,1.07483339309692 +35471,-0.224188163876533,0.200614959001541,-0.053293850272894,42383,-8854,-2793,-3653,1.07414925098419 +35473,-0.228629916906357,0.185589551925659,-0.055031523108482,42383,-8158,-2722,-3807,1.0749728679657 +35475,-0.23317189514637,0.168013468384743,-0.055671907961369,42383,-8402,-1984,-3675,1.07593107223511 +35477,-0.248532220721245,0.165579661726952,-0.054879125207663,42383,-7078,-3361,-3826,1.07644855976105 +35479,-0.267071217298508,0.164502993226051,-0.057589247822762,42383,-6931,-3173,-3694,1.07984101772308 +35481,-0.286407500505447,0.15550833940506,-0.063243485987187,42383,-6192,-2783,-3938,1.08004796504974 +35483,-0.310092657804489,0.142258122563362,-0.064718514680863,42383,-5945,-2036,-3750,1.07941424846649 +35485,-0.335766494274139,0.130313336849213,-0.06268497556448,42383,-4931,-2212,-3958,1.07446444034576 +35487,-0.362386703491211,0.117280311882496,-0.063275337219238,42383,-4962,-1736,-3748,1.0650669336319 +35489,-0.392047435045242,0.1019237190485,-0.066781625151634,42383,-3694,-1549,-4035,1.05859780311584 +35491,-0.431942701339722,0.094479449093342,-0.073347225785256,42383,-2964,-1840,-3827,1.05589532852173 +35493,-0.473727911710739,0.088325351476669,-0.074584655463696,42383,-1421,-2021,-4146,1.05529832839966 +35495,-0.51786595582962,0.082854487001896,-0.068892277777195,42383,-1337,-1840,-3807,1.05413866043091 +35497,-0.564048409461975,0.081773690879345,-0.066206961870194,42383,478,-2301,-4062,1.05799531936646 +35499,-0.607495844364166,0.086653165519238,-0.067083619534969,42383,32,-2659,-3805,1.06498908996582 +35501,-0.642410933971405,0.082377687096596,-0.066048353910446,42383,1094,-2102,-4068,1.0726854801178 +35503,-0.675501227378845,0.072180964052677,-0.063971027731896,42383,438,-1395,-3793,1.07757186889648 +35505,-0.707535445690155,0.057662911713123,-0.06304931640625,42383,2128,-979,-4062,1.08077025413513 +35507,-0.736579537391663,0.05505770072341,-0.060716766864061,42383,1227,-1704,-3781,1.08131814002991 +35509,-0.762741625308991,0.051524221897125,-0.057637605816126,42383,2823,-1673,-4012,1.08086407184601 +35511,-0.799854874610901,0.053516276180744,-0.059363592416048,42383,2944,-2019,-3780,1.07227718830109 +35513,-0.8378586769104,0.053944908082485,-0.063163489103317,42383,5137,-2004,-4084,1.05816113948822 +35515,-0.867315053939819,0.051807690411806,-0.063345372676849,42383,3630,-1708,-3818,1.0477819442749 +35517,-0.882932305335999,0.042650599032641,-0.060142204165459,42383,4537,-1138,-4068,1.04219818115234 +35519,-0.901826024055481,0.033584751188755,-0.05789539963007,42383,3658,-953,-3790,1.04636323451996 +35521,-0.913402795791626,0.028577104210854,-0.05864692479372,42383,5040,-1206,-4071,1.05201578140259 +35523,-0.923693835735321,0.036126956343651,-0.055924061685801,42383,3662,-2177,-3786,1.05974280834198 +35525,-0.935887157917023,0.034108094871044,-0.049131643027067,42383,5764,-1507,-3963,1.06455385684967 +35527,-0.953355312347412,0.03632902726531,-0.043786350637674,42383,4921,-1797,-3711,1.068598985672 +35529,-0.960746347904205,0.031160302460194,-0.0418840944767,42383,6152,-1228,-3888,1.07683372497559 +35531,-0.960859298706055,0.035569008439779,-0.04206058010459,42383,4120,-1941,-3706,1.07879614830017 +35533,-0.956035614013672,0.036636017262936,-0.042537957429886,42383,5526,-1766,-3898,1.07810926437378 +35535,-0.948982179164886,0.040178090333939,-0.041965868324041,42383,3769,-1945,-3713,1.0754519701004 +35537,-0.931651890277862,0.046071138232946,-0.042535062879324,42383,4552,-2272,-3896,1.07051050662994 +35539,-0.90361362695694,0.048749607056379,-0.048174642026425,42383,1937,-2012,-3762,1.06975209712982 +35541,-0.872790336608887,0.049176178872585,-0.054681427776814,42383,2935,-1948,-4042,1.06960201263428 +35543,-0.853327453136444,0.05273275449872,-0.05453085154295,42383,2128,-2141,-3814,1.0667005777359 +35545,-0.833451330661774,0.058806087821722,-0.050087604671717,42383,3373,-2522,-3987,1.06244266033173 +35547,-0.811280906200409,0.066068202257156,-0.044530171900988,42383,1613,-2612,-3753,1.06141149997711 +35549,-0.783879578113556,0.068146295845509,-0.041574910283089,42383,2305,-2399,-3884,1.06543636322021 +35551,-0.750095009803772,0.072660461068153,-0.040927957743406,42383,165,-2527,-3734,1.06803810596466 +35553,-0.715654015541077,0.075499542057514,-0.042687579989433,42383,941,-2585,-3894,1.07224655151367 +35555,-0.678033292293549,0.074046820402145,-0.042401120066643,42383,-910,-2140,-3750,1.07616543769836 +35557,-0.642670035362244,0.084669820964336,-0.039561785757542,42383,-89,-3305,-3853,1.07752394676209 +35559,-0.6105135679245,0.093631356954575,-0.036499299108982,42383,-1285,-3190,-3714,1.07371950149536 +35561,-0.580822825431824,0.104414522647858,-0.036275912076235,42383,-497,-3660,-3798,1.06690800189972 +35563,-0.545206606388092,0.106414616107941,-0.037980254739523,42383,-2295,-2906,-3728,1.06115520000458 +35579,-0.298418581485748,0.124604515731335,-0.031874760985375,42383,-4281,-3215,-3699,1.08572041988373 +35581,-0.279678791761398,0.117265060544014,-0.031809527426958,42383,-4115,-2759,-3748,1.08158254623413 +35583,-0.252000451087952,0.105005636811256,-0.032643735408783,42383,-5502,-2054,-3707,1.0757223367691 +35585,-0.229207426309586,0.099758192896843,-0.033159282058477,42383,-5201,-2664,-3784,1.0667462348938 +35587,-0.218292206525803,0.103313349187374,-0.032961290329695,42383,-4768,-3195,-3712,1.06308662891388 +35589,-0.209582835435867,0.105647392570972,-0.031173657625914,42383,-4495,-3332,-3757,1.06411838531494 +35591,-0.197889551520348,0.10440606623888,-0.031073989346624,42383,-5109,-2902,-3702,1.06869983673096 +35593,-0.18502514064312,0.100073717534542,-0.031974475830793,42383,-5185,-2798,-3775,1.07376873493195 +35595,-0.181364476680756,0.105605103075504,-0.033210832625628,42383,-4772,-3437,-3720,1.07427608966827 +35597,-0.183963850140572,0.116264224052429,-0.03482873365283,42383,-4096,-4177,-3794,1.07511138916016 +35599,-0.183563649654388,0.115493267774582,-0.035155892372131,42383,-4509,-3169,-3736,1.07966804504395 +35601,-0.183826506137848,0.117923259735107,-0.037028525024653,42383,-4274,-3655,-3822,1.08456337451935 +35603,-0.179769545793533,0.112317949533463,-0.038182463496924,42383,-4829,-2819,-3760,1.08218502998352 +35605,-0.180530622601509,0.101918585598469,-0.036567468196154,42383,-4305,-2521,-3837,1.07324707508087 +35607,-0.187996834516525,0.093587666749954,-0.034327428787947,42383,-3891,-2391,-3737,1.06870317459106 +35609,-0.199222058057785,0.08710415661335,-0.035908151417971,42383,-3260,-2595,-3849,1.06575477123261 +35611,-0.207270860671997,0.084824703633785,-0.039979066699743,42383,-3571,-2728,-3780,1.06265676021576 +35613,-0.21387192606926,0.075772769749165,-0.039847541600466,42383,-3351,-2253,-3912,1.06080138683319 +35615,-0.223659157752991,0.069921232759953,-0.038866739720106,42383,-3203,-2283,-3778,1.05883347988129 +35617,-0.233547225594521,0.069226451218128,-0.041073124855757,42383,-2778,-2772,-3938,1.05941379070282 +35619,-0.244433805346489,0.06408454477787,-0.043821733444929,42383,-2807,-2273,-3817,1.06404948234558 +35621,-0.259742468595505,0.060627531260252,-0.040448438376188,42383,-1933,-2460,-3945,1.06391859054565 +35623,-0.278023421764374,0.0503692291677,-0.033688057214022,42383,-1763,-1729,-3753,1.06703841686249 +35625,-0.287682086229324,0.043812934309244,-0.032876700162888,42383,-1841,-1978,-3879,1.0685727596283 +35627,-0.2960344851017,0.049394249916077,-0.032212290912867,42383,25416,-7549,-3748,1.0746556520462 +35629,-0.315059244632721,0.052986066788435,-0.028787232935429,42383,3981,-3647,-3827,1.07943320274353 +35631,-0.33714160323143,0.05253741890192,-0.02836649864912,42383,4144,-3284,-3726,1.0787752866745 +35633,-0.34683096408844,0.042061943560839,-0.030326947569847,42383,3938,-2479,-3861,1.07244956493378 +35635,-0.351268380880356,0.043045341968536,-0.032830949872732,42383,3203,-3266,-3762,1.06148982048035 +35637,-0.35516557097435,0.047292146831751,-0.036501463502646,42383,3781,-3638,-3932,1.05729341506958 +35639,-0.359339952468872,0.043003346771002,-0.04007763043046,42383,3425,-2907,-3817,1.05745446681976 +35641,-0.360708147287369,0.039436344057322,-0.041683923453093,42383,3823,-2972,-4006,1.0604852437973 +35643,-0.351043075323105,0.031526405364275,-0.04006901755929,42383,2444,-2499,-3824,1.06367039680481 +35645,-0.332992792129517,0.026215741410852,-0.037994299083948,42383,2109,-2645,-3984,1.06440412998199 +35647,-0.313665360212326,0.017458327114582,-0.036163605749607,42383,1333,-2247,-3803,1.06983363628387 +35649,-0.293436199426651,0.00167621136643,-0.035604353994131,42383,1420,-1495,-3989,1.07509851455688 +35651,-0.273470193147659,-0.007584713865072,-0.034824211150408,42383,811,-1850,-3801,1.07737803459167 +35653,-0.247271552681923,-0.01530235260725,-0.032016735523939,42383,334,-1789,-3973,1.07250285148621 +35655,-0.222530961036682,-0.019914427772164,-0.030362473800778,42383,-181,-1995,-3778,1.0636225938797 +35657,-0.201146572828293,-0.02023552544415,-0.027147714048624,42383,-7,-2228,-3929,1.05922031402588 +35659,-0.176764309406281,-0.023323459550738,-0.024078883230686,42383,-754,-2043,-3741,1.06051743030548 +35661,-0.14927114546299,-0.021270206198096,-0.025173846632242,42383,-1246,-2369,-3914,1.05992925167084 +35663,-0.115453720092773,-0.023449834436178,-0.026160603389144,42383,-2277,-2093,-3762,1.06002020835876 +35665,-0.08821301907301,-0.014355743303895,-0.02725032903254,42383,25393,-21731,-3936,1.0597870349884 +35667,-0.063192412257195,-0.007619780488312,-0.028864081948996,42383,2268,-6116,-3787,1.05973219871521 +35669,-0.037514913827181,-0.009844843298197,-0.029249254614115,42383,1775,-5417,-3961,1.06029295921326 +35671,-0.00747897522524,-0.020048590376973,-0.028871655464172,42383,1139,-4749,-3793,1.06042575836182 +35673,0.026959199458361,-0.031440816819668,-0.030079348012805,42383,116,-4429,-4001,1.06066834926605 +35675,0.061413198709488,-0.030100168660283,-0.032997582107782,42383,-165,-5446,-3829,1.06235814094543 +35677,0.097011625766754,-0.027884718030691,-0.03125337138772,42383,-1120,-5474,-4018,1.06332266330719 +35679,0.136701464653015,-0.036965403705835,-0.032482281327248,42383,-1654,-4617,-3833,1.059046626091 +35681,0.179057717323303,-0.055372077971697,-0.036134418100119,42383,-2990,-3565,-4113,1.05331432819366 +35683,0.223143219947815,-0.079399429261685,-0.037594951689243,42383,-3280,-2940,-3878,1.05072259902954 +35685,0.264129191637039,-0.091879449784756,-0.036574464291334,42383,-4372,-3389,-4168,1.05077457427979 +35687,0.306705445051193,-0.102988868951797,-0.034149553626776,42383,-4485,-3513,-3865,1.05138599872589 +35689,0.344834119081497,-0.115166567265987,-0.033484697341919,42383,-5606,-3018,-4166,1.0516197681427 +35691,0.378583759069443,-0.120043732225895,-0.034883745014668,42383,-5035,-3691,-3881,1.05101823806763 +35693,0.415018260478973,-0.130096346139908,-0.036743361502886,42383,-6785,-2913,-4230,1.0491646528244 +35695,0.447867631912231,-0.139098152518272,-0.039033327251673,42383,-6148,-3093,-3922,1.04948043823242 +35697,0.48236072063446,-0.154135704040527,-0.03951433300972,42383,-7936,-2129,-4298,1.05501675605774 +35699,0.507149994373322,-0.160585477948189,-0.038129564374685,42383,-6637,-2926,-3929,1.06317126750946 +35701,0.5235595703125,-0.170288890600205,-0.039493005722761,42383,-7539,-2196,-4326,1.07043135166168 +35703,0.541916251182556,-0.180731013417244,-0.04113632440567,42383,20673,-2301,-3963,1.07042872905731 +35705,0.561530530452728,-0.191921815276146,-0.040824040770531,42383,-3977,-1689,-4376,1.06472766399384 +35707,0.572527408599854,-0.205295503139496,-0.042889889329672,42383,-2399,-1678,-3989,1.06145739555359 +35709,0.580902993679047,-0.209318816661835,-0.045487839728594,42383,-3705,-1860,-4460,1.05820667743683 +35711,0.603416323661804,-0.212415114045143,-0.047950502485037,42383,-3890,-2245,-4040,1.05700945854187 +35731,0.746188640594482,-0.22313004732132,-0.051464602351189,42383,-6040,-1564,-4142,1.06820833683014 +35733,0.743842840194702,-0.226527392864227,-0.04930005595088,42383,-7213,-1163,-4593,1.06278860569 +35735,0.742047011852264,-0.217704147100449,-0.045412916690111,42383,-5831,-2560,-4116,1.06121981143951 +35737,0.740547776222229,-0.205860987305641,-0.043784890323877,42383,-7528,-2515,-4521,1.05988919734955 +35739,0.738570868968964,-0.20395739376545,-0.042423233389855,42383,-6078,-2189,-4110,1.05662965774536 +35741,0.738125264644623,-0.217118471860886,-0.044335290789604,42383,19711,-482,-4548,1.05570566654205 +35743,0.736733794212341,-0.228432148694992,-0.047900605946779,42383,-1746,-816,-4162,1.05170679092407 +35745,0.726049363613129,-0.223000526428223,-0.047888901084662,42383,-2568,-1648,-4606,1.05299270153046 +35747,0.710891127586365,-0.212771698832512,-0.04673345759511,42383,-651,-2506,-4169,1.06006824970245 +35749,0.695105969905853,-0.19547238945961,-0.047468058764935,42383,-1946,-2865,-4588,1.06666326522827 +35751,0.687909007072449,-0.191165700554848,-0.051684819161892,42383,-1139,-2325,-4217,1.07321691513062 +35753,0.678098857402802,-0.192462652921677,-0.052972987294197,42383,-2339,-1512,-4661,1.07035648822784 +35755,0.663948178291321,-0.189167305827141,-0.05208870023489,42383,-539,-2215,-4235,1.06426966190338 +35757,0.654037058353424,-0.180785953998566,-0.051144357770681,42383,-2179,-2328,-4641,1.05837881565094 +35759,0.6512091755867,-0.164973884820938,-0.048441126942635,42383,-1401,-3396,-4224,1.05226230621338 +35761,0.649182319641113,-0.147921085357666,-0.044269178062677,42383,-2897,-3426,-4544,1.04776537418365 +35763,0.656131207942963,-0.150563582777977,-0.04047154635191,42383,-2406,-2233,-4181,1.03891324996948 +35765,0.666716396808624,-0.155665308237076,-0.040634013712406,42383,-4326,-1666,-4518,1.03882956504822 +35767,0.67684406042099,-0.156653687357903,-0.043849945068359,42383,-3175,-2212,-4216,1.04585361480713 +35769,0.675710916519165,-0.140912041068077,-0.047662526369095,42383,-3881,-3348,-4598,1.05042016506195 +35771,0.67871218919754,-0.126974523067474,-0.049334820359945,42383,-2942,-3662,-4266,1.05574381351471 +35773,0.678554594516754,-0.113199785351753,-0.046585932374001,42383,-4238,-3621,-4573,1.05767524242401 +35775,0.676003813743591,-0.104175694286823,-0.040505968034268,42383,-2758,-3604,-4216,1.05712473392487 +35777,0.669321000576019,-0.101068109273911,-0.039667222648859,42383,-3860,-3024,-4491,1.05887842178345 +35779,0.657386481761932,-0.097870603203774,-0.041742410510779,42383,25338,-3250,-4235,1.05789458751678 +35781,0.650591969490051,-0.096202209591866,-0.040111407637596,42383,833,-2962,-4501,1.05605447292328 +35783,0.652571260929108,-0.094854578375816,-0.036337725818157,42383,1413,-3134,-4207,1.05630469322205 +35785,0.654501497745514,-0.08849386125803,-0.037076655775309,42383,-54,-3384,-4467,1.05612516403198 +35787,0.664053082466126,-0.09101253002882,-0.040540244430304,42383,505,-2885,-4245,1.05340969562531 +35789,0.678195714950562,-0.092201218008995,-0.042807593941689,42383,-1518,-2765,-4545,1.04849016666412 +35791,0.697658717632294,-0.090464845299721,-0.038637395948172,42383,-900,-3171,-4242,1.04983305931091 +35793,0.720748960971832,-0.084154956042767,-0.035125244408846,42383,-3062,-3409,-4457,1.05109095573425 +35795,0.743179857730866,-0.082925394177437,-0.039468534290791,42383,-1999,-3220,-4256,1.05453276634216 +35797,0.762814939022064,-0.083179749548435,-0.043139055371285,42383,-3734,-2934,-4557,1.05724728107452 +35799,0.77671229839325,-0.078343838453293,-0.039720471948385,42383,-2123,-3521,-4267,1.06287622451782 +35801,0.792961359024048,-0.075035609304905,-0.033974230289459,42383,-4244,-3297,-4452,1.06887757778168 +35803,0.816018581390381,-0.070680730044842,-0.034637156873942,42383,-3615,-3577,-4240,1.07239663600922 +35805,0.835083842277527,-0.066935360431671,-0.039329025894404,42383,-5416,-3443,-4517,1.07633852958679 +35807,0.854623675346375,-0.073660664260388,-0.038176409900189,42383,-4210,-2724,-4273,1.07478713989258 +35809,0.872279286384583,-0.069728262722492,-0.039697837084532,42383,-6221,-3400,-4530,1.07107079029083 +35811,0.887514054775238,-0.069604106247425,-0.040142349898815,42383,-4687,-3256,-4295,1.06778931617737 +35813,0.895192444324493,-0.070688419044018,-0.039084941148758,42383,-6201,-3009,-4531,1.06254065036774 +35815,0.907737791538238,-0.074133820831776,-0.038933478295803,42383,-5113,-2919,-4296,1.05781137943268 +35817,0.925833761692047,-0.07488689571619,-0.041665274649859,42383,-7783,-2941,-4571,1.05598258972168 +35819,0.943769931793213,-0.076067484915257,-0.041397612541914,42383,-6361,-3033,-4322,1.05434501171112 +35821,0.952408313751221,-0.072112143039703,-0.040094416588545,42383,-7882,-3305,-4558,1.05405843257904 +35823,0.95975923538208,-0.064679935574532,-0.042543154209852,42383,-6191,-3795,-4338,1.0541787147522 +35825,0.959357023239136,-0.049009807407856,-0.046724066138268,42383,-7697,-4518,-4630,1.05567359924316 +35827,0.950335383415222,-0.047966305166483,-0.045997351408005,42383,-5247,-3570,-4371,1.0605503320694 +35829,0.93291586637497,-0.047297574579716,-0.045536607503891,42383,-6408,-3468,-4624,1.0667473077774 +35831,0.92675918340683,-0.058181770145893,-0.047135163098574,42383,-5468,-2564,-4388,1.07552480697632 +35833,0.922924935817718,-0.059094734489918,-0.048345528542996,42383,-7573,-3149,-4671,1.07960069179535 +35835,0.913837730884552,-0.060762695968151,-0.049067657440901,42383,-5426,-3175,-4411,1.08477342128754 +35837,0.898176610469818,-0.069850109517574,-0.049887746572495,42383,-6672,-2373,-4704,1.07979667186737 +35839,0.886665463447571,-0.083651661872864,-0.049507237970829,42383,-5207,-1961,-4424,1.07078170776367 +35841,0.873371243476868,-0.088834814727306,-0.054221265017986,42383,-6780,-2326,-4773,1.0625718832016 +35843,0.851618647575378,-0.089183479547501,-0.058755598962307,42383,-4307,-2819,-4499,1.05683696269989 +35845,0.824130535125732,-0.086789786815643,-0.060125041753054,42383,-5292,-2876,-4852,1.05199372768402 +35847,0.798940658569336,-0.090338908135891,-0.058883748948574,42383,-3621,-2548,-4512,1.05037331581116 +35849,0.77576756477356,-0.090131364762783,-0.055550903081894,42383,-5120,-2638,-4810,1.05001652240753 +35851,0.754715621471405,-0.095563262701035,-0.051489926874638,42383,-3580,-2311,-4472,1.04967856407166 +35853,0.729997098445892,-0.098073117434979,-0.047521848231554,42383,-4544,-2290,-4728,1.04994869232178 +35855,0.701262593269348,-0.094912633299828,-0.042403273284435,42383,-2539,-2906,-4419,1.05271232128143 +35857,0.674660980701447,-0.096074834465981,-0.042898505926132,42383,-3771,-2388,-4681,1.05698800086975 +35859,0.647040009498596,-0.09637425839901,-0.046309176832438,42383,-2093,-2607,-4455,1.06037878990173 +35861,0.621918857097626,-0.110179014503956,-0.044904582202435,42383,-3256,-1222,-4718,1.06336438655853 +35863,0.591560482978821,-0.11412163823843,-0.043995156884194,42383,-1330,-2056,-4449,1.05730020999908 +35865,0.564034223556519,-0.117765098810196,-0.042323891073465,42383,-2361,-1782,-4699,1.05086290836334 +35881,0.388519942760468,-0.151305466890335,-0.034707386046648,42383,-491,-741,-4650,1.04601144790649 +35883,0.375905364751816,-0.159699782729149,-0.031276248395443,42383,-345,-826,-4404,1.0489262342453 +35885,0.367996841669083,-0.163142517209053,-0.030178882181645,42383,-1366,-797,-4607,1.0530332326889 +35887,0.356104612350464,-0.167013570666313,-0.029862593859434,42383,-232,-982,-4402,1.05789721012115 +35889,0.336446106433868,-0.162607192993164,-0.029538070783019,42383,-124,-1297,-4606,1.06174468994141 +35891,0.327071964740753,-0.163108482956886,-0.030642544850707,42383,32767,-1214,-4415,1.06510758399963 +35893,0.324884623289108,-0.165711283683777,-0.031287372112274,42383,29164,-673,-4634,1.06347620487213 +35895,0.317529797554016,-0.167937368154526,-0.032097604125738,42383,30388,-953,-4432,1.06217586994171 +35897,0.303403586149216,-0.15886452794075,-0.033816851675511,42383,30582,-1550,-4668,1.062983751297 +35899,0.301278442144394,-0.148399502038956,-0.034797325730324,42383,30457,-2077,-4459,1.06082165241241 +35901,0.314887702465057,-0.146559566259384,-0.040155410766602,42383,28617,-1171,-4746,1.05441176891327 +35903,0.347622990608215,-0.144562959671021,-0.049297749996185,42383,27499,-1465,-4568,1.04771065711975 +35905,0.39130362868309,-0.133542403578758,-0.05865041166544,42383,25396,-1988,-4969,1.04231786727905 +35907,0.448219507932663,-0.124270766973495,-0.064595140516758,42383,24490,-2223,-4685,1.04579508304596 +35909,0.518411993980408,-0.10849417001009,-0.068184912204743,42383,21570,-2690,-5084,1.05305874347687 +35911,0.60932457447052,-0.096147753298283,-0.070091500878334,42383,19849,-2805,-4736,1.06213390827179 +35913,0.70792818069458,-0.079972453415394,-0.070989817380905,42383,16524,-3149,-5120,1.07088446617126 +35915,0.815497994422913,-0.067755691707134,-0.070389196276665,42383,15715,-3174,-4751,1.08301436901093 +35917,0.933405935764313,-0.061344332993031,-0.072000160813332,42383,11440,-2722,-5139,1.09331369400024 +35919,1.06504356861115,-0.040274556726217,-0.077208586037159,42383,10320,-4181,-4811,1.10613000392914 +35921,1.20445656776428,-0.019030598923564,-0.079625852406025,42383,5339,-4458,-5230,1.10910427570343 +35923,1.34359192848206,-0.004985886625946,-0.078429482877255,42383,5568,-4182,-4833,1.1053581237793 +35925,1.48766124248505,0.001926545985043,-0.07537292689085,42383,120,-3781,-5188,1.09776520729065 +35927,1.63664329051971,0.023253746330738,-0.074566245079041,42383,303,-5118,-4820,1.08855032920837 +35929,1.78900802135468,0.051571905612946,-0.069821283221245,42383,-5783,-6139,-5125,1.09187853336334 +35931,1.94979345798492,0.067997127771378,-0.064909793436527,42383,-5531,-5440,-4765,1.09394383430481 +35933,2.1078200340271,0.087056882679463,-0.062194138765335,42383,-11925,-6089,-5042,1.09643375873566 +35935,2.2580201625824,0.097067430615425,-0.058678913861513,42383,-9843,-5445,-4733,1.0968621969223 +35937,2.40072059631348,0.119568206369877,-0.053387936204672,42383,-16296,-6912,-4948,1.0995100736618 +35939,2.53926968574524,0.137426033616066,-0.047662328928709,42383,-13833,-6647,-4666,1.10642719268799 +35941,2.66239905357361,0.165688619017601,-0.046136606484652,42383,-19996,-8142,-4874,1.10718643665314 +35943,2.78023338317871,0.179194658994675,-0.045585922896862,42383,-16724,-7018,-4660,1.10508573055267 +35945,2.8945300579071,0.1825752556324,-0.048348043113947,42383,-24104,-6729,-4917,1.09154903888702 +35947,2.99887323379517,0.196114584803581,-0.04958900436759,42383,-19928,-7356,-4696,1.07794094085693 +35949,3.09265661239624,0.20716404914856,-0.051261257380247,42383,-26924,-7777,-4972,1.07258200645447 +35951,3.17753839492798,0.213471844792366,-0.058255106210709,42383,-22229,-7191,-4765,1.07124972343445 +35953,3.25111937522888,0.205082580447197,-0.06624298542738,42383,-29203,-6457,-5171,1.07085955142975 +35955,3.30061674118042,0.203341573476791,-0.069208584725857,42383,-22672,-6574,-4853,1.06654179096222 +35957,3.33977746963501,0.210414156317711,-0.068297207355499,42383,-29393,-7759,-5221,1.06741487979889 +35959,3.37300634384155,0.224327638745308,-0.069780670106411,42383,-23805,-8105,-4870,1.07273256778717 +35961,3.39411306381226,0.233347609639168,-0.075200788676739,42383,-30250,-8374,-5334,1.0779402256012 +35963,3.40301966667175,0.239152789115906,-0.07737746834755,42383,-23787,-7854,-4937,1.07709145545959 +35965,3.40026593208313,0.241119593381882,-0.082301080226898,42383,-29939,-8106,-5451,1.07151854038239 +35967,3.38611841201782,0.234360858798027,-0.08886244148016,42383,-23200,-7006,-5033,1.06940853595734 +35969,3.36169505119324,0.227800026535988,-0.094066679477692,42383,-29058,-7389,-5617,1.06448352336884 +35971,3.32441401481628,0.224547475576401,-0.100263051688671,42383,-21957,-7230,-5130,1.0577358007431 +35973,3.27489399909973,0.221809223294258,-0.105927370488644,42383,-27116,-7674,-5787,1.04718172550201 +35975,3.20817708969116,0.216063916683197,-0.106473580002785,42383,-19447,-7041,-5194,1.04489517211914 +35977,3.1324577331543,0.200690627098083,-0.105768799781799,42383,-24155,-6528,-5809,1.05068647861481 +35979,3.05204844474792,0.198836028575897,-0.107960306107998,42383,-17435,-7174,-5226,1.05644512176514 +35981,2.96808934211731,0.195363402366638,-0.11196906119585,42383,-22066,-7394,-5911,1.05939495563507 +35983,2.87888026237488,0.182753831148148,-0.115115493535995,42383,-15462,-6272,-5297,1.05949747562408 +35985,2.78600072860718,0.162023335695267,-0.116026878356934,42383,-19560,-5706,-5971,1.06106865406036 +35987,2.67915320396423,0.147260010242462,-0.121352948248386,42383,-12398,-5693,-5363,1.06493711471558 +35989,2.56739974021912,0.123860381543636,-0.125281453132629,42383,-15656,-4961,-6084,1.07094395160675 +35991,2.44514393806458,0.100752659142017,-0.127493068575859,42383,-8905,-4493,-5429,1.06678783893585 +35993,2.32303667068481,0.084549963474274,-0.127442061901093,42383,-11857,-4888,-6110,1.06515693664551 +35995,2.20240950584412,0.072222322225571,-0.127032458782196,42383,-6402,-4902,-5450,1.06604278087616 +35997,2.07718634605408,0.063998229801655,-0.130365893244743,42383,-8448,-5165,-6155,1.05949115753174 +35999,1.95786798000336,0.042164504528046,-0.130404219031334,42383,-3743,-3826,-5496,1.05474305152893 +36001,1.83321964740753,0.023304555565119,-0.128533720970154,42383,-5220,-3772,-6126,1.04996705055237 +36003,1.71118676662445,-0.006454288028181,-0.12439800798893,42383,-657,-2579,-5477,1.05468559265137 +36005,1.59024751186371,-0.042554348707199,-0.119168534874916,42383,-2126,-1477,-5983,1.0511155128479 +36007,1.47200858592987,-0.072024397552013,-0.113228894770145,42383,1962,-1648,-5419,1.04701709747314 +36009,1.36166191101074,-0.101945735514164,-0.103914529085159,42383,339,-936,-5770,1.04539704322815 +36011,1.24773800373077,-0.122209042310715,-0.101218357682228,42383,4433,-1549,-5351,1.03290736675262 +36013,1.14390254020691,-0.1468525826931,-0.103068366646767,42383,3017,-537,-5733,1.0329464673996 +36033,0.46956467628479,-0.286872982978821,-0.085135661065579,42383,7947,980,-5428,1.08693671226501 +36035,0.446745067834854,-0.295211434364319,-0.083986520767212,42383,8389,655,-5285,1.08776700496674 +36037,0.432407975196838,-0.306765556335449,-0.08480180054903,42383,7325,1728,-5410,1.09350025653839 +36039,0.418112605810165,-0.30408301949501,-0.083988025784493,42383,8166,129,-5290,1.09764289855957 +36041,0.419422388076782,-0.294684708118439,-0.083277300000191,42383,6392,165,-5407,1.09209716320038 +36043,0.425407856702805,-0.282699227333069,-0.082669362425804,42168,6590,-712,-5286,1.08708608150482 +36045,0.435226738452911,-0.279855608940125,-0.079890534281731,42168,5493,517,-5385,1.08239912986755 +36047,0.451522201299667,-0.277542263269424,-0.082915589213371,42168,5448,30,-5293,1.07675158977509 +36049,0.483190208673477,-0.273647278547287,-0.085262648761273,42168,3105,469,-5457,1.0732489824295 +36051,0.513882637023926,-0.264502584934235,-0.081751927733421,42168,3469,-522,-5290,1.07039499282837 +36053,0.54170161485672,-0.246197417378426,-0.077586337924004,42168,2372,-891,-5398,1.06804263591766 +36055,0.574613034725189,-0.22696778178215,-0.073360107839108,42168,2359,-1671,-5238,1.06625390052795 +36057,0.609497785568237,-0.203435897827148,-0.06996438652277,42168,679,-1863,-5353,1.06694519519806 +36059,0.653082251548767,-0.186745598912239,-0.069306895136833,42168,357,-1974,-5216,1.07261276245117 +36061,0.705726325511932,-0.167632818222046,-0.066788256168366,42168,-2286,-2050,-5355,1.0761034488678 +36063,0.77047723531723,-0.142123758792877,-0.06600371748209,42168,-2999,-3171,-5199,1.08238244056702 +36065,0.8321413397789,-0.119188845157623,-0.071549385786057,42168,-5170,-3040,-5464,1.091463804245 +36067,0.883229553699493,-0.095979318022728,-0.073396004736424,42168,-3855,-3615,-5259,1.09078431129456 +36069,0.927548885345459,-0.07633750885725,-0.066920831799507,42168,-5722,-3460,-5460,1.08450603485107 +36071,0.968443036079407,-0.05987848341465,-0.06257013976574,42168,-4612,-3615,-5193,1.07747948169708 +36073,1.01114141941071,-0.038185074925423,-0.06280855089426,42168,-7258,-4201,-5459,1.07365643978119 +36075,1.06034469604492,-0.023121254518628,-0.059247221797705,42168,-6833,-4026,-5180,1.07135474681854 +36077,1.10557293891907,0.003279167925939,-0.050985664129257,42168,-9310,-5208,-5373,1.06805324554443 +36079,1.15131187438965,0.028375258669257,-0.044264983385801,42168,-8245,-5486,-5086,1.06518244743347 +36081,1.1868349313736,0.052731353789568,-0.041485335677862,41614,-10309,-5887,-5324,1.05631852149963 +36083,1.21951854228973,0.063207127153874,-0.039512313902378,41614,-8685,-4966,-5063,1.05589115619659 +36085,1.24620640277863,0.072561286389828,-0.039533466100693,41614,-11035,-5163,-5333,1.05954039096832 +36087,1.27537333965302,0.084750629961491,-0.041191753000021,41614,-9658,-5434,-5085,1.06416821479797 +36089,1.30406928062439,0.096787855029106,-0.04299833253026,41614,-12542,-5779,-5412,1.0672801733017 +36091,1.32680773735046,0.108418449759483,-0.042576398700476,41614,-10388,-5779,-5106,1.0693097114563 +36093,1.34082841873169,0.115283317863941,-0.041164357215166,41614,-12543,-5752,-5425,1.07210028171539 +36095,1.35008537769318,0.114178493618965,-0.040447395294905,41614,-10228,-5002,-5103,1.0707004070282 +36097,1.34526824951172,0.118016317486763,-0.041516080498695,41614,-11732,-5627,-5446,1.06695079803467 +36099,1.33582985401154,0.114880740642548,-0.037476286292076,41614,-9160,-4920,-5095,1.06352984905243 +36101,1.32290208339691,0.10997462272644,-0.031689237803221,41614,-11259,-4924,-5336,1.06136858463287 +36103,1.31263518333435,0.1010866984725,-0.030736971646547,41614,-9238,-4361,-5059,1.06066334247589 +36105,1.30470132827759,0.100282214581966,-0.034185566008091,41614,-11786,-5109,-5366,1.05250418186188 +36107,1.28464829921722,0.104002274572849,-0.036029882729054,41614,-8599,-5352,-5106,1.04353249073029 +36109,1.25463306903839,0.091317154467106,-0.035997040569782,41614,-9847,-4153,-5388,1.0404794216156 +36111,1.21857798099518,0.085022442042828,-0.038511972874403,41614,-6951,-4405,-5133,1.03775298595428 +36113,1.191890001297,0.076057568192482,-0.039545103907585,41614,-9498,-4207,-5423,1.03723406791687 +36115,1.15896308422089,0.065319299697876,-0.040151577442885,41614,-6739,-3838,-5155,1.03218734264374 +36117,1.1141003370285,0.044623203575611,-0.039254873991013,41614,-7325,-2893,-5390,1.03571534156799 +36119,1.06713473796844,0.023026660084725,-0.039169061928988,41257,-4801,-2475,-5157,1.03771650791168 +36121,1.01998281478882,0.006962309125811,-0.037104912102223,41257,-5985,-2628,-5325,1.04211282730103 +36123,0.975488781929016,-0.012536306865513,-0.032128546386957,41257,-4006,-2120,-5116,1.04465436935425 +36125,0.928642094135284,-0.016696942970157,-0.031908921897411,41257,-4837,-3097,-5241,1.04584884643555 +36127,0.88866263628006,-0.029470317065716,-0.036412753164768,41257,-3386,-2352,-5150,1.04669773578644 +36129,0.841464042663574,-0.042294971644878,-0.039962988346815,41257,-3681,-2043,-5305,1.04550337791443 +36131,0.792450487613678,-0.059107020497322,-0.038893096148968,41257,-1623,-1619,-5173,1.04886507987976 +36133,0.742733001708984,-0.077339068055153,-0.037537429481745,41257,-2146,-1064,-5235,1.04896128177643 +36135,0.696942687034607,-0.093137137591839,-0.032091092318297,41257,-705,-1168,-5129,1.04515063762665 +36137,0.647285997867584,-0.0983020439744,-0.02471455745399,41257,-805,-1633,-5060,1.03793203830719 +36139,0.599899291992188,-0.104786589741707,-0.022685652598739,41257,620,-1626,-5065,1.031378865242 +36141,0.55801123380661,-0.124760173261166,-0.021788852289319,41257,-72,-102,-4989,1.02591800689697 +36143,0.518239796161652,-0.14444836974144,-0.021429263055325,41257,1105,-57,-5055,1.01642167568207 +36145,0.48459780216217,-0.152673736214638,-0.020480854436755,41257,406,-436,-4934,1.01297008991241 +36147,0.451004207134247,-0.155100986361504,-0.019465832039714,41257,1520,-1075,-5039,1.017422914505 +36149,0.424660354852676,-0.165236175060272,-0.014799698255956,41257,766,-31,-4847,1.0261994600296 +36151,0.395700037479401,-0.175492614507675,-0.009503543376923,41257,1900,-150,-4966,1.02972912788391 +36153,0.368129312992096,-0.189016312360764,-0.005681629758328,41257,1705,658,-4703,1.0356924533844 +36155,0.340333998203278,-0.197274774312973,-0.002570746000856,40720,2556,98,-4912,1.04567921161652 +36157,0.30966117978096,-0.197835221886635,-0.002875153906643,40720,2834,-44,-4651,1.05573320388794 +36159,0.294571191072464,-0.203411653637886,-0.001651598606259,40720,2273,79,-4898,1.0635986328125 +36161,0.283073097467422,-0.205254331231117,0.00032118242234,40720,1872,255,-4595,1.06578063964844 +36163,0.271945059299469,-0.206654131412506,0.002590889809653,40720,2297,-83,-4860,1.06808483600616 +36165,0.252425283193588,-0.195935413241386,0.004234041087329,40720,2927,-704,-4554,1.06245696544647 +36167,0.243082419037819,-0.198269173502922,0.008192474022508,40720,2579,-50,-4813,1.05826580524445 +36169,0.243693500757217,-0.204765096306801,0.007776312064379,40720,1625,756,-4491,1.05170929431915 +36171,0.249278366565704,-0.192609459161758,0.003474726341665,40720,1420,-1080,-4836,1.04604434967041 +36173,0.256819128990173,-0.180270165205002,0.003956980537623,40720,912,-903,-4561,1.03745257854462 +36175,0.255700469017029,-0.166683360934258,0.005701566115022,40720,1801,-1475,-4812,1.03555965423584 +36177,0.260474026203156,-0.167069613933563,0.01049062050879,40720,1036,-139,-4495,1.03948783874512 +36179,0.261417001485825,-0.153942242264748,0.013624267652631,40720,1561,-1552,-4749,1.0444221496582 +36181,0.27183985710144,-0.149917542934418,0.013886413536966,40720,429,-671,-4471,1.0508406162262 +36183,0.289463609457016,-0.141663923859596,0.013789081014693,40720,-52,-1315,-4740,1.05566537380219 +36185,0.312108248472214,-0.123756609857082,0.013146750628948,40720,-1120,-2037,-4508,1.05644178390503 +36187,0.329968184232712,-0.105748876929283,0.014784180559218,40720,-685,-2478,-4726,1.0546658039093 +36189,0.344200789928436,-0.086505740880966,0.016619514673948,40720,-1084,-2692,-4513,1.05215930938721 +36191,0.358636289834976,-0.06806281208992,0.014341442845762,40720,-902,-3015,-4724,1.0508279800415 +36193,0.381619274616242,-0.056390482932329,0.012054758146405,40542,-2383,-2593,-4603,1.04743206501007 +36195,0.404026091098785,-0.039221871644259,0.012544575147331,40542,-2194,-3313,-4733,1.0446879863739 +36197,0.419392168521881,-0.02902315184474,0.016436478123069,40542,-2528,-2912,-4587,1.04167282581329 +36199,0.426244527101517,-0.011506566777825,0.019293719902635,40542,-1486,-3724,-4683,1.03500723838806 +36201,0.435030102729797,0.004806047771126,0.019372405484319,40542,-2403,-3898,-4598,1.03481781482697 +36203,0.452700853347778,0.027829123660922,0.019386293366551,40542,-2737,-4687,-4681,1.03508770465851 +36205,0.478901416063309,0.038764327764511,0.021423911675811,40542,-4464,-4073,-4621,1.03925907611847 +36207,0.503739595413208,0.035875119268894,0.021611036732793,40542,-4100,-2965,-4665,1.04375612735748 +36209,0.521414637565613,0.043197497725487,0.018971722573042,40542,-4657,-3908,-4656,1.04210543632507 +36211,0.536710917949677,0.044850066304207,0.021513374522328,40542,-4024,-3441,-4666,1.04177403450012 +36213,0.543559968471527,0.054246868938208,0.02533333003521,40542,-4375,-4262,-4598,1.0379546880722 +36215,0.550773859024048,0.059757996350527,0.02897391282022,40542,-3793,-3958,-4614,1.0390659570694 +36217,0.554695665836334,0.06233549490571,0.029952805489302,40542,-4497,-3928,-4556,1.03210186958313 +36219,0.553990244865418,0.064783446490765,0.029430249705911,40542,-3424,-3841,-4610,1.02372944355011 +36221,0.548188626766205,0.071156792342663,0.030843306332827,40542,-3855,-4377,-4559,1.01525294780731 +36223,0.54517924785614,0.075814500451088,0.030889598652721,40542,-3284,-4192,-4600,1.01368939876556 +36225,0.549020349979401,0.061945855617523,0.02725693397224,40542,-4705,-2808,-4587,1.01399838924408 +36227,0.552589893341064,0.054183289408684,0.02821858972311,40542,-4014,-3022,-4618,1.01401698589325 +36229,0.547704875469208,0.048512272536755,0.035132791846991,40542,-32767,-3206,-4475,1.01578760147095 +36231,0.541702628135681,0.041972026228905,0.037808153778315,39934,-9414,-2959,-4550,1.01428973674774 +36233,0.532363474369049,0.036835573613644,0.03787337988615,39934,-9900,-3076,-4424,1.01089572906494 +36235,0.521322429180145,0.023255506530404,0.037967968732119,39934,-8966,-2205,-4545,1.00964605808258 +36237,0.508031666278839,0.018933191895485,0.035080406814814,39934,-9423,-2851,-4427,1.00755190849304 +36239,0.489741832017899,0.013241260312498,0.031057143583894,39934,-8190,-2636,-4589,1.00317466259003 +36241,0.462618708610535,0.00856473762542,0.026533454656601,39934,-7890,-2671,-4507,0.993687212467194 +36243,0.428102135658264,0.000543677888345,0.024252019822598,39934,-6320,-2293,-4633,0.986879885196686 +36245,0.389435917139053,-0.019293861463666,0.025507725775242,39934,-6053,-1140,-4474,0.986955165863037 +36265,-0.078049913048744,-0.148773565888405,0.029704866930842,39934,2219,60,-4193,1.02221202850342 +36267,-0.117496646940708,-0.152861669659615,0.029745178297162,39934,-32767,-171,-4547,1.01858985424042 +36269,-0.154839217662811,-0.168158188462257,0.033427841961384,39576,-3524,1173,-4110,1.01377296447754 +36271,-0.189562976360321,-0.182310879230499,0.035779643803835,39576,-3718,1045,-4492,1.009526014328 +36273,-0.221907302737236,-0.191811591386795,0.034950997680426,39576,-2733,1217,-4045,1.00733375549316 +36275,-0.262592673301697,-0.189560487866402,0.033380102366209,39576,-2166,58,-4495,1.00263297557831 +36277,-0.311415761709213,-0.186319753527641,0.032863959670067,39576,0,292,-4065,1.00150287151337 +36279,-0.358163118362427,-0.190123379230499,0.028939893469215,39576,-241,580,-4512,0.999076843261719 +36281,-0.402020931243897,-0.203277796506882,0.027323385700584,39576,1259,1826,-4093,1.00205707550049 +36283,-0.445302575826645,-0.209630206227302,0.030435331165791,39576,924,1132,-4488,1.00023746490479 +36285,-0.497653186321259,-0.194139838218689,0.033927284181118,39576,3611,-281,-4019,1.00371551513672 +36287,-0.546265780925751,-0.183296173810959,0.033315345644951,39576,2964,-390,-4455,1.00811457633972 +36289,-0.580088138580322,-0.185227066278458,0.035236082971096,39576,3849,904,-4006,1.00318455696106 +36291,-0.612037777900696,-0.187534540891647,0.037573896348477,39576,2964,694,-4412,0.993565797805786 +36293,-0.642848670482636,-0.17932340502739,0.037501197308302,39576,4907,157,-3977,0.988318622112274 +36295,-0.676848113536835,-0.165906146168709,0.034103345125914,39576,4320,-662,-4422,0.990878343582153 +36297,-0.704655826091766,-0.164464995265007,0.032955843955278,39576,5991,483,-4041,0.99086457490921 +36299,-0.727203249931335,-0.173197820782661,0.035044100135565,39576,4533,1102,-4403,0.991547882556915 +36301,-0.756698608398438,-0.175392746925354,0.036790926009417,39576,7286,995,-3971,0.99420952796936 +36303,-0.779216706752777,-0.165842533111572,0.04015614464879,39576,5615,-233,-4355,0.994964480400085 +36305,-0.801861047744751,-0.141356810927391,0.041071429848671,39576,-28175,-1387,-3959,0.998362720012665 +36307,-0.817626595497131,-0.12496554851532,0.041136231273413,39219,-44,-1244,-4336,1.00167906284332 +36309,-0.82654333114624,-0.109138324856758,0.040174439549446,39219,1546,-1224,-4005,0.997251510620117 +36311,-0.827072978019714,-0.097507610917091,0.042965177446604,39219,-684,-1245,-4313,0.995528221130371 +36313,-0.824444949626923,-0.092279344797134,0.046108521521092,39219,979,-699,-3950,0.991814732551575 +36315,-0.833183944225311,-0.080952525138855,0.049606923013926,39219,305,-1417,-4257,0.987033426761627 +36317,-0.851780891418457,-0.068085961043835,0.053642477840185,39219,3249,-1610,-3885,0.985927104949951 +36319,-0.870104849338532,-0.044815219938755,0.054327320307493,39219,1849,-2761,-4214,0.98774516582489 +36321,-0.879273235797882,-0.030851168558002,0.055415812879801,39219,3357,-2270,-3904,0.99158251285553 +36323,-0.885424911975861,-0.021404128521681,0.056505993008614,39219,1540,-2093,-4190,0.993362724781036 +36325,-0.890997707843781,-0.009247324429452,0.05819433927536,39219,3639,-2475,-3891,0.99699854850769 +36327,-0.901341617107391,-0.004754768684506,0.061818405985832,39219,2421,-1971,-4145,1.00101518630981 +36329,-0.91096293926239,-0.001811806228943,0.063580624759197,39219,4613,-1929,-3829,1.00095915794373 +36331,-0.913443565368652,0.001268530497327,0.062134090811014,39219,2396,-1954,-4133,0.998739302158356 +36333,-0.916594207286835,0.017607843503356,0.060875467956066,39219,4593,-3206,-3876,0.99220871925354 +36335,-0.917661905288696,0.025120282545686,0.060852956026793,39219,2724,-2620,-4134,0.990436851978302 +36337,-0.914093792438507,0.029041443020105,0.066645458340645,39219,4440,-2524,-3814,0.988460004329681 +36339,-0.905237853527069,0.043312437832356,0.071592725813389,39219,2205,-3380,-4052,0.988915085792542 +36341,-0.89881157875061,0.05539695546031,0.072548121213913,39219,-31695,-3562,-3768,0.992900133132935 +36343,-0.89455771446228,0.061579294502735,0.071015559136868,39219,-3340,-3090,-4047,0.997133433818817 +36345,-0.887916326522827,0.05170738324523,0.07229594886303,39219,-1587,-1955,-3756,1.0010427236557 +36347,-0.878045201301575,0.050950847566128,0.071962915360928,39219,-3675,-2467,-4032,1.00399434566498 +36349,-0.867630243301392,0.059059530496597,0.072026699781418,39219,-1898,-3382,-3758,1.00999474525452 +36351,-0.862375557422638,0.062991105020046,0.07454189658165,39219,-3272,-3003,-4006,1.00751972198486 +36353,-0.86841094493866,0.065223172307015,0.076220415532589,39219,-424,-3093,-3706,1.00467193126678 +36355,-0.874817490577698,0.06287757307291,0.077677264809609,39219,-1961,-2583,-3976,1.00086498260498 +36357,-0.881937921047211,0.068759977817535,0.076341845095158,39219,162,-3448,-3698,0.994612693786621 +36359,-0.889057219028473,0.054637040942907,0.074346505105496,39219,-1401,-1655,-3990,0.991368770599365 +36361,-0.906493902206421,0.054662153124809,0.075774677097797,39219,1616,-2830,-3678,0.986915528774262 +36363,-0.924678683280945,0.060096755623818,0.076110206544399,39219,222,-3162,-3968,0.989157259464264 +36365,-0.933319449424744,0.055745914578438,0.074292711913586,39219,1758,-2558,-3686,0.989019989967346 +36367,-0.933759331703186,0.048187028616667,0.076026506721974,39219,-581,-2088,-3960,0.990233182907104 +36369,-0.936311721801758,0.03648266941309,0.079311773180962,39219,1706,-1739,-3595,0.990167379379272 +36371,-0.942718267440796,0.032857976853848,0.080071717500687,39219,315,-2169,-3922,0.987359404563904 +36373,-0.95180606842041,0.025054039433599,0.078574597835541,39219,2770,-1847,-3579,0.985956430435181 +36375,-0.964145660400391,0.022329268977046,0.078336201608181,39219,1398,-2096,-3923,0.979978978633881 +36377,-0.973349869251251,0.011468794196844,0.080419905483723,39219,3486,-1423,-3531,0.977373778820038 +36379,-0.977084875106812,-0.006153165828437,0.083819754421711,39219,-32767,-628,-3873,0.973340690135956 +36381,-0.981578290462494,-0.014626830816269,0.083942338824272,38969,-2437,-1175,-3451,0.972470223903656 +36383,-0.989415466785431,-0.020891405642033,0.084121227264404,38969,-3944,-1226,-3858,0.981911957263946 +36385,-0.997439444065094,-0.021011017262936,0.083055034279823,38969,-1614,-1659,-3441,0.98259961605072 +36387,-0.999533772468567,-0.037237007170916,0.080736353993416,38969,-3889,-270,-3868,0.978851556777954 +36389,-1.00748240947723,-0.048754930496216,0.078548051416874,38969,-1142,-376,-3453,0.97324001789093 +36391,-1.020174741745,-0.053233671933413,0.0727743729949,38969,-2505,-862,-3909,0.969916701316834 +36393,-1.0343953371048,-0.060125201940537,0.065860889852047,38969,69,-492,-3578,0.967335522174835 +36395,-1.05612194538116,-0.06736958026886,0.064825683832169,38969,-1000,-434,-3952,0.970490992069244 +36397,-1.07469320297241,-0.085372254252434,0.064505569636822,38969,1382,736,-3559,0.972201526165008 +36399,-1.08853626251221,-0.090356774628162,0.061512921005488,38969,-736,-228,-3962,0.9713134765625 +36401,-1.10088717937469,-0.102176383137703,0.060483921319246,38969,1729,601,-3580,0.97392863035202 +36403,-1.12202060222626,-0.103327214717865,0.062604486942291,38969,644,-273,-3942,0.981189668178558 +36405,-1.14363086223602,-0.104852415621281,0.067629002034664,38969,3474,-41,-3484,0.989149808883667 +36407,-1.16510379314423,-0.108638860285282,0.071372181177139,38969,1688,38,-3869,0.984160482883453 +36409,-1.18639695644379,-0.115737095475197,0.072382636368275,38969,4558,582,-3407,0.975501716136932 +36411,-1.20694208145142,-0.124701924622059,0.07033297419548,38969,2647,692,-3861,0.963956534862518 +36413,-1.22308564186096,-0.124393202364445,0.067747659981251,38969,5220,252,-3443,0.958347916603088 +36415,-1.23391830921173,-0.126487240195274,0.064431674778462,38969,2785,282,-3888,0.957740783691406 +36417,-1.23947060108185,-0.131033077836037,0.062142804265022,38969,5174,775,-3492,0.956650614738464 +36419,-1.24133157730103,-0.130261838436127,0.061431352049112,38969,2705,193,-3896,0.954837679862976 +36421,-1.239870429039,-0.126671895384788,0.060764476656914,38969,5144,182,-3502,0.953332781791687 +36423,-1.2388277053833,-0.115210212767124,0.062967285513878,38969,2924,-727,-3873,0.957793533802032 +36425,-1.23719239234924,-0.117217265069485,0.068408757448196,38969,5545,492,-3410,0.964013755321503 +36427,-1.23873889446259,-0.113590277731419,0.071679063141346,38969,3572,-132,-3799,0.966279149055481 +36429,-1.23403775691986,-0.109255351126194,0.072945095598698,38969,5729,-41,-3352,0.96795654296875 +36431,-1.22990107536316,-0.102970965206623,0.072332710027695,38969,3503,-422,-3781,0.964799761772156 +36433,-1.22832095623016,-0.10234209895134,0.073385566473007,38969,6312,155,-3340,0.965683043003082 +36435,-1.22499585151672,-0.110637962818146,0.074382811784744,38969,3955,780,-3753,0.97168231010437 +36437,-1.21570909023285,-0.113639988005161,0.073717437684536,38969,6012,645,-3316,0.976222217082977 +36439,-1.19463896751404,-0.11345499753952,0.0732262134552,38969,2710,266,-3747,0.979469895362854 +36441,-1.17493808269501,-0.097136251628399,0.074308723211289,38969,5056,-959,-3309,0.981849074363708 +36443,-1.15421950817108,-0.08929618448019,0.080243825912476,38969,2602,-582,-3685,0.986902415752411 +36445,-1.13532102108002,-0.083640933036804,0.082342870533466,38969,4904,-367,-3211,0.988220572471619 +36447,-1.11642324924469,-0.082891024649143,0.082515269517899,38969,2621,-125,-3655,0.987940311431885 +36449,-1.09561967849731,-0.076531231403351,0.085951089859009,38969,4546,-487,-3160,0.982841670513153 +36451,-1.07355630397797,-0.058849200606346,0.087547525763512,38969,2196,-1645,-3605,0.979422509670258 +36453,-1.04989516735077,-0.053319323807955,0.084900990128517,38969,4010,-767,-3173,0.977458298206329 +36455,-1.0272741317749,-0.041470099240542,0.077068276703358,38969,1891,-1448,-3663,0.973482668399811 +36457,-1.00281274318695,-0.031396508216858,0.077127911150456,38969,3580,-1421,-3265,0.971398591995239 +36459,-0.975635409355164,-0.020253092050552,0.080410309135914,38969,1206,-1683,-3627,0.964928507804871 +36461,-0.947477698326111,-0.016214109957218,0.082459211349487,38969,2771,-1219,-3198,0.964089393615723 +36463,-0.920896947383881,-0.014739845879376,0.082236558198929,38969,819,-1057,-3601,0.961433708667755 +36465,-0.899892508983612,-0.003206107998267,0.081476904451847,38969,2849,-1958,-3203,0.965198874473572 +36467,-0.879358232021332,0.011541343294084,0.078861683607102,38969,993,-2378,-3612,0.969955027103424 +36469,-0.854064702987671,0.036463942378759,0.077585257589817,38969,2139,-3560,-3258,0.973894834518433 +36471,-0.825837910175324,0.045239835977554,0.081348054111004,38969,-5,-2445,-3583,0.978595435619354 +36473,-0.796531617641449,0.053914193063974,0.082819171249867,38969,1230,-2697,-3193,0.976684093475342 +36475,-0.766977429389954,0.053901396691799,0.080585710704327,38969,-647,-1960,-3576,0.977378368377686 +36477,-0.745404005050659,0.058849897235632,0.079366505146027,38969,1227,-2534,-3223,0.976199507713318 +36493,-0.551261782646179,0.083150818943977,0.074315845966339,38969,-954,-2977,-3245,0.982606709003448 +36495,-0.537817239761353,0.088303171098232,0.078351408243179,38969,-1629,-2987,-3537,0.977559566497803 +36497,-0.527838826179504,0.100218296051025,0.082254126667976,38969,-385,-3870,-3147,0.978146493434906 +36499,-0.509603679180145,0.095685765147209,0.082849606871605,38969,-2195,-2441,-3494,0.97616696357727 +36501,-0.495847225189209,0.097413063049316,0.078511409461498,38969,-996,-3139,-3177,0.976055920124054 +36503,-0.474861890077591,0.081108994781971,0.072629205882549,38969,-2722,-1429,-3553,0.970515608787537 +36505,-0.46600478887558,0.086242191493511,0.073175504803658,38969,-958,-3246,-3224,0.969192624092102 +36507,-0.462223321199417,0.089675821363926,0.078136876225472,38969,-1512,-3004,-3505,0.968727827072144 +36509,-0.460156738758087,0.087852396070957,0.078115038573742,38969,-425,-2816,-3154,0.965197324752808 +36511,-0.451528429985046,0.076097957789898,0.078173562884331,38969,-1858,-1760,-3494,0.96276980638504 +36513,-0.43800699710846,0.059171918779612,0.081771738827229,38969,-1473,-1308,-3087,0.959462225437164 +36515,-0.433145225048065,0.055987473577261,0.083178326487541,38969,-1709,-2114,-3447,0.96122145652771 +36517,-0.429258763790131,0.052095122635365,0.079270772635937,38969,-779,-2143,-3101,0.96824836730957 +36519,-0.429174453020096,0.060182075947523,0.077047519385815,38969,-1283,-3004,-3477,0.975373685359955 +36521,-0.425783067941666,0.054190143942833,0.079001538455486,38969,-648,-2039,-3093,0.979512274265289 +36523,-0.424305409193039,0.048099149018526,0.079145804047585,38969,-1309,-1838,-3451,0.976527392864227 +36525,-0.428499042987824,0.037693981081247,0.084192112088204,38969,87,-1465,-3013,0.976020455360413 +36527,-0.433849930763245,0.028761126101017,0.087718583643437,38969,-537,-1370,-3379,0.970722854137421 +36529,-0.435535877943039,0.026900643482804,0.08515352755785,38969,164,-1917,-2984,0.964117705821991 +36531,-0.432749599218369,0.009853747673333,0.084610976278782,38969,-986,-526,-3387,0.954082250595093 +36533,-0.435089468955994,0.004776469897479,0.086411617696285,38969,347,-1350,-2948,0.944621622562408 +36535,-0.439887583255768,-0.007059711962938,0.088906861841679,38969,-190,-659,-3344,0.947624504566193 +36537,-0.443497538566589,-0.014085536822677,0.089539639651775,38969,723,-905,-2891,0.955215454101562 +36539,-0.440380752086639,-0.028434708714485,0.092766411602497,38969,-595,-166,-3303,0.964239478111267 +36541,-0.439739257097244,-0.045146327465773,0.094481520354748,38969,509,310,-2807,0.962760627269745 +36543,-0.446576982736587,-0.052882194519043,0.094088554382324,38969,359,-268,-3278,0.961593687534332 +36545,-0.448524087667465,-0.060819145292044,0.094456486403942,38969,991,-21,-2787,0.962173283100128 +36547,-0.449948906898499,-0.062647007405758,0.092925451695919,38969,179,-520,-3270,0.962200880050659 +36549,-0.450046271085739,-0.082001015543938,0.088548682630062,38969,1045,1180,-2835,0.962536633014679 +36551,-0.450159966945648,-0.086793459951878,0.087633147835732,38969,250,80,-3291,0.962311387062073 +36553,-0.445666342973709,-0.090263411402702,0.09009899944067,38969,808,203,-2800,0.964011669158936 +36555,-0.4475958943367,-0.081621117889881,0.09100653231144,38969,504,-913,-3253,0.965625047683716 +36557,-0.450659453868866,-0.071813002228737,0.089636996388435,38969,1595,-1011,-2796,0.967078685760498 +36559,-0.449915170669556,-0.079457372426987,0.086749285459519,38969,511,256,-3267,0.963842809200287 +36561,-0.452850073575974,-0.078851327300072,0.087733365595341,38969,1790,-201,-2802,0.964900076389313 +36563,-0.455738931894302,-0.073209829628468,0.092569172382355,38969,1023,-746,-3212,0.972303152084351 +36565,-0.457367181777954,-0.066536240279675,0.095546305179596,38969,1932,-796,-2699,0.978507936000824 +36567,-0.452623724937439,-0.072753243148327,0.094882637262344,38969,602,129,-3180,0.987466633319855 +36569,-0.453600764274597,-0.068558000028133,0.087785013020039,38969,2003,-548,-2775,0.989024698734283 +36571,-0.460399091243744,-0.057146850973368,0.07939875125885,38969,1713,-1322,-3272,0.993246138095856 +36573,-0.456934958696365,-0.057215549051762,0.076355785131455,38969,1918,-391,-2899,0.989075243473053 +36575,-0.451162546873093,-0.06108358129859,0.080375865101814,38969,855,-140,-3252,0.982045471668243 +36577,-0.445675909519196,-0.068836748600006,0.084606789052487,38969,1753,377,-2786,0.975888311862946 +36579,-0.440408766269684,-0.054210890084505,0.08583839982748,38969,907,-1529,-3201,0.971310675144196 +36581,-0.428558528423309,-0.042720500379801,0.086317203938961,38969,1181,-1404,-2758,0.967047393321991 +36583,-0.41754224896431,-0.025068979710341,0.084507748484612,38969,330,-2142,-3195,0.961881637573242 +36585,-0.407190680503845,-0.016311956569553,0.083294272422791,38969,1097,-1624,-2786,0.963638424873352 +36587,-0.39650622010231,-0.016248209401965,0.083220668137074,38969,206,-999,-3191,0.960594058036804 +36589,-0.395859152078628,-0.014089989475906,0.082062922418118,38969,1764,-1169,-2788,0.961890816688538 +36591,-0.394826501607895,-0.01716760545969,0.080352336168289,38969,1024,-750,-3197,0.961825549602508 +36593,-0.385966539382935,-0.012945540249348,0.079155154526234,38969,1154,-1327,-2809,0.957488298416138 +36595,-0.374012440443039,-0.009091635234654,0.078862816095352,38969,89,-1354,-3194,0.951579928398132 +36597,-0.370636194944382,0.008127182722092,0.077021211385727,38969,1432,-2597,-2826,0.948178052902222 +36599,-0.366190969944,0.011505639180541,0.074027687311173,38969,653,-1616,-3215,0.951874792575836 +36601,-0.352760404348373,0.005291468929499,0.072953671216965,38969,556,-879,-2861,0.955487668514252 +36603,-0.338631480932236,0.009264709427953,0.075236044824123,38969,-304,-1627,-3195,0.961369395256042 +36605,-0.331874221563339,0.020991878584027,0.076511427760124,38969,816,-2424,-2810,0.967315375804901 +36607,-0.32921177148819,0.034483291208744,0.075819656252861,38969,503,-2678,-3179,0.970359563827515 +36609,-0.326235264539719,0.025354826822877,0.076437510550022,38969,1120,-996,-2799,0.96979683637619 +36611,-0.322784453630447,0.02503040805459,0.077812261879444,38969,475,-1561,-3153,0.968653202056885 +36613,-0.313088625669479,0.017677517607808,0.076435998082161,38969,551,-998,-2786,0.965366899967194 +36615,-0.306045114994049,0.021197319030762,0.077269606292248,38969,95,-1785,-3144,0.964156985282898 +36617,-0.303921014070511,0.031124191358686,0.079336374998093,38969,1064,-2463,-2741,0.965991199016571 +36619,-0.300825953483582,0.034248150885105,0.078375674784184,38969,418,-1954,-3124,0.970204651355743 +36621,-0.293478608131409,0.04392858967185,0.077025607228279,38969,636,-2668,-2758,0.974578857421875 +36623,-0.284375101327896,0.048968460410833,0.075515188276768,38969,-136,-2318,-3131,0.975712299346924 +36625,-0.283599555492401,0.058790605515242,0.073606431484222,38969,1042,-2937,-2788,0.973934471607208 +36627,-0.280263841152191,0.055441230535507,0.07204382121563,38969,322,-1833,-3144,0.97523307800293 +36645,-0.223085418343544,0.046801097691059,0.079082541167736,38969,197,-2117,-2664,0.963363468647003 +36647,-0.220598265528679,0.041559994220734,0.075678586959839,38969,-19,-1578,-3062,0.96317332983017 +36649,-0.218583166599274,0.030220175161958,0.068878434598446,38969,445,-1064,-2770,0.972004354000092 +36651,-0.215843394398689,0.016894744709134,0.064291842281818,38969,-25,-658,-3129,0.980541229248047 +36653,-0.21658943593502,0.013025793246925,0.060411214828491,38969,683,-1323,-2857,0.982159912586212 +36655,-0.218710064888,0.006308820098639,0.058193385601044,38969,443,-982,-3161,0.98062664270401 +36657,-0.218813508749008,0.007342167198658,0.060687847435474,38969,745,-1574,-2843,0.978887319564819 +36659,-0.21431365609169,-0.003776711411774,0.066334754228592,38969,-14,-522,-3096,0.981862425804138 +36661,-0.212432116270065,-0.013732097111642,0.06744946539402,38969,575,-440,-2751,0.978451609611511 +36663,-0.214398309588432,-0.020165236666799,0.065315946936607,38969,526,-612,-3092,0.973017275333404 +36665,-0.216415986418724,-0.025200381875038,0.060185227543116,38969,1007,-590,-2824,0.966941177845001 +36667,-0.218511655926704,-0.021853275597096,0.058473732322455,38969,675,-1272,-3129,0.962076246738434 +36669,-0.215116649866104,-0.026832660660148,0.059561833739281,38969,687,-546,-2822,0.95911967754364 +36671,-0.209311127662659,-0.020277738571167,0.059911374002695,38969,60,-1507,-3109,0.953509330749512 +36673,-0.204131752252579,-0.027941651642323,0.057116959244013,38969,455,-326,-2841,0.951632261276245 +36675,-0.213267132639885,-0.028277903795242,0.05091492831707,38969,1264,-882,-3161,0.948003172874451 +36677,-0.222768276929855,-0.038081463426352,0.050973553210497,38969,1877,2,-2903,0.953084290027618 +36679,-0.223859027028084,-0.048007369041443,0.054485488682985,38969,924,108,-3128,0.954607427120209 +36681,-0.223164603114128,-0.039998974651098,0.054774183779955,38772,1248,-1228,-2850,0.958695948123932 +36683,-0.223192736506462,-0.02988013997674,0.052834711968899,38772,925,-1567,-3131,0.962676584720612 +36685,-0.218756750226021,-0.023059817031026,0.051862969994545,38772,986,-1398,-2877,0.964353978633881 +36687,-0.210240617394447,-0.036308962851763,0.050737787038088,38772,211,212,-3136,0.962451875209808 +36689,-0.206534445285797,-0.044598702341318,0.042822223156691,38772,917,62,-2974,0.958316683769226 +36691,-0.207747787237167,-0.0506856366992,0.037815436720848,38772,950,-69,-3218,0.958047926425934 +36693,-0.206468522548676,-0.045714434236288,0.038512468338013,38772,1185,-841,-3018,0.957440972328186 +36695,-0.206252947449684,-0.033215757459402,0.042966857552528,38772,908,-1625,-3176,0.961539089679718 +36697,-0.208779230713844,-0.026901781558991,0.045533753931522,38772,1586,-1232,-2930,0.966196894645691 +36699,-0.209222838282585,-0.010950847528875,0.045922499150038,38772,1083,-2177,-3148,0.973056018352508 +36701,-0.203877195715904,-0.01281654369086,0.044166777282953,38772,1014,-866,-2940,0.978498518466949 +36703,-0.204687401652336,-0.001888574683107,0.044501055032015,38772,1125,-1939,-3151,0.983788549900055 +36705,-0.1971076130867,-0.00164253031835,0.048301052302122,38772,818,-1194,-2884,0.98200798034668 +36707,-0.186136081814766,-0.002881746273488,0.046766664832831,38772,92,-1050,-3127,0.976026475429535 +36709,-0.178613945841789,-0.001318710157648,0.045138500630856,38772,604,-1287,-2914,0.975249648094177 +36711,-0.176817029714584,0.000640648184344,0.045933339744806,38772,687,-1326,-3126,0.971830010414124 +36713,-0.169375255703926,0.007549103815109,0.043267279863358,38772,533,-1802,-2929,0.964809060096741 +36715,-0.159972161054611,0.011212425306439,0.037370380014181,38772,-30,-1599,-3178,0.958417177200317 +36717,-0.161317870020866,0.023766703903675,0.035017091780901,38772,1095,-2466,-3021,0.948026955127716 +36719,-0.163367241621017,0.025966560468078,0.037321161478758,38772,902,-1710,-3172,0.945879161357879 +36721,-0.162021547555923,0.036522187292576,0.04050100967288,38772,968,-2540,-2951,0.947013437747955 +36723,-0.157257601618767,0.045463159680367,0.041576337069273,38772,390,-2485,-3136,0.957240402698517 +36727,-0.140815377235413,0.061866201460362,0.041719924658537,38772,108,-2860,-3129,0.971685111522675 +36729,-0.1356241106987,0.057550594210625,0.044716093689203,38772,366,-1857,-2889,0.978154718875885 +36731,-0.130623579025269,0.063314840197563,0.047928150743246,38772,96,-2556,-3079,0.982679486274719 +36733,-0.121859177947044,0.048779252916575,0.0463552698493,38772,-59,-998,-2861,0.978700935840607 +36735,-0.121501922607422,0.04495020955801,0.038689412176609,38772,344,-1623,-3135,0.967371582984924 +36737,-0.120236977934837,0.042043317109346,0.034104947000742,38772,497,-1745,-2999,0.957763135433197 +36739,-0.11808418482542,0.045481942594051,0.035032607614994,38772,211,-2167,-3154,0.947574377059936 +36741,-0.11811389029026,0.050930619239807,0.036919094622135,38772,599,-2510,-2960,0.949842154979706 +36743,-0.110293969511986,0.046150218695402,0.036063637584448,38772,-261,-1609,-3141,0.956001281738281 +36745,-0.102948628365994,0.047714471817017,0.033677738159895,38772,-136,-2199,-2992,0.957379519939423 +36747,-0.101276747882366,0.049579553306103,0.031990848481655,38772,86,-2153,-3164,0.958526968955994 +36749,-0.103742763400078,0.067087143659592,0.030218955129385,38772,614,-3664,-3028,0.957109093666077 +36751,-0.100393362343311,0.069461114704609,0.031834542751312,38772,-8,-2501,-3160,0.961996495723724 +36753,-0.093705452978611,0.064078345894814,0.030667472630739,38772,-164,-1993,-3018,0.962227165699005 +36755,-0.09081444144249,0.057702485471964,0.027974588796496,38772,-78,-1729,-3182,0.964441061019897 +36757,-0.089127436280251,0.055107116699219,0.026611128821969,38772,153,-2083,-3061,0.963864326477051 +36759,-0.090741045773029,0.06469638645649,0.027117693796754,38665,275,-2995,-3183,0.96689385175705 +36761,-0.091624200344086,0.052539791911841,0.02858567610383,38665,413,-1385,-3033,0.967686116695404 +36763,-0.093572348356247,0.045825242996216,0.028148844838142,38665,374,-1578,-3171,0.962746918201446 +36765,-0.090496800839901,0.029351126402617,0.027392474934459,38665,151,-717,-3041,0.960239350795746 +36767,-0.094979152083397,0.022627411410213,0.02781068906188,38665,610,-1257,-3169,0.962985694408417 +36769,-0.101120606064796,0.021726561710239,0.026064895093441,38665,1020,-1715,-3052,0.971719622612 +36771,-0.09778568893671,0.020445475354791,0.023582879453898,38665,130,-1623,-3194,0.975908756256104 +36773,-0.096636854112148,0.022826386615634,0.025090970098972,38665,474,-1971,-3060,0.979726254940033 +36775,-0.100890778005123,0.017293652519584,0.026660410687327,38665,758,-1280,-3169,0.985451996326446 +36777,-0.108273670077324,0.017553064972162,0.027117004618049,38665,1321,-1732,-3031,0.983299016952515 +36779,-0.108488515019417,0.002425150945783,0.02287613414228,38665,624,-383,-3190,0.978426575660706 +36781,-0.112457893788815,0.002193701919168,0.019075654447079,38665,1175,-1450,-3121,0.972995817661285 +36783,-0.113936327397823,0.000278176012216,0.023482218384743,38665,839,-1296,-3183,0.966888129711151 +36785,-0.113551899790764,-0.001036233035848,0.027631750330329,38665,927,-1324,-3017,0.959575831890106 +36787,-0.11441071331501,0.000826266186778,0.027436535805464,38665,848,-1571,-3151,0.958758592605591 +36789,-0.11982174962759,-0.00069117808016,0.024136558175087,38665,1493,-1310,-3054,0.959010779857636 +36791,-0.121128939092159,-0.002600254490972,0.023451769724488,38665,1026,-1249,-3175,0.963232040405273 +36793,-0.120042316615582,-0.015530138276517,0.023670857772231,38665,1081,-238,-3055,0.968458592891693 +36795,-0.122957117855549,-0.018977707251906,0.022654533386231,38272,1218,-893,-3176,0.969098389148712 +36797,-0.123589277267456,-0.013966035097838,0.022615944966674,38272,1305,-1541,-3063,0.965813338756561 +36799,-0.121435441076756,-0.00207562954165,0.024997584521771,38272,884,-2224,-3156,0.960857033729553 +36801,-0.115305237472057,-0.002221162663773,0.026886953040958,38272,725,-1362,-3009,0.960449755191803 +36803,-0.108162239193916,-0.019047578796744,0.028454754501581,38272,382,79,-3128,0.960601568222046 +36805,-0.11079353094101,-0.029328754171729,0.030088583007455,38272,1320,-188,-2966,0.960291266441345 +36807,-0.112029373645782,-0.032603021711111,0.030474405735731,38272,1081,-680,-3109,0.961882531642914 +36809,-0.111431077122688,-0.021671889349818,0.029377659782767,38272,1144,-1813,-2970,0.964522540569305 +36811,-0.099630899727345,-0.03279197588563,0.032338503748179,38272,13,-102,-3091,0.963170230388641 +36813,-0.095567993819714,-0.03415209800005,0.034670747816563,38272,687,-709,-2902,0.962723016738892 +36815,-0.096107415854931,-0.038905747234821,0.034286238253117,38272,885,-451,-3072,0.964228510856628 +36817,-0.101583130657673,-0.036034900695086,0.032402042299509,38272,1509,-964,-2923,0.967072665691376 +36819,-0.097628645598888,-0.03634587302804,0.033693481236696,38272,627,-785,-3071,0.971879541873932 +36821,-0.089535497128964,-0.034436136484146,0.03773295879364,38272,381,-905,-2855,0.977052330970764 +36823,-0.080778114497662,-0.02602007240057,0.036972664296627,38272,78,-1540,-3042,0.981309413909912 +36825,-0.077618472278118,-0.028186038136482,0.032098077237606,38272,575,-696,-2915,0.977362334728241 +36827,-0.079596266150475,-0.033268895000219,0.026973823085427,38272,861,-453,-3105,0.966311514377594 +36829,-0.079416945576668,-0.036127965897322,0.027618354186416,38272,854,-497,-2963,0.954237759113312 +36831,-0.07916970551014,-0.024549283087254,0.028977746143937,38272,729,-1751,-3087,0.944165408611298 +36833,-0.076232135295868,-0.014144727028906,0.031651888042688,38272,641,-1787,-2911,0.946021854877472 +36835,-0.068353965878487,-0.013451190665364,0.033750619739294,38272,60,-1120,-3049,0.949959695339203 +36837,-0.058346208184958,-0.016486654058099,0.030511574819684,38272,-127,-777,-2919,0.95441085100174 +36839,-0.048989068716765,-0.018710631877184,0.028551110997796,38272,-299,-824,-3079,0.956495404243469 +36841,-0.044024780392647,-0.001759539125487,0.032189346849918,38272,16,-2432,-2894,0.960712015628815 +36843,-0.039953406900168,-0.003376826411113,0.036663234233856,38272,-33,-1081,-3018,0.965048670768738 +36845,-0.038318432867527,-0.003569000400603,0.037734910845757,38272,172,-1164,-2823,0.965718328952789 +36847,-0.034880556166172,-0.005235830787569,0.035502497106791,38272,-47,-1043,-3020,0.963372528553009 +36849,-0.038362830877304,0.010511517524719,0.031428385525942,38272,556,-2537,-2891,0.961844205856323 +36851,-0.039990652352572,0.019537253305316,0.030382163822651,38272,403,-2165,-3050,0.96523380279541 +36853,-0.036355089396238,0.012931210920215,0.028354302048683,38272,33,-978,-2922,0.96373862028122 +36855,-0.038090914487839,0.016445705667138,0.028187306597829,38272,397,-1727,-3060,0.959254503250122 +36857,-0.04242368042469,0.019820548593998,0.031297855079174,38272,710,-1807,-2883,0.957321226596832 +36859,-0.046926081180573,0.02686095610261,0.030011320486665,38272,738,-2134,-3042,0.95711761713028 +36861,-0.039287775754929,0.024666704237461,0.028725674375892,38272,-170,-1500,-2908,0.958673655986786 +36863,-0.039607234299183,0.034687951207161,0.026936829090119,38272,350,-2469,-3059,0.961249709129334 +36865,-0.046832852065563,0.03676649928093,0.026777310296893,38272,1044,-2015,-2926,0.967067837715149 +36867,-0.047168727964163,0.035799939185381,0.026389254257083,38272,482,-1712,-3058,0.967521727085114 +36869,-0.042622309178114,0.036810200661421,0.025813175365329,38272,139,-1953,-2933,0.970381081104279 +36871,-0.034215345978737,0.042182024568319,0.023751562461257,38272,-312,-2271,-3072,0.972710490226746 +36873,-0.028126092627645,0.055913373827934,0.023500112816691,38272,-207,-3184,-2956,0.973198056221008 +36875,-0.027863370254636,0.053445048630238,0.023755939677358,38272,188,-1893,-3068,0.970848739147186 +36877,-0.03503181040287,0.059852454811335,0.020591098815203,38272,872,-2746,-2986,0.967440247535706 +36879,-0.04148655384779,0.047157667577267,0.018860658630729,38272,877,-1093,-3098,0.961081981658936 +36881,-0.050303503870964,0.03822460398078,0.022117996588349,38272,1272,-1325,-2965,0.957485735416412 +36883,-0.056159000843763,0.04107265919447,0.025655319914222,38272,1068,-2135,-3047,0.963104963302612 +36885,-0.053198840469122,0.039118178188801,0.02475699223578,38272,489,-1856,-2930,0.966301083564758 +36887,-0.04986035451293,0.041834950447083,0.022609082981944,38272,342,-2153,-3064,0.965804815292358 +36889,-0.050048653036356,0.042825032025576,0.022733332589269,38272,677,-2144,-2950,0.968886494636535 +36891,-0.053642239421606,0.049840122461319,0.023272266611457,38272,913,-2594,-3056,0.972438216209412 +36893,-0.050742417573929,0.043359655886889,0.019442476332188,38272,492,-1632,-2985,0.976993680000305 +36895,-0.050542876124382,0.046152040362358,0.016401018947363,38272,618,-2257,-3099,0.973613679409027 +36897,-0.051124628633261,0.038616795092821,0.020792884752154,38272,779,-1488,-2965,0.965562641620636 +36899,-0.0515899322927,0.033611796796322,0.025195864960551,38272,704,-1533,-3035,0.951346457004547 +36901,-0.04983589053154,0.030857289209962,0.025912893936038,38272,616,-1709,-2901,0.941371738910675 +36903,-0.047830659896135,0.030627507716417,0.023866841569543,38272,496,-1842,-3040,0.934734582901001 +36905,-0.051398511976004,0.036906365305185,0.02181732468307,38272,1028,-2477,-2945,0.93352997303009 +36907,-0.052067905664444,0.021335171535611,0.02255173586309,38272,770,-623,-3045,0.934292495250702 +36909,-0.056064121425152,0.021615523844957,0.023671848699451,38272,1152,-1818,-2920,0.939981639385223 +36911,-0.050701688975096,0.018400825560093,0.02357417717576,38272,340,-1475,-3034,0.946078956127167 +36913,-0.045196656137705,0.023779666051269,0.021947354078293,38272,330,-2213,-2936,0.949251055717468 +36915,-0.040754597634077,0.020887000486255,0.02326281554997,38272,284,-1541,-3033,0.953052580356598 +36917,-0.040924578905106,0.013267513364554,0.025313019752503,38272,695,-1104,-2892,0.948795795440674 +36919,-0.045581977814436,0.011334415525198,0.026002848520875,38272,1025,-1473,-3010,0.947721540927887 +36921,-0.044622804969549,0.008528363890946,0.024006241932511,38272,687,-1367,-2904,0.94832581281662 +36923,-0.040515772998333,0.008836148306727,0.020239995792508,38272,345,-1596,-3045,0.948416113853455 +36925,-0.034005500376225,0.007033024914563,0.019824529066682,38272,125,-1426,-2949,0.951244652271271 +36927,-0.034396138042212,0.025170734152198,0.02318724617362,38272,593,-3107,-3022,0.950245022773743 +36929,-0.028171479701996,0.027946926653385,0.026502111926675,38272,55,-2117,-2866,0.952693939208984 +36931,-0.02056385949254,0.031811658293009,0.026559047400951,38272,-168,-2193,-2994,0.954259037971497 +36933,-0.015386767685413,0.025304943323135,0.026837699115276,38272,-65,-1422,-2858,0.954382061958313 +36935,-0.011859741993249,0.010477091185749,0.027260728180409,38272,3,-559,-2984,0.948263645172119 +36937,-0.018150305375457,0.010413382202387,0.027233514934778,38272,815,-1646,-2849,0.952040612697601 +36939,-0.018813418224454,0.004535534884781,0.028759887441993,38272,411,-1118,-2969,0.960049629211426 +36961,-0.005160064436495,-0.009620625525713,0.023114206269384,38075,90,-636,-2871,0.959638237953186 +36963,-0.006482127122581,0.001881362404674,0.022051410749555,38075,300,-2330,-2989,0.967834532260895 +36965,-0.001259722630493,4.75123597425409E-05,0.022106841206551,38075,-270,-1344,-2879,0.971717953681946 +36967,0.003898038994521,-0.012065360322595,0.024177266284824,38075,-314,-435,-2971,0.96909636259079 +36969,0.001631711144,-0.015595101751387,0.027005944401026,38075,220,-962,-2817,0.969260990619659 +36971,-0.007173368241638,-0.015134449116886,0.027278337627649,38075,842,-1282,-2945,0.963560223579407 +36973,-0.012643303722143,-0.00699850730598,0.02743661031127,38075,686,-1929,-2807,0.954080164432526 +36975,-0.009738921187818,-0.002296074992046,0.029660006985068,38075,44,-1764,-2924,0.945454359054565 +36977,-0.01210998557508,0.008569505997002,0.032037679105997,38075,452,-2382,-2748,0.935555815696716 +36979,-0.015301460400224,0.003424085211009,0.033434860408306,38075,564,-1142,-2892,0.929011523723602 +36981,-0.014065390452743,-0.002565225819126,0.034103389829397,38075,216,-1003,-2718,0.923560798168182 +36983,-0.010142843239009,-0.005550479516387,0.031427972018719,38075,-17,-1167,-2900,0.930145263671875 +36985,-0.0035971456673,-0.005272316280752,0.024548295885325,38075,-322,-1405,-2825,0.937410235404968 +36987,-9.25271888263524E-05,-0.000505173520651,0.021502679213882,38075,-132,-1792,-2964,0.943698883056641 +36989,0.001069546211511,-0.005524388514459,0.024487448856235,38075,-8,-1009,-2822,0.949738800525665 +36991,-0.002852355362847,0.000237776708673,0.02597757615149,38075,436,-1870,-2929,0.952703416347504 +36993,-0.002055530901998,-0.01401056163013,0.026026964187622,38075,67,-190,-2800,0.953966617584228 +36995,-0.007654461544007,-0.012595829553902,0.026872122660279,38075,625,-1364,-2919,0.951668798923492 +36997,-0.013538926839829,-0.012675150297582,0.029890706762672,38075,734,-1219,-2749,0.95267117023468 +36999,-0.019709737971425,-0.007404628675431,0.026571346446872,38075,843,-1705,-2916,0.953505754470825 +37001,-0.016720902174711,0.000434321234934,0.024100862443447,38075,158,-1998,-2813,0.95609837770462 +37003,-0.008406759239733,0.002691995352507,0.027102397754788,38075,-349,-1631,-2908,0.955311596393585 +37005,-0.00395722547546,-0.001964732538909,0.027103148400784,38075,-144,-1060,-2773,0.949646711349487 +37007,-0.005625353660434,-0.010269184596837,0.024637810885906,38075,327,-684,-2920,0.945880115032196 +37009,-0.011284332722426,-0.005107006523758,0.02178473956883,38075,697,-1709,-2831,0.944877564907074 +37011,-0.010931232944131,-0.006309176795185,0.019564557820559,38075,262,-1245,-2951,0.949263513088226 +37013,-0.00536230718717,0.002835517283529,0.019903855398297,38075,-119,-1797,-2946,0.954808175563812 +37015,-0.001529490225948,0.005764672067016,0.018954956904054,38075,138,-1449,-2858,0.952783167362213 +37017,-0.001879037474282,0.009207639843225,0.019736228510738,38075,184,-1800,-2944,0.951122164726257 +37019,-0.000320186547469,0.004368189256638,0.023921208456159,37682,5,-1148,-2795,0.947798609733582 +37021,-0.000320186547469,0.004368189256638,0.023921208456159,37682,5,-1148,-2795,0.947798609733582 +37023,-0.000222396760364,0.004371629562229,0.021417479962111,37682,84,-1218,-2821,0.943729758262634 +37025,0.000863490509801,0.009066101163626,0.017876738682389,37682,38,-1889,-2948,0.940087616443634 +37027,0.006733608897775,0.011275753378868,0.018953498452902,37682,-432,-1782,-2846,0.93370509147644 +37029,0.00162031990476,0.021068612113595,0.014879017136991,37682,466,-2432,-2966,0.930898129940033 +37031,0.00162031990476,0.021068612113595,0.014879017136991,37682,466,-2432,-2966,0.930898129940033 +37033,-0.009118115529418,0.025063468143344,0.011516120284796,37682,455,-1869,-2987,0.940485775470733 +37035,-0.009122170507908,0.029833171516657,0.014309415593743,37682,258,-2280,-2896,0.942642748355866 +37037,-0.009463009424508,0.027412824332714,0.015650287270546,37682,288,-1673,-2956,0.945014595985413 +37039,-0.011769074015319,0.029113976284862,0.014024496078491,37682,465,-2057,-2897,0.947820067405701 +37041,-0.011769074015319,0.029113976284862,0.014024496078491,37682,465,-2057,-2897,0.947820067405701 +37047,-0.012679058127105,0.043712362647057,0.009180601686239,37682,571,-2343,-2950,0.948678314685822 +37049,-0.01654139906168,0.03807158023119,0.00879231095314,37682,653,-1640,-2997,0.946943283081055 +37051,-0.016549922525883,0.029502669349313,0.007665909361094,37682,398,-1371,-2967,0.94122838973999 +37053,-0.017807135358453,0.034667007625103,0.007830911315978,37682,493,-2377,-3003,0.937701344490051 +37055,-0.023612961173058,0.036931972950697,0.009751846082509,37378,930,-2290,-2940,0.934213042259216 +37057,-0.03072159178555,0.045019492506981,0.009390451945364,37378,1107,-2753,-2990,0.934944927692413 +37059,-0.030573977157474,0.041262421756983,0.006610990036279,37378,631,-1947,-2976,0.9376300573349 +37061,-0.036250129342079,0.047178022563458,0.002573862904683,37378,1097,-2647,-3036,0.935512065887451 +37063,-0.039920177310705,0.044883336871862,-0.000412553665228,37378,1072,-2128,-3058,0.932636082172394 +37065,-0.039193455129862,0.038643669337034,-0.003791669616476,37378,698,-1675,-3079,0.925150334835052 +37067,-0.040116116404533,0.034566540271044,-0.003432567464188,37378,894,-1842,-3093,0.922002792358398 +37069,-0.041002202779055,0.030401142314077,-0.000594505632762,37378,857,-1720,-3058,0.921441853046417 +37071,-0.040854416787624,0.036171618849039,3.41192280757241E-05,37378,845,-2594,-3053,0.922760367393494 +37073,-0.035897005349398,0.030090095475316,0.000172252795892,37378,383,-1594,-3052,0.929423093795776 +37075,-0.038729630410671,0.039598755538464,0.002619706792757,37378,1032,-2944,-3022,0.93815815448761 +37077,-0.035191014409065,0.031402762979269,0.003775917226449,37378,490,-1480,-3027,0.941103100776672 +37079,-0.033283859491348,0.031462397426367,0.00119666766841,37378,620,-2146,-3038,0.941938281059265 +37081,-0.032801076769829,0.025261659175158,-8.77739003044553E-05,37378,687,-1550,-3053,0.940159976482391 +37083,-0.037957556545735,0.026250518858433,-0.00108150660526,37378,1218,-2131,-3065,0.934491455554962 +37085,-0.036700416356325,0.028280729427934,-0.001195007935166,37378,704,-2194,-3060,0.935627400875092 +37087,-0.035006947815418,0.022068981081247,0.000667837623041,37378,703,-1558,-3044,0.940546452999115 +37089,-0.032340615987778,0.021476438269019,-0.000263264635578,37378,556,-1917,-3054,0.948832988739014 +37091,-0.028784086927772,0.01301830355078,-0.002366637811065,37378,483,-1261,-3080,0.950416684150696 +37093,-0.026290765032172,0.013623346574605,-0.004570615943521,37378,495,-1896,-3083,0.947228968143463 +37095,-0.014288996346295,0.00665852567181,-0.005562667734921,37378,-353,-1272,-3118,0.939757168292999 +37097,-0.013516979292035,0.009374345652759,-0.003892074106261,37378,440,-1990,-3079,0.931691348552704 +37099,-0.017248790711165,0.006945479195565,0.000413448055042,37378,829,-1602,-3048,0.928701162338257 +37101,-0.017522281035781,0.009232081472874,0.003272286150604,37378,580,-1960,-3030,0.925140261650085 +37103,-0.00869364105165,0.011820404790342,0.001980986446142,37378,-201,-2055,-3029,0.924713551998138 +37105,-0.0049520554021,0.00693810172379,-0.00177184084896,37378,115,-1421,-3064,0.92624706029892 +37107,-0.009251983836293,0.006899971980602,-0.000579928804655,37378,748,-1795,-3059,0.931206166744232 +37109,-0.006192079279572,-0.0092140622437,0.003433292731643,37378,185,-389,-3028,0.933972716331482 +37111,-0.000646728847641,-0.010356686078012,0.003883671481162,37378,-93,-1426,-3006,0.934566736221314 +37113,0.004013166762888,-0.015379155054689,0.003141063963994,37378,-76,-1090,-3029,0.939755320549011 +37115,0.000593415112235,-0.005355462431908,0.001036459230818,37378,533,-2296,-3039,0.943135380744934 +37117,0.007370854727924,-0.007578732911497,0.003100426634774,37378,-276,-1399,-3029,0.949133157730102 +37119,0.004671772941947,-0.006530362181365,0.001379852183163,37378,425,-1627,-3034,0.944601058959961 +37121,-0.008158089593053,-0.001539234421216,0.002772711450234,37378,1351,-1997,-3031,0.946124136447906 +37123,-0.004980531986803,-0.012241023592651,0.005148829892278,37378,145,-693,-2989,0.939818918704987 +37125,0.005083169322461,-0.020980086177588,0.004906365647912,37378,-477,-729,-3015,0.933189690113068 +37127,0.009976850822568,-0.032364442944527,0.003689347067848,37378,-233,-311,-3006,0.93020361661911 +37129,0.007785184308887,-0.033077530562878,0.003666765056551,37378,354,-1115,-3023,0.926546454429626 +37131,0.010230363346636,-0.047461584210396,0.007175542414188,37378,-57,162,-2964,0.92348837852478 +37133,0.008298725821078,-0.044004503637552,0.007534204982221,37378,322,-1237,-2995,0.920044660568237 +37135,0.007140559144318,-0.046155422925949,0.006644525099546,37378,250,-717,-2969,0.921763777732849 +37137,0.003756335936487,-0.040714435279369,0.004741747863591,37378,488,-1406,-3013,0.925530850887299 +37139,0.003427778370678,-0.032803762704134,0.004509370308369,37378,248,-1624,-2992,0.932184994220733 +37141,0.007313776761293,-0.034636370837689,0.005490437150002,37378,-85,-955,-3007,0.934058547019958 +37143,0.003064064541832,-0.027551589533687,0.004870261996984,37378,531,-1641,-2987,0.936663806438446 +37145,-0.000783773313742,-0.028289545327425,0.004643088206649,37378,582,-1112,-3012,0.943487405776978 +37147,-0.006345734000206,-0.023210549727082,0.003206027438864,37378,781,-1559,-3006,0.945968806743622 +37149,-6.84616170474328E-05,-0.033356752246618,0.000999345327727,37378,-150,-354,-3036,0.94657289981842 +37151,0.000453580112662,-0.027351858094335,0.000950814865064,37378,223,-1543,-3032,0.943558573722839 +37153,0.004764463752508,-0.028946215286851,0.002041266299784,37378,-81,-1017,-3028,0.940800726413727 +37155,0.000828649441246,-0.024795042350888,0.001129521871917,37378,521,-1440,-3029,0.934830844402313 +37157,-0.00314120715484,-0.022648584097624,0.001277208793908,37378,620,-1363,-3033,0.935458421707153 +37159,-0.002150509040803,-0.029393104836345,0.003700483823195,37378,226,-572,-2998,0.93468189239502 +37161,0.001258108415641,-0.037135027348995,0.009251425042748,37378,27,-433,-2978,0.936371624469757 +37163,0.005573041271418,-0.041917230933905,0.011010145768523,37378,-139,-488,-2911,0.939200341701508 +37165,0.006391189992428,-0.030408995226026,0.008973344229162,37378,134,-1888,-2978,0.941178858280182 +37167,0.00508897472173,-0.031123330816627,0.009143672883511,37378,265,-919,-2931,0.943133294582367 +37169,-0.003685570554808,-0.020443733781576,0.009525688365102,37378,961,-1953,-2972,0.944409787654877 +37171,-0.008106182329357,-0.020895982161164,0.010083797387779,37378,708,-1092,-2918,0.941879391670227 +37173,-0.008600776083767,-0.023876901715994,0.008959288708866,37378,441,-912,-2974,0.944538235664368 +37175,-0.003526710439473,-0.024837410077453,0.009550089016557,37378,-39,-996,-2923,0.950610935688019 +37177,0.002025335328653,-0.025633167475462,0.010801253840327,37378,-143,-1031,-2960,0.949886918067932 +37179,0.000935475574806,-0.015906112268567,0.008897591382265,37378,322,-1900,-2928,0.947410523891449 +37197,-0.001053518033586,-0.008087082765996,0.008941327221692,37378,0,-1290,-2964,0.953241467475891 +37199,0.000576019054279,-0.017620947211981,0.010929978452623,37378,121,-436,-2896,0.948883175849915 +37201,-0.005986054427922,-0.010935285128653,0.013160943984985,37378,835,-1732,-2933,0.946193158626556 +37203,-0.012662648223341,-0.008485094644129,0.016931859776378,37378,944,-1435,-2822,0.945297837257385 +37205,-0.01778032258153,-0.004865702241659,0.017509350553155,37378,905,-1592,-2900,0.942996621131897 +37207,-0.015120285563171,-0.007470231503248,0.016161557286978,37378,314,-1093,-2828,0.940204560756683 +37209,-0.015373730100691,0.002990690292791,0.012077691964805,37378,527,-2189,-2934,0.934131324291229 +37211,-0.01507103163749,0.016334403306246,0.010759089142084,37378,473,-2625,-2889,0.936370551586151 +37213,-0.010448765009642,0.027810065075755,0.012676332145929,37378,109,-2624,-2928,0.936444342136383 +37215,-0.0066032349132,0.03419391810894,0.014370839111507,37378,107,-2422,-2844,0.939788043498993 +37217,-0.004836979787797,0.044580452144146,0.013801434077323,37378,235,-2801,-2918,0.938905358314514 +37219,-0.004819815047085,0.054402381181717,0.015335654839873,37378,376,-3007,-2830,0.935653746128082 +37221,-0.000138872244861,0.042414400726557,0.016061631962657,37378,-35,-1188,-2899,0.935390412807465 +37223,0.003201487939805,0.044751882553101,0.014674453996122,37378,-4,-2344,-2835,0.938724100589752 +37225,0.004923168569803,0.036912586539984,0.016071885824204,37378,103,-1425,-2897,0.943527579307556 +37227,0.002492493484169,0.046523593366146,0.01470931340009,37378,416,-2918,-2832,0.944971740245819 +37229,0.008624371141195,0.045482870191336,0.013948000967503,37378,-267,-2056,-2908,0.936977565288544 +37231,0.006154303438962,0.048326183110476,0.015369610860944,37378,373,-2485,-2822,0.930039823055267 +37233,-0.002547433134168,0.057788610458374,0.016267886385322,37378,955,-3007,-2890,0.932521283626556 +37235,-0.00640810886398,0.056419994682074,0.015654679387808,37378,683,-2333,-2815,0.929815351963043 +37237,-0.005214989185333,0.055624037981033,0.016565481200814,37378,290,-2267,-2885,0.92556369304657 +37239,-0.006672481540591,0.060800589621067,0.016113115474582,37378,500,-2904,-2807,0.923964262008667 +37241,-0.004065942950547,0.070887163281441,0.012880676425994,37378,-32767,-32767,-2907,0.92772376537323 +37243,0.009233413264155,0.065241664648056,0.009378754533827,37163,-9374,-31675,-2884,0.937447965145111 +37245,0.014598153531551,0.067259460687637,0.005662267096341,37163,-8893,-32285,-2955,0.941006362438202 +37247,0.012603675015271,0.059506949037314,0.003384872572497,37163,-8404,-31740,-2953,0.942836463451386 +37249,0.007661750540137,0.054340295493603,0.002158431801945,37163,-8143,-31902,-2978,0.936566174030304 +37251,-0.000454629625892,0.041144169867039,0.00534606538713,37163,-7849,-31358,-2929,0.934534192085266 +37253,-0.009723755531013,0.014418295584619,0.00702594127506,37163,-7667,-30093,-2944,0.932982444763184 +37255,-0.022465793415904,-0.006141717545688,0.007215411867946,37163,-7255,-30368,-2907,0.937179207801819 +37257,-0.038029078394175,-0.048755716532469,0.005260656122118,37163,-6887,-28336,-2954,0.93578165769577 +37259,-0.063971094787121,-0.098648265004158,0.003467203816399,37163,-5699,-27038,-2950,0.933726131916046 +37261,-0.091773934662342,-0.17797726392746,0.003086796496063,37163,-5295,-24097,-2969,0.93109542131424 +37263,-0.123631671071053,-0.256536066532135,0.001864321064204,37163,-4347,-22630,-2970,0.929888963699341 +37265,-0.150233715772629,-0.34982368350029,0.003083290765062,37163,-4571,-20805,-2968,0.931882798671722 +37267,-0.183968499302864,-0.444407135248184,0.000554726284463,37163,-3263,-18558,-2988,0.930835902690887 +37269,-0.204268902540207,-0.553279101848602,-0.00330737628974,37163,-4250,-16854,-3012,0.932953417301178 +37271,-0.232601806521416,-0.66226863861084,-0.00789235625416,37163,-2847,-14013,-3093,0.929648578166962 +37273,-0.264238506555557,-0.779370486736298,-0.011430849321187,37163,-2557,-13001,-3069,0.927953839302063 +37275,-0.297402948141098,-0.908041298389435,-0.014481940306723,37163,-1406,-8539,-3181,0.9313884973526 +37277,-0.334743589162827,-1.04008913040161,-0.016488175839186,37163,-1084,-8055,-3107,0.936133742332458 +37279,-0.367701441049576,-1.16866087913513,-0.019476588815451,37163,-207,-4123,-3256,0.939995110034943 +37281,-0.400065690279007,-1.29443538188934,-0.022043554112315,37163,-417,-4599,-3149,0.948985695838928 +37283,-0.428822040557861,-1.43599998950958,-0.022290550172329,37163,599,1470,-3312,0.953225910663605 +37285,-0.461336433887482,-1.56257176399231,-0.023946769535542,37163,591,-310,-3167,0.951153337955475 +37287,-0.4897640645504,-1.70528697967529,-0.027481015771628,37163,1700,6366,-3404,0.950013756752014 +37289,-0.524682998657227,-1.82259857654572,-0.032926607877016,37163,1820,3268,-3236,0.951628684997559 +37291,-0.554029762744904,-1.95603251457214,-0.035967659205198,37163,2964,10332,-3541,0.941364407539368 +37293,-0.579648852348328,-2.07027173042297,-0.03838275000453,37163,2121,7233,-3282,0.933694899082184 +37295,-0.602877736091614,-2.19274520874023,-0.036814089864493,37163,3508,14065,-3598,0.930955529212952 +37297,-0.630511522293091,-2.28963470458984,-0.037229888141155,37163,3197,9882,-3285,0.933702349662781 +37299,-0.64055734872818,-2.38917875289917,-0.037816289812327,37163,3384,16394,-3662,0.942976176738739 +37301,-0.655533611774445,-2.47463154792786,-0.037033140659332,37163,2870,12558,-3296,0.941946685314178 +37303,-0.659888446331024,-2.56684970855713,-0.034075111150742,37163,3512,19633,-3675,0.94448447227478 +37305,-0.667873203754425,-2.6536431312561,-0.033951293677092,37163,2778,16152,-3288,0.946638405323029 +37307,-0.668364763259888,-2.72515082359314,-0.036137286573649,37163,3614,21689,-3762,0.943191468715668 +37309,-0.66810417175293,-2.7927508354187,-0.041283741593361,37163,2428,17784,-3353,0.936652183532715 +37311,-0.679609537124634,-2.83529162406921,-0.044122327119112,37163,4831,22429,-3920,0.936725318431854 +37313,-0.687178194522858,-2.85895967483521,-0.04213011264801,37163,3509,16655,-3377,0.943112850189209 +37315,-0.686087548732758,-2.87183618545532,-0.041514895856381,37163,4283,21963,-3949,0.949943602085114 +37317,-0.672066211700439,-2.89511203765869,-0.04082166403532,37163,1997,18237,-3387,0.950259506702423 +37319,-0.659361839294434,-2.89690113067627,-0.038333002477884,37163,3262,22663,-3971,0.945282638072968 +37321,-0.643766105175018,-2.90455865859985,-0.032855242490769,37163,1719,18364,-3352,0.940950691699982 +37323,-0.631729423999786,-2.88393521308899,-0.030780775472522,37163,3089,21946,-3932,0.9375821352005 +37325,-0.613426923751831,-2.85197472572327,-0.030279977247119,37163,1318,15882,-3354,0.937260985374451 +37327,-0.593374609947205,-2.81553196907043,-0.02898227237165,37163,2117,20781,-3953,0.9371697306633 +37329,-0.579756736755371,-2.76946258544922,-0.025402991101146,37163,1385,14772,-3340,0.943535029888153 +37331,-0.566348195075989,-2.71890616416931,-0.021592728793621,37163,2365,19254,-3900,0.948281049728394 +37333,-0.546226799488068,-2.65022563934326,-0.017587000504136,37163,641,12488,-3306,0.955464661121368 +37335,-0.526306331157684,-2.58207821846008,-0.012356700375676,37163,1441,16791,-3811,0.961150944232941 +37337,-0.51066517829895,-2.49142289161682,-0.009841220453382,37163,638,9626,-3270,0.970481276512146 +37339,-0.487118154764175,-2.40338587760925,-0.014948812313378,37163,717,13421,-3846,0.973810911178589 +37341,-0.461560696363449,-2.31250333786011,-0.017629789188504,37163,-607,7960,-3342,0.974064648151398 +37343,-0.440685153007507,-2.2057580947876,-0.014109945856035,37163,315,9745,-3834,0.977422893047333 +37345,-0.418618857860565,-2.10403490066528,-0.009691241197288,37163,-824,5026,-3304,0.973845422267914 +37347,-0.39972996711731,-2.00247120857239,-0.008368755690753,37163,-68,7598,-3755,0.967840790748596 +37349,-0.383240640163422,-1.90038061141968,-0.008762252517045,37163,-800,2822,-3313,0.962537944316864 +37351,-0.367180973291397,-1.79246580600739,-0.007975667715073,37163,-284,4423,-3726,0.952974379062653 +37353,-0.347708463668823,-1.67770135402679,-0.002604283858091,37163,-1409,-627,-3284,0.955679416656494 +37355,-0.33223757147789,-1.55616247653961,0.006291925441474,37163,-700,209,-3530,0.958360254764557 +37357,-0.322673261165619,-1.4364048242569,0.013613375835121,37163,-958,-3899,-3183,0.965026795864105 +37359,-0.309798389673233,-1.31433129310608,0.015186532400549,37163,-767,-3273,-3394,0.973014414310455 +37361,-0.294892281293869,-1.19603884220123,0.014950874261558,37163,-1645,-6803,-3181,0.978610634803772 +37363,-0.272976964712143,-1.09062659740448,0.013616796582937,37163,-1932,-5323,-3371,0.9790980219841 +37365,-0.260500013828278,-0.981457471847534,0.015245753340423,37163,-1888,-8889,-3185,0.971596300601959 +37367,-0.254273980855942,-0.884969115257263,0.022191340103746,37163,-1053,-7722,-3225,0.974706292152405 +37369,-0.248001366853714,-0.786431610584259,0.024432003498077,37163,-1556,-10677,-3125,0.979902744293213 +37371,-0.241099461913109,-0.69351989030838,0.021896284073591,37163,-1260,-10382,-3183,0.982546150684357 +37373,-0.229670897126198,-0.605022609233856,0.018851820379496,37163,-2129,-12400,-3164,0.980630099773407 +37375,-0.227848395705223,-0.517840623855591,0.024139955639839,37163,-1063,-12702,-3112,0.978853583335876 +37377,-0.238862171769142,-0.450545877218246,0.035554431378841,37163,-336,-13016,-3049,0.975864171981812 +37379,-0.244656205177307,-0.386896878480911,0.038283910602331,37163,-196,-13079,-2910,0.968556106090546 +37381,-0.244804292917252,-0.327946305274963,0.038990303874016,37163,-969,-14153,-3021,0.966711938381195 +37383,-0.240759462118149,-0.274123460054398,0.036276742815971,37163,-911,-14206,-2898,0.963216722011566 +37385,-0.238229632377624,-0.216616258025169,0.03302763774991,37163,-1198,-15674,-3058,0.963712811470032 +37387,-0.241230383515358,-0.171756967902184,0.034944277256727,37163,-350,-15278,-2878,0.965209305286408 +37389,-0.253490597009659,-0.124273680150509,0.038475655019283,37163,137,-16355,-3015,0.966317176818848 +37391,-0.264085471630096,-0.10121838748455,0.039231877774,37163,10899,20028,-2802,0.962486326694488 +37393,-0.269779741764069,-0.087041787803173,0.036398936063051,37163,1703,-8701,-3022,0.951180815696716 +37395,-0.280926614999771,-0.073155835270882,0.033820535987616,37163,2761,-8925,-2857,0.950994849205017 +37397,-0.290858924388885,-0.069710493087769,0.034605920314789,37163,2404,-8241,-3028,0.949808120727539 +37399,-0.304088115692139,-0.058655913919211,0.034390706568956,37163,3394,-9015,-2844,0.953566014766693 +37401,-0.305973261594772,-0.063759669661522,0.031893115490675,37163,2152,-7780,-3041,0.960154473781586 +37403,-0.304945021867752,-0.063355468213558,0.030664954334498,37163,2494,-8234,-2882,0.959727048873901 +37405,-0.301411062479019,-0.073568180203438,0.029145251959562,37163,1807,-7336,-3054,0.955748081207275 +37407,-0.312290042638779,-0.072505563497543,0.026022709906101,37163,3567,-8193,-2929,0.952945113182068 +37409,-0.316401332616806,-0.083447694778442,0.02686264552176,37163,2681,-7201,-3065,0.95479291677475 +37423,-0.284808933734894,-0.173229545354843,0.022773234173656,37163,2368,-4913,-2978,0.951906263828278 +37425,-0.281439125537872,-0.197886660695076,0.021443918347359,37163,2070,-4716,-3085,0.950431048870087 +37427,-0.275201618671417,-0.230158120393753,0.021006692200899,37163,2281,-3414,-3023,0.951949000358582 +37429,-0.273194223642349,-0.247394248843193,0.016823878511787,37163,12246,30273,-3115,0.954493761062622 +37431,-0.26362282037735,-0.270497500896454,0.014932879246771,37163,3666,2486,-3110,0.960855841636658 +37433,-0.248553231358528,-0.298849880695343,0.013821803964675,37163,2671,2949,-3135,0.960811614990234 +37435,-0.234051570296288,-0.321041315793991,0.015146176330745,37163,2931,3352,-3119,0.962547779083252 +37437,-0.219745054841042,-0.341571003198624,0.01545790117234,37163,2411,3118,-3123,0.961649060249329 +37439,-0.203432500362396,-0.358862966299057,0.014147978276014,37163,2394,3744,-3142,0.961762011051178 +37441,-0.184104636311531,-0.373053073883057,0.013457158580422,37163,1626,3251,-3137,0.957526981830597 +37443,-0.162687316536903,-0.36847659945488,0.013518201187253,37163,1445,2460,-3155,0.955305397510529 +37445,-0.134696021676064,-0.376753211021423,0.014056611806154,37163,364,3020,-3134,0.951982915401459 +37447,-0.11806358397007,-0.367381036281586,0.012104890309274,37163,1119,2233,-3172,0.951160609722137 +37449,-0.104210563004017,-0.36563977599144,0.010894016362727,37163,986,2281,-3156,0.949868738651276 +37451,-0.09069324284792,-0.355966210365295,0.011045888066292,37163,923,2159,-3174,0.946034371852875 +37453,-0.067922726273537,-0.341536432504654,0.013464283198118,37163,-141,1160,-3139,0.950308561325073 +37455,-0.042709954082966,-0.329919427633285,0.015500217676163,37163,-667,1722,-3116,0.950364351272583 +37457,-0.019943157210946,-0.314615458250046,0.016280464828014,37163,-818,832,-3119,0.955917835235596 +37459,0.000527659722138,-0.301450729370117,0.01745143160224,37163,-1023,1265,-3086,0.952935457229614 +37461,0.018021516501904,-0.278465569019318,0.018768006935716,37163,-993,-126,-3101,0.950225591659546 +37463,0.03883084282279,-0.260828882455826,0.019342929124832,37163,-1690,396,-3047,0.946620345115662 +37465,0.057737447321415,-0.232953101396561,0.018621621653438,37163,-1691,-1037,-3100,0.945206344127655 +37467,0.078481569886208,-0.222739696502686,0.019450476393104,37163,7729,32767,-3030,0.9498091340065 +37469,0.093435682356358,-0.194583773612976,0.021278712898493,37163,-260,4374,-3080,0.951439142227173 +37471,0.110515058040619,-0.174181967973709,0.023559730499983,37163,-972,4849,-2959,0.953902125358582 +37473,0.121556214988232,-0.142547249794006,0.021454146131873,37163,-429,3486,-3075,0.952970683574676 +37475,0.139501646161079,-0.116536393761635,0.019841464236379,37163,-1555,3604,-2981,0.95030665397644 +37477,0.160064145922661,-0.091827139258385,0.021007688716054,37163,-1722,3336,-3075,0.943391740322113 +37479,0.170655146241188,-0.04312364757061,0.022526860237122,37163,-1598,860,-2924,0.947309732437134 +37481,0.180985495448113,-0.004442614503205,0.025466224178672,37163,-1363,1130,-3039,0.951740562915802 +37483,0.200082540512085,0.040100034326315,0.024259306490421,37163,-2752,-168,-2879,0.961136043071747 +37485,0.21802830696106,0.092115074396134,0.020712226629257,37163,-2525,-1200,-3066,0.96852034330368 +37487,0.223890364170074,0.152730405330658,0.018789142370224,37163,-2278,-3159,-2906,0.974602282047272 +37489,0.240161180496216,0.197498649358749,0.018908264115453,37163,-2820,-2235,-3073,0.975092887878418 +37491,0.250361680984497,0.237994357943535,0.019096128642559,37163,-3126,-3151,-2869,0.967263758182526 +37493,0.25081193447113,0.281112730503082,0.01774949207902,37163,-1950,-3397,-3074,0.961403548717499 +37495,0.254480421543121,0.327282816171646,0.016978187486529,37163,-2849,-5101,-2856,0.954147160053253 +37497,0.260642230510712,0.38259094953537,0.017890570685268,37163,-2615,-5847,-3065,0.949172794818878 +37499,0.268195897340775,0.429994255304337,0.019118595868349,37163,-3473,-7007,-2794,0.944299280643463 +37501,0.266334474086761,0.480168342590332,0.019302304834128,37163,-2245,-7050,-3047,0.939102351665497 +37503,0.262946099042892,0.512637674808502,0.020572874695063,37163,-2728,-7468,-2746,0.93779319524765 +37505,0.249824792146683,0.556433975696564,0.022644808515906,37163,18869,26899,-3014,0.936668336391449 +37507,0.24313873052597,0.592305481433868,0.027049394324422,37163,1115,-3361,-2638,0.93760472536087 +37509,0.23883618414402,0.63156396150589,0.028369944542647,37163,1514,-2995,-2963,0.93993479013443 +37511,0.232127994298935,0.66560959815979,0.02882974408567,37163,1225,-4619,-2593,0.941407740116119 +37513,0.221937730908394,0.688145279884338,0.032991241663694,37163,2103,-2834,-2919,0.939673066139221 +37515,0.210884034633636,0.722856223583221,0.034782335162163,37163,1817,-5823,-2503,0.943429470062256 +37517,0.208207592368126,0.755959868431091,0.034394569694996,37163,1696,-4817,-2896,0.940172672271728 +37519,0.2074244171381,0.787704825401306,0.031181417405605,37163,1065,-6940,-2515,0.934077978134155 +37521,0.208827659487724,0.812418162822723,0.030099214985967,37163,1329,-5312,-2912,0.929791867733002 +37523,0.205181166529655,0.847597002983093,0.029007142409682,37163,1230,-8468,-2510,0.927173674106598 +37525,0.208583995699882,0.878353118896484,0.02871678583324,37163,1121,-7008,-2908,0.929097294807434 +37527,0.211570918560028,0.906980872154236,0.027980646118522,37163,588,-9290,-2501,0.926298975944519 +37529,0.205574706196785,0.940087139606476,0.025828178972006,37163,1768,-8410,-2914,0.928507268428802 +37531,0.202101185917854,0.963244140148163,0.024208882823587,37163,1143,-10167,-2526,0.931958079338074 +37533,0.197085499763489,0.984485864639282,0.02359214797616,37163,1754,-8573,-2916,0.938471376895904 +37535,0.198693677783012,0.989856004714966,0.022447146475315,37163,771,-9705,-2532,0.943064868450165 +37537,0.199020907282829,1.00855576992035,0.022121429443359,37163,1279,-9127,-2912,0.949055075645447 +37539,0.205507591366768,1.01270532608032,0.023867512121797,37163,246,-10386,-2502,0.952893674373627 +37541,0.205153286457062,1.02723288536072,0.0219766497612,37163,1172,-9501,-2900,0.953048527240753 +37543,0.205600708723068,1.02564430236816,0.020230825990439,37163,621,24215,-2539,0.954557538032532 +37545,0.204621031880379,1.02516388893127,0.020418964326382,37163,1158,-2931,-2898,0.949756920337677 +37547,0.202457576990128,1.02628636360168,0.018834816291928,37163,785,-5295,-2545,0.951579451560974 +37549,0.205681726336479,1.0143233537674,0.015162625350058,37163,774,-2311,-2922,0.947429180145264 +37551,0.204457104206085,1.00940704345703,0.011841299012303,37163,614,-4943,-2623,0.950392961502075 +37553,0.200063183903694,1.00344908237457,0.012663781642914,37163,1330,-2938,-2928,0.952239453792572 +37555,0.196234419941902,1.01113319396973,0.013982163742185,37163,873,-6217,-2595,0.948878407478332 +37575,0.207129746675491,0.999967455863952,0.010296883061528,37163,-298,-6859,-2617,0.941829323768616 +37577,0.213415458798408,0.998368322849274,0.011377116665244,37163,-38,-5350,-2875,0.933696448802948 +37579,0.211038202047348,0.991725206375122,0.012969058007002,37163,110,-7048,-2580,0.933373630046844 +37581,0.204525858163834,0.987275183200836,0.010887722484768,37163,928,-5353,-2869,0.934471428394318 +37583,0.212087273597717,0.965734601020813,0.009513090364635,37163,-684,-5915,-2625,0.938504934310913 +37585,0.217028349637985,0.955712020397186,0.005778967868537,37163,-147,-4857,-2895,0.936092853546143 +37587,0.21741209924221,0.943331003189087,0.006281773094088,37163,-326,-6547,-2667,0.937384247779846 +37589,0.214494898915291,0.933016896247864,0.010306100361049,37163,374,-4858,-2857,0.936874389648438 +37591,0.204970002174377,0.920969188213348,0.016296867281199,37163,504,-6544,-2548,0.941087424755096 +37593,0.195838704705238,0.902759253978729,0.01710488833487,37163,1013,-4197,-2801,0.941101789474487 +37595,0.194895327091217,0.892928540706635,0.013356882147491,37163,-19,-6585,-2583,0.946062326431274 +37597,0.197157695889473,0.870779573917389,0.009959596209228,37163,108,-3785,-2841,0.951672077178955 +37599,0.192757815122604,0.854345619678497,0.006417742464691,37163,202,-5798,-2670,0.956587255001068 +37601,0.18843050301075,0.831261873245239,0.007640884257853,37163,637,-3464,-2850,0.953138887882233 +37603,0.181479766964912,0.821907222270966,0.009629756212235,37163,497,-6087,-2634,0.943434417247772 +37605,0.183047950267792,0.806194841861725,0.008456635288894,37163,227,-3933,-2838,0.937383234500885 +37607,0.180309981107712,0.794313132762909,0.005315903574228,37163,143,-5751,-2684,0.928789734840393 +37609,0.181984663009644,0.764127671718597,0.003735294798389,37163,168,-2583,-2864,0.926903903484344 +37611,0.183152541518211,0.740251779556274,0.000373652146664,37163,-245,-4298,-2750,0.922151863574982 +37613,0.183249279856682,0.72479647397995,-0.000308198010316,37163,196,-3343,-2887,0.92280912399292 +37615,0.179921254515648,0.705694079399109,-0.003233114257455,37163,67,-4345,-2798,0.92255437374115 +37617,0.170040234923363,0.690209150314331,-0.003229474416003,37163,1035,-3101,-2903,0.926360785961151 +37619,0.167812019586563,0.660376489162445,0.002275138394907,37163,127,-3076,-2740,0.923969030380249 +37621,0.173088327050209,0.641734778881073,0.005447830539197,37163,-153,-2416,-2839,0.928885281085968 +37623,0.175358355045319,0.620495438575745,0.002913617761806,37163,-370,-3264,-2739,0.939172327518463 +37625,0.167618244886398,0.607421100139618,-0.004031880758703,37163,795,-2541,-2900,0.948890686035156 +37627,0.166610822081566,0.586723804473877,-0.004350533243269,37163,-38,-2965,-2832,0.95740133523941 +37629,0.161863312125206,0.579113960266113,-0.002036266028881,37163,607,-2731,-2884,0.956417560577393 +37631,0.165388464927673,0.567325949668884,-0.001814949326217,37163,-409,-3488,-2802,0.953719794750214 +37633,0.16626738011837,0.55949079990387,-0.003838261356577,37163,83,-2630,-2893,0.948490858078003 +37635,0.166990324854851,0.534911870956421,-0.008714146912098,37163,-310,-2223,-2884,0.947982430458069 +37637,0.170271337032318,0.511428773403168,-0.01710700802505,37163,-208,-1002,-2983,0.941883325576782 +37639,0.17184217274189,0.495807260274887,-0.018479902297258,37163,-507,-2409,-3007,0.943324089050293 +37641,0.168406024575233,0.480101704597473,-0.01756102219224,37163,235,-1276,-2986,0.948092937469482 +37643,0.160018846392632,0.478852540254593,-0.01444538589567,37163,338,-3343,-2964,0.957111120223999 +37645,0.157494440674782,0.466769546270371,-0.010427075438202,37163,267,-1507,-2937,0.953891932964325 +37647,0.158221930265427,0.46302005648613,-0.009355288930237,37163,-347,-3065,-2907,0.946310877799988 +37649,0.15751925110817,0.450619757175446,-0.008589753881097,37163,77,-1410,-2923,0.94050931930542 +37651,0.151681989431381,0.44431608915329,-0.009962423704565,37163,176,-2723,-2918,0.938302338123322 +37653,0.155075266957283,0.431770294904709,-0.007540345191956,37163,-236,-1277,-2915,0.940023243427277 +37655,0.152418151497841,0.431148707866669,-0.007422061171383,37163,-97,-3067,-2895,0.945070385932922 +37657,0.151272878050804,0.423737287521362,-0.012405663728714,37038,90,-1674,-2948,0.952278077602386 +37659,0.15256068110466,0.425577044487,-0.01921071484685,37038,-434,-3297,-3036,0.951761186122894 +37661,0.157983928918839,0.421394497156143,-0.020426865667105,37038,-530,-2016,-3004,0.951811671257019 +37663,0.163304716348648,0.417394876480103,-0.018413510173559,37038,-961,-2864,-3029,0.945307731628418 +37665,0.15701088309288,0.411982834339142,-0.01590976305306,37038,263,-1930,-2974,0.948627650737762 +37667,0.147255331277847,0.398355573415756,-0.014025921933353,37038,320,-1990,-2981,0.949309051036835 +37669,0.142991796135902,0.402178287506104,-0.011520347557962,37038,265,-2580,-2944,0.955893158912659 +37671,0.145518243312836,0.394503563642502,-0.009240195155144,37038,-587,-2496,-2926,0.958284258842468 +37673,0.141210377216339,0.402000099420548,-0.010769119486213,37038,240,-2971,-2939,0.951047658920288 +37675,0.136573702096939,0.403324216604233,-0.011433226056397,37038,6,-3412,-2950,0.9456387758255 +37677,0.130273178219795,0.405413389205933,-0.012592512182891,37038,487,-2768,-2951,0.938612043857574 +37679,0.134511947631836,0.39598336815834,-0.00817028619349,37038,-653,-2654,-2912,0.937820911407471 +37681,0.127425774931908,0.403601080179215,-0.00826308876276,37038,532,-3270,-2921,0.940658330917358 +37683,0.118817664682865,0.407362073659897,-0.009828290902078,37038,487,-3918,-2934,0.944692134857178 +37685,0.11612506955862,0.403291970491409,-0.011903014034033,37038,336,-2567,-2946,0.944006145000458 +37687,0.116077348589897,0.40223354101181,-0.013266454450786,37038,-112,-3638,-2978,0.946059048175812 +37689,0.119307145476341,0.403024733066559,-0.012142004445195,37038,-174,-3051,-2948,0.942709028720856 +37691,0.110471077263355,0.41378378868103,-0.010281825438142,37038,570,-4800,-2944,0.947555363178253 +37693,0.100330896675587,0.406508505344391,-0.008550164289773,37038,1017,-2667,-2923,0.948741376399994 +37695,0.091278083622456,0.415126383304596,-0.009559977799654,37038,864,-4800,-2936,0.949159681797028 +37697,0.092413388192654,0.411755919456482,-0.009254226461053,37038,294,-3165,-2928,0.95249480009079 +37699,0.092301122844219,0.419356286525726,-0.008524970151484,37038,173,-4951,-2924,0.952301442623138 +37701,0.091604024171829,0.414962828159332,-0.008820934221148,37038,405,-3286,-2925,0.950062334537506 +37703,0.076056860387325,0.416021913290024,-0.006785566452891,37038,1503,-4578,-2902,0.942039728164673 +37705,0.066967971622944,0.409681081771851,-0.001608435297385,37038,1334,-3219,-2874,0.938251554965973 +37707,0.06015931814909,0.403166919946671,2.39282599068247E-05,37038,1100,-3978,-2821,0.932224988937378 +37725,0.030980935320258,0.403542757034302,-0.002530917525291,37038,1504,-4390,-2873,0.943166553974152 +37727,0.038854062557221,0.388315677642822,-0.00128387263976,37038,359,-3832,-2837,0.947555065155029 +37729,0.041069831699133,0.383943408727646,0.001952128484845,37038,821,-3866,-2841,0.942899644374847 +37731,0.04090391471982,0.373358815908432,0.007113359868526,37038,897,-4063,-2738,0.938513815402985 +37733,0.045748293399811,0.352742671966553,0.006965120788664,37038,558,-2392,-2804,0.931192636489868 +37735,0.051572017371655,0.336260735988617,0.002876159269363,37038,277,-3170,-2788,0.932767033576965 +37737,0.054655387997627,0.32907047867775,-0.001540431403555,37038,542,-3136,-2860,0.932548701763153 +37739,0.060283292084932,0.333849638700485,-0.002947908826172,37038,133,-4780,-2856,0.931957066059112 +37741,0.063036426901817,0.328727811574936,-0.001192315365188,37038,427,-3401,-2857,0.928264856338501 +37743,0.053392451256514,0.33321812748909,-0.002466019708663,37038,1326,-4872,-2851,0.928427338600159 +37745,0.049246836453676,0.322583466768265,-0.002745606470853,37038,1104,-3041,-2867,0.927001059055328 +37747,0.051085580140352,0.32059571146965,-0.000802090449724,37038,529,-4320,-2832,0.923647522926331 +37749,0.059922374784947,0.31576856970787,0.006216690409929,37038,7,-3477,-2804,0.92739474773407 +37751,0.059376861900091,0.315480679273605,0.011544958688319,37038,542,-4476,-2685,0.928585052490234 +37753,0.06253257393837,0.302534520626068,0.012157578021288,37038,358,-2823,-2760,0.936484515666962 +37755,0.0694674924016,0.299056500196457,0.002543358597904,37038,-171,-4094,-2790,0.939545452594757 +37757,0.079045295715332,0.293782263994217,-0.002333736279979,37038,-361,-3357,-2859,0.944819688796997 +37759,0.084524050354958,0.279226690530777,0.000154531080625,37038,-333,-3077,-2820,0.944804668426514 +37761,0.083271883428097,0.269146531820297,-0.001074163243175,37038,324,-2760,-2849,0.945681750774384 +37763,0.086140878498554,0.256745040416718,-0.004194303881377,37038,-208,-2957,-2872,0.941480219364166 +37765,0.091028146445751,0.262107461690903,-0.005304477643222,37038,-257,-3856,-2878,0.938816070556641 +37767,0.095102563500404,0.265132337808609,-0.004181709140539,37038,-483,-4295,-2870,0.931644916534424 +37769,0.096361391246319,0.269555121660233,-0.002355777891353,37038,-111,-3991,-2857,0.928653120994568 +37771,0.101324185729027,0.259610831737518,0.00097328866832,37038,-690,-3375,-2810,0.927757501602173 +37773,0.101723894476891,0.253831565380096,0.004213644657284,37038,-167,-3130,-2811,0.92756325006485 +37775,0.109793111681938,0.240174949169159,0.002757630543783,37038,-1084,-2875,-2790,0.930013477802277 +37777,0.112850680947304,0.237703368067741,-0.001931048347615,37038,-561,-3220,-2852,0.926940262317658 +37779,0.117100082337856,0.227026969194412,-0.002667456399649,37038,-971,-2949,-2855,0.929922342300415 +37781,0.121371157467365,0.223192900419235,-0.002816518768668,37038,-817,-2993,-2857,0.928507268428802 +37783,0.122565880417824,0.219003468751907,-0.002396124182269,37038,-889,-3362,-2852,0.932025730609894 +37785,0.121006049215794,0.215178206562996,-0.002811713609844,37038,-444,-2954,-2857,0.934088408946991 +37787,0.120821282267571,0.21254052221775,-0.001433555386029,37038,-811,-3442,-2842,0.939118802547455 +37789,0.124434627592564,0.198453068733215,0.001935424748808,37038,-913,-2052,-2824,0.93768835067749 +37791,0.121659278869629,0.200998887419701,0.000919720623642,37038,-679,-3693,-2815,0.939991533756256 +37793,0.117735423147678,0.19585682451725,-0.000258337066043,37038,-326,-2723,-2838,0.94145542383194 +37795,0.121205471456051,0.194547683000565,-0.002027818467468,37038,-1165,-3371,-2850,0.93786358833313 +37797,0.129482835531235,0.186548143625259,-0.003124716691673,37038,-1417,-2449,-2857,0.933529675006866 +37799,0.124375246465206,0.188161566853523,-0.004015571437776,37038,-664,-3547,-2873,0.929560661315918 +37801,0.123636439442635,0.179002866148949,-0.00303501682356,37038,-740,-2321,-2857,0.929927229881287 +37803,0.124660044908524,0.179980829358101,-0.000191573984921,37038,-1163,-3436,-2829,0.924011707305908 +37805,0.129356443881989,0.171614646911621,0.000526699412148,37038,-1265,-2332,-2832,0.926906228065491 +37807,0.1266720443964,0.175076559185982,-0.00242855376564,37038,-982,-3589,-2856,0.927597880363464 +37809,0.116577737033367,0.176760122179985,-0.001359723391943,37038,-76,-3185,-2844,0.932340681552887 +37811,0.109054155647755,0.162453144788742,-0.002437558723614,37038,-409,-2172,-2856,0.930778443813324 +37813,0.107661284506321,0.164219111204147,-0.003399814246222,37038,-619,-3065,-2858,0.930744647979736 +37815,0.113085515797138,0.165788993239403,-0.001536726602353,37038,-1447,-3424,-2845,0.93428772687912 +37817,0.116386540234089,0.178617537021637,-0.001511948998086,37038,-1130,-4121,-2845,0.938806474208832 +37819,0.115237325429916,0.172982528805733,-3.76406860596035E-05,37038,-1040,-3067,-2829,0.940680146217346 +37821,0.10698527097702,0.166738301515579,-0.001453128759749,37038,-215,-2643,-2844,0.936721682548523 +37823,0.102786235511303,0.158023491501808,0.000877386017237,37038,-665,-2650,-2818,0.931840121746063 +37825,0.089295782148838,0.16433310508728,-0.000375275238184,37038,371,-3558,-2836,0.931072175502777 +37827,0.085994310677052,0.160228088498116,-0.003276590257883,37038,-509,-3076,-2866,0.931294023990631 +37829,0.086005836725235,0.167540609836578,-0.004698030650616,37038,-586,-3729,-2866,0.923911511898041 +37831,0.081211812794209,0.174622818827629,-0.00202877400443,37038,-361,-4179,-2851,0.921054005622864 +37833,0.080653242766857,0.17597009241581,0.002464044606313,37038,-504,-3485,-2816,0.914953827857971 +37835,0.073131434619427,0.174214065074921,0.005560657475144,37038,-63,-3601,-2762,0.919836938381195 +37837,0.064942307770252,0.162196859717369,0.003009624779224,37038,236,-2392,-2811,0.919052362442017 +37839,0.054030861705542,0.174221530556679,-0.000468135025585,37038,452,-4659,-2832,0.919178783893585 +37841,0.048451565206051,0.17263787984848,-0.00138468737714,37038,262,-3354,-2841,0.919220149517059 +37843,0.041861716657877,0.174185231328011,-0.000938269135077,37038,319,-3977,-2837,0.919198274612427 +37845,0.038623295724392,0.162763446569443,-0.001398528111167,37038,217,-2573,-2841,0.920381963253021 +37847,0.026238536462188,0.160677790641785,-0.003402794944122,37038,989,-3546,-2867,0.923840165138245 +37849,0.021022530272603,0.151395007967949,-0.002122724894434,37038,602,-2620,-2846,0.928276181221008 +37851,0.011259810999036,0.153389126062393,-0.000674530630931,37038,1039,-3767,-2835,0.930596709251404 +37853,0.00903997849673,0.152512714266777,0.001350569073111,37038,557,-3292,-2821,0.937500536441803 +37855,0.002420676639304,0.151545330882072,0.001180779770948,37038,950,-3577,-2813,0.936947464942932 +37857,0.000306277448544,0.147733330726624,0.002620136598125,37038,676,-3066,-2812,0.934478223323822 +37859,-0.001733666285872,0.1417266279459,0.000942147511523,37038,689,-3112,-2815,0.934511125087738 +37861,-0.010161379352212,0.141979455947876,-0.00438446411863,37038,1280,-3324,-2860,0.93559330701828 +37863,-0.013344459235668,0.134630933403969,-0.00421078177169,37038,959,-2954,-2875,0.933618605136871 +37865,-0.019032234326005,0.137906208634377,-0.001282060984522,37038,1218,-3530,-2839,0.932086169719696 +37867,-0.020751198753715,0.128295540809631,0.002096101408824,37038,981,-2734,-2801,0.926270961761475 +37869,-0.024371780455113,0.128882482647896,0.003088733879849,37038,1157,-3253,-2808,0.917929232120514 +37871,-0.024090191349387,0.12164469063282,0.002380408579484,37038,908,-2839,-2797,0.919138252735138 +37873,-0.030435694381595,0.127940177917481,0.000621140759904,37038,1451,-3691,-2824,0.925611853599548 +37875,-0.03010530769825,0.113390907645226,0.000930147769395,37038,1020,-2221,-2814,0.936191976070404 +37877,-0.028395561501384,0.100141987204552,0.001240102457814,37038,861,-1930,-2819,0.939673185348511 +37879,-0.02974352426827,0.099348530173302,0.002506459364668,37038,1145,-3007,-2795,0.946331262588501 +37881,-0.023479249328375,0.10368736833334,-7.82353163231164E-05,37038,479,-3272,-2827,0.943678975105285 +37883,-0.017175892367959,0.112859800457954,-0.003143200417981,37038,412,-3966,-2861,0.941269636154175 +37885,-0.019672585651279,0.109495125710964,-0.001361344009638,37038,1063,-2840,-2836,0.937175393104553 +37887,-0.022514555603266,0.112856082618237,0.003521262202412,37038,1167,-3594,-2782,0.940209031105042 +37889,-0.018940173089504,0.104715809226036,0.006842391099781,37038,630,-2467,-2779,0.944185674190521 +37891,-0.014168201945722,0.107380226254463,0.004669702611864,37038,499,-3503,-2767,0.947889447212219 +37893,-0.007101269904524,0.105492115020752,0.002909018425271,37038,220,-2964,-2805,0.948656618595123 +37895,-0.008469577878714,0.107013173401356,0.001729672425427,37038,844,-3455,-2801,0.93818461894989 +37897,-0.005498551297933,0.098934352397919,0.001531861722469,37038,495,-2464,-2813,0.927918255329132 +37899,-0.003574941540137,0.102761447429657,-0.000196919005248,37038,527,-3586,-2823,0.91963255405426 +37901,0.00534398900345,0.105795860290527,0.000143629251397,37038,-84,-3395,-2822,0.920069634914398 +37903,0.017765864729881,0.107384614646435,0.001770926406607,37038,-566,-3540,-2799,0.920104801654816 +37905,0.024520888924599,0.111715771257877,0.004484498407692,37038,-210,-3612,-2792,0.925055623054504 +37907,0.030928352847695,0.110729284584522,0.003772211493924,37038,-355,-3446,-2775,0.926116943359375 +37909,0.033767353743315,0.124147713184357,-0.000811500765849,37038,-75,-4482,-2827,0.931903302669525 +37911,0.033941574394703,0.124595306813717,0.000642062572297,37038,33,-3798,-2811,0.933152079582214 +37913,0.035742674022913,0.134137541055679,0.003865308128297,37038,-42,-4391,-2794,0.937463700771332 +37915,0.043424397706986,0.132538482546806,0.00653508445248,37038,-672,-3825,-2740,0.945611119270325 +37917,0.046720303595066,0.141333520412445,0.008455156348646,37038,-324,-4489,-2761,0.950929999351501 +37919,0.056793134659529,0.139576181769371,0.008872229605913,37038,-1084,-3983,-2711,0.950295090675354 +37921,0.061158262193203,0.135318875312805,0.007655644323677,37038,-632,-3520,-2765,0.939788341522217 +37923,0.068206004798412,0.129335969686508,0.009532533586025,37038,-1092,-3576,-2701,0.930616915225983 +37925,0.074014708399773,0.135999038815498,0.010130681097508,37038,-951,-4362,-2746,0.923286736011505 +37927,0.080252051353455,0.140669643878937,0.009283063933253,37038,-1268,-4579,-2702,0.92510598897934 +37929,0.0867660343647,0.132243305444717,0.011934631504119,37038,-1223,-3283,-2731,0.924455285072327 +37931,0.089203163981438,0.124342665076256,0.015343235805631,37038,-1164,-3466,-2629,0.925816416740418 +37933,0.094670064747334,0.119360409677029,0.014693643897772,37038,-1302,-3394,-2709,0.926630795001983 +37935,0.100270241498947,0.137206375598908,0.013062604703009,37038,-1605,-5566,-2654,0.92915290594101 +37937,0.104506142437458,0.137913778424263,0.013656462542713,37038,-1398,-4121,-2714,0.929235875606537 +37939,0.105895534157753,0.139082968235016,0.014081214554608,37038,-1445,-4454,-2639,0.932776689529419 +37957,0.121131986379623,0.119637824594975,0.019793590530753,37038,-1475,-4533,-2654,0.947770655155182 +37959,0.118070214986801,0.103069819509983,0.019767589867115,37038,-1588,-2834,-2555,0.94171816110611 +37961,0.111394926905632,0.0972980260849,0.02005772292614,37038,-1033,-3364,-2648,0.935906052589416 +37963,0.109221614897251,0.083227202296257,0.019806632772088,37038,-1565,-2723,-2551,0.930896639823914 +37965,0.102465927600861,0.095133990049362,0.020826974883676,37038,-951,-4630,-2639,0.93321305513382 +37967,0.102289743721485,0.105757087469101,0.021704282611609,37038,-1664,-4897,-2525,0.936424612998962 +37969,0.092532962560654,0.109988138079643,0.016588158905506,37038,-645,-4334,-2664,0.937640368938446 +37971,0.08982515335083,0.099754847586155,0.015834376215935,37038,-1316,-3350,-2591,0.943453729152679 +37973,0.080366276204586,0.092979863286018,0.018577409908176,37038,-536,-3342,-2648,0.942811548709869 +37975,0.0686439499259,0.082598142325878,0.02281491830945,37038,-338,-3093,-2506,0.946654081344604 +37977,0.06410862505436,0.073297195136547,0.025243958458304,37038,-686,-2910,-2598,0.944606900215149 +37979,0.059412524104118,0.068619579076767,0.021994259208441,37038,-732,-3303,-2511,0.948270797729492 +37981,0.057507682591677,0.059063777327538,0.017136419191957,37038,-808,-2712,-2649,0.949492990970612 +37983,0.046258807182312,0.066337816417217,0.014443661086261,37038,-88,-4143,-2596,0.950227081775665 +37985,0.035065293312073,0.053642272949219,0.014632878825069,37038,154,-2433,-2664,0.945140480995178 +37987,0.01934053376317,0.053555075079203,0.013303034007549,37038,646,-3442,-2607,0.936834871768951 +37989,0.010229722596705,0.037877511233091,0.017001058906317,37038,348,-2013,-2645,0.936738848686218 +37991,-0.007806649897248,0.034799244254828,0.020379969850183,37038,1247,-2939,-2520,0.943452477455139 +37993,-0.018112258985639,0.025459630414844,0.020365942269564,37038,840,-2300,-2618,0.947102248668671 +37995,-0.022820729762316,0.026456620544195,0.014777258038521,37038,544,-3098,-2583,0.940518856048584 +37997,-0.027281858026981,0.029912456870079,0.012137560173869,37163,560,-3287,-2672,0.941067934036255 +37999,-0.032707188278437,0.022153284400702,0.013515089638531,37163,771,-2404,-2595,0.936558842658997 +38001,-0.040517140179873,0.015613893046975,0.015543042682111,37163,1003,-2371,-2645,0.937820851802826 +38003,-0.050019446760416,0.003094877582043,0.016884351149201,37163,1361,-1753,-2552,0.938772857189178 +38005,-0.056565221399069,0.005046438425779,0.01677661575377,37163,1163,-2823,-2634,0.942370593547821 +38007,-0.055209912359715,-8.32900041132234E-05,0.015590838156641,37163,689,-2226,-2564,0.945151567459106 +38009,-0.057972270995379,0.00635598320514,0.015947224572301,37163,936,-3158,-2636,0.948702752590179 +38011,-0.061415228992701,-0.001426137983799,0.014967122115195,37163,1159,-2006,-2568,0.946563601493835 +38013,-0.068024091422558,-0.006322342902422,0.010430485010147,37163,1382,-2157,-2671,0.940750896930695 +38015,-0.064951568841934,-0.009187594056129,0.005571044050157,37163,768,-2233,-2677,0.934394359588623 +38017,-0.061299733817577,-0.006357263308018,0.003933376632631,37163,578,-2701,-2715,0.928024351596832 +38019,-0.055438868701458,-0.00785078201443,0.006709395442158,37163,435,-2350,-2662,0.932131290435791 +38021,-0.052493561059237,-0.010438024066389,0.010272574611008,37163,524,-2247,-2669,0.933074593544006 +38023,-0.055553339421749,-0.006427550222725,0.011573641560972,37163,1107,-2758,-2603,0.933100819587708 +38025,-0.050917934626341,-0.007023827172816,0.009338942356408,37163,404,-2431,-2673,0.931720614433289 +38027,-0.043712109327316,0.003350233426318,0.010369569063187,37163,204,-3359,-2615,0.935716331005096 +38029,-0.038063522428274,-0.000970191438682,0.01363383885473,37163,166,-2247,-2642,0.937332212924957 +38031,-0.036111284047365,0.003987871110439,0.014922190457583,37163,470,-2975,-2558,0.941583752632141 +38033,-0.029593892395496,0.001598841859959,0.015466889366508,37163,-2,-2418,-2626,0.947145640850067 +38035,-0.026890736073256,0.019720846787095,0.013326643966138,37163,280,-4167,-2574,0.951624751091003 +38037,-0.012214854359627,0.022066473960877,0.015701275318861,37163,-825,-3052,-2622,0.958299458026886 +38039,-0.004611150361598,0.024165226146579,0.01838299818337,37163,-421,-3096,-2512,0.95542973279953 +38041,0.001205677399412,0.028631394729018,0.018356697633863,37163,-382,-3303,-2600,0.953562557697296 +38043,0.008778841234744,0.030466191470623,0.01431982871145,37163,-644,-3185,-2556,0.944912910461426 +38045,0.012991809286177,0.031873431056738,0.011961678043008,37163,-442,-3138,-2641,0.936840176582336 +38047,0.016535490751267,0.032251484692097,0.013923874124885,37163,-494,-3118,-2558,0.934883773326874 +38049,0.019577991217375,0.047264602035284,0.014647766016424,37163,-463,-4342,-2620,0.935960948467254 +38051,0.035169292241335,0.048290599137545,0.013061700388789,37163,-1676,-3450,-2566,0.9397132396698 +38053,0.049270249903202,0.061080355197191,0.00904703233391,37163,-1700,-4399,-2656,0.944417655467987 +38055,0.061135403811932,0.051809329539538,0.007826064713299,37163,-1855,-2790,-2625,0.943122506141663 +38057,0.058140687644482,0.065970852971077,0.012686803005636,37163,-634,-4588,-2629,0.941166341304779 +38059,0.05995599552989,0.069097436964512,0.017914075404406,37163,-1145,-3972,-2504,0.940749883651733 +38061,0.056100342422724,0.075617760419846,0.017856199294329,37163,-573,-4206,-2590,0.947456240653992 +38063,0.066323347389698,0.071748957037926,0.016108695417643,37163,-1869,-3548,-2522,0.955117642879486 +38065,0.073571637272835,0.070990197360516,0.015229793265462,37163,-1651,-3647,-2605,0.960416793823242 +38067,0.073201157152653,0.086076885461807,0.016449647024274,37163,-1250,-5172,-2515,0.968087494373322 +38069,0.075346566736698,0.084803842008114,0.016445038840175,37163,-1345,-3844,-2593,0.957925498485565 +38071,0.074320919811726,0.075650587677956,0.013937750831246,37163,-1261,-3293,-2542,0.946402132511139 +38073,0.0735003054142,0.070657148957253,0.015067751519382,37163,-1141,-3405,-2600,0.943068981170654 +38075,0.0682602673769,0.074666224420071,0.013574654236436,37163,-896,-4255,-2543,0.942198812961578 +38077,0.070732854306698,0.070587195456028,0.010937990620732,37163,-1371,-3500,-2626,0.945376932621002 +38079,0.071696534752846,0.090608768165112,0.009319121949375,37163,-1433,-5719,-2591,0.942649781703949 +38081,0.076985113322735,0.093609154224396,0.010519038885832,37163,-1698,-4379,-2627,0.941922545433044 +38083,0.075148575007916,0.096607908606529,0.011684530414641,37163,-1329,-4626,-2562,0.943362236022949 +38085,0.073001742362976,0.084472648799419,0.011525535956025,37163,-1146,-3207,-2617,0.942834377288818 +38087,0.069798454642296,0.07193472981453,0.01025627925992,37163,-1180,-3128,-2576,0.939115881919861 +38089,0.062353156507015,0.075588993728161,0.010400339961052,37163,-650,-4239,-2623,0.940580606460571 +38091,0.056484017521143,0.070781707763672,0.010446129366756,37163,-804,-3695,-2572,0.943501114845276 +38093,0.051293727010489,0.077886514365673,0.009271146729589,37163,-682,-4548,-2628,0.947191119194031 +38095,0.047700621187687,0.075500145554543,0.011314168572426,37163,-838,-3975,-2559,0.947550058364868 +38097,0.037607911974192,0.072737887501717,0.016285538673401,37163,-157,-3798,-2578,0.94658088684082 +38099,0.033488105982542,0.059781886637211,0.017499253153801,37163,-593,-2987,-2483,0.942874312400818 +38101,0.026974521577358,0.060017824172974,0.01099777687341,37163,-278,-3854,-2611,0.944213330745697 +38103,0.027716243639588,0.047344461083412,0.009583668783307,37163,-878,-2820,-2574,0.947723805904388 +38105,0.02412947639823,0.040828377008438,0.007231270428747,37163,-464,-3112,-2635,0.944795191287994 +38107,0.02285710349679,0.029274366796017,0.005959313362837,37163,-673,-2625,-2614,0.941412389278412 +38109,0.013651283457875,0.024039441719651,0.006009128410369,37163,72,-2972,-2642,0.93622875213623 +38111,0.002811009529978,0.015153370797634,0.007127678021789,37163,328,-2598,-2598,0.938181757926941 +38113,-0.001028114580549,0.001737961196341,0.009643286466599,37163,-107,-2070,-2615,0.936394810676575 +38115,-0.00371927744709,-0.000115712246043,0.00831913203001,37163,-157,-2859,-2582,0.934971272945404 +38117,-0.009019669145346,-0.008403088897467,0.006692134775221,37163,108,-2289,-2633,0.93507182598114 +38119,-0.017078723758459,-0.007845223881304,0.004165675956756,37163,448,-2902,-2630,0.935714304447174 +38121,-0.020919045433402,-0.018970873206854,0.003523560008034,37163,177,-1928,-2654,0.94157862663269 +38123,-0.029535956680775,-0.016696093603969,0.006333136931062,37163,706,-2869,-2603,0.941622316837311 +38125,-0.032148327678442,-0.034700810909271,0.006844547111541,37163,261,-1198,-2630,0.9398113489151 +38127,-0.039441149681807,-0.04060784354806,0.002039002254605,37163,778,-1882,-2651,0.940115213394165 +38129,-0.039404410868883,-0.040306560695171,0.002719375072047,37163,190,-2408,-2657,0.945134162902832 +38131,-0.032744869589806,-0.045215141028166,0.005982117261738,37163,-322,-1855,-2604,0.945075154304504 +38133,-0.028438488021493,-0.049560628831387,0.010559633374214,37163,-262,-1918,-2602,0.94692450761795 +38135,-0.034859817475081,-0.052869368344545,0.01164625864476,37163,657,-1820,-2535,0.945773124694824 +38137,-0.036547791212797,-0.04153997451067,0.007416516542435,37163,294,-3129,-2621,0.950181126594543 +38139,-0.035135891288519,-0.037226147949696,0.004175952635705,37163,115,-2600,-2621,0.952211141586304 +38141,-0.043423376977444,-0.026449495926499,0.002550212899223,37163,877,-3287,-2653,0.948996365070343 +38143,-0.044515874236822,-0.031199239194393,0.002131151268259,37163,458,-2029,-2644,0.947167932987213 +38145,-0.04550701379776,-0.032736629247665,0.001010063569993,37163,400,-2297,-2663,0.947534263134003 +38147,-0.038265343755484,-0.034826893359423,0.001351489569061,37163,-218,-2144,-2653,0.953234314918518 +38149,-0.034191764891148,-0.024146428331733,-1.61421667144168E-05,37163,-110,-3277,-2669,0.958071947097778 +38151,-0.030937612056732,-0.021284334361553,0.000554227619432,37163,-27,-2694,-2662,0.96297562122345 +38153,-0.026678178459406,-0.030329637229443,0.001916073146276,37163,-218,-1761,-2655,0.957953155040741 +38155,-0.024470489472151,-0.028120007365942,0.002748178783804,37163,-50,-2517,-2635,0.953132748603821 +38157,-0.01613631285727,-0.029098235070706,0.002457706257701,37163,-652,-2338,-2650,0.948003053665161 +38159,-0.016164975240827,-0.016941564157605,0.003079074434936,37163,-22,-3396,-2630,0.949842512607574 +38161,-0.015163366682828,-0.018729770556092,0.00656663114205,37163,-136,-2416,-2621,0.945747256278992 +38163,-0.014367972500622,-0.008796046487987,0.008163734339178,37163,-111,-3373,-2569,0.946513295173645 +38165,-0.005439612083137,-0.009163391776383,0.00982791185379,37163,-840,-2648,-2597,0.947330355644226 +38167,0.003566508879885,0.002702532568946,0.005109227728099,37163,-991,-3692,-2604,0.946987807750702 +38169,0.0173195078969,0.004200987517834,0.00205819029361,37163,-1518,-2971,-2649,0.942825734615326 +38185,0.052346266806126,0.070003785192967,0.007747280877084,37396,-31364,-498,-2605,0.954109132289886 +38187,0.059552181512117,0.061129707843065,0.006748637184501,37396,-32181,596,-2579,0.952185571193695 +38189,0.054180014878512,0.080407999455929,0.00525532476604,37396,-31247,-1588,-2620,0.956459701061249 +38191,0.044399738311768,0.099720165133476,0.004412790294737,37396,-31051,-2055,-2606,0.959910750389099 +38193,0.019265536218882,0.115551918745041,-0.003168150316924,37396,-29654,-1852,-2677,0.956160724163055 +38195,-0.020952418446541,0.136218801140785,-0.011528491973877,37396,-28107,-2755,-2795,0.955491423606873 +38197,-0.074420928955078,0.152099370956421,-0.017926938831806,37396,-26571,-2404,-2780,0.949352085590362 +38199,-0.134295150637627,0.166867196559906,-0.020095337182283,37396,-25125,-2853,-2898,0.943916440010071 +38201,-0.208999842405319,0.181745871901512,-0.02608029730618,37396,-23358,-2794,-2839,0.937834799289703 +38203,-0.300659954547882,0.201424404978752,-0.033578846603632,37396,-20350,-3809,-3061,0.933179497718811 +38205,-0.401281654834747,0.217871055006981,-0.035728320479393,37396,-18905,-3477,-2911,0.932597756385803 +38207,-0.515494227409363,0.227922558784485,-0.038733080029488,37396,-15342,-3614,-3126,0.928054988384247 +38209,-0.638812303543091,0.242921575903892,-0.039411384612322,37396,-13930,-3799,-2943,0.928242564201355 +38211,-0.769408762454987,0.260210812091827,-0.039500828832388,37396,-10042,-4737,-3138,0.929589986801147 +38213,-0.898220419883728,0.285394638776779,-0.038827247917652,37396,-9755,-5222,-2945,0.93315577507019 +38215,-1.02376222610474,0.296077787876129,-0.037835150957108,37396,-6160,-4936,-3119,0.932591795921326 +38217,-1.16653966903687,0.309342265129089,-0.041075259447098,37396,-4725,-4812,-2966,0.92820942401886 +38219,-1.31254696846008,0.316848397254944,-0.040558453649283,37396,32767,-27506,-3149,0.929731369018555 +38221,-1.4638135433197,0.322862476110458,-0.039416093379259,37396,6461,-8373,-2961,0.931258976459503 +38223,-1.61382722854614,0.325885146856308,-0.037367783486843,37396,11816,-8881,-3108,0.932861030101776 +38225,-1.76302683353424,0.330489009618759,-0.037439197301865,37396,11122,-8534,-2952,0.933852732181549 +38227,-1.91134226322174,0.337039053440094,-0.041577752679586,37396,17115,-9462,-3150,0.939195036888123 +38229,-2.03516387939453,0.330989211797714,-0.046995770186186,37396,13868,-7935,-3023,0.94656252861023 +38231,-2.14586877822876,0.317750424146652,-0.051241930574179,37396,18942,-7883,-3260,0.953582465648651 +38233,-2.25120282173157,0.312892764806747,-0.057156477123499,37396,16416,-7910,-3100,0.95551210641861 +38235,-2.35123229026794,0.309680998325348,-0.064537793397904,37396,22330,-8613,-3411,0.956623911857605 +38237,-2.43329954147339,0.297116249799728,-0.071140371263027,37396,18236,-7277,-3204,0.960812032222748 +38239,-2.49872088432312,0.270713329315186,-0.075538419187069,37396,23152,-6462,-3545,0.961830019950867 +38241,-2.55443596839905,0.249438628554344,-0.080613479018211,37396,19035,-6099,-3280,0.957113087177277 +38243,-2.60017418861389,0.231738269329071,-0.078146189451218,37396,24356,-6580,-3584,0.958010792732239 +38245,-2.63335943222046,0.20979668200016,-0.075470231473446,37396,19555,-5596,-3255,0.958004415035248 +38247,-2.6467764377594,0.189199805259705,-0.076602585613728,37396,23803,-5788,-3580,0.963734328746796 +38249,-2.65216684341431,0.159862816333771,-0.075968019664288,37396,18864,-4444,-3269,0.963077962398529 +38251,-2.65758442878723,0.138808205723762,-0.073815144598484,37396,24426,-5024,-3568,0.963426947593689 +38253,-2.64897966384888,0.11398471146822,-0.070627950131893,37396,18856,-4182,-3243,0.964517056941986 +38255,-2.62093043327332,0.094982624053955,-0.072187349200249,37396,22440,-4527,-3572,0.962629973888397 +38257,-2.57606196403503,0.068727858364582,-0.072263777256012,37396,32767,-3484,-3264,0.965145528316498 +38259,-2.5276825428009,0.050126042217016,-0.068367399275303,37396,26460,-3870,-3555,0.963299691677094 +38261,-2.47130823135376,0.027845857664943,-0.062697425484657,37396,20929,-3215,-3209,0.970240414142608 +38263,-2.40023016929626,-0.000559951236937,-0.062474861741066,37396,23794,-2368,-3521,0.975575745105743 +38265,-2.32373237609863,-0.021199233829975,-0.064231917262077,37396,18369,-2639,-3230,0.985923409461975 +38267,-2.23411750793457,-0.040521040558815,-0.063753865659237,37396,20729,-2370,-3570,0.994134962558746 +38269,-2.13136315345764,-0.044100232422352,-0.059314090758562,37396,14656,-3524,-3208,1.00594329833984 +38271,-2.01492381095886,-0.065991081297398,-0.05420533567667,37396,16125,-1755,-3486,1.00696551799774 +38273,-1.89470207691193,-0.077071771025658,-0.053526390343905,37396,10843,-2493,-3178,1.01248455047607 +38275,-1.77109098434448,-0.093462996184826,-0.048739694058895,37396,12431,-1686,-3452,1.02310681343079 +38277,-1.64264476299286,-0.093815729022026,-0.044413257390261,37396,7364,-2990,-3126,1.02856016159058 +38279,-1.49589347839355,-0.098174899816513,-0.039694018661976,37396,6961,-2440,-3362,1.03265428543091 +38281,-1.35227298736572,-0.093735560774803,-0.034647963941097,37396,2714,-3300,-3067,1.02579009532928 +38283,-1.19938969612122,-0.101855076849461,-0.03054903075099,37396,2227,-2072,-3268,1.02068603038788 +38285,-1.04904961585999,-0.098209731280804,-0.027564140036702,37396,-1649,-3143,-3026,1.01479768753052 +38287,-0.891942083835602,-0.108098596334457,-0.022698471322656,37396,-2673,-1801,-3189,1.00726473331451 +38289,-0.738210797309876,-0.101985171437263,-0.021311422809959,37396,-6024,-3225,-2990,1.00342488288879 +38291,-0.586883068084717,-0.102540455758572,-0.018224472180009,37396,-6955,-2522,-3140,1.00449895858765 +38293,-0.447642385959625,-0.099525451660156,-0.013736972585321,37396,26733,-3000,-2943,1.00521552562714 +38295,-0.30752620100975,-0.09929858148098,-0.005648289807141,37396,-4534,-2586,-2995,1.00532126426697 +38297,-0.175192728638649,-0.097056210041046,0.000262854620814,37396,-6259,-2942,-2850,0.999074697494507 +38299,-0.050432227551937,-0.081480599939823,0.003933006431907,37396,-7547,-3934,-2872,1.00311970710754 +38301,0.078458964824677,-0.077746659517288,0.006826376542449,37396,-9649,-3294,-2806,1.00413262844086 +38303,0.201532661914825,-0.073370814323425,0.007812237832695,37396,-11559,-3230,-2821,1.01222622394562 +38305,0.321874231100082,-0.071390219032765,0.00884257350117,37396,-12640,-3231,-2793,1.01372539997101 +38307,0.438631176948547,-0.060380946844816,0.010526000522077,37396,-15111,-3883,-2778,1.01466131210327 +38309,0.549043297767639,-0.05682734400034,0.00999872200191,37396,-15408,-3528,-2785,1.0131915807724 +38311,0.644674122333527,-0.04789362847805,0.007702975533903,37396,-17214,-3908,-2801,1.01419079303741 +38313,0.739826500415802,-0.05722676217556,0.004597595892847,37396,-17370,-2579,-2821,1.01431977748871 +38315,0.819760859012604,-0.045375667512417,0.000611850060523,37396,-19298,-4145,-2882,1.00820028781891 +38317,0.898748695850372,-0.052763219922781,0.0009272856405,37396,-18893,-2764,-2848,1.00541090965271 +38337,1.07161629199982,0.014116054400802,-0.004170705098659,37396,-10128,-4454,-2883,0.973562180995941 +38339,1.0434467792511,0.010656657628715,-0.001238406053744,37396,-12167,-3946,-2864,0.977562963962555 +38341,1.00891840457916,0.020963076502085,-0.000790285528637,37396,-9379,-5083,-2859,0.979965150356293 +38343,0.971010982990265,0.021668365225196,-0.001943666487932,37396,-10731,-4438,-2866,0.979831218719482 +38345,0.931209564208984,0.024699913337827,-0.004768706858158,37396,-8317,-4630,-2886,0.976099908351898 +38347,0.886552631855011,0.037977200001478,-0.005721057299525,37396,-9288,-5633,-2902,0.97332751750946 +38349,0.847924530506134,0.039091695100069,-0.004021102096885,37396,-7601,-4724,-2881,0.972910284996033 +38351,0.800446629524231,0.033385206013918,-0.004069150891155,37396,-8057,-4222,-2885,0.969173669815064 +38353,0.743702948093414,0.023164922371507,-0.004439417738467,37396,-5164,-3705,-2884,0.96725195646286 +38355,0.680493116378784,0.035083871334791,-0.000836837571114,37396,-5311,-5528,-2847,0.96122944355011 +38357,0.625543594360352,0.039012428373098,0.002570226090029,37396,-3901,-4968,-2835,0.961513102054596 +38359,0.573754727840424,0.030267713591457,0.001354288775474,37396,-4671,-3985,-2823,0.958111226558685 +38361,0.509804606437683,0.021800927817822,-0.003225181251764,37396,-1851,-3852,-2874,0.953752756118774 +38363,0.441268891096115,0.010822428390384,-0.003475555451587,37396,-1546,-3519,-2889,0.951665461063385 +38365,0.374201208353043,0.010990468785167,-0.001343396375887,37396,121,-4325,-2861,0.955044269561768 +38367,0.318289399147034,-0.002718770178035,-0.006062106695026,37396,-621,-3109,-2926,0.958682298660278 +38369,0.255866408348083,-0.007808161433786,-0.012790343724191,37396,32767,-3682,-2941,0.965976536273956 +38371,0.197069153189659,-0.024979932233691,-0.010874888859689,37396,7438,-2502,-2995,0.966256737709045 +38373,0.133592948317528,-0.035700384527445,-0.007194998208433,37396,9118,-2872,-2904,0.964136064052582 +38375,0.074357368052006,-0.041151188313961,-0.008784810081124,37396,9446,-3066,-2980,0.962410390377045 +38377,0.021580683067441,-0.047550342977047,-0.013504050672054,37396,9985,-2996,-2949,0.959149539470673 +38379,-0.024721147492528,-0.049385141581297,-0.019153213128448,37396,10179,-3176,-3109,0.964151918888092 +38381,-0.056943818926811,-0.047304272651672,-0.020271729677916,37396,9711,-3589,-3000,0.969684183597565 +38383,-0.086562789976597,-0.044777628034353,-0.019687222316861,37396,10089,-3545,-3116,0.975912094116211 +38385,-0.105982698500156,-0.055414721369743,-0.021776668727398,37396,9600,-2545,-3014,0.979438066482544 +38387,-0.118388146162033,-0.05546410381794,-0.026377411559224,37396,9477,-3171,-3204,0.979329764842987 +38389,-0.123562835156918,-0.05822329595685,-0.025006968528032,37396,8949,-3047,-3041,0.982672810554504 +38391,-0.121081411838532,-0.059951771050692,-0.02284306101501,37396,8568,-2955,-3170,0.978383123874664 +38393,-0.118328720331192,-0.053031675517559,-0.026112152263522,37396,8424,-3792,-3053,0.980620861053467 +38395,-0.107015214860439,-0.060128562152386,-0.029206497594714,37396,7822,-2558,-3250,0.974306583404541 +38397,-0.094376228749752,-0.069026090204716,-0.032725401222706,37396,7483,-2408,-3104,0.966365218162537 +38399,-0.07687821239233,-0.081905335187912,-0.031823094934225,37396,6997,-1774,-3297,0.968639850616455 +38401,-0.06031234189868,-0.071427829563618,-0.030051989480853,37396,6812,-3732,-3092,0.971556603908539 +38403,-0.027903797104955,-0.074642963707447,-0.027824869379401,37396,5228,-2548,-3252,0.974124252796173 +38405,-0.000104278471554,-0.063275739550591,-0.026567287743092,37396,5220,-3885,-3074,0.97502589225769 +38407,0.028434287756682,-0.056551452726126,-0.023906119167805,37396,4657,-3521,-3202,0.980661034584045 +38409,0.066071555018425,-0.04867509379983,-0.023470981046558,37396,3617,-3823,-3057,0.977246880531311 +38411,0.116080172359943,-0.035356033593416,-0.023089164867997,37396,1732,-4317,-3187,0.9789679646492 +38413,0.165667414665222,-0.026870535686612,-0.022945793345571,37396,1344,-4166,-3058,0.979728937149048 +38415,0.212559103965759,-0.020301293581724,-0.024135332554579,37396,374,-4071,-3196,0.985162496566772 +38417,0.2604019343853,-0.026327902451158,-0.025492837652564,37396,75,-3129,-3079,0.987539887428284 +38419,0.307649940252304,-0.016173126176,-0.023550668731332,37396,-1252,-4388,-3191,0.988229095935822 +38421,0.35649362206459,-0.013888721354306,-0.019667502492666,37396,-1454,-3899,-3043,0.984414637088776 +38423,0.400474429130554,-0.000115520204417,-0.019837910309434,37396,-2630,-4908,-3144,0.975269675254822 +38425,0.450081050395966,0.003501951228827,-0.016033083200455,37396,-2975,-4247,-3021,0.974441647529602 +38427,0.493097096681595,0.014600086025894,-0.017127746716142,37396,-4213,-4963,-3108,0.980503857135773 +38429,0.53923749923706,0.010206990875304,-0.019661195576191,37396,-4175,-3779,-3048,0.985961616039276 +38431,0.582015872001648,0.012727541849017,-0.019685316830874,37396,-5834,-4335,-3142,0.984419703483582 +38433,0.626160204410553,0.020122550427914,-0.016278201714158,37396,-5491,-4777,-3028,0.985785841941834 +38435,0.665840744972229,0.026015542447567,-0.016142079606652,37396,-7199,-4799,-3097,0.981028020381928 +38437,0.704829216003418,0.03309091180563,-0.014293476007879,37396,-6502,-4956,-3016,0.976575255393982 +38439,0.738600730895996,0.027692580595613,-0.01226706057787,37396,-8213,-4025,-3053,0.969039022922516 +38441,0.76337468624115,0.034420352429152,-0.011987837962806,37396,-6609,-4966,-3002,0.970842242240906 +38443,0.793497085571289,0.033318821340799,-0.011383312754333,37396,-9136,-4441,-3042,0.975685298442841 +38445,0.817854821681976,0.045310903340578,-0.012758985161781,37396,-7673,-5517,-3008,0.980900764465332 +38447,0.841668367385864,0.047326076775789,-0.011251768097282,37396,-9792,-4916,-3036,0.981979727745056 +38449,0.857927858829498,0.048142913728953,-0.013894714415073,37396,-8005,-4782,-3017,0.975107848644257 +38451,0.875165522098541,0.028507120907307,-0.017001133412123,37396,-10222,-3089,-3114,0.9659423828125 +38453,0.882173240184784,0.018494607880712,-0.017190249636769,37396,-8048,-3599,-3042,0.955437362194061 +38455,0.881726503372192,0.01504557300359,-0.012343515641987,37396,-9418,-4042,-3066,0.951638042926788 +38457,0.882604539394379,0.009329022839665,-0.008194365538657,37396,-7978,-3786,-2982,0.946480691432953 +38459,0.882246434688568,0.015721503645182,-0.006916169077158,37396,-9785,-4767,-3003,0.948219239711762 +38461,0.882087111473084,0.017116317525506,-0.008315923623741,37396,-8260,-4418,-2984,0.948686599731445 +38463,0.874373912811279,0.022312758490443,-0.009794519282877,37396,-9488,-4801,-3036,0.953528583049774 +38465,0.857505857944489,0.014397175051272,-0.008203568868339,37396,-7072,-3727,-2984,0.954481542110443 +38467,0.832110345363617,0.013127054087818,-0.00972612015903,37396,-7883,-4188,-3039,0.955738961696625 +38469,0.812426865100861,0.003390479367226,-0.013157862238586,37396,-6568,-3446,-3019,0.952723681926727 +38487,0.534294366836548,-0.068551272153854,-0.018045568838716,37396,-3873,-2224,-3171,0.941972255706787 +38489,0.504723727703095,-0.060916069895029,-0.02000061608851,37396,-2827,-3700,-3082,0.937996804714203 +38491,0.472397744655609,-0.064180158078671,-0.021820012480021,37396,-3187,-2729,-3217,0.941759347915649 +38493,0.436246782541275,-0.084031358361244,-0.026113161817193,37396,-1564,-1373,-3128,0.942455053329468 +38495,0.390364915132523,-0.095896080136299,-0.027807423844934,37396,-1051,-1560,-3298,0.94860315322876 +38497,0.352784723043442,-0.11435117572546,-0.025151802226901,37396,-417,-997,-3126,0.949698567390442 +38499,0.321627885103226,-0.11610458791256,-0.022668082267046,37396,-1128,-1913,-3245,0.947747528553009 +38501,0.29169300198555,-0.128858625888824,-0.018216110765934,37396,-211,-1146,-3083,0.94781893491745 +38503,0.251737534999847,-0.12211187183857,-0.012637290172279,37396,524,-2371,-3131,0.948241531848908 +38505,0.220859125256538,-0.1268420368433,-0.007822862826288,37396,779,-1695,-3014,0.946136176586151 +38507,0.189934700727463,-0.129552200436592,-0.008102735504508,37396,806,-1520,-3081,0.941907405853272 +38509,0.157963886857033,-0.130753859877586,-0.006650202907622,37396,1696,-1835,-3008,0.944900691509247 +38511,0.124338455498219,-0.128741696476936,-0.00779330637306,37396,2014,-1816,-3078,0.947056829929352 +38513,0.103872835636139,-0.128301069140434,-0.009900107048452,37396,1613,-1931,-3032,0.951622366905212 +38515,0.089011706411839,-0.12383233755827,-0.012931946665049,37396,1225,-2007,-3140,0.95451557636261 +38517,0.074308313429356,-0.116311132907867,-0.01342726033181,37396,1608,-2554,-3059,0.955552816390991 +38519,0.057928420603275,-0.118559554219246,-0.0102280350402,37396,1839,-1545,-3109,0.95490825176239 +38521,0.042229522019625,-0.117403425276279,-0.008749470114708,37396,2138,-2026,-3029,0.95168399810791 +38523,0.029645871371031,-0.126865014433861,-0.011982096359134,37396,2025,-836,-3134,0.95405113697052 +38525,0.021821642294526,-0.125311776995659,-0.015896974131465,37396,1877,-1881,-3081,0.95150876045227 +38527,0.016881078481674,-0.120278537273407,-0.01344836410135,37396,1687,-1935,-3152,0.955800950527191 +38529,0.016330389305949,-0.115335732698441,-0.010069911368191,37396,1449,-2211,-3043,0.953794658184052 +38531,0.015685891732574,-0.102654479444027,-0.010507317259908,37396,1418,-2724,-3117,0.954246580600738 +38533,0.010062176734209,-0.101796820759773,-0.014569255523384,37396,1918,-2065,-3077,0.954053401947022 +38535,0.008051617071033,-0.08721049875021,-0.016536012291908,37396,1660,-3064,-3188,0.952407479286194 +38537,0.014724501408637,-0.083060279488564,-0.014040551148355,37396,989,-2529,-3076,0.954224109649658 +38539,0.024954965338111,-0.071902826428413,-0.011619124561548,37396,520,-3032,-3130,0.956328988075256 +38541,0.039068415760994,-0.060389790683985,-0.008996959775686,37396,118,-3348,-3043,0.963773012161255 +38543,0.051660973578692,-0.053704507648945,-0.011263400316238,37396,-70,-2979,-3124,0.967661023139954 +38545,0.066623508930206,-0.047898534685373,-0.011406703852117,37396,-338,-3094,-3062,0.971918225288391 +38547,0.081560418009758,-0.043136104941368,-0.009341951459646,37396,-729,-2986,-3102,0.971440076828003 +38549,0.096003495156765,-0.032806538045406,-0.008158850483596,37396,-736,-3613,-3041,0.969226598739624 +38551,0.105300769209862,-0.025092327967286,-0.007309237029403,37396,-738,-3464,-3076,0.969792306423187 +38553,0.116988390684128,-0.011683931574226,-0.007336215581745,37396,-867,-4123,-3037,0.971691489219666 +38555,0.139557152986527,-0.001763131120242,-0.006720670498908,37396,-2284,-3992,-3066,0.966859877109528 +38557,0.155361697077751,0.02357611246407,-0.005723827052861,37396,-1756,-5480,-3027,0.960986614227295 +38559,0.169702365994453,0.029737051576376,-0.004456087946892,37396,-2235,-4246,-3035,0.959118545055389 +38561,0.174255073070526,0.041814848780632,-0.005389335099608,37396,-1279,-4804,-3025,0.958969235420227 +38563,0.186637029051781,0.0381337441504,-0.003324012970552,37396,-2430,-3692,-3021,0.960880756378174 +38565,0.196675643324852,0.039379362016916,-0.000212505445234,37396,-2060,-4009,-2989,0.956849157810211 +38567,0.202784985303879,0.041467264294624,0.000325832836097,37396,-2322,-4177,-2977,0.957871794700623 +38569,0.211492151021957,0.042736269533634,-0.005112059414387,37396,-2253,-4077,-3022,0.953416168689728 +38571,0.215573281049728,0.049014903604984,-0.011277320794761,37396,-2465,-4621,-3113,0.955739319324493 +38573,0.220894739031792,0.050710294395685,-0.014808839187026,37396,-2228,-4243,-3091,0.95996767282486 +38575,0.2294532507658,0.065040558576584,-0.013207939453423,37396,-3087,-5478,-3135,0.960916459560394 +38577,0.233107402920723,0.065429896116257,-0.006338837556541,37396,-2372,-4389,-3034,0.962049067020416 +38579,0.226724252104759,0.070479467511177,-0.005021309945732,37396,-2056,-4924,-3040,0.962051391601562 +38581,0.225395545363426,0.062893725931645,-0.007392355240881,37396,-1991,-3811,-3042,0.958483517169952 +38583,0.224240779876709,0.06633547693491,-0.014575734734535,37396,-2484,-4779,-3154,0.952568173408508 +38585,0.227890864014626,0.067125856876373,-0.018919259309769,37396,-2472,-4501,-3123,0.949900090694428 +38587,0.230616822838783,0.068070225417614,-0.017969179898501,37396,-2958,-4666,-3196,0.943706393241882 +38589,0.224066168069839,0.073169082403183,-0.01506473403424,37396,-1778,-4929,-3099,0.947295725345612 +38591,0.220408365130424,0.067028366029263,-0.013778659515083,37396,-2419,-4174,-3150,0.952835023403168 +38593,0.21924053132534,0.069220297038555,-0.015277687460184,37396,-2181,-4696,-3102,0.955939769744873 +38595,0.224409207701683,0.059561304748058,-0.015331786125898,37396,-3198,-3829,-3171,0.961135685443878 +38597,0.219898357987404,0.064967267215252,-0.01491681765765,37789,-2039,-4894,-3102,0.959604859352112 +38599,0.215759754180908,0.054489731788635,-0.013838822022081,37789,-2470,-3704,-3156,0.956566214561462 +38601,0.202073931694031,0.066260881721974,-0.014190997928381,37789,-1210,-5393,-3098,0.956117689609528 +38603,0.196366399526596,0.066950939595699,-0.012720478698611,37789,-2119,-4736,-3144,0.957324266433716 +38605,0.19075134396553,0.060178592801094,-0.014088814146817,37789,-1701,-4007,-3099,0.963403105735779 +38607,0.192208722233772,0.044812552630901,-0.011835944838822,37789,-2632,-3264,-3138,0.969956815242767 +38609,0.186818778514862,0.029880881309509,-0.010368635877967,37789,-1733,-3011,-3075,0.970623791217804 +38611,0.183335781097412,0.027215579524636,-0.0138666825369,37789,-2222,-3906,-3166,0.968639731407166 +38613,0.184904277324676,0.020709043368697,-0.014467699453235,37789,-2276,-3497,-3106,0.961147427558899 +38615,0.179498642683029,0.021930148825049,-0.015454608947039,37789,-2112,-4107,-3187,0.953104317188263 +38617,0.169788673520088,0.022372612729669,-0.012956262566149,37789,-1325,-4029,-3098,0.948738873004913 +38619,0.154588058590889,0.032261971384287,-0.013065076433122,37789,-1065,-4906,-3160,0.947840631008148 +38621,0.155835554003716,0.017491314560175,-0.01651574485004,37789,-1972,-2885,-3124,0.950248837471008 +38623,0.15890945494175,0.011151820421219,-0.018944857642055,37789,-2493,-3427,-3234,0.948528528213501 +38625,0.165374800562859,0.00301866652444,-0.018242552876473,37789,-2545,-3161,-3139,0.954166650772095 +38627,0.160551443696022,0.001832432928495,-0.015173653140664,37789,-2014,-3642,-3193,0.960276782512665 +38629,0.15043143928051,-0.006815505679697,-0.012420822866261,37789,-1205,-2985,-3101,0.96625941991806 +38631,0.14693757891655,-0.017518138512969,-0.011996457353234,37789,-1946,-2635,-3159,0.963295936584473 +38633,0.139046147465706,-0.013918046839535,-0.011096749454737,38325,-1257,-3753,-3094,0.96041876077652 +38635,0.13013231754303,-0.023285387083888,-0.008146326988935,38325,-1342,-2628,-3116,0.963890969753265 +38637,0.12372662872076,-0.031219970434904,-0.007898634299636,38325,-1194,-2668,-3073,0.963865756988525 +38639,0.124302819371223,-0.041846536099911,-0.008429349400103,38325,-1976,-2224,-3122,0.963259279727936 +38641,0.118194781243801,-0.034091375768185,-0.005558835808188,38325,-1184,-3733,-3058,0.961586058139801 +38643,0.120375461876392,-0.038698244839907,-0.000709804531652,38325,-2073,-2686,-3032,0.958012878894806 +38645,0.116800375282764,-0.036389864981175,0.000668674882036,38325,-1391,-3292,-3016,0.955908596515656 +38647,0.112478226423264,-0.03388113155961,0.002872706390917,38325,-1521,-3256,-2989,0.954464793205261 +38649,0.11414097994566,-0.04102498665452,0.004372730851173,38325,-1771,-2532,-2989,0.9489905834198 +38651,0.112432986497879,-0.043951511383057,0.005946514196694,38325,-1748,-2687,-2952,0.954891979694366 +38653,0.10946124792099,-0.05079236254096,0.006657808087766,38325,-1414,-2393,-2973,0.961055338382721 +38655,0.103946231305599,-0.052321959286928,0.006913753692061,38325,-1367,-2624,-2940,0.96963357925415 +38657,0.100104801356792,-0.056297890841961,0.008532058447599,38325,-1255,-2494,-2959,0.974249064922333 +38659,0.099282898008823,-0.048767033964396,0.008048169314861,38325,-1660,-3304,-2925,0.973587989807129 +38661,0.105532884597778,-0.056334473192692,0.005601511802524,38325,-2090,-2212,-2977,0.974866032600403 +38663,0.106593385338783,-0.055276963859797,0.004962288308889,38325,-1969,-2712,-2961,0.972729504108429 +38665,0.111130215227604,-0.063290446996689,0.007480177562684,38325,-2090,-2053,-2964,0.978653907775879 +38667,0.117558985948563,-0.067562095820904,0.009290256537497,38325,-2584,-2101,-2910,0.976897120475769 +38669,0.118180155754089,-0.065006777644157,0.01335768122226,38325,-1958,-2753,-2922,0.976012706756592 +38671,0.114207774400711,-0.067586615681648,0.013859358616173,38665,-1821,-2188,-2854,0.973191261291504 +38673,0.111177548766136,-0.06208960711956,0.013601714745164,38665,-1642,-2972,-2918,0.974365472793579 +38675,0.113142095506191,-0.061672307550907,0.016055662184954,38665,-2265,-2476,-2825,0.977919161319733 +38677,0.121871009469032,-0.047015234827995,0.01639355160296,38665,-2681,-3816,-2896,0.981053173542023 +38679,0.132431924343109,-0.041374184191227,0.014222035184503,38665,-3251,-3160,-2842,0.982855200767517 +38681,0.134873509407043,-0.042782317847014,0.013752839528024,38665,-2472,-2707,-2912,0.98394912481308 +38683,0.139678135514259,-0.047641422599554,0.017847189679742,38665,-3008,-2287,-2797,0.98890870809555 +38685,0.14673812687397,-0.044487651437521,0.016538787633181,38665,-3030,-2987,-2889,0.986292362213135 +38687,0.15140688419342,-0.038038935512304,0.011643626727164,38665,-3232,-3231,-2867,0.98675125837326 +38689,0.14749151468277,-0.03610048443079,0.009293651208282,38665,-2315,-3002,-2937,0.985352516174316 +38691,0.142502203583717,-0.036727610975504,0.007540937047452,38665,-2463,-2726,-2914,0.986431956291199 +38693,0.145702481269836,-0.039233192801476,0.008757283911109,38665,-2858,-2621,-2939,0.984607636928558 +38695,0.142635002732277,-0.021521737799049,0.010672798380256,38665,-2665,-4269,-2874,0.978955805301666 +38697,0.14252071082592,-0.019869815558195,0.012873052619398,38665,-2634,-3185,-2909,0.972066640853882 +38699,0.138644695281982,-0.01631361618638,0.012349916622043,38665,-2599,-3332,-2852,0.962769865989685 +38701,0.140943259000778,-0.021695528179407,0.016652980819345,38665,-2842,-2646,-2881,0.963578343391418 +38719,0.141964510083199,0.005235438700765,0.011942972429097,38665,-3089,-3541,-2844,0.977985560894012 +38721,0.132022634148598,0.006467538885772,0.018469689413905,38665,-2152,-3488,-2857,0.97526627779007 +38723,0.127195179462433,0.010807806625962,0.018749637529254,38665,-2720,-3791,-2761,0.980114698410034 +38725,0.128133997321129,0.010210101492703,0.0167480930686,38665,-2932,-3415,-2866,0.983390092849731 +38727,0.122717648744583,0.008821125142276,0.014502090401948,38665,-2655,-3350,-2809,0.978629469871521 +38729,0.112074628472328,0.001562777790241,0.013825468719006,38665,-1925,-2816,-2883,0.976517856121063 +38731,0.102456077933311,0.008392252959311,0.016097165644169,38665,-2075,-3928,-2787,0.973944365978241 +38733,0.102193370461464,0.007605385500938,0.020325981080532,38665,-2572,-3367,-2836,0.976400911808014 +38735,0.100497223436832,0.011534295976162,0.020127343013883,38665,-2661,-3776,-2736,0.974587202072144 +38737,0.095762044191361,0.013104440644384,0.017994657158852,38665,-2204,-3618,-2848,0.973404049873352 +38739,0.092148877680302,0.009411948733032,0.015953401103616,38665,-2429,-3203,-2782,0.971848368644714 +38741,0.085516504943371,0.010659901425243,0.017396450042725,38665,-1962,-3563,-2849,0.974466979503632 +38743,0.080533884465695,0.000576880411245,0.019769942387939,38665,-2177,-2597,-2735,0.974160313606262 +38745,0.075451001524925,0.005468559917063,0.020207056775689,38665,-1964,-3748,-2175,0.968523859977722 +38747,0.073272787034512,0.002538320142776,0.020643033087254,38951,-2295,-3139,-2047,0.965603590011597 +38749,0.064067788422108,0.011944990605116,0.020234655588865,38951,-1538,-4164,-2127,0.965489208698273 +38751,0.066211573779583,0.012246999889612,0.015208431519568,38951,-2529,-3531,-2064,0.967722117900848 +38753,0.067888654768467,0.016297724097967,0.005531091243029,38951,-2403,-3846,-2182,0.96859073638916 +38755,0.062954030930996,0.028471402823925,0.00164398632478,38951,-1988,-4653,-2178,0.972680866718292 +38757,0.058274608105421,0.028831658884883,0.000890296942089,38951,-1837,-3772,-2170,0.97214138507843 +38759,0.058997329324484,0.024589162319899,-0.001275595859624,38951,-2357,-3425,-2169,0.971949875354767 +38761,0.062408361583948,0.017705971375108,-0.003602671204135,38951,-2503,-3103,-2157,0.973088622093201 +38763,0.056982688605785,0.021188490092754,-0.007258858997375,38951,-1914,-3925,-2196,0.978605628013611 +38765,0.053940206766129,0.014389017596841,-0.012364262714982,38951,-1945,-3069,-2175,0.981739819049835 +38767,0.052665375173092,0.013991485349834,-0.020518381148577,38951,-2168,-3544,-2311,0.980937123298645 +38769,0.057377997785807,0.020322421565652,-0.026737561449409,38951,-2575,-4099,-2233,0.983605086803436 +38771,0.061130654066801,0.02887967042625,-0.029453095048666,38951,-2693,-4442,-2376,0.981506943702698 +38773,0.059313606470823,0.036584421992302,-0.03309940546751,38951,-2164,-4444,-2238,0.984991431236267 +38775,0.059277217835188,0.03738946467638,-0.035296391695738,38951,-2415,-4035,-2406,0.990772068500519 +38777,0.059958752244711,0.046454329043627,-0.038083840161562,38951,-2379,-4700,-2234,0.994950175285339 +38779,0.07096965610981,0.047466538846493,-0.042576409876347,38951,-3421,-4231,-2454,0.997943222522736 +38781,0.078266508877277,0.054139439016581,-0.045662213116884,38951,-3148,-4660,-2249,0.997710287570953 +38783,0.090567342936993,0.037254113703966,-0.044660158455372,38951,-3390,-3313,-2205,0.995789527893066 +38785,0.090567342936993,0.037254113703966,-0.044660158455372,38951,-3390,-3313,-2437,0.99730795621872 +38787,0.108491450548172,0.045029688626528,-0.049793682992458,38951,-3884,-4403,-2205,0.997737526893616 +38789,0.108491450548172,0.045029688626528,-0.049793682992458,38951,-3884,-4403,-2205,0.997737526893616 +38791,0.135641038417816,0.060524787753821,-0.0509740896523,38951,-4634,-4456,-2177,1.00019192695618 +38793,0.13598507642746,0.070487000048161,-0.051853198558092,38951,-3903,-5337,-2419,1.00629067420959 +38795,0.133248791098595,0.068493880331516,-0.056509725749493,38951,-3421,-4338,-2180,1.01032209396362 +38797,0.135666847229004,0.06805594265461,-0.065613925457001,38951,-4130,-4590,-2547,1.00816297531128 +38803,0.160579428076744,0.0618020221591,-0.071661569178104,38951,-4462,-4116,-2218,1.00655031204224 +38805,0.166677191853523,0.059796389192343,-0.074354879558086,38951,-5033,-4397,-2585,1.00333762168884 +38807,0.160590931773186,0.066475942730904,-0.077554538846016,38951,-3799,-5023,-2227,1.00117385387421 +38809,0.160590931773186,0.066475942730904,-0.077554538846016,38951,-3799,-5023,-2227,1.00117385387421 +38811,0.151948392391205,0.062957145273686,-0.080101430416107,38951,-3849,-4615,-2213,1.000248670578 +38813,0.14881819486618,0.053938392549753,-0.083327755331993,38951,-4240,-3845,-2629,0.997804760932922 +38815,0.145416274666786,0.051645796746016,-0.086760900914669,38951,-3924,-4219,-2229,0.988171637058258 +38817,0.141172289848328,0.054055411368609,-0.090375810861588,38951,-4102,-4692,-3334,0.979553997516632 +38819,0.141172289848328,0.054055411368609,-0.090375810861588,38951,-4102,-4692,-3334,0.979553997516632 +38821,0.120334401726723,0.043296940624714,-0.089872054755688,39165,-3259,-4034,-3343,0.9761563539505 +38823,0.115067966282368,0.03668762370944,-0.091624714434147,39165,-3484,-3740,-2921,0.982996881008148 +38825,0.115441627800465,0.03764520585537,-0.091884732246399,39165,-4123,-4359,-3381,0.988327622413635 +38827,0.114993825554848,0.028838194906712,-0.088902555406094,39165,-3884,-3487,-2917,0.993987023830414 +38829,0.108911648392677,0.011099076829851,-0.087812766432762,39165,-3606,-2595,-3347,0.990772545337677 +38831,0.09399576485157,0.008531163446605,-0.089180387556553,39165,-2599,-3646,-2933,0.984254419803619 +38833,0.08284093439579,0.006711794063449,-0.091059103608131,39165,-2869,-3670,-3399,0.979364156723022 +38835,0.067036360502243,0.016759037971497,-0.091138273477554,39165,-2190,-4670,-2961,0.98106724023819 +38837,0.057141695171595,0.01275516115129,-0.088774226605892,39165,-2589,-3624,-3387,0.979028582572937 +38839,0.041218765079975,0.018641050904989,-0.085657432675362,39165,-1843,-4406,-2938,0.97638326883316 +38841,0.028978854417801,0.020001325756312,-0.082800172269344,39165,-1998,-4146,-3331,0.980065584182739 +38843,0.016316007822752,0.021093495190144,-0.083182066679001,39165,-1740,-4109,-2934,0.985345482826233 +38845,0.005339027848095,0.010649004019797,-0.087201751768589,39165,-1710,-3152,-3396,0.988868772983551 +38847,-0.000926083361264,-0.01201459672302,-0.085776656866074,39165,-1959,-1939,-2966,0.984796345233917 +38849,-0.005112045444548,-0.024162340909243,-0.081746622920036,39165,-2036,-2460,-3344,0.981107473373413 +38851,-0.010793996043503,-0.026438772678375,-0.081260807812214,39165,-1863,-3182,-2948,0.976399958133698 +38853,-0.023967292159796,-0.020704928785563,-0.084184072911739,39165,-1091,-3781,-3386,0.974627137184143 +38855,-0.032712981104851,-0.025686789304018,-0.081442788243294,39165,-1325,-2989,-2963,0.976617753505707 +38857,-0.041430119425058,-0.03897063061595,-0.081826388835907,39165,-1115,-2112,-3372,0.976830124855042 +38859,-0.050466660410166,-0.041583202779293,-0.086871549487114,39165,-1036,-2913,-3013,0.975083708763123 +38861,-0.051319271326065,-0.039199251681566,-0.085766978561878,39165,-1495,-3220,-3431,0.971155047416687 +38863,-0.059948097914457,-0.028400029987097,-0.078741647303104,39165,-911,-4047,-2971,0.977782547473908 +38865,-0.070493437349796,-0.030374860391021,-0.071233779191971,39165,-462,-3029,-3273,0.987054884433746 +38867,-0.080537095665932,-0.031425777822733,-0.072506226599217,39165,-485,-3140,-2940,0.99081426858902 +38869,-0.07726277410984,-0.034897778183222,-0.076866500079632,39165,-1311,-2830,-3351,0.988685727119446 +38871,-0.072729900479317,-0.031279377639294,-0.078931644558907,39165,-1610,-3460,-2996,0.980559706687927 +38873,-0.070501133799553,-0.028703447431326,-0.076110102236271,39165,-1320,-3342,-3355,0.977094769477844 +38875,-0.063482828438282,-0.033662710338831,-0.069068126380444,39165,-1892,-2797,-2941,0.979115009307861 +38877,-0.059558108448982,-0.036149222403765,-0.063329875469208,39165,-1599,-2833,-3216,0.981079876422882 +38879,-0.057651717215777,-0.038745276629925,-0.062965750694275,39165,-1587,-2873,-2909,0.980815827846527 +38881,-0.065705694258213,-0.021146355196834,-0.064098432660103,39165,-613,-4508,-3235,0.978816032409668 +38883,-0.072053842246533,-0.015406185761094,-0.06112601608038,39165,-763,-3793,-2906,0.981447219848633 +38885,-0.077418528497219,-0.012986861169338,-0.05915691703558,39165,-587,-3546,-3187,0.986625134944916 +38887,-0.07710862159729,-0.010553649626672,-0.060082297772169,39165,-1135,-3618,-2909,0.99498462677002 +38889,-0.066261246800423,-0.014894516207278,-0.058707736432552,39165,-1907,-3026,-3191,0.996390521526337 +38891,-0.059028156101704,-0.007396577391773,-0.058470461517572,39165,-1865,-4018,-2907,0.998428106307983 +38893,-0.059988968074322,0.003821999533102,-0.059479735791683,39165,-1144,-4444,-3210,1.00288915634155 +38895,-0.062894478440285,0.015787107869983,-0.060019627213478,39165,-1061,-4672,-2927,1.00614583492279 +38897,-0.055295880883932,0.012742867693305,-0.055591445416212,39165,-1807,-3572,-3173,1.00537168979645 +38899,-0.04912992939353,0.014704508706927,-0.050507444888353,39165,-1887,-3946,-2870,0.996654152870178 +38901,-0.050564125180245,0.017863921821117,-0.048077490180731,39165,-1209,-4103,-3093,0.992397785186768 +38903,-0.043141789734364,0.014607824385166,-0.049526520073414,39165,-2043,-3578,-2871,0.987129867076874 +38905,-0.03315394371748,0.016976123675704,-0.051166959106922,39165,-2290,-4034,-3137,0.991256177425384 +38907,-0.022014636546373,0.014683860354126,-0.049261558800936,39165,-2599,-3654,-2877,0.995071530342102 +38909,-0.019081275910139,0.022417867556214,-0.043833125382662,39165,-2005,-4516,-3058,0.996613144874573 +38911,-0.011713069863618,0.015865471214056,-0.043255094438791,39165,-2471,-3374,-2843,0.997062742710114 +38913,-0.006688960827887,0.023881850764155,-0.044012252241373,39165,-2354,-4573,-3067,0.99834555387497 +38915,0.000123942183563,0.029160557314754,-0.040598455816507,39165,-2601,-4423,-2832,1.00421583652496 +38917,0.00690745189786,0.029167395085096,-0.038758710026741,39165,-2701,-4097,-3012,1.0057018995285 +38919,0.004578513093293,0.034999381750822,-0.037127166986466,39165,-2015,-4560,-2814,1.00589287281036 +38921,0.010505127720535,0.036165073513985,-0.033923152834177,39165,-2706,-4305,-2961,1.00187170505524 +38923,0.023985961452127,0.039586771279574,-0.031217329204083,39165,-3433,-4469,-2778,0.998956978321075 +38925,0.03800605237484,0.02977054566145,-0.027248064056039,39165,-3747,-3430,-2887,0.993778586387634 +38927,0.035017367452383,0.035531204193831,-0.023242793977261,39165,-2432,-4591,-2728,0.994702100753784 +38929,0.036878477782011,0.029708011075854,-0.019893066957593,39165,-2884,-3728,-2804,0.995186328887939 +38931,0.04995821416378,0.020458072423935,-0.020517695695162,39165,-3818,-3313,-2712,0.9891636967659 +38933,0.060003865510225,0.013011077418923,-0.02346271649003,39165,-3870,-3354,-2849,0.991077661514282 +38935,0.060502778738737,0.010127512738109,-0.024206019937992,39165,-3100,-3627,-2741,0.995884001255035 +38955,0.070191331207752,0.0241982601583,-0.024088576436043,39165,-3084,-4638,-2759,0.992969393730164 +38957,0.064760483801365,0.026422660797834,-0.02378423884511,39165,-3042,-4329,-2875,0.997591137886047 +38959,0.05611028149724,0.033010166138411,-0.024908548220992,39165,-2599,-4700,-2768,0.99742865562439 +38961,0.04755375534296,0.036183591932058,-0.022017538547516,39165,-2571,-4568,-2858,0.999645113945007 +38963,0.044927317649126,0.031343743205071,-0.021401841193438,39165,-2895,-3874,-2747,0.993590652942658 +38965,0.042562678456307,0.035256020724774,-0.021851733326912,39165,-2963,-4629,-2859,0.985565900802612 +38967,0.036199025809765,0.035569321364164,-0.021898565813899,39165,-2526,-4322,-2754,0.983349144458771 +38969,0.02831157669425,0.04230322316289,-0.020215990021825,39165,-2359,-4965,-2844,0.986746430397034 +38971,0.033083945512772,0.035355314612389,-0.017451765015721,39165,-3297,-3819,-2726,0.986602783203125 +38973,0.034352537244558,0.039629328995943,-0.01883064955473,39165,-3126,-4767,-2830,0.983180522918701 +38975,0.033144876360893,0.036045752465725,-0.018146581947804,39165,-2890,-4090,-2734,0.986757040023804 +38977,0.024053324013949,0.036899525672197,-0.014007277786732,39165,-2232,-4492,-2775,0.992983222007751 +38979,0.01713527366519,0.040103599429131,-0.013825627043843,39165,-2266,-4653,-2706,1.00329351425171 +38981,0.010924128815532,0.045665983110666,-0.012786850333214,39165,-2240,-4985,-2763,1.01212239265442 +38983,0.004433632828295,0.051398750394583,-0.012710261158645,39165,-2123,-5018,-2700,1.00710725784302 +38985,-0.005016546230763,0.052382156252861,-0.010988270863891,39165,-1756,-4781,-2744,1.00119173526764 +38987,-0.012602675706148,0.058483771979809,-0.008361623622477,39165,-1802,-5169,-2671,0.992544054985046 +38989,-0.019657265394926,0.058671459555626,-0.007389024831355,39165,-1686,-4845,-2702,0.990474820137024 +38991,-0.022023763507605,0.060204718261957,-0.007578870281577,39165,-2036,-4892,-2667,0.987102746963501 +38993,-0.023203730583191,0.066784776747227,-0.008931423537433,39165,-2026,-5468,-2722,0.984271049499512 +38995,-0.024029584601522,0.062164314091206,-0.007164644543082,39165,-2108,-4509,-2665,0.983738839626312 +38997,-0.027093084529042,0.070994071662426,-0.0041842199862,39165,-1818,-5737,-2666,0.993091702461243 +38999,-0.026248266920447,0.072174206376076,-0.002805315656587,39165,-2184,-5102,-2635,1.00643122196198 +39001,-0.024177582934499,0.080817528069019,-0.00336219323799,39165,-2240,-5916,-2657,1.00992274284363 +39003,-0.020592795684934,0.072663798928261,-0.002073634415865,39165,-2454,-4478,-2630,1.00074172019959 +39005,-0.027352286502719,0.071761749684811,0.000889156654011,39165,-1546,-5121,-1766,0.992580890655518 +39007,-0.032900232821703,0.078421086072922,0.006497467402369,39934,-1614,-5656,-1702,0.987277567386627 +39009,-0.022152943536639,0.078641891479492,0.00711908005178,39934,-2878,-5345,-1635,0.98283040523529 +39011,-0.007176985032856,0.090651787817478,0.005243241321296,39934,-3447,-6252,-1652,0.981625735759735 +39013,-0.001045408193022,0.10471598058939,0.003420288441703,39934,-2890,-6808,-1622,0.981734991073608 +39015,-0.007374334149063,0.121682867407799,0.003063448471949,39934,-1921,-7102,-1610,0.988139510154724 +39017,-0.011893118731678,0.117122314870358,0.004579151514918,39934,-1956,-5731,-1551,0.994218170642853 +39019,-0.009838369674981,0.114552676677704,0.004283288959414,39934,-2485,-5657,-1544,0.996455907821655 +39021,-0.000657449709252,0.109579496085644,0.001762941945344,39934,-3119,-5627,-1526,1.00079667568207 +39023,0.010318991728127,0.103067837655544,-0.004440514370799,39934,-3417,-5262,-1547,0.997953295707702 +39025,0.014833768829703,0.106323249638081,-0.011142193339765,39934,-3046,-6215,-1622,0.993855714797974 +39027,0.013380853459239,0.110394679009914,-0.013872971758247,39934,-2582,-6176,-1556,0.992608428001404 +39029,0.009903404861689,0.115170188248158,-0.015774860978127,39934,-2409,-6522,-1622,0.990018248558044 +39031,0.014675217680633,0.102220013737679,-0.017074374482036,39934,-3057,-4895,-1524,0.991696298122406 +39033,0.017171068117023,0.103109650313854,-0.018441097810865,39934,-2971,-6104,-1599,0.991403222084045 +39035,0.018963690847159,0.104875348508358,-0.021835833787918,39934,-2919,-6038,-1503,0.99535083770752 +39037,0.024479206651449,0.104588873684406,-0.026237415149808,39934,-3322,-6101,-1637,0.99559885263443 +39039,0.028100125491619,0.100115574896336,-0.026993880048394,39934,-3199,-5576,-1486,0.996621966362 +39041,0.025982456281781,0.083729706704617,-0.026347449049354,39934,-2812,-4647,-1585,0.995282590389252 +39043,0.014750784263015,0.083083562552929,-0.02827606536448,39934,-1960,-5648,-1305,0.993286907672882 +39045,0.00146016466897,0.075357422232628,-0.029693463817239,40720,-1626,-5168,-1431,0.995628118515015 +39047,-0.007175339851528,0.080764479935169,-0.035205624997616,40720,-1838,-6086,-1291,0.9969242811203 +39049,-0.007542822510004,0.077005594968796,-0.037580285221338,40720,-2405,-5519,-1463,0.999732315540314 +39051,-0.010208392515779,0.066512726247311,-0.037795692682266,40720,-2223,-4781,-1249,0.99659538269043 +39053,-0.024570409208536,0.066739320755005,-0.041718740016222,40720,-1123,-5676,-1451,0.99651575088501 +39055,-0.033265836536884,0.058618273586035,-0.050068996846676,40720,-1454,-4872,-1273,0.995305359363556 +39057,-0.032306183129549,0.062044907361269,-0.057716179639101,40720,-2089,-5867,-1581,0.998246014118195 +39059,-0.026778379455209,0.062080081552267,-0.059128172695637,40720,-2556,-5540,-1279,0.998160600662231 +39061,-0.027850175276399,0.070146016776562,-0.058099079877138,40720,-2012,-6362,-1529,1.00144195556641 +39063,-0.033774983137846,0.069026120007038,-0.059767436236143,40720,-1628,-5593,-1226,1.00583970546722 +39065,-0.035565614700317,0.059746209532023,-0.064487501978874,40720,-1831,-4989,-1548,1.00294494628906 +39067,-0.039581958204508,0.053443055599928,-0.068860203027725,40720,-1672,-5031,-1233,1.0076060295105 +39069,-0.043867398053408,0.048582393676043,-0.072681725025177,40720,-1501,-5152,-1589,1.01451861858368 +39071,-0.04876446351409,0.041470002382994,-0.073141597211361,40720,-1462,-4829,-1208,1.01839232444763 +39073,-0.04523590952158,0.025185050442815,-0.075716830790043,40720,-2016,-3971,-1569,1.01997101306915 +39075,-0.039808873087168,0.020923128351569,-0.080256223678589,40720,-2313,-4754,-1203,1.01628720760345 +39077,-0.036313399672508,0.013610139489174,-0.080211512744427,40720,-2143,-4433,-1568,1.01682043075562 +39079,-0.034850660711527,0.006172084715217,-0.079123944044113,40720,-2088,-4325,-1141,1.01812779903412 +39081,-0.037374261766672,-0.002202848205343,-0.079009294509888,40720,-1686,-4109,-1500,1.01627933979034 +39083,-0.027692791074514,-0.007503739092499,-0.081135913729668,41185,-2767,-4284,-1101,1.01215481758118 +39085,-0.022876745089889,-0.006605571135879,-0.085294984281063,41185,-2429,-4706,-1521,1.00629675388336 +39087,-0.020101765170693,-0.025402653962374,-0.091163240373135,41185,-2373,-3061,-1118,0.999638974666595 +39089,-0.023036865517497,-0.033411785960198,-0.095192275941372,41185,-1861,-3630,-1585,1.00123536586761 +39091,-0.018904922530055,-0.039053928107023,-0.095754913985729,41185,-2480,-3797,-1098,1.00911903381348 +39093,-0.010744044557214,-0.038830369710922,-0.096623048186302,41185,-2853,-4124,-1551,1.01491713523865 +39095,-0.005299123935401,-0.037915546447039,-0.098568312823773,41185,-2767,-4270,-1067,1.01725995540619 +39097,0.002258781110868,-0.039726201444864,-0.096949242055416,41185,-3016,-3947,-1504,1.0186038017273 +39099,0.012097289785743,-0.041618011891842,-0.096755348145962,41185,-3334,-4002,-1003,1.01879000663757 +39101,0.02149205096066,-0.050048150122166,-0.099253132939339,41185,-3467,-3285,-1480,1.02073359489441 +39103,0.02847714535892,-0.05555322766304,-0.104128360748291,41185,-3377,-3523,-1003,1.02131533622742 +39105,0.032501645386219,-0.055532492697239,-0.108301386237144,41185,-3282,-3772,-1537,1.02216994762421 +39107,0.036904335021973,-0.063234999775887,-0.110365621745586,41185,-3330,-3232,-997,1.0193395614624 +39109,0.034015290439129,-0.061510536819697,-0.108423143625259,41185,-2831,-3772,-1489,1.02073609828949 +39111,0.027990514412522,-0.06151108443737,-0.107506722211838,41185,-2475,-3782,-928,1.02459311485291 +39113,0.013790004886687,-0.048671923577786,-0.113628052175045,41185,-1708,-4767,-1502,1.03126680850983 +39115,0.004096241202205,-0.041325371712446,-0.121247075498104,41185,-1879,-4579,-974,1.03460943698883 +39117,8.1232916272711E-05,-0.046794757246971,-0.126309111714363,41185,-2227,-3470,-1604,1.03753280639648 +39119,-0.005533686839044,-0.044270250946283,-0.131196320056915,41185,-2037,-4174,-997,1.03543925285339 +39121,-0.016723373904824,-0.037574600428343,-0.135766550898552,41543,-1436,-4477,-1670,1.03448641300201 +39123,-0.02561197988689,-0.025100124999881,-0.141213327646256,41543,-1510,-5149,-1021,1.03216207027435 +39125,-0.022097546607256,-0.02290197648108,-0.146843805909157,41543,-2398,-4378,-1757,1.03246557712555 +39127,-0.019578564912081,-0.025072636082769,-0.150911495089531,41543,-2408,-4093,-1045,1.03226721286774 +39129,-0.02491932362318,-0.023618705570698,-0.151317596435547,41543,-1706,-4306,-1767,1.0295330286026 +39131,-0.035799045115709,-0.022128699347377,-0.150135844945908,41543,-1206,-4389,-997,1.03337037563324 +39133,-0.048452183604241,-0.015128763392568,-0.14828135073185,41543,-791,-4840,-1689,1.03972208499908 +39135,-0.050004046410322,-0.019062496721745,-0.14882780611515,41543,-1652,-4042,-946,1.04759895801544 +39137,-0.047742638736963,-0.016975456848741,-0.153327256441116,41543,-1856,-4456,-1706,1.053591132164 +39139,-0.047220945358276,-0.005203984677792,-0.156252071261406,41543,-1823,-5362,-955,1.05566549301147 +39141,-0.049549106508494,0.001092561054975,-0.158163771033287,41543,-1474,-5046,-1722,1.05339443683624 +39143,-0.054115314036608,-0.003119201865047,-0.155921757221222,41543,-1339,-4250,-911,1.04884934425354 +39145,-0.059325739741325,-0.015413084067404,-0.152523010969162,41543,-1087,-3446,-1613,1.04419612884521 +39147,-0.064074262976647,-0.016927832737565,-0.152994304895401,41543,-1159,-4241,-849,1.03905153274536 +39149,-0.065307401120663,-0.015408901497722,-0.15439473092556,41543,-1263,-4427,-1594,1.03951740264893 +39151,-0.058521471917629,-0.01843960955739,-0.156707152724266,41543,-2040,-4106,-833,1.04245746135712 +39153,-0.054637424647808,-0.020155511796475,-0.163056090474129,41543,-1781,-4121,-1655,1.04479265213013 +39155,-0.052982665598393,-0.025458831340075,-0.16723145544529,41543,-1731,-3837,-865,1.04670989513397 +39157,-0.054709892719984,-0.02189514040947,-0.166388854384422,41543,-1352,-4470,-1654,1.04444801807404 +39159,-0.058356333523989,-0.021254325285554,-0.165716305375099,41543,-1253,-4317,-815,1.04529440402985 +39161,-0.060565855354071,-0.022329399362207,-0.167594254016876,41543,-1200,-4112,-1628,1.04502856731415 +39163,-0.068792179226875,-0.023307017982006,-0.169319912791252,41543,-751,-4164,-800,1.04969012737274 +39165,-0.076191075146198,-0.026915358379483,-0.169291526079178,41543,-546,-3845,-1608,1.05059540271759 +39167,-0.084585681557655,-0.016255790367723,-0.16867507994175,41543,-481,-5088,-756,1.04948532581329 +39185,-0.098330162465572,0.010372123681009,-0.196854174137116,41543,-506,-4018,-1746,1.02842891216278 +39187,-0.092939980328083,0.003131444100291,-0.204953730106354,41543,-1140,-4135,-820,1.03110206127167 +39189,-0.07755945622921,-0.005629876162857,-0.20935383439064,41543,-1927,-3878,-1859,1.03733253479004 +39191,-0.065252684056759,-0.003582494333386,-0.212612688541412,41543,-2000,-4705,-840,1.04414737224579 +39193,-0.056486360728741,-0.001529169036075,-0.213754966855049,41543,-1767,-4729,-1879,1.05129742622375 +39195,-0.053058918565512,-0.007158534601331,-0.207954198122025,41543,-1517,-4108,-776,1.05549573898315 +39197,-0.051001377403736,-0.006685837637633,-0.206959173083305,41543,-1336,-4532,-1766,1.05887341499329 +39199,-0.046883054077625,-0.00597522361204,-0.211401030421257,41543,-1631,-4581,-766,1.06289684772491 +39201,-0.047738090157509,-0.000910735689104,-0.213490918278694,41543,-1147,-4951,-1809,1.06322956085205 +39203,-0.045817006379366,0.000290572497761,-0.214850097894669,41543,-1465,-4709,-758,1.06282603740692 +39205,-0.041763000190258,1.67140060511883E-05,-0.219410568475723,41543,-1582,-4582,-1847,1.06066632270813 +39207,-0.036794107407332,0.005196974147111,-0.221952825784683,41543,-1794,-5067,-775,1.05823302268982 +39209,-0.028971582651138,0.012245498597622,-0.223050937056541,41543,-2039,-5317,-1859,1.05721867084503 +39211,-0.022933475673199,0.015225461684167,-0.22705440223217,41543,-2054,-5062,-779,1.05561292171478 +39213,-0.016346318647266,0.009718448854983,-0.227260380983353,41543,-2141,-4389,-1878,1.05857729911804 +39215,-0.00293883215636,0.001476550824009,-0.228496894240379,41543,-2860,-4070,-759,1.06223154067993 +39217,0.007444463670254,-0.000475049135275,-0.231323301792145,41543,-2799,-4481,-1896,1.06636834144592 +39219,0.009250342845917,-0.008733886294067,-0.232452139258385,41543,-2206,-3925,-757,1.06702923774719 +39221,0.005027906503528,-0.013086035847664,-0.233158007264137,41543,-1718,-4101,-1889,1.06744074821472 +39223,0.007910279557109,-0.011588900350034,-0.236645370721817,41543,-2266,-4580,-757,1.06576204299927 +39225,0.02181313931942,-0.005144876427948,-0.240206360816956,41543,-3298,-5002,-1943,1.06075572967529 +39227,0.034615937620401,-0.001045571290888,-0.240437656641006,41543,-3369,-4918,-755,1.06180214881897 +39229,0.039520401507616,-0.008760409429669,-0.237624004483223,41543,-2961,-3932,-1885,1.06561744213104 +39231,0.03964775800705,-0.014840462245047,-0.238039910793304,41543,-2553,-3991,-710,1.06966483592987 +39233,0.040727704763413,-0.014574823901057,-0.243470281362534,41721,-2726,-4410,-1926,1.07421875 +39235,0.044245038181543,-0.007480145432055,-0.250137150287628,41721,-2881,-5037,-766,1.0770777463913 +39237,0.046921338886023,0.00035944726551,-0.254493981599808,41721,-2956,-5197,-2029,1.07699632644653 +39239,0.051478415727615,0.002643168671057,-0.25835394859314,41721,-3082,-4842,-796,1.07521295547485 +39241,0.051436189562082,0.000188509962754,-0.261579483747482,41721,-2852,-4460,-2087,1.07281291484833 +39243,0.04494808614254,-0.005362699739635,-0.264758259057999,41721,-2220,-4170,-816,1.07120704650879 +39245,0.038441270589829,-0.009646526537836,-0.2685367166996,41721,-2198,-4160,-2145,1.06739616394043 +39247,0.035100471228361,-0.008325774222612,-0.272380799055099,41721,-2321,-4617,-845,1.06396973133087 +39249,0.032976277172566,-0.014404173009098,-0.276914864778519,41721,-2437,-3947,-2221,1.06421720981598 +39251,0.026766017079353,-0.017873568460345,-0.278947651386261,41721,-2010,-4132,-868,1.06481599807739 +39253,0.016869384795427,-0.030112413689494,-0.277171581983566,41721,-1622,-3258,-2202,1.06685566902161 +39255,0.005076190456748,-0.042568657547236,-0.279154121875763,41721,-1305,-3124,-848,1.06643617153168 +39257,-0.005824939347804,-0.046332012861967,-0.284073710441589,41721,-1185,-3595,-2262,1.07088255882263 +39259,-0.017459908500314,-0.050240270793438,-0.287098318338394,41721,-988,-3609,-882,1.07832682132721 +39261,-0.031872265040875,-0.052901156246662,-0.286581009626389,41721,-514,-3537,-2272,1.08658742904663 +39263,-0.040432538837195,-0.064736932516098,-0.287155389785767,41721,-865,-2812,-862,1.09266102313995 +39265,-0.040855299681425,-0.077835835516453,-0.291094571352005,41721,-1359,-2352,-2305,1.08507025241852 +39267,-0.044175643473864,-0.082443810999394,-0.295231968164444,41721,-1169,-3041,-898,1.07399880886078 +39269,-0.046887934207916,-0.081510543823242,-0.299051493406296,41721,-1077,-3263,-2380,1.06472885608673 +39271,-0.044817708432675,-0.074580237269402,-0.304382532835007,41721,-1526,-3945,-943,1.05925273895264 +39273,-0.038326982408762,-0.080346554517746,-0.305207252502441,41721,-1855,-2764,-2435,1.05937039852142 +39275,-0.034870136529207,-0.086833536624909,-0.305325388908386,41721,-1751,-2772,-932,1.05969154834747 +39277,-0.039611823856831,-0.081099778413773,-0.306854635477066,41721,-1005,-3542,-2437,1.06047141551971 +39279,-0.046297390013933,-0.067890428006649,-0.306399643421173,41721,-841,-4418,-922,1.06270325183868 +39281,-0.050163865089417,-0.05328256636858,-0.30316349864006,41721,-877,-4599,-2376,1.0681426525116 +39283,-0.049756422638893,-0.056947238743305,-0.30046471953392,41721,-1276,-3342,-864,1.0782698392868 +39285,-0.053553275763989,-0.063965804874897,-0.30237203836441,41721,-810,-2847,-2350,1.08184349536896 +39287,-0.060746677219868,-0.070935100317001,-0.305752128362656,41721,-550,-2875,-883,1.08078706264496 +39289,-0.063296861946583,-0.079560786485672,-0.30610203742981,41721,-713,-2447,-2376,1.0751781463623 +39291,-0.061147224158049,-0.08333395421505,-0.305882632732391,41721,-1184,-2890,-866,1.06620025634766 +39293,-0.056598898023367,-0.078108407557011,-0.307065963745117,41721,-1298,-3427,-2371,1.06307542324066 +39295,-0.049957368522883,-0.062387615442276,-0.310814470052719,41721,-1640,-4551,-883,1.06219470500946 +39297,-0.042083114385605,-0.052381560206413,-0.313578188419342,41721,-1736,-4159,-2431,1.06414830684662 +39299,-0.033289093524218,-0.050870139151812,-0.315063297748566,41721,-2011,-3674,-897,1.06575155258179 +39301,-0.024794045835734,-0.046582560986281,-0.317357748746872,41721,-2047,-3821,-2459,1.06441354751587 +39303,-0.021423943340778,-0.044441346079111,-0.318161606788635,41721,-1778,-3790,-903,1.06571578979492 +39305,-0.019434813410044,-0.051868755370379,-0.317219942808151,41721,-1665,-2872,-2443,1.06847620010376 +39307,-0.014057309366763,-0.062268115580082,-0.318631500005722,41721,-2018,-2611,-891,1.07302224636078 +39309,0.001037184265442,-0.067836090922356,-0.323142290115356,41721,-2942,-2725,-2498,1.07763063907623 +39311,0.014226046390832,-0.055230285972357,-0.329273194074631,41721,-2985,-4329,-950,1.08262574672699 +39313,0.024226063862443,-0.042180363088846,-0.329412221908569,41721,-2964,-4461,-2558,1.08562850952148 +39315,0.033425342291594,-0.030174341052771,-0.330798089504242,41721,-2988,-4629,-947,1.08221220970154 +39317,0.033005394041538,-0.021621033549309,-0.333342522382736,41721,-2365,-4457,-2591,1.08054637908936 +39319,0.028079178184271,-0.02395704202354,-0.334160923957825,41721,-1914,-3682,-957,1.07986116409302 +39321,0.021412951871753,-0.023191684857011,-0.335772454738617,41721,-1734,-3857,-2607,1.07936429977417 +39323,0.018425052985549,-0.012500405311585,-0.337606400251389,41721,-1923,-4769,-969,1.07833957672119 +39325,0.014536472968757,0.001312844571657,-0.339840292930603,41721,-1823,-5185,-2642,1.07671749591827 +39327,0.004666995722801,0.00326910475269,-0.342796087265015,41721,-1237,-4370,-993,1.07368433475494 +39329,-0.002004660200328,0.001172455027699,-0.344411879777908,41721,-1358,-4041,-2685,1.07321965694428 +39331,-0.001863566110842,0.009804337285459,-0.346655160188675,41721,-1858,-4942,-1009,1.07356035709381 +39333,0.001871618209407,0.020034078508616,-0.350393146276474,41721,-2171,-5228,-2745,1.07220590114594 +39335,0.001716299913824,0.025983797386289,-0.352325111627579,41721,-1888,-4990,-1038,1.07468092441559 +39337,-0.000933558563702,0.021664703264833,-0.355483472347259,41721,-1667,-4230,-2795,1.07749497890472 +39339,-0.003749267663807,0.009971789084375,-0.360049337148666,41721,-1618,-3507,-1082,1.0800815820694 +39341,-0.010090285912156,0.014384157024324,-0.361257076263428,41721,-1256,-4757,-2855,1.0828127861023 +39343,-0.008667279034853,0.027830220758915,-0.360513746738434,41721,-1847,-5572,-1078,1.08720803260803 +39345,-0.005798339378089,0.042497366666794,-0.363177239894867,41721,-1983,-5957,-2870,1.08878755569458 +39347,-0.010006564669311,0.045276485383511,-0.365922957658768,41721,-1421,-5079,-1107,1.08903563022614 +39349,-0.016894247382879,0.038231927901507,-0.365687489509583,41721,-1094,-4347,-2892,1.08552706241608 +39351,-0.019810250028968,0.039103377610445,-0.365273714065552,41721,-1365,-4872,-1095,1.07809066772461 +39353,-0.019539322704077,0.037970762699843,-0.361963242292404,41721,-1550,-4789,-2840,1.07153105735779 +39355,-0.016969658434391,0.031563922762871,-0.361940026283264,41721,-1788,-4261,-1065,1.06512188911438 +39357,-0.015289637260139,0.019381495192647,-0.3691665828228,41721,-1711,-3712,-2918,1.06869506835938 +39359,-0.014207667671144,0.014787883497775,-0.376956611871719,41721,-1713,-4161,-1161,1.07610189914703 +39361,-0.016448663547635,0.018355194479227,-0.379711747169495,41721,-1409,-4832,-3037,1.07720386981964 +39363,-0.019660213962197,0.013034092262387,-0.379318445920944,41721,-1319,-4093,-1173,1.07719099521637 +39365,-0.023181123659015,0.003875514958054,-0.379338711500168,41721,-1210,-3692,-3028,1.07443118095398 +39367,-0.025068990886211,-0.002908774651587,-0.382998168468475,41721,-1327,-3763,-1193,1.06994879245758 +39369,-0.022075895220041,-0.006694125011563,-0.388954877853394,41721,-1690,-3904,-3137,1.0687084197998 +39371,-0.016832267865539,-0.006059596315026,-0.393827736377716,41721,-1948,-4247,-1264,1.06951355934143 +39373,-0.010744138620794,-0.006373790092766,-0.395502835512161,41721,-2074,-4152,-3211,1.07069277763367 +39375,-0.013653476722539,-0.001879828167148,-0.394513577222824,41721,-1404,-4581,-1267,1.0682657957077 +39377,-0.02085667848587,0.000903490523342,-0.395354896783829,41721,-933,-4489,-3207,1.07119429111481 +39379,-0.018286094069481,-0.002748362487182,-0.397541075944901,41721,-1717,-3986,-1286,1.07750856876373 +39381,-0.018313433974981,-0.000855943653733,-0.399916678667068,41721,-1478,-4390,-3259,1.08426415920258 +39383,-0.02065191604197,-0.006195981986821,-0.402122110128403,41721,-1319,-3814,-1316,1.08423030376434 +39385,-0.022195300087333,-0.01658371090889,-0.404338717460632,41721,-1299,-3256,-3311,1.08063948154449 +39387,-0.026510320603848,-0.025608977302909,-0.406176000833511,41721,-1081,-3263,-1343,1.07645392417908 +39389,-0.031140612438321,-0.034383341670036,-0.405358910560608,41721,-929,-3072,-3322,1.07280480861664 +39391,-0.030598249286413,-0.038065683096647,-0.405392497777939,41721,-1355,-3451,-1337,1.07019603252411 +39393,-0.019335690885782,-0.043420702219009,-0.408928722143173,41721,-2253,-3155,-3365,1.07326602935791 +39395,-0.004684233572334,-0.041931513696909,-0.413202494382858,41721,-2729,-3747,-1391,1.0729124546051 +39397,0.000904854037799,-0.033823307603598,-0.414695024490356,41721,-2166,-4261,-3433,1.0722599029541 +39399,-0.002213473664597,-0.033048033714295,-0.41366907954216,41721,-1492,-3808,-1395,1.07720518112183 +39419,0.031597465276718,-0.050022453069687,-0.422115713357925,41721,-2013,-3444,-1462,1.09209954738617 +39421,0.03334965929389,-0.039585791528225,-0.425960153341293,41382,-2455,-4186,-3576,1.0934009552002 +39423,0.03894766792655,-0.029587617143989,-0.429456353187561,41382,-2753,-4373,-1515,1.09413063526154 +39425,0.042509812861681,-0.02060954272747,-0.430344581604004,41382,-2735,-4376,-3631,1.09239161014557 +39427,0.043681025505066,-0.018630554899573,-0.433498919010162,41382,-2521,-3945,-1547,1.0873806476593 +39429,0.047124531120062,-0.019726840779185,-0.439163148403168,41382,-2819,-3651,-3739,1.0805516242981 +39431,0.050048250705004,-0.012685521505773,-0.444878399372101,41382,-2756,-4382,-1631,1.07509636878967 +39433,0.05506668612361,-0.011731006205082,-0.447893232107163,41382,-3083,-3911,-3848,1.0735604763031 +39435,0.054067753255367,-0.014740406535566,-0.449256360530853,41382,-2556,-3623,-1668,1.07202768325806 +39437,0.050804249942303,-0.024093236774206,-0.448593497276306,41382,-2434,-2965,-3863,1.07187163829803 +39439,0.054278485476971,-0.032196555286646,-0.442970395088196,41382,-2899,-2994,-1631,1.07179009914398 +39441,0.05679227784276,-0.031750693917275,-0.437332600355148,41382,-2963,-3535,-3737,1.07652938365936 +39443,0.055479750037193,-0.034178048372269,-0.436388373374939,41382,-2595,-3355,-1591,1.08167743682861 +39445,0.050556842237711,-0.026424411684275,-0.439674764871597,41382,-2364,-4127,-3770,1.09145522117615 +39447,0.051614373922348,-0.016714427620173,-0.443873256444931,41382,-2731,-4461,-1648,1.10159981250763 +39449,0.054462060332298,-0.006828173529357,-0.446801483631134,41382,-3016,-4587,-3859,1.09891653060913 +39451,0.050549566745758,-0.000529000128154,-0.449609696865082,41382,-2385,-4443,-1694,1.08636975288391 +39453,0.039458386600018,-0.004478609189391,-0.453932493925095,41382,-1794,-3630,-3951,1.0772111415863 +39455,0.022266222164035,-0.009853249415755,-0.457277476787567,41382,-1046,-3469,-1755,1.07416415214539 +39457,0.013270838186145,-0.016383605077863,-0.459242105484009,41382,-1527,-3242,-4021,1.07388305664063 +39459,0.008568123914301,-0.019129831343889,-0.460485458374023,41203,-1749,-3513,-1786,1.07378172874451 +39461,0.001271043205634,-0.012078302912414,-0.457562685012817,41203,-1453,-4277,-4010,1.071160197258 +39463,-0.006318846251816,-0.006945083849132,-0.456322103738785,41203,-1328,-4244,-1766,1.06927728652954 +39465,-0.017779603600502,-0.008184592239559,-0.457480847835541,41203,-836,-3734,-4018,1.07113409042358 +39467,-0.027653332799673,-0.013733740895987,-0.458308935165405,41203,-848,-3374,-1788,1.07505369186401 +39469,-0.034932687878609,-0.01068226993084,-0.46161550283432,41203,-842,-3988,-4076,1.07237374782562 +39471,-0.040190529078245,-0.006519735790789,-0.466174006462097,41203,-980,-4164,-1851,1.06760895252228 +39473,-0.046790271997452,-0.010783791542053,-0.467928409576416,41203,-682,-3462,-4160,1.06303906440735 +39475,-0.058115124702454,-0.009220479056239,-0.470472872257233,41203,-265,-3931,-1891,1.06320023536682 +39477,-0.073984734714031,-0.003471480449662,-0.471875458955765,41203,453,-4296,-4217,1.06828391551971 +39479,-0.087965369224548,-0.000592930824496,-0.470591306686401,41203,388,-4145,-1903,1.07183444499969 +39481,-0.09614535421133,0.00010734910029,-0.471313387155533,41203,305,-3989,-4221,1.07573699951172 +39483,-0.096911385655403,-0.003768973052502,-0.47515869140625,41203,-382,-3614,-1945,1.07965850830078 +39485,-0.102427639067173,-0.002155799651518,-0.476679086685181,41203,262,-4012,-4296,1.08132457733154 +39487,-0.105491377413273,-0.012682928703725,-0.476606726646423,41203,-45,-3005,-1967,1.08286333084106 +39489,-0.097914643585682,-0.021024279296398,-0.478350222110748,41203,-701,-2982,-4328,1.07841622829437 +39491,-0.089043840765953,-0.022093743085861,-0.480155348777771,41203,-1088,-3535,-2004,1.07329261302948 +39493,-0.084861762821674,-0.029327817261219,-0.479648351669311,41203,-623,-2909,-4356,1.06417334079742 +39495,-0.082149133086205,-0.026817569509149,-0.478150367736816,41203,-704,-3706,-2003,1.05543804168701 +39497,-0.075207024812698,-0.032949890941382,-0.479557275772095,41203,-938,-2915,-4367,1.05036222934723 +39499,-0.069596655666828,-0.032337486743927,-0.487630873918533,41203,-1053,-3472,-2080,1.05183184146881 +39501,-0.058792922645807,-0.032107319682837,-0.489980071783066,41203,-1444,-3362,-4503,1.06074094772339 +39503,-0.043953411281109,-0.033377982676029,-0.488148182630539,41203,-2051,-3304,-2098,1.06443464756012 +39505,-0.031270951032639,-0.037792973220348,-0.486977815628052,41203,-1994,-2921,-4482,1.06299495697021 +39507,-0.019094966351986,-0.040065731853247,-0.488787353038788,41203,-2198,-3115,-2116,1.06213450431824 +39509,-0.006932803895324,-0.035631787031889,-0.491195648908615,41203,-2338,-3570,-4546,1.06029105186462 +39511,0.006135419011116,-0.033175934106112,-0.490227162837982,41203,-2615,-3532,-2141,1.06215691566467 +39513,0.019563334062696,-0.038191687315703,-0.488191455602646,41203,-2863,-2828,-4525,1.06418168544769 +39515,0.029716549441218,-0.04728788509965,-0.486617624759674,41203,-2750,-2481,-2130,1.06718671321869 +39517,0.047609884291887,-0.055076338350773,-0.488261610269547,41203,-3657,-2336,-4540,1.06849658489227 +39519,0.060839883983135,-0.050077527761459,-0.490251481533051,41203,-3436,-3422,-2169,1.06759440898895 +39521,0.068508639931679,-0.050545200705528,-0.49118646979332,41203,-3291,-2923,-4589,1.06593430042267 +39523,0.077265307307243,-0.047935802489519,-0.492352068424225,41203,-3380,-3257,-2198,1.06382513046265 +39525,0.085702151060104,-0.044662155210972,-0.489764183759689,41203,-3658,-3266,-4586,1.0679190158844 +39527,0.091788522899151,-0.053075574338436,-0.486758440732956,41203,-3435,-2373,-2174,1.07341587543488 +39529,0.091708235442638,-0.059607714414597,-0.486408829689026,41203,-3183,-2286,-4561,1.0777999162674 +39531,0.096369594335556,-0.064120307564735,-0.486111730337143,41203,-3439,-2464,-2183,1.07962596416473 +39533,0.10025355219841,-0.054890401661396,-0.482327073812485,41203,-3641,-3456,-4526,1.07534968852997 +39535,0.105845578014851,-0.049239970743656,-0.476741224527359,41203,-3685,-3376,-2132,1.07141017913818 +39537,0.115450069308281,-0.055940598249436,-0.476854562759399,41203,-4348,-2256,-4474,1.07163083553314 +39539,0.12346675246954,-0.060461916029453,-0.482518076896668,41203,-4163,-2455,-2184,1.06724345684052 +39541,0.125088855624199,-0.05639772862196,-0.486872524023056,41203,-3980,-2983,-4605,1.06176614761353 +39543,0.119293563067913,-0.041853867471218,-0.488185048103332,41203,-3168,-4055,-2237,1.05568015575409 +39545,0.115610957145691,-0.044011764228344,-0.485457509756088,41203,-3493,-2712,-4602,1.0533539056778 +39547,0.116269648075104,-0.059122048318386,-0.485625267028809,41203,-3637,-1656,-2233,1.05231463909149 +39549,0.116529747843742,-0.068025439977646,-0.488309442996979,41203,-3840,-1812,-4650,1.05531466007233 +39551,0.116411589086056,-0.059182651340962,-0.488459706306457,41203,-3634,-3333,-2266,1.06209266185761 +39553,0.111737236380577,-0.041700839996338,-0.486271411180496,41203,-3462,-4102,-4639,1.06378495693207 +39555,0.106508381664753,-0.033341143280268,-0.485940307378769,41203,-3175,-3645,-2263,1.05983197689056 +39557,0.102706648409367,-0.033992908895016,-0.484737128019333,41203,-3432,-2911,-4635,1.05241310596466 +39559,0.097516126930714,-0.029017062857747,-0.485719740390778,41203,-3096,-3444,-2275,1.04411923885345 +39561,0.096828915178776,-0.025528497993946,-0.486650168895721,41203,-3611,-3327,-4671,1.04464960098267 +39563,0.09827122092247,-0.018275070935488,-0.484926074743271,41203,-3627,-3745,-2283,1.04988467693329 +39565,0.103471554815769,-0.017670191824436,-0.485003441572189,41203,-4178,-3232,-4665,1.05603897571564 +39567,0.101749047636986,-0.013765553943813,-0.491744607686996,41203,-3497,-3557,-2344,1.05752289295197 +39569,0.090470403432846,-0.005159069318324,-0.497796148061752,41203,-2826,-3992,-4831,1.06110966205597 +39571,0.07645146548748,-0.001627167221159,-0.498061656951904,41203,-2294,-3696,-2403,1.06792974472046 +39573,0.069461792707443,-0.000494303880259,-0.495521157979965,41203,-2828,-3513,-4820,1.07074356079102 +39575,0.070074580609799,-0.009743663482368,-0.493717670440674,41203,-3281,-2655,-2389,1.06455659866333 +39577,0.061258401721716,-0.015317249111831,-0.494247049093246,41203,-2590,-2783,-4820,1.05263030529022 +39579,0.043099764734507,-0.010315340943635,-0.494958877563477,41203,-1577,-3653,-2413,1.04332733154297 +39581,0.033841047435999,0.000497615488712,-0.493491470813751,41203,-2138,-4206,-4827,1.03708469867706 +39583,0.036553204059601,0.006805294193327,-0.493276596069336,41203,-2993,-3986,-2416,1.03801703453064 +39585,0.03955115750432,-0.000454830791568,-0.495304614305496,41203,-3114,-2894,-4863,1.04234516620636 +39587,0.034131079912186,-0.010606876574457,-0.497927874326706,41203,-2391,-2550,-2464,1.04469585418701 +39589,0.018400460481644,-0.014088809490204,-0.501156806945801,41203,-1440,-2933,-4948,1.04877817630768 +39591,0.004274435807019,-0.003157779807225,-0.502624750137329,41203,-1346,-4154,-2513,1.04897737503052 +39593,-0.003615894820541,0.010382229462266,-0.501531958580017,41203,-1651,-4541,-4969,1.04976511001587 +39595,-0.006787402089685,0.011550726369023,-0.501619160175324,41203,-1969,-3664,-2522,1.0511702299118 +39597,-0.01143219601363,0.009972150437534,-0.501392543315887,41203,-1760,-3449,-4984,1.05212676525116 +39599,-0.01207899581641,-0.003727019065991,-0.500622987747192,41203,-2069,-2377,-2532,1.05373167991638 +39601,-0.013615292496979,-0.010688802227378,-0.50330263376236,41203,-1944,-2728,-5023,1.05028212070465 +39603,-0.023946853354573,-0.008817167021334,-0.505958020687103,41203,-1199,-3409,-2586,1.05054116249084 +39605,-0.038088627159596,-0.008566155098379,-0.508060932159424,41203,-637,-3274,-5097,1.05390536785126 +39607,-0.051774900406599,-0.007148689124733,-0.51072758436203,41203,-542,-3392,-2636,1.05644047260284 +39609,-0.060098651796579,-0.012285460717976,-0.510362207889557,41203,-670,-2822,-5142,1.05974209308624 +39611,-0.066711291670799,-0.015102989040315,-0.50786018371582,41203,-807,-2964,-2635,1.0614185333252 +39613,-0.074723891913891,-0.014694682322443,-0.506167709827423,41203,-424,-3172,-5110,1.06433463096619 +39615,-0.077567026019096,-0.017619546502829,-0.5062096118927,41203,-887,-2910,-2641,1.06914627552032 +39617,-0.078613437712193,-0.021106813102961,-0.509855806827545,41203,-824,-2772,-5172,1.06988370418549 +39619,-0.076729260385037,-0.028143811970949,-0.508815169334412,41203,-1201,-2450,-2677,1.06577134132385 +39621,-0.078690625727177,-0.014612413942814,-0.502246856689453,41203,-711,-4076,-5100,1.06000566482544 +39623,-0.082685016095638,-0.005602950695902,-0.501596629619598,41203,-656,-3910,-2644,1.0572361946106 +39625,-0.088275581598282,-0.006581800058484,-0.505529463291168,41203,-251,-3153,-5156,1.05075323581696 +39627,-0.091328598558903,-0.015885768458247,-0.508722066879272,41203,-556,-2441,-2711,1.04648196697235 +39629,-0.091943420469761,-0.021782603114843,-0.509103298187256,41203,-506,-2544,-5216,1.04352676868439 +39631,-0.091258995234966,-0.023746225982905,-0.50603461265564,41203,-779,-2837,-2710,1.04240214824677 +39649,-0.06684735417366,-0.001429603202268,-0.520721197128296,41203,-1085,-3886,-5448,1.05721521377563 +39651,-0.055943287909031,0.002385345753282,-0.52338707447052,41203,-1821,-3558,-2927,1.0554758310318 +39653,-0.044046342372894,0.001346690580249,-0.526027500629425,41203,-1960,-3197,-5531,1.0576206445694 +39655,-0.034068834036589,-0.001539158634841,-0.528963088989258,41203,-2045,-3018,-2986,1.0623584985733 +39657,-0.024769203737378,-0.003514538053423,-0.531615436077118,41203,-2066,-3048,-5619,1.06714034080505 +39659,-0.015555222518742,0.001662594731897,-0.534821629524231,41203,-2242,-3635,-3049,1.06361198425293 +39661,-0.013846718706191,0.007789418566972,-0.534930169582367,41203,-1698,-3807,-5680,1.05941832065582 +39663,-0.010808021761477,0.009252029471099,-0.531767308712006,41203,-1860,-3476,-3050,1.06119740009308 +39665,-0.006143388804048,0.017615551128984,-0.531535863876343,41203,-2046,-4122,-5662,1.06437075138092 +39667,0.009998654946685,0.015040870755911,-0.536253392696381,41203,-3096,-3272,-3103,1.06319904327393 +39669,0.020124724134803,0.015720976516605,-0.539640784263611,41203,-2865,-3551,-5780,1.05869054794312 +39671,0.023199208080769,0.010558395646513,-0.538468897342682,41203,-2359,-3026,-3142,1.05519247055054 +39673,0.023506596684456,0.020141558721662,-0.537468552589417,41203,-2220,-4272,-5778,1.05236744880676 +39675,0.024018401280046,0.032303713262081,-0.538871586322784,41203,-2198,-4585,-3168,1.0561341047287 +39677,0.023192565888167,0.036034736782312,-0.5384721159935,41203,-2135,-4116,-5813,1.0618109703064 +39679,0.028138482943177,0.037687122821808,-0.539983868598938,41203,-2583,-3922,-3199,1.0618782043457 +39681,0.0372757576406,0.036304417997599,-0.544091701507568,41203,-3087,-3763,-5903,1.05750453472137 +39683,0.045973226428032,0.036303658038378,-0.546993315219879,41203,-3123,-3797,-3272,1.0510014295578 +39685,0.050621625036001,0.03983897715807,-0.546840965747833,41203,-3007,-4183,-5960,1.04730081558228 +39687,0.05478934571147,0.041677262634039,-0.546516954898834,41203,-2948,-4019,-3293,1.0446240901947 +39689,0.051798138767481,0.051930740475655,-0.548056423664093,41203,-2501,-4876,-5999,1.04419410228729 +39691,0.055161338299513,0.05472594499588,-0.549112915992737,41203,-2919,-4294,-3336,1.04199552536011 +39693,0.055942840874195,0.059524465352297,-0.549199998378754,41203,-2852,-4634,-6038,1.03567481040955 +39695,0.055615749210119,0.050129670649767,-0.547352612018585,41203,-2684,-3378,-3349,1.03339731693268 +39697,0.04910472035408,0.04721200093627,-0.547344446182251,41203,-2229,-3900,-6041,1.03330969810486 +39699,0.041278555989266,0.046013630926609,-0.549658596515656,41203,-1959,-3924,-3390,1.03897082805634 +39701,0.03419454395771,0.039366487413645,-0.550173401832581,41203,-1955,-3513,-6100,1.04702198505402 +39703,0.033099938184023,0.037824116647244,-0.549448430538178,41203,-2335,-3795,-3414,1.05043017864227 +39705,0.035090573132038,0.03604219481349,-0.548724353313446,41203,-2636,-3817,-6109,1.0513014793396 +39707,0.030604550614953,0.035274289548397,-0.552659690380096,41203,-2068,-3825,-3462,1.04828500747681 +39709,0.019336933270097,0.032258491963148,-0.557304680347443,41203,-1443,-3680,-6236,1.04460227489471 +39711,0.011552170850337,0.027953080832958,-0.557092308998108,41203,-1564,-3476,-3519,1.03802502155304 +39713,0.004654588643461,0.025809109210968,-0.554169058799744,41203,-1522,-3650,-6225,1.03364109992981 +39715,0.004171288572252,0.013011378236115,-0.55445921421051,41203,-1980,-2661,-3528,1.0317234992981 +39717,0.000920273771044,0.009971947409213,-0.554809808731079,41203,-1719,-3337,-6260,1.03433275222778 +39719,-0.002061658073217,0.004446988925338,-0.550452709197998,41203,-1709,-3060,-3526,1.03979480266571 +39721,-0.009611456654966,0.007486932445318,-0.548961043357849,41203,-1228,-3729,-6217,1.0432151556015 +39723,-0.019300723448396,0.008568401448429,-0.548247396945953,41203,-972,-3591,-3537,1.05017018318176 +39725,-0.027610179036856,0.002223687013611,-0.54756486415863,41203,-867,-2967,-6226,1.05231177806854 +39727,-0.030853124335408,-0.001400645123795,-0.545434951782227,41203,-1250,-3108,-3543,1.052001953125 +39731,-0.023414691910148,-0.001327481819317,-0.550803780555725,41203,-1951,-3657,-3605,1.04352104663849 +39733,-0.018474603071809,-0.005357018206269,-0.550991892814636,41203,-1936,-2999,-6317,1.03817594051361 +39735,-0.024037977680564,-0.007167430594563,-0.546045899391174,41203,-1151,-3141,-3598,1.02935385704041 +39737,-0.036406945437193,-0.005519653204829,-0.543390095233917,41203,-397,-3403,-6253,1.03051602840424 +39739,-0.044519722461701,0.000470559229143,-0.544749855995178,41203,-655,-3804,-3614,1.03817796707153 +39741,-0.046188376843929,0.007713701110333,-0.545148313045502,41203,-984,-4020,-6298,1.04208612442017 +39743,-0.039563797414303,0.003040035022423,-0.544861316680908,41203,-1758,-3078,-3640,1.04645264148712 +39745,-0.0347635820508,0.00517560262233,-0.545579969882965,41203,-1610,-3612,-6328,1.0474898815155 +39747,-0.030811585485935,-0.000639637000859,-0.543551802635193,41203,-1673,-2943,-3656,1.04878568649292 +39749,-0.033124811947346,-0.012377426959574,-0.542150259017944,41203,-1104,-2328,-6313,1.04734671115875 +39751,-0.041958652436733,-0.010505023412407,-0.539953827857971,41203,-577,-3343,-3656,1.05093884468079 +39753,-0.041643463075161,-0.006044310517609,-0.539496541023254,41203,-1131,-3578,-6306,1.04972004890442 +39755,-0.041217047721148,-0.002713897963986,-0.542263746261597,41203,-1228,-3553,-3696,1.04694223403931 +39757,-0.040050018578768,-0.007086281199008,-0.543495893478394,41203,-1197,-2928,-6378,1.04116857051849 +39759,-0.038550619035959,0.006964129395783,-0.542025923728943,41203,-1320,-4454,-3719,1.04184460639954 +39761,-0.029224526137114,0.012762335129082,-0.538575708866119,41203,-1946,-3977,-6344,1.04567277431488 +39763,-0.022131590172649,0.008484233170748,-0.535166263580322,41203,-1940,-3166,-3696,1.04503977298737 +39765,-0.023201322183013,0.006876043044031,-0.532385885715485,41203,-1285,-3349,-6295,1.04435575008392 +39767,-0.022887451574206,0.010688126087189,-0.530192255973816,41203,-1430,-3777,-3685,1.04491293430328 +39769,-0.018005389720202,0.024496134370566,-0.532416760921478,41203,-1778,-4747,-6318,1.04764020442963 +39771,-0.005961266346276,0.024134024977684,-0.532219111919403,41203,-2501,-3679,-3722,1.04892909526825 +39773,-0.000263407855527,0.035438228398562,-0.528630673885345,41203,-2122,-4754,-6296,1.05539238452911 +39775,0.004687398206443,0.040799912065268,-0.527258813381195,41203,-2143,-4341,-3710,1.06192123889923 +39777,0.010268646292389,0.043382838368416,-0.530732929706574,41203,-2290,-4272,-6343,1.06272912025452 +39779,0.016501838341355,0.05042477324605,-0.533552587032318,41203,-2408,-4617,-3776,1.06088602542877 +39781,0.023939402773976,0.053563330322504,-0.531118154525757,41203,-2651,-4490,-6370,1.05990731716156 +39783,0.025741769000888,0.058486964553595,-0.529825866222382,41203,-2232,-4602,-3773,1.052973985672 +39785,0.032282970845699,0.055513396859169,-0.530581414699554,41203,-2730,-4096,-6387,1.05011343955994 +39787,0.036320544779301,0.065114259719849,-0.531658470630646,41203,-2556,-5052,-3809,1.04534089565277 +39789,0.041404873132706,0.070180594921112,-0.526802778244019,41203,-2783,-4937,-6364,1.04751241207123 +39791,0.043742571026087,0.074206493794918,-0.518864154815674,41203,-2557,-4811,-3743,1.0491818189621 +39793,0.043534580618143,0.073363751173019,-0.514513969421387,41203,-2454,-4600,-6241,1.05673038959503 +39795,0.042897004634142,0.07359205186367,-0.516173660755158,41203,-2349,-4561,-3745,1.06557154655457 +39797,0.037980038672686,0.081900082528591,-0.517166674137116,41203,-2046,-5430,-6292,1.07118654251099 +39799,0.040924813598394,0.072529062628746,-0.516796588897705,41203,-2592,-3892,-3770,1.07104408740997 +39801,0.043745256960392,0.069821134209633,-0.51928985118866,41203,-2709,-4483,-6339,1.0680958032608 +39803,0.046114038676024,0.073799230158329,-0.519201457500458,41203,-2643,-4898,-3807,1.06468331813812 +39805,0.046275947242975,0.078151755034924,-0.515742003917694,41203,-2580,-5150,-6317,1.06156349182129 +39807,0.046860199421644,0.079416640102863,-0.511761844158173,41203,-2545,-4818,-3776,1.05847120285034 +39809,0.051591794937849,0.07205256819725,-0.509690999984741,41203,-3014,-4242,-6266,1.05244469642639 +39811,0.051785949617624,0.071731187403202,-0.510822355747223,41203,-2610,-4625,-3789,1.0465714931488 +39813,0.047359135001898,0.068337455391884,-0.514355957508087,41203,-2310,-4498,-6339,1.0421028137207 +39815,0.042659763246775,0.067797891795635,-0.517699539661408,41203,-2148,-4582,-3855,1.03755414485931 +39817,0.045841731131077,0.059633869677782,-0.51562774181366,41203,-2849,-4041,-6374,1.03988230228424 +39819,0.053077921271324,0.040044106543064,-0.511878669261932,41203,-3172,-2845,-3834,1.04066622257233 +39821,0.049571510404348,0.034745547920466,-0.508757591247559,41203,-2444,-3863,-6312,1.04053199291229 +39823,0.042196165770292,0.036717720329762,-0.509102582931519,41203,-1989,-4356,-3833,1.04225993156433 +39825,0.035714220255613,0.048272702842951,-0.512641131877899,41203,-2025,-5299,-6376,1.05028128623962 +39827,0.034949295222759,0.036232773214579,-0.512695372104645,41203,-2373,-3364,-3877,1.05645537376404 +39829,0.025687763467431,0.033476997166872,-0.508062183856964,41203,-1681,-4046,-6340,1.05359375476837 +39831,0.022476878017187,0.020805099979043,-0.506454169750214,41203,-2029,-3109,-3852,1.04599726200104 +39833,0.01706731133163,0.014773546718061,-0.507900714874268,41203,-1830,-3524,-6441,1.0350501537323 +39835,0.003520401660353,0.010666438378394,-0.506989181041718,40685,-1024,-3582,-3961,1.02519297599792 +39837,-0.003254138631746,0.00148071476724,-0.505435407161713,40685,-1412,-3084,-6436,1.01872026920319 +39839,0.000563079025596,-0.000299095059745,-0.499913215637207,40685,-2225,-3591,-3935,1.01885902881622 +39841,0.008577384985983,-0.015338626690209,-0.496833860874176,40685,-2659,-2392,-6357,1.01755142211914 +39843,0.001069389050826,-0.023895161226392,-0.499721378087997,40685,-1424,-2759,-3956,1.02317404747009 +39845,-0.013212343677878,-0.043418005108833,-0.497959166765213,40685,-696,-1600,-6393,1.03359758853912 +39847,-0.019915262237191,-0.057348642498255,-0.492833822965622,40685,-1173,-1873,-3931,1.04151487350464 +39849,-0.023570125922561,-0.060979261994362,-0.492547422647476,40685,-1268,-2419,-6351,1.05245673656464 +39851,-0.025365047156811,-0.05834299698472,-0.496388584375382,40685,-1431,-3014,-3976,1.06324756145477 +39853,-0.030680933967233,-0.054579567164183,-0.498688727617264,40685,-1016,-3017,-6445,1.0575475692749 +39855,-0.03195483237505,-0.058795336633921,-0.497570723295212,40685,-1356,-2488,-4007,1.05110859870911 +39857,-0.036471288651228,-0.055224783718586,-0.494221031665802,40685,-967,-2963,-6415,1.04465532302856 +39859,-0.034536983817816,-0.060752276331186,-0.490139812231064,40685,-1529,-2336,-3977,1.03391909599304 +39861,-0.025938550010324,-0.066312953829765,-0.488269567489624,40685,-2071,-2105,-6365,1.0223126411438 +39863,-0.031646698713303,-0.074739418923855,-0.487375289201736,40685,-1009,-1893,-3978,1.0247939825058 +39865,-0.03230868652463,-0.088881246745586,-0.485724866390228,40685,-1287,-1092,-6356,1.02849996089935 +39887,-0.01804518327117,-0.05943276360631,-0.476513415575027,40685,-1872,-2348,-4023,1.02032101154327 +39889,-0.020364552736282,-0.053559020161629,-0.474023342132568,40685,-1280,-2853,-6336,1.01669347286224 +39891,-0.022354507818818,-0.057133384048939,-0.4710992872715,40685,-1307,-2213,-4004,1.02054357528687 +39893,-0.017644640058279,-0.066949218511582,-0.468567132949829,40685,-1808,-1482,-6290,1.02184224128723 +39895,-0.004486071877182,-0.077740266919136,-0.466966986656189,40685,-2637,-1365,-3993,1.02663695812225 +39897,0.007030897773802,-0.077890902757645,-0.465759366750717,40685,-2684,-1960,-6275,1.03407287597656 +39899,0.009155671112239,-0.059959530830383,-0.46504732966423,40685,-2042,-3638,-3997,1.0388023853302 +39901,0.00396357383579,-0.047555550932884,-0.46589195728302,40685,-1433,-3316,-6293,1.03951895236969 +39903,-0.000101398800325,-0.042078994214535,-0.46464130282402,40685,-1463,-2976,-4011,1.0371595621109 +39905,-7.89285259088501E-05,-0.038025993853808,-0.459924608469009,40685,-1746,-2846,-6239,1.03614282608032 +39907,0.006202735472471,-0.038545824587345,-0.454972475767136,40685,-2291,-2574,-3960,1.0321991443634 +39909,0.005578052252531,-0.036516185849905,-0.454208701848984,40148,-1791,-2702,-6187,1.0312488079071 +39911,0.002829984296113,-0.03840583562851,-0.454106241464615,40148,-1595,-2456,-3969,1.02694666385651 +39913,0.006953537464142,-0.038897257298231,-0.450763136148453,40148,-2149,-2458,-6161,1.02976930141449 +39915,0.018409239128232,-0.045518230646849,-0.450686126947403,40148,-2836,-1991,-3960,1.03205120563507 +39917,0.024938011541963,-0.03585521876812,-0.456291913986206,40148,-2612,-3216,-6241,1.03286445140839 +39919,0.026205871254206,-0.029175907373428,-0.459157317876816,40148,-2225,-3156,-4034,1.03816306591034 +39921,0.024590715765953,-0.021004360169172,-0.455148667097092,40148,-2026,-3337,-6243,1.03807878494263 +39923,0.017699526622892,-0.006913633551449,-0.4515041410923,40148,-1525,-3992,-3996,1.03944194316864 +39925,0.016397831961513,-0.004153471440077,-0.451797127723694,40148,-1928,-3210,-6218,1.04091894626617 +39927,0.016563512384892,0.008633585646749,-0.45479741692543,40148,-2018,-4115,-4034,1.04088032245636 +39929,0.023335309699178,0.00475407904014,-0.454054355621338,40148,-2627,-2875,-6259,1.03651201725006 +39931,0.015000231564045,0.010267233476043,-0.451630800962448,40148,-1393,-3615,-4027,1.03311359882355 +39933,0.007124818395823,-0.002650128910318,-0.448586165904999,40148,-1319,-2100,-6209,1.03144204616547 +39935,0.000311130163027,-0.007153934799135,-0.449379026889801,40148,-1292,-2641,-4026,1.02977120876312 +39937,-0.00226771296002,-0.007404218893498,-0.451404750347138,40148,-1545,-2925,-6257,1.0287458896637 +39939,-0.006044172216207,-0.005530868656933,-0.4523566365242,40148,-1414,-3113,-4061,1.02803611755371 +39941,-0.002063292544335,-0.003446702379733,-0.450258731842041,40148,-2010,-3155,-6258,1.02536952495575 +39943,0.003995560109615,-0.010110963135958,-0.448599338531494,40148,-2258,-2430,-4049,1.02633106708527 +39945,0.002703774953261,-0.009476519189775,-0.447690963745117,40148,-1708,-2946,-6242,1.02903616428375 +39947,0.004770445637405,-0.02116976864636,-0.44797158241272,40148,-1981,-1902,-4059,1.03009819984436 +39949,0.001175471348688,-0.019836520776153,-0.449256986379623,40148,-1511,-2814,-6275,1.03058767318726 +39951,0.000970473920461,-0.0170454736799,-0.447996288537979,40148,-1760,-2985,-4074,1.02986407279968 +39953,-0.004584671929479,0.004644844215363,-0.449545115232468,40148,-1269,-4659,-6292,1.02737212181091 +39955,-0.002930831862614,0.023786224424839,-0.453102469444275,40148,-1831,-4739,-4123,1.02566111087799 +39957,0.006976872682571,0.027883052825928,-0.45019918680191,40148,-2562,-3773,-6314,1.02394044399261 +39959,0.017489625141025,0.025872796773911,-0.444857329130173,40148,-2757,-3261,-4081,1.02042400836945 +39961,0.023486275225878,0.015853758901358,-0.447174429893494,40148,-2552,-2566,-6293,1.01803183555603 +39963,0.025903588160873,0.019693510606885,-0.454311102628708,40148,-2304,-3592,-4160,1.01525270938873 +39965,0.026444111019373,0.018504014238715,-0.454915642738342,40148,-2213,-3246,-6399,1.01784455776215 +39967,0.027129275724292,0.016351275146008,-0.452583491802216,40148,-2205,-3117,-4163,1.02260339260101 +39969,0.028971284627915,0.007806774228811,-0.453732639551163,40148,-2355,-2548,-6400,1.02885866165161 +39971,0.030632620677352,0.004779771436006,-0.453604906797409,40148,-2334,-2886,-4185,1.0334939956665 +39973,0.034469392150641,0.01669636555016,-0.452596515417099,40148,-2596,-4161,-6402,1.03354394435883 +39975,0.034730169922114,0.01841127127409,-0.448174089193344,40148,-2303,-3424,-4163,1.03287327289581 +39977,0.034497451037169,0.011676176451147,-0.445298969745636,40148,-2318,-2743,-6330,1.02938306331635 +39979,0.035522785037756,-0.001336170244031,-0.444363415241242,40148,-2380,-2086,-4151,1.02872502803803 +39981,0.036394249647856,0.001428510760888,-0.440453380346298,40148,-2441,-3247,-6286,1.02268838882446 +39983,0.03918195143342,0.009588754735887,-0.433477610349655,40148,-2572,-3753,-4134,1.01927900314331 +39985,0.038000721484423,0.010008045472205,-0.427962929010391,39791,-2336,-3215,-6198,1.01953113079071 +39987,0.023765064775944,0.013610952533782,-0.428681761026382,39791,-1144,-3482,-4115,1.02067220211029 +39989,0.019522333517671,0.013499362394214,-0.430300652980804,39791,-1831,-3236,-6240,1.02555978298187 +39991,0.028500825166702,0.014225163497031,-0.429694294929504,39791,-2882,-3285,-4136,1.02377080917358 +39993,0.038438942283392,0.005314591340721,-0.427442997694016,39791,-3162,-2481,-6220,1.02471578121185 +39995,0.035772979259491,0.011671235784888,-0.426628112792969,39791,-2166,-3650,-4129,1.02273178100586 +39997,0.036740824580193,0.004320709500462,-0.422137826681137,39791,-2506,-2576,-6171,1.02320873737335 +39999,0.045309089124203,-0.003872763831168,-0.420249253511429,39791,-3122,-2383,-4098,1.02144420146942 +40001,0.053671680390835,-0.001386785181239,-0.421213150024414,39791,-3329,-3183,-6173,1.02028262615204 +40003,0.064728952944279,-0.004242261406034,-0.424957811832428,39791,-3601,-2755,-4143,1.02046573162079 +40005,0.06351238489151,0.00220155576244,-0.427385985851288,39791,-2828,-3518,-6259,1.01624500751495 +40007,0.058107353746891,0.000979337957688,-0.422554492950439,39791,-2354,-2943,-4141,1.01397514343262 +40009,0.054905038326979,0.005655483808368,-0.419866442680359,39791,-2572,-3440,-6184,1.00871229171753 +40011,0.06540259718895,-0.004957547876984,-0.416003465652466,39791,-3621,-2182,-4108,1.01007521152496 +40013,0.069040484726429,0.001407020143233,-0.412519156932831,39791,-3314,-3488,-6110,1.00903952121735 +40015,0.074903562664986,-0.000516976288054,-0.410459667444229,39791,-3454,-2863,-4082,1.01365613937378 +40017,0.082007110118866,-0.006847290322185,-0.409319370985031,39791,-3806,-2447,-6083,1.01751470565796 +40019,0.084204569458962,-0.00449138507247,-0.406835049390793,39791,-3361,-3106,-4068,1.02460610866547 +40021,0.083240121603012,-0.004526457283646,-0.405933171510696,39791,-3287,-2933,-6054,1.02997076511383 +40023,0.086225293576717,0.004062798805535,-0.404451876878738,39255,-3483,-3670,-4062,1.02898228168488 +40025,0.090443812310696,0.00077699002577,-0.400598734617233,39255,-3811,-2781,-6001,1.0327570438385 +40027,0.080091550946236,0.002374243689701,-0.398068606853485,39255,-2479,-3142,-4027,1.02465510368347 +40029,0.079495519399643,-0.015416195616126,-0.396570086479187,39255,-3324,-1465,-5963,1.02273333072662 +40031,0.080171719193459,-0.025200149044395,-0.398510932922363,39255,-3305,-1919,-4039,1.0214284658432 +40033,0.077031426131725,-0.027811387553811,-0.392781466245651,39255,-3143,-2330,-5927,1.0241619348526 +40035,0.069255463778973,-0.035194713622332,-0.386835277080536,39255,-2578,-1929,-3967,1.02037370204926 +40037,0.060678463429213,-0.037428956478834,-0.383021742105484,39255,-2521,-2184,-5819,1.02054214477539 +40039,0.053611125797033,-0.0379125662148,-0.378856301307678,39255,-2433,-2361,-3919,1.0237033367157 +40041,0.051771361380816,-0.031235264614225,-0.376078277826309,39255,-2886,-2902,-5743,1.02398121356964 +40043,0.056221775710583,-0.043378923088312,-0.376296907663345,39255,-3319,-1427,-3907,1.02746295928955 +40045,0.049204859882593,-0.039912674576044,-0.378395736217499,39255,-2496,-2512,-5776,1.02375483512878 +40047,0.04645860940218,-0.038002323359251,-0.375596582889557,39255,-2687,-2488,-3908,1.02801084518433 +40049,0.039136376231909,-0.038957644253969,-0.371267169713974,39255,-2332,-2183,-5698,1.02636349201202 +40051,0.02363975904882,-0.039755761623383,-0.365113466978073,39255,-1465,-2245,-3840,1.02650761604309 +40053,0.012421158142388,-0.049346644431353,-0.362753838300705,39255,-1633,-1360,-5601,1.02363777160645 +40055,0.005701025947928,-0.047966700047255,-0.362365752458572,39255,-1843,-2253,-3825,1.0141669511795 +40057,-0.001876858761534,-0.04400472342968,-0.357590466737747,39255,-1661,-2392,-5543,1.00971627235413 +40059,-0.019749581813812,-0.029497541487217,-0.35470986366272,39255,-678,-3431,-3774,1.00314521789551 +40061,-0.029124215245247,-0.045426450669766,-0.351102858781815,39255,-1076,-919,-5469,1.00187838077545 +40063,-0.035597391426563,-0.048217937350273,-0.348794281482697,39255,-1253,-1896,-3735,0.994746088981628 +40065,-0.041942674666643,-0.040675304830074,-0.34421294927597,39255,-1062,-2652,-5389,0.994190156459808 +40067,-0.052949991077185,-0.035151496529579,-0.340596616268158,39255,-657,-2653,-3679,0.990736901760101 +40069,-0.060648325830698,-0.033409796655178,-0.337899535894394,39255,-633,-2330,-5315,0.992358148097992 +40071,-0.066285699605942,-0.040185406804085,-0.337466418743134,39255,-820,-1677,-3656,0.994198977947235 +40073,-0.078541330993176,-0.036658853292465,-0.335095435380936,39255,18,-2383,-5280,0.991552233695984 +40075,-0.090597845613957,-0.037898950278759,-0.328513890504837,39255,27,-2082,-3594,0.992904245853424 +40077,-0.106463007628918,-0.024852080270648,-0.322658598423004,39255,773,-3236,-5132,0.991369366645813 +40079,-0.106163896620274,-0.035717975348234,-0.318199217319488,39255,-582,-1405,-3519,0.993900239467621 +40081,-0.10715626180172,-0.04049663245678,-0.317249953746796,39255,-224,-1683,-5065,0.989247262477875 +40083,-0.11215927451849,-0.034234873950482,-0.313666522502899,39255,-63,-2628,-3484,0.994999825954437 +40085,-0.121689528226852,-0.032861962914467,-0.310396879911423,39255,677,-2225,-4979,0.998766958713532 +40087,-0.124392457306385,-0.035785686224699,-0.308949589729309,39255,7,-1925,-3446,1.0045473575592 +40089,-0.126977041363716,-0.040904514491558,-0.304687261581421,39255,321,-1612,-4906,1.01516616344452 +40091,-0.132826685905457,-0.027714531868696,-0.301563918590546,39255,415,-3171,-3389,1.02085328102112 +40093,-0.131987065076828,-0.027090940624476,-0.296480774879456,39255,217,-2225,-4802,1.02275907993317 +40095,-0.131400510668755,-0.029152881354094,-0.293196856975555,39255,32767,-32767,-3324,1.01957201957703 +40097,-0.124275229871273,-0.040693044662476,-0.289635211229324,39255,30150,-7472,-4714,1.01756012439728 +40099,-0.118364728987217,-0.039070583879948,-0.287427455186844,39255,30091,-8531,-3275,1.00985074043274 +40117,0.291094422340393,-0.103424899280071,-0.299260407686234,39255,18732,-6920,-4788,1.0219920873642 +40119,0.394058078527451,-0.111006081104279,-0.296049445867538,39255,17243,-6983,-3295,1.01557195186615 +40121,0.506648600101471,-0.126500636339188,-0.296078532934189,39255,14020,-5965,-4742,1.00716197490692 +40123,0.630877077579498,-0.145385265350342,-0.294702142477035,39255,12391,-5678,-3278,1.00384879112244 +40125,0.761978983879089,-0.155464872717857,-0.293659389019012,39255,8551,-5881,-4704,1.00569677352905 +40127,0.902371942996979,-0.160573735833168,-0.29464390873909,39255,7286,-6433,-3269,1.01379132270813 +40129,1.04872906208038,-0.176996201276779,-0.294069617986679,39255,2685,-5051,-4697,1.02199959754944 +40131,1.19760572910309,-0.185731083154678,-0.289389967918396,39255,2256,-5786,-3225,1.03183007240295 +40133,1.35591471195221,-0.211786597967148,-0.279323697090149,39255,-3415,-3753,-4613,1.03131544589996 +40135,1.50874257087708,-0.225760847330093,-0.268091112375259,39147,-2821,-4793,-3175,1.03719711303711 +40137,1.66762983798981,-0.241456016898155,-0.259114921092987,39147,-8913,-3952,-4361,1.03499531745911 +40139,1.81694602966309,-0.246505379676819,-0.253071129322052,39147,-7470,-5074,-3064,1.03783094882965 +40141,1.96565306186676,-0.262574344873428,-0.243643447756767,39147,-13563,-3514,-4159,1.04386007785797 +40143,2.10528349876404,-0.272578179836273,-0.236773788928986,39147,-11533,-4274,-2942,1.0501149892807 +40145,2.24814009666443,-0.297231167554855,-0.233007088303566,39147,-18401,-2251,-4007,1.05727565288544 +40147,2.37587308883667,-0.304842621088028,-0.22873267531395,39147,-15316,-3894,-2874,1.0559287071228 +40149,2.50873470306396,-0.32504865527153,-0.22601780295372,39147,-22730,-2020,-3892,1.05026638507843 +40151,2.62143707275391,-0.327479958534241,-0.225467205047607,39147,-18643,-3837,-2837,1.04612803459167 +40153,2.72577357292175,-0.33870267868042,-0.220419749617577,39147,-25149,-2331,-3790,1.04267954826355 +40155,2.82748126983643,-0.344955384731293,-0.220367267727852,39147,-21802,-3202,-2785,1.03738152980804 +40157,2.9200484752655,-0.355390876531601,-0.220848485827446,39147,-28492,-2004,-3755,1.03064393997192 +40159,2.99041724205017,-0.362757563591003,-0.223419532179832,39147,-22982,-2747,-2790,1.02118968963623 +40161,3.04941296577454,-0.372382581233978,-0.226009383797646,39147,-29299,-1667,-3772,1.01799380779266 +40163,3.09798336029053,-0.386361002922058,-0.228031352162361,39147,-24118,-1807,-2804,1.01276028156281 +40165,3.13194179534912,-0.383552223443985,-0.231457993388176,39147,-30016,-2248,-3792,1.01081788539886 +40167,3.15269374847412,-0.392385303974152,-0.234485805034637,39147,-24111,-1955,-2832,1.01183462142944 +40169,3.16339993476868,-0.395805776119232,-0.234481960535049,39147,-30064,-1459,-3781,1.01486957073212 +40171,3.1725902557373,-0.409200102090836,-0.235982969403267,39147,-24792,-1245,-2909,1.01893794536591 +40173,3.16218662261963,-0.401696354150772,-0.243148446083069,39147,-29740,-1984,-3925,1.02068471908569 +40175,3.14363574981689,-0.401124477386475,-0.250718206167221,39147,-23620,-2212,-2999,1.01865065097809 +40177,3.10074496269226,-0.391745179891586,-0.25463455915451,39147,-27617,-2122,-4031,1.01519751548767 +40179,3.04479718208313,-0.38414677977562,-0.25625205039978,39147,-20731,-2811,-3027,1.01035416126251 +40181,2.98760151863098,-0.381125092506409,-0.258448958396912,39147,-25933,-1687,-4049,1.00822031497955 +40183,2.92605686187744,-0.377465188503265,-0.262171924114227,39147,-19790,-2480,-3057,1.00494933128357 +40185,2.85051894187927,-0.37669187784195,-0.263063251972198,39147,-23516,-1460,-4075,0.999190151691437 +40187,2.76229000091553,-0.374869823455811,-0.261008381843567,39147,-16637,-2243,-3039,0.996171593666077 +40189,2.66064071655273,-0.366760730743408,-0.261008679866791,39147,-19624,-2010,-4028,0.996015548706055 +40191,2.55224657058716,-0.359088927507401,-0.266860872507095,39147,-13206,-2749,-3069,1.00105369091034 +40193,2.44392991065979,-0.351711392402649,-0.272008866071701,39147,-16607,-2059,-4140,1.00180578231812 +40195,2.32934665679932,-0.356764376163483,-0.270520329475403,39147,-10500,-1737,-3085,1.00527834892273 +40197,2.20494604110718,-0.34895396232605,-0.266328483819962,39147,-12454,-1996,-4049,1.00233256816864 +40199,2.07081365585327,-0.336273908615112,-0.263110190629959,39147,-6222,-3166,-3023,0.994319021701813 +40201,1.93351030349731,-0.33108514547348,-0.263446271419525,39147,-7875,-1967,-4008,0.98655378818512 +40203,1.79741501808167,-0.321017682552338,-0.266654670238495,39147,-2868,-3070,-3037,0.983054041862488 +40205,1.66232967376709,-0.308645069599152,-0.26574519276619,39147,-4269,-2721,-4034,0.991784811019897 +40207,1.53118336200714,-0.298301249742508,-0.264027893543243,39147,8,-3297,-3008,0.99449896812439 +40209,1.39760565757751,-0.295852541923523,-0.261395573616028,39147,-32767,5477,-3975,0.997403919696808 +40211,1.27371203899384,-0.312209516763687,-0.253560185432434,39147,-3377,209,-2925,1.00063741207123 +40213,1.14846408367157,-0.316595017910004,-0.251045316457748,39147,-3693,135,-3814,0.998037934303284 +40215,1.02356398105621,-0.310541152954102,-0.252467066049576,39147,-136,-1281,-2904,0.997448563575745 +40217,0.894705057144165,-0.300559312105179,-0.251455307006836,39147,330,-1017,-3816,0.991229295730591 +40219,0.753421306610107,-0.289139986038208,-0.250212728977203,39147,4609,-1840,-2876,0.988245725631714 +40221,0.618496060371399,-0.292932480573654,-0.248480051755905,39147,5014,-16,-3773,0.984833419322968 +40223,0.490835636854172,-0.283713817596436,-0.248285070061684,39147,7222,-1629,-2849,0.981562852859497 +40225,0.375381410121918,-0.283171325922012,-0.248550787568092,39147,7445,-359,-3768,0.986185789108276 +40227,0.262304335832596,-0.275194108486176,-0.247575089335442,39147,9390,-1536,-2831,0.979829490184784 +40229,0.160676196217537,-0.266182601451874,-0.245259955525398,39147,9923,-1120,-3733,0.97482830286026 +40231,0.069884203374386,-0.263193190097809,-0.243183270096779,39147,10585,-1231,-2788,0.97778582572937 +40233,-0.017192585393787,-0.25415113568306,-0.244617372751236,39147,11843,-1198,-3726,0.981509029865265 +40235,-0.093620464205742,-0.256652891635895,-0.246284008026123,39147,12016,-815,-2796,0.993469595909119 +40237,-0.168310165405273,-0.255116313695908,-0.248962849378586,39147,13566,-532,-3765,0.999325573444366 +40239,-0.234730213880539,-0.249070301651955,-0.248361423611641,39147,13509,-1420,-2798,1.00276339054108 +40241,-0.290663123130798,-0.248931273818016,-0.247244998812675,39147,14431,-416,-3743,1.00063359737396 +40243,-0.340424001216888,-0.240247011184692,-0.245289504528046,39147,14076,-1621,-2765,0.996495723724365 +40245,-0.379713118076324,-0.230835571885109,-0.242474749684334,39147,-21108,6318,-3696,0.997738540172577 +40247,-0.407872349023819,-0.224364578723907,-0.242382988333702,39147,7693,-302,-2733,0.997319340705872 +40249,-0.417310059070587,-0.228371649980545,-0.24179595708847,39147,7586,1058,-3680,0.996030807495117 +40251,-0.421773374080658,-0.223016932606697,-0.236200898885727,39147,6438,-121,-2678,0.993832290172577 +40253,-0.425883740186691,-0.20330186188221,-0.230909287929535,39147,7581,-946,-3567,0.9957315325737 +40255,-0.433477014303207,-0.184470042586327,-0.228751108050346,39147,7077,-1532,-2614,1.00173377990723 +40257,-0.434044867753983,-0.172852411866188,-0.230976730585098,39147,7710,-767,-3588,1.00525856018066 +40259,-0.42503148317337,-0.165723204612732,-0.233532875776291,39147,6019,-869,-2635,1.01292335987091 +40261,-0.410325616598129,-0.149353235960007,-0.23076231777668,39147,6479,-1405,-3599,1.02210032939911 +40263,-0.396850377321243,-0.122962616384029,-0.227035567164421,39147,5539,-2781,-2579,1.02506530284882 +40265,-0.38240310549736,-0.106082916259766,-0.223502174019814,39147,6270,-2076,-3545,1.02647948265076 +40267,-0.366459995508194,-0.084935396909714,-0.216655030846596,39147,5156,-2889,-2497,1.02808225154877 +40269,-0.338406801223755,-0.070181995630264,-0.210730627179146,39147,4794,-2455,-3419,1.02552127838135 +40271,-0.305548369884491,-0.048061933368445,-0.210351273417473,39147,3281,-3442,-2442,1.0173727273941 +40273,-0.273144543170929,-0.031215835362673,-0.20868755877018,39147,3626,-3198,-3422,1.01437139511108 +40275,-0.242891162633896,-0.022430146113038,-0.209657594561577,39147,2751,-2826,-2426,1.01368045806885 +40277,-0.213157325983047,-0.011489895172417,-0.212165877223015,39147,3018,-3061,-3472,1.01473319530487 +40279,-0.173926070332527,-0.001591834006831,-0.208361104130745,39147,1275,-3184,-2408,1.01597774028778 +40281,-0.13333386182785,0.018288748338819,-0.203062936663628,39147,1079,-4168,-3383,1.01245701313019 +40283,-0.093987941741943,0.037708334624767,-0.201259478926659,39147,-32767,18115,-2349,1.00913596153259 +40285,-0.048608388751745,0.052123490720987,-0.201744139194489,39147,-6636,-523,-3387,0.998504996299744 +40287,-0.004111545160413,0.062959626317024,-0.200193509459496,39147,-7457,-353,-2332,0.989838123321533 +40289,0.034297291189432,0.076530866324902,-0.196277111768723,39147,-7488,-838,-3336,0.988655388355255 +40291,0.069120928645134,0.097800597548485,-0.19328998029232,39147,-7834,-1582,-2275,0.992895483970642 +40293,0.105841599404812,0.103667765855789,-0.192644461989403,39147,-8560,-727,-3309,0.998007118701935 +40295,0.133369877934456,0.117258332669735,-0.194133296608925,39147,-8284,-1309,-2272,1.00257587432861 +40297,0.149164706468582,0.125976517796516,-0.199209302663803,39147,-7831,-1290,-3397,1.00908243656158 +40299,0.157715663313866,0.14972759783268,-0.203632742166519,39147,-7346,-2510,-2329,1.01462864875793 +40301,0.169519305229187,0.17422553896904,-0.202221065759659,39147,-7956,-3204,-3469,1.01927876472473 +40303,0.17633381485939,0.188441097736359,-0.198698624968529,39147,-7571,-2408,-2290,1.01496350765228 +40305,0.17034175992012,0.205083444714546,-0.196500524878502,39147,-6767,-3181,-3427,1.00420558452606 +40307,0.159329786896706,0.22113698720932,-0.196009635925293,39147,-6131,-3051,-2266,0.994726300239563 +40309,0.151426270604134,0.240752935409546,-0.198531523346901,39147,-6390,-4026,-3480,0.986805140972137 +40311,0.143192872405052,0.262554377317429,-0.199062496423721,39147,-6169,-4116,-2283,0.992373406887054 +40313,0.137880593538284,0.277200043201447,-0.19674876332283,39147,-6424,-4329,-3489,1.00075840950012 +40315,0.131239160895348,0.28857421875,-0.195043191313744,39147,-6177,-3819,-2252,1.00566864013672 +40317,0.115551143884659,0.304151594638824,-0.196493580937386,39147,-5377,-4919,-3508,1.00846993923187 +40319,0.088114015758038,0.332980066537857,-0.197097212076187,39147,-4123,-5797,-2264,1.00904500484467 +40321,0.059312418103218,0.352937340736389,-0.19306106865406,39147,-3579,-6117,-3509,1.00938940048218 +40323,0.038089737296105,0.358401387929916,-0.191990420222282,39147,-3881,-4601,-2227,1.00609612464905 +40325,0.018991420045495,0.35731714963913,-0.195607602596283,39147,-3633,-4792,-3541,0.996822655200958 +40327,-0.008347602561116,0.361996352672577,-0.195748135447502,39147,-2787,-4711,-2252,0.986696302890778 +40329,-0.042897030711174,0.375294148921967,-0.19402514398098,39147,-1510,-6234,-3538,0.978341519832611 +40349,-0.326865494251251,0.334575891494751,-0.18784311413765,39147,2813,-4585,-3415,0.973588407039642 +40351,-0.350494712591171,0.321083873510361,-0.188663646578789,39147,2386,-3553,-2198,0.97211617231369 +40353,-0.371529847383499,0.323469221591949,-0.187325686216354,39147,3469,-5331,-3392,0.97476464509964 +40355,-0.385766983032227,0.31285485625267,-0.184023275971413,39147,2396,-3747,-2162,0.981077671051025 +40357,-0.398248434066772,0.305266350507736,-0.181892037391663,39147,3459,-4428,-3304,0.988567590713501 +40359,-0.412039697170258,0.297063946723938,-0.182593956589699,39147,-32767,-3792,-2805,1.00012969970703 +40361,-0.418552279472351,0.277687340974808,-0.185885712504387,39147,-2548,-3229,-3997,0.999373912811279 +40363,-0.420625925064087,0.269518226385117,-0.187160357832909,39147,-3708,-3487,-2875,0.990374445915222 +40365,-0.42577937245369,0.265742838382721,-0.184319511055946,39147,-2396,-4245,-4002,0.982929527759552 +40367,-0.436682373285294,0.267352938652039,-0.181885480880737,39147,-2705,-4241,-2876,0.976787745952606 +40369,-0.441948711872101,0.251300752162933,-0.177371233701706,39147,-1981,-3214,-3943,0.97292971611023 +40371,-0.452401965856552,0.235226213932037,-0.175429970026016,39147,-2362,-2592,-2867,0.967908322811127 +40373,-0.47158682346344,0.222927510738373,-0.17461371421814,39147,-341,-3096,-3919,0.966232478618622 +40375,-0.496665686368942,0.209596991539001,-0.169102355837822,39147,-513,-2487,-2858,0.969910025596619 +40377,-0.514359354972839,0.191990897059441,-0.162948086857796,39147,413,-2274,-3787,0.976465880870819 +40379,-0.527338266372681,0.169952765107155,-0.158527076244354,39147,-754,-1347,-2817,0.981993913650513 +40381,-0.544986426830292,0.160993710160255,-0.154257297515869,39147,1095,-2438,-3688,0.982644021511078 +40383,-0.561863720417023,0.150587737560272,-0.149034723639488,39147,220,-1941,-2780,0.979785978794098 +40385,-0.575979292392731,0.140354141592979,-0.141321554780006,39147,1552,-2051,-3546,0.974110245704651 +40387,-0.594155788421631,0.133468925952911,-0.134439006447792,39147,994,-1979,-2707,0.975659668445587 +40389,-0.608408868312836,0.120432332158089,-0.131279021501541,39147,2316,-1559,-3437,0.979513823986053 +40391,-0.616697371006012,0.114530079066753,-0.129164695739746,39147,843,-1801,-2695,0.981559455394745 +40393,-0.61957186460495,0.103229008615017,-0.125254154205322,39147,1924,-1430,-3375,0.985039293766022 +40395,-0.631079733371735,0.095945484936237,-0.121274091303349,39147,-32767,-1452,-2663,0.984208941459656 +40397,-0.639061510562897,0.070942632853985,-0.113630376756191,39147,-3248,63,-3234,0.987317502498627 +40399,-0.637641370296478,0.046814043074846,-0.105479769408703,39147,-5178,456,-2575,0.985462963581085 +40401,-0.637787401676178,0.041988171637058,-0.10006807744503,39147,-3646,-912,-3070,0.987248957157135 +40403,-0.649232804775238,0.044869583100081,-0.09597559273243,39147,-3898,-1440,-2526,0.987358450889587 +40405,-0.665543675422668,0.051285944879055,-0.094703108072281,39147,-1840,-1865,-3031,0.987815201282501 +40407,-0.68107795715332,0.051700066775084,-0.095992252230644,39147,-2942,-1356,-2543,0.984806597232819 +40409,-0.700374722480774,0.053354777395725,-0.097308643162251,39147,-837,-1555,-3079,0.980623364448547 +40411,-0.720564723014831,0.047512542456389,-0.09552063792944,39147,-1816,-844,-2557,0.978902220726013 +40413,-0.739938080310822,0.045876186341047,-0.091195046901703,39147,54,-1193,-3019,0.977347254753113 +40415,-0.761752367019653,0.04864851385355,-0.088654436171055,39147,-860,-1471,-2525,0.972034692764282 +40417,-0.779338598251343,0.051369450986385,-0.086268343031406,39147,829,-1587,-2980,0.967705190181732 +40419,-0.79967325925827,0.06283961981535,-0.080222070217133,39147,-153,-2293,-2482,0.965520560741425 +40421,-0.816229701042175,0.066457979381085,-0.074025459587574,39147,1619,-1897,-2859,0.966480195522308 +40423,-0.833865344524383,0.06860862672329,-0.068224266171455,39147,431,-1711,-2413,0.965998947620392 +40425,-0.855390071868897,0.062206279486418,-0.063983671367169,39147,2892,-1125,-2748,0.967991173267364 +40427,-0.869682013988495,0.062751710414887,-0.062023457139731,39147,1010,-1516,-2382,0.96293181180954 +40429,-0.880153238773346,0.069786794483662,-0.062482424080372,39147,2810,-2226,-2746,0.959615647792816 +40431,-0.896397769451141,0.074044272303581,-0.061335694044829,39147,1852,-1952,-2388,0.959608912467956 +40433,-0.918113946914673,0.084491446614266,-0.055329967290163,39147,4560,-2720,-2680,0.963720321655273 +40435,-0.937855064868927,0.08892384916544,-0.050074588507414,39147,3037,-2194,-2321,0.968722522258758 +40437,-0.951168894767761,0.096084237098694,-0.047209441661835,39147,4841,-2690,-2600,0.970804512500763 +40439,-0.961706638336181,0.108276180922985,-0.043211784213781,39147,3077,-3048,-2283,0.974977970123291 +40441,-0.960999488830566,0.108615137636662,-0.039706192910671,39147,4347,-2426,-2525,0.982341945171356 +40443,-0.958100080490112,0.112576328217983,-0.037701141089201,39147,2426,-2547,-2253,0.987341940402985 +40445,-0.957233488559723,0.12042348831892,-0.034618634730578,39147,4633,-3188,-2478,0.991754770278931 +40447,-0.963012874126434,0.143158286809921,-0.028881426900625,39147,3483,-4364,-2200,0.996075987815857 +40449,-0.95681369304657,0.150040611624718,-0.024743020534515,39147,4599,-3643,-2381,1.00402438640594 +40451,-0.944574475288391,0.156800776720047,-0.024940578266978,39147,2292,-3463,-2179,1.00350606441498 +40453,-0.933209359645844,0.169766694307327,-0.026069812476635,39147,4204,-4448,-2411,1.00081074237823 +40455,-0.922919452190399,0.18177130818367,-0.024613054469228,39147,2478,-4254,-2184,0.995163857936859 +40457,-0.910465478897095,0.191535532474518,-0.021843440830708,39147,4113,-4630,-2375,0.991840660572052 +40459,-0.894511282444,0.19245371222496,-0.020729381591082,39147,2015,-3679,-2163,0.991598308086395 +40461,-0.877757430076599,0.200164839625359,-0.019897745922208,39147,3619,-4695,-2359,0.993522644042969 +40463,-0.859267234802246,0.204329207539558,-0.01765213534236,39147,1665,-4154,-2148,0.998459339141846 +40465,-0.839661717414856,0.202146828174591,-0.015636069700122,39147,3128,-4096,-2312,1.00053179264069 +40467,-0.825757801532745,0.202025547623634,-0.011366421356797,39147,1837,-3888,-2110,1.0038195848465 +40469,-0.809447646141052,0.206697389483452,-0.008622035384178,39147,3187,-4734,-2232,1.00393867492676 +40471,-0.785492837429047,0.215994998812675,-0.007608101237565,39147,851,-4839,-2088,0.999358057975769 +40473,-0.757432341575623,0.213668242096901,-0.005684376694262,39147,1792,-4425,-2200,0.996453821659088 +40475,-0.731898128986358,0.222127079963684,-0.003904213663191,39147,258,-4948,-2066,0.994084477424622 +40477,-0.704859972000122,0.219508394598961,0.000704146979842,39147,1286,-4584,-2127,0.993051469326019 +40479,-0.681609332561493,0.216583237051964,0.003030128544196,39147,-33,-4137,-2020,0.994200646877289 +40481,-0.659943878650665,0.214405938982964,0.004026545211673,39147,1198,-4609,-2085,0.996900498867035 +40501,-0.420363992452622,0.209828346967697,0.011369971558452,39147,-1584,-4128,-1986,0.969744980335236 +40503,-0.403196007013321,0.209035485982895,0.012456327676773,39147,-2436,-4684,-1958,0.973455309867859 +40505,-0.383186399936676,0.195976734161377,0.014376270584762,39147,-2093,-4035,-1943,0.978669166564941 +40507,-0.377489686012268,0.191529721021652,0.015004147775471,39147,-1854,-4249,-1939,0.980692327022552 +40509,-0.370732426643372,0.178227320313454,0.017339000478387,39147,-1226,-3808,-1899,0.981146514415741 +40511,-0.363522350788116,0.169992670416832,0.020361695438624,39147,-2040,-3740,-1901,0.980192840099335 +40513,-0.359444886445999,0.164540007710457,0.021199386566877,39147,-1100,-4218,-1845,0.98456734418869 +40515,-0.349479198455811,0.150564670562744,0.020265894010663,39147,-2321,-3116,-1899,0.984399557113647 +40517,-0.333343744277954,0.1384496986866,0.017595510929823,39147,-2267,-3370,-1876,0.979236423969269 +40519,-0.319836318492889,0.130995765328407,0.014645495451987,39147,-2891,-3355,-1935,0.973354279994965 +40521,-0.317234814167023,0.136416345834732,0.01417787745595,39147,-1445,-4637,-1913,0.961913824081421 +40523,-0.316465735435486,0.124156169593334,0.013370394706726,39147,-1923,-2963,-1942,0.959353744983673 +40525,-0.316443175077438,0.110549442470074,0.007815743796527,39147,-1173,-2895,-1977,0.959689319133758 +40527,-0.324399471282959,0.106545709073544,0.001325413351879,39147,-1080,-3341,-2024,0.964917957782745 +40529,-0.325647354125977,0.10476341843605,-0.00213796691969,39147,-836,-3691,-2091,0.963842689990997 +40531,-0.321275800466537,0.107885465025902,0.001120401313528,39147,-1900,-3908,-2026,0.962812781333923 +40533,-0.32257804274559,0.098027229309082,0.006224445998669,39147,-772,-3047,-1990,0.960032641887665 +40535,-0.334098130464554,0.096756309270859,0.007076332811266,39147,-470,-3470,-1984,0.959139943122864 +40537,-0.344654649496078,0.087084442377091,0.005868387874216,39147,366,-2915,-1989,0.960701942443848 +40539,-0.355057328939438,0.085431590676308,0.002246113261208,39147,-130,-3311,-2016,0.957972228527069 +40541,-0.367166489362717,0.081461228430271,-5.89912015129812E-05,39147,956,-3258,-2056,0.959824740886688 +40543,-0.371870338916779,0.066777534782887,0.002912255935371,39147,-167,-2138,-2011,0.960439026355743 +40545,-0.373408675193787,0.057273350656033,0.004536280874163,39147,426,-2492,-1994,0.961698830127716 +40547,-0.375851511955261,0.054514300078154,0.003721616463736,39147,-140,-2834,-2005,0.964608728885651 +40549,-0.381983935832977,0.067156463861466,0.004503114148974,39147,1034,-4255,-1996,0.967830181121826 +40551,-0.384441912174225,0.060715179890394,0.008324395865202,39147,122,-2680,-1972,0.968406558036804 +40553,-0.387202948331833,0.054164741188288,0.006215134169906,39147,1018,-2681,-1970,0.968360722064972 +40555,-0.38895782828331,0.052483063191176,0.002957204123959,39147,279,-2917,-2008,0.972273826599121 +40557,-0.3872349858284,0.049558278173208,0.00095175311435,39147,839,-2873,-2030,0.969587326049805 +40559,-0.386098921298981,0.054920580238104,-0.00287645123899,39147,174,-3468,-2047,0.967926859855652 +40561,-0.386640876531601,0.059421382844448,-0.004004275426269,39147,892,-3610,-2055,0.96358186006546 +40563,-0.394526869058609,0.061198614537716,-0.007278081960976,39147,1516,-3081,-2128,0.965148210525513 +40565,-0.400044769048691,0.06551206111908,-0.011724955402315,39147,1141,-3584,-2109,0.966652035713196 +40567,-0.400044769048691,0.06551206111908,-0.011724955402315,39147,1141,-3584,-2109,0.966652035713196 +40569,-0.398882925510406,0.06862610578537,-0.018691001459956,39147,597,-3131,-2159,0.980493068695068 +40571,-0.397273808717728,0.062452379614115,-0.019217673689127,39147,1595,-2945,-2273,0.9793341755867 +40573,-0.39542829990387,0.058226481080055,-0.018977658823133,39147,852,-2913,-2164,0.97897082567215 +40575,-0.393124520778656,0.078712865710259,-0.020619450137019,39147,1624,-5134,-2295,0.978293776512146 +40577,-0.393124520778656,0.078712865710259,-0.020619450137019,39147,1624,-5134,-2295,0.978293776512146 +40579,-0.381844699382782,0.0895821377635,-0.020472602918744,39147,1547,-4115,-2298,0.974402844905853 +40581,-0.378151506185532,0.087023563683033,-0.020915493369103,39147,769,-3506,-2184,0.974329173564911 +40583,-0.374000400304794,0.090472251176834,-0.020643269643188,39147,1474,-4184,-2303,0.973304212093353 +40585,-0.373103946447372,0.09874976426363,-0.022900274023414,39147,1041,-4487,-2201,0.976958572864532 +40587,-0.373103946447372,0.09874976426363,-0.022900274023414,39147,1041,-4487,-2201,0.976958572864532 +40589,-0.372847884893417,0.098653808236122,-0.024063482880592,39147,1219,-3853,-2213,0.975689828395844 +40591,-0.367257237434387,0.092510625720024,-0.022173274308443,39147,1559,-3590,-2327,0.972036361694336 +40593,-0.36457622051239,0.100649356842041,-0.022940712049604,39147,1081,-4578,-2208,0.970062136650085 +40595,-0.356576085090637,0.104674972593784,-0.025650365278125,39147,1341,-4555,-2373,0.975259602069855 +40597,-0.356576085090637,0.104674972593784,-0.025650365278125,39147,1341,-4555,-2373,0.975259602069855 +40599,-0.324350267648697,0.10795808583498,-0.032658584415913,39147,438,-4671,-2460,0.981108367443085 +40601,-0.310361087322235,0.111573100090027,-0.035658720880747,39147,-243,-4495,-2305,0.979385197162628 +40603,-0.29720264673233,0.123114973306656,-0.038674030452967,39147,258,-5485,-2538,0.976787328720093 +40605,-0.284435451030731,0.121896870434284,-0.040345005691052,39147,-414,-4347,-2344,0.976022720336914 +40607,-0.285037338733673,0.133687198162079,-0.038888480514288,39147,1166,-5719,-2548,0.975126326084137 +40609,-0.285469174385071,0.131119668483734,-0.037354923784733,39147,656,-4437,-2330,0.972335636615753 +40611,-0.286474615335464,0.133334755897522,-0.039779685437679,39147,1318,-5077,-2564,0.966233253479004 +40613,-0.278479009866714,0.134126290678978,-0.043114267289639,39147,62,-4775,-2376,0.966723620891571 +40615,-0.267298072576523,0.127459272742271,-0.042169470340014,39147,242,-4407,-2598,0.965343773365021 +40617,-0.259597212076187,0.127963468432426,-0.041914992034435,39147,-84,-4719,-2375,0.966115295886993 +40619,-0.258279502391815,0.128648966550827,-0.041995167732239,39147,913,-5012,-2602,0.972565174102783 +40621,-0.254020839929581,0.133916616439819,-0.041602712124586,39147,182,-5201,-2380,0.974343180656433 +40623,-0.242018148303032,0.126266419887543,-0.041622534394264,39147,-22,-4431,-2604,0.97124171257019 +40625,-0.235912546515465,0.123176790773869,-0.045081824064255,39147,-115,-4503,-2410,0.970055818557739 +40627,-0.22889918088913,0.115202702581882,-0.047224055975676,39147,209,-4275,-2675,0.970484256744385 +40629,-0.219327792525291,0.109552554786205,-0.048407200723887,39147,-514,-4173,-2441,0.969647943973541 +40631,-0.210547596216202,0.104352191090584,-0.047395512461662,39147,-127,-4355,-2683,0.971268832683563 +40633,-0.204625591635704,0.101248487830162,-0.047357313334942,39147,-382,-4282,-2442,0.970205068588257 +40635,-0.201431959867477,0.108604393899441,-0.05200744047761,39147,200,-5371,-2745,0.976840615272522 +40655,-0.160647585988045,0.039096340537071,-0.061421882361174,39147,-381,-2656,-2890,0.984434127807617 +40657,-0.166587650775909,0.039539340883494,-0.059848163276911,39147,319,-3824,-2579,0.983267962932587 +40659,-0.168314144015312,0.03333992138505,-0.059167236089707,39004,392,-3318,-2872,0.980547964572906 +40661,-0.167338073253632,0.027880450710654,-0.060285672545433,39004,-102,-3246,-2592,0.979017853736877 +40663,-0.164481565356255,0.024454116821289,-0.061262503266335,39004,64,-3384,-2905,0.981412887573242 +40665,-0.163535892963409,0.019420942291617,-0.063548751175404,39004,-93,-3164,-2624,0.985678553581238 +40667,-0.159239649772644,0.019195174798369,-0.065952055156231,39004,-58,-3540,-2970,0.98871785402298 +40669,-0.1533512622118,0.009136078879237,-0.064965039491654,39004,-533,-2663,-2644,0.994007289409637 +40671,-0.15347857773304,0.004393116105348,-0.065850131213665,39004,229,-2977,-2978,0.994000971317291 +40673,-0.149442210793495,-0.004930354189128,-0.069571413099766,39004,-398,-2513,-2686,0.991355359554291 +40675,-0.15027491748333,0.005971895996481,-0.076313532888889,39004,288,-4116,-3113,0.989512741565704 +40677,-0.149141371250153,0.009563291445374,-0.07752937078476,39004,-136,-3645,-2754,0.981497704982758 +40679,-0.150009483098984,-0.003240750171244,-0.078163467347622,39004,342,-2268,-3147,0.967165946960449 +40681,-0.155552312731743,-0.010568167082965,-0.080671824514866,39004,492,-2570,-2788,0.95418792963028 +40683,-0.158891409635544,-0.011875261552632,-0.081308990716934,39004,721,-2948,-3196,0.948994159698486 +40685,-0.159168154001236,-0.006292182020843,-0.080429144203663,39004,229,-3548,-2799,0.955246269702911 +40687,-0.155318066477776,-0.008897760882974,-0.079644076526165,39004,212,-2896,-3190,0.964452505111694 +40689,-0.153421059250832,-0.006265136878937,-0.080108299851418,39004,53,-3330,-2810,0.969602644443512 +40691,-0.149613335728645,-0.009097173810005,-0.082350268959999,39004,171,-2873,-3235,0.972147405147552 +40693,-0.148972392082214,0.000290178781142,-0.087881080806255,39004,136,-3902,-2877,0.971547842025757 +40695,-0.148647502064705,0.011458761058748,-0.089979775249958,39004,443,-4203,-3340,0.97493702173233 +40697,-0.14578415453434,0.004578416235745,-0.086299911141396,38879,-13,-2800,-2881,0.973423600196838 +40699,-0.151117220520973,-0.002494250657037,-0.084397472441197,38879,949,-2663,-3288,0.973444879055023 +40701,-0.155700623989105,-0.016377614811063,-0.087010480463505,38879,718,-1993,-2900,0.967530727386475 +40703,-0.156485989689827,-0.011355858296156,-0.091549023985863,38879,788,-3386,-3386,0.964238166809082 +40705,-0.153689354658127,-0.009381392039359,-0.094579696655274,38879,224,-3221,-2967,0.967833697795868 +40707,-0.160930246114731,0.007436581887305,-0.097719207406044,38879,1389,-4533,-3475,0.979692339897156 +40709,-0.161189049482346,0.014772244729102,-0.09938009083271,38879,616,-3952,-3016,0.987933158874512 +40711,-0.161074236035347,0.017160646617413,-0.100840650498867,38879,921,-3657,-3529,0.986730933189392 +40713,-0.159009337425232,0.024255836382508,-0.10144405066967,38879,484,-4076,-3047,0.985456645488739 +40715,-0.156876012682915,0.027677297592163,-0.100242882966995,38879,765,-3907,-3539,0.985811591148376 +40717,-0.156673982739449,0.032437119632959,-0.099446028470993,38879,646,-4035,-3050,0.985585808753967 +40719,-0.156394690275192,0.025711951777339,-0.102067708969116,38879,959,-3158,-3577,0.981852054595947 +40721,-0.157518997788429,0.026560470461845,-0.103691838681698,38879,817,-3679,-3096,0.977821409702301 +40723,-0.154529765248299,0.017090259119868,-0.101563550531864,38879,804,-2823,-3588,0.978188097476959 +40725,-0.15575934946537,0.024237053468824,-0.104480311274529,38879,863,-4101,-3118,0.97766101360321 +40727,-0.152630627155304,0.021492928266525,-0.106101877987385,38879,826,-3382,-3659,0.976697444915772 +40729,-0.154953643679619,0.02593183144927,-0.103782005608082,38879,994,-3938,-3131,0.9708331823349 +40731,-0.159920960664749,0.031462583690882,-0.101453885436058,38879,1581,-4149,-3621,0.970813393592834 +40733,-0.158763974905014,0.024898471310735,-0.10136566311121,38879,865,-3146,-3131,0.969966053962708 +40735,-0.156260490417481,0.024917718023062,-0.101098097860813,38879,1063,-3658,-3634,0.972479999065399 +40737,-0.153454333543777,0.021946499124169,-0.101199217140675,38879,738,-3369,-3147,0.976197719573975 +40739,-0.151504904031754,0.032885041087866,-0.100170582532883,38879,1097,-4574,-3640,0.979672968387604 +40741,-0.1421759724617,0.019754266366363,-0.096008315682411,38879,175,-2621,-3128,0.976294815540314 +40743,-0.143002524971962,0.020414954051375,-0.094027519226074,38879,1225,-3640,-3583,0.974734127521515 +40745,-0.138771653175354,0.016023442149162,-0.090619288384914,38879,554,-3198,-3107,0.977576434612274 +40747,-0.137663692235947,0.016218200325966,-0.087861426174641,38879,1058,-3539,-3526,0.974748730659485 +40749,-0.134430423378944,0.010935048572719,-0.089555867016316,38879,624,-3064,-3114,0.973461329936981 +40751,-0.12973764538765,0.007302255369723,-0.090314127504826,38879,719,-3132,-3569,0.966120660305023 +40753,-0.127391621470451,0.017493741586804,-0.090895161032677,38879,642,-4267,-3138,0.958175718784332 +40755,-0.123512625694275,0.0177231580019,-0.091400064527989,38879,725,-3589,-3597,0.960224092006683 +40757,-0.118241250514984,0.016767520457506,-0.092428356409073,38879,353,-3465,-3164,0.961566209793091 +40759,-0.105136878788471,0.007587199099362,-0.093941077589989,38879,-187,-2761,-3643,0.966320693492889 +40761,-0.100517816841602,0.024023871868849,-0.095390185713768,38879,189,-4818,-3200,0.969575822353363 +40763,-0.088467217981815,0.026421574875712,-0.095883950591087,38879,-339,-3894,-3682,0.975002825260162 +40765,-0.08303914219141,0.02537845261395,-0.097180061042309,38879,-82,-3596,-3229,0.975690066814423 +40767,-0.0806984603405,0.022409567609429,-0.092395596206188,38879,272,-3445,-3656,0.97666347026825 +40769,-0.083771891891956,0.025459788739681,-0.091565437614918,38879,571,-3897,-3206,0.979301571846008 +40771,-0.081014275550842,0.029299503192306,-0.096366368234158,38879,279,-4053,-3719,0.986703157424927 +40773,-0.074821978807449,0.026152459904552,-0.097101211547852,38879,-186,-3473,-3260,0.994287312030792 +40775,-0.066581420600414,0.027919603511691,-0.099556930363178,38879,-314,-3897,-3773,0.996193051338196 +40777,-0.055733643472195,0.025054195895791,-0.100050061941147,38879,-765,-3487,-3297,0.995981931686401 +40779,-0.052249662578106,0.028125569224358,-0.102218821644783,38879,-180,-4000,-3821,0.98987603187561 +40781,-0.045547094196081,0.013969210907817,-0.101821467280388,38879,-592,-2529,-3326,0.986059129238129 +40783,-0.042076423764229,0.016033621504903,-0.100329697132111,38879,-329,-3735,-3816,0.982481241226196 +40785,-0.039890721440315,0.018720846623182,-0.095958329737187,38879,-333,-3807,-3303,0.974917829036713 +40787,-0.038629584014416,0.017135301604867,-0.097460143268108,38879,-213,-3502,-3799,0.962713360786438 +40789,-0.03596306592226,0.018637537956238,-0.100670464336872,38879,-409,-3727,-3352,0.959727048873901 +40791,-0.035772293806076,0.018636617809534,-0.099753484129906,38879,-166,-3650,-3843,0.964290618896484 +40793,-0.031987763941288,0.016078285872936,-0.100674197077751,38879,-532,-3406,-3369,0.974454164505005 +40795,-0.025997968390584,0.004533739294857,-0.103786699473858,38879,-725,-2594,-3907,0.984660744667053 +40797,-0.026011660695076,0.008554935455322,-0.107031658291817,38879,-335,-3769,-3430,0.987610816955566 +40799,-0.020271046087146,0.013956018723548,-0.105589553713799,38879,-801,-3963,-3946,0.987914085388184 +40801,-0.016831317916513,0.02736059576273,-0.103866919875145,38879,-708,-4716,-3426,0.98543906211853 +40803,-0.013137398287654,0.022748295217753,-0.101480327546597,38879,-770,-3389,-3916,0.983856678009033 +40805,-0.014528057537973,0.019364416599274,-0.102697938680649,38879,-393,-3406,-3436,0.975340962409973 +40807,-0.016960883513093,0.021209601312876,-0.101657710969448,38879,-253,-3833,-3935,0.972121894359589 +40809,-0.015903295949102,0.020299041643739,-0.099057845771313,38879,-543,-3603,-3428,0.964687168598175 +40811,-0.019217936322093,0.025991210713983,-0.095604605972767,38879,-140,-4195,-3881,0.968600690364838 +40813,-0.019871154800058,0.028760408982635,-0.093217626214027,38879,-355,-3997,-3404,0.976438522338867 +40815,-0.02202202565968,0.034225717186928,-0.097480848431587,38879,-173,-4320,-3919,0.978318393230438 +40817,-0.025206448510289,0.027789102867246,-0.102498963475227,38879,-88,-3335,-3484,0.979715168476105 +40819,-0.029952043667436,0.026788434013724,-0.099724799394608,38879,143,-3746,-3963,0.980776071548462 +40821,-0.0245222710073,0.009192693047225,-0.095159098505974,38879,-704,-2277,-3451,0.983541905879974 +40823,-0.023393897339702,0.009450842626393,-0.097638532519341,38879,-376,-3564,-3955,0.983564555644989 +40825,-0.023666420951486,0.011140597052872,-0.098486818373203,38879,-300,-3688,-3491,0.982001900672913 +40827,-0.030808938667178,0.015930313616991,-0.096298046410084,38879,347,-3998,-3955,0.977198839187622 +40829,-0.042019464075565,0.020412296056748,-0.090727426111698,38879,758,-4026,-3454,0.980688631534576 +40831,-0.051541168242693,0.011731117032468,-0.087667599320412,38879,878,-2966,-3869,0.976642429828644 +40833,-0.061007715761662,0.004736787173897,-0.091744258999825,38879,928,-2982,-3476,0.97271454334259 +40835,-0.065079219639301,-0.008085181936622,-0.093252651393414,38879,721,-2345,-3951,0.972034394741058 +40837,-0.070284172892571,-0.009885828010738,-0.09358511120081,38879,783,-3137,-3504,0.969132244586945 +40839,-0.067776739597321,-0.024835370481014,-0.092601642012596,38879,314,-1917,-3959,0.968807101249695 +40841,-0.075237229466438,-0.015032597817481,-0.089133463799954,38879,1043,-3882,-3490,0.972793817520142 +40843,-0.074002042412758,-0.017035119235516,-0.083505235612393,38879,535,-2961,-3867,0.975521385669708 +40845,-0.073068179190159,-0.025099730119109,-0.082035608589649,38879,441,-2448,-3455,0.973046541213989 +40847,-0.070352368056774,-0.035801570862532,-0.083310194313526,38879,406,-2024,-3879,0.975579798221588 +40849,-0.074426449835301,-0.035941645503044,-0.086566686630249,38879,849,-2842,-3501,0.978988885879517 +40851,-0.083374731242657,-0.031756434589624,-0.088609479367733,38879,1494,-3128,-3956,0.984778225421906 +40853,-0.089982509613037,-0.039884306490421,-0.086269952356815,38879,1291,-2196,-3514,0.978923380374908 +40855,-0.092026710510254,-0.036225453019142,-0.086238600313664,38879,1181,-3001,-3943,0.968853771686554 +40857,-0.093474574387074,-0.035754315555096,-0.088846445083618,38879,1014,-2851,-3547,0.965412259101868 +40859,-0.094265595078468,-0.033668838441372,-0.088537164032459,38879,1166,-2907,-3986,0.962383925914764 +40861,-0.083079643547535,-0.054710764437914,-0.084891706705093,38879,2,-1018,-3534,0.963807642459869 +40863,-0.080034449696541,-0.05868873000145,-0.086508616805077,38879,696,-2044,-3976,0.962329268455505 +40865,-0.080149918794632,-0.051244221627712,-0.087495878338814,38879,805,-3078,-3567,0.966788589954376 +40867,-0.085114292800427,-0.042236745357514,-0.087240636348724,38879,1385,-3225,-3999,0.970983862876892 +40885,-0.062006369233132,-0.043933663517237,-0.093979805707932,38879,779,-2722,-3687,0.986591637134552 +40887,-0.058199685066938,-0.04635127261281,-0.091754794120789,38879,495,-2200,-4129,0.995695531368256 +40889,-0.056554239243269,-0.048139106482267,-0.089713871479035,38879,540,-2307,-3673,0.995036721229553 +40891,-0.055013552308083,-0.040318407118321,-0.089490823447704,38879,623,-3009,-4118,0.996051609516144 +40893,-0.048257645219565,-0.034276150166988,-0.085213541984558,38879,79,-3044,-3657,0.993525445461273 +40895,-0.039867755025625,-0.027432410046458,-0.084806576371193,38879,-90,-3126,-4077,0.992450714111328 +40897,-0.032757941633463,-0.032780438661575,-0.08714184910059,38879,-149,-2232,-3685,0.995541512966156 +40899,-0.033013910055161,-0.025225913152099,-0.087339535355568,38879,451,-3190,-4121,0.992765069007874 +40901,-0.020755246281624,-0.032925706356764,-0.082712523639202,38879,-672,-2043,-3669,0.991439700126648 +40903,-0.014801844954491,-0.023700473830104,-0.081013590097427,38879,-268,-3315,-4061,0.993159472942352 +40905,-0.009430945850909,-0.025368142873049,-0.07869578897953,38879,-331,-2566,-3655,0.994874358177185 +40907,-0.01507633458823,-0.022750789299607,-0.077058464288712,38879,574,-2833,-4028,0.99372410774231 +40909,-0.009785198606551,-0.025943174958229,-0.075888879597187,38879,-310,-2431,-3648,0.99042820930481 +40911,-0.005520809441805,-0.02737476490438,-0.073567770421505,38879,-291,-2451,-3999,0.986274480819702 +40913,-0.009210783056915,-0.017031604424119,-0.075462639331818,38879,329,-3509,-3658,0.98584258556366 +40915,-0.007094461470842,-0.018943196162582,-0.076330773532391,38879,-125,-2544,-4044,0.988160192966461 +40917,-0.000591043033637,-0.023092310875654,-0.076265700161457,38879,-521,-2369,-3676,0.990947008132935 +40919,0.006647114641964,-0.02552992105484,-0.076315879821777,38879,-721,-2396,-4057,0.991860449314117 +40921,0.002384966006503,-0.007770288735628,-0.078833684325218,38879,202,-4143,-3707,0.990779757499695 +40923,0.007789856288582,-0.006103202700615,-0.077766731381416,38879,-613,-3003,-4087,0.99093222618103 +40925,0.012632773257792,0.000526469899341,-0.077668890357018,38879,-602,-3460,-3712,0.991614460945129 +40927,0.017297424376011,-0.00458261044696,-0.079292364418507,38879,-714,-2532,-4118,0.985040843486786 +40929,0.017747169360519,-0.004324534907937,-0.078618600964546,38879,-369,-2928,-3732,0.975304484367371 +40931,0.018289312720299,-0.002264743437991,-0.073568731546402,38879,-431,-3071,-4063,0.974003076553345 +40933,0.020673435181379,-0.001238695927896,-0.071151956915856,38879,-557,-3022,-3693,0.975754499435425 +40935,0.020854197442532,0.004231126047671,-0.075893558561802,38879,-437,-3411,-4103,0.983367085456848 +40937,0.017454113811255,0.000411819753936,-0.078835010528565,38879,-102,-2694,-3759,0.988357305526733 +40939,0.010249184444547,0.006862285546958,-0.074341930449009,38879,267,-3515,-4098,0.992832005023956 +40941,0.013191822916269,-0.004209647420794,-0.069337978959084,38879,-494,-2105,-3706,0.996476769447327 +40943,0.013870979659259,-0.00539858546108,-0.070068277418614,38879,-375,-2769,-4060,0.997182309627533 +40945,0.014863885007799,-0.014792231842876,-0.067449204623699,38879,-383,-2065,-3705,0.999248206615448 +40947,0.010917434468865,-0.013761213049293,-0.068613797426224,38879,-16,-2788,-4055,0.995527744293213 +40949,0.012297688052058,-0.023920461535454,-0.071402192115784,38879,-380,-1868,-3744,0.987645328044891 +40951,0.007993180304766,-0.029120851308107,-0.071917355060577,38879,53,-2085,-4106,0.977611005306244 +40953,-0.003027656814083,-0.02648701146245,-0.070909336209297,38879,723,-2731,-3753,0.976463615894318 +40955,-0.009849845431745,-0.033491641283035,-0.069382846355438,38879,531,-1864,-4088,0.978464543819428 +40957,-0.006163385231048,-0.037202198058367,-0.069510906934738,38879,-279,-2103,-3755,0.974921524524689 +40959,-0.003328787395731,-0.043982986360788,-0.069524072110653,38879,-254,-1687,-4102,0.974311828613281 +40961,-0.013232417404652,-0.033662293106318,-0.068562738597393,38879,799,-3135,-3760,0.978102385997772 +40963,-0.017741870135069,-0.04071606323123,-0.067468732595444,38879,513,-1686,-4089,0.980284154415131 +40965,-0.020839456468821,-0.043361067771912,-0.068865641951561,38879,431,-2042,-3774,0.982455492019653 +40967,-0.019310813397169,-0.050168950110674,-0.070163704454899,38879,112,-1525,-4132,0.98722231388092 +40969,-0.026323882862926,-0.049229729920626,-0.071006022393704,38879,801,-2185,-3800,0.990339875221252 +40971,-0.032893761992455,-0.050563089549542,-0.069669134914875,38879,922,-1888,-4139,0.996824145317077 +40973,-0.033101938664913,-0.058505527675152,-0.067217364907265,38879,427,-1387,-3786,0.998928308486938 +40975,-0.036722112447023,-0.051961813122034,-0.066000148653984,38879,798,-2401,-4107,1.00276291370392 +40977,-0.033470116555691,-0.062421724200249,-0.062281642109156,38879,204,-1121,-3764,1.00294315814972 +40979,-0.031026003882289,-0.06515584141016,-0.058680456131697,38879,284,-1491,-4032,1.00108397006989 +40981,-0.029948590323329,-0.071276694536209,-0.055559739470482,38879,325,-1269,-3727,0.995581686496735 +40983,-0.035003058612347,-0.062268704175949,-0.057911679148674,38879,901,-2343,-4033,0.990117013454437 +40985,-0.035514198243618,-0.067673318088055,-0.065150544047356,38879,536,-1338,-3803,0.985510766506195 +40987,-0.046797294169664,-0.061579756438732,-0.070183485746384,38879,1559,-2110,-4188,0.988034784793854 +40989,-0.0523118712008,-0.062420658767223,-0.067278422415257,38879,1158,-1706,-3830,0.998216331005096 +40991,-0.051273435354233,-0.063431635499001,-0.065045326948166,38879,783,-1530,-4139,1.00132155418396 +40993,-0.053409531712532,-0.059311710298061,-0.061781115829945,38879,959,-2069,-3803,1.00883138179779 +40995,-0.056154489517212,-0.060775138437748,-0.057415466755629,38879,1161,-1502,-4060,1.00558185577393 +40997,-0.061375100165606,-0.055401310324669,-0.053453128784895,38879,1324,-2179,-3756,0.999226570129394 +40999,-0.062687128782272,-0.062773145735264,-0.051970213651657,38879,1180,-1013,-4006,1.00073528289795 +41001,-0.065759055316448,-0.056425262242556,-0.053722761571407,38879,1263,-2198,-3767,1.00396287441254 +41003,-0.060446575284004,-0.058844227343798,-0.053833145648241,38879,693,-1395,-4037,0.999226689338684 +41005,-0.062055736780167,-0.049919094890356,-0.051115818321705,38879,1134,-2441,-3758,0.996963083744049 +41007,-0.060129553079605,-0.057124231010676,-0.049383148550987,38879,964,-1049,-3993,0.993155896663666 +41009,-0.063956707715988,-0.061327956616879,-0.054325185716152,38879,1349,-1303,-3789,0.987839341163635 +41011,-0.064712427556515,-0.059825636446476,-0.060251463204622,38879,1269,-1593,-4131,0.988601446151733 +41013,-0.066573522984982,-0.049428749829531,-0.061580285429955,38879,1278,-2484,-3849,0.98473334312439 +41015,-0.06810063123703,-0.033474016934633,-0.056997206062079,38879,1417,-3024,-4102,0.986149787902832 +41017,-0.061462573707104,-0.038327381014824,-0.051728684455156,38879,631,-1526,-3792,0.989923357963562 +41019,-0.054783340543509,-0.040943495929241,-0.049483273178339,38879,642,-1547,-4023,0.992853760719299 +41021,-0.048496540635824,-0.050043638795614,-0.048973388969898,38879,499,-1026,-3781,0.992688536643982 +41023,-0.049296334385872,-0.046028826385737,-0.052593141794205,38879,1114,-1911,-4069,0.996807873249054 +41025,-0.045890066772699,-0.049916509538889,-0.05264425650239,38879,694,-1371,-3816,1.00306916236877 +41027,-0.047388687729836,-0.035606030374765,-0.05164622887969,38879,1153,-2791,-4067,1.01049625873566 +41029,-0.043269623070955,-0.028951728716493,-0.051879908889532,38879,629,-2402,-3819,1.01883614063263 +41031,-0.040828812867403,-0.019970409572125,-0.052271831780672,38879,786,-2640,-4083,1.01812589168549 +41033,-0.041958998888731,-0.005801672581583,-0.049624294042587,38879,1008,-3254,-3813,1.01774668693542 +41035,-0.041620947420597,-0.000475466513308,-0.049074586480856,38879,965,-2686,-4053,1.01003074645996 +41037,-0.03879576548934,0.009919394738972,-0.050195347517729,38879,700,-3201,-3825,1.01069808006287 +41039,-0.0243847258389,0.00880884192884,-0.049378838390112,38879,-298,-2363,-4065,1.00976860523224 +41041,-0.014682522043586,0.014374122954905,-0.048433110117912,38879,-124,-2914,-3822,1.00436556339264 +41043,-0.00257754442282,0.003194100921974,-0.044572006911039,38879,-464,-1543,-4017,0.998088777065277 +41045,-0.006209997460246,0.01138208527118,-0.043285313993692,38879,716,-3051,-3794,0.999269127845764 +41047,-0.00791687797755,0.003228729590774,-0.044565252959728,38879,619,-1746,-4025,1.00210404396057 +41049,-0.012032771483064,-0.000449118611868,-0.049552846699953,38879,843,-2022,-3845,1.00545632839203 +41051,-0.005987742450088,-0.009630985558033,-0.053878404200077,38879,38,-1447,-4144,1.00698673725128 +41053,-0.00697691552341,-0.009646022692323,-0.053387209773064,38879,554,-2137,-3881,1.0039986371994 +41055,-0.012696428224444,-0.001984654692933,-0.051641900092363,38879,987,-2767,-4126,1.00493025779724 +41057,-0.009029572829604,-0.002610006602481,-0.052876397967339,38879,258,-2182,-3887,1.00025045871735 +41059,-0.007509160786867,0.008853517472744,-0.05419285222888,38879,384,-3215,-4165,0.997182190418243 +41061,-0.004524101037532,0.015797944739461,-0.054925657808781,38879,248,-2983,-3910,0.993331849575043 +41063,-0.00394834857434,0.028362482786179,-0.050835143774748,38879,391,-3619,-4134,0.993205308914185 +41065,0.001542736426927,0.020045993849635,-0.045002955943346,38879,-16,-1955,-3851,0.99003279209137 +41067,0.003257735399529,0.021911410614848,-0.047079268842936,38879,198,-2746,-4099,0.989100694656372 +41069,0.003561862744391,0.010651784017682,-0.045866072177887,38879,325,-1611,-3865,0.983399569988251 +41071,-0.003094821702689,0.002749554580078,-0.043191216886044,38879,911,-1730,-4061,0.974161744117737 +41073,-0.011089747771621,0.001422110828571,-0.042183484882116,38879,1134,-2182,-3847,0.978693842887878 +41075,-0.014820449054241,0.003385337069631,-0.04509523883462,38879,907,-2438,-4092,0.981699645519257 +41077,-0.016070507466793,0.016524938866496,-0.045307256281376,38879,733,-3427,-3877,0.992518544197082 +41079,-0.010526420548558,0.008786055259407,-0.044228650629521,38879,196,-1816,-4090,1.00175881385803 +41081,-0.01086041238159,0.001439994317479,-0.043935772031546,38879,604,-1737,-3875,1.00570058822632 +41083,-0.009283191524446,-0.014400978572667,-0.044516477733851,38879,465,-848,-4101,1.01001787185669 +41085,-0.009902250021696,-0.010393557138741,-0.045895710587502,38879,621,-2363,-3897,1.01488971710205 +41087,-0.001959659392014,-0.017101600766182,-0.046266954392195,38879,-114,-1446,-4130,1.01337134838104 +41089,-0.00328724924475,-0.012668514624238,-0.047496739774942,38879,581,-2344,-3916,1.00846493244171 +41091,-0.004888313356787,-0.022559583187103,-0.04629897326231,38879,617,-1121,-4138,1.00194549560547 +41093,-0.013844653964043,-0.022458648309112,-0.043773621320725,38879,1284,-1875,-3898,0.998004794120789 +41095,-0.01503991894424,-0.018798796460033,-0.043009955435991,38879,763,-2138,-4108,0.997608721256256 +41097,-0.009514139965177,-0.01801972091198,-0.0426215082407,38879,194,-1970,-3898,0.996300876140594 +41119,0.041338533163071,-0.054147489368916,-0.052592664957047,38879,-746,-1012,-4271,1.01317763328552 +41121,0.042732071131468,-0.046926163136959,-0.052790302783251,38879,-303,-1833,-4019,1.00619721412659 +41123,0.049456082284451,-0.047957126051188,-0.051636695861817,38879,-911,-1126,-4269,1.00202703475952 +41125,0.052471917122603,-0.034136459231377,-0.050391800701618,38879,-581,-2460,-4012,0.998618543148041 +41127,0.060080267488957,-0.041065134108067,-0.049466576427221,38879,-1162,-787,-4252,0.992709457874298 +41129,0.054798796772957,-0.031406342983246,-0.051268141716719,38879,-45,-2174,-4027,0.988205015659332 +41131,0.051953822374344,-0.033125516027212,-0.050650734454393,38879,-296,-1262,-4275,0.9881312251091 +41133,0.046585343778133,-0.027330556884408,-0.052437376230955,38879,57,-1932,-4044,0.994240522384644 +41135,0.051363077014685,-0.031822573393583,-0.053465414792299,38879,-850,-1051,-4318,1.00001633167267 +41137,0.052274446934462,-0.027630258351565,-0.049738552421332,38879,-494,-1788,-4035,0.998121023178101 +41139,0.045468855649233,-0.011637541465461,-0.049614172428846,38879,48,-2818,-4281,0.999571859836578 +41141,0.046336054801941,-0.008956546895206,-0.052983082830906,38879,-424,-1930,-4066,1.00033831596375 +41143,0.053606327623129,-0.000199745350983,-0.052319154143334,38879,-1115,-2474,-4321,1.00405693054199 +41145,0.061391398310661,0.006613298784941,-0.049878928810358,38879,-1159,-2438,-4054,1.00599300861359 +41147,0.062937840819359,0.025264136493206,-0.047778654843569,38879,-889,-3602,-4276,1.00831866264343 +41149,0.070526674389839,0.030994724482298,-0.045895036309958,38879,-1305,-2712,-4035,1.00905561447144 +41151,0.072739124298096,0.049059450626373,-0.044383764266968,38879,-1125,-3950,-4244,1.00931668281555 +41153,0.077118173241615,0.055087987333536,-0.044786836951971,38879,-1204,-3091,-4035,1.00129592418671 +41155,0.080750063061714,0.059321280568838,-0.049051746726036,38879,-1386,-3139,-4308,0.991409778594971 +41157,0.080347336828709,0.069954507052899,-0.052916329354048,38879,-944,-3652,-4100,0.990972399711609 +41159,0.081472456455231,0.071339644491673,-0.051991250365973,38879,-1246,-3150,-4352,0.993715226650238 +41161,0.07833756506443,0.087223790585995,-0.046560153365135,38879,-755,-4299,-4065,1.00278949737549 +41163,0.078483663499355,0.094518676400185,-0.042303174734116,38879,-1149,-3971,-4246,1.01049494743347 +41165,0.080921560525894,0.109210252761841,-0.042810831218958,38879,-1223,-4562,-4047,1.01379954814911 +41167,0.092922680079937,0.107194229960442,-0.046674016863108,38879,-2271,-3543,-4306,1.01605367660522 +41169,0.096099987626076,0.117035359144211,-0.046141762286425,38879,-1533,-4366,-4078,1.01963758468628 +41171,0.104835256934166,0.114217579364777,-0.040820576250553,38879,-2284,-3644,-4244,1.01680457592011 +41173,0.108112551271915,0.11418604105711,-0.045874580740929,38879,-1760,-3660,-4084,1.0095351934433 +41175,0.10934080183506,0.106965057551861,-0.053395908325911,38879,-1876,-3264,-4401,1.00310480594635 +41177,0.098897576332092,0.108651958405972,-0.051833998411894,38879,-696,-3746,-4134,0.996417224407196 +41179,0.082902669906616,0.115180730819702,-0.04894945025444,38879,-267,-4429,-4358,0.991658210754394 +41181,0.072673857212067,0.105812706053257,-0.045286141335964,38879,-376,-2959,-4098,0.990974009037018 +41183,0.067279428243637,0.097359910607338,-0.041935369372368,38879,-805,-3110,-4284,0.989067792892456 +41185,0.062145289033651,0.080982133746147,-0.040568705648184,38879,-622,-2139,-4073,0.99015885591507 +41187,0.04688211157918,0.082892373204231,-0.040861550718546,38879,208,-3647,-4279,0.995313286781311 +41189,0.032623395323753,0.074659988284111,-0.041907656937838,38879,431,-2662,-4090,0.999501705169678 +41191,0.012140213511884,0.071329697966576,-0.045024022459984,38879,1134,-3101,-4336,1.00318741798401 +41193,0.000471754465252,0.056212898343802,-0.044987820088863,38879,700,-1928,-4119,1.00767374038696 +41195,-0.015012020245195,0.050108198076487,-0.047448795288801,38879,1218,-2573,-4372,1.01400935649872 +41197,-0.028784714639187,0.037737879902125,-0.052032683044672,38879,1276,-1874,-4176,1.02573692798615 +41199,-0.041035626083613,0.019014943391085,-0.054963197559118,38879,1422,-1172,-4470,1.0298308134079 +41201,-0.059182580560446,0.006728666834533,-0.054048761725426,38879,2045,-1435,-4200,1.02584278583527 +41203,-0.079468585550785,-0.007801465690136,-0.049559198319912,38879,2654,-1027,-4416,1.01897025108337 +41205,-0.09514857083559,-0.013155337423086,-0.045689385384321,38879,2421,-1633,-4151,1.00827085971832 +41207,-0.099678501486778,-0.033875066787005,-0.040274433791638,38879,1898,-137,-4315,0.998358070850372 +41209,-0.110412001609802,-0.040530499070883,-0.035135500133038,38879,2333,-1122,-4086,0.990326046943665 +41211,-0.124667577445507,-0.059601590037346,-0.028576726093888,38879,3053,190,-4183,0.978441596031189 +41213,-0.152514800429344,-0.064079634845257,-0.021390661597252,38879,4222,-902,-3997,0.964300155639648 +41215,-0.178954109549522,-0.069787450134754,-0.014924084767699,38879,4877,-568,-4027,0.966192781925201 +41217,-0.201744973659515,-0.078233607113361,-0.011812413111329,38879,4651,-374,-3934,0.971445798873901 +41219,-0.224192768335342,-0.086229287087917,-0.010399889200926,38879,5425,-93,-3977,0.981367647647858 +41221,-0.235904037952423,-0.107410073280334,-0.012152350507677,38879,4454,1005,-3939,0.984854936599731 +41223,-0.239393264055252,-0.123864538967609,-0.011972152628005,38790,4410,1175,-3999,0.987890422344208 +41225,-0.232622906565666,-0.152472451329231,-0.005489202216268,38790,3195,2250,-3896,0.995664179325104 +41227,-0.22558020055294,-0.159067913889885,0.002761048031971,38790,3526,1118,-3828,1.00238800048828 +41229,-0.206955075263977,-0.174707427620888,0.005967231467366,38790,2081,1723,-3817,1.00722670555115 +41231,-0.193458423018456,-0.171092450618744,0.003022457705811,38790,2640,663,-3826,1.01008582115173 +41233,-0.169742852449417,-0.178564503788948,-8.37514835438924E-06,38790,1272,1282,-3859,1.01124906539917 +41235,-0.151428520679474,-0.177682682871819,0.001622507581487,38790,1697,1050,-3844,1.01422476768494 +41237,-0.126486629247665,-0.18132920563221,0.005592401605099,38790,634,1139,-3821,1.01261818408966 +41239,-0.094316855072975,-0.182557389140129,0.009540366008878,38790,-150,1374,-3751,1.00771081447601 +41241,-0.069706879556179,-0.16955828666687,0.015142923220992,38790,-108,-128,-3754,1.00677192211151 +41243,-0.047003466635943,-0.169233098626137,0.020761327818036,38790,-202,1140,-3618,1.01067364215851 +41245,-0.022328374907374,-0.1620212495327,0.02256646938622,38790,-766,266,-3701,1.01502478122711 +41247,0.008613617159426,-0.15685510635376,0.025676418095827,38790,-1682,678,-3556,1.01955235004425 +41249,0.034958276897669,-0.129817768931389,0.028665376827121,38790,-1707,-1532,-3655,1.02540481090546 +41251,0.061559442430735,-0.115475326776505,0.031635012477636,38790,-2243,-578,-3481,1.02599358558655 +41273,0.096078760921955,0.153644442558289,0.003387508215383,38790,-350,-5687,-3805,1.05357527732849 +41275,0.083844311535359,0.180825561285019,-0.005176431965083,38790,-107,-6286,-3887,1.05039823055267 +41277,0.068062916398048,0.205280900001526,-0.011379608884454,38790,527,-6145,-3908,1.04718470573425 +41279,0.043009202927351,0.232160210609436,-0.015414510853589,38790,1448,-7174,-4009,1.04049146175385 +41281,0.011389814317227,0.258715391159058,-0.022223630920053,38790,2457,-7156,-3986,1.03466987609863 +41283,-0.027188304811716,0.26963683962822,-0.028082178905606,38790,3559,-6742,-4162,1.03273069858551 +41285,-0.065003789961338,0.283815145492554,-0.031540524214506,38790,4012,-6742,-4055,1.02964162826538 +41287,-0.097570031881332,0.295620143413544,-0.033123504370451,38790,4305,-7349,-4227,1.02938234806061 +41289,-0.123945906758308,0.317209780216217,-0.038602031767368,38790,4086,-7877,-4109,1.02433586120605 +41291,-0.137173280119896,0.329016536474228,-0.038956500589848,38790,3616,-8024,-4301,1.02617621421814 +41293,-0.146523132920265,0.336526840925217,-0.038239281624556,38790,3257,-7288,-4114,1.02411985397339 +41295,-0.153769299387932,0.349366724491119,-0.041461102664471,38790,3521,-8579,-4336,1.02513754367828 +41297,-0.156117767095566,0.361072570085526,-0.046023976057768,34178,2966,-8093,-4175,1.02428531646729 +41299,-0.158876106142998,0.374916464090347,-0.04685589671135,34178,3355,-9234,-4406,1.03138601779938 +41301,-0.158157750964165,0.371695786714554,-0.043957069516182,34178,2851,-7343,-4169,1.04007756710053 +41303,-0.159001529216766,0.371721118688583,-0.045995615422726,34178,3299,-8356,-4403,1.04914855957031 +41305,-0.155009910464287,0.362213850021362,-0.048076014965773,34178,2647,-6923,-4205,1.0551632642746 +41307,-0.154745519161224,0.357173979282379,-0.050356578081846,34178,3230,-7916,-4462,1.05066955089569 +41309,-0.151961967349052,0.334449291229248,-0.056111980229616,34178,2766,-5738,-4269,1.04441869258881 +41311,-0.152866199612618,0.3178371489048,-0.062631621956825,34178,3353,-6600,-4616,1.03558111190796 +41313,-0.146260738372803,0.291130572557449,-0.064465291798115,34178,2485,-4974,-4337,1.03012812137604 +41315,-0.141174882650375,0.267407774925232,-0.066785380244255,34178,2808,-5403,-4677,1.02256894111633 +41317,-0.130905345082283,0.247573554515839,-0.069852508604527,34178,2072,-4961,-4386,1.02219820022583 +41319,-0.121542297303677,0.217238813638687,-0.075482442975044,34178,2247,-4232,-4793,1.02319800853729 +41321,-0.116463743150234,0.194476440548897,-0.08447352796793,34178,2297,-4090,-4499,1.03074657917023 +41323,-0.108373522758484,0.165642082691193,-0.088977344334126,34178,2180,-3583,-4967,1.03151297569275 +41325,-0.10908118635416,0.144146412611008,-0.09529635310173,34178,2661,-3534,-4589,1.02390813827515 +41327,-0.111101746559143,0.114284731447697,-0.099808044731617,34178,3005,-2731,-5112,1.01953899860382 +41329,-0.119374893605709,0.096418797969818,-0.102355860173702,34178,3407,-3160,-4654,1.0165342092514 +41331,-0.118106357753277,0.056196209043264,-0.105123795568943,34178,2942,-1080,-5195,1.01359605789185 +41333,-0.112586237490177,0.030003076419234,-0.105089455842972,34178,2382,-1634,-4691,1.01556634902954 +41335,-0.088292054831982,-0.014753070659936,-0.104549929499626,29709,865,389,-5209,1.01318681240082 +41337,-0.071210585534573,-0.045314878225327,-0.105723015964031,29709,1008,-231,-4714,1.0144145488739 +41339,-0.048872318118811,-0.076778143644333,-0.105386592447758,29709,407,468,-5240,1.01817870140076 +41341,-0.034974470734596,-0.086826175451279,-0.107350178062916,29709,746,-1067,-4743,1.01861786842346 +41343,-0.012793133035302,-0.104860380291939,-0.106655530631542,29709,-149,5,-5275,1.01468753814697 +41345,0.015593689866364,-0.125039979815483,-0.108840145170689,29709,-1005,257,-4772,1.00492918491364 +41347,0.052532702684403,-0.15316079556942,-0.107838578522205,29709,-2274,1572,-5309,1.00199067592621 +41349,0.087598852813244,-0.180779665708542,-0.1091643050313,29709,-2535,1663,-4793,0.992139995098114 +41351,0.120021291077137,-0.210545718669891,-0.108878374099731,29709,-3083,2705,-5343,0.989467144012451 +41353,0.146268859505653,-0.233766868710518,-0.111593507230282,29709,-2795,2208,-4829,0.983659744262695 +41355,0.173152089118958,-0.25494110584259,-0.113382078707218,29709,-3612,2921,-5416,0.977406799793243 +41357,0.187842041254044,-0.274264961481094,-0.113719776272774,29709,-2639,2631,-4863,0.968699038028717 +41359,0.198424220085144,-0.280893832445145,-0.114694580435753,29709,-2943,2430,-5452,0.964201092720032 +41361,0.212652191519737,-0.292282372713089,-0.109865367412567,29709,-3051,2456,-4857,0.957691967487335 +41363,0.211196795105934,-0.295419365167618,-0.103114493191242,29709,-2377,2554,-5333,0.960282862186432 +41365,0.206995248794556,-0.308911949396133,-0.098073974251747,29709,-1744,2988,-4794,0.961018145084381 +41367,0.198120802640915,-0.312965720891953,-0.092638164758682,29709,-1716,3047,-5227,0.960975587368012 +41369,0.197550922632217,-0.318138360977173,-0.088598854839802,29709,-1957,2675,-4745,0.951490163803101 +41371,0.188925728201866,-0.304300278425217,-0.08880190551281,29709,-1667,1772,-5196,0.955470323562622 +41373,0.176876068115234,-0.306694865226746,-0.088759697973728,25223,-921,2459,-4762,0.949835002422333 +41375,0.159157991409302,-0.29240220785141,-0.088132157921791,25223,-606,1699,-5203,0.942964494228363 +41377,0.151256963610649,-0.280069440603256,-0.08642140775919,25223,-921,1166,-4762,0.93546587228775 +41379,0.138947203755379,-0.26170226931572,-0.088987402617931,25223,-726,1046,-5227,0.935354053974152 +41381,0.132255405187607,-0.253693878650665,-0.088303565979004,25223,-795,1228,-4791,0.940279185771942 +41383,0.126467794179916,-0.249663978815079,-0.078125603497028,25223,-1035,2001,-5114,0.939139902591705 +41385,0.133521378040314,-0.253177464008331,-0.069179177284241,25223,-1851,2171,-4673,0.940183043479919 +41387,0.138477012515068,-0.239983528852463,-0.063098534941673,25223,-2052,1311,-4948,0.938664197921753 +41389,0.15315592288971,-0.243249222636223,-0.056457623839378,25223,-2737,2133,-4597,0.93196713924408 +41391,0.16415499150753,-0.224779352545738,-0.050230771303177,25223,-2972,803,-4807,0.931484282016754 +41393,0.173685789108276,-0.230461150407791,-0.049472391605377,25223,-2735,2239,-4558,0.931179940700531 +41395,0.165889516472817,-0.229817882180214,-0.048758391290903,25223,-1728,2270,-4798,0.938100636005402 +41397,0.149671450257301,-0.226429313421249,-0.040362473577261,25223,-619,1648,-4505,0.941463470458984 +41399,0.120165765285492,-0.225270658731461,-0.036867529153824,25223,505,2275,-4665,0.935472011566162 +41401,0.085429236292839,-0.238063126802444,-0.035266272723675,25223,1576,3089,-4477,0.937787532806396 +41403,0.01188097987324,-0.215514808893204,-0.034593537449837,25223,5365,689,-4644,0.976733505725861 +41405,-0.410504311323166,0.137366741895676,0.002785505261272,25223,32767,-28387,-4222,1.20120203495026 +41407,-1.77432692050934,1.25743222236633,0.124139912426472,25223,32767,-32767,-2745,1.7115683555603 +41427,0.750599086284637,0.241395950317383,-0.064928457140923,20736,-10638,-11505,-4847,1.42421579360962 +41429,0.709084570407867,0.225074887275696,-0.038839939981699,20736,-5564,-4496,-4371,1.10313010215759 +41431,0.664185285568237,0.185002326965332,-0.048097491264343,20736,-6101,-2608,-4665,0.86780446767807 +41433,0.673608362674713,0.169594660401344,-0.04919021576643,20736,-9004,-3848,-4450,0.730710387229919 +41435,0.664377510547638,0.158680126070976,-0.02111154794693,20736,-8912,-4344,-4358,0.661762416362762 +41437,0.627263009548187,0.095813192427158,0.007336039096117,20736,-5299,540,-4066,0.614609777927399 +41439,0.594831466674805,0.0712154135108,0.006834309082478,20736,-6406,-1998,-4034,0.618655443191528 +41441,0.577632904052734,0.070630080997944,0.001931395381689,20736,-6279,-3591,-4103,0.655628502368927 +41443,0.541695535182953,0.043295405805111,0.016950754448772,20736,-5569,-1366,-3915,0.679241597652435 +41445,0.511117577552795,-0.015669113025069,0.034642539918423,20736,-4612,1811,-3876,0.685614824295044 +41447,0.474608600139618,-0.071847759187222,0.032494656741619,0,0,0,0,0.724970638751983 +41449,0.462882667779923,-0.094689190387726,0.021697625517845,0,0,0,0,0.73938661813736 +41451,0.444439262151718,-0.114395074546337,0.031650435179472,0,0,0,0,0.752538979053497 +41453,0.417722344398499,-0.149864047765732,0.043833237141371,0,0,0,0,0.769319653511047 +41455,0.393191367387772,-0.177248761057854,0.040179844945669,0,0,0,0,0.774745881557465 +41457,0.364074885845184,-0.182242959737778,0.023778799921274,0,0,0,0,0.775455236434937 +41459,0.351249247789383,-0.159544035792351,0.019145937636495,0,0,0,0,0.774362564086914 +41461,0.328800499439239,-0.150306150317192,0.013383007608354,0,0,0,0,0.776336014270783 +41463,0.306222587823868,-0.143281728029251,0.006582044064999,0,0,0,0,0.765446424484253 +41465,0.258818417787552,-0.129945442080498,-0.011029403656721,0,0,0,0,0.74468332529068 +41467,0.250426381826401,-0.103591971099377,-0.023878771811724,0,0,0,0,0.727062463760376 +41469,0.220544323325157,-0.08087407797575,-0.031556904315949,0,0,0,0,0.712164521217346 +41471,0.198598191142082,-0.07186758518219,-0.045678850263357,0,0,0,0,0.689722299575806 +41473,0.180020570755005,-0.033516403287649,-0.058701325207949,0,0,0,0,0.673854827880859 +41475,0.156361386179924,-0.005244446452707,-0.064401291310787,0,0,0,0,0.663444697856903 +41477,0.128239572048187,0.010293133556843,-0.068047396838665,0,0,0,0,0.653298854827881 +41479,0.086511373519898,0.014140443876386,-0.081093482673168,0,0,0,0,0.658920884132385 +41481,0.063999779522419,0.030463701114059,-0.090234413743019,0,0,0,0,0.657798409461975 +41483,0.034473463892937,0.053434785455465,-0.100684344768524,0,0,0,0,0.658149182796478 +41485,0.022355739027262,0.046059604734182,-0.110826157033443,0,0,0,0,0.647314369678497 +41487,-0.011003993451595,0.040200162678957,-0.120073981583118,0,0,0,0,0.648841857910156 +41489,-0.037708342075348,0.053405087441206,-0.13287265598774,0,0,0,0,0.638338923454285 +41491,-0.06744359433651,0.06277534365654,-0.138373032212257,0,0,0,0,0.629089832305908 +41493,-0.089620009064674,0.080932110548019,-0.144360542297363,0,0,0,0,0.622074544429779 +41495,-0.107724018394947,0.062659330666065,-0.153726845979691,0,0,0,0,0.607577443122864 +41497,-0.125053972005844,0.069768525660038,-0.16133551299572,0,0,0,0,0.594379365444183 +41499,-0.144751161336899,0.05682959780097,-0.170696452260017,0,0,0,0,0.57573527097702 +41501,-0.171154543757439,0.048933457583189,-0.171526715159416,0,0,0,0,0.567485749721527 +41503,-0.202307462692261,0.043632332235575,-0.184108331799507,0,0,0,0,0.571853220462799 +41505,-0.213459312915802,0.034820303320885,-0.189240112900734,0,0,0,0,0.548038423061371 +41507,-0.236775651574135,0.042432244867086,-0.197571516036987,0,0,0,0,0.549529373645783 +41509,-0.246797144412994,0.040219657123089,-0.202896282076836,0,0,0,0,0.535700678825378 +41511,-0.283069849014282,0.02075775898993,-0.209208622574806,0,0,0,0,0.557921767234802 +41513,-0.420570611953735,0.079635426402092,-0.201951399445534,0,0,0,0,0.648216664791107 +41515,-1.09683001041412,0.174370169639587,-0.150925487279892,0,0,0,0,0.876615285873413 +41517,-2.44819235801697,0.198614344000816,-0.06296119093895,0,0,0,0,1.04948055744171 +41519,-3.69397211074829,-0.101705878973007,-0.006904961541295,0,0,0,0,1.24091112613678 +41521,-3.64276242256165,-0.915726244449616,-0.026311809197068,0,0,0,0,1.7305281162262 +41523,-2.25345516204834,-1.5161612033844,-0.126863807439804,0,0,0,0,2.40520524978638 +41525,-0.673352301120758,-1.06632399559021,-0.201032936573029,0,0,0,0,2.78232908248901 +41527,0.289360851049423,-0.15511916577816,-0.195796698331833,0,0,0,0,2.74490141868591 +41529,0.643368601799011,0.41651377081871,-0.174450844526291,0,0,0,0,2.45256066322327 +41531,0.681808114051819,0.563691258430481,-0.155895873904228,0,0,0,0,2.07139611244202 +41533,0.553386449813843,0.451816827058792,-0.146060809493065,0,0,0,0,1.69134616851807 +41535,0.447810381650925,0.364887684583664,-0.166006296873093,0,0,0,0,1.31007266044617 +41537,0.398013561964035,0.331832945346832,-0.183562472462654,0,0,0,0,1.00426137447357 +41539,0.379895955324173,0.31839194893837,-0.177225366234779,0,0,0,0,0.755447089672089 +41541,0.357422888278961,0.29659241437912,-0.182236686348915,0,0,0,0,0.571384787559509 +41543,0.336307436227798,0.253573268651962,-0.18040107190609,0,0,0,0,0.445335537195206 +41545,0.317532747983932,0.25803405046463,-0.182923033833504,0,0,0,0,0.390536099672318 +41547,0.230067312717438,0.201439961791038,-0.195383548736572,0,0,0,0,0.392419159412384 +41549,-0.082224883139134,0.044210221618414,-0.20084622502327,0,0,0,0,0.47927114367485 +41551,-0.577849388122559,-0.248402953147888,-0.215195178985596,0,0,0,0,0.663225829601288 +41553,-0.941851079463959,-0.677713096141815,-0.210244864225388,0,0,0,0,0.904999315738678 +41555,-1.09619092941284,-1.0473747253418,-0.157514959573746,0,0,0,0,1.18939793109894 +41557,-1.0647007226944,-1.17320609092712,-0.068220518529415,0,0,0,0,1.3847188949585 +41559,-0.888834714889526,-1.04183638095856,0.004712991416454,0,0,0,0,1.48136782646179 +41561,-0.681776463985443,-0.820192158222199,0.02801263704896,0,0,0,0,1.48235952854157 +41563,-0.41146582365036,-0.520402371883392,0.00983657874167,0,0,0,0,1.35441517829895 +41565,-0.175340875983238,-0.270904272794723,-0.051272206008434,0,0,0,0,1.18815934658051 +41567,-0.024786673486233,-0.110651053488255,-0.100560046732426,0,0,0,0,0.997394561767578 +41569,0.068480953574181,0.029849303886294,-0.128022432327271,0,0,0,0,0.845064878463745 +41571,0.100557558238506,0.104168258607388,-0.16059809923172,0,0,0,0,0.747183322906494 +41573,0.1508519500494,0.288837254047394,-0.174802139401436,0,0,0,0,0.719443678855896 +41575,0.251379191875458,0.432312339544296,-0.178381696343422,0,0,0,0,0.813410222530365 +41577,0.385412156581879,0.455232828855514,-0.165787070989609,0,0,0,0,0.946064352989197 +41579,0.440398633480072,0.487898766994476,-0.123438835144043,0,0,0,0,1.08778810501099 +41581,0.392029285430908,0.398165762424469,-0.07967833429575,0,0,0,0,1.18063080310822 +41583,0.276987224817276,0.291836857795715,-0.082720659673214,0,0,0,0,1.18903398513794 +41585,0.127755418419838,0.172309055924416,-0.122087903320789,0,0,0,0,1.15608489513397 +41587,0.050684273242951,0.033576857298613,-0.138385429978371,0,0,0,0,1.05897974967957 +41589,-0.01044062897563,0.006084179040045,-0.143028095364571,0,0,0,0,0.980664551258087 +41591,-0.053459987044334,-0.038913059979677,-0.136374250054359,0,0,0,0,0.93128365278244 +41593,-0.048440851271153,-0.059639025479555,-0.089301072061062,0,0,0,0,0.895709037780762 +41595,-0.061866167932749,-0.035326316952705,-0.05493963137269,0,0,0,0,0.958839535713196 +41597,-0.042682986706495,-0.052016194909811,-0.02599822729826,0,0,0,0,1.0254579782486 +41599,-0.015050983987749,-0.031923044472933,0.022748682647944,0,0,0,0,1.05754673480988 +41601,-0.001885494915769,-0.038633994758129,0.03742828220129,0,0,0,0,1.09830188751221 +41603,-0.00062963727396,-0.032099556177855,0.020616022869945,0,0,0,0,1.06143271923065 +41605,-0.048559557646513,-0.001446336740628,-0.011247957125306,0,0,0,0,1.01820802688599 +41607,-0.060458950698376,-0.038500111550093,-0.042795516550541,0,0,0,0,1.00236976146698 +41609,-0.045972712337971,-0.039834048599005,-0.034240636974573,0,0,0,0,0.951344728469849 +41611,-0.067831709980965,-0.051250666379929,-0.01579075306654,0,0,0,0,0.947904646396637 +41613,-0.061610717326403,-0.09791012853384,0.017775949090719,0,0,0,0,0.960283458232879 +41615,-0.069985091686249,-0.077915802598,0.062384836375713,0,0,0,0,0.961234271526337 +41617,-0.093050122261047,-0.104663006961346,0.051742818206549,0,0,0,0,1.00528466701508 +41619,-0.090668827295303,-0.122787222266197,0.023905199021101,0,0,0,0,1.01347148418427 +41621,-0.101038493216038,-0.084943138062954,0.014143140055239,0,0,0,0,1.00706517696381 +41623,-0.095457389950752,-0.126704663038254,-0.016600154340267,0,0,0,0,1.0199955701828 +41625,-0.102403394877911,-0.136320620775223,-0.036773975938559,0,0,0,0,0.988716304302216 +41627,-0.12583090364933,-0.112232618033886,-0.025060772895813,0,0,0,0,0.981041610240936 +41629,-0.104126907885075,-0.147444501519203,-0.004728964529932,0,0,0,0,1.00068473815918 +41631,-0.067698419094086,-0.094330079853535,0.012597399763763,0,0,0,0,0.9993577003479 +41633,-0.033494215458632,-0.008920972235501,0.01178209669888,0,0,0,0,1.00775229930878 +41635,0.005765924230218,-0.015954747796059,0.008816820569336,0,0,0,0,0.997554361820221 +41637,0.005421974696219,0.009928151033819,-0.000782746647019,0,0,0,0,0.987717986106873 +41639,0.000436326721683,0.024904690682888,-0.037285856902599,0,0,0,0,1.01185572147369 +41659,0.065780766308308,0.042510084807873,-0.014907737262547,0,0,0,0,0.992046892642975 +41661,0.036524102091789,0.048158183693886,-0.01653896830976,0,0,0,0,0.974548995494842 +41663,0.022479904815555,0.020865622907877,-0.022831415757537,0,0,0,0,0.998045146465302 +41665,-0.0020936508663,-0.010902185924351,0.010250001214445,0,0,0,0,0.996625423431396 +41667,-0.028763797134161,-0.009403922595084,0.046143688261509,0,0,0,0,0.975704431533814 +41669,-0.029983751475811,-0.0312514975667,0.02506472915411,0,0,0,0,0.98503440618515 +41671,-0.042208131402731,-0.055719196796417,-0.006912144366652,0,0,0,0,0.98932558298111 +41673,-0.057589892297983,-0.036980181932449,-0.006387592293322,0,0,0,0,0.984913289546967 +41675,-0.032143454998732,-0.030024539679289,-0.007595413830131,0,0,0,0,1.00867009162903 +41677,-0.020692981779575,-0.047588538378477,-0.017482372000814,0,0,0,0,1.01046574115753 +41679,-0.047598659992218,-0.039162751287222,-0.015139608643949,0,0,0,0,0.9913569688797 +41681,-0.048270668834448,-0.030774582177401,-0.006251628044993,0,0,0,0,1.00667655467987 +41683,-0.04141266271472,-0.059076603502035,0.012302737683058,0,0,0,0,1.00298571586609 +41685,-0.057163294404745,-0.078976072371006,0.025217898190022,0,0,0,0,0.985265076160431 +41687,-0.061512608081102,-0.070052281022072,0.003757990663871,0,0,0,0,1.0126678943634 +41689,-0.052039287984371,-0.067380115389824,-0.011764019727707,0,0,0,0,1.02804851531982 +41691,-0.028269149363041,-0.04006963968277,0.005998645443469,0,0,0,0,0.995111882686615 +41693,0.007914592511952,0.003602741984651,-0.001825384795666,0,0,0,0,0.979380369186401 +41695,0.015444715507329,0.014929688535631,-0.043405622243881,0,0,0,0,0.995471477508545 +41697,0.001289556501433,0.020610492676497,-0.036436662077904,0,0,0,0,0.993650078773498 +41699,0.022364279255271,0.045146867632866,0.023869628086686,0,0,0,0,0.988394021987915 +41701,0.053596843034029,0.040260564535856,0.050918027758598,0,0,0,0,1.0047265291214 +41703,0.035629823803902,0.021864609792829,0.029186468571425,0,0,0,0,1.00791895389557 +41705,-0.001888170838356,0.03040730394423,0.009995127096772,0,0,0,0,0.997107744216919 +41707,0.001249984954484,0.024853883311153,0.004044731613249,0,0,0,0,1.01271593570709 +41709,0.015358805656433,-0.005406405776739,-0.001892581582069,0,0,0,0,1.02261817455292 +41711,0.007666104007512,-0.001666132942773,-0.018495621159673,0,0,0,0,1.01006531715393 +41713,0.012396608479321,0.030372019857168,-0.040276069194079,0,0,0,0,1.00961852073669 +41715,0.027313940227032,0.027507029473782,-0.029046488925815,0,0,0,0,1.00772213935852 +41717,0.018251579254866,-5.68604918953497E-05,0.01602410338819,0,0,0,0,0.983309030532837 +41719,0.000701883633155,-0.001396992709488,0.034016758203507,0,0,0,0,0.981937170028686 +41721,-0.010984997265041,-0.001519628218375,0.008117563091218,0,0,0,0,1.00509870052338 +41723,-0.031798478215933,-0.031401876360178,-0.000359426659998,0,0,0,0,0.996244251728058 +41725,-0.05448791757226,-0.054388463497162,0.023552436381579,0,0,0,0,0.982018828392029 +41727,-0.05003733932972,-0.061220269650221,0.015253402292729,0,0,0,0,1.00030386447907 +41729,-0.03267427533865,-0.05928747355938,-0.032379344105721,0,0,0,0,1.01600158214569 +41731,-0.016269389539957,-0.022048408165574,-0.054774913936854,0,0,0,0,0.995874524116516 +41733,0.004039000254124,0.027494855225086,-0.030144587159157,0,0,0,0,0.97761607170105 +41735,0.026151740923524,0.033044971525669,0.000922386709135,0,0,0,0,0.987333059310913 +41737,0.025086954236031,0.012059960514307,0.01795849762857,0,0,0,0,0.998025298118591 +41739,0.019489457830787,0.026829097419977,0.026760956272483,0,0,0,0,0.994585037231445 +41741,0.029158342629671,0.045395974069834,0.025211246684194,0,0,0,0,0.994848310947418 +41743,0.027668710798025,0.018636833876371,0.017747409641743,0,0,0,0,0.997755646705627 +41745,-0.001674926257692,-0.016083599999547,0.012523669749498,0,0,0,0,0.99215167760849 +41747,-0.020400920882821,-0.014961128123105,-0.003673013765365,0,0,0,0,0.993704319000244 +41749,-0.008535512723029,-0.002409416483715,-0.033936023712158,0,0,0,0,1.00974321365356 +41751,0.004409219138324,0.000860034604557,-0.035916991531849,0,0,0,0,1.01106798648834 +41753,0.011177376843989,0.015279622748494,0.00532533088699,0,0,0,0,0.992730975151062 +41755,0.031377073377371,0.031379502266646,0.034190744161606,0,0,0,0,0.984565854072571 +41757,0.04046268388629,0.020600248128176,0.014806505292654,0,0,0,0,0.995417475700378 +41759,0.008349601179361,-0.002390679204836,-0.010129763744772,0,0,0,0,1.00300645828247 +41761,-0.031693767756224,-0.003021009033546,-0.002172185573727,0,0,0,0,1.00553023815155 +41763,-0.033967345952988,-0.011424822732806,0.016493121162057,0,0,0,0,1.01012694835663 +41765,-0.024034976959229,-0.051936384290457,0.010222712531686,0,0,0,0,1.0096663236618 +41767,-0.031246341764927,-0.071571677923203,-0.017386715859175,0,0,0,0,1.00411474704742 +41769,-0.032078884541988,-0.03130828589201,-0.04393806681037,0,0,0,0,0.999331891536713 +41771,-0.012614976614714,0.015745345503092,-0.045261263847351,0,0,0,0,0.99809592962265 +41773,0.009400124661624,0.015338195487857,-0.007966955192387,0,0,0,0,0.998328447341919 +41775,0.018826611340046,0.002860843669623,0.037168633192778,0,0,0,0,0.994513630867004 +41777,0.023029966279864,0.012864684686065,0.03874322026968,0,0,0,0,0.995268762111664 +41779,0.023453848436475,0.024103067815304,-8.20597197161987E-05,0,0,0,0,1.00665378570557 +41781,0.014307877980173,0.017135012894869,-0.01756863668561,0,0,0,0,1.00979602336884 +41783,0.00291809043847,0.001590135274455,0.009189965203404,0,0,0,0,0.997224807739258 +41785,0.002714624162763,-0.011721299961209,0.023409860208631,0,0,0,0,0.999168932437897 +41787,0.00081889575813,-0.023901987820864,-0.007959648966789,0,0,0,0,1.01954352855682 +41789,-0.012873540632427,-0.01934870518744,-0.037568885833025,0,0,0,0,1.02559232711792 +41791,-0.014580326154828,0.009754904545844,-0.019964557141066,0,0,0,0,1.00826561450958 +41793,0.013055265881121,0.031755186617375,0.0220235157758,0,0,0,0,0.995032072067261 +41795,0.036739829927683,0.015340610407293,0.034451734274626,0,0,0,0,0.997476160526275 +41797,0.020718662068248,-0.012019839137793,0.011139525100589,0,0,0,0,1.00555491447449 +41799,-0.011892264708877,-0.002996413735673,-0.013765388168395,0,0,0,0,1.0135041475296 +41801,-0.021310199052096,0.021449398249388,-0.015220177359879,0,0,0,0,1.01629781723022 +41803,-0.012443623505533,0.00682067591697,0.003165621543303,0,0,0,0,1.00881814956665 +41805,-0.0125951487571,-0.036212529987097,0.016282018274069,0,0,0,0,0.996307194232941 +41807,-0.018835885450244,-0.04373687133193,0.003347143530846,0,0,0,0,0.994155704975128 +41809,-0.009836920537055,-0.004707984626293,-0.030663225799799,0,0,0,0,1.00227808952332 +41811,0.004776784684509,0.024140283465386,-0.042096812278032,0,0,0,0,1.00631630420685 +41813,0.006312473211437,0.01690461114049,-0.001006001257338,0,0,0,0,0.998563706874847 +41815,-0.000529166369233,-0.000584445369896,0.054393503814936,0,0,0,0,0.986531019210815 +41817,0.001737177604809,-0.00630497187376,0.058604300022125,0,0,0,0,0.989437282085419 +41819,0.007895170710981,-0.005845574196428,0.004690235480666,0,0,0,0,1.00998771190643 +41821,0.003927110228688,-0.00013693087385,-0.041501939296722,0,0,0,0,1.0202020406723 +41823,-0.001838749391027,0.013888369314373,-0.033373899757862,0,0,0,0,1.00448274612427 +41825,0.005706555675715,0.022271594032645,-0.000911563052796,0,0,0,0,0.991111874580383 +41827,0.016023427248001,0.007614767178893,0.007926631718874,0,0,0,0,0.994246661663055 +41829,0.013072015717626,-0.010762771591544,-0.006560862995684,0,0,0,0,1.00104916095734 +41831,0.004996449220926,0.000946010928601,-0.013452085666359,0,0,0,0,1.00161242485046 +41833,0.005091940518469,0.028064910322428,-0.00067250803113,0,0,0,0,0.99667501449585 +41835,0.015790086239576,0.033140987157822,0.017982820048928,0,0,0,0,0.995829045772552 +41837,0.02068798057735,0.008688032627106,0.027295883744955,0,0,0,0,0.996302485466003 +41839,0.009330206550658,-0.014126478694379,0.021438321098685,0,0,0,0,0.991896450519562 +41841,-0.006528929807246,-0.011552360840142,-0.001648745615967,0,0,0,0,0.996552348136902 +41843,-0.014292004518211,-0.000506455951836,-0.031158708035946,0,0,0,0,1.01158142089844 +41845,-0.019327184185386,-0.005989216268063,-0.032389160245657,0,0,0,0,1.01506721973419 +41847,-0.021524716168642,-0.018068455159664,0.003882264252752,0,0,0,0,0.999188661575317 +41849,-0.011649701744318,-0.017463460564613,0.037330493330956,0,0,0,0,0.98261570930481 +41851,0.004919234663248,-0.01242021843791,0.028912421315909,0,0,0,0,0.986106812953949 +41853,0.01204991620034,-0.011431821621955,-0.010314476676285,0,0,0,0,1.00625967979431 +41855,0.000849008967634,-0.006017624866217,-0.033705867826939,0,0,0,0,1.01515960693359 +41857,-0.015189447440207,0.011491275392473,-0.012658185325563,0,0,0,0,1.00195324420929 +41859,-0.011628556065261,0.023724503815174,0.020657384768128,0,0,0,0,0.988897621631622 +41861,0.008287302218378,0.006621211767197,0.025065742433071,0,0,0,0,0.990481436252594 +41863,0.020516142249107,-0.022453207522631,0.001497264020145,0,0,0,0,1.00196409225464 +41865,0.012685284018517,-0.020049439743161,-0.022401481866837,0,0,0,0,1.00843358039856 +41867,0.001184917171486,0.019163658842445,-0.02662093937397,0,0,0,0,1.0061023235321 +41869,0.01206323876977,0.054762475192547,-0.013479839079082,0,0,0,0,1.00435495376587 +41871,0.035056792199612,0.050995647907257,0.010195983573794,0,0,0,0,0.99775493144989 +41891,-0.016819655895233,-0.020213210955262,-0.042848087847233,0,0,0,0,1.0212150812149 +41893,-0.030439650639892,0.011922110803425,-0.011335791088641,0,0,0,0,1.00761580467224 +41895,-0.015477717854083,0.025153551250696,0.030310118570924,0,0,0,0,0.982742547988892 +41897,0.011059943586588,-0.001734071644023,0.03743152692914,0,0,0,0,0.974237740039825 +41899,0.021571097895503,-0.038296811282635,0.010481745935977,0,0,0,0,0.993112921714783 +41901,0.015769006684423,-0.03072751313448,-0.021886764094234,0,0,0,0,1.01573920249939 +41903,0.002792738610879,0.020041007548571,-0.040629267692566,0,0,0,0,1.01737749576569 +41905,0.00063400156796,0.066802307963371,-0.036121502518654,0,0,0,0,1.00908279418945 +41907,0.019604096189141,0.068963907659054,-0.006578398868442,0,0,0,0,0.999130010604858 +41909,0.039267111569643,0.029791675508022,0.03394116461277,0,0,0,0,0.983047008514404 +41911,0.041567232459784,-0.008581966161728,0.056041713804007,0,0,0,0,0.980103552341461 +41913,0.028475752100349,-0.011657041497529,0.037657096982002,0,0,0,0,0.999856054782867 +41915,0.009991333819926,0.012076514773071,-0.010815540328622,0,0,0,0,1.02356612682343 +41917,-0.003433871548623,0.029951326549053,-0.051436554640532,0,0,0,0,1.03352463245392 +41919,-0.010623621754348,0.025456380099058,-0.043595526367426,0,0,0,0,1.01937389373779 +41921,-0.004789399914444,0.006059773731977,0.005297860130668,0,0,0,0,0.986564338207245 +41923,0.014376752078533,-0.011512576602399,0.038621935993433,0,0,0,0,0.966853320598602 +41925,0.025440156459808,-0.019651556387544,0.024174805730581,0,0,0,0,0.980572283267975 +41927,0.005212213844061,-0.017470555379987,-0.012497680261731,0,0,0,0,1.00526595115662 +41929,-0.036677990108729,-0.013186578638852,-0.026076827198267,0,0,0,0,1.01798844337463 +41931,-0.058837782591581,-0.012209775857627,-0.008304499089718,0,0,0,0,1.01092672348022 +41933,-0.038619343191385,-0.014473077841103,0.01604582183063,0,0,0,0,0.992352426052094 +41935,-0.000178322719876,-0.02260390855372,0.018605252727866,0,0,0,0,0.984821379184723 +41937,0.019493727013469,-0.037376459687948,-0.003045267658308,0,0,0,0,0.995315611362457 +41939,0.005406927317381,-0.038136638700962,-0.023497434332967,0,0,0,0,1.01076114177704 +41941,-0.020719442516565,-0.010420742444694,-0.02732334472239,0,0,0,0,1.01407158374786 +41943,-0.033498015254736,0.022833550348878,-0.016983710229397,0,0,0,0,1.00349318981171 +41945,-0.023275563493371,0.027742061764002,-0.002954330062494,0,0,0,0,0.992201685905456 +41947,-0.002148153493181,-0.001991356257349,0.013218615204096,0,0,0,0,0.988140821456909 +41949,0.011025717481971,-0.032191578298807,0.031180316582322,0,0,0,0,0.992095053195953 +41951,0.018637906759977,-0.029310094192624,0.035819981247187,0,0,0,0,0.999695241451263 +41953,0.01718576811254,0.004455756861717,0.011712353676558,0,0,0,0,1.00503480434418 +41955,0.00406745960936,0.033302329480648,-0.032893009483814,0,0,0,0,1.01127922534943 +41957,-0.011121322400868,0.031949814409018,-0.060678318142891,0,0,0,0,1.01449084281921 +41959,-0.015757670626044,0.010010529309511,-0.037138480693102,0,0,0,0,1.00349235534668 +41961,-0.000301544961985,-0.008710551075637,0.02057683467865,0,0,0,0,0.986780762672424 +41963,0.030515121296048,-0.009994113817811,0.058833427727223,0,0,0,0,0.980479717254639 +41965,0.047026444226503,-0.001545477542095,0.048043701797724,0,0,0,0,0.989000678062439 +41967,0.027048295363784,0.003291270928457,0.004897994920611,0,0,0,0,1.00756084918976 +41969,-0.018902581185103,0.001956717344001,-0.032783173024654,0,0,0,0,1.02036416530609 +41971,-0.056121334433556,-0.003026778809726,-0.037832293659449,0,0,0,0,1.01434659957886 +41973,-0.054538484662771,-0.008133467286825,-0.017744529992342,0,0,0,0,0.99725067615509 +41975,-0.013628256507218,-0.015670280903578,0.001126976567321,0,0,0,0,0.986158847808838 +41977,0.029530322179198,-0.026638986542821,0.008357117883861,0,0,0,0,0.987110674381256 +41979,0.038398072123528,-0.028019307181239,0.013185608200729,0,0,0,0,0.997223615646362 +41981,0.012532219290733,-0.005118398461491,0.01802882924676,0,0,0,0,1.00519275665283 +41983,-0.020140253007412,0.02777555026114,0.011913715861738,0,0,0,0,1.0041835308075 +41985,-0.031438779085875,0.043375078588724,-0.009083278477192,0,0,0,0,1.00285804271698 +41987,-0.011717326007784,0.030735095962882,-0.030807426199317,0,0,0,0,1.00559675693512 +41989,0.017907626926899,0.001186800422147,-0.028584161773324,0,0,0,0,1.00585317611694 +41991,0.031841352581978,-0.022175073623657,0.002362229162827,0,0,0,0,0.998838841915131 +41993,0.026216326281428,-0.021381223574281,0.036100901663303,0,0,0,0,0.990129590034485 +41995,0.007588851265609,-0.001873110421002,0.040289968252182,0,0,0,0,0.99024224281311 +41997,-0.011941775679588,0.014015289954841,0.008500074967742,0,0,0,0,1.00342321395874 +41999,-0.020829143002629,0.017747500911355,-0.026310887187719,0,0,0,0,1.01689767837524 +42001,-0.016531912609935,0.013300109654665,-0.032669670879841,0,0,0,0,1.01625180244446 +42003,0.001617468427867,0.012412242591381,-0.012840094044805,0,0,0,0,1.0021390914917 +42005,0.03056944347918,0.01796286739409,0.011502154171467,0,0,0,0,0.985719084739685 +42007,0.05376723408699,0.020919913426042,0.020727915689349,0,0,0,0,0.979571104049683 +42009,0.044733192771673,0.007516722660512,0.016016654670239,0,0,0,0,0.989308297634125 +42011,-0.004078805912286,-0.015014133416116,0.00986120570451,0,0,0,0,1.00418257713318 +42013,-0.058930862694979,-0.031878054141998,0.006879340391606,0,0,0,0,1.01189506053925 +42015,-0.073610737919808,-0.027244260534644,-0.000701484677847,0,0,0,0,1.00922250747681 +42017,-0.037467867136002,-0.00865810085088,-0.017137438058853,0,0,0,0,0.999723613262176 +42019,0.017903303727508,0.003883398137987,-0.032184701412916,0,0,0,0,0.994263648986816 +42021,0.0520497597754,0.00397469708696,-0.023508815094829,0,0,0,0,0.995747864246368 +42023,0.044736091047526,-0.004775719717145,0.012225253507495,0,0,0,0,0.995884120464325 +42047,0.005101216956973,0.02068036980927,-0.048189241439104,0,0,0,0,1.01483118534088 +42049,0.005002742167562,0.027402492240071,-0.047452449798584,0,0,0,0,0.99942022562027 +42051,0.018099145963788,0.03305908292532,-0.026379210874438,0,0,0,0,0.983545780181885 +42053,0.03742104023695,0.027357295155525,0.006655497010797,0,0,0,0,0.979629278182983 +42055,0.037387873977423,0.009972931817174,0.041374307125807,0,0,0,0,0.986300647258758 +42057,0.010214080102742,-0.008716978132725,0.060793090611696,0,0,0,0,0.995803654193878 +42059,-0.025870215147734,-0.017446823418141,0.049832545220852,0,0,0,0,1.00430750846863 +42061,-0.04409471899271,-0.011579805053771,0.007165337912738,0,0,0,0,1.00992655754089 +42063,-0.032034508883953,0.001602006261237,-0.048837672919035,0,0,0,0,1.01338994503021 +42065,-0.000689037609845,0.010953978635371,-0.082830227911472,0,0,0,0,1.01465404033661 +42067,0.028239091858268,0.0097551131621,-0.068332649767399,0,0,0,0,1.00845873355865 +42069,0.031107515096665,-0.003750941716135,-0.007712001446635,0,0,0,0,0.991328656673431 +42071,0.000882657594047,-0.021518994122744,0.061477027833462,0,0,0,0,0.972990930080414 +42073,-0.036894299089909,-0.033777207136154,0.092521645128727,0,0,0,0,0.973369300365448 +42075,-0.039418015629053,-0.019400510936976,0.06285847723484,0,0,0,0,0.994003176689148 +42077,0.002633038209751,0.021591959521175,-0.005104750860482,0,0,0,0,1.01500201225281 +42079,0.04151675850153,0.04988718777895,-0.064374096691609,0,0,0,0,1.02901566028595 +42081,0.043824646621943,0.047301106154919,-0.080150380730629,0,0,0,0,1.02626860141754 +42083,0.022235816344619,0.027362164109945,-0.048791211098433,0,0,0,0,0.996053159236908 +42085,0.007404921576381,0.011078396812081,0.005212155170739,0,0,0,0,0.965352356433868 +42087,0.010516125708819,0.007264885120094,0.048925597220659,0,0,0,0,0.960463166236877 +42089,0.024214303120971,0.01136289164424,0.06577080488205,0,0,0,0,0.977225720882416 +42091,0.035292323678732,0.017679488286376,0.053754791617394,0,0,0,0,1.00496828556061 +42093,0.030347583815456,0.025287419557572,0.022051179781556,0,0,0,0,1.02637851238251 +42095,0.012492490001023,0.033221691846848,-0.018345039337874,0,0,0,0,1.02163422107697 +42097,0.003501578466967,0.039147734642029,-0.063774667680264,0,0,0,0,1.0032856464386 +42099,0.015381945297122,0.040736868977547,-0.087277106940746,0,0,0,0,0.99356597661972 +42101,0.03726327419281,0.034320816397667,-0.062069971114397,0,0,0,0,0.989903211593628 +42103,0.051597360521555,0.021165881305933,0.004782501142472,0,0,0,0,0.99189567565918 +42105,0.042911488562822,0.004551945719868,0.077612370252609,0,0,0,0,0.995545208454132 +42107,0.008374408818781,-0.008365272544324,0.111068829894066,0,0,0,0,0.989978611469269 +42109,-0.028819607570767,-0.01085742842406,0.078942567110062,0,0,0,0,0.98744809627533 +42111,-0.038175899535418,-0.003193303244188,-0.000169442195329,0,0,0,0,1.00222432613373 +42113,-0.016640888527036,0.006990523077548,-0.081155702471733,0,0,0,0,1.021409034729 +42115,0.017881110310555,0.012562856078148,-0.115314058959484,0,0,0,0,1.02943027019501 +42117,0.040577299892902,0.01308405213058,-0.082275278866291,0,0,0,0,1.01875734329224 +42119,0.035770818591118,0.010891608893871,-0.004922203719616,0,0,0,0,0.987484157085419 +42121,0.01363933365792,0.010889711789787,0.066479377448559,0,0,0,0,0.958569765090942 +42123,-0.002798721892759,0.015342867001891,0.095670394599438,0,0,0,0,0.960149943828583 +42125,-0.000782442977652,0.017244463786483,0.079396888613701,0,0,0,0,0.989150524139404 +42127,0.013432392850518,0.01085024047643,0.033843401819468,0,0,0,0,1.02484750747681 +42129,0.017973031848669,-0.000254196900642,-0.021223653107882,0,0,0,0,1.04605662822723 +42131,0.000470520084491,-0.013199459761381,-0.065596200525761,0,0,0,0,1.03614866733551 +42133,-0.029225064441562,-0.021539762616158,-0.085220761597157,0,0,0,0,1.00307977199554 +42135,-0.041983664035797,-0.018133079633117,-0.07317066192627,0,0,0,0,0.976180255413055 +42137,-0.023963982239366,-0.005209283903241,-0.027630209922791,0,0,0,0,0.970950305461884 +42139,0.014457715675235,0.011491823010147,0.038675729185343,0,0,0,0,0.982657432556152 +42141,0.049458984285593,0.026188896968961,0.095501355826855,0,0,0,0,0.999112069606781 +42143,0.056747678667307,0.028926301747561,0.107145309448242,0,0,0,0,1.00634682178497 +42145,0.030115235596895,0.01877566985786,0.062714748084545,0,0,0,0,1.00335586071014 +42147,-0.010845269076526,0.004600291606039,-0.017788972705603,0,0,0,0,1.00169718265533 +42149,-0.03970755264163,-0.007449388038367,-0.091995991766453,0,0,0,0,1.00890231132507 +42151,-0.042156137526035,-0.016878707334399,-0.118009209632874,0,0,0,0,1.01701641082764 +42153,-0.023044358938933,-0.023281073197723,-0.081801973283291,0,0,0,0,1.01397526264191 +42155,0.001233956660144,-0.025572292506695,-0.00571818696335,0,0,0,0,0.997839272022247 +42157,0.010182516649366,-0.021178172901273,0.067495346069336,0,0,0,0,0.97816002368927 +42159,0.001420076121576,-0.007396129425615,0.099143728613854,0,0,0,0,0.968567371368408 +42161,-0.003685730043799,0.011838590726256,0.08198094367981,0,0,0,0,0.979994416236877 +42163,0.004801652859896,0.02673939242959,0.0339230671525,0,0,0,0,1.0086954832077 +42165,0.022904416546226,0.029244152829051,-0.022413622587919,0,0,0,0,1.03481674194336 +42167,0.029540259391069,0.017592370510101,-0.066295556724072,0,0,0,0,1.03985857963562 +42169,0.013322208076716,-0.002916423836723,-0.083683624863625,0,0,0,0,1.02274930477142 +42171,-0.023526085540652,-0.026398228481412,-0.070758268237114,0,0,0,0,0.994640409946442 +42173,-0.059794321656227,-0.04222260043025,-0.02867054194212,0,0,0,0,0.972211301326752 +42175,-0.069296143949032,-0.042334474623203,0.029926570132375,0,0,0,0,0.970887720584869 +42177,-0.03807308152318,-0.025617219507694,0.082097709178925,0,0,0,0,0.987399935722351 +42179,0.015621542930603,0.000166651283507,0.101073831319809,0,0,0,0,1.00615346431732 +42181,0.054099142551422,0.026147294789553,0.072117269039154,0,0,0,0,1.01787173748016 +42199,0.000956506875809,0.007644964847714,0.041827421635389,0,0,0,0,1.00194811820984 +42201,0.001475077238865,0.021654944866896,0.007299636956304,0,0,0,0,1.00712156295776 +42203,0.009785500355065,0.026877947151661,-0.025509594008327,0,0,0,0,1.00916028022766 +42205,0.024565158411861,0.023142915219069,-0.044708900153637,0,0,0,0,1.00856292247772 +42207,0.027981597930193,0.007505116518587,-0.046804387122393,0,0,0,0,1.00516211986542 +42209,0.010292122140527,-0.017124289646745,-0.034505169838667,0,0,0,0,0.999836802482605 +42211,-0.024349903687835,-0.036667574197054,-0.010754024609923,0,0,0,0,0.995642066001892 +42213,-0.058540403842926,-0.046678178012371,0.018040517345071,0,0,0,0,0.992845714092254 +42215,-0.06748466193676,-0.045448295772076,0.037574168294668,0,0,0,0,0.990669190883636 +42217,-0.042917031794787,-0.029278595000506,0.038171015679836,0,0,0,0,0.993111252784729 +42219,0.004090358503163,-0.001189832342789,0.020107191056013,0,0,0,0,1.00095450878143 +42221,0.048200003802776,0.0306037645787,-0.003854077542201,0,0,0,0,1.00920414924622 +42223,0.064376190304756,0.049628511071205,-0.021722715348005,0,0,0,0,1.01315474510193 +42225,0.046100050210953,0.044921599328518,-0.02807186357677,0,0,0,0,1.01062476634979 +42227,0.002957957563922,0.018522439524531,-0.021790133789182,0,0,0,0,1.00201308727264 +42229,-0.04125752300024,-0.020222494378686,-0.007618953008205,0,0,0,0,0.991451501846314 +42231,-0.062557376921177,-0.052551917731762,0.007561733946204,0,0,0,0,0.98661082983017 +42233,-0.055838197469711,-0.064998179674149,0.016967259347439,0,0,0,0,0.991783559322357 +42235,-0.030554229393602,-0.054597698152065,0.015852253884077,0,0,0,0,1.00238013267517 +42237,-0.002179503208026,-0.023149812594056,0.006573846563697,0,0,0,0,1.01049387454987 +42239,0.017366649582982,0.014949824661017,-0.006998666096479,0,0,0,0,1.0115875005722 +42241,0.023359816521406,0.040209665894508,-0.014258933253586,0,0,0,0,1.00556480884552 +42243,0.020681135356426,0.045390419661999,-0.009013419039547,0,0,0,0,0.99580454826355 +42245,0.018951019272208,0.031579799950123,0.008041393011808,0,0,0,0,0.988618493080139 +42247,0.020687982439995,0.006808399688452,0.024778932332993,0,0,0,0,0.989478886127472 +42249,0.012368396855891,-0.017002092674375,0.026473574340344,0,0,0,0,0.99767005443573 +42251,-0.010119767859578,-0.037723921239376,0.012025225907564,0,0,0,0,1.00711262226105 +42253,-0.035867940634489,-0.048180866986513,-0.012096697464585,0,0,0,0,1.01229763031006 +42255,-0.053456820547581,-0.045126594603062,-0.034121125936508,0,0,0,0,1.01144552230835 +42257,-0.04976798966527,-0.033271834254265,-0.042547658085823,0,0,0,0,1.00546824932098 +42259,-0.024614337831736,-0.015679558739066,-0.029498141258955,0,0,0,0,0.996801316738129 +42261,0.013140297494829,0.005854129325598,-0.001173465978354,0,0,0,0,0.991078853607178 +42263,0.046987675130367,0.028665037825704,0.028027562424541,0,0,0,0,0.991839706897736 +42265,0.059868436306715,0.043770767748356,0.045497134327889,0,0,0,0,0.997377097606659 +42267,0.046328775584698,0.042873524129391,0.043401401489973,0,0,0,0,1.00424838066101 +42269,0.014415201731026,0.023635875433683,0.018861858174205,0,0,0,0,1.00902616977692 +42271,-0.02381095290184,-0.008118375204504,-0.01614498719573,0,0,0,0,1.01058447360992 +42273,-0.054845508188009,-0.044262640178204,-0.040683943778277,0,0,0,0,1.00861871242523 +42275,-0.063751861453056,-0.070957079529762,-0.043122489005327,0,0,0,0,1.00292015075684 +42277,-0.048009254038334,-0.070304796099663,-0.028159137815237,0,0,0,0,0.997874140739441 +42279,-0.017441611737013,-0.036664053797722,-0.005794939119369,0,0,0,0,0.995921552181244 +42281,0.016474939882755,0.01056949980557,0.013697849586606,0,0,0,0,0.99499785900116 +42283,0.039751023054123,0.047836448997259,0.022490743547678,0,0,0,0,0.996836602687836 +42285,0.050651710480452,0.067096672952175,0.022748995572329,0,0,0,0,1.00130891799927 +42287,0.049851328134537,0.061444289982319,0.0201186966151,0,0,0,0,1.00348687171936 +42289,0.034137200564146,0.031258501112461,0.013944709673524,0,0,0,0,1.00248539447784 +42291,0.010624988004565,-0.003046998754144,0.003867232706398,0,0,0,0,1.00037372112274 +42293,-0.014686206355691,-0.027972841635347,-0.006751439068466,0,0,0,0,0.999007821083069 +42295,-0.033453553915024,-0.041458979249001,-0.015039356425405,0,0,0,0,1.00185441970825 +42297,-0.038903802633286,-0.040383249521256,-0.020762143656612,0,0,0,0,1.00729596614838 +42299,-0.029986780136824,-0.024550700560212,-0.022328361868858,0,0,0,0,1.0082551240921 +42301,-0.009701387025416,-0.001563602825627,-0.01767748221755,0,0,0,0,1.0042576789856 +42303,0.014072417281568,0.019607976078987,-0.008446793071926,0,0,0,0,0.998624980449676 +42305,0.031662650406361,0.033435869961977,0.004703111946583,0,0,0,0,0.992785334587097 +42307,0.037605281919241,0.037217818200588,0.017919778823853,0,0,0,0,0.990357160568237 +42309,0.032729350030422,0.032446499913931,0.026249591261149,0,0,0,0,0.994791865348816 +42311,0.02252358943224,0.022528266534209,0.025191450491548,0,0,0,0,1.00076985359192 +42313,0.012156047858298,0.007608540821821,0.012878534384072,0,0,0,0,1.00420928001404 +42315,0.000254750368185,-0.006824861746281,-0.005998917389661,0,0,0,0,1.00509393215179 +42317,-0.013509584590793,-0.016566071659327,-0.018481284379959,0,0,0,0,1.00290942192078 +42319,-0.021860007196665,-0.025585077702999,-0.022218562662602,0,0,0,0,1.00113689899445 +42321,-0.024787409231067,-0.030157649889588,-0.019528659060598,0,0,0,0,1.00012278556824 +42323,-0.019503455609083,-0.021716680377722,-0.004973740316927,0,0,0,0,0.997487306594849 +42325,-0.005842474289238,-0.002151240361854,0.012544536963105,0,0,0,0,0.996510446071625 +42327,0.010386657901108,0.01705844886601,0.019018996506929,0,0,0,0,0.999365866184235 +42329,0.024155853316188,0.030157566070557,0.009455718100071,0,0,0,0,1.00586712360382 +42331,0.02794872969389,0.029643766582012,-0.015544745139778,0,0,0,0,1.00613939762115 +42333,0.016672495752573,0.012492589652538,-0.012063516303897,0,0,0,0,1.00225389003754 +42335,0.016672495752573,0.012492589652538,-0.012063516303897,0,0,0,0,1.00225389003754 +42337,-0.016680736094713,-0.019866505637765,0.018874384462833,0,0,0,0,0.991043746471405 +42339,-0.020443521440029,-0.023441070690751,0.028949001803994,0,0,0,0,0.991544544696808 +42341,-0.011073554866016,-0.017439413815737,0.026584897190333,0,0,0,0,0.999623537063599 +42343,0.006568010430783,-0.002360937884077,0.009685316123068,0,0,0,0,1.01010191440582 +42345,0.006568010430783,-0.002360937884077,0.009685316123068,0,0,0,0,1.01010191440582 +42347,0.027390664443374,0.030188929289579,-0.038011249154806,0,0,0,0,1.01331388950348 +42349,0.02486265450716,0.033891353756189,-0.041777435690165,0,0,0,0,1.00586473941803 +42351,0.017102029174566,0.025609375908971,-0.028673995286226,0,0,0,0,0.997204542160034 +42353,0.004395443480462,0.008782063610852,-0.004036874044687,0,0,0,0,0.990329027175903 +42355,0.004395443480462,0.008782063610852,-0.004036874044687,0,0,0,0,0.990329027175903 +42357,-0.006141440942884,-0.013522527180612,0.043751936405897,0,0,0,0,0.991401314735413 +42359,-0.00055264600087,-0.006119429599494,0.045525524765253,0,0,0,0,0.998700141906738 +42361,0.01188837736845,0.008349953219295,0.024451134726405,0,0,0,0,1.00707304477692 +42363,0.02774347551167,0.025107027962804,-0.007974341511726,0,0,0,0,1.01270949840546 +42365,0.02774347551167,0.025107027962804,-0.007974341511726,0,0,0,0,1.01270949840546 +42367,0.039549358189106,0.042090196162462,-0.04236650839448,0,0,0,0,1.00990736484528 +42369,0.032566659152508,0.035666663199663,-0.028664447367191,0,0,0,0,1.00374209880829 +42371,0.021872710436583,0.022247988730669,-0.001652767066844,0,0,0,0,0.996733784675598 +42373,0.01136336568743,0.008859665133059,0.024420000612736,0,0,0,0,0.994109809398651 +42375,0.000718950584996,0.001512352493592,0.034536514431238,0,0,0,0,0.997559130191803 +42377,-0.005182004999369,0.000606424058788,0.023894459009171,0,0,0,0,1.00439143180847 +42379,-0.003222472034395,0.005676679778844,0.001714053680189,0,0,0,0,1.01075732707977 +42381,0.006135408300906,0.015283640474081,-0.022899460047484,0,0,0,0,1.01250040531158 +42383,0.019114628434181,0.027093585580587,-0.036148425191641,0,0,0,0,1.00836598873138 +42385,0.029924867674708,0.040659245103598,-0.028819685801864,0,0,0,0,1.00177276134491 +42387,0.035586774349213,0.048665873706341,-0.005837415345013,0,0,0,0,0.99533349275589 +42389,0.038672816008329,0.047950714826584,0.022109728306532,0,0,0,0,0.990905821323395 +42391,0.03732768073678,0.043479707092047,0.042657066136599,0,0,0,0,0.992843329906464 +42393,0.034032989293337,0.035908307880163,0.042204160243273,0,0,0,0,0.999261975288391 +42395,0.028563028201461,0.026403957977891,0.019490208476782,0,0,0,0,1.00553226470947 +42397,0.020193349570036,0.021445253863931,-0.011936390772462,0,0,0,0,1.01074254512787 +42399,0.01433839648962,0.017622131854296,-0.039135552942753,0,0,0,0,1.0118842124939 +42401,0.009644093923271,0.011932618916035,-0.051329981535673,0,0,0,0,1.00729918479919 +42403,0.005889932624996,0.008820774964988,-0.039361141622067,0,0,0,0,1.00070476531982 +42405,0.00634724041447,0.010595746338368,-0.008100079372525,0,0,0,0,0.99376106262207 +42407,0.013926199637354,0.016867937520146,0.028920572251082,0,0,0,0,0.98873507976532 +42409,0.025224773213267,0.027851091697812,0.052324552088976,0,0,0,0,0.990957140922546 +42411,0.037292022258043,0.039828389883041,0.04938991740346,0,0,0,0,0.998687982559204 +42429,0.022132277488709,0.01677811704576,0.039654348045588,0,0,0,0,0.99883645772934 +42431,0.031959407031536,0.025117928162217,0.011605186387897,0,0,0,0,1.00575888156891 +42433,0.038253780454397,0.036117415875197,-0.025198008865118,0,0,0,0,1.00969350337982 +42435,0.041262648999691,0.045583602041006,-0.048893488943577,0,0,0,0,1.00827050209045 +42437,0.043644454330206,0.050209660083056,-0.049145773053169,0,0,0,0,1.00100588798523 +42439,0.043848026543856,0.049483135342598,-0.028275165706873,0,0,0,0,0.992831885814667 +42441,0.03864786401391,0.042033117264509,0.00668088812381,0,0,0,0,0.987586557865143 +42443,0.031264275312424,0.033338576555252,0.041759464889765,0,0,0,0,0.985774457454681 +42445,0.02938143722713,0.028577033430338,0.056696597486734,0,0,0,0,0.990040957927704 +42447,0.034185823053122,0.029480451717973,0.044154405593872,0,0,0,0,0.99947327375412 +42449,0.039081260561943,0.037951730191708,0.01466281991452,0,0,0,0,1.00856137275696 +42451,0.045542236417532,0.048597365617752,-0.018756104633212,0,0,0,0,1.01454019546509 +42453,0.051858637481928,0.055219352245331,-0.042440220713616,0,0,0,0,1.01486611366272 +42455,0.052315011620522,0.05584143102169,-0.048817723989487,0,0,0,0,1.00792813301086 +42457,0.047069337219,0.052382715046406,-0.033605936914682,0,0,0,0,0.998723268508911 +42459,0.039283636957407,0.044947843998671,-0.001457158476114,0,0,0,0,0.992958784103394 +42461,0.031697269529104,0.032816637307406,0.030917966738343,0,0,0,0,0.990817785263062 +42463,0.024953279644251,0.021943517029286,0.048416394740343,0,0,0,0,0.993050873279572 +42465,0.022236943244934,0.019421234726906,0.043864391744137,0,0,0,0,1.00050866603851 +42467,0.0248879827559,0.026417234912515,0.018317189067602,0,0,0,0,1.00860595703125 +42469,0.032580483704805,0.038117159157992,-0.016292382031679,0,0,0,0,1.01396703720093 +42471,0.045625425875187,0.051359713077545,-0.045175064355135,0,0,0,0,1.01510274410248 +42473,0.059948600828648,0.065190635621548,-0.05301121994853,0,0,0,0,1.00997948646545 +42475,0.065890349447727,0.074614889919758,-0.037009991705418,0,0,0,0,1.00128102302551 +42477,0.064484603703022,0.077434077858925,-0.00670393416658,0,0,0,0,0.994484007358551 +42479,0.05982967466116,0.072023168206215,0.026983680203557,0,0,0,0,0.992153286933899 +42481,0.053604416549206,0.059701219201088,0.049750927835703,0,0,0,0,0.993835866451263 +42483,0.046346485614777,0.047081187367439,0.050147335976362,0,0,0,0,0.99955028295517 +42485,0.040076330304146,0.039173185825348,0.02766715362668,0,0,0,0,1.00672876834869 +42487,0.035440299659968,0.036348309367895,-0.005404459312558,0,0,0,0,1.01152169704437 +42489,0.035764768719673,0.038693629205227,-0.032864339649677,0,0,0,0,1.01327955722809 +42491,0.042218435555697,0.043640118092299,-0.045952085405588,0,0,0,0,1.01142990589142 +42493,0.048696078360081,0.049895934760571,-0.042114306241274,0,0,0,0,1.00567007064819 +42495,0.055582996457815,0.058181785047054,-0.020563768222928,0,0,0,0,0.998862445354462 +42497,0.063368566334248,0.066090196371079,0.01024201605469,0,0,0,0,0.994336247444153 +42499,0.065456837415695,0.069364167749882,0.036243706941605,0,0,0,0,0.994339346885681 +42501,0.060488723218441,0.066205374896526,0.044928163290024,0,0,0,0,0.998163163661957 +42503,0.053853560239077,0.057317715138197,0.034213472157717,0,0,0,0,1.00354444980621 +42505,0.05051700770855,0.049682576209307,0.008002378977835,0,0,0,0,1.00808751583099 +42507,0.051570042967796,0.049101497977972,-0.021787287667394,0,0,0,0,1.00991225242615 +42511,0.060787305235863,0.064368717372418,-0.043276771903038,0,0,0,0,1.00523972511292 +42513,0.065659150481224,0.073801316320896,-0.023871820420027,0,0,0,0,0.999425172805786 +42515,0.069133840501309,0.079447619616985,0.004500074777752,0,0,0,0,0.996275961399078 +42517,0.05708572268486,0.068783082067967,0.028043271973729,0,0,0,0,0.99756121635437 +42519,0.02610320597887,0.036863680928946,0.03672656789422,0,0,0,0,0.995304524898529 +42521,-0.00562522560358,-0.001111938268878,0.024878328666091,0,0,0,0,0.990004003047943 +42523,-0.019838785752654,-0.026169961318374,0.000918040750548,0,0,0,0,0.991951763629913 +42525,-0.017520258203149,-0.029997166246176,-0.014875890687108,0,0,0,0,0.99965912103653 +42527,-0.012563838623464,-0.022011656314135,-0.016101436689496,0,0,0,0,1.00607120990753 +42529,-0.011100278235972,-0.010771292261779,-0.007361293304712,0,0,0,0,1.00686156749725 +42531,-0.008493687957525,-0.000981058459729,-0.000214883039007,0,0,0,0,1.00220215320587 +42533,-0.00583194475621,0.001225177198648,-0.000780778005719,0,0,0,0,0.997063159942627 +42535,-0.005935417022556,-0.002892194548622,-0.006037262268364,0,0,0,0,0.996929705142975 +42537,-0.008831002749503,-0.010182415135205,-0.007862203754485,0,0,0,0,1.00097608566284 +42539,-0.013791377656162,-0.017576362937689,0.000349003064912,0,0,0,0,1.00486660003662 +42541,-0.02084755897522,-0.025435289368034,0.011157980188727,0,0,0,0,1.00576162338257 +42543,-0.02563832513988,-0.027692787349224,0.014073177240789,0,0,0,0,1.002068400383 +42545,-0.022903215140104,-0.023800428956747,0.007463885936886,0,0,0,0,0.99778139591217 +42547,-0.014652794227004,-0.019368395209313,-0.004737503360957,0,0,0,0,0.998096764087677 +42549,-0.003383085364476,-0.011962367221713,-0.010119794867933,0,0,0,0,1.00167965888977 +42551,0.007932273671031,0.001711965771392,-0.005312933586538,0,0,0,0,1.00518417358398 +42553,0.016644781455398,0.013723290525377,0.00126572244335,0,0,0,0,1.00606691837311 +42555,0.015545116737485,0.015299645252526,0.005755505058914,0,0,0,0,1.00273180007935 +42557,0.005354538559914,0.008148985914886,0.005474293138832,0,0,0,0,0.998261630535126 +42559,-0.004244581330568,-0.002602343214676,-7.29988823877647E-05,0,0,0,0,0.99662059545517 +42561,-0.007272204849869,-0.010422788560391,-0.002601706888527,0,0,0,0,0.998503684997559 +42563,-0.006201377138495,-0.012849510647357,0.00152063393034,0,0,0,0,1.00195026397705 +42565,-0.005219750106335,-0.012872444465757,0.006452921312302,0,0,0,0,1.00222647190094 +42567,-0.002619222505018,-0.010997231118381,0.005684911739081,0,0,0,0,0.999257683753967 +42569,0.001051325351,-0.003968564793468,0.000597434816882,0,0,0,0,0.997344076633453 +42571,0.006483213510364,0.006352041848004,-0.00709678651765,0,0,0,0,0.998203635215759 +42573,0.01555790565908,0.017642011865974,-0.012913533486426,0,0,0,0,1.00113451480865 +42575,0.024948151782155,0.026719752699137,-0.012161596678197,0,0,0,0,1.00410258769989 +42577,0.02868727594614,0.029426708817482,-0.007793627679348,0,0,0,0,1.00386393070221 +42579,0.024838862940669,0.026797093451023,-0.003183260792866,0,0,0,0,1.00060904026032 +42581,0.019022597000003,0.020591804757714,-0.000759394140914,0,0,0,0,0.99755322933197 +42583,0.012989038601518,0.013550276868045,0.002458109054714,0,0,0,0,0.997483372688293 +42585,0.006566365715116,0.007915825583041,0.004705572500825,0,0,0,0,0.999975800514221 +42587,0.003697636071593,0.004309877753258,0.005632710177451,0,0,0,0,1.0018949508667 +42589,0.005136904772371,0.002522192196921,0.007793889846653,0,0,0,0,1.00214672088623 +42591,0.007456418126822,0.004575443454087,0.007089283782989,0,0,0,0,1.00151550769806 +42593,0.005674965213984,0.004831227008253,0.002297544153407,0,0,0,0,1.00140583515167 +42595,-0.001186243258417,-0.002881619147956,-0.006288642995059,0,0,0,0,1.00144696235657 +42597,-0.009040008299053,-0.011066091246903,-0.011501983739436,0,0,0,0,1.00022125244141 +42599,-0.010930797085166,-0.013393603265286,-0.011661449447274,0,0,0,0,0.998839735984802 +42601,-0.005177218001336,-0.013092568144202,-0.008135562762618,0,0,0,0,0.998256325721741 +42603,-0.000478325528093,-0.009414530359209,0.002203288022429,0,0,0,0,0.997659981250763 +42605,-0.000732715416234,-0.00579451629892,0.010805496945977,0,0,0,0,0.997662246227264 +42607,-0.002811673562974,-0.007650824263692,0.010558288544417,0,0,0,0,0.999149262905121 +42609,-0.007364333141595,-0.011848250404,0.00653079431504,0,0,0,0,1.00012636184692 +42611,-0.015087581239641,-0.014702333137393,0.001893642242067,0,0,0,0,1.00105583667755 +42613,-0.018579598516226,-0.016805810853839,-0.002834273502231,0,0,0,0,1.00285923480988 +42615,-0.016774781048298,-0.018155613914132,-0.006811507977545,0,0,0,0,1.00295150279999 +42617,-0.012291386723518,-0.013717866502702,-0.008372844196856,0,0,0,0,1.00185787677765 +42619,-0.004903085529804,-0.003096668282524,-0.007569818757474,0,0,0,0,1.00157797336578 +42621,0.002965260995552,0.006064579822123,-0.005528980400413,0,0,0,0,1.00107395648956 +42623,0.007218559272587,0.00924825668335,-0.004584620241076,0,0,0,0,1.00010108947754 +42625,0.007008325308561,0.011589070782065,-0.003535080468282,0,0,0,0,1.00030970573425 +42627,0.007080764975399,0.013312267139554,-0.000430960091762,0,0,0,0,1.00033676624298 +42629,0.011423348449171,0.011978046037257,0.002767546335235,0,0,0,0,1.00013053417206 +42631,0.013620926998556,0.01086953561753,0.003774316981435,0,0,0,0,1.00066721439362 +42633,0.010994808748365,0.008957852609456,0.003309434745461,0,0,0,0,0.999741852283478 +42635,0.007117358502001,0.006436769384891,0.003556228009984,0,0,0,0,0.998927295207977 +42637,0.005621095653623,0.005302669946104,0.001447644433938,0,0,0,0,1.00033104419708 +42639,0.006421410478652,0.008250151760876,-0.000906656146981,0,0,0,0,1.00183057785034 +42641,0.008282818831503,0.012243846431375,-0.001268587075174,0,0,0,0,1.00296580791473 +42643,0.008797597140074,0.0130287213251,-0.002001078799367,0,0,0,0,1.00375080108643 +42645,0.007295270916075,0.011252665892243,-0.00542595051229,0,0,0,0,1.00283217430115 +42647,0.004381213802844,0.007138238288462,-0.008852632716298,0,0,0,0,1.00114548206329 +42649,0.000940897967666,0.002330292016268,-0.008088038302958,0,0,0,0,0.999895274639129 +42651,-0.001973556121811,-0.002939510624856,-0.00316197425127,0,0,0,0,0.999247014522552 +42653,-0.00493271369487,-0.004814889747649,0.005358904600143,0,0,0,0,0.999335885047913 +42655,-0.006404047366232,-0.005328163970262,0.010395707562566,0,0,0,0,0.999537885189056 +42657,-0.006102843675762,-0.008802922442555,0.008802528493106,0,0,0,0,0.999336004257202 +42659,-0.008861203677952,-0.012456591241062,0.003978379070759,0,0,0,0,0.999864220619202 +42661,-0.014638774096966,-0.01472818851471,-0.000557835155632,0,0,0,0,1.00143718719482 +42663,-0.016466492787004,-0.016057509928942,-0.004870401229709,0,0,0,0,1.00274848937988 +42665,-0.012301382608712,-0.014673814177513,-0.008372588083148,0,0,0,0,1.00317323207855 +42667,-0.005158914253116,-0.009569560177624,-0.008686847053468,0,0,0,0,1.00209379196167 +42669,0.000887163681909,-0.002142407931387,-0.006569692399353,0,0,0,0,0.999952137470245 +42671,0.005295743700117,0.003093733917922,-0.003912112209946,0,0,0,0,0.998587429523468 +42673,0.007376153953373,0.007547843735665,-0.002612058538944,0,0,0,0,0.998773694038391 +42675,0.00750936428085,0.014121570624411,0.002174481516704,0,0,0,0,0.999354898929596 +42677,0.011774784885347,0.018926344811916,0.007336921524256,0,0,0,0,1.00026309490204 +42679,0.015922488644719,0.020407842472196,0.005271576344967,0,0,0,0,1.0014089345932 +42681,0.011742069385946,0.015349601395428,0.001690358505584,0,0,0,0,1.00077688694 +42683,0.00367128662765,0.005511842668056,0.001204991480336,0,0,0,0,0.999215364456177 +42685,-0.000783181167208,-0.003452265402302,0.000873885175679,0,0,0,0,0.998843967914581 +42687,-0.003772241761908,-0.007225377019495,0.000360606209142,0,0,0,0,0.999414443969727 +42689,-0.007723393384367,-0.005320291034877,-0.000182785559446,0,0,0,0,1.00083422660828 +42691,-0.006098710931838,-0.003277911571786,-0.002804900985211,0,0,0,0,1.0022656917572 +42693,-0.000807412608992,-0.002431420842186,-0.004185763653368,0,0,0,0,1.00273823738098 +42695,0.003289298387244,0.000340779166436,-0.003281350480393,0,0,0,0,1.00257968902588 +42697,0.005644456949085,0.002819973742589,-0.003346634563059,0,0,0,0,1.00252950191498 +42699,0.003638415364549,0.003130702767521,-0.00449606589973,0,0,0,0,1.00255179405212 +42701,0.000804028066341,0.002271258970723,-0.002092282520607,0,0,0,0,1.00190269947052 +42703,0.001605705008842,0.001110878889449,0.001976968022063,0,0,0,0,1.00176560878754 +42705,0.000277385290246,-0.001732490491122,0.00345468474552,0,0,0,0,1.00276124477386 +42707,-0.00444476865232,-0.006905429065228,0.004357142839581,0,0,0,0,1.00298595428467 +42709,-0.006902909372002,-0.008978488855064,0.00389306107536,0,0,0,0,1.00333344936371 +42711,-0.006212950218469,-0.006193528417498,0.002598191611469,0,0,0,0,1.00440394878387 +42713,-0.005662271752954,-0.002629928523675,-7.90412450442091E-05,0,0,0,0,1.00474381446838 +42715,-0.004245683550835,0.001806105137803,-0.002071966417134,0,0,0,0,1.00491380691528 +42717,-0.000126362239826,0.008009603247046,-0.004604032728821,0,0,0,0,1.00505936145782 +42719,0.004412177484483,0.013358194380999,-0.00700674764812,0,0,0,0,1.00389349460602 +42721,0.008703962899745,0.015917040407658,-0.007929902523756,0,0,0,0,1.00229692459106 +42723,0.009346175938845,0.01404776237905,-0.005369790364057,0,0,0,0,1.00132369995117 +42725,0.005318563431501,0.010292565450072,-0.001505282474682,0,0,0,0,1.00036752223969 +42743,-0.003743691835552,-0.004806735552847,-0.00383215979673,0,0,0,0,1.00267469882965 +42745,-0.005015036091208,-0.003391179023311,-0.003324695164338,0,0,0,0,1.00225472450256 +42747,-0.003503635525703,-0.001237499644049,-0.003984205890447,0,0,0,0,1.00176727771759 +42749,-0.000233046608628,0.000995373469777,-0.003425702219829,0,0,0,0,1.00131058692932 +42751,0.001631380058825,0.006255776621401,-0.001973900245503,0,0,0,0,1.00066483020782 +42753,0.003248233115301,0.012824881821871,0.000400021555834,0,0,0,0,0.999927520751953 +42755,0.007958552800119,0.015406196005643,0.004750892985612,0,0,0,0,0.999269783496857 +42757,0.011817159131169,0.011854665353894,0.005425044335425,0,0,0,0,0.999744594097137 +42759,0.009500159882009,0.005615232978016,0.002275734907016,0,0,0,0,0.999955832958221 +42761,0.003607809310779,-0.001147521659732,-0.000660753808916,0,0,0,0,0.998929083347321 +42763,-0.00142988213338,-0.007544841617346,-0.002693229587749,0,0,0,0,0.998454868793488 +42765,-0.004680732730776,-0.009716922417283,-0.000398827221943,0,0,0,0,0.998938739299774 +42767,-0.00743770878762,-0.007942596450448,0.004136566072702,0,0,0,0,0.999691426753998 +42769,-0.007869986817241,-0.004745556041598,0.004082087893039,0,0,0,0,1.00038492679596 +42771,-0.003227335400879,-0.000401459546993,-1.01545429060934E-05,0,0,0,0,1.00044286251068 +42773,0.002361346269026,0.003383273258805,-0.003403403796256,0,0,0,0,0.999865293502808 +42775,0.004645167384297,0.003343026852235,-0.004338429775089,0,0,0,0,0.999219417572022 +42777,0.003933323547244,0.002433636458591,-0.005472554825246,0,0,0,0,0.998732209205627 +42779,0.000838320003822,0.001973016187549,-0.00452373130247,0,0,0,0,0.998447000980377 +42781,-0.001003726501949,0.00048656767467,-0.002475425135344,0,0,0,0,0.997824013233185 +42783,-0.00035247579217,0.002160871168599,0.000470381957712,0,0,0,0,0.997470319271088 +42785,0.000621854094788,0.004416820593178,0.002387026324868,0,0,0,0,0.99803763628006 +42787,-0.000664045161102,0.00170104810968,-0.000655424606521,0,0,0,0,0.998440146446228 +42789,-0.002492854371667,-0.004664263222367,-0.00317929405719,0,0,0,0,0.999155461788178 +42791,-0.003010926302522,-0.007617996074259,-0.001378055312671,0,0,0,0,1.00076961517334 +42793,-0.001473571057431,-0.006621223408729,0.000197834757273,0,0,0,0,1.00219488143921 +42795,-0.000960558420047,-0.006574580911547,0.002065697917715,0,0,0,0,1.00291693210602 +42797,-0.002005330519751,-0.004891723860055,0.002291414653882,0,0,0,0,1.00304758548737 +42799,-0.001817647833377,-0.000120403812616,-0.001645770738833,0,0,0,0,1.00233352184296 +42801,-0.000767608755268,0.003158276434988,-0.006009964738041,0,0,0,0,1.00148093700409 +42803,0.00100621196907,0.002783968346193,-0.006326741538942,0,0,0,0,1.00102972984314 +42805,0.004626047797501,0.001836017123424,-0.004211768042296,0,0,0,0,1.00051689147949 +42807,0.007067219819874,0.002610869007185,-0.001421004184522,0,0,0,0,1.00023663043976 +42809,0.007802294567227,0.006648537237197,0.001718030776829,0,0,0,0,0.999957621097565 +42811,0.005671426653862,0.009401978924871,0.00264791212976,0,0,0,0,0.999706387519836 +42813,0.001084503019229,0.004896689672023,0.002077980898321,0,0,0,0,0.999792516231537 +42815,-0.001309002516791,-0.000224547780817,0.000426014885306,0,0,0,0,0.9996297955513 +42817,-0.00026913365582,-0.000985885853879,-0.001015853136778,0,0,0,0,0.999009370803833 +42819,0.000730369705707,-0.00014010668383,0.00042028282769,0,0,0,0,0.998518049716949 +42821,-0.001402226975188,-0.000641875434667,0.002681801561266,0,0,0,0,0.998560667037964 +42823,-0.005159562919289,-0.003156516235322,0.001562135177664,0,0,0,0,0.998971939086914 +42825,-0.00702581461519,-0.00352089991793,-0.001006047823466,0,0,0,0,0.999708831310272 +42827,-0.007271330803633,-0.001661277958192,-0.003838513977826,0,0,0,0,1.00064539909363 +42829,-0.006279009860009,-0.001496224314906,-0.005100711714476,0,0,0,0,1.00130164623261 +42831,-0.001942740404047,0.000924576947,-0.003880909644067,0,0,0,0,1.00132048130035 +42833,0.004680236335844,0.004832034464926,-0.003127014730126,0,0,0,0,1.00093650817871 +42835,0.009462211281061,0.007526746485382,-0.002380784135312,0,0,0,0,1.00026845932007 +42837,0.011441754177213,0.008549767546356,-0.002063526539132,0,0,0,0,0.999435603618622 +42839,0.014073905535042,0.007641505915672,-0.001884603640065,0,0,0,0,0.998525202274322 +42841,0.014341300353408,0.005713555030525,-0.001788446330465,0,0,0,0,0.997660160064697 +42843,0.009926837868989,0.004635245073587,7.94046427472494E-05,0,0,0,0,0.997477293014526 +42845,0.003148666350171,0.002881037071347,0.002818787936121,0,0,0,0,0.998448669910431 +42847,-0.003371779341251,0.001780374790542,0.002722741803154,0,0,0,0,1.00018286705017 +42849,-0.006279557477683,-0.000460863870103,0.00114361057058,0,0,0,0,1.00230705738068 +42851,-0.006627327296883,-0.004089102614671,0.002090122317895,0,0,0,0,1.00415849685669 +42853,-0.004722569137812,-0.007060737349093,0.001212550094351,0,0,0,0,1.00473606586456 +42855,-0.002887647831813,-0.008135851472616,-0.001151136122644,0,0,0,0,1.00392162799835 +42857,-0.002863613655791,-0.005357237998396,-0.001249896828085,0,0,0,0,1.00265693664551 +42859,0.000679924269207,-0.002725389320403,-0.002230079611763,0,0,0,0,1.00151646137238 +42861,0.003740106942132,-0.000678585085552,-0.004054259043187,0,0,0,0,1.00073826313019 +42863,0.00244717602618,0.001357339555398,-0.003534255316481,0,0,0,0,1.00027227401733 +42865,0.004304642323405,0.003099782625213,-0.0038188660983,0,0,0,0,0.999415040016174 +42867,0.007567844353616,0.010338303633034,-0.002407592488453,0,0,0,0,0.99851644039154 +42869,0.007802315521985,0.01683440618217,0.000168828250025,0,0,0,0,0.999086380004883 +42871,0.006094137672335,0.016710449010134,0.0018000631826,0,0,0,0,1.00045847892761 +42873,0.004051573108882,0.014490962959826,0.001117085223086,0,0,0,0,1.00093114376068 +42875,0.002226690994576,0.009754290804267,-0.001717153703794,0,0,0,0,1.00090157985687 +42895,0.006275361869484,0.005213296040893,-0.003813913557678,0,0,0,0,1.00229167938232 +42897,0.008273843675852,0.008476503193378,-0.000924296618905,0,0,0,0,1.00191175937653 +42899,0.010884692892432,0.011375542730093,-0.001257576048374,0,0,0,0,1.00226354598999 +42901,0.010430789552629,0.013782719150186,-0.000911927781999,0,0,0,0,1.00314176082611 +42903,0.005079573486,0.014580047689378,0.003199019702151,0,0,0,0,1.0027402639389 +42905,0.001105960807763,0.010319233871996,0.004883541259915,0,0,0,0,1.00089228153229 +42907,0.001853949273936,0.004624373745173,0.001543148653582,0,0,0,0,0.999623417854309 +42909,0.001525962376036,0.001153116347268,-0.000246697716648,0,0,0,0,0.99903929233551 +42911,9.00568775250576E-05,0.000120798336866,0.002793254097924,0,0,0,0,0.998500108718872 +42913,-0.003353792708367,2.46918734774226E-05,0.004172137472779,0,0,0,0,0.998710572719574 +42915,-0.005738144740462,-0.003871002234519,0.002559206914157,0,0,0,0,0.999781966209412 +42917,-0.003860263619572,-0.008493592962623,0.000239451837842,0,0,0,0,1.00133049488068 +42919,-0.003473537042737,-0.008393376134336,-0.000232809557929,0,0,0,0,1.00274968147278 +42921,-0.004202279262245,-0.005639122333378,-0.001515095122159,0,0,0,0,1.00270712375641 +42923,-0.003427746007219,-0.002756192348897,-0.004775755107403,0,0,0,0,1.00169539451599 +42925,-0.00102367461659,-0.000152220425662,-0.008013599552214,0,0,0,0,1.00117957592011 +42927,0.004482022020966,0.002745356177911,-0.009236787445843,0,0,0,0,1.0014181137085 +42929,0.010508939623833,0.008136321790516,-0.005173174198717,0,0,0,0,1.00228154659271 +42931,0.01387523021549,0.01338523440063,6.81804813211784E-05,0,0,0,0,1.00290906429291 +42933,0.011481802910566,0.012769847176969,0.003664188552648,0,0,0,0,1.002720952034 +42935,0.004800598602742,0.009670455008745,0.003505636239424,0,0,0,0,1.00138294696808 +42937,0.001486776163802,0.004755130037665,-0.00073737843195,0,0,0,0,0.999910891056061 +42939,0.001161280786619,-0.003156763501465,-0.00476039480418,0,0,0,0,0.999825477600098 +42941,0.000812175159808,-0.008903605863452,-0.003850240260363,0,0,0,0,1.00078058242798 +42943,-0.000517938809935,-0.008887713775039,2.9844411983504E-05,0,0,0,0,1.00135946273804 +42945,-0.001291589811444,-0.007395324297249,0.004979335237294,0,0,0,0,1.00112795829773 +42947,-0.001719352905639,-0.007682088762522,0.008009252138436,0,0,0,0,1.00031399726868 +42949,-0.003220471553504,-0.006102776620537,0.006800557952374,0,0,0,0,0.999629735946655 +42951,-0.004138187039644,-0.00283076078631,0.003419431392103,0,0,0,0,0.999903559684753 +42953,-0.002399434102699,-0.00253208912909,-0.000225067284191,0,0,0,0,1.00065338611603 +42955,-0.001284569269046,-0.004779065493494,-0.001402163761668,0,0,0,0,1.00061559677124 +42957,-0.002253860468045,-0.004156655631959,-0.002180453855544,0,0,0,0,1.00013160705566 +42959,-0.002002515131608,0.001224129809998,-0.002126561012119,0,0,0,0,0.999942183494568 +42961,0.002126809675246,0.003897368442267,0.000412011344451,0,0,0,0,1.0002498626709 +42963,0.007031383924186,0.004596789833158,0.002884860383347,0,0,0,0,1.00163280963898 +42965,0.01144428178668,0.007421905174851,0.004542274866253,0,0,0,0,1.00366353988647 +42967,0.013277075253427,0.011221275664866,0.003288876032457,0,0,0,0,1.00453948974609 +42969,0.010066043585539,0.007466447073966,-0.001800807891414,0,0,0,0,1.00330722332001 +42971,0.004303793422878,-0.000988142914139,-0.005196593236178,0,0,0,0,1.00096035003662 +42973,-0.000787606288213,-0.003011243417859,-0.004314629361033,0,0,0,0,0.999115526676178 +42975,-0.00364466314204,-0.000558333878871,-0.000184792254004,0,0,0,0,0.998445093631744 +42977,-0.005302647128701,1.99456972040935E-05,0.003610769286752,0,0,0,0,0.998691856861114 +42979,-0.006363650318235,-0.002959363395348,0.005368873011321,0,0,0,0,0.99926882982254 +42981,-0.006559032481164,-0.007199597544968,0.005894420202822,0,0,0,0,0.999614119529724 +42983,-0.005302804056555,-0.00966929178685,0.001630317769013,0,0,0,0,0.999877572059631 +42985,-0.003741335822269,-0.008629379794002,-0.003916397225112,0,0,0,0,1.0006822347641 +42987,-0.003543721279129,-0.006907737348229,-0.004021370783448,0,0,0,0,1.00155901908875 +42989,-0.003785523353145,-0.007613242603838,0.000494240608532,0,0,0,0,1.00205528736115 +42991,-0.004615722224116,-0.006977163255215,0.001894763321616,0,0,0,0,1.00186848640442 +42993,-0.003084225812927,-0.002510919002816,0.001120963599533,0,0,0,0,1.0010734796524 +42995,0.001366048818454,0.003313715336844,-0.002078430727124,0,0,0,0,1.00062680244446 +42997,0.00443961750716,0.006911575328559,-0.004077667370439,0,0,0,0,1.00089859962463 +42999,0.006341866217554,0.007260805927217,-0.002152547240257,0,0,0,0,1.00130116939545 +43001,0.008374145254493,0.009093066677451,0.000558629108127,0,0,0,0,1.00158286094666 +43003,0.008769696578383,0.010684652253985,0.001232427428477,0,0,0,0,1.00128257274628 +43005,0.008676428347826,0.008335743099451,-0.003053162479773,0,0,0,0,1.0004791021347 +43007,0.007364500313997,0.00597362825647,-0.006166667211801,0,0,0,0,0.99969345331192 +43009,0.001634536660276,0.002902200212702,-0.002022081520408,0,0,0,0,0.999184131622314 +43011,-0.002891662996262,-0.00241094850935,0.00522033078596,0,0,0,0,0.999383330345154 +43013,-0.004727042745799,-0.00750337401405,0.008697712793946,0,0,0,0,0.99995744228363 +43015,-0.005928071215749,-0.008220987394452,0.008562211878598,0,0,0,0,1.00055766105652 +43017,-0.006534959189594,-0.005334089510143,0.004329358693212,0,0,0,0,1.00144672393799 +43019,-0.0060446546413,-0.004758386407048,-0.001366689801216,0,0,0,0,1.00234520435333 +43021,-0.00687322113663,-0.008312377147377,-0.004392832517624,0,0,0,0,1.00305986404419 +43023,-0.006554843392223,-0.011618669144809,-0.003940927330405,0,0,0,0,1.00357568264008 +43025,-0.006054202094674,-0.010489804670215,-0.000304703309666,0,0,0,0,1.00350570678711 +43027,-0.004919765982777,-0.005377994850278,0.00275469222106,0,0,0,0,1.00276041030884 +43029,-0.00135107873939,0.000132113869768,0.003686116542667,0,0,0,0,1.00168406963348 +43031,0.002881046617404,0.00441551534459,0.001116754836403,0,0,0,0,1.00054442882538 +43033,0.0056810406968,0.007652940694243,-0.002856136765331,0,0,0,0,1.00001788139343 +43035,0.008169079199433,0.011242614127696,-0.003631782485172,0,0,0,0,1.00021326541901 +43037,0.009346914477646,0.013786187395454,-0.002593616489321,0,0,0,0,1.00060212612152 +43039,0.008394717238843,0.011248169466853,-0.002282513072714,0,0,0,0,1.00040566921234 +43041,0.006447176914662,0.006797097157687,-0.00203646812588,0,0,0,0,0.99931389093399 +43043,0.003302583703771,0.005239024758339,-0.000388329150155,0,0,0,0,0.998535633087158 +43045,-0.001067899633199,0.002675655065104,0.001123071531765,0,0,0,0,0.99872761964798 +43047,-0.002723472192884,-0.000964232487604,0.001200250000693,0,0,0,0,0.999290347099304 +43049,-0.00160610943567,-0.00195332034491,0.002611191244796,0,0,0,0,0.999781370162964 +43051,-0.001209189416841,-0.000838959764224,0.003545879153535,0,0,0,0,1.00050282478333 +43053,8.14809900475666E-05,0.000360454287147,0.000759530346841,0,0,0,0,1.00102758407593 +43055,0.000143486482557,-0.000427707913332,-0.002780448179692,0,0,0,0,1.0011899471283 +43057,-0.001241271500476,-0.002137197181582,-0.002841970184818,0,0,0,0,1.00124764442444 +43059,-0.002442200900987,-0.001969747245312,-0.001296873437241,0,0,0,0,1.00047779083252 +43061,-0.003809735877439,-0.004165345802903,-0.000904758402612,0,0,0,0,0.999337196350098 +43063,-0.003761215833947,-0.008728982880712,0.001222909893841,0,0,0,0,0.998828709125519 +43065,0.000107472398668,-0.008722509257495,0.002409387845546,0,0,0,0,0.999191224575043 +43067,0.00570399267599,-0.003305266844109,-0.000343512510881,0,0,0,0,0.999821543693542 +43069,0.007784568239003,0.003217892255634,-0.00330405915156,0,0,0,0,1.00024175643921 +43071,0.008997807279229,0.009407083503902,-0.002679869299755,0,0,0,0,1.00049090385437 +43073,0.010054514743388,0.012179733254016,-0.000550757918973,0,0,0,0,1.00117301940918 +43075,0.008971970528364,0.008010006509721,-0.002619362669066,0,0,0,0,1.00197231769562 +43077,0.00610364601016,0.001455916790292,-0.007017379626632,0,0,0,0,1.00164937973022 +43079,0.002910151612014,-0.001611123210751,-0.006642538122833,0,0,0,0,1.00045359134674 +43081,0.000374539376935,0.000129109903355,-0.001382446265779,0,0,0,0,0.99954092502594 +43083,-0.001202422194183,-0.001244133454748,0.000291396048851,0,0,0,0,0.999534130096436 +43085,-0.002200025366619,-0.003344514174387,0.001487148576416,0,0,0,0,0.999919950962067 +43087,-0.002127948682755,-0.003341829171404,0.004100129473954,0,0,0,0,1.00072574615479 +43089,-0.000235664716456,-0.002907568821684,0.001463467255235,0,0,0,0,1.00168144702911 +43091,0.002282358240336,-0.00242524035275,-0.001304660923779,0,0,0,0,1.00218880176544 +43093,0.001945939147845,-0.000906184548512,-0.00033058016561,0,0,0,0,1.00226724147797 +43095,0.001915552536957,-0.000756357971113,0.000578322913498,0,0,0,0,1.00184261798859 +43097,0.00234948261641,-0.001330911763944,0.001255941810086,0,0,0,0,1.00116086006165 +43099,0.001992886187509,-0.00340455560945,6.81219826219603E-05,0,0,0,0,1.00109875202179 +43101,0.00189168646466,-0.005158636718988,0.001932656741701,0,0,0,0,1.00122308731079 +43103,0.002809205558151,-0.00395129295066,0.005019871518016,0,0,0,0,1.00134694576263 +43105,0.003147584153339,-0.00204102974385,0.003253396600485,0,0,0,0,1.00113666057587 +43107,0.001883163815364,-0.002428667852655,-0.000512544764206,0,0,0,0,1.00055801868439 +43125,0.003839490935206,-0.000986802042462,-0.002973572583869,0,0,0,0,1.00213277339935 +43127,0.001333049265668,0.000298181897961,-0.004534784238786,0,0,0,0,1.00184333324432 +43129,-0.001238240743987,0.000592644908465,-0.00232519977726,0,0,0,0,1.00088095664978 +43131,-0.001531822374091,0.002543029142544,0.001909235259518,0,0,0,0,1.00003743171692 +43133,0.000706256134436,0.003664604853839,0.004966509528458,0,0,0,0,0.999748528003693 +43135,0.001820459030569,0.002030106727034,0.003167593851686,0,0,0,0,0.999349176883698 +43137,-0.001128578092903,0.000247526884777,0.001613628235646,0,0,0,0,0.999054193496704 +43139,-0.003811122616753,-0.002122559119016,0.00262032286264,0,0,0,0,0.999337077140808 +43141,-0.002962810918689,-0.002111555077136,0.003133712569252,0,0,0,0,0.999967813491821 +43143,-0.00063021335518,0.000625638058409,0.002398012205958,0,0,0,0,1.00041091442108 +43145,-6.57934060654952E-06,-0.000570997246541,0.001165791181847,0,0,0,0,1.00056731700897 +43147,0.001327004050836,-0.002917325822636,-0.000213679188164,0,0,0,0,1.00050699710846 +43149,0.00293599255383,-0.002475996036083,-0.000334004522301,0,0,0,0,1.00061023235321 +43151,0.002909101545811,-0.00261122873053,0.002702125580981,0,0,0,0,1.00064086914063 +43153,0.002596469363198,-0.003132459009066,0.00384297571145,0,0,0,0,1.00051009654999 +43155,0.000267169438303,-0.001484603155404,0.001608603750356,0,0,0,0,1.00038397312164 +43157,-0.001250938512385,0.001367793884128,-0.000235145766055,0,0,0,0,1.00074625015259 +43159,0.00102358602453,0.001834701979533,-0.001716836355627,0,0,0,0,1.00145626068115 +43161,0.004177145194262,-0.000309188850224,-0.002934550866485,0,0,0,0,1.00200545787811 +43163,0.005711074452847,-0.002353446325287,-0.004768306855112,0,0,0,0,1.00225651264191 +43165,0.005141768138856,-0.001889816601761,-0.003137831110507,0,0,0,0,1.00199401378632 +43167,0.001947467564605,2.52614972851006E-05,0.000430487154517,0,0,0,0,1.00143921375275 +43169,-0.000506582786329,6.43344378659094E-07,0.000485005410155,0,0,0,0,1.00115561485291 +43171,-0.001540041761473,-4.78378606203478E-05,-0.002483004936948,0,0,0,0,1.000812292099 +43173,-0.002468222286552,0.000569845025893,-0.001977782230824,0,0,0,0,1.00020122528076 +43175,0.000620220554993,0.001610041130334,-0.001083730137907,0,0,0,0,1.00011825561523 +43177,0.003015514928848,0.001760814571753,-0.001257653930224,0,0,0,0,1.00023710727692 +43179,0.002602622844279,0.001305004581809,-0.000246493378654,0,0,0,0,1.00022923946381 +43181,0.000484147953102,0.001179777784273,0.00072784157237,0,0,0,0,1.00038814544678 +43183,0.000444649253041,-0.000598493614234,0.001875337795354,0,0,0,0,1.0005167722702 +43185,0.002660202793777,-0.003915759269148,-0.001184111810289,0,0,0,0,1.00049793720245 +43187,0.001109687844291,-0.002860658336431,-0.001517493161373,0,0,0,0,1.00045561790466 +43189,-0.001979613676667,-0.000490178412292,0.000716728623956,0,0,0,0,1.00034081935883 +43191,-0.002476567635313,-0.00133271550294,0.00204040738754,0,0,0,0,1.00002324581146 +43193,-0.000798246008344,-0.003590870648623,0.001430166768841,0,0,0,0,0.999794602394104 +43195,0.000147646234836,-0.000464626384201,-0.002681242767721,0,0,0,0,0.999737501144409 +43197,0.000292676035315,0.005131938494742,-0.002047694986686,0,0,0,0,0.999856412410736 +43199,-0.000772849423811,0.0035893288441,-0.00011373628513,0,0,0,0,1.00020170211792 +43201,-0.000508577213623,-0.002567283576354,0.001691126613878,0,0,0,0,1.00028085708618 +43203,0.002653256757185,-0.00604895176366,0.003365684300661,0,0,0,0,0.999951899051666 +43205,0.004818989429623,-0.006000757217407,0.001155290636234,0,0,0,0,0.999582767486572 +43207,0.00302269984968,-0.003943873103708,-0.000663003243972,0,0,0,0,0.999628603458404 +43209,-0.001766666769981,-0.00289915734902,-0.001667408272624,0,0,0,0,0.999942183494568 +43211,-0.003938824869692,-0.004049847368151,-0.001501012709923,0,0,0,0,1.00012695789337 +43213,-0.001687276992016,-0.004056120757014,-0.001026397687383,0,0,0,0,1.00011575222015 +43215,0.002996457740664,-0.001985061680898,-0.000559040694498,0,0,0,0,1.0001562833786 +43217,0.006557796616107,0.000820754445158,-0.000360611971701,0,0,0,0,1.00002670288086 +43219,0.005467772018164,-6.00838684476912E-05,-0.000831603305414,0,0,0,0,0.999641358852386 +43221,0.004078515339643,-0.00166507717222,-0.00136706023477,0,0,0,0,0.999564111232758 +43223,0.0045524709858,-0.002727027982473,-0.001873541274108,0,0,0,0,1.00000476837158 +43225,0.002414359245449,-0.005869247019291,-0.001017626607791,0,0,0,0,1.00041460990906 +43227,-0.000277120445389,-0.006319751963019,0.00050031230785,0,0,0,0,1.00073349475861 +43229,0.000281761429505,-0.002880035201088,0.001368573168293,0,0,0,0,1.00103199481964 +43231,0.001933286897838,5.30734032508917E-05,0.000362003658665,0,0,0,0,1.00125372409821 +43233,0.001244131359272,-0.001175842713565,-0.00310546788387,0,0,0,0,1.00134646892548 +43235,0.000648876011837,-0.002219035523012,-0.004273941274732,0,0,0,0,1.00135898590088 +43237,0.000766029290389,0.000502567738295,-0.001171223120764,0,0,0,0,1.00077509880066 +43239,-8.81185114849359E-05,0.002805809723213,0.001197481178679,0,0,0,0,0.999824941158295 +43241,-0.000674598792102,0.003663326147944,0.000470028811833,0,0,0,0,0.999167084693909 +43243,0.001099816989154,0.002855994738638,-0.001016665017232,0,0,0,0,0.999256014823914 +43245,0.002532799961045,0.001548980711959,-0.000879697909113,0,0,0,0,0.999260663986206 +43247,0.002457104856148,-0.00083329732297,-0.000871697324328,0,0,0,0,0.999100625514984 +43249,0.002177821472287,-0.001718956395052,-0.00324023142457,0,0,0,0,0.998897969722748 +43251,0.001979472581297,-0.001581134041771,-0.002474002307281,0,0,0,0,0.99871164560318 +43253,0.005392955616117,-0.000208001118153,-0.000817427528091,0,0,0,0,0.998876333236694 +43255,0.008065778762102,0.000303961656755,0.001629190868698,0,0,0,0,0.999286711215973 +43257,0.003913802560419,-0.001727773109451,0.003559049451724,0,0,0,0,0.999784886837006 +43281,-0.001064964570105,-0.004181126598269,-5.2754141506739E-05,0,0,0,0,1.00167977809906 +43283,-0.001443705637939,-0.003870703745633,0.000548544107005,0,0,0,0,1.0012903213501 +43285,-0.002059291349724,-0.000459790753666,-0.000880238134414,0,0,0,0,1.00091898441315 +43287,-0.001884318306111,0.001749780843966,-0.00023744443024,0,0,0,0,1.00076568126678 +43289,-0.000220887071919,0.001881639705971,-0.0022378989961,0,0,0,0,1.00090503692627 +43291,0.000309806200676,0.002574281999841,-0.005330339539796,0,0,0,0,1.00131785869598 +43293,-0.001004603574984,0.004431035369635,-0.004540957510471,0,0,0,0,1.00157749652863 +43295,-0.002123034093529,0.006094478070736,-0.000655966752674,0,0,0,0,1.00133633613586 +43297,0.000139322000905,0.003991735633463,0.001291015534662,0,0,0,0,1.00091814994812 +43299,0.001970338169485,6.38331766822375E-05,-0.002165050012991,0,0,0,0,1.00072836875916 +43301,0.001035578548908,-0.004052265081555,-0.005168683826923,0,0,0,0,1.00077021121979 +43303,-0.000441010692157,-0.006294500082731,-0.003265957580879,0,0,0,0,1.00062024593353 +43305,0.000599087157752,-0.004515033215284,0.000212042010389,0,0,0,0,0.99998265504837 +43307,0.001425311202183,-0.001042736344971,0.000299554114463,0,0,0,0,0.999354958534241 +43309,0.000421893433668,0.000683229183778,-0.000369659945136,0,0,0,0,0.999272465705872 +43311,0.000781517708674,-0.001595561509021,0.00192255852744,0,0,0,0,0.999500215053558 +43313,0.000360259960871,-0.005865049548447,0.004676375072449,0,0,0,0,0.999579906463623 +43315,-0.002006981754676,-0.006827030796558,0.003278750926256,0,0,0,0,0.999498605728149 +43317,-0.002841199049726,-0.003425036091357,-0.001372526865453,0,0,0,0,0.999660432338715 +43319,-0.001394667080604,3.13870368700009E-05,-0.001586405560374,0,0,0,0,0.999919652938843 +43321,0.000104105412902,-0.000508724944666,-0.000429807172623,0,0,0,0,1.00031185150146 +43323,0.000403745187214,-0.002588049741462,-0.0008985340246,0,0,0,0,1.00088679790497 +43325,0.000195939035621,-0.00202521821484,-0.001202302635647,0,0,0,0,1.00086772441864 +43327,0.000119349046145,0.000608126923908,-0.000344778469298,0,0,0,0,1.0004255771637 +43329,0.001832982059568,0.001262575271539,0.001067085308023,0,0,0,0,1.00034427642822 +43331,0.003645144402981,0.000118737647426,-7.25832651369274E-05,0,0,0,0,1.0008682012558 +43333,0.003566350322217,-2.03884756047046E-05,-0.001224232488312,0,0,0,0,1.00142252445221 +43335,0.002644715132192,-0.001260663964786,0.000772777129896,0,0,0,0,1.00159335136414 +43337,0.002025449182838,-0.002972728107125,0.002480783499777,0,0,0,0,1.00148868560791 +43339,0.000533795158844,-0.002940466394648,0.001662151073106,0,0,0,0,1.00145971775055 +43341,-0.001891775638796,-0.002726687816903,-0.001581098185852,0,0,0,0,1.00164043903351 +43343,-0.002824580529705,-0.001323109259829,-0.001967975171283,0,0,0,0,1.00182712078094 +43345,-0.002262390451506,0.001407339354046,0.000197384462808,0,0,0,0,1.0018355846405 +43347,-0.000758115551434,0.004315013531595,0.000965238665231,0,0,0,0,1.00164747238159 +43349,0.00247888895683,0.004973631352186,-0.000226041069254,0,0,0,0,1.00135314464569 +43351,0.005043881945312,0.00380050460808,-0.001331462175585,0,0,0,0,1.0009480714798 +43353,0.004092826507986,0.003766806796193,-0.001157602877356,0,0,0,0,1.00082719326019 +43355,0.002581730950624,0.003383463481441,-0.002123133977875,0,0,0,0,1.0008978843689 +43357,0.000881892512552,0.000915484095458,-0.004437672439963,0,0,0,0,1.00096249580383 +43359,0.000332786788931,-0.002859387779608,-0.006470684427768,0,0,0,0,1.00109386444092 +43361,0.000505751988385,-0.003313314868137,-0.004047575872391,0,0,0,0,1.00143122673035 +43363,0.00106492114719,-0.001636942266487,0.000669136235956,0,0,0,0,1.00197172164917 +43365,0.001718094805256,-0.00075098691741,0.004022805020213,0,0,0,0,1.00248074531555 +43367,0.001569050131366,0.001329750404693,0.005747573450208,0,0,0,0,1.00238537788391 +43369,-0.000187595505849,0.000663557031658,0.003906859550625,0,0,0,0,1.00167393684387 +43371,-0.001732277800329,-0.001589147374034,-0.00050195568474,0,0,0,0,1.00092852115631 +43373,0.000294036028208,-0.002816561376676,-0.004264358431101,0,0,0,0,1.00046801567078 +43375,0.002947895089164,-0.003024231409654,-0.005428022705019,0,0,0,0,1.00038051605225 +43377,0.001562049728818,0.000425126432674,-0.003937371540815,0,0,0,0,1.0008020401001 +43379,-0.000746926409192,0.002480758121237,-7.01406634107116E-06,0,0,0,0,1.00156593322754 +43381,-0.003461508080363,-0.000593751086853,0.002875100122765,0,0,0,0,1.00204479694366 +43383,-0.002917724195868,-0.003638131311163,0.002772609703243,0,0,0,0,1.00182163715363 +43385,-7.74836444179527E-05,-0.003903244389221,0.000893866759725,0,0,0,0,1.00149345397949 +43387,-0.000154084220412,-0.002367700682953,0.001223647268489,0,0,0,0,1.00127553939819 +43389,-0.00072848162381,-2.48346059379401E-05,0.002476754132658,0,0,0,0,1.00098216533661 +43391,0.000761503586546,0.00384561647661,0.00134395074565,0,0,0,0,1.00091779232025 +43393,0.00281902262941,0.005416390486062,-0.000540327222552,0,0,0,0,1.00083923339844 +43395,0.000769628153648,0.004190486390144,-0.002020814921707,0,0,0,0,1.00054240226746 +43397,-0.001427081879228,0.00205287639983,-0.002929158508778,0,0,0,0,1.00039505958557 +43399,-0.000450219609775,-0.001720441039652,-0.001693071448244,0,0,0,0,1.00075256824493 +43401,0.001469837501645,-0.00429811514914,0.00090048846323,0,0,0,0,1.00131499767303 +43403,0.002936040749773,-0.002165365964174,0.001387622090988,0,0,0,0,1.00154376029968 +43405,0.001151822973043,0.000691715802532,0.002205199794844,0,0,0,0,1.00146245956421 +43407,-0.002213144674897,0.000580115825869,0.001996884122491,0,0,0,0,1.0009628534317 +43409,-0.003960002213717,-0.00067001656862,7.59040922275744E-05,0,0,0,0,1.00022757053375 +43411,-0.002419974189252,-0.000166640485986,-0.001677158055827,0,0,0,0,0.999949097633362 +43413,3.45900843967684E-05,-5.88183720537927E-05,-0.000879618455656,0,0,0,0,1.00044143199921 +43435,-0.001821580342948,-0.00262498180382,-0.003116199979559,0,0,0,0,0.998512804508209 +43437,0.000548417214304,-0.002645084867254,-0.003057736204937,0,0,0,0,0.999268651008606 +43439,0.000575137324631,0.000555523496587,-0.001647281576879,0,0,0,0,1.00034952163696 +43441,-0.000189195052371,0.00265080970712,-0.002829510020092,0,0,0,0,1.00137197971344 +43443,0.001049613696523,0.00182157382369,-0.003460888052359,0,0,0,0,1.00203549861908 +43445,0.002985978731886,-0.001279160613194,-0.001426003407687,0,0,0,0,1.00191378593445 +43447,0.000136889619171,-0.003307613776997,-0.00018091511447,0,0,0,0,1.0012618303299 +43449,-0.003298142924905,-0.000757690693717,-0.001003089011647,0,0,0,0,1.00057435035706 +43451,-0.000873369630426,0.003829970955849,-3.75345880456734E-05,0,0,0,0,0.999862432479858 +43453,0.001533487811685,0.004031135700643,-0.000906534958631,0,0,0,0,0.999007821083069 +43455,0.000860941596329,0.001707573886961,-0.001704170834273,0,0,0,0,0.998214364051819 +43457,0.000153245418915,0.000707134197,-0.000765898788814,0,0,0,0,0.997823894023895 +43459,0.001809300505556,-0.002402152866125,-0.001430855016224,0,0,0,0,0.997963309288025 +43461,0.003309811698273,-0.003939441405237,-0.003159184241667,0,0,0,0,0.998343110084534 +43463,0.002399191260338,-0.00220010150224,-0.000490142148919,0,0,0,0,0.998231172561646 +43465,0.001443174667656,-0.000491056416649,0.001765656401403,0,0,0,0,0.997902512550354 +43467,0.001569331041537,0.001485146582127,-0.000789827434346,0,0,0,0,0.9978107213974 +43469,0.002220757072791,0.002817207248881,-0.003116838401183,0,0,0,0,0.997707366943359 +43471,0.002544153481722,0.001843489590101,-0.003347842954099,0,0,0,0,0.997924029827118 +43473,0.003591695101932,-0.000933735107537,-0.00237735779956,0,0,0,0,0.998525857925415 +43475,0.003270768560469,-0.000395645125536,-0.001043134136125,0,0,0,0,0.999127805233002 +43477,0.001252776361071,0.003307529725134,-0.000100006982393,0,0,0,0,0.999701738357544 +43479,0.000169109131093,0.004052991978824,0.001355172949843,0,0,0,0,0.999822497367859 +43481,0.001100890571252,0.000730010098778,0.001218499382958,0,0,0,0,0.99972128868103 +43483,0.001814130228013,-0.0025631620083,-0.000276049366221,0,0,0,0,0.999514997005463 +43485,0.0020096602384,-0.003099908586591,-0.001346837147139,0,0,0,0,0.999048590660095 +43487,0.002755743684247,-0.003684579394758,-0.001465588924475,0,0,0,0,0.998899638652802 +43489,0.002145394450054,-0.00545711023733,-0.000566487375181,0,0,0,0,0.99918407201767 +43491,0.003568600164726,-0.006790942046791,3.5656015825225E-05,0,0,0,0,0.999503970146179 +43493,0.005574088077992,-0.005626705940813,-0.001936229644343,0,0,0,0,0.999741077423096 +43495,0.00398707203567,-0.002888485556468,-0.001984816975892,0,0,0,0,1.0000364780426 +43497,0.002638392150402,-0.002481864765286,0.001147952745669,0,0,0,0,1.00031435489655 +43499,0.0016363466857,-0.002450459869578,0.001734146149829,0,0,0,0,1.00056135654449 +43501,0.002888384042308,-0.00053079315694,0.00023651959782,0,0,0,0,1.0007928609848 +43503,0.005140368826687,0.002091267611831,-0.000513888895512,0,0,0,0,1.00106763839722 +43505,0.003256351919845,0.002694101072848,8.1023586972151E-05,0,0,0,0,1.00177884101868 +43507,-0.000448805600172,0.001058391411789,0.000854177691508,0,0,0,0,1.00233936309814 +43509,-0.001555919181556,0.001574300345965,0.000936978205573,0,0,0,0,1.00192189216614 +43511,-0.001407793490216,0.003844985272735,-0.000932260008994,0,0,0,0,1.00121057033539 +43513,-0.000922209292185,0.006128369830549,-0.002248756121844,0,0,0,0,1.00090146064758 +43515,-0.002094122814015,0.006904124747962,-0.00208979845047,0,0,0,0,1.00060760974884 +43517,-0.002057478064671,0.005424209404737,-0.001301969401538,0,0,0,0,1.00023770332336 +43519,0.000271168159088,0.005411939229816,0.002326688729227,0,0,0,0,1.00001180171967 +43521,0.002385853556916,0.005515685770661,0.002343045314774,0,0,0,0,0.999936938285827 +43523,0.003095716936514,0.002844236791134,0.001294944435358,0,0,0,0,0.999937474727631 +43525,0.001997083891183,-4.26589031121694E-05,0.000481984257931,0,0,0,0,1.00008547306061 +43527,0.000174546366907,-0.001371944090351,0.000153665387188,0,0,0,0,1.00049912929535 +43529,-0.000525667506736,-0.002347599714994,0.001833889866248,0,0,0,0,1.00121581554413 +43531,-0.000796155189164,-0.001997488783672,0.002286607166752,0,0,0,0,1.0015230178833 +43533,-0.000797213171609,-0.001131912460551,-0.000614177202806,0,0,0,0,1.00095283985138 +43535,-0.000408302934375,0.000928171270061,-0.001389050506987,0,0,0,0,1.00012695789337 +43537,-0.000185763492482,0.00051515357336,0.000876476173289,0,0,0,0,0.99972277879715 +43539,4.26199818548412E-07,-0.002585509326309,0.003387961769477,0,0,0,0,1.00014019012451 +43541,0.0011540845735,-0.004066081251949,0.00279015256092,0,0,0,0,1.00083065032959 +43543,0.001214810297824,-0.002104024635628,0.00139499513898,0,0,0,0,1.00103652477264 +43545,0.000554461788852,-0.002217816188931,0.002116999356076,0,0,0,0,1.00088560581207 +43547,-0.000323295680573,-0.002872013486922,0.001797990989871,0,0,0,0,1.00076544284821 +43549,-0.001222585327923,-0.002734985202551,-0.001301737036556,0,0,0,0,1.00074243545532 +43551,8.57303311931901E-05,-0.003305678488687,-0.00362969795242,0,0,0,0,1.00091278553009 +43553,0.001926945056766,0.000169031205587,-0.001331314328127,0,0,0,0,1.00145423412323 +43555,0.001719940337352,0.005207407753915,0.002353436779231,0,0,0,0,1.0016405582428 +43557,-0.000457336311229,0.004712492693216,0.003523955121636,0,0,0,0,1.00148832798004 +43559,-0.001993250800297,0.002606357680634,0.003573380643502,0,0,0,0,1.00131595134735 +43561,-0.003019966185093,0.00450064567849,0.002039371524006,0,0,0,0,1.00122845172882 +43563,-0.003420996014029,0.006252606865019,-0.000995752634481,0,0,0,0,1.00121903419495 +43565,-0.003168916096911,0.002795625943691,-0.0011985959718,0,0,0,0,1.00115072727203 +43567,-0.003150461008772,-0.001218245131895,0.002351752249524,0,0,0,0,1.00113236904144 +43585,-0.00052893202519,0.003933064639568,0.000738636474125,0,0,0,0,0.998282134532928 +43587,-0.001491295406595,0.003588341642171,-0.000358955381671,0,0,0,0,0.9980428814888 +43589,-0.000807039032225,0.000143377954373,-3.62020073225722E-05,0,0,0,0,0.998312830924988 +43591,-0.001046441379003,-0.004013192374259,-0.000370377674699,0,0,0,0,0.999275326728821 +43593,-0.002041345462203,-0.00582823716104,-0.001037657726556,0,0,0,0,1.00001978874207 +43595,7.1363385359291E-05,-0.005166670307517,-0.001071880804375,0,0,0,0,1.00034296512604 +43597,0.005760867148638,-0.002491988008842,0.000354024843546,0,0,0,0,1.00070464611053 +43599,0.007074453402311,-0.000908043934032,-0.001088227843866,0,0,0,0,1.0008864402771 +43601,0.002810702193528,-0.001487324829213,-0.003489885944873,0,0,0,0,1.00056338310242 +43603,0.001528914319351,0.000429011735832,-0.001955020008609,0,0,0,0,1.000075340271 +43605,0.00037212841562,0.001198089099489,0.001376802683808,0,0,0,0,0.999815225601196 +43607,-0.001307494938374,-0.002237043576315,0.002868110779673,0,0,0,0,0.999922633171082 +43609,-0.00032553874189,-0.004735165275633,0.003856310620904,0,0,0,0,1.00028109550476 +43611,-0.000841528002638,-0.004661424551159,0.004094772506505,0,0,0,0,1.00066411495209 +43613,-0.002313679084182,-0.002832754980773,0.001530795823783,0,0,0,0,1.00104641914368 +43615,-0.000317943398841,-0.000179004651727,-0.001971520483494,0,0,0,0,1.00147271156311 +43617,0.002625089138746,0.001508462009951,-0.003264045342803,0,0,0,0,1.002028465271 +43619,0.003184168832377,0.002735276240855,0.000339952326613,0,0,0,0,1.00243246555328 +43621,0.002974126022309,0.00224103173241,0.002898062579334,0,0,0,0,1.00220859050751 +43623,0.003561591729522,0.000141565775266,0.002577660605311,0,0,0,0,1.00149714946747 +43625,0.002948582405224,-0.001145975897089,-1.52099664774141E-05,0,0,0,0,1.00120389461517 +43627,0.003433858510107,-0.001607753685676,-0.004817281849682,0,0,0,0,1.00121164321899 +43629,0.003900495357811,-0.002423375844955,-0.004343300126493,0,0,0,0,1.00120365619659 +43631,0.00098705268465,-0.002975011011586,-0.000102597412479,0,0,0,0,1.00120103359222 +43633,-0.002235438907519,-0.003202842082828,0.000488184916321,0,0,0,0,1.00147032737732 +43635,-0.001525196712464,-0.001659919857048,-0.003135001985356,0,0,0,0,1.00175356864929 +43637,-0.000432758155512,0.004005310125649,-0.004413492511958,0,0,0,0,1.00190269947052 +43639,-0.001548163825646,0.005431466735899,-0.000900978804566,0,0,0,0,1.00194418430328 +43641,-0.001032249303535,0.001493273884989,0.000781571900006,0,0,0,0,1.00164246559143 +43643,0.000994336442091,-0.001315005705692,-0.001721472945064,0,0,0,0,1.00083494186401 +43645,-0.001048914622515,-0.000481170631247,-0.0010790086817,0,0,0,0,1.00017404556274 +43647,-0.00221401755698,0.000605957291555,0.002130066743121,0,0,0,0,1.00004494190216 +43649,-0.000395278562792,-0.000940759200603,0.002173075685278,0,0,0,0,1.00029802322388 +43651,0.002276031300426,-0.003089553676546,0.000622664287221,0,0,0,0,1.00049042701721 +43653,0.004593682941049,-0.003170447656885,-0.000956031261012,0,0,0,0,1.00065052509308 +43655,0.004608229734004,-0.001757975202054,-0.002167635364458,0,0,0,0,1.00109970569611 +43657,0.003647939302027,0.000545504852198,-0.004687269683927,0,0,0,0,1.00171709060669 +43659,0.003110382938758,0.002599944593385,-0.006123183760792,0,0,0,0,1.00222265720367 +43661,0.002657070290297,0.000854235317092,-0.003200018778443,0,0,0,0,1.00230300426483 +43663,0.000490018166602,-0.001182070816867,0.001543651334941,0,0,0,0,1.00205755233765 +43665,-0.002838196698576,-0.000294416706311,0.002585792914033,0,0,0,0,1.00177919864655 +43667,-0.003858569543809,0.001896110712551,0.00156495522242,0,0,0,0,1.00163841247559 +43669,0.000136567949085,0.002368488814682,-0.000299842795357,0,0,0,0,1.00162088871002 +43671,0.002882953034714,-0.000745423196349,-0.000536164501682,0,0,0,0,1.00171005725861 +43673,0.000664263323415,-0.005291686858982,0.000768988742493,0,0,0,0,1.00189745426178 +43675,-0.001125250128098,-0.00675592571497,0.001239759381861,0,0,0,0,1.00206387042999 +43677,-0.000886110065039,-0.004899978172034,-0.000298081024084,0,0,0,0,1.00224912166595 +43679,0.001442161854357,-0.00271077058278,-0.000416153925471,0,0,0,0,1.00219523906708 +43681,0.004289593547583,-0.00220206938684,-0.000478655158076,0,0,0,0,1.00189411640167 +43683,0.003333839122206,-0.00145005970262,-0.001905605313368,0,0,0,0,1.00158703327179 +43685,0.001249942695722,-0.000598649552558,-0.001801346079446,0,0,0,0,1.00126385688782 +43687,-0.000675945077091,-0.000500701600686,0.001895151450299,0,0,0,0,1.0005989074707 +43689,-0.001187837449834,-0.00240830425173,0.004105353727937,0,0,0,0,0.999667644500732 +43691,-0.001045783283189,-0.006178092677146,0.001382466056384,0,0,0,0,0.999063670635223 +43693,-0.000827993557323,-0.007276212796569,-0.001346765784547,0,0,0,0,0.998681247234344 +43695,-0.000724704121239,-0.003635065164417,-0.001153145101853,0,0,0,0,0.998358488082886 +43697,0.000607419176959,0.000509313831571,0.00114080356434,0,0,0,0,0.998508512973785 +43699,0.001830481225625,0.002176031470299,0.002095530740917,0,0,0,0,0.999367892742157 +43701,0.002474784851074,0.003118069143966,-0.000102999212686,0,0,0,0,1.00075078010559 +43703,0.002316024620086,0.002449478954077,-0.001100526773371,0,0,0,0,1.00186336040497 +43705,0.001888525323011,0.001933398540132,-9.62362901191227E-05,0,0,0,0,1.00215244293213 +43707,0.001119594438933,0.000526283285581,0.000454829685623,0,0,0,0,1.002028465271 +43709,0.001528411055915,0.000314994627843,-0.000274314719718,0,0,0,0,1.00205790996552 +43711,0.000127074905322,0.002206086413935,-0.000657955009956,0,0,0,0,1.00239300727844 +43713,-0.001916733221151,0.001278030569665,0.00087242887821,0,0,0,0,1.00253367424011 +43715,-0.00206640525721,-0.001765244873241,0.00048188213259,0,0,0,0,1.00237786769867 +43717,-0.000757003901526,-0.00278113828972,-0.000609031645581,0,0,0,0,1.00216698646545 +43719,0.0001085538388,0.000665969564579,-0.00281836441718,0,0,0,0,1.00180435180664 +43737,0.002635405166075,0.001434325706214,-0.001597890048288,0,0,0,0,1.00069487094879 +43739,0.001801407779567,0.000638436351437,0.000859651016071,0,0,0,0,1.00035858154297 +43741,0.000317154859658,0.003809089073911,0.002631365321577,0,0,0,0,1.00007975101471 +43743,0.000849608681165,0.005263505503535,0.003191767260432,0,0,0,0,1.00008881092072 +43745,0.00305357738398,0.004344592802227,0.001044389442541,0,0,0,0,1.00020027160645 +43747,0.005136111751199,0.001368669327348,0.000227683311095,0,0,0,0,0.999921381473541 +43749,0.003548237262294,-0.000656521820929,0.00124863802921,0,0,0,0,0.999403715133667 +43751,0.000536295119673,0.00020263280021,-0.001472420524806,0,0,0,0,0.999203443527222 +43753,-0.002868332667276,0.001326766563579,-0.00509084481746,0,0,0,0,0.999582350254059 +43755,-0.00476247491315,0.001044794917107,-0.004945307038724,0,0,0,0,1.00036430358887 +43757,-0.003655424341559,-0.000646272790618,-0.001946939737536,0,0,0,0,1.0010199546814 +43759,-0.001595503883436,-0.002515052910894,-0.001715836813673,0,0,0,0,1.00135803222656 +43761,-0.000118936382933,-0.002683557104319,-0.001243497943506,0,0,0,0,1.00200605392456 +43763,0.000364651990822,0.001139658968896,0.001480523962528,0,0,0,0,1.00311934947968 +43765,0.000186684643268,0.0039591062814,0.002062115352601,0,0,0,0,1.00382459163666 +43767,-0.001428271876648,0.004039676859975,-0.000719554023817,0,0,0,0,1.00369942188263 +43769,-0.001818539225496,0.003101775655523,-0.003065064782277,0,0,0,0,1.00331676006317 +43771,-0.000514110317454,0.002683908911422,-0.003051371080801,0,0,0,0,1.00280261039734 +43773,-0.001202317187563,0.000878057209775,-0.002298892941326,0,0,0,0,1.00165390968323 +43775,-0.00394258229062,-0.001373407430947,-0.002371647628024,0,0,0,0,1.00042402744293 +43777,-0.003367397701368,-0.002111786743626,-0.002984248800203,0,0,0,0,1.00023090839386 +43779,-0.000985752791166,-0.00266973185353,-0.001460670842789,0,0,0,0,1.00075817108154 +43781,-0.001868830760941,-0.003111139172688,0.002179210307077,0,0,0,0,1.00094473361969 +43783,-0.002006370108575,-0.00296085444279,0.005279312841594,0,0,0,0,1.00099730491638 +43785,0.000746560050175,-0.003810046473518,0.005749963223934,0,0,0,0,1.00127065181732 +43787,0.001505705760792,-0.001933621824719,0.001288213417865,0,0,0,0,1.0015059709549 +43789,-0.000188865175005,0.002229270758107,-0.000781779759564,0,0,0,0,1.00138568878174 +43791,-0.00199320865795,0.001571090542711,-0.001103391987272,0,0,0,0,1.0011522769928 +43793,-0.005013860296458,0.000535070546903,-0.00183189031668,0,0,0,0,1.00108063220978 +43795,-0.00639833509922,0.00421077478677,-0.001838858937845,0,0,0,0,1.00119709968567 +43797,-0.003854424925521,0.007216823287308,-0.001245167688467,0,0,0,0,1.00125336647034 +43799,-0.001710108364932,0.004395710304379,3.74663177353796E-05,0,0,0,0,1.00117838382721 +43801,4.9772370402934E-06,4.6344444854185E-05,0.000955549010541,0,0,0,0,1.00115036964417 +43803,0.001637869514525,0.002020656131208,-0.000111204375571,0,0,0,0,1.00105571746826 +43805,0.002500534290448,0.005511355120689,-0.001324580516666,0,0,0,0,1.00069320201874 +43807,0.003351012244821,0.003934876993299,-0.002691260306165,0,0,0,0,0.999866187572479 +43809,0.002679774072021,0.001271133078262,-0.003519030986354,0,0,0,0,0.999059677124023 +43811,0.000548178097233,0.002042961539701,-0.004228729754686,0,0,0,0,0.998892784118652 +43813,-0.001226967899129,0.002404460217804,-0.001478847698309,0,0,0,0,0.999360144138336 +43815,-0.000841792556457,-0.001655683503486,0.002814656123519,0,0,0,0,0.999758958816528 +43819,0.002444955287501,0.002172722946852,-0.000112492518383,0,0,0,0,1.00082719326019 +43821,0.001594928908162,0.00414578570053,-0.002085972111672,0,0,0,0,1.00158429145813 +43823,-0.000938548473641,-0.000178252230398,-0.003293186426163,0,0,0,0,1.00188040733337 +43825,-0.000849313335493,-0.002586676506326,-0.003116725478321,0,0,0,0,1.00216794013977 +43827,0.00096912344452,-0.002250380115584,-0.0002872129553,0,0,0,0,1.00256037712097 +43829,0.002246249932796,-0.00101565127261,0.001716109691188,0,0,0,0,1.00226819515228 +43831,0.003328318940476,0.001165925292298,0.003383904695511,0,0,0,0,1.00149416923523 +43833,0.001976420171559,0.00247589731589,0.004361033439636,0,0,0,0,1.00105440616608 +43835,-0.000889789662324,0.001595392124727,0.002191264880821,0,0,0,0,1.00102436542511 +43837,-0.000680252793245,-0.000622317427769,0.002661842852831,0,0,0,0,1.00115072727203 +43839,0.001625757548027,-0.003596152411774,0.0034645635169,0,0,0,0,1.00126266479492 +43841,0.003615729976445,-0.004573182668537,0.002190320985392,0,0,0,0,1.00105857849121 +43843,0.003092450555414,-0.001843334757723,-0.000605378940236,0,0,0,0,1.00081717967987 +43845,0.002319559687749,-0.000863834575284,-0.001753907301463,0,0,0,0,1.00105488300323 +43847,0.00225786678493,-0.000311119889375,-0.000393488444388,0,0,0,0,1.00133574008942 +43849,0.000327488698531,0.003689278615639,-0.000159805567819,0,0,0,0,1.00154185295105 +43851,-0.001623546821065,0.005774221848696,0.000953667447902,0,0,0,0,1.00190782546997 +43853,-0.000627763161901,0.003626076970249,0.003088635625318,0,0,0,0,1.00193452835083 +43855,0.002220740076154,4.76557906949893E-05,0.00535035924986,0,0,0,0,1.00133037567139 +43857,0.002831868827343,-0.000799905217718,0.005045020952821,0,0,0,0,1.00063002109528 +43859,0.000690824817866,0.000420966302045,0.002557954750955,0,0,0,0,1.00057721138 +43861,-0.00130771251861,6.33184172329493E-05,0.000934498035349,0,0,0,0,1.00098848342896 +43863,-0.000890146242455,0.00012345588766,-0.000219145615119,0,0,0,0,1.00136387348175 +43865,0.000896470737644,0.000924427586142,-0.001601193565875,0,0,0,0,1.00150799751282 +43867,0.000500406662468,0.000875031983014,-0.003588419174775,0,0,0,0,1.00128698348999 +43869,0.000149318613694,0.003295644884929,-0.005509449634701,0,0,0,0,1.00094306468964 +43871,0.00107578758616,0.006517919246107,-0.006455476395786,0,0,0,0,1.00070476531982 +43873,0.003425993025303,0.007191079668701,-0.007071565836668,0,0,0,0,1.00075161457062 +43875,0.004371143877506,0.004283207003027,-0.005525990854949,0,0,0,0,1.00085520744324 +43877,0.00223220908083,-0.000990131520666,-0.001755119184963,0,0,0,0,1.00052690505981 +43879,-0.000242933383561,-0.005061469040811,-9.31245958781801E-05,0,0,0,0,0.999787092208862 +43881,0.001453471020795,-0.003144253278151,0.000106079001853,0,0,0,0,0.998996913433075 +43883,0.004110414534807,0.000678054406308,-0.000320792663842,0,0,0,0,0.998553693294525 +43885,0.004093118943274,0.002524294424802,0.000529359851498,0,0,0,0,0.998531818389893 +43887,0.003426032373682,0.001196675002575,0.001097030006349,0,0,0,0,0.998498439788818 +43889,0.003452635835856,-0.000916986668017,0.00022770135547,0,0,0,0,0.998647332191467 +43891,0.003504801308736,-0.000622600025963,-0.001794090028852,0,0,0,0,0.99926233291626 +43893,0.002787806559354,0.000945433683228,-0.00197891658172,0,0,0,0,1.00018072128296 +43895,0.001548609230667,0.000626831897534,0.000380130513804,0,0,0,0,1.00084340572357 +43897,0.000858588202391,-0.000466304132715,0.001157849561423,0,0,0,0,1.00131857395172 +43899,-0.000740487477742,-0.001537427306175,0.0012240690412,0,0,0,0,1.002112865448 +43901,-0.001444500521757,-0.001009761821479,4.49972867500037E-06,0,0,0,0,1.00303721427917 +43903,-0.000625248881988,0.00089865893824,-0.001424215384759,0,0,0,0,1.00353908538818 +43905,0.000846817623824,0.002064511878416,-0.001476995064877,0,0,0,0,1.00352919101715 +43907,0.002251346828416,0.002489458303899,1.08846352304681E-05,0,0,0,0,1.00322389602661 +43909,0.001165765686892,0.001141361659393,0.000562966975849,0,0,0,0,1.00286650657654 +43911,-0.001467674621381,-0.001451369491406,-0.000471116829431,0,0,0,0,1.00263965129852 +43913,-0.005087187513709,-0.001733762794174,-0.00355964852497,0,0,0,0,1.00257933139801 +43915,-0.006450959015638,-0.000163502598298,-0.00502156605944,0,0,0,0,1.00270819664001 +43917,-0.003619275521487,0.001386793330312,-0.000376754294848,0,0,0,0,1.00273811817169 +43919,0.001303231925704,0.00151102244854,0.004437424708158,0,0,0,0,1.00261652469635 +43921,0.005346567369998,0.000247943302384,0.002218568697572,0,0,0,0,1.00225293636322 +43923,0.004624539520592,-0.002591418335214,-0.00344259175472,0,0,0,0,1.00157999992371 +43925,0.002550430130214,-0.000550552445929,-0.004685597959906,0,0,0,0,1.00122821331024 +43927,0.000725932128262,0.00503127137199,-0.002906215144321,0,0,0,0,1.00113105773926 +43929,-0.000407562736655,0.00377212674357,-0.000379750330467,0,0,0,0,1.00109672546387 +43931,0.000391908542952,-0.001046671764925,0.001580736017786,0,0,0,0,1.00139439105988 +43933,-0.000119869255286,-0.003074265550822,0.000634323921986,0,0,0,0,1.00195968151093 +43935,-8.93507021828555E-05,-0.004155240021646,-0.001221386599354,0,0,0,0,1.00223743915558 +43937,0.000604380154982,-0.005849214270711,-6.33685049251653E-05,0,0,0,0,1.00199937820435 +43939,0.001464536529966,-0.00459328526631,0.000977753312327,0,0,0,0,1.00171995162964 +43941,0.001845747698098,-0.002182374941185,-0.000945984618738,0,0,0,0,1.0012983083725 +43943,0.001698118518107,0.000114777838462,-0.003342030802742,0,0,0,0,1.00054860115051 +43945,0.001829110668041,0.003341163974255,-0.003550349967554,0,0,0,0,0.999803721904754 +43947,0.001594705507159,0.003388608340174,-0.001953603466973,0,0,0,0,0.999021053314209 +43949,0.000631100439932,0.001550856977701,-0.001711891382001,0,0,0,0,0.998354732990265 +43951,-0.000599856371991,0.001078572589904,-0.001717541716062,0,0,0,0,0.998314678668976 +43971,-0.001177690341137,-0.001304044737481,0.00161892361939,0,0,0,0,0.998593032360077 +43973,-0.001761550898664,-0.001286152401008,-0.000163221862749,0,0,0,0,0.998939096927643 +43975,-0.001122872228734,-0.000346939108567,-0.00345778814517,0,0,0,0,0.999557793140411 +43977,-0.001435330603272,0.000462337018689,-0.004264907445759,0,0,0,0,1.00029599666595 +43979,-0.001449498930015,0.001890191575512,-0.00260122329928,0,0,0,0,1.00070405006409 +43981,0.000981399556622,0.002968820743263,-0.002156024798751,0,0,0,0,1.00079047679901 +43983,0.003087296616286,0.002067164052278,-0.000347210443579,0,0,0,0,1.0007791519165 +43985,0.004988324362785,-0.000803737551905,0.000388697517337,0,0,0,0,1.00071477890015 +43987,0.004101714119315,-0.002009328221902,-0.001628642785363,0,0,0,0,1.00054001808167 +43989,0.000991654000245,0.000131463413709,-0.000518497370649,0,0,0,0,1.00039434432983 +43991,-0.001081465277821,0.000754286185838,0.001223253086209,0,0,0,0,1.00041913986206 +43993,-0.001597144524567,0.001111775520258,0.002614283002913,0,0,0,0,1.00039207935333 +43995,-0.000667792919558,0.001518108649179,0.002170849591494,0,0,0,0,1.0002601146698 +43997,-0.000304566463456,0.001204754109494,-0.0008901625406,0,0,0,0,1.00047397613525 +43999,-0.000701690791175,-5.75503554500756E-06,-0.008231342770159,0,0,0,0,1.00104558467865 +44001,0.001506719039753,0.00070990389213,-0.015865182504058,0,0,0,0,1.00206553936005 +44003,0.006304207257926,0.003584336256608,-0.019919080659747,0,0,0,0,1.00302481651306 +44005,0.012591382488608,0.008835641667247,-0.017818016931415,0,0,0,0,1.00322616100311 +44007,0.01763348467648,0.015268743038178,-0.011871729977429,0,0,0,0,1.00217473506928 +44009,0.018306577578187,0.019378090277314,-0.006314917467535,0,0,0,0,0.999819695949554 +44011,0.013223024085164,0.018764903768897,-0.005271617788821,0,0,0,0,0.997146487236023 +44013,0.004721090663224,0.012423717416823,-0.007748007308692,0,0,0,0,0.995741903781891 +44015,-0.001359491958283,0.003242924576625,-0.008632597513497,0,0,0,0,0.996272563934326 +44017,-0.003590462030843,-0.002159679774195,-0.009589411318302,0,0,0,0,0.998317301273346 +44019,-0.001862552948296,-0.002510965801775,-0.013733126223087,0,0,0,0,1.00124335289001 +44021,0.002947584260255,0.001491080853157,-0.021146401762962,0,0,0,0,1.00383567810059 +44023,0.009591574780643,0.008740983903408,-0.023419873788953,0,0,0,0,1.00426304340363 +44025,0.01586358807981,0.01448471006006,-0.014251466840506,0,0,0,0,1.00228095054626 +44027,0.01526287663728,0.013317384757102,-0.00556961260736,0,0,0,0,0.999847948551178 +44029,0.006256122607738,0.006149930413812,-0.011729800142348,0,0,0,0,0.997735023498535 +44031,-0.001283166930079,-0.007219093851745,-0.045359093695879,0,0,0,0,0.993065178394318 +44033,0.000953115115408,-0.030705591663718,-0.123883634805679,0,0,0,0,0.989831984043121 +44035,-0.000360011850717,-0.044102672487497,-0.241757795214653,0,0,0,0,0.994391083717346 +44037,-0.013330621644855,-0.038320500403643,-0.373041331768036,0,0,0,0,1.00193393230438 +44039,-0.023432116955519,-0.016839444637299,-0.492313086986542,0,0,0,0,1.00771403312683 +44041,-0.018550503998995,0.018909515812993,-0.586514472961426,0,0,0,0,1.00747787952423 +44043,0.00647894339636,0.056643135845661,-0.656328737735748,0,0,0,0,1.0014021396637 +44045,0.029809663072229,0.084030255675316,-0.703425645828247,0,0,0,0,1.00239753723145 +44047,0.028060793876648,0.078221037983894,-0.725732803344727,0,0,0,0,1.00733959674835 +44049,0.005427533760667,0.046303175389767,-0.729983329772949,0,0,0,0,1.00628995895386 +44051,-0.008172681555152,0.017420940101147,-0.729931473731995,0,0,0,0,1.00373756885529 +44053,0.004993650596589,0.012804076075554,-0.727024018764496,0,0,0,0,1.01040291786194 +44055,0.027580358088017,0.025777325034142,-0.71761965751648,0,0,0,0,1.02154159545898 +44057,0.039964571595192,0.042398810386658,-0.699521124362946,0,0,0,0,1.02518308162689 +44059,0.042637806385756,0.062784127891064,-0.683087289333344,0,0,0,0,1.01965749263763 +44061,0.045156367123127,0.081815987825394,-0.679178416728973,0,0,0,0,1.01032638549805 +44063,0.039607528597117,0.084262862801552,-0.685391902923584,0,0,0,0,1.00011241436005 +44065,0.021315421909094,0.056714605540037,-0.686523795127869,0,0,0,0,0.98713356256485 +44067,0.001569763058797,0.016344519332051,-0.666394531726837,0,0,0,0,0.974943041801452 +44069,-0.007726072799414,-0.009471365250647,-0.606900095939636,0,0,0,0,0.972087681293488 +44071,-0.004170802887529,-0.013733531348407,-0.496744960546494,0,0,0,0,0.979101896286011 +44073,0.007885933853686,-0.006648185662925,-0.341650038957596,0,0,0,0,0.985997915267944 +44075,0.021865854039788,-0.003035289933905,-0.16532076895237,0,0,0,0,0.986622631549835 +44077,0.025624105706811,-0.004992701578885,-0.001498166820966,0,0,0,0,0.982816100120544 +44079,0.008599154651165,-0.015631582587957,0.129103943705559,0,0,0,0,0.979175269603729 +44081,-0.026201782748103,-0.035594280809164,0.224201276898384,0,0,0,0,0.981345474720001 +44083,-0.058521594852209,-0.047298852354288,0.293426841497421,0,0,0,0,0.992050766944885 +44085,-0.065309002995491,-0.033449891954661,0.340676337480545,0,0,0,0,1.00917887687683 +44087,-0.039800118654966,0.004326036199927,0.366993695497513,0,0,0,0,1.02552568912506 +44089,0.002213530475274,0.052319556474686,0.379446268081665,0,0,0,0,1.03568339347839 +44091,0.032771077007055,0.093440748751164,0.383665382862091,0,0,0,0,1.03478717803955 +44093,0.035707034170628,0.10866117477417,0.380251526832581,0,0,0,0,1.0220639705658 +44095,0.015520678833127,0.094478204846382,0.36704871058464,0,0,0,0,1.00366580486298 +44097,-0.011088974773884,0.058739699423313,0.337497860193253,0,0,0,0,0.987544536590576 +44099,-0.032079372555018,0.016416219994426,0.283892244100571,0,0,0,0,0.980820715427399 +44101,-0.041429296135903,-0.013071122579277,0.20550362765789,0,0,0,0,0.994548738002777 +44103,-0.033281546086073,-0.018917759880424,0.114056922495365,0,0,0,0,0.994548738002777 +44127,-0.149741426110268,0.206121757626533,-0.226288929581642,0,0,0,0,1.07060611248016 +44129,-0.188299179077148,0.217930719256401,-0.255872547626495,0,0,0,0,1.07072949409485 +44131,-0.222503662109375,0.221594840288162,-0.281972497701645,0,0,0,0,1.06847858428955 +44133,-0.222503662109375,0.221594840288162,-0.281972497701645,0,0,0,0,1.06847858428955 +44135,-0.280444502830505,0.225142419338226,-0.330725342035294,0,0,0,0,1.05895555019379 +44137,-0.308079868555069,0.218717232346535,-0.350347638130188,0,0,0,0,1.05441200733185 +44139,-0.336782395839691,0.209471106529236,-0.369811475276947,0,0,0,0,1.0505713224411 +44141,-0.365124106407165,0.204961404204369,-0.392122328281403,0,0,0,0,1.04677903652191 +44143,-0.365124106407165,0.204961404204369,-0.414439499378204,0,0,0,0,1.04285836219788 +44145,-0.424879878759384,0.201721221208572,-0.434573590755463,0,0,0,0,1.04084002971649 +44147,-0.460548281669617,0.198674350976944,-0.457835793495178,0,0,0,0,1.04323625564575 +44149,-0.498227149248123,0.196702405810356,-0.485362499952316,0,0,0,0,1.04877138137817 +44151,-0.533715724945068,0.191293895244598,-0.513037383556366,0,0,0,0,1.05354487895966 +44153,-0.565051376819611,0.185143336653709,-0.544143736362457,0,0,0,0,1.0547696352005 +44155,-0.595087289810181,0.181932717561722,-0.581687927246094,0,0,0,0,1.05176079273224 +44157,-0.624734222888947,0.181781694293022,-0.628357887268066,0,0,0,0,1.04713702201843 +44159,-0.654223203659058,0.180831521749496,-0.678521513938904,0,0,0,0,1.04442095756531 +44161,-0.680103123188019,0.17510499060154,-0.727087199687958,0,0,0,0,1.04251635074615 +44163,-0.699583411216736,0.163719937205315,-0.775982260704041,0,0,0,0,1.03864359855652 +44165,-0.71570885181427,0.141808554530144,-0.824341177940369,0,0,0,0,1.02929139137268 +44167,-0.734136521816254,0.115783050656319,-0.872358500957489,0,0,0,0,1.0162478685379 +44169,-0.760412991046906,0.091559126973152,-0.917943000793457,0,0,0,0,1.00634396076202 +44171,-0.790638566017151,0.063825406134129,-0.956392824649811,0,0,0,0,1.00152504444122 +44173,-0.817150056362152,0.028381424024701,-0.985841870307922,0,0,0,0,1.00150084495544 +44175,-0.836478531360626,-0.008646076545119,-1.01454317569733,0,0,0,0,1.00286436080933 +44177,-0.851633012294769,-0.039397872984409,-1.04506063461304,0,0,0,0,0.999387800693512 +44179,-0.870211899280548,-0.057928636670113,-1.07823503017426,0,0,0,0,0.992979347705841 +44181,-0.896175801753998,-0.057870227843523,-1.1181321144104,0,0,0,0,0.990848481655121 +44183,-0.92001748085022,-0.046856224536896,-1.16571497917175,0,0,0,0,0.995112597942352 +44185,-0.931710958480835,-0.03779860585928,-1.21795248985291,0,0,0,0,1.00432872772217 +44187,-0.934852063655853,-0.036521594971418,-1.27147233486176,0,0,0,0,1.01596295833588 +44189,-0.935214996337891,-0.039467979222536,-1.32227623462677,0,0,0,0,1.02449369430542 +44191,-0.935746371746063,-0.034223284572363,-1.36690819263458,0,0,0,0,1.02819418907166 +44193,-0.934702754020691,-0.016485139727593,-1.40627074241638,0,0,0,0,1.02920269966125 +44195,-0.927954018115997,0.002818291541189,-1.44162106513977,0,0,0,0,1.02621865272522 +44197,-0.916389644145966,0.018612764775753,-1.47739326953888,0,0,0,0,1.01979291439056 +44199,-0.901381611824035,0.033406067639589,-1.51287484169006,0,0,0,0,1.01530241966248 +44201,-0.886911511421204,0.050897188484669,-1.54136061668396,0,0,0,0,1.01606559753418 +44203,-0.871894478797913,0.076051898300648,-1.55931913852692,0,0,0,0,1.02271044254303 +44205,-0.853218138217926,0.103745944797993,-1.56672537326813,0,0,0,0,1.03427612781525 +44207,-0.8321333527565,0.129243820905685,-1.56765043735504,0,0,0,0,1.04369878768921 +44209,-0.810282468795776,0.164419069886208,-1.56588542461395,0,0,0,0,1.04521870613098 +44211,-0.78783506155014,0.213690176606178,-1.56406247615814,0,0,0,0,1.04110741615295 +44213,-0.763895034790039,0.267904996871948,-1.56853330135345,0,0,0,0,1.03420269489288 +44215,-0.733089208602905,0.325387686491013,-1.5771347284317,0,0,0,0,1.02868986129761 +44217,-0.691638350486755,0.384947836399078,-1.58641028404236,0,0,0,0,1.02908682823181 +44219,-0.639273166656494,0.443052083253861,-1.59637594223022,0,0,0,0,1.03156411647797 +44221,-0.58321076631546,0.50441437959671,-1.60116672515869,0,0,0,0,1.03105890750885 +44223,-0.530460178852081,0.577581822872162,-1.60189759731293,0,0,0,0,1.02881300449371 +44225,-0.479824393987656,0.665410876274109,-1.60026180744171,0,0,0,0,1.02626895904541 +44227,-0.428056478500366,0.756366431713104,-1.59429156780243,0,0,0,0,1.020378947258 +44229,-0.368966549634934,0.834565877914429,-1.58586633205414,0,0,0,0,1.00117242336273 +44231,-0.30238801240921,0.887459456920624,-1.57600164413452,0,0,0,0,0.976138532161713 +44233,-0.249561861157417,0.921824932098389,-1.56242263317108,0,0,0,0,0.957384765148163 +44235,-0.21613997220993,0.936111986637116,-1.53083908557892,0,0,0,0,0.951249837875366 +44237,-0.198367118835449,0.94133996963501,-1.47110462188721,0,0,0,0,0.969625234603882 +44239,-0.189166560769081,0.944060742855072,-1.38378489017487,0,0,0,0,0.998264133930206 +44241,-0.189300924539566,0.945994317531586,-1.27939331531525,0,0,0,0,1.01618933677673 +44243,-0.20602248609066,0.959164142608643,-1.17382597923279,0,0,0,0,1.02386939525604 +44245,-0.230445101857185,0.978446841239929,-1.07863283157349,0,0,0,0,1.02386629581451 +44247,-0.258714139461517,1.00243949890137,-0.993462979793549,0,0,0,0,1.02296423912048 +44249,-0.292257934808731,1.02756464481354,-0.911288380622864,0,0,0,0,1.03484523296356 +44251,-0.32285875082016,1.03785634040833,-0.819609522819519,0,0,0,0,1.05386185646057 +44253,-0.350901007652283,1.0336058139801,-0.718830287456512,0,0,0,0,1.06543338298798 +44255,-0.38743731379509,1.02695536613464,-0.621345043182373,0,0,0,0,1.06857013702393 +44257,-0.43335098028183,1.02555763721466,-0.532428801059723,0,0,0,0,1.06645500659943 +44259,-0.483456969261169,1.02194213867188,-0.450561553239822,0,0,0,0,1.05872571468353 +44281,-1.41628575325012,0.2322568744421,0.134154006838799,0,0,0,0,1.02684688568115 +44283,-1.51588690280914,0.146225228905678,0.131080105900764,0,0,0,0,1.0266340970993 +44285,-1.6086243391037,0.06172002106905,0.118016980588436,0,0,0,0,1.02120876312256 +44287,-1.70799160003662,-0.022828493267298,0.105872631072998,0,0,0,0,1.01729893684387 +44289,-1.82138454914093,-0.112356409430504,0.097912892699242,0,0,0,0,1.0155463218689 +44291,-1.93861043453217,-0.203486025333405,0.08619699627161,0,0,0,0,1.02197098731995 +44293,-2.05476856231689,-0.288704216480255,0.071518249809742,0,0,0,0,1.0377608537674 +44295,-2.16700792312622,-0.373773545026779,0.05457279458642,0,0,0,0,1.04870247840881 +44297,-2.27575707435608,-0.458697199821472,0.036056082695723,0,0,0,0,1.0520738363266 +44299,-2.38856267929077,-0.537095963954926,0.015277328900993,0,0,0,0,1.05118930339813 +44301,-2.5066659450531,-0.611127555370331,-0.004580031149089,0,0,0,0,1.046910405159 +44303,-2.62516760826111,-0.683532655239105,-0.021581375971437,0,0,0,0,1.04288613796234 +44305,-2.73365712165833,-0.757387280464172,-0.043065395206213,0,0,0,0,1.03488206863403 +44307,-2.82527542114258,-0.843044757843018,-0.068022400140762,0,0,0,0,1.01663839817047 +44309,-2.91741299629211,-0.935389757156372,-0.09276282787323,0,0,0,0,0.997118353843689 +44311,-3.02754211425781,-1.01796126365662,-0.110820703208447,0,0,0,0,0.992119073867798 +44313,-3.14604377746582,-1.08756220340729,-0.125713765621185,0,0,0,0,1.00637745857239 +44315,-3.25036716461182,-1.1454451084137,-0.144461750984192,0,0,0,0,1.03081488609314 +44317,-3.33343100547791,-1.19546842575073,-0.166310340166092,0,0,0,0,1.04688632488251 +44319,-3.40533638000488,-1.23969173431396,-0.191000729799271,0,0,0,0,1.04193139076233 +44321,-3.48607087135315,-1.27731645107269,-0.214056923985481,0,0,0,0,1.02739977836609 +44323,-3.57750391960144,-1.30941212177277,-0.239470079541206,0,0,0,0,1.01821005344391 +44325,-3.65837812423706,-1.34331274032593,-0.269128412008285,0,0,0,0,1.02012825012207 +44327,-3.71805167198181,-1.37903809547424,-0.298846155405045,0,0,0,0,1.02829134464264 +44329,-3.76430344581604,-1.4117112159729,-0.320437133312225,0,0,0,0,1.02840673923492 +44331,-3.80253601074219,-1.43880534172058,-0.329073250293732,0,0,0,0,1.01542687416077 +44333,-3.83341360092163,-1.47033274173737,-0.327011555433273,0,0,0,0,0.998169898986816 +44335,-3.86690139770508,-1.51066374778748,-0.314372658729553,0,0,0,0,0.98417192697525 +44337,-3.91247463226318,-1.54300665855408,-0.292620450258255,0,0,0,0,0.973539233207702 +44339,-3.96829438209534,-1.55342066287994,-0.268713653087616,0,0,0,0,0.969209313392639 +44341,-4.02843713760376,-1.54162526130676,-0.242034658789635,0,0,0,0,0.969205617904663 +44343,-4.08198928833008,-1.51874816417694,-0.205342948436737,0,0,0,0,0.971022725105285 +44345,-4.12091016769409,-1.48817467689514,-0.15855561196804,0,0,0,0,0.978929936885834 +44347,-4.1428484916687,-1.45016598701477,-0.106073714792728,0,0,0,0,0.989641964435577 +44349,-4.14237308502197,-1.4051319360733,-0.052485723048449,0,0,0,0,1.00169432163239 +44351,-4.12064695358276,-1.34972453117371,0.002986053237692,0,0,0,0,1.01622891426086 +44353,-4.08125782012939,-1.28383147716522,0.058963607996702,0,0,0,0,1.02987253665924 +44355,-4.02371215820313,-1.20755219459534,0.111017182469368,0,0,0,0,1.0425751209259 +44357,-3.95360422134399,-1.12137448787689,0.153976961970329,0,0,0,0,1.05796337127686 +44359,-3.87732648849487,-1.02132868766785,0.188743233680725,0,0,0,0,1.07532894611359 +44361,-3.79138016700745,-0.901655912399292,0.221486121416092,0,0,0,0,1.09401869773865 +44363,-3.6828715801239,-0.77079176902771,0.253098696470261,0,0,0,0,1.11167049407959 +44365,-3.54649305343628,-0.64277595281601,0.281472623348236,0,0,0,0,1.12478566169739 +44367,-3.38871765136719,-0.521902799606323,0.307599574327469,0,0,0,0,1.13480091094971 +44369,-3.21951150894165,-0.408700108528137,0.333892017602921,0,0,0,0,1.14555835723877 +44371,-3.04847192764282,-0.296913325786591,0.361766964197159,0,0,0,0,1.15718185901642 +44373,-2.87700867652893,-0.177307903766632,0.390761882066727,0,0,0,0,1.16948521137238 +44375,-2.6973876953125,-0.050787147134543,0.421341210603714,0,0,0,0,1.18190634250641 +44377,-2.49960207939148,0.072810828685761,0.446230739355087,0,0,0,0,1.19182968139648 +44379,-2.27980852127075,0.185813426971436,0.465774774551392,0,0,0,0,1.19960296154022 +44381,-2.04556632041931,0.291327506303787,0.48644345998764,0,0,0,0,1.2050324678421 +44383,-1.81204950809479,0.400773614645004,0.505533516407013,0,0,0,0,1.20658957958221 +44385,-1.59033179283142,0.515412271022797,0.520066380500793,0,0,0,0,1.20450580120087 +44387,-1.37892484664917,0.625207602977753,0.53022962808609,0,0,0,0,1.19841766357422 +44389,-1.17662370204926,0.726874232292175,0.533142566680908,0,0,0,0,1.18901383876801 +44391,-0.984164595603943,0.822036862373352,0.527516722679138,0,0,0,0,1.17759525775909 +44393,-0.804291486740112,0.911661148071289,0.51110577583313,0,0,0,0,1.16402232646942 +44395,-0.642851114273071,0.99593859910965,0.484789371490479,0,0,0,0,1.14822661876678 +44397,-0.498076766729355,1.06844305992126,0.44895350933075,0,0,0,0,1.13066411018372 +44399,-0.366255283355713,1.12386858463287,0.404279947280884,0,0,0,0,1.1111980676651 +44401,-0.247051924467087,1.16517913341522,0.348656177520752,0,0,0,0,1.09067416191101 +44403,-0.143481686711311,1.19912266731262,0.289259076118469,0,0,0,0,1.06952941417694 +44405,-0.059411328285933,1.22511923313141,0.230006292462349,0,0,0,0,1.04880738258362 +44407,0.00393154239282,1.24176204204559,0.170969977974892,0,0,0,0,1.02989459037781 +44409,0.045979350805283,1.24945640563965,0.111816219985485,0,0,0,0,1.01349079608917 +44411,0.065709017217159,1.2487006187439,0.057303871959448,0,0,0,0,1.00085246562958 +44413,0.06350214779377,1.2478791475296,0.010571303777397,0,0,0,0,0.992664813995361 +44431,-0.319858461618423,0.959487915039062,0.161144584417343,0,0,0,0,1.05111753940582 +44433,-0.336486577987671,0.904455244541168,0.231309771537781,0,0,0,0,1.06144773960114 +44435,-0.346687853336334,0.857182264328003,0.297757863998413,0,0,0,0,1.07251632213593 +44437,-0.348983585834503,0.819497525691986,0.358874648809433,0,0,0,0,1.08444762229919 +44439,-0.344197899103165,0.790883719921112,0.419312655925751,0,0,0,0,1.096510887146 +44441,-0.331866800785065,0.767019629478455,0.477449119091034,0,0,0,0,1.10831093788147 +44443,-0.312707781791687,0.743241429328918,0.532492876052856,0,0,0,0,1.11918878555298 +44445,-0.287871599197388,0.720338463783264,0.582122564315796,0,0,0,0,1.12869238853455 +44447,-0.255700796842575,0.69877690076828,0.623754382133484,0,0,0,0,1.13601589202881 +44449,-0.217802613973618,0.676430940628052,0.660116910934448,0,0,0,0,1.14088404178619 +44451,-0.178026154637337,0.653929591178894,0.688608765602112,0,0,0,0,1.14373993873596 +44453,-0.141028344631195,0.633647203445435,0.70679122209549,0,0,0,0,1.14443564414978 +44455,-0.106487892568111,0.617026925086975,0.717572391033173,0,0,0,0,1.14294028282166 +44457,-0.075774095952511,0.601123571395874,0.719026565551758,0,0,0,0,1.13984835147858 +44459,-0.050972759723663,0.57874071598053,0.713426947593689,0,0,0,0,1.13504087924957 +44461,-0.032344654202461,0.552060782909393,0.696970105171204,0,0,0,0,1.12809479236603 +44463,-0.019115444272757,0.524922251701355,0.669238150119782,0,0,0,0,1.11945700645447 +44465,-0.012440948747099,0.491602718830109,0.637193441390991,0,0,0,0,1.10927605628967 +44467,-0.016194993630052,0.457892149686813,0.601992666721344,0,0,0,0,1.09808123111725 +44469,-0.03073169849813,0.428520917892456,0.561870872974396,0,0,0,0,1.08739459514618 +44471,-0.05790450796485,0.399683684110641,0.521840512752533,0,0,0,0,1.0786120891571 +44473,-0.100768640637398,0.371321797370911,0.486698895692825,0,0,0,0,1.07285916805267 +44475,-0.157049730420113,0.349886476993561,0.459786504507065,0,0,0,0,1.07052910327911 +44477,-0.224394470453262,0.333347976207733,0.440617740154266,0,0,0,0,1.07149243354797 +44479,-0.300869077444077,0.316728949546814,0.427006125450134,0,0,0,0,1.07608759403229 +44481,-0.379938840866089,0.298460394144058,0.423818647861481,0,0,0,0,1.08460879325867 +44483,-0.454470664262772,0.276456117630005,0.43425977230072,0,0,0,0,1.09604895114899 +44485,-0.519804239273071,0.246407955884933,0.458399295806885,0,0,0,0,1.10887169837952 +44487,-0.571901738643646,0.205681771039963,0.496263056993485,0,0,0,0,1.12290441989899 +44489,-0.608603894710541,0.156730085611343,0.539868474006653,0,0,0,0,1.13775265216827 +44491,-0.631515204906464,0.104998029768467,0.585616052150726,0,0,0,0,1.15286672115326 +44493,-0.642781138420105,0.054481972008944,0.633683621883392,0,0,0,0,1.16795945167542 +44495,-0.641118347644806,0.005846965592355,0.676576793193817,0,0,0,0,1.1827164888382 +44497,-0.632918119430542,-0.036902468651533,0.711024582386017,0,0,0,0,1.19655454158783 +44499,-0.623962581157684,-0.071454904973507,0.740458846092224,0,0,0,0,1.2084789276123 +44501,-0.60945051908493,-0.105046167969704,0.764395594596863,0,0,0,0,1.21783018112183 +44503,-0.583609223365784,-0.140502721071243,0.779468178749085,0,0,0,0,1.22467851638794 +44505,-0.550057113170624,-0.175543323159218,0.79026061296463,0,0,0,0,1.22869515419006 +44507,-0.515254616737366,-0.20843231678009,0.800165474414825,0,0,0,0,1.23019933700562 +44509,-0.479078501462936,-0.241660296916962,0.809218049049377,0,0,0,0,1.22987163066864 +44511,-0.444376647472382,-0.277017861604691,0.814743936061859,0,0,0,0,1.22761738300323 +44513,-0.413534104824066,-0.312866598367691,0.820815145969391,0,0,0,0,1.2232837677002 +44515,-0.38856229186058,-0.346097320318222,0.828246116638184,0,0,0,0,1.21747207641602 +44517,-0.369875431060791,-0.380320370197296,0.840337216854095,0,0,0,0,1.21031713485718 +44519,-0.35433641076088,-0.416750758886337,0.857834875583649,0,0,0,0,1.20211231708527 +44521,-0.343098342418671,-0.455717086791992,0.875438094139099,0,0,0,0,1.19364154338837 +44523,-0.335968315601349,-0.497681796550751,0.88683021068573,0,0,0,0,1.18507277965546 +44525,-0.333693712949753,-0.541245579719543,0.892491102218628,0,0,0,0,1.17688226699829 +44527,-0.33889839053154,-0.584850549697876,0.897654294967651,0,0,0,0,1.169393658638 +44529,-0.352353692054749,-0.629005491733551,0.901639640331268,0,0,0,0,1.16217291355133 +44531,-0.371230214834213,-0.672767877578735,0.904020130634308,0,0,0,0,1.15546023845673 +44533,-0.392255663871765,-0.716245532035828,0.904908239841461,0,0,0,0,1.14940249919891 +44535,-0.418386220932007,-0.757545471191406,0.90379136800766,0,0,0,0,1.1438080072403 +44537,-0.447077184915543,-0.793596625328064,0.898801147937775,0,0,0,0,1.13840508460999 +44539,-0.473028898239136,-0.82303112745285,0.890445947647095,0,0,0,0,1.13303339481354 +44541,-0.49649578332901,-0.847707092761993,0.879571437835693,0,0,0,0,1.12710726261139 +44543,-0.516057074069977,-0.868480265140533,0.866132616996765,0,0,0,0,1.12031841278076 +44545,-0.526288092136383,-0.88409286737442,0.850651025772095,0,0,0,0,1.1128716468811 +44547,-0.52694970369339,-0.894896805286408,0.834627270698547,0,0,0,0,1.10535621643066 +44549,-0.521952986717224,-0.900980949401856,0.820629358291626,0,0,0,0,1.09799492359161 +44551,-0.512163698673248,-0.903311431407928,0.812862634658814,0,0,0,0,1.09132027626038 +44553,-0.496199637651444,-0.89984118938446,0.812395393848419,0,0,0,0,1.08626687526703 +44555,-0.478621900081634,-0.889954388141632,0.817943572998047,0,0,0,0,1.08353078365326 +44557,-0.458366602659226,-0.874493956565857,0.830099642276764,0,0,0,0,1.08323657512665 +44559,-0.433986604213715,-0.857426404953003,0.847495973110199,0,0,0,0,1.08525884151459 +44561,-0.407288610935211,-0.844468653202057,0.867299199104309,0,0,0,0,1.08926367759705 +44563,-0.378790587186813,-0.831299185752869,0.887891292572022,0,0,0,0,1.09474849700928 +44565,-0.347441732883453,-0.815910935401917,0.908537089824676,0,0,0,0,1.10113215446472 +44567,-0.314358055591583,-0.800095319747925,0.928090155124664,0,0,0,0,1.10792231559753 +44569,-0.282450705766678,-0.788087129592896,0.940958142280579,0,0,0,0,1.11455416679382 +44571,-0.252360105514526,-0.787585258483887,0.947256505489349,0,0,0,0,1.11951720714569 +44573,-0.221238538622856,-0.795403063297272,0.950964868068695,0,0,0,0,1.12232649326324 +44575,-0.190688520669937,-0.806763529777527,0.949876129627228,0,0,0,0,1.12297713756561 +44577,-0.166830092668533,-0.823397874832153,0.943324983119965,0,0,0,0,1.12101018428803 +44579,-0.150046825408936,-0.851153254508972,0.931618750095367,0,0,0,0,1.11638784408569 +44581,-0.1382667273283,-0.887629389762878,0.91512531042099,0,0,0,0,1.1096076965332 +44583,-0.1368478089571,-0.925228297710419,0.893273293972015,0,0,0,0,1.10097694396973 +44585,-0.145469546318054,-0.967724204063416,0.868118464946747,0,0,0,0,1.09135317802429 +44587,-0.161385998129845,-1.01465594768524,0.846780955791473,0,0,0,0,1.0819925069809 +44589,-0.181782424449921,-1.05890142917633,0.831444919109345,0,0,0,0,1.07310593128204 +44591,-0.206759318709373,-1.10139787197113,0.819164097309112,0,0,0,0,1.06485748291016 +44593,-0.236428156495094,-1.14647722244263,0.80843460559845,0,0,0,0,1.05773973464966 +44595,-0.26894024014473,-1.19186413288116,0.801142156124115,0,0,0,0,1.05201828479767 +44597,-0.302664935588837,-1.23437523841858,0.796555578708649,0,0,0,0,1.04776799678803 +44599,-0.336738437414169,-1.27656579017639,0.788813710212708,0,0,0,0,1.04501724243164 +44601,-0.369511008262634,-1.3169196844101,0.783816277980804,0,0,0,0,1.04386258125305 +44603,-0.401727437973022,-1.35611581802368,0.783210873603821,0,0,0,0,1.04395699501038 +44605,-0.431533336639404,-1.39927411079407,0.78321635723114,0,0,0,0,1.04507374763489 +44607,-0.455538332462311,-1.44346523284912,0.787050604820251,0,0,0,0,1.04730665683746 +44609,-0.476641744375229,-1.48299098014832,0.798065721988678,0,0,0,0,1.05044412612915 +44611,-0.493951290845871,-1.5171149969101,0.812129259109497,0,0,0,0,1.05397868156433 +44613,-0.505382537841797,-1.54243445396423,0.829597234725952,0,0,0,0,1.05770456790924 +44615,-0.512173473834991,-1.55754721164703,0.850358009338379,0,0,0,0,1.06163847446442 +44617,-0.513128399848938,-1.56219470500946,0.868941366672516,0,0,0,0,1.06591689586639 +44619,-0.508181571960449,-1.5550320148468,0.882215976715088,0,0,0,0,1.07081663608551 +44621,-0.496273994445801,-1.54017400741577,0.889689803123474,0,0,0,0,1.07617914676666 +44623,-0.474458485841751,-1.51840209960938,0.888436198234558,0,0,0,0,1.08095896244049 +44625,-0.440305352210999,-1.48581290245056,0.873827278614044,0,0,0,0,1.08472776412964 +44627,-0.399618536233902,-1.44637703895569,0.846549689769745,0,0,0,0,1.08781683444977 +44629,-0.358087509870529,-1.40155446529388,0.805203974246979,0,0,0,0,1.08990335464478 +44631,-0.313733994960785,-1.35330069065094,0.747146189212799,0,0,0,0,1.0906286239624 +44633,-0.26642432808876,-1.30568516254425,0.678800225257874,0,0,0,0,1.08999967575073 +44635,-0.218223348259926,-1.25939869880676,0.607674062252045,0,0,0,0,1.08772802352905 +44637,-0.174806520342827,-1.21178650856018,0.535686910152435,0,0,0,0,1.08340585231781 +44639,-0.13683457672596,-1.16085243225098,0.466935485601425,0,0,0,0,1.07778000831604 +44641,-0.104426831007004,-1.1134318113327,0.403589069843292,0,0,0,0,1.0712856054306 +44643,-0.076659135520458,-1.07234346866608,0.348438292741776,0,0,0,0,1.06440043449402 +44645,-0.051716897636652,-1.03542530536652,0.305314391851425,0,0,0,0,1.0571037530899 +44663,0.119415268301964,-1.26779961585999,0.506623864173889,0,0,0,0,1.01808428764343 +44665,0.09462434053421,-1.32599627971649,0.615709900856018,0,0,0,0,1.01680123806 +44667,0.062684468924999,-1.3899302482605,0.73004674911499,0,0,0,0,1.01450848579407 +44669,0.0252147577703,-1.4551796913147,0.842399895191193,0,0,0,0,1.01134967803955 +44671,-0.015122405253351,-1.51931715011597,0.949502289295196,0,0,0,0,1.00744926929474 +44673,-0.05642955377698,-1.58196473121643,1.04647612571716,0,0,0,0,1.00341618061066 +44675,-0.098148137331009,-1.64333510398865,1.13319194316864,0,0,0,0,0.999981224536896 +44677,-0.14364267885685,-1.70376479625702,1.21289813518524,0,0,0,0,0.996917068958282 +44679,-0.193729847669601,-1.75933837890625,1.28733229637146,0,0,0,0,0.993579149246216 +44681,-0.245413318276405,-1.81189346313477,1.35237848758698,0,0,0,0,0.990036308765411 +44683,-0.293427258729935,-1.86469030380249,1.40330243110657,0,0,0,0,0.986346900463104 +44685,-0.339182585477829,-1.91635239124298,1.43903362751007,0,0,0,0,0.982538521289825 +44687,-0.385788917541504,-1.96289110183716,1.46964573860168,0,0,0,0,0.9792160987854 +44689,-0.433593809604645,-2.00048899650574,1.49507367610931,0,0,0,0,0.976625382900238 +44691,-0.483380287885666,-2.02562069892883,1.51064884662628,0,0,0,0,0.974494934082031 +44693,-0.53062903881073,-2.03837490081787,1.51836860179901,0,0,0,0,0.972185969352722 +44695,-0.571936368942261,-2.04379653930664,1.51957201957703,0,0,0,0,0.96958315372467 +44697,-0.60734748840332,-2.04539394378662,1.51435661315918,0,0,0,0,0.966919779777527 +44699,-0.636492908000946,-2.04060792922974,1.50174760818481,0,0,0,0,0.964151680469513 +44701,-0.658932983875275,-2.02924633026123,1.48384463787079,0,0,0,0,0.961153745651245 +44703,-0.672553479671478,-2.01233220100403,1.46325695514679,0,0,0,0,0.958009898662567 +44705,-0.678869903087616,-1.99226450920105,1.4414473772049,0,0,0,0,0.95502632856369 +44707,-0.680478990077972,-1.97141885757446,1.419060587883,0,0,0,0,0.951474666595459 +44709,-0.679385125637054,-1.94788658618927,1.39881789684296,0,0,0,0,0.947102427482605 +44711,-0.675226509571075,-1.92456686496735,1.38194477558136,0,0,0,0,0.942407965660095 +44713,-0.666028618812561,-1.90095293521881,1.37130486965179,0,0,0,0,0.93851637840271 +44715,-0.649010896682739,-1.87402594089508,1.37013268470764,0,0,0,0,0.93555873632431 +44717,-0.627831518650055,-1.84699988365173,1.37447714805603,0,0,0,0,0.933522582054138 +44719,-0.605761468410492,-1.82038259506226,1.38359308242798,0,0,0,0,0.932433485984802 +44721,-0.578756809234619,-1.79575264453888,1.40025556087494,0,0,0,0,0.930863797664642 +44723,-0.547500669956207,-1.77180421352386,1.42471694946289,0,0,0,0,0.928904831409454 +44725,-0.512958526611328,-1.74930691719055,1.45803642272949,0,0,0,0,0.926027774810791 +44727,-0.472720414400101,-1.72843885421753,1.4925000667572,0,0,0,0,0.921688854694366 +44729,-0.423724800348282,-1.70437133312225,1.52480959892273,0,0,0,0,0.916743695735931 +44731,-0.368135750293732,-1.67341554164886,1.55359637737274,0,0,0,0,0.911353051662445 +44733,-0.315914005041122,-1.63034296035767,1.5755273103714,0,0,0,0,0.904741764068604 +44735,-0.268888801336288,-1.57575142383575,1.59038758277893,0,0,0,0,0.896454036235809 +44737,-0.224557444453239,-1.51582264900208,1.60287714004517,0,0,0,0,0.8865727186203 +44739,-0.181348383426666,-1.45317935943604,1.61186146736145,0,0,0,0,0.875694930553436 +44741,-0.136314019560814,-1.38591849803925,1.61518096923828,0,0,0,0,0.864444196224213 +44743,-0.090259745717049,-1.31887912750244,1.61515128612518,0,0,0,0,0.853394091129303 +44745,-0.04609515145421,-1.25448858737946,1.6115255355835,0,0,0,0,0.842881143093109 +44747,-0.002838640939444,-1.18601095676422,1.60838449001312,0,0,0,0,0.833063900470733 +44749,0.041674166917801,-1.11228847503662,1.6045389175415,0,0,0,0,0.824743986129761 +44751,0.089078113436699,-1.03691172599792,1.59881091117859,0,0,0,0,0.818538665771484 +44753,0.136799454689026,-0.957402348518372,1.5979939699173,0,0,0,0,0.814980387687683 +44755,0.182175561785698,-0.87149715423584,1.60483431816101,0,0,0,0,0.814504325389862 +44757,0.231552615761757,-0.780224502086639,1.61681187152863,0,0,0,0,0.817068338394165 +44759,0.287576377391815,-0.684739410877228,1.63655149936676,0,0,0,0,0.823394656181335 +44761,0.347795456647873,-0.585131287574768,1.66842567920685,0,0,0,0,0.832601487636566 +44763,0.416484445333481,-0.483164936304092,1.70591104030609,0,0,0,0,0.843965709209442 +44765,0.4984290599823,-0.379527062177658,1.74010932445526,0,0,0,0,0.856869101524353 +44767,0.595897734165192,-0.276960164308548,1.76704347133636,0,0,0,0,0.870087325572968 +44769,0.706968903541565,-0.181296825408936,1.79032003879547,0,0,0,0,0.883216023445129 +44771,0.823180437088013,-0.090129368007183,1.80924332141876,0,0,0,0,0.895576357841492 +44773,0.940788567066193,-0.00355489901267,1.81805455684662,0,0,0,0,0.905878067016602 +44775,1.06193387508392,0.07778163254261,1.81806457042694,0,0,0,0,0.914421200752258 +44777,1.18583953380585,0.150927275419235,1.81291651725769,0,0,0,0,0.921627819538116 +44779,1.30908870697021,0.214212283492088,1.80558395385742,0,0,0,0,0.927274882793426 +44781,1.42460465431213,0.268018752336502,1.80029594898224,0,0,0,0,0.931907832622528 +44783,1.52795374393463,0.314300388097763,1.79858541488647,0,0,0,0,0.935669720172882 +44785,1.61845648288727,0.354390174150467,1.79645502567291,0,0,0,0,0.938497304916382 +44787,1.69833397865295,0.389629274606705,1.79748284816742,0,0,0,0,0.940414667129517 +44789,1.76999080181122,0.42058727145195,1.79904365539551,0,0,0,0,0.9410679936409 +44791,1.83021402359009,0.442371338605881,1.79812502861023,0,0,0,0,0.940898597240448 +44793,1.87084424495697,0.452618390321732,1.79909086227417,0,0,0,0,0.940043091773987 +44795,1.89394342899323,0.451703757047653,1.80110228061676,0,0,0,0,0.938585877418518 +44797,1.90691149234772,0.43699324131012,1.80312383174896,0,0,0,0,0.937063217163086 +44799,1.91014397144318,0.406975507736206,1.7976930141449,0,0,0,0,0.935598969459534 +44801,1.90214049816132,0.361890435218811,1.78475618362427,0,0,0,0,0.934841573238373 +44803,1.88555347919464,0.309780865907669,1.77408802509308,0,0,0,0,0.935224413871765 +44805,1.86084365844727,0.259513407945633,1.76906657218933,0,0,0,0,0.936220586299896 +44807,1.82591116428375,0.202025845646858,1.76667666435242,0,0,0,0,0.938161790370941 +44809,1.78222215175629,0.129718914628029,1.7686607837677,0,0,0,0,0.941142022609711 +44811,1.73613584041595,0.047049216926098,1.7786500453949,0,0,0,0,0.944170832633972 +44813,1.68701243400574,-0.039104949682951,1.79830896854401,0,0,0,0,0.945835769176483 +44815,1.6332004070282,-0.130228832364082,1.82246148586273,0,0,0,0,0.945258319377899 +44817,1.57470273971558,-0.225837901234627,1.8467093706131,0,0,0,0,0.941868007183075 +44819,1.51186203956604,-0.321167171001434,1.87734687328339,0,0,0,0,0.935586154460907 +44821,1.44838774204254,-0.407956868410111,1.91460704803467,0,0,0,0,0.926398456096649 +44823,1.38264763355255,-0.48066908121109,1.9501725435257,0,0,0,0,0.91427731513977 +44825,1.31267106533051,-0.536718964576721,1.98002707958221,0,0,0,0,0.899187326431274 +44827,1.24541997909546,-0.572917222976685,2.00285124778748,0,0,0,0,0.88124942779541 +44829,1.18856930732727,-0.587530553340912,2.01626348495483,0,0,0,0,0.860723674297333 +44831,1.14428007602692,-0.58845728635788,2.02053570747375,0,0,0,0,0.838617920875549 +44833,1.11211812496185,-0.573324024677277,2.02140545845032,0,0,0,0,0.816483438014984 +44835,1.09164571762085,-0.536234021186829,2.02192044258118,0,0,0,0,0.795983254909515 +44837,1.07914340496063,-0.478856801986694,2.02170729637146,0,0,0,0,0.778698205947876 +44839,1.07245230674744,-0.398251295089722,2.02530026435852,0,0,0,0,0.76631760597229 +44841,1.07129597663879,-0.293710082769394,2.03154444694519,0,0,0,0,0.759785294532776 +44843,1.07678258419037,-0.172252997756004,2.03725695610046,0,0,0,0,0.759095072746277 +44845,1.09478378295898,-0.040250588208437,2.04759478569031,0,0,0,0,0.764457523822784 +44847,1.13234865665436,0.095806337893009,2.06094861030579,0,0,0,0,0.775601327419281 +44849,1.18987464904785,0.234324172139168,2.07252264022827,0,0,0,0,0.792193293571472 +44851,1.2683299779892,0.373904943466186,2.08481812477112,0,0,0,0,0.813790202140808 +44853,1.36919903755188,0.511512219905853,2.09877181053162,0,0,0,0,0.839706540107727 +44855,1.49199676513672,0.650626242160797,2.11168956756592,0,0,0,0,0.868556201457977 +44857,1.63259196281433,0.791136562824249,2.11766338348389,0,0,0,0,0.898451864719391 +44859,1.78698825836182,0.930731177330017,2.11190676689148,0,0,0,0,0.928397297859192 +44861,1.95635104179382,1.06796526908875,2.09236621856689,0,0,0,0,0.957950174808502 +44863,2.14446115493774,1.20113980770111,2.06211709976196,0,0,0,0,0.985913693904877 +44865,2.34892511367798,1.32873916625977,2.02690625190735,0,0,0,0,1.010049700737 +44867,2.56472420692444,1.44505035877228,1.98548924922943,0,0,0,0,1.02921676635742 +44869,2.78470611572266,1.54857337474823,1.93556070327759,0,0,0,0,1.04295825958252 +44871,2.99442672729492,1.64076638221741,1.8851774930954,0,0,0,0,1.05069303512573 +44873,3.18118405342102,1.72113454341888,1.84392666816711,0,0,0,0,1.05254256725311 +44875,3.34228658676147,1.78759682178497,1.81434333324432,0,0,0,0,1.04843521118164 +44893,3.59368181228638,1.80011475086212,1.99074363708496,0,0,0,0,0.895305752754211 +44895,3.51816129684448,1.75230038166046,2.00754261016846,0,0,0,0,0.880937039852142 +44897,3.43221831321716,1.69573271274567,2.01652002334595,0,0,0,0,0.86894702911377 +44899,3.34390044212341,1.62902784347534,2.02505254745483,0,0,0,0,0.860785007476806 +44901,3.25269389152527,1.55875825881958,2.04156160354614,0,0,0,0,0.857319533824921 +44903,3.15351343154907,1.49476945400238,2.06587338447571,0,0,0,0,0.857506453990936 +44905,3.05398273468018,1.43966150283813,2.09841275215149,0,0,0,0,0.85938960313797 +44907,2.96385502815247,1.3925621509552,2.14312934875488,0,0,0,0,0.860209107398987 +44909,2.89152026176453,1.34875965118408,2.19814133644104,0,0,0,0,0.851539731025696 +44911,2.841148853302,1.29475939273834,2.25723457336426,0,0,0,0,0.827434837818146 +44913,2.78848075866699,1.23142898082733,2.3192503452301,0,0,0,0,0.80424165725708 +44915,2.66588473320007,1.20963275432587,2.3865327835083,0,0,0,0,0.799876093864441 +44917,2.40760040283203,1.28654718399048,2.46172380447388,0,0,0,0,0.798925936222076 +44919,2.04178237915039,1.43344104290009,2.54085826873779,0,0,0,0,0.776633560657501 +44921,1.68524956703186,1.52082622051239,2.59084010124207,0,0,0,0,0.738678276538849 +44923,1.44441986083984,1.43869781494141,2.56350231170654,0,0,0,0,0.703748226165772 +44925,1.33351480960846,1.21475267410278,2.4496021270752,0,0,0,0,0.698538959026337 +44927,1.28452301025391,0.978987634181976,2.29149460792541,0,0,0,0,0.732827961444855 +44929,1.22407448291779,0.822488784790039,2.15335536003113,0,0,0,0,0.790187060832977 +44931,1.12933611869812,0.73987752199173,2.08692097663879,0,0,0,0,0.861941576004028 +44933,1.02766978740692,0.67479407787323,2.10660719871521,0,0,0,0,0.947119414806366 +44935,0.94942569732666,0.578325629234314,2.19112157821655,0,0,0,0,1.03533709049225 +44937,0.906521499156952,0.430644124746323,2.31272268295288,0,0,0,0,1.11642527580261 +44939,0.903750836849213,0.2306047976017,2.45034623146057,0,0,0,0,1.18567931652069 +44941,0.937436044216156,-0.007981815375388,2.58195567131042,0,0,0,0,1.23825013637543 +44943,0.987589120864868,-0.249124199151993,2.68274784088135,0,0,0,0,1.26981043815613 +44945,1.0307137966156,-0.468779593706131,2.73950672149658,0,0,0,0,1.27638578414917 +44947,1.05095756053925,-0.663789749145508,2.75138020515442,0,0,0,0,1.25819575786591 +44949,1.04230535030365,-0.832818031311035,2.72538232803345,0,0,0,0,1.21951651573181 +44951,0.993877530097961,-0.976697385311127,2.67404246330261,0,0,0,0,1.16405975818634 +44953,0.897155463695526,-1.09947109222412,2.61310958862305,0,0,0,0,1.09779298305511 +44955,0.754827082157135,-1.21227836608887,2.56154108047485,0,0,0,0,1.02855134010315 +44957,0.573529124259949,-1.3200181722641,2.5298125743866,0,0,0,0,0.963729798793793 +44959,0.358802855014801,-1.42003929615021,2.51934957504272,0,0,0,0,0.907912135124206 +44961,0.122760489583015,-1.51569533348084,2.52916646003723,0,0,0,0,0.863903760910034 +44963,-0.115139506757259,-1.61211204528809,2.55117964744568,0,0,0,0,0.834470093250275 +44965,-0.341582894325256,-1.70580339431763,2.57559323310852,0,0,0,0,0.820290267467499 +44967,-0.544941902160645,-1.79569375514984,2.59520697593689,0,0,0,0,0.819706857204437 +44969,-0.718229949474335,-1.88657784461975,2.60464930534363,0,0,0,0,0.830065369606018 +44971,-0.861699104309082,-1.97250199317932,2.60137486457825,0,0,0,0,0.849270343780518 +44973,-0.976617634296417,-2.04776740074158,2.58983325958252,0,0,0,0,0.875684082508087 +44975,-1.06499826908112,-2.11296033859253,2.574223279953,0,0,0,0,0.906672954559326 +44977,-1.12814915180206,-2.17392206192017,2.56100749969482,0,0,0,0,0.939060568809509 diff --git a/tools/param_est/import_logdata.m b/tools/param_est/import_logdata.m new file mode 100644 index 0000000000..f33f875902 --- /dev/null +++ b/tools/param_est/import_logdata.m @@ -0,0 +1,42 @@ +function [tick, gyro_roll, gyro_pitch, gyro_yaw, ... + cmd_thrust, cmd_roll, cmd_pitch, cmd_yaw,... + accelz] = import_logdata(filename) + +%% Import data from text file +% Script for importing data from the following text file: +% +% filename: /home/evgheniivolodscoi/LRZ Sync+Share/TUM/Master_AS_RCI/Semester_3/Semesterarbeit/code/param_est/csv_data/data_1901.csv +% +% Auto-generated by MATLAB on 20-Jan-2020 01:14:14 + +%% Setup the Import Options +opts = delimitedTextImportOptions("NumVariables", 9); + +% Specify range and delimiter +opts.DataLines = [2, Inf]; +opts.Delimiter = ","; + +% Specify column names and types +opts.VariableNames = ["tick", "controllerr_roll", "controllerr_pitch", "controllerr_yaw", "controllercmd_thrust", "controllercmd_roll", "controllercmd_pitch", "controllercmd_yaw", "controlleraccelz"]; +opts.VariableTypes = ["double", "double", "double", "double", "double", "double", "double", "double", "double"]; +opts.ExtraColumnsRule = "ignore"; +opts.EmptyLineRule = "read"; + +% Import the data +tbl = readtable(filename, opts); + +%% Convert to output type +tick = tbl.tick; +gyro_roll = tbl.controllerr_roll; +gyro_pitch = tbl.controllerr_pitch; +gyro_yaw = tbl.controllerr_yaw; +cmd_thrust = tbl.controllercmd_thrust; +cmd_roll = tbl.controllercmd_roll; +cmd_pitch = tbl.controllercmd_pitch; +cmd_yaw = tbl.controllercmd_yaw; +accelz = tbl.controlleraccelz; + +%% Clear temporary variables +clear opts tbl + +end \ No newline at end of file diff --git a/tools/param_est/param_estimation.m b/tools/param_est/param_estimation.m new file mode 100644 index 0000000000..4d451af843 --- /dev/null +++ b/tools/param_est/param_estimation.m @@ -0,0 +1,81 @@ +clc +clear +close all + +%% Parameters +Ts = 1/500; +Fs = 1/Ts; + +T = 0.0617; % Time constant T [s] +alpha = 1 - exp(-Ts/T); + +filename = "data_1901.csv"; + +%% Import data + +[tick, gyro_roll, gyro_pitch, gyro_yaw, cmd_thrust, cmd_roll,... + cmd_pitch, cmd_yaw, accelz] = import_logdata(filename); + +time = (tick - tick(1)) / 1000; + +%% Actuator dynamics +cmd_roll_a = filter([alpha], [1, -(1-alpha)], cmd_roll); +cmd_pitch_a = filter([alpha], [1, -(1-alpha)], cmd_pitch); +cmd_yaw_a = filter([alpha], [1, -(1-alpha)], cmd_yaw); +cmd_thrust_a = filter([alpha], [1, -(1-alpha)], cmd_thrust); + + +%% Data preprocessing + +[b, a] = butter(4, 4/(Fs/2)); % compute filter coeffs + +% Filtering gyro data to remove noise +gyro_roll_f = filter(b, a, gyro_roll); +gyro_pitch_f = filter(b, a, gyro_pitch); +gyro_yaw_f = filter(b, a, gyro_yaw); + +% Filtering cmd data to remove noise +cmd_roll_f = filter(b, a, cmd_roll_a); +cmd_pitch_f = filter(b, a, cmd_pitch_a); +cmd_yaw_f = filter(b, a, cmd_yaw_a); + +% Differtiating angular velocities to get angular accelerations +ang_accel_roll = [0; diff(gyro_roll_f)]/Ts; +ang_accel_pitch = [0; diff(gyro_pitch_f)]/Ts; +ang_accel_yaw = [0; diff(gyro_yaw_f)]/Ts; + +% Differentiating 2nd time (for parameter estimation) +ang_accel_roll_d = [0; diff(ang_accel_roll)]/Ts; +ang_accel_pitch_d = [0; diff(ang_accel_pitch)]/Ts; +ang_accel_yaw_d = [0; diff(ang_accel_yaw)]/Ts; + +% Differentiating cmd (for parameter estimation) +cmd_roll_fd = [0; diff(cmd_roll_f)]/Ts; +cmd_pitch_fd = [0; diff(cmd_pitch_f)]/Ts; +cmd_yaw_fd = [0; diff(cmd_yaw_f)]/Ts; +cmd_yaw_fdd = [0; diff(cmd_yaw_fd)]/Ts; + + +%% Compute control effectiveness parameters (least squares fitting) +G_roll = cmd_roll_fd \ ang_accel_roll_d; +G_pitch = cmd_pitch_fd \ ang_accel_pitch_d; +G_yaw = [cmd_yaw_fd cmd_yaw_fdd] \ ang_accel_yaw_d; + + +%% Plot results +display(['T = ' num2str(T) 's; Fs = ' num2str(Fs) 'Hz; alpha = ' num2str(alpha)]) +display(['G1_roll = ' num2str(G_roll) '; G1_pitch = ' num2str(G_pitch) ... + '; G1_yaw = ' num2str(G_yaw(1)) '; G2_yaw = ' num2str(G_yaw(2))]) + +% % Plot contributions of G matrices +% figure('Name','G1_yaw contribution'); +% plot(ang_accel_yaw_d); hold on +% plot([cmd_yaw_fd 0*cmd_yaw_fdd]*G_yaw) +% xlim([0 inf]); grid on; +% legend('ang\_accel\_yaw\_d', 'cmd*G1') +% +% figure('Name','G2_yaw contribution'); +% plot(ang_accel_yaw_d); hold on +% plot([0*cmd_yaw_fd cmd_yaw_fdd]*G_yaw) +% xlim([0 inf]); grid on; +% legend('ang\_accel\_yaw\_d', 'cmdd*G2') \ No newline at end of file