Compare commits

...

4 Commits

Author SHA1 Message Date
bresch 14d21c64ba ekf2: update change indicator 2024-03-25 16:36:28 +01:00
bresch b7f62b41a6 ekf2: integrate mag heading into mag 3D 2024-03-25 16:36:28 +01:00
bresch 41acb1ba7e ekf2: improve tilt leveling speed
Starting with no yaw uncertainty makes the tilt more observable when
using fake position fusion during the quasi-stationary alignment phase.
2024-03-25 16:36:28 +01:00
bresch d9169ba07d ekf2: use global definition of quaternion error 2024-03-25 16:36:28 +01:00
35 changed files with 2153 additions and 2174 deletions

View File

@ -20,5 +20,5 @@ bool fused # true if the sample was successfully fused
# TOPICS estimator_aid_src_baro_hgt estimator_aid_src_ev_hgt estimator_aid_src_gnss_hgt estimator_aid_src_rng_hgt
# TOPICS estimator_aid_src_airspeed estimator_aid_src_sideslip
# TOPICS estimator_aid_src_fake_hgt
# TOPICS estimator_aid_src_mag_heading estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw
# TOPICS estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw
# TOPICS estimator_aid_src_terrain_range_finder

View File

@ -189,7 +189,6 @@ if(CONFIG_EKF2_MAGNETOMETER)
EKF/mag_3d_control.cpp
EKF/mag_control.cpp
EKF/mag_fusion.cpp
EKF/mag_heading_control.cpp
)
endif()

View File

@ -107,7 +107,6 @@ if(CONFIG_EKF2_MAGNETOMETER)
mag_3d_control.cpp
mag_control.cpp
mag_fusion.cpp
mag_heading_control.cpp
)
endif()

View File

@ -53,7 +53,7 @@ void Ekf::initialiseCovariance()
{
P.zero();
resetQuatCov();
resetQuatCov(0.f); // Start with no initial uncertainty to improve fine leveling through zero vel/pos fusion
// velocity
#if defined(CONFIG_EKF2_GNSS)
@ -271,7 +271,7 @@ void Ekf::resetQuatCov(const float yaw_noise)
// update the yaw angle variance using the variance of the measurement
if (PX4_ISFINITE(yaw_noise)) {
// using magnetic heading tuning parameter
yaw_var = math::max(sq(yaw_noise), yaw_var);
yaw_var = sq(yaw_noise);
}
resetQuatCov(Vector3f(tilt_var, tilt_var, yaw_var));
@ -279,8 +279,7 @@ void Ekf::resetQuatCov(const float yaw_noise)
void Ekf::resetQuatCov(const Vector3f &rot_var_ned)
{
matrix::SquareMatrix<float, State::quat_nominal.dof> q_cov_ned = diag(rot_var_ned);
resetStateCovariance<State::quat_nominal>(_R_to_earth.T() * q_cov_ned * _R_to_earth);
P.uncorrelateCovarianceSetVariance<State::quat_nominal.dof>(State::quat_nominal.idx, rot_var_ned);
}
#if defined(CONFIG_EKF2_MAGNETOMETER)

View File

@ -155,7 +155,6 @@ void Ekf::reset()
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_MAGNETOMETER)
resetEstimatorAidStatus(_aid_src_mag_heading);
resetEstimatorAidStatus(_aid_src_mag);
#endif // CONFIG_EKF2_MAGNETOMETER

View File

@ -149,11 +149,7 @@ public:
float getHeadingInnov() const
{
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg) {
return _aid_src_mag_heading.innovation;
}
if (_control_status.flags.mag_3D) {
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
return Vector3f(_aid_src_mag.innovation).max();
}
#endif // CONFIG_EKF2_MAGNETOMETER
@ -176,11 +172,7 @@ public:
float getHeadingInnovVar() const
{
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg) {
return _aid_src_mag_heading.innovation_variance;
}
if (_control_status.flags.mag_3D) {
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
return Vector3f(_aid_src_mag.innovation_variance).max();
}
#endif // CONFIG_EKF2_MAGNETOMETER
@ -203,11 +195,7 @@ public:
float getHeadingInnovRatio() const
{
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg) {
return _aid_src_mag_heading.test_ratio;
}
if (_control_status.flags.mag_3D) {
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
return Vector3f(_aid_src_mag.test_ratio).max();
}
#endif // CONFIG_EKF2_MAGNETOMETER
@ -254,7 +242,7 @@ public:
// get the diagonal elements of the covariance matrix
matrix::Vector<float, State::size> covariances_diagonal() const { return P.diag(); }
matrix::Vector<float, State::quat_nominal.dof> getQuaternionVariance() const { return getStateVariance<State::quat_nominal>(); }
matrix::Vector3f getRotVarBody() const;
matrix::Vector3f getRotVarNed() const;
float getYawVar() const;
float getTiltVariance() const;
@ -460,7 +448,6 @@ public:
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_MAGNETOMETER)
const auto &aid_src_mag_heading() const { return _aid_src_mag_heading; }
const auto &aid_src_mag() const { return _aid_src_mag; }
#endif // CONFIG_EKF2_MAGNETOMETER
@ -715,19 +702,13 @@ private:
#endif // CONFIG_EKF2_BAROMETER
#if defined(CONFIG_EKF2_MAGNETOMETER)
float _mag_heading_prev{}; ///< previous value of mag heading (rad)
float _mag_heading_pred_prev{}; ///< previous value of yaw state used by mag heading fusion (rad)
// used by magnetometer fusion mode selection
bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable
AlphaFilter<float> _mag_heading_innov_lpf{0.1f};
float _mag_heading_last_declination{}; ///< last magnetic field declination used for heading fusion (rad)
bool _mag_decl_cov_reset{false}; ///< true after the fuseDeclination() function has been used to modify the earth field covariances after a magnetic field reset event.
uint8_t _nb_mag_heading_reset_available{0};
uint8_t _nb_mag_3d_reset_available{0};
uint32_t _min_mag_health_time_us{1'000'000}; ///< magnetometer is marked as healthy only after this amount of time
estimator_aid_source1d_s _aid_src_mag_heading{};
estimator_aid_source3d_s _aid_src_mag{};
AlphaFilter<Vector3f> _mag_lpf{0.1f}; ///< filtered magnetometer measurement for instant reset (Gauss)
@ -777,7 +758,7 @@ private:
#if defined(CONFIG_EKF2_MAGNETOMETER)
// ekf sequential fusion of magnetometer measurements
bool fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states = true);
bool fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states = true, bool update_tilt = true);
// fuse magnetometer declination measurement
// argument passed in is the declination uncertainty in radians
@ -1048,7 +1029,6 @@ private:
#if defined(CONFIG_EKF2_MAGNETOMETER)
// control fusion of magnetometer observations
void controlMagFusion();
void controlMagHeadingFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, estimator_aid_source1d_s &aid_src);
void controlMag3DFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, estimator_aid_source3d_s &aid_src);
bool checkHaglYawResetReq() const;
@ -1058,12 +1038,11 @@ private:
bool haglYawResetReq();
void checkYawAngleObservability();
void checkMagHeadingConsistency();
void checkMagHeadingConsistency(const magSample &mag_sample);
bool checkMagField(const Vector3f &mag);
static bool isMeasuredMatchingExpected(float measured, float expected, float gate);
void stopMagHdgFusion();
void stopMagFusion();
// calculate a synthetic value for the magnetometer Z component, given the 3D magnetomter
@ -1109,7 +1088,7 @@ private:
#endif // CONFIG_EKF2_GRAVITY_FUSION
void resetQuatCov(const float yaw_noise = NAN);
void resetQuatCov(const Vector3f &euler_noise_ned);
void resetQuatCov(const Vector3f &rot_var_ned);
#if defined(CONFIG_EKF2_MAGNETOMETER)
void resetMagCov();
@ -1124,9 +1103,6 @@ private:
void resetGyroBiasZCov();
// uncorrelate quaternion states from other states
void uncorrelateQuatFromOtherStates();
bool isTimedOut(uint64_t last_sensor_timestamp, uint64_t timeout_period) const
{
return (last_sensor_timestamp == 0) || (last_sensor_timestamp + timeout_period < _time_delayed_us);

View File

@ -381,11 +381,7 @@ void Ekf::get_innovation_test_status(uint16_t &status, float &mag, float &vel, f
mag = 0.f;
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg) {
mag = math::max(mag, sqrtf(_aid_src_mag_heading.test_ratio));
}
if (_control_status.flags.mag_3D) {
if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) {
mag = math::max(mag, sqrtf(Vector3f(_aid_src_mag.test_ratio).max()));
}
#endif // CONFIG_EKF2_MAGNETOMETER
@ -523,12 +519,7 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const
bool mag_innov_good = true;
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg) {
if (_aid_src_mag_heading.test_ratio < 1.f) {
mag_innov_good = false;
}
} else if (_control_status.flags.mag_3D) {
if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) {
if (Vector3f(_aid_src_mag.test_ratio).max() < 1.f) {
mag_innov_good = false;
}
@ -552,7 +543,7 @@ void Ekf::fuse(const VectorState &K, float innovation)
{
// quat_nominal
Quatf delta_quat(matrix::AxisAnglef(K.slice<State::quat_nominal.dof, 1>(State::quat_nominal.idx, 0) * (-1.f * innovation)));
_state.quat_nominal *= delta_quat;
_state.quat_nominal = delta_quat * _state.quat_nominal;
_state.quat_nominal.normalize();
_R_to_earth = Dcmf(_state.quat_nominal);
@ -586,11 +577,6 @@ void Ekf::fuse(const VectorState &K, float innovation)
#endif // CONFIG_EKF2_WIND
}
void Ekf::uncorrelateQuatFromOtherStates()
{
P.uncorrelateCovarianceBlock<State::quat_nominal.dof>(State::quat_nominal.idx);
}
void Ekf::updateDeadReckoningStatus()
{
updateHorizontalDeadReckoningstatus();
@ -660,10 +646,16 @@ void Ekf::updateVerticalDeadReckoningStatus()
}
}
Vector3f Ekf::getRotVarNed() const
Vector3f Ekf::getRotVarBody() const
{
const matrix::SquareMatrix3f rot_cov_body = getStateCovariance<State::quat_nominal>();
return matrix::SquareMatrix<float, State::quat_nominal.dof>(_R_to_earth * rot_cov_body * _R_to_earth.T()).diag();
return matrix::SquareMatrix3f(_R_to_earth.T() * rot_cov_body * _R_to_earth).diag();
}
Vector3f Ekf::getRotVarNed() const
{
const matrix::SquareMatrix3f rot_cov_ned = getStateCovariance<State::quat_nominal>();
return rot_cov_ned.diag();
}
float Ekf::getYawVar() const
@ -707,12 +699,10 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance)
// save a copy of the quaternion state for later use in calculating the amount of reset change
const Quatf quat_before_reset = _state.quat_nominal;
// save a copy of covariance in NED frame to restore it after the quat reset
Vector3f rot_var_ned_before_reset = getRotVarNed();
// update the yaw angle variance
if (PX4_ISFINITE(yaw_variance) && (yaw_variance > FLT_EPSILON)) {
rot_var_ned_before_reset(2) = yaw_variance;
// rot_var_ned_before_reset(2) = yaw_variance;
P.uncorrelateCovarianceSetVariance<1>(2, yaw_variance);
}
// update transformation matrix from body to world frame using the current estimate
@ -725,10 +715,6 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance)
// update quaternion states
_state.quat_nominal = quat_after_reset;
uncorrelateQuatFromOtherStates();
// restore covariance
resetQuatCov(rot_var_ned_before_reset);
// add the reset amount to the output observer buffered data
_output_predictor.resetQuaternion(q_error);

View File

@ -67,6 +67,18 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star
&& !_control_status.flags.ev_yaw
&& !_control_status.flags.gps_yaw;
const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps;
_control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING)
|| (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D))
&& _control_status.flags.tilt_align
&& ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss)
|| (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align))
&& !_control_status.flags.mag_fault
&& !_control_status.flags.mag_field_disturbed
&& !_control_status.flags.ev_yaw
&& !_control_status.flags.gps_yaw;
// TODO: allow clearing mag_fault if mag_3d is good?
if (_control_status.flags.mag_3D && !_control_status_prev.flags.mag_3D) {
@ -108,8 +120,9 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star
// The normal sequence is to fuse the magnetometer data first before fusing
// declination angle at a higher uncertainty to allow some learning of
// declination angle over time.
const bool update_all_states = _control_status.flags.mag_3D;
fuseMag(mag_sample.mag, aid_src, update_all_states);
const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg;
const bool update_tilt = _control_status.flags.mag_3D;
fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt);
if (_control_status.flags.mag_dec) {
fuseDeclination(0.5f);
@ -199,6 +212,12 @@ void Ekf::stopMagFusion()
_control_status.flags.mag_3D = false;
}
if (_control_status.flags.mag_hdg) {
ECL_INFO("stopping mag heading fusion");
_control_status.flags.mag_hdg = false;
_fault_status.flags.bad_hdg = false;
}
_fault_status.flags.bad_mag_x = false;
_fault_status.flags.bad_mag_y = false;
_fault_status.flags.bad_mag_z = false;

View File

@ -48,11 +48,9 @@ void Ekf::controlMagFusion()
}
checkYawAngleObservability();
checkMagHeadingConsistency();
if (_params.mag_fusion_type == MagFuseType::NONE) {
stopMagFusion();
stopMagHdgFusion();
return;
}
@ -105,12 +103,11 @@ void Ekf::controlMagFusion()
_control_status.flags.synthetic_mag_z = false;
}
checkMagHeadingConsistency(mag_sample);
controlMag3DFusion(mag_sample, starting_conditions_passing, _aid_src_mag);
controlMagHeadingFusion(mag_sample, starting_conditions_passing, _aid_src_mag_heading);
} else if (!isNewestSampleRecent(_time_last_mag_buffer_push, 2 * MAG_MAX_INTERVAL)) {
// No data anymore. Stop until it comes back.
stopMagHdgFusion();
stopMagFusion();
}
}
@ -239,8 +236,34 @@ void Ekf::checkYawAngleObservability()
}
}
void Ekf::checkMagHeadingConsistency()
void Ekf::checkMagHeadingConsistency(const magSample &mag_sample)
{
// use mag bias if variance good
Vector3f mag_bias{0.f, 0.f, 0.f};
const Vector3f mag_bias_var = getMagBiasVariance();
if ((mag_bias_var.min() > 0.f) && (mag_bias_var.max() <= sq(_params.mag_noise))) {
mag_bias = _state.mag_B;
}
// calculate mag heading
// Rotate the measurements into earth frame using the zero yaw angle
const Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth);
// the angle of the projection onto the horizontal gives the yaw angle
// calculate the yaw innovation and wrap to the interval between +-pi
const Vector3f mag_earth_pred = R_to_earth * (mag_sample.mag - mag_bias);
const float declination = getMagDeclination();
const float measured_hdg = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + declination;
if (_control_status.flags.yaw_align) {
const float innovation = wrap_pi(getEulerYaw(_R_to_earth) - measured_hdg);
_mag_heading_innov_lpf.update(innovation);
} else {
_mag_heading_innov_lpf.reset(0.f);
}
if (fabsf(_mag_heading_innov_lpf.getState()) < _params.mag_heading_noise) {
if (_yaw_angle_observable) {
// yaw angle must be observable to consider consistency
@ -349,7 +372,6 @@ void Ekf::resetMagHeading(const Vector3f &mag)
// update quaternion states and corresponding covarainces
resetQuatStateYaw(yaw_new, yaw_new_variance);
_mag_heading_last_declination = declination;
_time_last_heading_fuse = _time_delayed_us;

View File

@ -51,7 +51,7 @@
#include <mathlib/mathlib.h>
bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states)
bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states, bool update_tilt)
{
// XYZ Measurement uncertainty. Need to consider timing errors for fast rotations
const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f));
@ -191,6 +191,11 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo
Kfusion.slice<State::mag_B.dof, 1>(State::mag_B.idx, 0) = K_mag_B;
}
if (!update_tilt) {
Kfusion(State::quat_nominal.idx) = 0.f;
Kfusion(State::quat_nominal.idx + 1) = 0.f;
}
if (measurementUpdate(Kfusion, H, aid_src_mag.observation_variance[index], aid_src_mag.innovation[index])) {
fused[index] = true;
limitDeclination();

View File

@ -1,204 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mag_heading_control.cpp
* Control functions for ekf mag heading fusion
*/
#include "ekf.h"
void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common_starting_conditions_passing,
estimator_aid_source1d_s &aid_src)
{
static constexpr const char *AID_SRC_NAME = "mag heading";
// use mag bias if variance good
Vector3f mag_bias{0.f, 0.f, 0.f};
const Vector3f mag_bias_var = getMagBiasVariance();
if ((mag_bias_var.min() > 0.f) && (mag_bias_var.max() <= sq(_params.mag_noise))) {
mag_bias = _state.mag_B;
}
// calculate mag heading
// Rotate the measurements into earth frame using the zero yaw angle
const Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth);
// the angle of the projection onto the horizontal gives the yaw angle
// calculate the yaw innovation and wrap to the interval between +-pi
const Vector3f mag_earth_pred = R_to_earth * (mag_sample.mag - mag_bias);
const float declination = getMagDeclination();
const float measured_hdg = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + declination;
resetEstimatorAidStatus(aid_src);
aid_src.observation = measured_hdg;
aid_src.observation_variance = math::max(sq(_params.mag_heading_noise), sq(0.01f));
if (_control_status.flags.yaw_align) {
// mag heading
aid_src.innovation = wrap_pi(getEulerYaw(_R_to_earth) - aid_src.observation);
_mag_heading_innov_lpf.update(aid_src.innovation);
} else {
// mag heading delta (logging only)
aid_src.innovation = wrap_pi(wrap_pi(getEulerYaw(_R_to_earth) - _mag_heading_pred_prev)
- wrap_pi(measured_hdg - _mag_heading_prev));
_mag_heading_innov_lpf.reset(0.f);
}
// determine if we should use mag heading aiding
const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps;
bool continuing_conditions_passing = ((_params.mag_fusion_type == MagFuseType::HEADING)
|| (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D))
&& _control_status.flags.tilt_align
&& ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss)
|| (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align))
&& !_control_status.flags.mag_fault
&& !_control_status.flags.mag_field_disturbed
&& !_control_status.flags.ev_yaw
&& !_control_status.flags.gps_yaw
&& PX4_ISFINITE(aid_src.observation)
&& PX4_ISFINITE(aid_src.observation_variance);
const bool starting_conditions_passing = common_starting_conditions_passing
&& continuing_conditions_passing
&& isTimedOut(aid_src.time_last_fuse, 3e6);
if (_control_status.flags.mag_hdg) {
aid_src.timestamp_sample = mag_sample.time_us;
if (continuing_conditions_passing && _control_status.flags.yaw_align) {
const bool declination_changed = _control_status_prev.flags.mag_hdg
&& (fabsf(declination - _mag_heading_last_declination) > math::radians(3.f));
bool skip_timeout_check = false;
if (mag_sample.reset || declination_changed) {
if (declination_changed) {
ECL_INFO("reset to %s, declination changed %.5f->%.5f",
AID_SRC_NAME, (double)_mag_heading_last_declination, (double)declination);
} else {
ECL_INFO("reset to %s", AID_SRC_NAME);
}
resetMagHeading(_mag_lpf.getState());
aid_src.time_last_fuse = _time_delayed_us;
} else {
VectorState H_YAW;
computeYawInnovVarAndH(aid_src.observation_variance, aid_src.innovation_variance, H_YAW);
if ((aid_src.innovation_variance - aid_src.observation_variance) > sq(_params.mag_heading_noise / 2.f)) {
// Only fuse mag to constrain the yaw variance to a safe value
fuseYaw(aid_src, H_YAW);
} else {
// Yaw variance is low enough, stay in mag heading mode but don't fuse the data and skip the fusion timeout check
skip_timeout_check = true;
aid_src.test_ratio = 0.f; // required for preflight checks to pass
}
}
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max) && !skip_timeout_check;
if (is_fusion_failing) {
if (_nb_mag_heading_reset_available > 0) {
// Data seems good, attempt a reset
ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME);
resetMagHeading(_mag_lpf.getState());
aid_src.time_last_fuse = _time_delayed_us;
if (_control_status.flags.in_air) {
_nb_mag_heading_reset_available--;
}
} else if (starting_conditions_passing) {
// Data seems good, but previous reset did not fix the issue
// something else must be wrong, declare the sensor faulty and stop the fusion
_control_status.flags.mag_fault = true;
ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME);
stopMagHdgFusion();
} else {
// A reset did not fix the issue but all the starting checks are not passing
// This could be a temporary issue, stop the fusion without declaring the sensor faulty
ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME);
stopMagHdgFusion();
}
}
} else {
// Stop fusion but do not declare it faulty
ECL_WARN("stopping %s fusion, continuing conditions failing", AID_SRC_NAME);
stopMagHdgFusion();
}
} else {
if (starting_conditions_passing) {
// activate fusion
ECL_INFO("starting %s fusion", AID_SRC_NAME);
if (!_control_status.flags.yaw_align) {
// reset heading
resetMagHeading(_mag_lpf.getState());
_control_status.flags.yaw_align = true;
}
_control_status.flags.mag_hdg = true;
aid_src.time_last_fuse = _time_delayed_us;
_nb_mag_heading_reset_available = 1;
}
}
// record corresponding mag heading and yaw state for future mag heading delta heading innovation (logging only)
_mag_heading_prev = measured_hdg;
_mag_heading_pred_prev = getEulerYaw(_state.quat_nominal);
_mag_heading_last_declination = getMagDeclination();
}
void Ekf::stopMagHdgFusion()
{
if (_control_status.flags.mag_hdg) {
ECL_INFO("stopping mag heading fusion");
resetEstimatorAidStatus(_aid_src_mag_heading);
_control_status.flags.mag_hdg = false;
_fault_status.flags.bad_hdg = false;
}
}

View File

@ -148,7 +148,7 @@ def predict_covariance(
for key in state.keys():
if key == "quat_nominal":
# Create true quaternion using small angle approximation of the error rotation
state_t["quat_nominal"] = state["quat_nominal"] * sf.Rot3(sf.Quaternion(xyz=(state_error["theta"] / 2), w=1))
state_t["quat_nominal"] = sf.Rot3(sf.Quaternion(xyz=(state_error["theta"] / 2), w=1)) * state["quat_nominal"]
else:
state_t[key] = state[key] + state_error[key]
@ -184,7 +184,7 @@ def predict_covariance(
state_error_pred = Values()
for key in state_error.keys():
if key == "theta":
delta_q = sf.Quaternion.from_storage(state_pred["quat_nominal"].to_storage()).conj() * sf.Quaternion.from_storage(state_t_pred["quat_nominal"].to_storage())
delta_q = sf.Quaternion.from_storage(state_t_pred["quat_nominal"].to_storage()) * sf.Quaternion.from_storage(state_pred["quat_nominal"].to_storage()).conj()
state_error_pred["theta"] = 2 * sf.V3(delta_q.x, delta_q.y, delta_q.z) # Use small angle approximation to obtain a simpler jacobian
else:
state_error_pred[key] = state_t_pred[key] - state_pred[key]
@ -216,6 +216,36 @@ def predict_covariance(
return P_new
def jacobian_chain_rule(expr: sf.Scalar , state: State):
# First compute the jacobian in the parameter space
dh_dx = sf.V1(expr).jacobian(state, tangent_space=False)
class MStorageTangent(sf.Matrix):
SHAPE = (State.storage_dim(), State.tangent_dim())
# Then compute the jarobian mapping infinitesimal elements of the parameter space to the error state
# Note that this jacobian only depends on the structure of the EKF
dx_derror = MStorageTangent()
q = sf.Quaternion.from_storage(state["quat_nominal"].to_storage())
p = sf.Quaternion.symbolic('p')
pq = p * q
qR = sf.M41(pq.to_storage()).jacobian(sf.M41(p.to_storage())) # Right quaternion product matrix
dx_derror[0:4, 0:3] = qR / 2 * sf.M43([[1, 0, 0],
[0, 1, 0],
[0, 0, 1],
[0, 0, 0]])
# The rest of the matrix is trivial
for i in range(4, State.storage_dim()):
for j in range(3, State.tangent_dim()):
if (i == j+1):
dx_derror[i, j] = 1
# Finally use the chain rule: dh/derror = dh/dx * dx/derror
H = dh_dx * dx_derror
return H
def compute_airspeed_innov_and_innov_var(
state: VState,
P: MTangent,
@ -231,7 +261,7 @@ def compute_airspeed_innov_and_innov_var(
innov = airspeed_pred - airspeed
H = sf.V1(airspeed_pred).jacobian(state)
H = jacobian_chain_rule(airspeed_pred, state)
innov_var = (H * P * H.T + R)[0,0]
return (innov, innov_var)
@ -247,7 +277,7 @@ def compute_airspeed_h_and_k(
wind = sf.V3(state["wind_vel"][0], state["wind_vel"][1], 0.0)
vel_rel = state["vel"] - wind
airspeed_pred = vel_rel.norm(epsilon=epsilon)
H = sf.V1(airspeed_pred).jacobian(state)
H = jacobian_chain_rule(airspeed_pred, state)
K = P * H.T / sf.Max(innov_var, epsilon)
@ -309,7 +339,7 @@ def compute_sideslip_innov_and_innov_var(
innov = sideslip_pred - 0.0
H = sf.V1(sideslip_pred).jacobian(state)
H = jacobian_chain_rule(sideslip_pred, state)
innov_var = (H * P * H.T + R)[0,0]
return (innov, innov_var)
@ -324,7 +354,7 @@ def compute_sideslip_h_and_k(
state = vstate_to_state(state)
sideslip_pred = predict_sideslip(state, epsilon);
H = sf.V1(sideslip_pred).jacobian(state)
H = jacobian_chain_rule(sideslip_pred, state)
K = P * H.T / sf.Max(innov_var, epsilon)
@ -351,11 +381,11 @@ def compute_mag_innov_innov_var_and_hx(
innov = meas_pred - meas
innov_var = sf.V3()
Hx = sf.V1(meas_pred[0]).jacobian(state)
Hx = jacobian_chain_rule(meas_pred[0], state)
innov_var[0] = (Hx * P * Hx.T + R)[0,0]
Hy = sf.V1(meas_pred[1]).jacobian(state)
Hy = jacobian_chain_rule(meas_pred[1], state)
innov_var[1] = (Hy * P * Hy.T + R)[0,0]
Hz = sf.V1(meas_pred[2]).jacobian(state)
Hz = jacobian_chain_rule(meas_pred[2], state)
innov_var[2] = (Hz * P * Hz.T + R)[0,0]
return (innov, innov_var, Hx.T)
@ -370,7 +400,7 @@ def compute_mag_y_innov_var_and_h(
state = vstate_to_state(state)
meas_pred = predict_mag_body(state);
H = sf.V1(meas_pred[1]).jacobian(state)
H = jacobian_chain_rule(meas_pred[1], state)
innov_var = (H * P * H.T + R)[0,0]
return (innov_var, H.T)
@ -385,7 +415,7 @@ def compute_mag_z_innov_var_and_h(
state = vstate_to_state(state)
meas_pred = predict_mag_body(state);
H = sf.V1(meas_pred[2]).jacobian(state)
H = jacobian_chain_rule(meas_pred[2], state)
innov_var = (H * P * H.T + R)[0,0]
return (innov_var, H.T)
@ -402,8 +432,11 @@ def compute_yaw_innov_var_and_h(
delta_q = q * r.conj() # create a quaternion error of the measurement at the origin
delta_meas_pred = 2 * delta_q.z # Use small angle approximation to obtain a simpler jacobian
H = sf.V1(delta_meas_pred).jacobian(state)
H = jacobian_chain_rule(delta_meas_pred, state)
H = H.subs({r.w: q.w, r.x: q.x, r.y: q.y, r.z: q.z}) # assume innovation is small
for i in range(State.tangent_dim()):
H[i] = sp.factor(H[i]).subs(q.w**2 + q.x**2 + q.y**2 + q.z**2, 1) # unit norm quaternion
innov_var = (H * P * H.T + R)[0,0]
return (innov_var, H.T)
@ -418,7 +451,7 @@ def compute_mag_declination_pred_innov_var_and_h(
state = vstate_to_state(state)
meas_pred = sf.atan2(state["mag_I"][1], state["mag_I"][0], epsilon=epsilon)
H = sf.V1(meas_pred).jacobian(state)
H = jacobian_chain_rule(meas_pred, state)
innov_var = (H * P * H.T + R)[0,0]
return (meas_pred, innov_var, H.T)
@ -450,9 +483,9 @@ def compute_flow_xy_innov_var_and_hx(
meas_pred = predict_opt_flow(state, distance, epsilon);
innov_var = sf.V2()
Hx = sf.V1(meas_pred[0]).jacobian(state)
Hx = jacobian_chain_rule(meas_pred[0], state)
innov_var[0] = (Hx * P * Hx.T + R)[0,0]
Hy = sf.V1(meas_pred[1]).jacobian(state)
Hy = jacobian_chain_rule(meas_pred[1], state)
innov_var[1] = (Hy * P * Hy.T + R)[0,0]
return (innov_var, Hx.T)
@ -467,7 +500,7 @@ def compute_flow_y_innov_var_and_h(
state = vstate_to_state(state)
meas_pred = predict_opt_flow(state, distance, epsilon);
Hy = sf.V1(meas_pred[1]).jacobian(state)
Hy = jacobian_chain_rule(meas_pred[1], state)
innov_var = (Hy * P * Hy.T + R)[0,0]
return (innov_var, Hy.T)
@ -492,7 +525,7 @@ def compute_gnss_yaw_pred_innov_var_and_h(
# Calculate the yaw angle from the projection
meas_pred = sf.atan2(ant_vec_ef[1], ant_vec_ef[0], epsilon=epsilon)
H = sf.V1(meas_pred).jacobian(state)
H = jacobian_chain_rule(meas_pred, state)
innov_var = (H * P * H.T + R)[0,0]
return (meas_pred, innov_var, H.T)
@ -529,7 +562,7 @@ def compute_drag_x_innov_var_and_h(
state = vstate_to_state(state)
meas_pred = predict_drag(state, rho, cd, cm, epsilon)
Hx = sf.V1(meas_pred[0]).jacobian(state)
Hx = jacobian_chain_rule(meas_pred[0], state)
innov_var = (Hx * P * Hx.T + R)[0,0]
return (innov_var, Hx.T)
@ -546,7 +579,7 @@ def compute_drag_y_innov_var_and_h(
state = vstate_to_state(state)
meas_pred = predict_drag(state, rho, cd, cm, epsilon)
Hy = sf.V1(meas_pred[1]).jacobian(state)
Hy = jacobian_chain_rule(meas_pred[1], state)
innov_var = (Hy * P * Hy.T + R)[0,0]
return (innov_var, Hy.T)
@ -575,7 +608,7 @@ def compute_gravity_xyz_innov_var_and_hx(
# calculate observation jacobian (H), kalman gain (K), and innovation variance (S)
# for each axis
for i in range(3):
H[i] = sf.V1(meas_pred[i]).jacobian(state)
H[i] = jacobian_chain_rule(meas_pred[i], state)
innov_var[i] = (H[i] * P * H[i].T + R)[0,0]
return (innov_var, H[0].T)
@ -590,7 +623,7 @@ def compute_gravity_y_innov_var_and_h(
meas_pred = predict_gravity_direction(state)
# calculate observation jacobian (H), kalman gain (K), and innovation variance (S)
H = sf.V1(meas_pred[1]).jacobian(state)
H = jacobian_chain_rule(meas_pred[1], state)
innov_var = (H * P * H.T + R)[0,0]
return (innov_var, H.T)
@ -605,7 +638,7 @@ def compute_gravity_z_innov_var_and_h(
meas_pred = predict_gravity_direction(state)
# calculate observation jacobian (H), kalman gain (K), and innovation variance (S)
H = sf.V1(meas_pred[2]).jacobian(state)
H = jacobian_chain_rule(meas_pred[2], state)
innov_var = (H * P * H.T + R)[0,0]
return (innov_var, H.T)

View File

@ -34,95 +34,108 @@ void ComputeDragXInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const Scalar cd, const Scalar cm, const Scalar R,
const Scalar epsilon, Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const Hx = nullptr) {
// Total ops: 317
// Total ops: 357
// Input arrays
// Intermediate terms (73)
const Scalar _tmp0 = 2 * state(3, 0);
const Scalar _tmp1 = _tmp0 * state(0, 0);
const Scalar _tmp2 = 2 * state(2, 0);
const Scalar _tmp3 = _tmp2 * state(1, 0);
// Intermediate terms (79)
const Scalar _tmp0 = 2 * state(0, 0);
const Scalar _tmp1 = _tmp0 * state(3, 0);
const Scalar _tmp2 = 2 * state(1, 0);
const Scalar _tmp3 = _tmp2 * state(2, 0);
const Scalar _tmp4 = _tmp1 + _tmp3;
const Scalar _tmp5 = _tmp4 * cm;
const Scalar _tmp6 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp7 = -2 * _tmp6;
const Scalar _tmp8 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp9 = -2 * _tmp8;
const Scalar _tmp10 = _tmp7 + _tmp9 + 1;
const Scalar _tmp11 = -state(22, 0) + state(4, 0);
const Scalar _tmp12 = -state(23, 0) + state(5, 0);
const Scalar _tmp13 = _tmp2 * state(0, 0);
const Scalar _tmp14 = -_tmp13;
const Scalar _tmp15 = _tmp0 * state(1, 0);
const Scalar _tmp16 = _tmp14 + _tmp15;
const Scalar _tmp17 = _tmp12 * _tmp4 + _tmp16 * state(6, 0);
const Scalar _tmp18 = _tmp10 * _tmp11 + _tmp17;
const Scalar _tmp19 = 2 * _tmp18;
const Scalar _tmp20 = _tmp19 * _tmp4;
const Scalar _tmp21 = _tmp0 * state(2, 0);
const Scalar _tmp22 = 2 * state(0, 0) * state(1, 0);
const Scalar _tmp23 = -_tmp22;
const Scalar _tmp24 = _tmp21 + _tmp23;
const Scalar _tmp25 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp26 = 1 - 2 * _tmp25;
const Scalar _tmp27 = _tmp26 + _tmp9;
const Scalar _tmp28 = _tmp13 + _tmp15;
const Scalar _tmp29 = _tmp11 * _tmp28 + _tmp12 * _tmp24;
const Scalar _tmp30 = _tmp27 * state(6, 0) + _tmp29;
const Scalar _tmp6 = -2 * std::pow(state(3, 0), Scalar(2));
const Scalar _tmp7 = -2 * std::pow(state(2, 0), Scalar(2));
const Scalar _tmp8 = _tmp6 + _tmp7 + 1;
const Scalar _tmp9 = -state(22, 0) + state(4, 0);
const Scalar _tmp10 = -state(23, 0) + state(5, 0);
const Scalar _tmp11 = 2 * state(2, 0);
const Scalar _tmp12 = _tmp11 * state(0, 0);
const Scalar _tmp13 = _tmp2 * state(3, 0);
const Scalar _tmp14 = -_tmp12 + _tmp13;
const Scalar _tmp15 = _tmp10 * _tmp4 + _tmp14 * state(6, 0) + _tmp8 * _tmp9;
const Scalar _tmp16 = 2 * _tmp15;
const Scalar _tmp17 = _tmp16 * _tmp4;
const Scalar _tmp18 = _tmp11 * state(3, 0);
const Scalar _tmp19 = _tmp2 * state(0, 0);
const Scalar _tmp20 = _tmp18 - _tmp19;
const Scalar _tmp21 = _tmp12 + _tmp13;
const Scalar _tmp22 = 1 - 2 * std::pow(state(1, 0), Scalar(2));
const Scalar _tmp23 = _tmp22 + _tmp7;
const Scalar _tmp24 = _tmp10 * _tmp20 + _tmp21 * _tmp9 + _tmp23 * state(6, 0);
const Scalar _tmp25 = 2 * _tmp24;
const Scalar _tmp26 = _tmp20 * _tmp25;
const Scalar _tmp27 = _tmp22 + _tmp6;
const Scalar _tmp28 = -_tmp1 + _tmp3;
const Scalar _tmp29 = _tmp18 + _tmp19;
const Scalar _tmp30 = _tmp10 * _tmp27 + _tmp28 * _tmp9 + _tmp29 * state(6, 0);
const Scalar _tmp31 = 2 * _tmp30;
const Scalar _tmp32 = _tmp24 * _tmp31;
const Scalar _tmp33 = _tmp26 + _tmp7;
const Scalar _tmp34 = -_tmp1;
const Scalar _tmp35 = _tmp3 + _tmp34;
const Scalar _tmp36 = _tmp21 + _tmp22;
const Scalar _tmp37 = _tmp11 * _tmp35 + _tmp36 * state(6, 0);
const Scalar _tmp38 = _tmp12 * _tmp33 + _tmp37;
const Scalar _tmp39 = 2 * _tmp38;
const Scalar _tmp40 = _tmp33 * _tmp39;
const Scalar _tmp41 = std::sqrt(Scalar(std::pow(_tmp18, Scalar(2)) + std::pow(_tmp30, Scalar(2)) +
std::pow(_tmp38, Scalar(2)) + epsilon));
const Scalar _tmp42 = cd * rho;
const Scalar _tmp43 = Scalar(0.25) * _tmp18 * _tmp42 / _tmp41;
const Scalar _tmp44 = Scalar(0.5) * _tmp41 * _tmp42;
const Scalar _tmp45 = _tmp4 * _tmp44;
const Scalar _tmp46 = -_tmp43 * (_tmp20 + _tmp32 + _tmp40) - _tmp45 - _tmp5;
const Scalar _tmp47 = -_tmp25;
const Scalar _tmp48 = _tmp47 + _tmp6;
const Scalar _tmp49 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp50 = -_tmp49;
const Scalar _tmp51 = _tmp50 + _tmp8;
const Scalar _tmp52 = -_tmp3;
const Scalar _tmp53 = -_tmp15;
const Scalar _tmp54 = -_tmp6;
const Scalar _tmp55 = _tmp12 * (_tmp47 + _tmp49 + _tmp54 + _tmp8) + _tmp37;
const Scalar _tmp56 = -_tmp43 * (_tmp19 * _tmp55 + _tmp39 * (_tmp11 * (_tmp48 + _tmp51) +
_tmp12 * (_tmp34 + _tmp52) +
state(6, 0) * (_tmp13 + _tmp53))) -
_tmp44 * _tmp55 - _tmp55 * cm;
const Scalar _tmp57 = -_tmp43 * (-_tmp20 - _tmp32 - _tmp40) + _tmp45 + _tmp5;
const Scalar _tmp58 = _tmp10 * cm;
const Scalar _tmp59 = _tmp10 * _tmp19;
const Scalar _tmp60 = _tmp28 * _tmp31;
const Scalar _tmp61 = _tmp35 * _tmp39;
const Scalar _tmp62 = _tmp10 * _tmp44;
const Scalar _tmp63 = -_tmp43 * (-_tmp59 - _tmp60 - _tmp61) + _tmp58 + _tmp62;
const Scalar _tmp64 = -_tmp8;
const Scalar _tmp65 = -_tmp21;
const Scalar _tmp66 = _tmp49 + _tmp64;
const Scalar _tmp67 =
_tmp43 * (_tmp31 * (_tmp11 * (_tmp1 + _tmp52) + _tmp12 * (_tmp25 + _tmp50 + _tmp6 + _tmp64) +
state(6, 0) * (_tmp23 + _tmp65)) +
_tmp39 * (_tmp29 + state(6, 0) * (_tmp48 + _tmp66)));
const Scalar _tmp68 = _tmp25 + _tmp54;
const Scalar _tmp69 =
_tmp11 * (_tmp14 + _tmp53) + _tmp12 * (_tmp22 + _tmp65) + state(6, 0) * (_tmp51 + _tmp68);
const Scalar _tmp70 =
-_tmp43 * (_tmp19 * _tmp69 + _tmp31 * (_tmp11 * (_tmp66 + _tmp68) + _tmp17)) -
_tmp44 * _tmp69 - _tmp69 * cm;
const Scalar _tmp71 = -_tmp43 * (_tmp59 + _tmp60 + _tmp61) - _tmp58 - _tmp62;
const Scalar _tmp72 = -_tmp16 * _tmp44 - _tmp16 * cm -
_tmp43 * (_tmp16 * _tmp19 + _tmp27 * _tmp31 + _tmp36 * _tmp39);
const Scalar _tmp32 = _tmp27 * _tmp31;
const Scalar _tmp33 = std::sqrt(Scalar(std::pow(_tmp15, Scalar(2)) + std::pow(_tmp24, Scalar(2)) +
std::pow(_tmp30, Scalar(2)) + epsilon));
const Scalar _tmp34 = cd * rho;
const Scalar _tmp35 = Scalar(0.25) * _tmp15 * _tmp34 / _tmp33;
const Scalar _tmp36 = Scalar(0.5) * _tmp33 * _tmp34;
const Scalar _tmp37 = _tmp36 * _tmp4;
const Scalar _tmp38 = -_tmp35 * (-_tmp17 - _tmp26 - _tmp32) + _tmp37 + _tmp5;
const Scalar _tmp39 = -_tmp35 * (_tmp17 + _tmp26 + _tmp32) - _tmp37 - _tmp5;
const Scalar _tmp40 = _tmp8 * cm;
const Scalar _tmp41 = _tmp16 * _tmp8;
const Scalar _tmp42 = _tmp21 * _tmp25;
const Scalar _tmp43 = _tmp28 * _tmp31;
const Scalar _tmp44 = _tmp36 * _tmp8;
const Scalar _tmp45 = -_tmp35 * (-_tmp41 - _tmp42 - _tmp43) + _tmp40 + _tmp44;
const Scalar _tmp46 = 2 * state(3, 0);
const Scalar _tmp47 = _tmp10 * _tmp46;
const Scalar _tmp48 = 2 * state(6, 0);
const Scalar _tmp49 = _tmp48 * state(2, 0);
const Scalar _tmp50 = _tmp47 - _tmp49;
const Scalar _tmp51 = _tmp10 * _tmp2;
const Scalar _tmp52 = _tmp11 * _tmp9;
const Scalar _tmp53 = _tmp46 * _tmp9;
const Scalar _tmp54 = _tmp2 * state(6, 0);
const Scalar _tmp55 =
-_tmp35 * (_tmp16 * _tmp50 + _tmp25 * (-_tmp51 + _tmp52) + _tmp31 * (-_tmp53 + _tmp54)) -
_tmp36 * _tmp50 - _tmp50 * cm;
const Scalar _tmp56 = (Scalar(1) / Scalar(2)) * _tmp55;
const Scalar _tmp57 = _tmp10 * _tmp11;
const Scalar _tmp58 = _tmp48 * state(3, 0);
const Scalar _tmp59 = _tmp57 + _tmp58;
const Scalar _tmp60 = _tmp0 * _tmp10;
const Scalar _tmp61 = 4 * state(6, 0);
const Scalar _tmp62 = 4 * _tmp10;
const Scalar _tmp63 = _tmp48 * state(0, 0);
const Scalar _tmp64 =
-_tmp35 * (_tmp16 * _tmp59 + _tmp25 * (_tmp53 - _tmp60 - _tmp61 * state(1, 0)) +
_tmp31 * (_tmp52 - _tmp62 * state(1, 0) + _tmp63)) -
_tmp36 * _tmp59 - _tmp59 * cm;
const Scalar _tmp65 = (Scalar(1) / Scalar(2)) * state(2, 0);
const Scalar _tmp66 = 4 * _tmp9;
const Scalar _tmp67 = _tmp54 + _tmp60 - _tmp66 * state(3, 0);
const Scalar _tmp68 = _tmp2 * _tmp9;
const Scalar _tmp69 = _tmp0 * _tmp9;
const Scalar _tmp70 = -Scalar(1) / Scalar(2) * _tmp35 *
(_tmp16 * _tmp67 + _tmp25 * (_tmp57 + _tmp68) +
_tmp31 * (_tmp49 - _tmp62 * state(3, 0) - _tmp69)) -
Scalar(1) / Scalar(2) * _tmp36 * _tmp67 -
Scalar(1) / Scalar(2) * _tmp67 * cm;
const Scalar _tmp71 = _tmp51 - _tmp63 - _tmp66 * state(2, 0);
const Scalar _tmp72 = -Scalar(1) / Scalar(2) * _tmp35 *
(_tmp16 * _tmp71 + _tmp25 * (_tmp47 - _tmp61 * state(2, 0) + _tmp69) +
_tmp31 * (_tmp58 + _tmp68)) -
Scalar(1) / Scalar(2) * _tmp36 * _tmp71 -
Scalar(1) / Scalar(2) * _tmp71 * cm;
const Scalar _tmp73 =
-_tmp56 * state(3, 0) - _tmp64 * _tmp65 + _tmp70 * state(0, 0) + _tmp72 * state(1, 0);
const Scalar _tmp74 = (Scalar(1) / Scalar(2)) * _tmp64;
const Scalar _tmp75 =
-_tmp55 * _tmp65 - _tmp70 * state(1, 0) + _tmp72 * state(0, 0) + _tmp74 * state(3, 0);
const Scalar _tmp76 =
-_tmp56 * state(1, 0) + _tmp70 * state(2, 0) - _tmp72 * state(3, 0) + _tmp74 * state(0, 0);
const Scalar _tmp77 = -_tmp35 * (_tmp41 + _tmp42 + _tmp43) - _tmp40 - _tmp44;
const Scalar _tmp78 = -_tmp14 * _tmp36 - _tmp14 * cm -
_tmp35 * (_tmp14 * _tmp16 + _tmp23 * _tmp25 + _tmp29 * _tmp31);
// Output terms (2)
if (innov_var != nullptr) {
@ -130,22 +143,22 @@ void ComputeDragXInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_innov_var =
R +
_tmp46 * (-P(0, 4) * _tmp67 + P(1, 4) * _tmp70 + P(2, 4) * _tmp56 + P(21, 4) * _tmp63 +
P(22, 4) * _tmp57 + P(3, 4) * _tmp71 + P(4, 4) * _tmp46 + P(5, 4) * _tmp72) +
_tmp56 * (-P(0, 2) * _tmp67 + P(1, 2) * _tmp70 + P(2, 2) * _tmp56 + P(21, 2) * _tmp63 +
P(22, 2) * _tmp57 + P(3, 2) * _tmp71 + P(4, 2) * _tmp46 + P(5, 2) * _tmp72) +
_tmp57 * (-P(0, 22) * _tmp67 + P(1, 22) * _tmp70 + P(2, 22) * _tmp56 + P(21, 22) * _tmp63 +
P(22, 22) * _tmp57 + P(3, 22) * _tmp71 + P(4, 22) * _tmp46 + P(5, 22) * _tmp72) +
_tmp63 * (-P(0, 21) * _tmp67 + P(1, 21) * _tmp70 + P(2, 21) * _tmp56 + P(21, 21) * _tmp63 +
P(22, 21) * _tmp57 + P(3, 21) * _tmp71 + P(4, 21) * _tmp46 + P(5, 21) * _tmp72) -
_tmp67 * (-P(0, 0) * _tmp67 + P(1, 0) * _tmp70 + P(2, 0) * _tmp56 + P(21, 0) * _tmp63 +
P(22, 0) * _tmp57 + P(3, 0) * _tmp71 + P(4, 0) * _tmp46 + P(5, 0) * _tmp72) +
_tmp70 * (-P(0, 1) * _tmp67 + P(1, 1) * _tmp70 + P(2, 1) * _tmp56 + P(21, 1) * _tmp63 +
P(22, 1) * _tmp57 + P(3, 1) * _tmp71 + P(4, 1) * _tmp46 + P(5, 1) * _tmp72) +
_tmp71 * (-P(0, 3) * _tmp67 + P(1, 3) * _tmp70 + P(2, 3) * _tmp56 + P(21, 3) * _tmp63 +
P(22, 3) * _tmp57 + P(3, 3) * _tmp71 + P(4, 3) * _tmp46 + P(5, 3) * _tmp72) +
_tmp72 * (-P(0, 5) * _tmp67 + P(1, 5) * _tmp70 + P(2, 5) * _tmp56 + P(21, 5) * _tmp63 +
P(22, 5) * _tmp57 + P(3, 5) * _tmp71 + P(4, 5) * _tmp46 + P(5, 5) * _tmp72);
_tmp38 * (P(0, 22) * _tmp76 + P(1, 22) * _tmp75 + P(2, 22) * _tmp73 + P(21, 22) * _tmp45 +
P(22, 22) * _tmp38 + P(3, 22) * _tmp77 + P(4, 22) * _tmp39 + P(5, 22) * _tmp78) +
_tmp39 * (P(0, 4) * _tmp76 + P(1, 4) * _tmp75 + P(2, 4) * _tmp73 + P(21, 4) * _tmp45 +
P(22, 4) * _tmp38 + P(3, 4) * _tmp77 + P(4, 4) * _tmp39 + P(5, 4) * _tmp78) +
_tmp45 * (P(0, 21) * _tmp76 + P(1, 21) * _tmp75 + P(2, 21) * _tmp73 + P(21, 21) * _tmp45 +
P(22, 21) * _tmp38 + P(3, 21) * _tmp77 + P(4, 21) * _tmp39 + P(5, 21) * _tmp78) +
_tmp73 * (P(0, 2) * _tmp76 + P(1, 2) * _tmp75 + P(2, 2) * _tmp73 + P(21, 2) * _tmp45 +
P(22, 2) * _tmp38 + P(3, 2) * _tmp77 + P(4, 2) * _tmp39 + P(5, 2) * _tmp78) +
_tmp75 * (P(0, 1) * _tmp76 + P(1, 1) * _tmp75 + P(2, 1) * _tmp73 + P(21, 1) * _tmp45 +
P(22, 1) * _tmp38 + P(3, 1) * _tmp77 + P(4, 1) * _tmp39 + P(5, 1) * _tmp78) +
_tmp76 * (P(0, 0) * _tmp76 + P(1, 0) * _tmp75 + P(2, 0) * _tmp73 + P(21, 0) * _tmp45 +
P(22, 0) * _tmp38 + P(3, 0) * _tmp77 + P(4, 0) * _tmp39 + P(5, 0) * _tmp78) +
_tmp77 * (P(0, 3) * _tmp76 + P(1, 3) * _tmp75 + P(2, 3) * _tmp73 + P(21, 3) * _tmp45 +
P(22, 3) * _tmp38 + P(3, 3) * _tmp77 + P(4, 3) * _tmp39 + P(5, 3) * _tmp78) +
_tmp78 * (P(0, 5) * _tmp76 + P(1, 5) * _tmp75 + P(2, 5) * _tmp73 + P(21, 5) * _tmp45 +
P(22, 5) * _tmp38 + P(3, 5) * _tmp77 + P(4, 5) * _tmp39 + P(5, 5) * _tmp78);
}
if (Hx != nullptr) {
@ -153,14 +166,14 @@ void ComputeDragXInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_hx.setZero();
_hx(0, 0) = -_tmp67;
_hx(1, 0) = _tmp70;
_hx(2, 0) = _tmp56;
_hx(3, 0) = _tmp71;
_hx(4, 0) = _tmp46;
_hx(5, 0) = _tmp72;
_hx(21, 0) = _tmp63;
_hx(22, 0) = _tmp57;
_hx(0, 0) = _tmp76;
_hx(1, 0) = _tmp75;
_hx(2, 0) = _tmp73;
_hx(3, 0) = _tmp77;
_hx(4, 0) = _tmp39;
_hx(5, 0) = _tmp78;
_hx(21, 0) = _tmp45;
_hx(22, 0) = _tmp38;
}
} // NOLINT(readability/fn_size)

View File

@ -34,97 +34,108 @@ void ComputeDragYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const Scalar cd, const Scalar cm, const Scalar R,
const Scalar epsilon, Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const Hy = nullptr) {
// Total ops: 317
// Total ops: 360
// Input arrays
// Intermediate terms (73)
const Scalar _tmp0 = 2 * state(2, 0) * state(3, 0);
const Scalar _tmp1 = 2 * state(1, 0);
const Scalar _tmp2 = _tmp1 * state(0, 0);
const Scalar _tmp3 = _tmp0 + _tmp2;
const Scalar _tmp4 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp5 = -2 * _tmp4;
const Scalar _tmp6 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp7 = -2 * _tmp6;
const Scalar _tmp8 = _tmp5 + _tmp7 + 1;
// Intermediate terms (76)
const Scalar _tmp0 = 2 * state(0, 0);
const Scalar _tmp1 = _tmp0 * state(3, 0);
const Scalar _tmp2 = 2 * state(1, 0);
const Scalar _tmp3 = _tmp2 * state(2, 0);
const Scalar _tmp4 = -_tmp1 + _tmp3;
const Scalar _tmp5 = _tmp4 * cm;
const Scalar _tmp6 = -2 * std::pow(state(3, 0), Scalar(2));
const Scalar _tmp7 = -2 * std::pow(state(2, 0), Scalar(2));
const Scalar _tmp8 = _tmp6 + _tmp7 + 1;
const Scalar _tmp9 = -state(22, 0) + state(4, 0);
const Scalar _tmp10 = 2 * state(0, 0);
const Scalar _tmp11 = _tmp10 * state(3, 0);
const Scalar _tmp12 = _tmp1 * state(2, 0);
const Scalar _tmp13 = _tmp11 + _tmp12;
const Scalar _tmp14 = -state(23, 0) + state(5, 0);
const Scalar _tmp15 = _tmp10 * state(2, 0);
const Scalar _tmp16 = -_tmp15;
const Scalar _tmp17 = _tmp1 * state(3, 0);
const Scalar _tmp18 = _tmp16 + _tmp17;
const Scalar _tmp19 = _tmp13 * _tmp14 + _tmp18 * state(6, 0);
const Scalar _tmp20 = _tmp19 + _tmp8 * _tmp9;
const Scalar _tmp21 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp22 = 1 - 2 * _tmp21;
const Scalar _tmp23 = _tmp22 + _tmp7;
const Scalar _tmp24 = -_tmp2;
const Scalar _tmp25 = _tmp0 + _tmp24;
const Scalar _tmp26 = _tmp15 + _tmp17;
const Scalar _tmp27 = _tmp14 * _tmp25 + _tmp26 * _tmp9;
const Scalar _tmp28 = _tmp23 * state(6, 0) + _tmp27;
const Scalar _tmp29 = _tmp22 + _tmp5;
const Scalar _tmp30 = -_tmp11;
const Scalar _tmp31 = _tmp12 + _tmp30;
const Scalar _tmp32 = _tmp3 * state(6, 0) + _tmp31 * _tmp9;
const Scalar _tmp33 = _tmp14 * _tmp29 + _tmp32;
const Scalar _tmp34 = std::sqrt(Scalar(std::pow(_tmp20, Scalar(2)) + std::pow(_tmp28, Scalar(2)) +
std::pow(_tmp33, Scalar(2)) + epsilon));
const Scalar _tmp35 = cd * rho;
const Scalar _tmp36 = Scalar(0.5) * _tmp34 * _tmp35;
const Scalar _tmp37 = 2 * _tmp20;
const Scalar _tmp38 = 2 * _tmp28;
const Scalar _tmp39 = 2 * _tmp33;
const Scalar _tmp40 = Scalar(0.25) * _tmp33 * _tmp35 / _tmp34;
const Scalar _tmp41 =
-_tmp3 * _tmp36 - _tmp3 * cm - _tmp40 * (_tmp18 * _tmp37 + _tmp23 * _tmp38 + _tmp3 * _tmp39);
const Scalar _tmp42 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp43 = -_tmp42;
const Scalar _tmp44 = -_tmp6;
const Scalar _tmp45 = -_tmp12;
const Scalar _tmp46 = -_tmp0;
const Scalar _tmp47 = -_tmp21;
const Scalar _tmp48 = _tmp4 + _tmp47;
const Scalar _tmp49 = _tmp42 + _tmp44;
const Scalar _tmp50 = _tmp27 + state(6, 0) * (_tmp48 + _tmp49);
const Scalar _tmp51 =
-_tmp36 * _tmp50 -
_tmp40 * (_tmp38 * (_tmp14 * (_tmp21 + _tmp4 + _tmp43 + _tmp44) + _tmp9 * (_tmp11 + _tmp45) +
state(6, 0) * (_tmp24 + _tmp46)) +
_tmp39 * _tmp50) -
_tmp50 * cm;
const Scalar _tmp52 = _tmp43 + _tmp6;
const Scalar _tmp53 = -_tmp17;
const Scalar _tmp54 =
_tmp14 * (_tmp30 + _tmp45) + _tmp9 * (_tmp48 + _tmp52) + state(6, 0) * (_tmp15 + _tmp53);
const Scalar _tmp55 = -_tmp4;
const Scalar _tmp10 = _tmp1 + _tmp3;
const Scalar _tmp11 = -state(23, 0) + state(5, 0);
const Scalar _tmp12 = _tmp0 * state(2, 0);
const Scalar _tmp13 = _tmp2 * state(3, 0);
const Scalar _tmp14 = -_tmp12 + _tmp13;
const Scalar _tmp15 = _tmp10 * _tmp11 + _tmp14 * state(6, 0) + _tmp8 * _tmp9;
const Scalar _tmp16 = 2 * state(3, 0);
const Scalar _tmp17 = _tmp16 * state(2, 0);
const Scalar _tmp18 = _tmp2 * state(0, 0);
const Scalar _tmp19 = _tmp17 - _tmp18;
const Scalar _tmp20 = _tmp12 + _tmp13;
const Scalar _tmp21 = 1 - 2 * std::pow(state(1, 0), Scalar(2));
const Scalar _tmp22 = _tmp21 + _tmp7;
const Scalar _tmp23 = _tmp11 * _tmp19 + _tmp20 * _tmp9 + _tmp22 * state(6, 0);
const Scalar _tmp24 = _tmp21 + _tmp6;
const Scalar _tmp25 = _tmp17 + _tmp18;
const Scalar _tmp26 = _tmp11 * _tmp24 + _tmp25 * state(6, 0) + _tmp4 * _tmp9;
const Scalar _tmp27 = std::sqrt(Scalar(std::pow(_tmp15, Scalar(2)) + std::pow(_tmp23, Scalar(2)) +
std::pow(_tmp26, Scalar(2)) + epsilon));
const Scalar _tmp28 = cd * rho;
const Scalar _tmp29 = Scalar(0.5) * _tmp27 * _tmp28;
const Scalar _tmp30 = _tmp29 * _tmp4;
const Scalar _tmp31 = 2 * _tmp15;
const Scalar _tmp32 = _tmp31 * _tmp8;
const Scalar _tmp33 = 2 * _tmp23;
const Scalar _tmp34 = _tmp20 * _tmp33;
const Scalar _tmp35 = 2 * _tmp26;
const Scalar _tmp36 = _tmp35 * _tmp4;
const Scalar _tmp37 = Scalar(0.25) * _tmp26 * _tmp28 / _tmp27;
const Scalar _tmp38 = _tmp30 - _tmp37 * (-_tmp32 - _tmp34 - _tmp36) + _tmp5;
const Scalar _tmp39 = -_tmp30 - _tmp37 * (_tmp32 + _tmp34 + _tmp36) - _tmp5;
const Scalar _tmp40 = _tmp24 * cm;
const Scalar _tmp41 = _tmp10 * _tmp31;
const Scalar _tmp42 = _tmp19 * _tmp33;
const Scalar _tmp43 = _tmp24 * _tmp35;
const Scalar _tmp44 = _tmp24 * _tmp29;
const Scalar _tmp45 = -_tmp37 * (_tmp41 + _tmp42 + _tmp43) - _tmp40 - _tmp44;
const Scalar _tmp46 = _tmp16 * _tmp9;
const Scalar _tmp47 = _tmp0 * _tmp11;
const Scalar _tmp48 = state(1, 0) * state(6, 0);
const Scalar _tmp49 = 2 * state(2, 0);
const Scalar _tmp50 = _tmp11 * _tmp49;
const Scalar _tmp51 = _tmp16 * state(6, 0);
const Scalar _tmp52 = 4 * _tmp11;
const Scalar _tmp53 = _tmp49 * _tmp9;
const Scalar _tmp54 = _tmp0 * state(6, 0);
const Scalar _tmp55 = -_tmp52 * state(1, 0) + _tmp53 + _tmp54;
const Scalar _tmp56 =
-_tmp36 * _tmp54 -
_tmp40 * (_tmp37 * (_tmp14 * (_tmp42 + _tmp47 + _tmp55 + _tmp6) + _tmp32) + _tmp39 * _tmp54) -
_tmp54 * cm;
const Scalar _tmp57 = _tmp29 * cm;
const Scalar _tmp58 = _tmp13 * _tmp37;
const Scalar _tmp59 = _tmp25 * _tmp38;
const Scalar _tmp60 = _tmp29 * _tmp39;
const Scalar _tmp61 = _tmp29 * _tmp36;
const Scalar _tmp62 = -_tmp40 * (-_tmp58 - _tmp59 - _tmp60) + _tmp57 + _tmp61;
const Scalar _tmp63 = _tmp21 + _tmp55;
const Scalar _tmp64 = _tmp40 * (_tmp37 * (_tmp14 * (_tmp2 + _tmp46) + _tmp9 * (_tmp16 + _tmp53) +
state(6, 0) * (_tmp52 + _tmp63)) +
_tmp38 * (_tmp19 + _tmp9 * (_tmp49 + _tmp63)));
const Scalar _tmp65 = -_tmp40 * (_tmp58 + _tmp59 + _tmp60) - _tmp57 - _tmp61;
const Scalar _tmp66 = _tmp31 * cm;
const Scalar _tmp67 = _tmp31 * _tmp36;
const Scalar _tmp68 = _tmp37 * _tmp8;
const Scalar _tmp69 = _tmp26 * _tmp38;
const Scalar _tmp70 = _tmp31 * _tmp39;
const Scalar _tmp71 = -_tmp40 * (_tmp68 + _tmp69 + _tmp70) - _tmp66 - _tmp67;
const Scalar _tmp72 = -_tmp40 * (-_tmp68 - _tmp69 - _tmp70) + _tmp66 + _tmp67;
-Scalar(1) / Scalar(2) * _tmp29 * _tmp55 -
Scalar(1) / Scalar(2) * _tmp37 *
(_tmp31 * (_tmp50 + _tmp51) + _tmp33 * (_tmp46 - _tmp47 - 4 * _tmp48) + _tmp35 * _tmp55) -
Scalar(1) / Scalar(2) * _tmp55 * cm;
const Scalar _tmp57 = 2 * _tmp48;
const Scalar _tmp58 = -_tmp46 + _tmp57;
const Scalar _tmp59 = _tmp11 * _tmp2;
const Scalar _tmp60 = _tmp11 * _tmp16;
const Scalar _tmp61 = state(2, 0) * state(6, 0);
const Scalar _tmp62 = 2 * _tmp61;
const Scalar _tmp63 =
-Scalar(1) / Scalar(2) * _tmp29 * _tmp58 -
Scalar(1) / Scalar(2) * _tmp37 *
(_tmp31 * (_tmp60 - _tmp62) + _tmp33 * (_tmp53 - _tmp59) + _tmp35 * _tmp58) -
Scalar(1) / Scalar(2) * _tmp58 * cm;
const Scalar _tmp64 = _tmp2 * _tmp9;
const Scalar _tmp65 = _tmp51 + _tmp64;
const Scalar _tmp66 = _tmp0 * _tmp9;
const Scalar _tmp67 = 4 * _tmp9;
const Scalar _tmp68 = -Scalar(1) / Scalar(2) * _tmp29 * _tmp65 -
Scalar(1) / Scalar(2) * _tmp37 *
(_tmp31 * (-_tmp54 + _tmp59 - _tmp67 * state(2, 0)) +
_tmp33 * (_tmp60 - 4 * _tmp61 + _tmp66) + _tmp35 * _tmp65) -
Scalar(1) / Scalar(2) * _tmp65 * cm;
const Scalar _tmp69 = -_tmp52 * state(3, 0) + _tmp62 - _tmp66;
const Scalar _tmp70 = -Scalar(1) / Scalar(2) * _tmp29 * _tmp69 -
Scalar(1) / Scalar(2) * _tmp37 *
(_tmp31 * (_tmp47 + _tmp57 - _tmp67 * state(3, 0)) +
_tmp33 * (_tmp50 + _tmp64) + _tmp35 * _tmp69) -
Scalar(1) / Scalar(2) * _tmp69 * cm;
const Scalar _tmp71 =
-_tmp56 * state(2, 0) - _tmp63 * state(3, 0) + _tmp68 * state(1, 0) + _tmp70 * state(0, 0);
const Scalar _tmp72 =
_tmp56 * state(3, 0) - _tmp63 * state(2, 0) + _tmp68 * state(0, 0) - _tmp70 * state(1, 0);
const Scalar _tmp73 =
_tmp56 * state(0, 0) - _tmp63 * state(1, 0) - _tmp68 * state(3, 0) + _tmp70 * state(2, 0);
const Scalar _tmp74 = -_tmp37 * (-_tmp41 - _tmp42 - _tmp43) + _tmp40 + _tmp44;
const Scalar _tmp75 = -_tmp25 * _tmp29 - _tmp25 * cm -
_tmp37 * (_tmp14 * _tmp31 + _tmp22 * _tmp33 + _tmp25 * _tmp35);
// Output terms (2)
if (innov_var != nullptr) {
@ -132,22 +143,22 @@ void ComputeDragYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_innov_var =
R +
_tmp41 * (P(0, 5) * _tmp51 - P(1, 5) * _tmp64 + P(2, 5) * _tmp56 + P(21, 5) * _tmp72 +
P(22, 5) * _tmp62 + P(3, 5) * _tmp71 + P(4, 5) * _tmp65 + P(5, 5) * _tmp41) +
_tmp51 * (P(0, 0) * _tmp51 - P(1, 0) * _tmp64 + P(2, 0) * _tmp56 + P(21, 0) * _tmp72 +
P(22, 0) * _tmp62 + P(3, 0) * _tmp71 + P(4, 0) * _tmp65 + P(5, 0) * _tmp41) +
_tmp56 * (P(0, 2) * _tmp51 - P(1, 2) * _tmp64 + P(2, 2) * _tmp56 + P(21, 2) * _tmp72 +
P(22, 2) * _tmp62 + P(3, 2) * _tmp71 + P(4, 2) * _tmp65 + P(5, 2) * _tmp41) +
_tmp62 * (P(0, 22) * _tmp51 - P(1, 22) * _tmp64 + P(2, 22) * _tmp56 + P(21, 22) * _tmp72 +
P(22, 22) * _tmp62 + P(3, 22) * _tmp71 + P(4, 22) * _tmp65 + P(5, 22) * _tmp41) -
_tmp64 * (P(0, 1) * _tmp51 - P(1, 1) * _tmp64 + P(2, 1) * _tmp56 + P(21, 1) * _tmp72 +
P(22, 1) * _tmp62 + P(3, 1) * _tmp71 + P(4, 1) * _tmp65 + P(5, 1) * _tmp41) +
_tmp65 * (P(0, 4) * _tmp51 - P(1, 4) * _tmp64 + P(2, 4) * _tmp56 + P(21, 4) * _tmp72 +
P(22, 4) * _tmp62 + P(3, 4) * _tmp71 + P(4, 4) * _tmp65 + P(5, 4) * _tmp41) +
_tmp71 * (P(0, 3) * _tmp51 - P(1, 3) * _tmp64 + P(2, 3) * _tmp56 + P(21, 3) * _tmp72 +
P(22, 3) * _tmp62 + P(3, 3) * _tmp71 + P(4, 3) * _tmp65 + P(5, 3) * _tmp41) +
_tmp72 * (P(0, 21) * _tmp51 - P(1, 21) * _tmp64 + P(2, 21) * _tmp56 + P(21, 21) * _tmp72 +
P(22, 21) * _tmp62 + P(3, 21) * _tmp71 + P(4, 21) * _tmp65 + P(5, 21) * _tmp41);
_tmp38 * (P(0, 21) * _tmp73 + P(1, 21) * _tmp72 + P(2, 21) * _tmp71 + P(21, 21) * _tmp38 +
P(22, 21) * _tmp74 + P(3, 21) * _tmp39 + P(4, 21) * _tmp45 + P(5, 21) * _tmp75) +
_tmp39 * (P(0, 3) * _tmp73 + P(1, 3) * _tmp72 + P(2, 3) * _tmp71 + P(21, 3) * _tmp38 +
P(22, 3) * _tmp74 + P(3, 3) * _tmp39 + P(4, 3) * _tmp45 + P(5, 3) * _tmp75) +
_tmp45 * (P(0, 4) * _tmp73 + P(1, 4) * _tmp72 + P(2, 4) * _tmp71 + P(21, 4) * _tmp38 +
P(22, 4) * _tmp74 + P(3, 4) * _tmp39 + P(4, 4) * _tmp45 + P(5, 4) * _tmp75) +
_tmp71 * (P(0, 2) * _tmp73 + P(1, 2) * _tmp72 + P(2, 2) * _tmp71 + P(21, 2) * _tmp38 +
P(22, 2) * _tmp74 + P(3, 2) * _tmp39 + P(4, 2) * _tmp45 + P(5, 2) * _tmp75) +
_tmp72 * (P(0, 1) * _tmp73 + P(1, 1) * _tmp72 + P(2, 1) * _tmp71 + P(21, 1) * _tmp38 +
P(22, 1) * _tmp74 + P(3, 1) * _tmp39 + P(4, 1) * _tmp45 + P(5, 1) * _tmp75) +
_tmp73 * (P(0, 0) * _tmp73 + P(1, 0) * _tmp72 + P(2, 0) * _tmp71 + P(21, 0) * _tmp38 +
P(22, 0) * _tmp74 + P(3, 0) * _tmp39 + P(4, 0) * _tmp45 + P(5, 0) * _tmp75) +
_tmp74 * (P(0, 22) * _tmp73 + P(1, 22) * _tmp72 + P(2, 22) * _tmp71 + P(21, 22) * _tmp38 +
P(22, 22) * _tmp74 + P(3, 22) * _tmp39 + P(4, 22) * _tmp45 + P(5, 22) * _tmp75) +
_tmp75 * (P(0, 5) * _tmp73 + P(1, 5) * _tmp72 + P(2, 5) * _tmp71 + P(21, 5) * _tmp38 +
P(22, 5) * _tmp74 + P(3, 5) * _tmp39 + P(4, 5) * _tmp45 + P(5, 5) * _tmp75);
}
if (Hy != nullptr) {
@ -155,14 +166,14 @@ void ComputeDragYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_hy.setZero();
_hy(0, 0) = _tmp51;
_hy(1, 0) = -_tmp64;
_hy(2, 0) = _tmp56;
_hy(3, 0) = _tmp71;
_hy(4, 0) = _tmp65;
_hy(5, 0) = _tmp41;
_hy(21, 0) = _tmp72;
_hy(22, 0) = _tmp62;
_hy(0, 0) = _tmp73;
_hy(1, 0) = _tmp72;
_hy(2, 0) = _tmp71;
_hy(3, 0) = _tmp39;
_hy(4, 0) = _tmp45;
_hy(5, 0) = _tmp75;
_hy(21, 0) = _tmp38;
_hy(22, 0) = _tmp74;
}
} // NOLINT(readability/fn_size)

View File

@ -32,77 +32,88 @@ void ComputeFlowXyInnovVarAndHx(const matrix::Matrix<Scalar, 24, 1>& state,
const Scalar R, const Scalar epsilon,
matrix::Matrix<Scalar, 2, 1>* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 196
// Total ops: 275
// Input arrays
// Intermediate terms (33)
const Scalar _tmp0 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp2 = 1 - 2 * _tmp1;
const Scalar _tmp3 =
// Intermediate terms (42)
const Scalar _tmp0 = 2 * state(4, 0);
const Scalar _tmp1 = 2 * state(1, 0);
const Scalar _tmp2 = _tmp1 * state(6, 0);
const Scalar _tmp3 = -_tmp0 * state(3, 0) + _tmp2;
const Scalar _tmp4 =
Scalar(1.0) /
(distance + epsilon * (2 * math::min<Scalar>(0, (((distance) > 0) - ((distance) < 0))) + 1));
const Scalar _tmp4 = _tmp3 * (-2 * _tmp0 + _tmp2);
const Scalar _tmp5 = 2 * state(2, 0);
const Scalar _tmp6 = _tmp5 * state(0, 0);
const Scalar _tmp7 = 2 * state(1, 0) * state(3, 0);
const Scalar _tmp8 = _tmp5 * state(3, 0);
const Scalar _tmp5 = (Scalar(1) / Scalar(2)) * _tmp4;
const Scalar _tmp6 = _tmp5 * state(2, 0);
const Scalar _tmp7 = 2 * state(3, 0) * state(6, 0);
const Scalar _tmp8 = _tmp5 * (_tmp0 * state(1, 0) + _tmp7);
const Scalar _tmp9 = 2 * state(0, 0);
const Scalar _tmp10 = _tmp9 * state(1, 0);
const Scalar _tmp11 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp12 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp13 = -_tmp0;
const Scalar _tmp14 = _tmp12 + _tmp13;
const Scalar _tmp15 = _tmp3 * (state(4, 0) * (_tmp6 + _tmp7) + state(5, 0) * (-_tmp10 + _tmp8) +
state(6, 0) * (_tmp1 - _tmp11 + _tmp14));
const Scalar _tmp16 = _tmp9 * state(3, 0);
const Scalar _tmp17 = -_tmp16;
const Scalar _tmp18 = _tmp5 * state(1, 0);
const Scalar _tmp19 = _tmp17 + _tmp18;
const Scalar _tmp20 = _tmp19 * _tmp3;
const Scalar _tmp21 = _tmp10 + _tmp8;
const Scalar _tmp22 = _tmp21 * _tmp3;
const Scalar _tmp23 = -_tmp7;
const Scalar _tmp24 = -_tmp12;
const Scalar _tmp25 = _tmp3 * (state(4, 0) * (_tmp1 + _tmp11 + _tmp13 + _tmp24) +
state(5, 0) * (_tmp17 - _tmp18) + state(6, 0) * (_tmp23 + _tmp6));
const Scalar _tmp26 = _tmp3 * (-2 * _tmp11 + _tmp2);
const Scalar _tmp27 = -_tmp6;
const Scalar _tmp28 = -_tmp1 + _tmp11;
const Scalar _tmp29 = _tmp3 * (state(4, 0) * (_tmp23 + _tmp27) + state(5, 0) * (_tmp10 - _tmp8) +
state(6, 0) * (_tmp0 + _tmp24 + _tmp28));
const Scalar _tmp30 =
_tmp3 * (_tmp19 * state(4, 0) + _tmp21 * state(6, 0) + state(5, 0) * (_tmp14 + _tmp28));
const Scalar _tmp31 = _tmp3 * (_tmp16 + _tmp18);
const Scalar _tmp32 = _tmp3 * (_tmp27 + _tmp7);
const Scalar _tmp10 = state(3, 0) * state(5, 0);
const Scalar _tmp11 = 2 * state(2, 0);
const Scalar _tmp12 = _tmp11 * state(6, 0);
const Scalar _tmp13 = -4 * _tmp10 + _tmp12 - _tmp9 * state(4, 0);
const Scalar _tmp14 = _tmp5 * state(1, 0);
const Scalar _tmp15 = _tmp9 * state(6, 0);
const Scalar _tmp16 = _tmp0 * state(2, 0) + _tmp15 - 4 * state(1, 0) * state(5, 0);
const Scalar _tmp17 = _tmp5 * state(3, 0);
const Scalar _tmp18 = -_tmp13 * _tmp14 + _tmp16 * _tmp17 - _tmp3 * _tmp6 + _tmp8 * state(0, 0);
const Scalar _tmp19 = 1 - 2 * std::pow(state(3, 0), Scalar(2));
const Scalar _tmp20 = _tmp4 * (_tmp19 - 2 * std::pow(state(1, 0), Scalar(2)));
const Scalar _tmp21 = _tmp3 * _tmp5;
const Scalar _tmp22 = _tmp5 * state(0, 0);
const Scalar _tmp23 =
_tmp13 * _tmp6 + _tmp16 * _tmp22 - _tmp21 * state(1, 0) - _tmp8 * state(3, 0);
const Scalar _tmp24 =
_tmp13 * _tmp22 - _tmp16 * _tmp6 - _tmp21 * state(3, 0) + _tmp8 * state(1, 0);
const Scalar _tmp25 = _tmp9 * state(3, 0);
const Scalar _tmp26 = _tmp1 * state(2, 0);
const Scalar _tmp27 = _tmp4 * (-_tmp25 + _tmp26);
const Scalar _tmp28 = _tmp4 * (_tmp11 * state(3, 0) + _tmp9 * state(1, 0));
const Scalar _tmp29 = _tmp4 * (_tmp19 - 2 * std::pow(state(2, 0), Scalar(2)));
const Scalar _tmp30 = 4 * state(4, 0);
const Scalar _tmp31 = _tmp2 - _tmp30 * state(3, 0) + _tmp9 * state(5, 0);
const Scalar _tmp32 = 2 * state(5, 0);
const Scalar _tmp33 = -_tmp15 - _tmp30 * state(2, 0) + _tmp32 * state(1, 0);
const Scalar _tmp34 = _tmp32 * state(2, 0) + _tmp7;
const Scalar _tmp35 = 2 * _tmp10 - _tmp12;
const Scalar _tmp36 = _tmp35 * _tmp5;
const Scalar _tmp37 = _tmp17 * _tmp33 - _tmp22 * _tmp34 - _tmp31 * _tmp6 + _tmp36 * state(1, 0);
const Scalar _tmp38 = -_tmp14 * _tmp33 - _tmp22 * _tmp31 + _tmp34 * _tmp6 + _tmp36 * state(3, 0);
const Scalar _tmp39 = _tmp14 * _tmp31 - _tmp17 * _tmp34 - _tmp22 * _tmp33 + _tmp35 * _tmp6;
const Scalar _tmp40 = _tmp4 * (_tmp25 + _tmp26);
const Scalar _tmp41 = _tmp4 * (_tmp1 * state(3, 0) - _tmp9 * state(2, 0));
// Output terms (2)
if (innov_var != nullptr) {
matrix::Matrix<Scalar, 2, 1>& _innov_var = (*innov_var);
_innov_var(0, 0) = R +
_tmp15 * (P(0, 0) * _tmp15 + P(2, 0) * _tmp25 + P(3, 0) * _tmp20 +
P(4, 0) * _tmp4 + P(5, 0) * _tmp22) +
_tmp20 * (P(0, 3) * _tmp15 + P(2, 3) * _tmp25 + P(3, 3) * _tmp20 +
P(4, 3) * _tmp4 + P(5, 3) * _tmp22) +
_tmp22 * (P(0, 5) * _tmp15 + P(2, 5) * _tmp25 + P(3, 5) * _tmp20 +
P(4, 5) * _tmp4 + P(5, 5) * _tmp22) +
_tmp25 * (P(0, 2) * _tmp15 + P(2, 2) * _tmp25 + P(3, 2) * _tmp20 +
P(4, 2) * _tmp4 + P(5, 2) * _tmp22) +
_tmp4 * (P(0, 4) * _tmp15 + P(2, 4) * _tmp25 + P(3, 4) * _tmp20 +
P(4, 4) * _tmp4 + P(5, 4) * _tmp22);
_tmp18 * (P(0, 1) * _tmp23 + P(1, 1) * _tmp18 + P(2, 1) * _tmp24 +
P(3, 1) * _tmp27 + P(4, 1) * _tmp20 + P(5, 1) * _tmp28) +
_tmp20 * (P(0, 4) * _tmp23 + P(1, 4) * _tmp18 + P(2, 4) * _tmp24 +
P(3, 4) * _tmp27 + P(4, 4) * _tmp20 + P(5, 4) * _tmp28) +
_tmp23 * (P(0, 0) * _tmp23 + P(1, 0) * _tmp18 + P(2, 0) * _tmp24 +
P(3, 0) * _tmp27 + P(4, 0) * _tmp20 + P(5, 0) * _tmp28) +
_tmp24 * (P(0, 2) * _tmp23 + P(1, 2) * _tmp18 + P(2, 2) * _tmp24 +
P(3, 2) * _tmp27 + P(4, 2) * _tmp20 + P(5, 2) * _tmp28) +
_tmp27 * (P(0, 3) * _tmp23 + P(1, 3) * _tmp18 + P(2, 3) * _tmp24 +
P(3, 3) * _tmp27 + P(4, 3) * _tmp20 + P(5, 3) * _tmp28) +
_tmp28 * (P(0, 5) * _tmp23 + P(1, 5) * _tmp18 + P(2, 5) * _tmp24 +
P(3, 5) * _tmp27 + P(4, 5) * _tmp20 + P(5, 5) * _tmp28);
_innov_var(1, 0) = R -
_tmp26 * (-P(1, 3) * _tmp29 - P(2, 3) * _tmp30 - P(3, 3) * _tmp26 -
P(4, 3) * _tmp31 - P(5, 3) * _tmp32) -
_tmp29 * (-P(1, 1) * _tmp29 - P(2, 1) * _tmp30 - P(3, 1) * _tmp26 -
P(4, 1) * _tmp31 - P(5, 1) * _tmp32) -
_tmp30 * (-P(1, 2) * _tmp29 - P(2, 2) * _tmp30 - P(3, 2) * _tmp26 -
P(4, 2) * _tmp31 - P(5, 2) * _tmp32) -
_tmp31 * (-P(1, 4) * _tmp29 - P(2, 4) * _tmp30 - P(3, 4) * _tmp26 -
P(4, 4) * _tmp31 - P(5, 4) * _tmp32) -
_tmp32 * (-P(1, 5) * _tmp29 - P(2, 5) * _tmp30 - P(3, 5) * _tmp26 -
P(4, 5) * _tmp31 - P(5, 5) * _tmp32);
_tmp29 * (P(0, 3) * _tmp37 + P(1, 3) * _tmp39 + P(2, 3) * _tmp38 -
P(3, 3) * _tmp29 - P(4, 3) * _tmp40 - P(5, 3) * _tmp41) +
_tmp37 * (P(0, 0) * _tmp37 + P(1, 0) * _tmp39 + P(2, 0) * _tmp38 -
P(3, 0) * _tmp29 - P(4, 0) * _tmp40 - P(5, 0) * _tmp41) +
_tmp38 * (P(0, 2) * _tmp37 + P(1, 2) * _tmp39 + P(2, 2) * _tmp38 -
P(3, 2) * _tmp29 - P(4, 2) * _tmp40 - P(5, 2) * _tmp41) +
_tmp39 * (P(0, 1) * _tmp37 + P(1, 1) * _tmp39 + P(2, 1) * _tmp38 -
P(3, 1) * _tmp29 - P(4, 1) * _tmp40 - P(5, 1) * _tmp41) -
_tmp40 * (P(0, 4) * _tmp37 + P(1, 4) * _tmp39 + P(2, 4) * _tmp38 -
P(3, 4) * _tmp29 - P(4, 4) * _tmp40 - P(5, 4) * _tmp41) -
_tmp41 * (P(0, 5) * _tmp37 + P(1, 5) * _tmp39 + P(2, 5) * _tmp38 -
P(3, 5) * _tmp29 - P(4, 5) * _tmp40 - P(5, 5) * _tmp41);
}
if (H != nullptr) {
@ -110,11 +121,12 @@ void ComputeFlowXyInnovVarAndHx(const matrix::Matrix<Scalar, 24, 1>& state,
_h.setZero();
_h(0, 0) = _tmp15;
_h(2, 0) = _tmp25;
_h(3, 0) = _tmp20;
_h(4, 0) = _tmp4;
_h(5, 0) = _tmp22;
_h(0, 0) = _tmp23;
_h(1, 0) = _tmp18;
_h(2, 0) = _tmp24;
_h(3, 0) = _tmp27;
_h(4, 0) = _tmp20;
_h(5, 0) = _tmp28;
}
} // NOLINT(readability/fn_size)

View File

@ -32,51 +32,56 @@ void ComputeFlowYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const Scalar R, const Scalar epsilon,
Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 116
// Total ops: 151
// Input arrays
// Intermediate terms (19)
const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp1 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp2 =
// Intermediate terms (21)
const Scalar _tmp0 =
Scalar(1.0) /
(distance + epsilon * (2 * math::min<Scalar>(0, (((distance) > 0) - ((distance) < 0))) + 1));
const Scalar _tmp3 = _tmp2 * (-2 * _tmp0 - 2 * _tmp1 + 1);
const Scalar _tmp4 = -2 * state(0, 0) * state(2, 0);
const Scalar _tmp5 = 2 * state(3, 0);
const Scalar _tmp6 = _tmp5 * state(1, 0);
const Scalar _tmp7 = _tmp5 * state(2, 0);
const Scalar _tmp1 =
_tmp0 * (-2 * std::pow(state(2, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1);
const Scalar _tmp2 = 4 * state(4, 0);
const Scalar _tmp3 = 2 * state(0, 0);
const Scalar _tmp4 = 2 * state(6, 0);
const Scalar _tmp5 = -_tmp2 * state(3, 0) + _tmp3 * state(5, 0) + _tmp4 * state(1, 0);
const Scalar _tmp6 = (Scalar(1) / Scalar(2)) * _tmp0;
const Scalar _tmp7 = _tmp5 * _tmp6;
const Scalar _tmp8 = 2 * state(1, 0);
const Scalar _tmp9 = _tmp8 * state(0, 0);
const Scalar _tmp10 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp11 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp12 = -_tmp0 + _tmp1;
const Scalar _tmp13 = _tmp2 * (state(4, 0) * (_tmp4 - _tmp6) + state(5, 0) * (-_tmp7 + _tmp9) +
state(6, 0) * (-_tmp10 + _tmp11 + _tmp12));
const Scalar _tmp14 = _tmp5 * state(0, 0);
const Scalar _tmp15 = _tmp8 * state(2, 0);
const Scalar _tmp16 =
_tmp2 * (state(4, 0) * (-_tmp14 + _tmp15) + state(5, 0) * (_tmp10 - _tmp11 + _tmp12) +
state(6, 0) * (_tmp7 + _tmp9));
const Scalar _tmp17 = _tmp2 * (_tmp14 + _tmp15);
const Scalar _tmp18 = _tmp2 * (_tmp4 + _tmp6);
const Scalar _tmp9 = -_tmp2 * state(2, 0) - _tmp4 * state(0, 0) + _tmp8 * state(5, 0);
const Scalar _tmp10 = _tmp6 * _tmp9;
const Scalar _tmp11 = 2 * state(5, 0);
const Scalar _tmp12 = _tmp6 * (_tmp11 * state(2, 0) + _tmp4 * state(3, 0));
const Scalar _tmp13 = _tmp11 * state(3, 0) - _tmp4 * state(2, 0);
const Scalar _tmp14 = _tmp6 * state(1, 0);
const Scalar _tmp15 =
_tmp10 * state(3, 0) - _tmp12 * state(0, 0) + _tmp13 * _tmp14 - _tmp7 * state(2, 0);
const Scalar _tmp16 = _tmp13 * _tmp6;
const Scalar _tmp17 =
_tmp12 * state(2, 0) - _tmp14 * _tmp9 + _tmp16 * state(3, 0) - _tmp7 * state(0, 0);
const Scalar _tmp18 =
-_tmp10 * state(0, 0) - _tmp12 * state(3, 0) + _tmp14 * _tmp5 + _tmp16 * state(2, 0);
const Scalar _tmp19 = _tmp0 * (_tmp3 * state(3, 0) + _tmp8 * state(2, 0));
const Scalar _tmp20 = _tmp0 * (-_tmp3 * state(2, 0) + _tmp8 * state(3, 0));
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = R -
_tmp13 * (-P(1, 1) * _tmp13 - P(2, 1) * _tmp16 - P(3, 1) * _tmp3 -
P(4, 1) * _tmp17 - P(5, 1) * _tmp18) -
_tmp16 * (-P(1, 2) * _tmp13 - P(2, 2) * _tmp16 - P(3, 2) * _tmp3 -
P(4, 2) * _tmp17 - P(5, 2) * _tmp18) -
_tmp17 * (-P(1, 4) * _tmp13 - P(2, 4) * _tmp16 - P(3, 4) * _tmp3 -
P(4, 4) * _tmp17 - P(5, 4) * _tmp18) -
_tmp18 * (-P(1, 5) * _tmp13 - P(2, 5) * _tmp16 - P(3, 5) * _tmp3 -
P(4, 5) * _tmp17 - P(5, 5) * _tmp18) -
_tmp3 * (-P(1, 3) * _tmp13 - P(2, 3) * _tmp16 - P(3, 3) * _tmp3 -
P(4, 3) * _tmp17 - P(5, 3) * _tmp18);
_tmp1 * (P(0, 3) * _tmp15 + P(1, 3) * _tmp18 + P(2, 3) * _tmp17 - P(3, 3) * _tmp1 -
P(4, 3) * _tmp19 - P(5, 3) * _tmp20) +
_tmp15 * (P(0, 0) * _tmp15 + P(1, 0) * _tmp18 + P(2, 0) * _tmp17 -
P(3, 0) * _tmp1 - P(4, 0) * _tmp19 - P(5, 0) * _tmp20) +
_tmp17 * (P(0, 2) * _tmp15 + P(1, 2) * _tmp18 + P(2, 2) * _tmp17 -
P(3, 2) * _tmp1 - P(4, 2) * _tmp19 - P(5, 2) * _tmp20) +
_tmp18 * (P(0, 1) * _tmp15 + P(1, 1) * _tmp18 + P(2, 1) * _tmp17 -
P(3, 1) * _tmp1 - P(4, 1) * _tmp19 - P(5, 1) * _tmp20) -
_tmp19 * (P(0, 4) * _tmp15 + P(1, 4) * _tmp18 + P(2, 4) * _tmp17 -
P(3, 4) * _tmp1 - P(4, 4) * _tmp19 - P(5, 4) * _tmp20) -
_tmp20 * (P(0, 5) * _tmp15 + P(1, 5) * _tmp18 + P(2, 5) * _tmp17 -
P(3, 5) * _tmp1 - P(4, 5) * _tmp19 - P(5, 5) * _tmp20);
}
if (H != nullptr) {
@ -84,11 +89,12 @@ void ComputeFlowYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_h.setZero();
_h(1, 0) = -_tmp13;
_h(2, 0) = -_tmp16;
_h(3, 0) = -_tmp3;
_h(4, 0) = -_tmp17;
_h(5, 0) = -_tmp18;
_h(0, 0) = _tmp15;
_h(1, 0) = _tmp18;
_h(2, 0) = _tmp17;
_h(3, 0) = -_tmp1;
_h(4, 0) = -_tmp19;
_h(5, 0) = -_tmp20;
}
} // NOLINT(readability/fn_size)

View File

@ -34,57 +34,62 @@ void ComputeGnssYawPredInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const Scalar epsilon, Scalar* const meas_pred = nullptr,
Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 95
// Total ops: 114
// Input arrays
// Intermediate terms (28)
const Scalar _tmp0 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp2 = 1 - 2 * _tmp1;
const Scalar _tmp3 = std::sin(antenna_yaw_offset);
const Scalar _tmp4 = 2 * state(0, 0);
const Scalar _tmp5 = _tmp4 * state(3, 0);
const Scalar _tmp6 = 2 * state(2, 0);
const Scalar _tmp7 = _tmp6 * state(1, 0);
const Scalar _tmp8 = std::cos(antenna_yaw_offset);
const Scalar _tmp9 = _tmp3 * (-2 * _tmp0 + _tmp2) + _tmp8 * (_tmp5 + _tmp7);
const Scalar _tmp10 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp11 = -_tmp5;
const Scalar _tmp12 = _tmp11 + _tmp7;
const Scalar _tmp13 = _tmp12 * _tmp3 + _tmp8 * (-2 * _tmp10 + _tmp2);
const Scalar _tmp14 = _tmp13 + epsilon * ((((_tmp13) > 0) - ((_tmp13) < 0)) + Scalar(0.5));
const Scalar _tmp15 = _tmp6 * state(0, 0);
const Scalar _tmp16 = 2 * state(1, 0) * state(3, 0);
const Scalar _tmp17 = std::pow(_tmp14, Scalar(2));
const Scalar _tmp18 = _tmp9 / _tmp17;
const Scalar _tmp19 = _tmp6 * state(3, 0);
const Scalar _tmp20 = _tmp4 * state(1, 0);
const Scalar _tmp21 = Scalar(1.0) / (_tmp14);
const Scalar _tmp22 = _tmp17 / (_tmp17 + std::pow(_tmp9, Scalar(2)));
const Scalar _tmp23 =
_tmp22 * (-_tmp18 * _tmp8 * (-_tmp15 - _tmp16) + _tmp21 * _tmp8 * (-_tmp19 + _tmp20));
const Scalar _tmp24 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp25 = -_tmp0 + _tmp10;
const Scalar _tmp26 =
_tmp22 * (-_tmp18 * (_tmp12 * _tmp8 + _tmp3 * (_tmp1 - _tmp24 + _tmp25)) +
_tmp21 * (_tmp3 * (_tmp11 - _tmp7) + _tmp8 * (-_tmp1 + _tmp24 + _tmp25)));
// Intermediate terms (29)
const Scalar _tmp0 = 1 - 2 * std::pow(state(3, 0), Scalar(2));
const Scalar _tmp1 = std::sin(antenna_yaw_offset);
const Scalar _tmp2 = 2 * state(0, 0) * state(3, 0);
const Scalar _tmp3 = 2 * state(1, 0) * state(2, 0);
const Scalar _tmp4 = std::cos(antenna_yaw_offset);
const Scalar _tmp5 =
_tmp1 * (_tmp0 - 2 * std::pow(state(1, 0), Scalar(2))) + _tmp4 * (_tmp2 + _tmp3);
const Scalar _tmp6 =
_tmp1 * (-_tmp2 + _tmp3) + _tmp4 * (_tmp0 - 2 * std::pow(state(2, 0), Scalar(2)));
const Scalar _tmp7 = _tmp6 + epsilon * ((((_tmp6) > 0) - ((_tmp6) < 0)) + Scalar(0.5));
const Scalar _tmp8 = 2 * _tmp1;
const Scalar _tmp9 = std::pow(_tmp7, Scalar(2));
const Scalar _tmp10 = _tmp5 / _tmp9;
const Scalar _tmp11 = _tmp10 * _tmp8;
const Scalar _tmp12 = 4 * _tmp1;
const Scalar _tmp13 = 2 * _tmp4;
const Scalar _tmp14 = Scalar(1.0) / (_tmp7);
const Scalar _tmp15 =
-_tmp11 * state(2, 0) + _tmp14 * (-_tmp12 * state(1, 0) + _tmp13 * state(2, 0));
const Scalar _tmp16 = (Scalar(1) / Scalar(2)) * _tmp9 / (std::pow(_tmp5, Scalar(2)) + _tmp9);
const Scalar _tmp17 = _tmp15 * _tmp16;
const Scalar _tmp18 = _tmp13 * _tmp14;
const Scalar _tmp19 = _tmp11 * state(3, 0) + _tmp18 * state(3, 0);
const Scalar _tmp20 = _tmp16 * _tmp19;
const Scalar _tmp21 = 4 * _tmp4;
const Scalar _tmp22 = -_tmp10 * (-_tmp21 * state(3, 0) - _tmp8 * state(0, 0)) +
_tmp14 * (-_tmp12 * state(3, 0) + _tmp13 * state(0, 0));
const Scalar _tmp23 = _tmp16 * state(2, 0);
const Scalar _tmp24 =
_tmp16 * (-_tmp10 * (-_tmp21 * state(2, 0) + _tmp8 * state(1, 0)) + _tmp18 * state(1, 0));
const Scalar _tmp25 =
_tmp17 * state(0, 0) - _tmp20 * state(1, 0) + _tmp22 * _tmp23 - _tmp24 * state(3, 0);
const Scalar _tmp26 = _tmp16 * _tmp22;
const Scalar _tmp27 =
_tmp22 * (-_tmp18 * _tmp3 * (_tmp15 + _tmp16) + _tmp21 * _tmp3 * (_tmp19 - _tmp20));
_tmp17 * state(3, 0) - _tmp19 * _tmp23 + _tmp24 * state(0, 0) - _tmp26 * state(1, 0);
const Scalar _tmp28 =
-_tmp15 * _tmp23 - _tmp20 * state(3, 0) + _tmp24 * state(1, 0) + _tmp26 * state(0, 0);
// Output terms (3)
if (meas_pred != nullptr) {
Scalar& _meas_pred = (*meas_pred);
_meas_pred = std::atan2(_tmp9, _tmp14);
_meas_pred = std::atan2(_tmp5, _tmp7);
}
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = R + _tmp23 * (P(0, 1) * _tmp27 + P(1, 1) * _tmp23 + P(2, 1) * _tmp26) +
_tmp26 * (P(0, 2) * _tmp27 + P(1, 2) * _tmp23 + P(2, 2) * _tmp26) +
_tmp27 * (P(0, 0) * _tmp27 + P(1, 0) * _tmp23 + P(2, 0) * _tmp26);
_innov_var = R + _tmp25 * (P(0, 0) * _tmp25 + P(1, 0) * _tmp27 + P(2, 0) * _tmp28) +
_tmp27 * (P(0, 1) * _tmp25 + P(1, 1) * _tmp27 + P(2, 1) * _tmp28) +
_tmp28 * (P(0, 2) * _tmp25 + P(1, 2) * _tmp27 + P(2, 2) * _tmp28);
}
if (H != nullptr) {
@ -92,9 +97,9 @@ void ComputeGnssYawPredInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_h.setZero();
_h(0, 0) = _tmp27;
_h(1, 0) = _tmp23;
_h(2, 0) = _tmp26;
_h(0, 0) = _tmp25;
_h(1, 0) = _tmp27;
_h(2, 0) = _tmp28;
}
} // NOLINT(readability/fn_size)

View File

@ -29,38 +29,35 @@ void ComputeGravityXyzInnovVarAndHx(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
matrix::Matrix<Scalar, 3, 1>* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const Hx = nullptr) {
// Total ops: 51
// Total ops: 53
// Input arrays
// Intermediate terms (16)
const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp1 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp2 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp3 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp4 = _tmp0 + _tmp1 - _tmp2 - _tmp3;
const Scalar _tmp5 = 2 * state(2, 0);
const Scalar _tmp6 = _tmp5 * state(3, 0);
const Scalar _tmp7 = 2 * state(1, 0);
const Scalar _tmp8 = _tmp7 * state(0, 0);
const Scalar _tmp9 = -_tmp6 - _tmp8;
const Scalar _tmp10 = -_tmp0 - _tmp1 + _tmp2 + _tmp3;
const Scalar _tmp11 = _tmp5 * state(0, 0);
const Scalar _tmp12 = _tmp7 * state(3, 0);
const Scalar _tmp13 = -_tmp11 + _tmp12;
const Scalar _tmp14 = _tmp6 + _tmp8;
const Scalar _tmp15 = _tmp11 - _tmp12;
// Intermediate terms (13)
const Scalar _tmp0 = 2 * state(0, 0);
const Scalar _tmp1 = -_tmp0 * state(3, 0);
const Scalar _tmp2 = 2 * state(2, 0);
const Scalar _tmp3 = _tmp2 * state(1, 0);
const Scalar _tmp4 = _tmp1 - _tmp3;
const Scalar _tmp5 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp6 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp7 = std::pow(state(1, 0), Scalar(2)) - std::pow(state(2, 0), Scalar(2));
const Scalar _tmp8 = -_tmp5 + _tmp6 + _tmp7;
const Scalar _tmp9 = _tmp1 + _tmp3;
const Scalar _tmp10 = _tmp5 - _tmp6 + _tmp7;
const Scalar _tmp11 = _tmp0 * state(1, 0) - _tmp2 * state(3, 0);
const Scalar _tmp12 = _tmp2 * state(0, 0) + 2 * state(1, 0) * state(3, 0);
// Output terms (2)
if (innov_var != nullptr) {
matrix::Matrix<Scalar, 3, 1>& _innov_var = (*innov_var);
_innov_var(0, 0) = R + _tmp4 * (P(1, 1) * _tmp4 + P(2, 1) * _tmp9) +
_tmp9 * (P(1, 2) * _tmp4 + P(2, 2) * _tmp9);
_innov_var(1, 0) = R + _tmp10 * (P(0, 0) * _tmp10 + P(2, 0) * _tmp13) +
_tmp13 * (P(0, 2) * _tmp10 + P(2, 2) * _tmp13);
_innov_var(2, 0) = R + _tmp14 * (P(0, 0) * _tmp14 + P(1, 0) * _tmp15) +
_tmp15 * (P(0, 1) * _tmp14 + P(1, 1) * _tmp15);
_innov_var(0, 0) = R + _tmp4 * (P(0, 0) * _tmp4 + P(1, 0) * _tmp8) +
_tmp8 * (P(0, 1) * _tmp4 + P(1, 1) * _tmp8);
_innov_var(1, 0) = R + _tmp10 * (P(0, 0) * _tmp10 + P(1, 0) * _tmp9) +
_tmp9 * (P(0, 1) * _tmp10 + P(1, 1) * _tmp9);
_innov_var(2, 0) = R + _tmp11 * (P(0, 0) * _tmp11 + P(1, 0) * _tmp12) +
_tmp12 * (P(0, 1) * _tmp11 + P(1, 1) * _tmp12);
}
if (Hx != nullptr) {
@ -68,8 +65,8 @@ void ComputeGravityXyzInnovVarAndHx(const matrix::Matrix<Scalar, 24, 1>& state,
_hx.setZero();
_hx(1, 0) = _tmp4;
_hx(2, 0) = _tmp9;
_hx(0, 0) = _tmp4;
_hx(1, 0) = _tmp8;
}
} // NOLINT(readability/fn_size)

View File

@ -34,16 +34,16 @@ void ComputeGravityYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
// Input arrays
// Intermediate terms (2)
const Scalar _tmp0 = -std::pow(state(0, 0), Scalar(2)) + std::pow(state(1, 0), Scalar(2)) +
std::pow(state(2, 0), Scalar(2)) - std::pow(state(3, 0), Scalar(2));
const Scalar _tmp1 = -2 * state(0, 0) * state(2, 0) + 2 * state(1, 0) * state(3, 0);
const Scalar _tmp0 = -2 * state(0, 0) * state(3, 0) + 2 * state(1, 0) * state(2, 0);
const Scalar _tmp1 = -std::pow(state(0, 0), Scalar(2)) + std::pow(state(1, 0), Scalar(2)) -
std::pow(state(2, 0), Scalar(2)) + std::pow(state(3, 0), Scalar(2));
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = R + _tmp0 * (P(0, 0) * _tmp0 + P(2, 0) * _tmp1) +
_tmp1 * (P(0, 2) * _tmp0 + P(2, 2) * _tmp1);
_innov_var = R + _tmp0 * (P(0, 1) * _tmp1 + P(1, 1) * _tmp0) +
_tmp1 * (P(0, 0) * _tmp1 + P(1, 0) * _tmp0);
}
if (Hy != nullptr) {
@ -51,8 +51,8 @@ void ComputeGravityYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_hy.setZero();
_hy(0, 0) = _tmp0;
_hy(2, 0) = _tmp1;
_hy(0, 0) = _tmp1;
_hy(1, 0) = _tmp0;
}
} // NOLINT(readability/fn_size)

View File

@ -36,8 +36,8 @@ void ComputeGravityZInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
// Intermediate terms (4)
const Scalar _tmp0 = 2 * state(2, 0);
const Scalar _tmp1 = 2 * state(1, 0);
const Scalar _tmp2 = _tmp0 * state(3, 0) + _tmp1 * state(0, 0);
const Scalar _tmp3 = _tmp0 * state(0, 0) - _tmp1 * state(3, 0);
const Scalar _tmp2 = -_tmp0 * state(3, 0) + _tmp1 * state(0, 0);
const Scalar _tmp3 = _tmp0 * state(0, 0) + _tmp1 * state(3, 0);
// Output terms (2)
if (innov_var != nullptr) {

View File

@ -35,114 +35,153 @@ void ComputeMagInnovInnovVarAndHx(const matrix::Matrix<Scalar, 24, 1>& state,
matrix::Matrix<Scalar, 3, 1>* const innov = nullptr,
matrix::Matrix<Scalar, 3, 1>* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const Hx = nullptr) {
// Total ops: 314
// Total ops: 461
// Unused inputs
(void)epsilon;
// Input arrays
// Intermediate terms (47)
const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp1 = -2 * _tmp0;
const Scalar _tmp2 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp3 = -2 * _tmp2;
const Scalar _tmp4 = _tmp1 + _tmp3 + 1;
const Scalar _tmp5 = 2 * state(0, 0);
const Scalar _tmp6 = _tmp5 * state(3, 0);
const Scalar _tmp7 = 2 * state(1, 0);
const Scalar _tmp8 = _tmp7 * state(2, 0);
const Scalar _tmp9 = _tmp6 + _tmp8;
const Scalar _tmp10 = _tmp5 * state(2, 0);
const Scalar _tmp11 = -_tmp10;
const Scalar _tmp12 = _tmp7 * state(3, 0);
const Scalar _tmp13 = _tmp11 + _tmp12;
const Scalar _tmp14 = _tmp13 * state(18, 0) + _tmp9 * state(17, 0);
const Scalar _tmp15 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp16 = 1 - 2 * _tmp15;
const Scalar _tmp17 = _tmp1 + _tmp16;
const Scalar _tmp18 = 2 * state(2, 0) * state(3, 0);
const Scalar _tmp19 = _tmp7 * state(0, 0);
const Scalar _tmp20 = _tmp18 + _tmp19;
const Scalar _tmp21 = -_tmp6;
const Scalar _tmp22 = _tmp21 + _tmp8;
const Scalar _tmp23 = _tmp20 * state(18, 0) + _tmp22 * state(16, 0);
const Scalar _tmp24 = _tmp16 + _tmp3;
const Scalar _tmp25 = -_tmp19;
const Scalar _tmp26 = _tmp18 + _tmp25;
const Scalar _tmp27 = _tmp10 + _tmp12;
const Scalar _tmp28 = _tmp26 * state(17, 0) + _tmp27 * state(16, 0);
const Scalar _tmp29 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp30 = -_tmp29;
const Scalar _tmp31 = _tmp2 + _tmp30;
const Scalar _tmp32 = -_tmp0;
const Scalar _tmp33 = _tmp15 + _tmp32;
const Scalar _tmp34 = -_tmp18;
const Scalar _tmp35 = -_tmp12;
const Scalar _tmp36 = state(16, 0) * (_tmp11 + _tmp35) + state(17, 0) * (_tmp19 + _tmp34) +
state(18, 0) * (_tmp31 + _tmp33);
const Scalar _tmp37 = -_tmp15;
const Scalar _tmp38 = _tmp23 + state(17, 0) * (_tmp2 + _tmp29 + _tmp32 + _tmp37);
const Scalar _tmp39 = _tmp0 + _tmp37;
const Scalar _tmp40 = -_tmp8;
const Scalar _tmp41 = state(16, 0) * (_tmp31 + _tmp39) + state(17, 0) * (_tmp21 + _tmp40) +
state(18, 0) * (_tmp10 + _tmp35);
const Scalar _tmp42 = -_tmp2;
const Scalar _tmp43 = _tmp29 + _tmp42;
const Scalar _tmp44 = _tmp28 + state(18, 0) * (_tmp39 + _tmp43);
const Scalar _tmp45 = _tmp14 + state(16, 0) * (_tmp33 + _tmp43);
const Scalar _tmp46 = state(16, 0) * (_tmp40 + _tmp6) +
state(17, 0) * (_tmp0 + _tmp15 + _tmp30 + _tmp42) +
state(18, 0) * (_tmp25 + _tmp34);
// Intermediate terms (68)
const Scalar _tmp0 = -2 * std::pow(state(3, 0), Scalar(2));
const Scalar _tmp1 = 1 - 2 * std::pow(state(2, 0), Scalar(2));
const Scalar _tmp2 = _tmp0 + _tmp1;
const Scalar _tmp3 = 2 * state(3, 0);
const Scalar _tmp4 = _tmp3 * state(0, 0);
const Scalar _tmp5 = 2 * state(2, 0);
const Scalar _tmp6 = _tmp5 * state(1, 0);
const Scalar _tmp7 = _tmp4 + _tmp6;
const Scalar _tmp8 = _tmp5 * state(0, 0);
const Scalar _tmp9 = 2 * state(1, 0);
const Scalar _tmp10 = _tmp9 * state(3, 0);
const Scalar _tmp11 = _tmp10 - _tmp8;
const Scalar _tmp12 = -2 * std::pow(state(1, 0), Scalar(2));
const Scalar _tmp13 = _tmp0 + _tmp12 + 1;
const Scalar _tmp14 = _tmp5 * state(3, 0);
const Scalar _tmp15 = _tmp9 * state(0, 0);
const Scalar _tmp16 = _tmp14 + _tmp15;
const Scalar _tmp17 = -_tmp4 + _tmp6;
const Scalar _tmp18 = _tmp1 + _tmp12;
const Scalar _tmp19 = _tmp14 - _tmp15;
const Scalar _tmp20 = _tmp10 + _tmp8;
const Scalar _tmp21 = _tmp3 * state(18, 0);
const Scalar _tmp22 = _tmp5 * state(17, 0);
const Scalar _tmp23 = _tmp21 + _tmp22;
const Scalar _tmp24 = (Scalar(1) / Scalar(2)) * state(2, 0);
const Scalar _tmp25 = 2 * state(17, 0);
const Scalar _tmp26 = _tmp25 * state(3, 0);
const Scalar _tmp27 = _tmp5 * state(18, 0);
const Scalar _tmp28 = _tmp26 - _tmp27;
const Scalar _tmp29 = (Scalar(1) / Scalar(2)) * _tmp28;
const Scalar _tmp30 = 4 * state(2, 0);
const Scalar _tmp31 = _tmp9 * state(17, 0);
const Scalar _tmp32 = 2 * state(0, 0);
const Scalar _tmp33 = _tmp32 * state(18, 0);
const Scalar _tmp34 = -_tmp30 * state(16, 0) + _tmp31 - _tmp33;
const Scalar _tmp35 = (Scalar(1) / Scalar(2)) * state(1, 0);
const Scalar _tmp36 = _tmp9 * state(18, 0);
const Scalar _tmp37 = _tmp25 * state(0, 0);
const Scalar _tmp38 = (Scalar(1) / Scalar(2)) * _tmp36 + (Scalar(1) / Scalar(2)) * _tmp37 -
2 * state(16, 0) * state(3, 0);
const Scalar _tmp39 =
-_tmp23 * _tmp24 - _tmp29 * state(3, 0) + _tmp34 * _tmp35 + _tmp38 * state(0, 0);
const Scalar _tmp40 = (Scalar(1) / Scalar(2)) * _tmp23;
const Scalar _tmp41 = (Scalar(1) / Scalar(2)) * state(0, 0);
const Scalar _tmp42 =
-_tmp24 * _tmp28 + _tmp34 * _tmp41 - _tmp38 * state(1, 0) + _tmp40 * state(3, 0);
const Scalar _tmp43 = (Scalar(1) / Scalar(2)) * state(3, 0);
const Scalar _tmp44 =
-_tmp29 * state(1, 0) - _tmp34 * _tmp43 + _tmp38 * state(2, 0) + _tmp40 * state(0, 0);
const Scalar _tmp45 = _tmp3 * state(16, 0);
const Scalar _tmp46 = _tmp36 - _tmp45;
const Scalar _tmp47 = (Scalar(1) / Scalar(2)) * _tmp46;
const Scalar _tmp48 = _tmp9 * state(16, 0);
const Scalar _tmp49 = (Scalar(1) / Scalar(2)) * _tmp21 + (Scalar(1) / Scalar(2)) * _tmp48;
const Scalar _tmp50 = _tmp5 * state(16, 0);
const Scalar _tmp51 = 4 * state(17, 0);
const Scalar _tmp52 = _tmp33 + _tmp50 - _tmp51 * state(1, 0);
const Scalar _tmp53 = _tmp32 * state(16, 0);
const Scalar _tmp54 = _tmp27 - _tmp51 * state(3, 0) - _tmp53;
const Scalar _tmp55 =
_tmp24 * _tmp54 + _tmp41 * _tmp52 - _tmp47 * state(1, 0) - _tmp49 * state(3, 0);
const Scalar _tmp56 =
-_tmp24 * _tmp52 + _tmp41 * _tmp54 - _tmp47 * state(3, 0) + _tmp49 * state(1, 0);
const Scalar _tmp57 = -_tmp24 * _tmp46 - _tmp35 * _tmp54 + _tmp43 * _tmp52 + _tmp49 * state(0, 0);
const Scalar _tmp58 = -_tmp31 + _tmp50;
const Scalar _tmp59 = (Scalar(1) / Scalar(2)) * _tmp58;
const Scalar _tmp60 = _tmp22 + _tmp48;
const Scalar _tmp61 = (Scalar(1) / Scalar(2)) * _tmp60;
const Scalar _tmp62 = _tmp26 - _tmp30 * state(18, 0) + _tmp53;
const Scalar _tmp63 = -Scalar(1) / Scalar(2) * _tmp37 + (Scalar(1) / Scalar(2)) * _tmp45 -
2 * state(1, 0) * state(18, 0);
const Scalar _tmp64 =
_tmp35 * _tmp62 - _tmp59 * state(3, 0) + _tmp61 * state(0, 0) - _tmp63 * state(2, 0);
const Scalar _tmp65 = (Scalar(1) / Scalar(2)) * _tmp62;
const Scalar _tmp66 =
_tmp24 * _tmp60 - _tmp59 * state(1, 0) + _tmp63 * state(0, 0) - _tmp65 * state(3, 0);
const Scalar _tmp67 =
-_tmp24 * _tmp58 - _tmp61 * state(1, 0) + _tmp63 * state(3, 0) + _tmp65 * state(0, 0);
// Output terms (3)
if (innov != nullptr) {
matrix::Matrix<Scalar, 3, 1>& _innov = (*innov);
_innov(0, 0) = _tmp14 + _tmp4 * state(16, 0) - meas(0, 0) + state(19, 0);
_innov(1, 0) = _tmp17 * state(17, 0) + _tmp23 - meas(1, 0) + state(20, 0);
_innov(2, 0) = _tmp24 * state(18, 0) + _tmp28 - meas(2, 0) + state(21, 0);
_innov(0, 0) = _tmp11 * state(18, 0) + _tmp2 * state(16, 0) + _tmp7 * state(17, 0) -
meas(0, 0) + state(19, 0);
_innov(1, 0) = _tmp13 * state(17, 0) + _tmp16 * state(18, 0) + _tmp17 * state(16, 0) -
meas(1, 0) + state(20, 0);
_innov(2, 0) = _tmp18 * state(18, 0) + _tmp19 * state(17, 0) + _tmp20 * state(16, 0) -
meas(2, 0) + state(21, 0);
}
if (innov_var != nullptr) {
matrix::Matrix<Scalar, 3, 1>& _innov_var = (*innov_var);
_innov_var(0, 0) = P(1, 18) * _tmp36 + P(15, 18) * _tmp4 + P(16, 18) * _tmp9 +
P(17, 18) * _tmp13 + P(18, 18) + P(2, 18) * _tmp38 + R +
_tmp13 * (P(1, 17) * _tmp36 + P(15, 17) * _tmp4 + P(16, 17) * _tmp9 +
P(17, 17) * _tmp13 + P(18, 17) + P(2, 17) * _tmp38) +
_tmp36 * (P(1, 1) * _tmp36 + P(15, 1) * _tmp4 + P(16, 1) * _tmp9 +
P(17, 1) * _tmp13 + P(18, 1) + P(2, 1) * _tmp38) +
_tmp38 * (P(1, 2) * _tmp36 + P(15, 2) * _tmp4 + P(16, 2) * _tmp9 +
P(17, 2) * _tmp13 + P(18, 2) + P(2, 2) * _tmp38) +
_tmp4 * (P(1, 15) * _tmp36 + P(15, 15) * _tmp4 + P(16, 15) * _tmp9 +
P(17, 15) * _tmp13 + P(18, 15) + P(2, 15) * _tmp38) +
_tmp9 * (P(1, 16) * _tmp36 + P(15, 16) * _tmp4 + P(16, 16) * _tmp9 +
P(17, 16) * _tmp13 + P(18, 16) + P(2, 16) * _tmp38);
_innov_var(1, 0) = P(0, 19) * _tmp44 + P(15, 19) * _tmp22 + P(16, 19) * _tmp17 +
P(17, 19) * _tmp20 + P(19, 19) + P(2, 19) * _tmp41 + R +
_tmp17 * (P(0, 16) * _tmp44 + P(15, 16) * _tmp22 + P(16, 16) * _tmp17 +
P(17, 16) * _tmp20 + P(19, 16) + P(2, 16) * _tmp41) +
_tmp20 * (P(0, 17) * _tmp44 + P(15, 17) * _tmp22 + P(16, 17) * _tmp17 +
P(17, 17) * _tmp20 + P(19, 17) + P(2, 17) * _tmp41) +
_tmp22 * (P(0, 15) * _tmp44 + P(15, 15) * _tmp22 + P(16, 15) * _tmp17 +
P(17, 15) * _tmp20 + P(19, 15) + P(2, 15) * _tmp41) +
_tmp41 * (P(0, 2) * _tmp44 + P(15, 2) * _tmp22 + P(16, 2) * _tmp17 +
P(17, 2) * _tmp20 + P(19, 2) + P(2, 2) * _tmp41) +
_tmp44 * (P(0, 0) * _tmp44 + P(15, 0) * _tmp22 + P(16, 0) * _tmp17 +
P(17, 0) * _tmp20 + P(19, 0) + P(2, 0) * _tmp41);
_innov_var(2, 0) = P(0, 20) * _tmp46 + P(1, 20) * _tmp45 + P(15, 20) * _tmp27 +
P(16, 20) * _tmp26 + P(17, 20) * _tmp24 + P(20, 20) + R +
_tmp24 * (P(0, 17) * _tmp46 + P(1, 17) * _tmp45 + P(15, 17) * _tmp27 +
P(16, 17) * _tmp26 + P(17, 17) * _tmp24 + P(20, 17)) +
_tmp26 * (P(0, 16) * _tmp46 + P(1, 16) * _tmp45 + P(15, 16) * _tmp27 +
P(16, 16) * _tmp26 + P(17, 16) * _tmp24 + P(20, 16)) +
_tmp27 * (P(0, 15) * _tmp46 + P(1, 15) * _tmp45 + P(15, 15) * _tmp27 +
P(16, 15) * _tmp26 + P(17, 15) * _tmp24 + P(20, 15)) +
_tmp45 * (P(0, 1) * _tmp46 + P(1, 1) * _tmp45 + P(15, 1) * _tmp27 +
P(16, 1) * _tmp26 + P(17, 1) * _tmp24 + P(20, 1)) +
_tmp46 * (P(0, 0) * _tmp46 + P(1, 0) * _tmp45 + P(15, 0) * _tmp27 +
P(16, 0) * _tmp26 + P(17, 0) * _tmp24 + P(20, 0));
_innov_var(0, 0) =
P(0, 18) * _tmp44 + P(1, 18) * _tmp42 + P(15, 18) * _tmp2 + P(16, 18) * _tmp7 +
P(17, 18) * _tmp11 + P(18, 18) + P(2, 18) * _tmp39 + R +
_tmp11 * (P(0, 17) * _tmp44 + P(1, 17) * _tmp42 + P(15, 17) * _tmp2 + P(16, 17) * _tmp7 +
P(17, 17) * _tmp11 + P(18, 17) + P(2, 17) * _tmp39) +
_tmp2 * (P(0, 15) * _tmp44 + P(1, 15) * _tmp42 + P(15, 15) * _tmp2 + P(16, 15) * _tmp7 +
P(17, 15) * _tmp11 + P(18, 15) + P(2, 15) * _tmp39) +
_tmp39 * (P(0, 2) * _tmp44 + P(1, 2) * _tmp42 + P(15, 2) * _tmp2 + P(16, 2) * _tmp7 +
P(17, 2) * _tmp11 + P(18, 2) + P(2, 2) * _tmp39) +
_tmp42 * (P(0, 1) * _tmp44 + P(1, 1) * _tmp42 + P(15, 1) * _tmp2 + P(16, 1) * _tmp7 +
P(17, 1) * _tmp11 + P(18, 1) + P(2, 1) * _tmp39) +
_tmp44 * (P(0, 0) * _tmp44 + P(1, 0) * _tmp42 + P(15, 0) * _tmp2 + P(16, 0) * _tmp7 +
P(17, 0) * _tmp11 + P(18, 0) + P(2, 0) * _tmp39) +
_tmp7 * (P(0, 16) * _tmp44 + P(1, 16) * _tmp42 + P(15, 16) * _tmp2 + P(16, 16) * _tmp7 +
P(17, 16) * _tmp11 + P(18, 16) + P(2, 16) * _tmp39);
_innov_var(1, 0) =
P(0, 19) * _tmp55 + P(1, 19) * _tmp57 + P(15, 19) * _tmp17 + P(16, 19) * _tmp13 +
P(17, 19) * _tmp16 + P(19, 19) + P(2, 19) * _tmp56 + R +
_tmp13 * (P(0, 16) * _tmp55 + P(1, 16) * _tmp57 + P(15, 16) * _tmp17 + P(16, 16) * _tmp13 +
P(17, 16) * _tmp16 + P(19, 16) + P(2, 16) * _tmp56) +
_tmp16 * (P(0, 17) * _tmp55 + P(1, 17) * _tmp57 + P(15, 17) * _tmp17 + P(16, 17) * _tmp13 +
P(17, 17) * _tmp16 + P(19, 17) + P(2, 17) * _tmp56) +
_tmp17 * (P(0, 15) * _tmp55 + P(1, 15) * _tmp57 + P(15, 15) * _tmp17 + P(16, 15) * _tmp13 +
P(17, 15) * _tmp16 + P(19, 15) + P(2, 15) * _tmp56) +
_tmp55 * (P(0, 0) * _tmp55 + P(1, 0) * _tmp57 + P(15, 0) * _tmp17 + P(16, 0) * _tmp13 +
P(17, 0) * _tmp16 + P(19, 0) + P(2, 0) * _tmp56) +
_tmp56 * (P(0, 2) * _tmp55 + P(1, 2) * _tmp57 + P(15, 2) * _tmp17 + P(16, 2) * _tmp13 +
P(17, 2) * _tmp16 + P(19, 2) + P(2, 2) * _tmp56) +
_tmp57 * (P(0, 1) * _tmp55 + P(1, 1) * _tmp57 + P(15, 1) * _tmp17 + P(16, 1) * _tmp13 +
P(17, 1) * _tmp16 + P(19, 1) + P(2, 1) * _tmp56);
_innov_var(2, 0) =
P(0, 20) * _tmp66 + P(1, 20) * _tmp67 + P(15, 20) * _tmp20 + P(16, 20) * _tmp19 +
P(17, 20) * _tmp18 + P(2, 20) * _tmp64 + P(20, 20) + R +
_tmp18 * (P(0, 17) * _tmp66 + P(1, 17) * _tmp67 + P(15, 17) * _tmp20 + P(16, 17) * _tmp19 +
P(17, 17) * _tmp18 + P(2, 17) * _tmp64 + P(20, 17)) +
_tmp19 * (P(0, 16) * _tmp66 + P(1, 16) * _tmp67 + P(15, 16) * _tmp20 + P(16, 16) * _tmp19 +
P(17, 16) * _tmp18 + P(2, 16) * _tmp64 + P(20, 16)) +
_tmp20 * (P(0, 15) * _tmp66 + P(1, 15) * _tmp67 + P(15, 15) * _tmp20 + P(16, 15) * _tmp19 +
P(17, 15) * _tmp18 + P(2, 15) * _tmp64 + P(20, 15)) +
_tmp64 * (P(0, 2) * _tmp66 + P(1, 2) * _tmp67 + P(15, 2) * _tmp20 + P(16, 2) * _tmp19 +
P(17, 2) * _tmp18 + P(2, 2) * _tmp64 + P(20, 2)) +
_tmp66 * (P(0, 0) * _tmp66 + P(1, 0) * _tmp67 + P(15, 0) * _tmp20 + P(16, 0) * _tmp19 +
P(17, 0) * _tmp18 + P(2, 0) * _tmp64 + P(20, 0)) +
_tmp67 * (P(0, 1) * _tmp66 + P(1, 1) * _tmp67 + P(15, 1) * _tmp20 + P(16, 1) * _tmp19 +
P(17, 1) * _tmp18 + P(2, 1) * _tmp64 + P(20, 1));
}
if (Hx != nullptr) {
@ -150,11 +189,12 @@ void ComputeMagInnovInnovVarAndHx(const matrix::Matrix<Scalar, 24, 1>& state,
_hx.setZero();
_hx(1, 0) = _tmp36;
_hx(2, 0) = _tmp38;
_hx(15, 0) = _tmp4;
_hx(16, 0) = _tmp9;
_hx(17, 0) = _tmp13;
_hx(0, 0) = _tmp44;
_hx(1, 0) = _tmp42;
_hx(2, 0) = _tmp39;
_hx(15, 0) = _tmp2;
_hx(16, 0) = _tmp7;
_hx(17, 0) = _tmp11;
_hx(18, 0) = 1;
}
} // NOLINT(readability/fn_size)

View File

@ -30,7 +30,7 @@ void ComputeMagYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
const Scalar epsilon, Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 110
// Total ops: 159
// Unused inputs
(void)epsilon;
@ -38,43 +38,50 @@ void ComputeMagYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
// Input arrays
// Intermediate terms (18)
const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp1 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp2 = -2 * _tmp0 - 2 * _tmp1 + 1;
const Scalar _tmp3 = 2 * state(2, 0);
const Scalar _tmp4 = _tmp3 * state(3, 0);
const Scalar _tmp5 = 2 * state(0, 0);
const Scalar _tmp6 = _tmp5 * state(1, 0);
const Scalar _tmp7 = _tmp4 + _tmp6;
const Scalar _tmp8 = -_tmp5 * state(3, 0);
const Scalar _tmp9 = _tmp3 * state(1, 0);
const Scalar _tmp10 = _tmp8 + _tmp9;
const Scalar _tmp11 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp12 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp13 = _tmp0 - _tmp1;
const Scalar _tmp14 = _tmp3 * state(0, 0);
const Scalar _tmp15 = 2 * state(1, 0) * state(3, 0);
const Scalar _tmp16 = state(16, 0) * (-_tmp11 + _tmp12 + _tmp13) +
state(17, 0) * (_tmp8 - _tmp9) + state(18, 0) * (_tmp14 - _tmp15);
const Scalar _tmp17 = state(16, 0) * (_tmp14 + _tmp15) + state(17, 0) * (_tmp4 - _tmp6) +
state(18, 0) * (_tmp11 - _tmp12 + _tmp13);
const Scalar _tmp0 = 2 * state(2, 0);
const Scalar _tmp1 = 2 * state(1, 0);
const Scalar _tmp2 = _tmp0 * state(3, 0) + _tmp1 * state(0, 0);
const Scalar _tmp3 = 2 * state(3, 0);
const Scalar _tmp4 = _tmp0 * state(1, 0) - _tmp3 * state(0, 0);
const Scalar _tmp5 =
-2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1;
const Scalar _tmp6 = _tmp1 * state(18, 0) - _tmp3 * state(16, 0);
const Scalar _tmp7 = (Scalar(1) / Scalar(2)) * _tmp6;
const Scalar _tmp8 = (Scalar(1) / Scalar(2)) * _tmp1 * state(16, 0) +
(Scalar(1) / Scalar(2)) * _tmp3 * state(18, 0);
const Scalar _tmp9 = 4 * state(17, 0);
const Scalar _tmp10 = 2 * state(0, 0);
const Scalar _tmp11 = _tmp0 * state(16, 0) + _tmp10 * state(18, 0) - _tmp9 * state(1, 0);
const Scalar _tmp12 = (Scalar(1) / Scalar(2)) * _tmp11;
const Scalar _tmp13 = (Scalar(1) / Scalar(2)) * _tmp0 * state(18, 0) -
Scalar(1) / Scalar(2) * _tmp10 * state(16, 0) -
Scalar(1) / Scalar(2) * _tmp9 * state(3, 0);
const Scalar _tmp14 =
_tmp12 * state(0, 0) + _tmp13 * state(2, 0) - _tmp7 * state(1, 0) - _tmp8 * state(3, 0);
const Scalar _tmp15 = (Scalar(1) / Scalar(2)) * state(2, 0);
const Scalar _tmp16 =
-_tmp11 * _tmp15 + _tmp13 * state(0, 0) - _tmp7 * state(3, 0) + _tmp8 * state(1, 0);
const Scalar _tmp17 =
_tmp12 * state(3, 0) - _tmp13 * state(1, 0) - _tmp15 * _tmp6 + _tmp8 * state(0, 0);
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = P(0, 19) * _tmp17 + P(15, 19) * _tmp10 + P(16, 19) * _tmp2 + P(17, 19) * _tmp7 +
P(19, 19) + P(2, 19) * _tmp16 + R +
_tmp10 * (P(0, 15) * _tmp17 + P(15, 15) * _tmp10 + P(16, 15) * _tmp2 +
P(17, 15) * _tmp7 + P(19, 15) + P(2, 15) * _tmp16) +
_tmp16 * (P(0, 2) * _tmp17 + P(15, 2) * _tmp10 + P(16, 2) * _tmp2 +
P(17, 2) * _tmp7 + P(19, 2) + P(2, 2) * _tmp16) +
_tmp17 * (P(0, 0) * _tmp17 + P(15, 0) * _tmp10 + P(16, 0) * _tmp2 +
P(17, 0) * _tmp7 + P(19, 0) + P(2, 0) * _tmp16) +
_tmp2 * (P(0, 16) * _tmp17 + P(15, 16) * _tmp10 + P(16, 16) * _tmp2 +
P(17, 16) * _tmp7 + P(19, 16) + P(2, 16) * _tmp16) +
_tmp7 * (P(0, 17) * _tmp17 + P(15, 17) * _tmp10 + P(16, 17) * _tmp2 +
P(17, 17) * _tmp7 + P(19, 17) + P(2, 17) * _tmp16);
_innov_var = P(0, 19) * _tmp14 + P(1, 19) * _tmp17 + P(15, 19) * _tmp4 + P(16, 19) * _tmp5 +
P(17, 19) * _tmp2 + P(19, 19) + P(2, 19) * _tmp16 + R +
_tmp14 * (P(0, 0) * _tmp14 + P(1, 0) * _tmp17 + P(15, 0) * _tmp4 +
P(16, 0) * _tmp5 + P(17, 0) * _tmp2 + P(19, 0) + P(2, 0) * _tmp16) +
_tmp16 * (P(0, 2) * _tmp14 + P(1, 2) * _tmp17 + P(15, 2) * _tmp4 +
P(16, 2) * _tmp5 + P(17, 2) * _tmp2 + P(19, 2) + P(2, 2) * _tmp16) +
_tmp17 * (P(0, 1) * _tmp14 + P(1, 1) * _tmp17 + P(15, 1) * _tmp4 +
P(16, 1) * _tmp5 + P(17, 1) * _tmp2 + P(19, 1) + P(2, 1) * _tmp16) +
_tmp2 * (P(0, 17) * _tmp14 + P(1, 17) * _tmp17 + P(15, 17) * _tmp4 +
P(16, 17) * _tmp5 + P(17, 17) * _tmp2 + P(19, 17) + P(2, 17) * _tmp16) +
_tmp4 * (P(0, 15) * _tmp14 + P(1, 15) * _tmp17 + P(15, 15) * _tmp4 +
P(16, 15) * _tmp5 + P(17, 15) * _tmp2 + P(19, 15) + P(2, 15) * _tmp16) +
_tmp5 * (P(0, 16) * _tmp14 + P(1, 16) * _tmp17 + P(15, 16) * _tmp4 +
P(16, 16) * _tmp5 + P(17, 16) * _tmp2 + P(19, 16) + P(2, 16) * _tmp16);
}
if (H != nullptr) {
@ -82,11 +89,12 @@ void ComputeMagYInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_h.setZero();
_h(0, 0) = _tmp17;
_h(0, 0) = _tmp14;
_h(1, 0) = _tmp17;
_h(2, 0) = _tmp16;
_h(15, 0) = _tmp10;
_h(16, 0) = _tmp2;
_h(17, 0) = _tmp7;
_h(15, 0) = _tmp4;
_h(16, 0) = _tmp5;
_h(17, 0) = _tmp2;
_h(19, 0) = 1;
}
} // NOLINT(readability/fn_size)

View File

@ -30,51 +30,58 @@ void ComputeMagZInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
const Scalar epsilon, Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 110
// Total ops: 161
// Unused inputs
(void)epsilon;
// Input arrays
// Intermediate terms (18)
const Scalar _tmp0 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp1 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp2 = -2 * _tmp0 - 2 * _tmp1 + 1;
const Scalar _tmp3 = 2 * state(2, 0);
const Scalar _tmp4 = _tmp3 * state(3, 0);
const Scalar _tmp5 = 2 * state(0, 0);
const Scalar _tmp6 = -_tmp5 * state(1, 0);
const Scalar _tmp7 = _tmp4 + _tmp6;
const Scalar _tmp8 = _tmp3 * state(0, 0);
const Scalar _tmp9 = 2 * state(1, 0) * state(3, 0);
const Scalar _tmp10 = _tmp8 + _tmp9;
const Scalar _tmp11 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp12 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp13 = -_tmp0 + _tmp1;
const Scalar _tmp14 = _tmp5 * state(3, 0);
const Scalar _tmp15 = _tmp3 * state(1, 0);
const Scalar _tmp16 = state(16, 0) * (-_tmp11 + _tmp12 + _tmp13) +
state(17, 0) * (_tmp14 + _tmp15) + state(18, 0) * (-_tmp8 + _tmp9);
const Scalar _tmp17 = state(16, 0) * (_tmp14 - _tmp15) +
state(17, 0) * (_tmp11 - _tmp12 + _tmp13) + state(18, 0) * (-_tmp4 + _tmp6);
// Intermediate terms (15)
const Scalar _tmp0 = 2 * state(16, 0);
const Scalar _tmp1 = 2 * state(17, 0);
const Scalar _tmp2 =
(Scalar(1) / Scalar(2)) * _tmp0 * state(2, 0) - Scalar(1) / Scalar(2) * _tmp1 * state(1, 0);
const Scalar _tmp3 = 2 * state(1, 0);
const Scalar _tmp4 = (Scalar(1) / Scalar(2)) * _tmp1 * state(2, 0) +
(Scalar(1) / Scalar(2)) * _tmp3 * state(16, 0);
const Scalar _tmp5 = 4 * state(18, 0);
const Scalar _tmp6 = (Scalar(1) / Scalar(2)) * _tmp0 * state(0, 0) +
(Scalar(1) / Scalar(2)) * _tmp1 * state(3, 0) -
Scalar(1) / Scalar(2) * _tmp5 * state(2, 0);
const Scalar _tmp7 = (Scalar(1) / Scalar(2)) * _tmp0 * state(3, 0) -
Scalar(1) / Scalar(2) * _tmp1 * state(0, 0) -
Scalar(1) / Scalar(2) * _tmp5 * state(1, 0);
const Scalar _tmp8 =
-_tmp2 * state(3, 0) + _tmp4 * state(0, 0) + _tmp6 * state(1, 0) - _tmp7 * state(2, 0);
const Scalar _tmp9 =
-_tmp2 * state(1, 0) + _tmp4 * state(2, 0) - _tmp6 * state(3, 0) + _tmp7 * state(0, 0);
const Scalar _tmp10 =
-_tmp2 * state(2, 0) - _tmp4 * state(1, 0) + _tmp6 * state(0, 0) + _tmp7 * state(3, 0);
const Scalar _tmp11 =
-2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(2, 0), Scalar(2)) + 1;
const Scalar _tmp12 = 2 * state(2, 0);
const Scalar _tmp13 = _tmp12 * state(3, 0) - _tmp3 * state(0, 0);
const Scalar _tmp14 = _tmp12 * state(0, 0) + _tmp3 * state(3, 0);
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = P(0, 20) * _tmp17 + P(1, 20) * _tmp16 + P(15, 20) * _tmp10 + P(16, 20) * _tmp7 +
P(17, 20) * _tmp2 + P(20, 20) + R +
_tmp10 * (P(0, 15) * _tmp17 + P(1, 15) * _tmp16 + P(15, 15) * _tmp10 +
P(16, 15) * _tmp7 + P(17, 15) * _tmp2 + P(20, 15)) +
_tmp16 * (P(0, 1) * _tmp17 + P(1, 1) * _tmp16 + P(15, 1) * _tmp10 +
P(16, 1) * _tmp7 + P(17, 1) * _tmp2 + P(20, 1)) +
_tmp17 * (P(0, 0) * _tmp17 + P(1, 0) * _tmp16 + P(15, 0) * _tmp10 +
P(16, 0) * _tmp7 + P(17, 0) * _tmp2 + P(20, 0)) +
_tmp2 * (P(0, 17) * _tmp17 + P(1, 17) * _tmp16 + P(15, 17) * _tmp10 +
P(16, 17) * _tmp7 + P(17, 17) * _tmp2 + P(20, 17)) +
_tmp7 * (P(0, 16) * _tmp17 + P(1, 16) * _tmp16 + P(15, 16) * _tmp10 +
P(16, 16) * _tmp7 + P(17, 16) * _tmp2 + P(20, 16));
_innov_var = P(0, 20) * _tmp9 + P(1, 20) * _tmp10 + P(15, 20) * _tmp14 + P(16, 20) * _tmp13 +
P(17, 20) * _tmp11 + P(2, 20) * _tmp8 + P(20, 20) + R +
_tmp10 * (P(0, 1) * _tmp9 + P(1, 1) * _tmp10 + P(15, 1) * _tmp14 +
P(16, 1) * _tmp13 + P(17, 1) * _tmp11 + P(2, 1) * _tmp8 + P(20, 1)) +
_tmp11 * (P(0, 17) * _tmp9 + P(1, 17) * _tmp10 + P(15, 17) * _tmp14 +
P(16, 17) * _tmp13 + P(17, 17) * _tmp11 + P(2, 17) * _tmp8 + P(20, 17)) +
_tmp13 * (P(0, 16) * _tmp9 + P(1, 16) * _tmp10 + P(15, 16) * _tmp14 +
P(16, 16) * _tmp13 + P(17, 16) * _tmp11 + P(2, 16) * _tmp8 + P(20, 16)) +
_tmp14 * (P(0, 15) * _tmp9 + P(1, 15) * _tmp10 + P(15, 15) * _tmp14 +
P(16, 15) * _tmp13 + P(17, 15) * _tmp11 + P(2, 15) * _tmp8 + P(20, 15)) +
_tmp8 * (P(0, 2) * _tmp9 + P(1, 2) * _tmp10 + P(15, 2) * _tmp14 +
P(16, 2) * _tmp13 + P(17, 2) * _tmp11 + P(2, 2) * _tmp8 + P(20, 2)) +
_tmp9 * (P(0, 0) * _tmp9 + P(1, 0) * _tmp10 + P(15, 0) * _tmp14 +
P(16, 0) * _tmp13 + P(17, 0) * _tmp11 + P(2, 0) * _tmp8 + P(20, 0));
}
if (H != nullptr) {
@ -82,11 +89,12 @@ void ComputeMagZInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_h.setZero();
_h(0, 0) = _tmp17;
_h(1, 0) = _tmp16;
_h(15, 0) = _tmp10;
_h(16, 0) = _tmp7;
_h(17, 0) = _tmp2;
_h(0, 0) = _tmp9;
_h(1, 0) = _tmp10;
_h(2, 0) = _tmp8;
_h(15, 0) = _tmp14;
_h(16, 0) = _tmp13;
_h(17, 0) = _tmp11;
_h(20, 0) = 1;
}
} // NOLINT(readability/fn_size)

View File

@ -30,63 +30,66 @@ void ComputeSideslipHAndK(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar innov_var,
const Scalar epsilon, matrix::Matrix<Scalar, 23, 1>* const H = nullptr,
matrix::Matrix<Scalar, 23, 1>* const K = nullptr) {
// Total ops: 469
// Total ops: 497
// Input arrays
// Intermediate terms (46)
const Scalar _tmp0 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp2 = 1 - 2 * _tmp1;
const Scalar _tmp3 = -2 * _tmp0 + _tmp2;
const Scalar _tmp4 = -state(22, 0) + state(4, 0);
const Scalar _tmp5 = 2 * state(0, 0);
const Scalar _tmp6 = _tmp5 * state(3, 0);
const Scalar _tmp7 = 2 * state(2, 0);
const Scalar _tmp8 = _tmp7 * state(1, 0);
const Scalar _tmp9 = _tmp6 + _tmp8;
const Scalar _tmp10 = -state(23, 0) + state(5, 0);
const Scalar _tmp11 = _tmp7 * state(0, 0);
const Scalar _tmp12 = -_tmp11;
const Scalar _tmp13 = 2 * state(1, 0) * state(3, 0);
const Scalar _tmp14 = _tmp12 + _tmp13;
const Scalar _tmp15 = _tmp10 * _tmp9 + _tmp14 * state(6, 0) + _tmp3 * _tmp4;
const Scalar _tmp16 =
_tmp15 + epsilon * (2 * math::min<Scalar>(0, (((_tmp15) > 0) - ((_tmp15) < 0))) + 1);
const Scalar _tmp17 = Scalar(1.0) / (_tmp16);
const Scalar _tmp18 = _tmp7 * state(3, 0);
const Scalar _tmp19 = _tmp5 * state(1, 0);
const Scalar _tmp20 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp21 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp22 = -_tmp21;
const Scalar _tmp23 = _tmp20 + _tmp22;
const Scalar _tmp24 = _tmp17 * (_tmp10 * (_tmp18 - _tmp19) + _tmp4 * (_tmp11 + _tmp13) +
state(6, 0) * (-_tmp0 + _tmp1 + _tmp23));
const Scalar _tmp25 = -_tmp13;
const Scalar _tmp26 = -_tmp20;
const Scalar _tmp27 = _tmp0 - _tmp1;
const Scalar _tmp28 = _tmp2 - 2 * _tmp21;
const Scalar _tmp29 = -_tmp6;
const Scalar _tmp30 = _tmp29 + _tmp8;
const Scalar _tmp31 = _tmp18 + _tmp19;
const Scalar _tmp32 = _tmp30 * _tmp4 + _tmp31 * state(6, 0);
const Scalar _tmp33 = (_tmp10 * _tmp28 + _tmp32) / std::pow(_tmp16, Scalar(2));
const Scalar _tmp34 = _tmp33 * (_tmp10 * (-_tmp18 + _tmp19) + _tmp4 * (_tmp12 + _tmp25) +
state(6, 0) * (_tmp21 + _tmp26 + _tmp27));
const Scalar _tmp35 =
_tmp17 * (_tmp10 * (_tmp29 - _tmp8) + _tmp4 * (_tmp0 + _tmp1 + _tmp22 + _tmp26) +
state(6, 0) * (_tmp11 + _tmp25)) -
_tmp33 * (_tmp10 * (_tmp23 + _tmp27) + _tmp32);
const Scalar _tmp36 = _tmp3 * _tmp33;
const Scalar _tmp37 = _tmp17 * _tmp30;
const Scalar _tmp38 = -_tmp36 + _tmp37;
const Scalar _tmp39 = _tmp33 * _tmp9;
const Scalar _tmp40 = _tmp17 * _tmp28;
const Scalar _tmp41 = -_tmp39 + _tmp40;
const Scalar _tmp42 = -_tmp14 * _tmp33 + _tmp17 * _tmp31;
const Scalar _tmp43 = _tmp36 - _tmp37;
const Scalar _tmp44 = _tmp39 - _tmp40;
const Scalar _tmp45 = Scalar(1.0) / (math::max<Scalar>(epsilon, innov_var));
// Intermediate terms (45)
const Scalar _tmp0 = -state(23, 0) + state(5, 0);
const Scalar _tmp1 = 2 * state(1, 0);
const Scalar _tmp2 = -state(22, 0) + state(4, 0);
const Scalar _tmp3 = 2 * state(6, 0);
const Scalar _tmp4 = _tmp3 * state(0, 0);
const Scalar _tmp5 = 1 - 2 * std::pow(state(3, 0), Scalar(2));
const Scalar _tmp6 = _tmp5 - 2 * std::pow(state(2, 0), Scalar(2));
const Scalar _tmp7 = 2 * state(0, 0);
const Scalar _tmp8 = _tmp7 * state(3, 0);
const Scalar _tmp9 = 2 * state(2, 0);
const Scalar _tmp10 = _tmp9 * state(1, 0);
const Scalar _tmp11 = _tmp10 + _tmp8;
const Scalar _tmp12 = _tmp1 * state(3, 0) - _tmp9 * state(0, 0);
const Scalar _tmp13 = _tmp0 * _tmp11 + _tmp12 * state(6, 0) + _tmp2 * _tmp6;
const Scalar _tmp14 =
_tmp13 + epsilon * (2 * math::min<Scalar>(0, (((_tmp13) > 0) - ((_tmp13) < 0))) + 1);
const Scalar _tmp15 = _tmp5 - 2 * std::pow(state(1, 0), Scalar(2));
const Scalar _tmp16 = _tmp10 - _tmp8;
const Scalar _tmp17 = _tmp7 * state(1, 0) + _tmp9 * state(3, 0);
const Scalar _tmp18 =
(_tmp0 * _tmp15 + _tmp16 * _tmp2 + _tmp17 * state(6, 0)) / std::pow(_tmp14, Scalar(2));
const Scalar _tmp19 = _tmp3 * state(3, 0);
const Scalar _tmp20 = Scalar(1.0) / (_tmp14);
const Scalar _tmp21 = -_tmp18 * (_tmp0 * _tmp1 - 4 * _tmp2 * state(2, 0) - _tmp4) +
_tmp20 * (_tmp1 * _tmp2 + _tmp19);
const Scalar _tmp22 = (Scalar(1) / Scalar(2)) * state(3, 0);
const Scalar _tmp23 =
-Scalar(1) / Scalar(2) * _tmp18 * (_tmp0 * _tmp9 + _tmp19) +
(Scalar(1) / Scalar(2)) * _tmp20 * (-4 * _tmp0 * state(1, 0) + _tmp2 * _tmp9 + _tmp4);
const Scalar _tmp24 = 2 * state(3, 0);
const Scalar _tmp25 = _tmp3 * state(2, 0);
const Scalar _tmp26 = _tmp3 * state(1, 0);
const Scalar _tmp27 = -_tmp18 * (_tmp0 * _tmp24 - _tmp25) + _tmp20 * (-_tmp2 * _tmp24 + _tmp26);
const Scalar _tmp28 = (Scalar(1) / Scalar(2)) * _tmp27;
const Scalar _tmp29 = 4 * state(3, 0);
const Scalar _tmp30 =
-Scalar(1) / Scalar(2) * _tmp18 * (_tmp0 * _tmp7 - _tmp2 * _tmp29 + _tmp26) +
(Scalar(1) / Scalar(2)) * _tmp20 * (-_tmp0 * _tmp29 - _tmp2 * _tmp7 + _tmp25);
const Scalar _tmp31 =
-_tmp21 * _tmp22 + _tmp23 * state(0, 0) - _tmp28 * state(1, 0) + _tmp30 * state(2, 0);
const Scalar _tmp32 = (Scalar(1) / Scalar(2)) * _tmp21;
const Scalar _tmp33 =
_tmp23 * state(3, 0) - _tmp28 * state(2, 0) - _tmp30 * state(1, 0) + _tmp32 * state(0, 0);
const Scalar _tmp34 =
-_tmp22 * _tmp27 - _tmp23 * state(2, 0) + _tmp30 * state(0, 0) + _tmp32 * state(1, 0);
const Scalar _tmp35 = _tmp18 * _tmp6;
const Scalar _tmp36 = _tmp16 * _tmp20;
const Scalar _tmp37 = -_tmp35 + _tmp36;
const Scalar _tmp38 = _tmp11 * _tmp18;
const Scalar _tmp39 = _tmp15 * _tmp20;
const Scalar _tmp40 = -_tmp38 + _tmp39;
const Scalar _tmp41 = -_tmp12 * _tmp18 + _tmp17 * _tmp20;
const Scalar _tmp42 = _tmp35 - _tmp36;
const Scalar _tmp43 = _tmp38 - _tmp39;
const Scalar _tmp44 = Scalar(1.0) / (math::max<Scalar>(epsilon, innov_var));
// Output terms (2)
if (H != nullptr) {
@ -94,88 +97,88 @@ void ComputeSideslipHAndK(const matrix::Matrix<Scalar, 24, 1>& state,
_h.setZero();
_h(0, 0) = _tmp24;
_h(1, 0) = -_tmp34;
_h(2, 0) = _tmp35;
_h(3, 0) = _tmp38;
_h(4, 0) = _tmp41;
_h(5, 0) = _tmp42;
_h(21, 0) = _tmp43;
_h(22, 0) = _tmp44;
_h(0, 0) = _tmp31;
_h(1, 0) = _tmp33;
_h(2, 0) = _tmp34;
_h(3, 0) = _tmp37;
_h(4, 0) = _tmp40;
_h(5, 0) = _tmp41;
_h(21, 0) = _tmp42;
_h(22, 0) = _tmp43;
}
if (K != nullptr) {
matrix::Matrix<Scalar, 23, 1>& _k = (*K);
_k(0, 0) =
_tmp45 * (P(0, 0) * _tmp24 - P(0, 1) * _tmp34 + P(0, 2) * _tmp35 + P(0, 21) * _tmp43 +
P(0, 22) * _tmp44 + P(0, 3) * _tmp38 + P(0, 4) * _tmp41 + P(0, 5) * _tmp42);
_tmp44 * (P(0, 0) * _tmp31 + P(0, 1) * _tmp33 + P(0, 2) * _tmp34 + P(0, 21) * _tmp42 +
P(0, 22) * _tmp43 + P(0, 3) * _tmp37 + P(0, 4) * _tmp40 + P(0, 5) * _tmp41);
_k(1, 0) =
_tmp45 * (P(1, 0) * _tmp24 - P(1, 1) * _tmp34 + P(1, 2) * _tmp35 + P(1, 21) * _tmp43 +
P(1, 22) * _tmp44 + P(1, 3) * _tmp38 + P(1, 4) * _tmp41 + P(1, 5) * _tmp42);
_tmp44 * (P(1, 0) * _tmp31 + P(1, 1) * _tmp33 + P(1, 2) * _tmp34 + P(1, 21) * _tmp42 +
P(1, 22) * _tmp43 + P(1, 3) * _tmp37 + P(1, 4) * _tmp40 + P(1, 5) * _tmp41);
_k(2, 0) =
_tmp45 * (P(2, 0) * _tmp24 - P(2, 1) * _tmp34 + P(2, 2) * _tmp35 + P(2, 21) * _tmp43 +
P(2, 22) * _tmp44 + P(2, 3) * _tmp38 + P(2, 4) * _tmp41 + P(2, 5) * _tmp42);
_tmp44 * (P(2, 0) * _tmp31 + P(2, 1) * _tmp33 + P(2, 2) * _tmp34 + P(2, 21) * _tmp42 +
P(2, 22) * _tmp43 + P(2, 3) * _tmp37 + P(2, 4) * _tmp40 + P(2, 5) * _tmp41);
_k(3, 0) =
_tmp45 * (P(3, 0) * _tmp24 - P(3, 1) * _tmp34 + P(3, 2) * _tmp35 + P(3, 21) * _tmp43 +
P(3, 22) * _tmp44 + P(3, 3) * _tmp38 + P(3, 4) * _tmp41 + P(3, 5) * _tmp42);
_tmp44 * (P(3, 0) * _tmp31 + P(3, 1) * _tmp33 + P(3, 2) * _tmp34 + P(3, 21) * _tmp42 +
P(3, 22) * _tmp43 + P(3, 3) * _tmp37 + P(3, 4) * _tmp40 + P(3, 5) * _tmp41);
_k(4, 0) =
_tmp45 * (P(4, 0) * _tmp24 - P(4, 1) * _tmp34 + P(4, 2) * _tmp35 + P(4, 21) * _tmp43 +
P(4, 22) * _tmp44 + P(4, 3) * _tmp38 + P(4, 4) * _tmp41 + P(4, 5) * _tmp42);
_tmp44 * (P(4, 0) * _tmp31 + P(4, 1) * _tmp33 + P(4, 2) * _tmp34 + P(4, 21) * _tmp42 +
P(4, 22) * _tmp43 + P(4, 3) * _tmp37 + P(4, 4) * _tmp40 + P(4, 5) * _tmp41);
_k(5, 0) =
_tmp45 * (P(5, 0) * _tmp24 - P(5, 1) * _tmp34 + P(5, 2) * _tmp35 + P(5, 21) * _tmp43 +
P(5, 22) * _tmp44 + P(5, 3) * _tmp38 + P(5, 4) * _tmp41 + P(5, 5) * _tmp42);
_tmp44 * (P(5, 0) * _tmp31 + P(5, 1) * _tmp33 + P(5, 2) * _tmp34 + P(5, 21) * _tmp42 +
P(5, 22) * _tmp43 + P(5, 3) * _tmp37 + P(5, 4) * _tmp40 + P(5, 5) * _tmp41);
_k(6, 0) =
_tmp45 * (P(6, 0) * _tmp24 - P(6, 1) * _tmp34 + P(6, 2) * _tmp35 + P(6, 21) * _tmp43 +
P(6, 22) * _tmp44 + P(6, 3) * _tmp38 + P(6, 4) * _tmp41 + P(6, 5) * _tmp42);
_tmp44 * (P(6, 0) * _tmp31 + P(6, 1) * _tmp33 + P(6, 2) * _tmp34 + P(6, 21) * _tmp42 +
P(6, 22) * _tmp43 + P(6, 3) * _tmp37 + P(6, 4) * _tmp40 + P(6, 5) * _tmp41);
_k(7, 0) =
_tmp45 * (P(7, 0) * _tmp24 - P(7, 1) * _tmp34 + P(7, 2) * _tmp35 + P(7, 21) * _tmp43 +
P(7, 22) * _tmp44 + P(7, 3) * _tmp38 + P(7, 4) * _tmp41 + P(7, 5) * _tmp42);
_tmp44 * (P(7, 0) * _tmp31 + P(7, 1) * _tmp33 + P(7, 2) * _tmp34 + P(7, 21) * _tmp42 +
P(7, 22) * _tmp43 + P(7, 3) * _tmp37 + P(7, 4) * _tmp40 + P(7, 5) * _tmp41);
_k(8, 0) =
_tmp45 * (P(8, 0) * _tmp24 - P(8, 1) * _tmp34 + P(8, 2) * _tmp35 + P(8, 21) * _tmp43 +
P(8, 22) * _tmp44 + P(8, 3) * _tmp38 + P(8, 4) * _tmp41 + P(8, 5) * _tmp42);
_tmp44 * (P(8, 0) * _tmp31 + P(8, 1) * _tmp33 + P(8, 2) * _tmp34 + P(8, 21) * _tmp42 +
P(8, 22) * _tmp43 + P(8, 3) * _tmp37 + P(8, 4) * _tmp40 + P(8, 5) * _tmp41);
_k(9, 0) =
_tmp45 * (P(9, 0) * _tmp24 - P(9, 1) * _tmp34 + P(9, 2) * _tmp35 + P(9, 21) * _tmp43 +
P(9, 22) * _tmp44 + P(9, 3) * _tmp38 + P(9, 4) * _tmp41 + P(9, 5) * _tmp42);
_tmp44 * (P(9, 0) * _tmp31 + P(9, 1) * _tmp33 + P(9, 2) * _tmp34 + P(9, 21) * _tmp42 +
P(9, 22) * _tmp43 + P(9, 3) * _tmp37 + P(9, 4) * _tmp40 + P(9, 5) * _tmp41);
_k(10, 0) =
_tmp45 * (P(10, 0) * _tmp24 - P(10, 1) * _tmp34 + P(10, 2) * _tmp35 + P(10, 21) * _tmp43 +
P(10, 22) * _tmp44 + P(10, 3) * _tmp38 + P(10, 4) * _tmp41 + P(10, 5) * _tmp42);
_tmp44 * (P(10, 0) * _tmp31 + P(10, 1) * _tmp33 + P(10, 2) * _tmp34 + P(10, 21) * _tmp42 +
P(10, 22) * _tmp43 + P(10, 3) * _tmp37 + P(10, 4) * _tmp40 + P(10, 5) * _tmp41);
_k(11, 0) =
_tmp45 * (P(11, 0) * _tmp24 - P(11, 1) * _tmp34 + P(11, 2) * _tmp35 + P(11, 21) * _tmp43 +
P(11, 22) * _tmp44 + P(11, 3) * _tmp38 + P(11, 4) * _tmp41 + P(11, 5) * _tmp42);
_tmp44 * (P(11, 0) * _tmp31 + P(11, 1) * _tmp33 + P(11, 2) * _tmp34 + P(11, 21) * _tmp42 +
P(11, 22) * _tmp43 + P(11, 3) * _tmp37 + P(11, 4) * _tmp40 + P(11, 5) * _tmp41);
_k(12, 0) =
_tmp45 * (P(12, 0) * _tmp24 - P(12, 1) * _tmp34 + P(12, 2) * _tmp35 + P(12, 21) * _tmp43 +
P(12, 22) * _tmp44 + P(12, 3) * _tmp38 + P(12, 4) * _tmp41 + P(12, 5) * _tmp42);
_tmp44 * (P(12, 0) * _tmp31 + P(12, 1) * _tmp33 + P(12, 2) * _tmp34 + P(12, 21) * _tmp42 +
P(12, 22) * _tmp43 + P(12, 3) * _tmp37 + P(12, 4) * _tmp40 + P(12, 5) * _tmp41);
_k(13, 0) =
_tmp45 * (P(13, 0) * _tmp24 - P(13, 1) * _tmp34 + P(13, 2) * _tmp35 + P(13, 21) * _tmp43 +
P(13, 22) * _tmp44 + P(13, 3) * _tmp38 + P(13, 4) * _tmp41 + P(13, 5) * _tmp42);
_tmp44 * (P(13, 0) * _tmp31 + P(13, 1) * _tmp33 + P(13, 2) * _tmp34 + P(13, 21) * _tmp42 +
P(13, 22) * _tmp43 + P(13, 3) * _tmp37 + P(13, 4) * _tmp40 + P(13, 5) * _tmp41);
_k(14, 0) =
_tmp45 * (P(14, 0) * _tmp24 - P(14, 1) * _tmp34 + P(14, 2) * _tmp35 + P(14, 21) * _tmp43 +
P(14, 22) * _tmp44 + P(14, 3) * _tmp38 + P(14, 4) * _tmp41 + P(14, 5) * _tmp42);
_tmp44 * (P(14, 0) * _tmp31 + P(14, 1) * _tmp33 + P(14, 2) * _tmp34 + P(14, 21) * _tmp42 +
P(14, 22) * _tmp43 + P(14, 3) * _tmp37 + P(14, 4) * _tmp40 + P(14, 5) * _tmp41);
_k(15, 0) =
_tmp45 * (P(15, 0) * _tmp24 - P(15, 1) * _tmp34 + P(15, 2) * _tmp35 + P(15, 21) * _tmp43 +
P(15, 22) * _tmp44 + P(15, 3) * _tmp38 + P(15, 4) * _tmp41 + P(15, 5) * _tmp42);
_tmp44 * (P(15, 0) * _tmp31 + P(15, 1) * _tmp33 + P(15, 2) * _tmp34 + P(15, 21) * _tmp42 +
P(15, 22) * _tmp43 + P(15, 3) * _tmp37 + P(15, 4) * _tmp40 + P(15, 5) * _tmp41);
_k(16, 0) =
_tmp45 * (P(16, 0) * _tmp24 - P(16, 1) * _tmp34 + P(16, 2) * _tmp35 + P(16, 21) * _tmp43 +
P(16, 22) * _tmp44 + P(16, 3) * _tmp38 + P(16, 4) * _tmp41 + P(16, 5) * _tmp42);
_tmp44 * (P(16, 0) * _tmp31 + P(16, 1) * _tmp33 + P(16, 2) * _tmp34 + P(16, 21) * _tmp42 +
P(16, 22) * _tmp43 + P(16, 3) * _tmp37 + P(16, 4) * _tmp40 + P(16, 5) * _tmp41);
_k(17, 0) =
_tmp45 * (P(17, 0) * _tmp24 - P(17, 1) * _tmp34 + P(17, 2) * _tmp35 + P(17, 21) * _tmp43 +
P(17, 22) * _tmp44 + P(17, 3) * _tmp38 + P(17, 4) * _tmp41 + P(17, 5) * _tmp42);
_tmp44 * (P(17, 0) * _tmp31 + P(17, 1) * _tmp33 + P(17, 2) * _tmp34 + P(17, 21) * _tmp42 +
P(17, 22) * _tmp43 + P(17, 3) * _tmp37 + P(17, 4) * _tmp40 + P(17, 5) * _tmp41);
_k(18, 0) =
_tmp45 * (P(18, 0) * _tmp24 - P(18, 1) * _tmp34 + P(18, 2) * _tmp35 + P(18, 21) * _tmp43 +
P(18, 22) * _tmp44 + P(18, 3) * _tmp38 + P(18, 4) * _tmp41 + P(18, 5) * _tmp42);
_tmp44 * (P(18, 0) * _tmp31 + P(18, 1) * _tmp33 + P(18, 2) * _tmp34 + P(18, 21) * _tmp42 +
P(18, 22) * _tmp43 + P(18, 3) * _tmp37 + P(18, 4) * _tmp40 + P(18, 5) * _tmp41);
_k(19, 0) =
_tmp45 * (P(19, 0) * _tmp24 - P(19, 1) * _tmp34 + P(19, 2) * _tmp35 + P(19, 21) * _tmp43 +
P(19, 22) * _tmp44 + P(19, 3) * _tmp38 + P(19, 4) * _tmp41 + P(19, 5) * _tmp42);
_tmp44 * (P(19, 0) * _tmp31 + P(19, 1) * _tmp33 + P(19, 2) * _tmp34 + P(19, 21) * _tmp42 +
P(19, 22) * _tmp43 + P(19, 3) * _tmp37 + P(19, 4) * _tmp40 + P(19, 5) * _tmp41);
_k(20, 0) =
_tmp45 * (P(20, 0) * _tmp24 - P(20, 1) * _tmp34 + P(20, 2) * _tmp35 + P(20, 21) * _tmp43 +
P(20, 22) * _tmp44 + P(20, 3) * _tmp38 + P(20, 4) * _tmp41 + P(20, 5) * _tmp42);
_tmp44 * (P(20, 0) * _tmp31 + P(20, 1) * _tmp33 + P(20, 2) * _tmp34 + P(20, 21) * _tmp42 +
P(20, 22) * _tmp43 + P(20, 3) * _tmp37 + P(20, 4) * _tmp40 + P(20, 5) * _tmp41);
_k(21, 0) =
_tmp45 * (P(21, 0) * _tmp24 - P(21, 1) * _tmp34 + P(21, 2) * _tmp35 + P(21, 21) * _tmp43 +
P(21, 22) * _tmp44 + P(21, 3) * _tmp38 + P(21, 4) * _tmp41 + P(21, 5) * _tmp42);
_tmp44 * (P(21, 0) * _tmp31 + P(21, 1) * _tmp33 + P(21, 2) * _tmp34 + P(21, 21) * _tmp42 +
P(21, 22) * _tmp43 + P(21, 3) * _tmp37 + P(21, 4) * _tmp40 + P(21, 5) * _tmp41);
_k(22, 0) =
_tmp45 * (P(22, 0) * _tmp24 - P(22, 1) * _tmp34 + P(22, 2) * _tmp35 + P(22, 21) * _tmp43 +
P(22, 22) * _tmp44 + P(22, 3) * _tmp38 + P(22, 4) * _tmp41 + P(22, 5) * _tmp42);
_tmp44 * (P(22, 0) * _tmp31 + P(22, 1) * _tmp33 + P(22, 2) * _tmp34 + P(22, 21) * _tmp42 +
P(22, 22) * _tmp43 + P(22, 3) * _tmp37 + P(22, 4) * _tmp40 + P(22, 5) * _tmp41);
}
} // NOLINT(readability/fn_size)

View File

@ -30,69 +30,70 @@ void ComputeSideslipInnovAndInnovVar(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
const Scalar epsilon, Scalar* const innov = nullptr,
Scalar* const innov_var = nullptr) {
// Total ops: 235
// Total ops: 265
// Input arrays
// Intermediate terms (46)
const Scalar _tmp0 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp2 = 1 - 2 * _tmp1;
const Scalar _tmp3 = -2 * _tmp0 + _tmp2;
const Scalar _tmp4 = -state(22, 0) + state(4, 0);
const Scalar _tmp5 = 2 * state(0, 0);
const Scalar _tmp6 = _tmp5 * state(3, 0);
const Scalar _tmp7 = 2 * state(1, 0);
const Scalar _tmp8 = _tmp7 * state(2, 0);
const Scalar _tmp9 = _tmp6 + _tmp8;
const Scalar _tmp10 = -state(23, 0) + state(5, 0);
const Scalar _tmp11 = _tmp5 * state(2, 0);
const Scalar _tmp12 = -_tmp11;
const Scalar _tmp13 = _tmp7 * state(3, 0);
const Scalar _tmp14 = _tmp12 + _tmp13;
const Scalar _tmp15 = _tmp10 * _tmp9 + _tmp14 * state(6, 0) + _tmp3 * _tmp4;
const Scalar _tmp16 =
_tmp15 + epsilon * (2 * math::min<Scalar>(0, (((_tmp15) > 0) - ((_tmp15) < 0))) + 1);
const Scalar _tmp17 = Scalar(1.0) / (_tmp16);
const Scalar _tmp18 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp19 = -2 * _tmp18 + _tmp2;
const Scalar _tmp20 = -_tmp6;
const Scalar _tmp21 = _tmp20 + _tmp8;
const Scalar _tmp22 = 2 * state(2, 0) * state(3, 0);
const Scalar _tmp23 = _tmp5 * state(1, 0);
const Scalar _tmp24 = _tmp22 + _tmp23;
const Scalar _tmp25 = _tmp21 * _tmp4 + _tmp24 * state(6, 0);
const Scalar _tmp26 = _tmp10 * _tmp19 + _tmp25;
const Scalar _tmp27 = _tmp26 / std::pow(_tmp16, Scalar(2));
const Scalar _tmp28 = -_tmp14 * _tmp27 + _tmp17 * _tmp24;
const Scalar _tmp29 = _tmp27 * _tmp3;
const Scalar _tmp30 = _tmp17 * _tmp21;
const Scalar _tmp31 = -_tmp29 + _tmp30;
const Scalar _tmp32 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp33 = -_tmp32;
const Scalar _tmp34 = -_tmp18;
const Scalar _tmp35 = -_tmp13;
const Scalar _tmp36 = _tmp0 - _tmp1;
const Scalar _tmp37 = _tmp32 + _tmp34;
// Intermediate terms (42)
const Scalar _tmp0 = 1 - 2 * std::pow(state(3, 0), Scalar(2));
const Scalar _tmp1 = _tmp0 - 2 * std::pow(state(2, 0), Scalar(2));
const Scalar _tmp2 = -state(22, 0) + state(4, 0);
const Scalar _tmp3 = 2 * state(0, 0);
const Scalar _tmp4 = _tmp3 * state(3, 0);
const Scalar _tmp5 = 2 * state(1, 0);
const Scalar _tmp6 = _tmp5 * state(2, 0);
const Scalar _tmp7 = _tmp4 + _tmp6;
const Scalar _tmp8 = -state(23, 0) + state(5, 0);
const Scalar _tmp9 = 2 * state(2, 0);
const Scalar _tmp10 = _tmp5 * state(3, 0) - _tmp9 * state(0, 0);
const Scalar _tmp11 = _tmp1 * _tmp2 + _tmp10 * state(6, 0) + _tmp7 * _tmp8;
const Scalar _tmp12 =
_tmp11 + epsilon * (2 * math::min<Scalar>(0, (((_tmp11) > 0) - ((_tmp11) < 0))) + 1);
const Scalar _tmp13 = Scalar(1.0) / (_tmp12);
const Scalar _tmp14 = _tmp0 - 2 * std::pow(state(1, 0), Scalar(2));
const Scalar _tmp15 = -_tmp4 + _tmp6;
const Scalar _tmp16 = _tmp5 * state(0, 0) + _tmp9 * state(3, 0);
const Scalar _tmp17 = _tmp14 * _tmp8 + _tmp15 * _tmp2 + _tmp16 * state(6, 0);
const Scalar _tmp18 = _tmp17 / std::pow(_tmp12, Scalar(2));
const Scalar _tmp19 = _tmp18 * _tmp7;
const Scalar _tmp20 = _tmp13 * _tmp14;
const Scalar _tmp21 = _tmp19 - _tmp20;
const Scalar _tmp22 = -_tmp10 * _tmp18 + _tmp13 * _tmp16;
const Scalar _tmp23 = _tmp1 * _tmp18;
const Scalar _tmp24 = _tmp13 * _tmp15;
const Scalar _tmp25 = -_tmp23 + _tmp24;
const Scalar _tmp26 = 2 * state(6, 0);
const Scalar _tmp27 = _tmp26 * state(0, 0);
const Scalar _tmp28 = _tmp26 * state(3, 0);
const Scalar _tmp29 =
(Scalar(1) / Scalar(2)) * _tmp13 * (_tmp2 * _tmp5 + _tmp28) -
Scalar(1) / Scalar(2) * _tmp18 * (-4 * _tmp2 * state(2, 0) - _tmp27 + _tmp5 * _tmp8);
const Scalar _tmp30 =
(Scalar(1) / Scalar(2)) * _tmp13 * (_tmp2 * _tmp9 + _tmp27 - 4 * _tmp8 * state(1, 0)) -
Scalar(1) / Scalar(2) * _tmp18 * (_tmp28 + _tmp8 * _tmp9);
const Scalar _tmp31 = 2 * state(3, 0);
const Scalar _tmp32 = _tmp26 * state(2, 0);
const Scalar _tmp33 = _tmp26 * state(1, 0);
const Scalar _tmp34 = (Scalar(1) / Scalar(2)) * _tmp13 * (-_tmp2 * _tmp31 + _tmp33) -
Scalar(1) / Scalar(2) * _tmp18 * (_tmp31 * _tmp8 - _tmp32);
const Scalar _tmp35 = 4 * state(3, 0);
const Scalar _tmp36 =
(Scalar(1) / Scalar(2)) * _tmp13 * (-_tmp2 * _tmp3 + _tmp32 - _tmp35 * _tmp8) -
Scalar(1) / Scalar(2) * _tmp18 * (-_tmp2 * _tmp35 + _tmp3 * _tmp8 + _tmp33);
const Scalar _tmp37 =
_tmp29 * state(1, 0) - _tmp30 * state(2, 0) - _tmp34 * state(3, 0) + _tmp36 * state(0, 0);
const Scalar _tmp38 =
_tmp17 * (_tmp10 * (_tmp20 - _tmp8) + _tmp4 * (_tmp0 + _tmp1 + _tmp33 + _tmp34) +
state(6, 0) * (_tmp11 + _tmp35)) -
_tmp27 * (_tmp10 * (_tmp36 + _tmp37) + _tmp25);
const Scalar _tmp39 = _tmp29 - _tmp30;
const Scalar _tmp40 = _tmp27 * _tmp9;
const Scalar _tmp41 = _tmp17 * _tmp19;
const Scalar _tmp42 = -_tmp40 + _tmp41;
const Scalar _tmp43 = _tmp27 * (_tmp10 * (-_tmp22 + _tmp23) + _tmp4 * (_tmp12 + _tmp35) +
state(6, 0) * (_tmp18 + _tmp33 + _tmp36));
const Scalar _tmp44 = _tmp40 - _tmp41;
const Scalar _tmp45 = _tmp17 * (_tmp10 * (_tmp22 - _tmp23) + _tmp4 * (_tmp11 + _tmp13) +
state(6, 0) * (-_tmp0 + _tmp1 + _tmp37));
-_tmp29 * state(3, 0) + _tmp30 * state(0, 0) - _tmp34 * state(1, 0) + _tmp36 * state(2, 0);
const Scalar _tmp39 =
_tmp29 * state(0, 0) + _tmp30 * state(3, 0) - _tmp34 * state(2, 0) - _tmp36 * state(1, 0);
const Scalar _tmp40 = _tmp23 - _tmp24;
const Scalar _tmp41 = -_tmp19 + _tmp20;
// Output terms (2)
if (innov != nullptr) {
Scalar& _innov = (*innov);
_innov = _tmp17 * _tmp26;
_innov = _tmp13 * _tmp17;
}
if (innov_var != nullptr) {
@ -100,22 +101,22 @@ void ComputeSideslipInnovAndInnovVar(const matrix::Matrix<Scalar, 24, 1>& state,
_innov_var =
R +
_tmp28 * (P(0, 5) * _tmp45 - P(1, 5) * _tmp43 + P(2, 5) * _tmp38 + P(21, 5) * _tmp39 +
P(22, 5) * _tmp44 + P(3, 5) * _tmp31 + P(4, 5) * _tmp42 + P(5, 5) * _tmp28) +
_tmp31 * (P(0, 3) * _tmp45 - P(1, 3) * _tmp43 + P(2, 3) * _tmp38 + P(21, 3) * _tmp39 +
P(22, 3) * _tmp44 + P(3, 3) * _tmp31 + P(4, 3) * _tmp42 + P(5, 3) * _tmp28) +
_tmp38 * (P(0, 2) * _tmp45 - P(1, 2) * _tmp43 + P(2, 2) * _tmp38 + P(21, 2) * _tmp39 +
P(22, 2) * _tmp44 + P(3, 2) * _tmp31 + P(4, 2) * _tmp42 + P(5, 2) * _tmp28) +
_tmp39 * (P(0, 21) * _tmp45 - P(1, 21) * _tmp43 + P(2, 21) * _tmp38 + P(21, 21) * _tmp39 +
P(22, 21) * _tmp44 + P(3, 21) * _tmp31 + P(4, 21) * _tmp42 + P(5, 21) * _tmp28) +
_tmp42 * (P(0, 4) * _tmp45 - P(1, 4) * _tmp43 + P(2, 4) * _tmp38 + P(21, 4) * _tmp39 +
P(22, 4) * _tmp44 + P(3, 4) * _tmp31 + P(4, 4) * _tmp42 + P(5, 4) * _tmp28) -
_tmp43 * (P(0, 1) * _tmp45 - P(1, 1) * _tmp43 + P(2, 1) * _tmp38 + P(21, 1) * _tmp39 +
P(22, 1) * _tmp44 + P(3, 1) * _tmp31 + P(4, 1) * _tmp42 + P(5, 1) * _tmp28) +
_tmp44 * (P(0, 22) * _tmp45 - P(1, 22) * _tmp43 + P(2, 22) * _tmp38 + P(21, 22) * _tmp39 +
P(22, 22) * _tmp44 + P(3, 22) * _tmp31 + P(4, 22) * _tmp42 + P(5, 22) * _tmp28) +
_tmp45 * (P(0, 0) * _tmp45 - P(1, 0) * _tmp43 + P(2, 0) * _tmp38 + P(21, 0) * _tmp39 +
P(22, 0) * _tmp44 + P(3, 0) * _tmp31 + P(4, 0) * _tmp42 + P(5, 0) * _tmp28);
_tmp21 * (P(0, 22) * _tmp38 + P(1, 22) * _tmp39 + P(2, 22) * _tmp37 + P(21, 22) * _tmp40 +
P(22, 22) * _tmp21 + P(3, 22) * _tmp25 + P(4, 22) * _tmp41 + P(5, 22) * _tmp22) +
_tmp22 * (P(0, 5) * _tmp38 + P(1, 5) * _tmp39 + P(2, 5) * _tmp37 + P(21, 5) * _tmp40 +
P(22, 5) * _tmp21 + P(3, 5) * _tmp25 + P(4, 5) * _tmp41 + P(5, 5) * _tmp22) +
_tmp25 * (P(0, 3) * _tmp38 + P(1, 3) * _tmp39 + P(2, 3) * _tmp37 + P(21, 3) * _tmp40 +
P(22, 3) * _tmp21 + P(3, 3) * _tmp25 + P(4, 3) * _tmp41 + P(5, 3) * _tmp22) +
_tmp37 * (P(0, 2) * _tmp38 + P(1, 2) * _tmp39 + P(2, 2) * _tmp37 + P(21, 2) * _tmp40 +
P(22, 2) * _tmp21 + P(3, 2) * _tmp25 + P(4, 2) * _tmp41 + P(5, 2) * _tmp22) +
_tmp38 * (P(0, 0) * _tmp38 + P(1, 0) * _tmp39 + P(2, 0) * _tmp37 + P(21, 0) * _tmp40 +
P(22, 0) * _tmp21 + P(3, 0) * _tmp25 + P(4, 0) * _tmp41 + P(5, 0) * _tmp22) +
_tmp39 * (P(0, 1) * _tmp38 + P(1, 1) * _tmp39 + P(2, 1) * _tmp37 + P(21, 1) * _tmp40 +
P(22, 1) * _tmp21 + P(3, 1) * _tmp25 + P(4, 1) * _tmp41 + P(5, 1) * _tmp22) +
_tmp40 * (P(0, 21) * _tmp38 + P(1, 21) * _tmp39 + P(2, 21) * _tmp37 + P(21, 21) * _tmp40 +
P(22, 21) * _tmp21 + P(3, 21) * _tmp25 + P(4, 21) * _tmp41 + P(5, 21) * _tmp22) +
_tmp41 * (P(0, 4) * _tmp38 + P(1, 4) * _tmp39 + P(2, 4) * _tmp37 + P(21, 4) * _tmp40 +
P(22, 4) * _tmp21 + P(3, 4) * _tmp25 + P(4, 4) * _tmp41 + P(5, 4) * _tmp22);
}
} // NOLINT(readability/fn_size)

View File

@ -29,25 +29,20 @@ void ComputeYawInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 36
// Total ops: 1
// Unused inputs
(void)state;
// Input arrays
// Intermediate terms (5)
const Scalar _tmp0 = 2 * state(2, 0);
const Scalar _tmp1 = 2 * state(1, 0);
const Scalar _tmp2 = -_tmp0 * state(0, 0) + _tmp1 * state(3, 0);
const Scalar _tmp3 = _tmp0 * state(3, 0) + _tmp1 * state(0, 0);
const Scalar _tmp4 = std::pow(state(0, 0), Scalar(2)) - std::pow(state(1, 0), Scalar(2)) -
std::pow(state(2, 0), Scalar(2)) + std::pow(state(3, 0), Scalar(2));
// Intermediate terms (0)
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = R + _tmp2 * (P(0, 0) * _tmp2 + P(1, 0) * _tmp3 + P(2, 0) * _tmp4) +
_tmp3 * (P(0, 1) * _tmp2 + P(1, 1) * _tmp3 + P(2, 1) * _tmp4) +
_tmp4 * (P(0, 2) * _tmp2 + P(1, 2) * _tmp3 + P(2, 2) * _tmp4);
_innov_var = P(2, 2) + R;
}
if (H != nullptr) {
@ -55,9 +50,7 @@ void ComputeYawInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
_h.setZero();
_h(0, 0) = _tmp2;
_h(1, 0) = _tmp3;
_h(2, 0) = _tmp4;
_h(2, 0) = 1;
}
} // NOLINT(readability/fn_size)

View File

@ -34,172 +34,211 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
const matrix::Matrix<Scalar, 3, 1>& accel_var,
const matrix::Matrix<Scalar, 3, 1>& gyro,
const Scalar gyro_var, const Scalar dt) {
// Total ops: 1793
// Total ops: 1754
// Unused inputs
(void)gyro;
// Input arrays
// Intermediate terms (134)
const Scalar _tmp0 = dt * gyro(1, 0);
const Scalar _tmp1 = dt * state(11, 0);
const Scalar _tmp2 = -_tmp0 + _tmp1;
const Scalar _tmp3 = dt * gyro(2, 0);
const Scalar _tmp4 = dt * state(12, 0);
const Scalar _tmp5 = _tmp3 - _tmp4;
const Scalar _tmp6 = P(0, 2) + P(1, 2) * _tmp5 + P(2, 2) * _tmp2 - P(9, 2) * dt;
const Scalar _tmp7 = P(0, 1) + P(1, 1) * _tmp5 + P(2, 1) * _tmp2 - P(9, 1) * dt;
const Scalar _tmp8 = P(0, 9) + P(1, 9) * _tmp5 + P(2, 9) * _tmp2 - P(9, 9) * dt;
const Scalar _tmp9 = std::pow(dt, Scalar(2));
const Scalar _tmp10 = _tmp9 * gyro_var;
const Scalar _tmp11 = P(0, 0) + P(1, 0) * _tmp5 + P(2, 0) * _tmp2 - P(9, 0) * dt;
const Scalar _tmp12 = P(0, 10) + P(1, 10) * _tmp5 + P(2, 10) * _tmp2 - P(9, 10) * dt;
const Scalar _tmp13 = -_tmp3 + _tmp4;
const Scalar _tmp14 = dt * gyro(0, 0);
const Scalar _tmp15 = dt * state(10, 0);
const Scalar _tmp16 = _tmp14 - _tmp15;
const Scalar _tmp17 = P(0, 10) * _tmp13 + P(1, 10) - P(10, 10) * dt + P(2, 10) * _tmp16;
const Scalar _tmp18 = P(0, 0) * _tmp13 + P(1, 0) - P(10, 0) * dt + P(2, 0) * _tmp16;
const Scalar _tmp19 = P(0, 2) * _tmp13 + P(1, 2) - P(10, 2) * dt + P(2, 2) * _tmp16;
const Scalar _tmp20 = P(0, 1) * _tmp13 + P(1, 1) - P(10, 1) * dt + P(2, 1) * _tmp16;
const Scalar _tmp21 = P(0, 11) + P(1, 11) * _tmp5 + P(2, 11) * _tmp2 - P(9, 11) * dt;
const Scalar _tmp22 = _tmp0 - _tmp1;
const Scalar _tmp23 = -_tmp14 + _tmp15;
const Scalar _tmp24 = P(0, 11) * _tmp13 + P(1, 11) - P(10, 11) * dt + P(2, 11) * _tmp16;
const Scalar _tmp25 = P(0, 11) * _tmp22 + P(1, 11) * _tmp23 - P(11, 11) * dt + P(2, 11);
const Scalar _tmp26 = P(0, 1) * _tmp22 + P(1, 1) * _tmp23 - P(11, 1) * dt + P(2, 1);
const Scalar _tmp27 = P(0, 0) * _tmp22 + P(1, 0) * _tmp23 - P(11, 0) * dt + P(2, 0);
const Scalar _tmp28 = P(0, 2) * _tmp22 + P(1, 2) * _tmp23 - P(11, 2) * dt + P(2, 2);
const Scalar _tmp29 = 2 * state(0, 0);
const Scalar _tmp30 = _tmp29 * state(3, 0);
const Scalar _tmp31 = -_tmp30;
const Scalar _tmp32 = 2 * state(1, 0);
const Scalar _tmp33 = _tmp32 * state(2, 0);
// Intermediate terms (147)
const Scalar _tmp0 = 2 * state(1, 0);
const Scalar _tmp1 = _tmp0 * state(3, 0);
const Scalar _tmp2 = -_tmp1 * dt;
const Scalar _tmp3 = 2 * state(0, 0);
const Scalar _tmp4 = _tmp3 * state(2, 0);
const Scalar _tmp5 = _tmp4 * dt;
const Scalar _tmp6 = _tmp2 - _tmp5;
const Scalar _tmp7 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp8 = _tmp7 * dt;
const Scalar _tmp9 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp10 = -_tmp9 * dt;
const Scalar _tmp11 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp12 = _tmp11 * dt;
const Scalar _tmp13 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp14 = _tmp13 * dt;
const Scalar _tmp15 = _tmp10 + _tmp12 - _tmp14 + _tmp8;
const Scalar _tmp16 = _tmp13 + _tmp7;
const Scalar _tmp17 = _tmp11 + _tmp9;
const Scalar _tmp18 = _tmp16 + _tmp17;
const Scalar _tmp19 = _tmp0 * state(2, 0);
const Scalar _tmp20 = -_tmp19 * dt;
const Scalar _tmp21 = _tmp3 * state(3, 0);
const Scalar _tmp22 = _tmp21 * dt;
const Scalar _tmp23 = _tmp20 + _tmp22;
const Scalar _tmp24 =
P(0, 11) * _tmp18 + P(10, 11) * _tmp23 + P(11, 11) * _tmp6 + P(9, 11) * _tmp15;
const Scalar _tmp25 =
P(0, 10) * _tmp18 + P(10, 10) * _tmp23 + P(11, 10) * _tmp6 + P(9, 10) * _tmp15;
const Scalar _tmp26 = P(0, 0) * _tmp18 + P(10, 0) * _tmp23 + P(11, 0) * _tmp6 + P(9, 0) * _tmp15;
const Scalar _tmp27 = P(0, 9) * _tmp18 + P(10, 9) * _tmp23 + P(11, 9) * _tmp6 + P(9, 9) * _tmp15;
const Scalar _tmp28 = _tmp10 + _tmp14;
const Scalar _tmp29 = -_tmp12 + _tmp28 + _tmp8;
const Scalar _tmp30 = _tmp0 * state(0, 0);
const Scalar _tmp31 = _tmp30 * dt;
const Scalar _tmp32 = 2 * state(2, 0) * state(3, 0);
const Scalar _tmp33 = -_tmp32 * dt;
const Scalar _tmp34 = _tmp31 + _tmp33;
const Scalar _tmp35 = accel(0, 0) - state(13, 0);
const Scalar _tmp36 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp37 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp38 = -_tmp37;
const Scalar _tmp39 = _tmp36 + _tmp38;
const Scalar _tmp40 = std::pow(state(0, 0), Scalar(2));
const Scalar _tmp41 = -_tmp40;
const Scalar _tmp42 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp43 = _tmp41 + _tmp42;
const Scalar _tmp44 = accel(1, 0) - state(14, 0);
const Scalar _tmp45 = dt * (_tmp34 * _tmp35 + _tmp44 * (_tmp39 + _tmp43));
const Scalar _tmp46 = P(0, 12) + P(1, 12) * _tmp5 + P(2, 12) * _tmp2 - P(9, 12) * dt;
const Scalar _tmp47 = -2 * _tmp42;
const Scalar _tmp48 = -2 * _tmp36;
const Scalar _tmp49 = _tmp47 + _tmp48 + 1;
const Scalar _tmp50 = _tmp49 * dt;
const Scalar _tmp51 = _tmp29 * state(2, 0);
const Scalar _tmp52 = -_tmp51;
const Scalar _tmp53 = _tmp32 * state(3, 0);
const Scalar _tmp54 = -_tmp53;
const Scalar _tmp55 = -_tmp42;
const Scalar _tmp56 = _tmp40 + _tmp55;
const Scalar _tmp57 = -_tmp36;
const Scalar _tmp58 = _tmp37 + _tmp57;
const Scalar _tmp59 = accel(2, 0) - state(15, 0);
const Scalar _tmp60 = dt * (_tmp35 * (_tmp52 + _tmp54) + _tmp59 * (_tmp56 + _tmp58));
const Scalar _tmp61 = _tmp51 + _tmp53;
const Scalar _tmp62 = -_tmp33;
const Scalar _tmp63 = dt * (_tmp44 * _tmp61 + _tmp59 * (_tmp30 + _tmp62));
const Scalar _tmp64 = P(0, 13) + P(1, 13) * _tmp5 + P(2, 13) * _tmp2 - P(9, 13) * dt;
const Scalar _tmp65 = _tmp34 * dt;
const Scalar _tmp66 = P(0, 14) + P(1, 14) * _tmp5 + P(2, 14) * _tmp2 - P(9, 14) * dt;
const Scalar _tmp67 = _tmp61 * dt;
const Scalar _tmp68 = P(0, 3) + P(1, 3) * _tmp5 + P(2, 3) * _tmp2 - P(9, 3) * dt;
const Scalar _tmp69 = P(0, 13) * _tmp13 + P(1, 13) - P(10, 13) * dt + P(2, 13) * _tmp16;
const Scalar _tmp70 = P(0, 14) * _tmp13 + P(1, 14) - P(10, 14) * dt + P(2, 14) * _tmp16;
const Scalar _tmp71 = P(0, 12) * _tmp13 + P(1, 12) - P(10, 12) * dt + P(2, 12) * _tmp16;
const Scalar _tmp72 = P(0, 3) * _tmp13 + P(1, 3) - P(10, 3) * dt + P(2, 3) * _tmp16;
const Scalar _tmp73 = P(0, 14) * _tmp22 + P(1, 14) * _tmp23 - P(11, 14) * dt + P(2, 14);
const Scalar _tmp74 = P(0, 13) * _tmp22 + P(1, 13) * _tmp23 - P(11, 13) * dt + P(2, 13);
const Scalar _tmp75 = P(0, 12) * _tmp22 + P(1, 12) * _tmp23 - P(11, 12) * dt + P(2, 12);
const Scalar _tmp76 = P(0, 3) * _tmp22 + P(1, 3) * _tmp23 - P(11, 3) * dt + P(2, 3);
const Scalar _tmp77 = P(0, 1) * _tmp63 + P(1, 1) * _tmp60 - P(12, 1) * _tmp50 -
P(13, 1) * _tmp65 - P(14, 1) * _tmp67 + P(2, 1) * _tmp45 + P(3, 1);
const Scalar _tmp78 = P(0, 14) * _tmp63 + P(1, 14) * _tmp60 - P(12, 14) * _tmp50 -
P(13, 14) * _tmp65 - P(14, 14) * _tmp67 + P(2, 14) * _tmp45 + P(3, 14);
const Scalar _tmp79 = P(0, 13) * _tmp63 + P(1, 13) * _tmp60 - P(12, 13) * _tmp50 -
P(13, 13) * _tmp65 - P(14, 13) * _tmp67 + P(2, 13) * _tmp45 + P(3, 13);
const Scalar _tmp80 = P(0, 0) * _tmp63 + P(1, 0) * _tmp60 - P(12, 0) * _tmp50 -
P(13, 0) * _tmp65 - P(14, 0) * _tmp67 + P(2, 0) * _tmp45 + P(3, 0);
const Scalar _tmp81 = _tmp9 * accel_var(0, 0);
const Scalar _tmp82 = P(0, 2) * _tmp63 + P(1, 2) * _tmp60 - P(12, 2) * _tmp50 -
P(13, 2) * _tmp65 - P(14, 2) * _tmp67 + P(2, 2) * _tmp45 + P(3, 2);
const Scalar _tmp83 = _tmp9 * accel_var(1, 0);
const Scalar _tmp84 = _tmp9 * accel_var(2, 0);
const Scalar _tmp85 = P(0, 12) * _tmp63 + P(1, 12) * _tmp60 - P(12, 12) * _tmp50 -
P(13, 12) * _tmp65 - P(14, 12) * _tmp67 + P(2, 12) * _tmp45 + P(3, 12);
const Scalar _tmp86 = P(0, 3) * _tmp63 + P(1, 3) * _tmp60 - P(12, 3) * _tmp50 -
P(13, 3) * _tmp65 - P(14, 3) * _tmp67 + P(2, 3) * _tmp45 + P(3, 3);
const Scalar _tmp87 = 2 * state(2, 0) * state(3, 0);
const Scalar _tmp88 = _tmp29 * state(1, 0);
const Scalar _tmp89 = -_tmp88;
const Scalar _tmp90 = _tmp87 + _tmp89;
const Scalar _tmp91 = dt * (_tmp44 * _tmp90 + _tmp59 * (_tmp43 + _tmp58));
const Scalar _tmp92 = dt * (_tmp35 * (_tmp39 + _tmp56) + _tmp44 * (_tmp31 + _tmp62));
const Scalar _tmp93 = 1 - 2 * _tmp37;
const Scalar _tmp94 = _tmp47 + _tmp93;
const Scalar _tmp95 = _tmp94 * dt;
const Scalar _tmp96 = _tmp90 * dt;
const Scalar _tmp97 = _tmp30 + _tmp33;
const Scalar _tmp98 = -_tmp87;
const Scalar _tmp99 = dt * (_tmp35 * (_tmp88 + _tmp98) + _tmp59 * _tmp97);
const Scalar _tmp100 = _tmp97 * dt;
const Scalar _tmp101 = P(0, 4) + P(1, 4) * _tmp5 + P(2, 4) * _tmp2 - P(9, 4) * dt;
const Scalar _tmp102 = P(0, 4) * _tmp13 + P(1, 4) - P(10, 4) * dt + P(2, 4) * _tmp16;
const Scalar _tmp103 = _tmp74 * dt;
const Scalar _tmp104 = P(0, 4) * _tmp22 + P(1, 4) * _tmp23 - P(11, 4) * dt + P(2, 4);
const Scalar _tmp105 = _tmp81 * _tmp97;
const Scalar _tmp106 = _tmp84 * _tmp90;
const Scalar _tmp107 = P(0, 4) * _tmp63 + P(1, 4) * _tmp60 - P(12, 4) * _tmp50 -
P(13, 4) * _tmp65 - P(14, 4) * _tmp67 + P(2, 4) * _tmp45 + P(3, 4);
const Scalar _tmp108 = P(0, 14) * _tmp91 + P(1, 14) * _tmp99 - P(12, 14) * _tmp100 -
P(13, 14) * _tmp95 - P(14, 14) * _tmp96 + P(2, 14) * _tmp92 + P(4, 14);
const Scalar _tmp109 = P(0, 0) * _tmp91 + P(1, 0) * _tmp99 - P(12, 0) * _tmp100 -
P(13, 0) * _tmp95 - P(14, 0) * _tmp96 + P(2, 0) * _tmp92 + P(4, 0);
const Scalar _tmp110 = P(0, 13) * _tmp91 + P(1, 13) * _tmp99 - P(12, 13) * _tmp100 -
P(13, 13) * _tmp95 - P(14, 13) * _tmp96 + P(2, 13) * _tmp92 + P(4, 13);
const Scalar _tmp111 = P(0, 12) * _tmp91 + P(1, 12) * _tmp99 - P(12, 12) * _tmp100 -
P(13, 12) * _tmp95 - P(14, 12) * _tmp96 + P(2, 12) * _tmp92 + P(4, 12);
const Scalar _tmp112 = P(0, 1) * _tmp91 + P(1, 1) * _tmp99 - P(12, 1) * _tmp100 -
P(13, 1) * _tmp95 - P(14, 1) * _tmp96 + P(2, 1) * _tmp92 + P(4, 1);
const Scalar _tmp113 = P(0, 2) * _tmp91 + P(1, 2) * _tmp99 - P(12, 2) * _tmp100 -
P(13, 2) * _tmp95 - P(14, 2) * _tmp96 + P(2, 2) * _tmp92 + P(4, 2);
const Scalar _tmp114 = P(0, 4) * _tmp91 + P(1, 4) * _tmp99 - P(12, 4) * _tmp100 -
P(13, 4) * _tmp95 - P(14, 4) * _tmp96 + P(2, 4) * _tmp92 + P(4, 4);
const Scalar _tmp115 =
dt * (_tmp44 * (_tmp38 + _tmp40 + _tmp42 + _tmp57) + _tmp59 * (_tmp89 + _tmp98));
const Scalar _tmp116 = _tmp48 + _tmp93;
const Scalar _tmp117 = _tmp116 * dt;
const Scalar _tmp118 = _tmp87 + _tmp88;
const Scalar _tmp119 = _tmp118 * dt;
const Scalar _tmp120 = dt * (_tmp118 * _tmp35 + _tmp44 * (_tmp51 + _tmp54));
const Scalar _tmp121 = _tmp52 + _tmp53;
const Scalar _tmp122 = dt * (_tmp121 * _tmp59 + _tmp35 * (_tmp36 + _tmp37 + _tmp41 + _tmp55));
const Scalar _tmp123 = _tmp121 * dt;
const Scalar _tmp124 = P(0, 5) + P(1, 5) * _tmp5 + P(2, 5) * _tmp2 - P(9, 5) * dt;
const Scalar _tmp125 = P(0, 5) * _tmp13 + P(1, 5) - P(10, 5) * dt + P(2, 5) * _tmp16;
const Scalar _tmp126 = P(0, 5) * _tmp22 + P(1, 5) * _tmp23 - P(11, 5) * dt + P(2, 5);
const Scalar _tmp127 = _tmp118 * _tmp83;
const Scalar _tmp128 = P(0, 5) * _tmp63 + P(1, 5) * _tmp60 - P(12, 5) * _tmp50 -
P(13, 5) * _tmp65 - P(14, 5) * _tmp67 + P(2, 5) * _tmp45 + P(3, 5);
const Scalar _tmp129 = P(0, 5) * _tmp91 + P(1, 5) * _tmp99 - P(12, 5) * _tmp100 -
P(13, 5) * _tmp95 - P(14, 5) * _tmp96 + P(2, 5) * _tmp92 + P(4, 5);
const Scalar _tmp130 = P(0, 13) * _tmp115 + P(1, 13) * _tmp122 - P(12, 13) * _tmp123 -
P(13, 13) * _tmp119 - P(14, 13) * _tmp117 + P(2, 13) * _tmp120 + P(5, 13);
const Scalar _tmp131 = P(0, 14) * _tmp115 + P(1, 14) * _tmp122 - P(12, 14) * _tmp123 -
P(13, 14) * _tmp119 - P(14, 14) * _tmp117 + P(2, 14) * _tmp120 + P(5, 14);
const Scalar _tmp132 = P(0, 12) * _tmp115 + P(1, 12) * _tmp122 - P(12, 12) * _tmp123 -
P(13, 12) * _tmp119 - P(14, 12) * _tmp117 + P(2, 12) * _tmp120 + P(5, 12);
const Scalar _tmp133 = P(0, 5) * _tmp115 + P(1, 5) * _tmp122 - P(12, 5) * _tmp123 -
P(13, 5) * _tmp119 - P(14, 5) * _tmp117 + P(2, 5) * _tmp120 + P(5, 5);
const Scalar _tmp35 = P(0, 1) * _tmp18 + P(10, 1) * _tmp23 + P(11, 1) * _tmp6 + P(9, 1) * _tmp15;
const Scalar _tmp36 = _tmp20 - _tmp22;
const Scalar _tmp37 = _tmp23 * gyro_var;
const Scalar _tmp38 = _tmp36 * gyro_var;
const Scalar _tmp39 = _tmp6 * gyro_var;
const Scalar _tmp40 =
P(1, 10) * _tmp18 + P(10, 10) * _tmp29 + P(11, 10) * _tmp34 + P(9, 10) * _tmp36;
const Scalar _tmp41 =
P(1, 11) * _tmp18 + P(10, 11) * _tmp29 + P(11, 11) * _tmp34 + P(9, 11) * _tmp36;
const Scalar _tmp42 = P(1, 9) * _tmp18 + P(10, 9) * _tmp29 + P(11, 9) * _tmp34 + P(9, 9) * _tmp36;
const Scalar _tmp43 = P(1, 1) * _tmp18 + P(10, 1) * _tmp29 + P(11, 1) * _tmp34 + P(9, 1) * _tmp36;
const Scalar _tmp44 = _tmp12 + _tmp28 - _tmp8;
const Scalar _tmp45 = -_tmp31 + _tmp33;
const Scalar _tmp46 = P(0, 2) * _tmp18 + P(10, 2) * _tmp23 + P(11, 2) * _tmp6 + P(9, 2) * _tmp15;
const Scalar _tmp47 = _tmp2 + _tmp5;
const Scalar _tmp48 = P(1, 2) * _tmp18 + P(10, 2) * _tmp29 + P(11, 2) * _tmp34 + P(9, 2) * _tmp36;
const Scalar _tmp49 =
P(10, 10) * _tmp45 + P(11, 10) * _tmp44 + P(2, 10) * _tmp18 + P(9, 10) * _tmp47;
const Scalar _tmp50 =
P(10, 11) * _tmp45 + P(11, 11) * _tmp44 + P(2, 11) * _tmp18 + P(9, 11) * _tmp47;
const Scalar _tmp51 = P(10, 2) * _tmp45 + P(11, 2) * _tmp44 + P(2, 2) * _tmp18 + P(9, 2) * _tmp47;
const Scalar _tmp52 = P(10, 9) * _tmp45 + P(11, 9) * _tmp44 + P(2, 9) * _tmp18 + P(9, 9) * _tmp47;
const Scalar _tmp53 =
P(0, 12) * _tmp18 + P(10, 12) * _tmp23 + P(11, 12) * _tmp6 + P(9, 12) * _tmp15;
const Scalar _tmp54 = -2 * _tmp7;
const Scalar _tmp55 = -2 * _tmp11;
const Scalar _tmp56 = _tmp54 + _tmp55 + 1;
const Scalar _tmp57 = _tmp56 * dt;
const Scalar _tmp58 =
P(0, 13) * _tmp18 + P(10, 13) * _tmp23 + P(11, 13) * _tmp6 + P(9, 13) * _tmp15;
const Scalar _tmp59 = -_tmp21;
const Scalar _tmp60 = _tmp19 + _tmp59;
const Scalar _tmp61 = _tmp60 * dt;
const Scalar _tmp62 =
P(0, 14) * _tmp18 + P(10, 14) * _tmp23 + P(11, 14) * _tmp6 + P(9, 14) * _tmp15;
const Scalar _tmp63 = _tmp1 + _tmp4;
const Scalar _tmp64 = _tmp63 * dt;
const Scalar _tmp65 = -_tmp4;
const Scalar _tmp66 = _tmp1 + _tmp65;
const Scalar _tmp67 = accel(0, 0) - state(13, 0);
const Scalar _tmp68 = -_tmp13;
const Scalar _tmp69 = _tmp68 + _tmp7;
const Scalar _tmp70 = -_tmp11;
const Scalar _tmp71 = _tmp70 + _tmp9;
const Scalar _tmp72 = accel(2, 0) - state(15, 0);
const Scalar _tmp73 = _tmp30 + _tmp32;
const Scalar _tmp74 = accel(1, 0) - state(14, 0);
const Scalar _tmp75 = dt * (_tmp66 * _tmp67 + _tmp72 * (_tmp69 + _tmp71) + _tmp73 * _tmp74);
const Scalar _tmp76 = -_tmp19;
const Scalar _tmp77 = -_tmp9;
const Scalar _tmp78 = -_tmp32;
const Scalar _tmp79 = dt * (_tmp67 * (_tmp59 + _tmp76) + _tmp72 * (_tmp30 + _tmp78) +
_tmp74 * (_tmp16 + _tmp70 + _tmp77));
const Scalar _tmp80 = P(0, 3) * _tmp18 + P(10, 3) * _tmp23 + P(11, 3) * _tmp6 + P(9, 3) * _tmp15;
const Scalar _tmp81 =
P(1, 12) * _tmp18 + P(10, 12) * _tmp29 + P(11, 12) * _tmp34 + P(9, 12) * _tmp36;
const Scalar _tmp82 =
P(1, 13) * _tmp18 + P(10, 13) * _tmp29 + P(11, 13) * _tmp34 + P(9, 13) * _tmp36;
const Scalar _tmp83 =
P(1, 14) * _tmp18 + P(10, 14) * _tmp29 + P(11, 14) * _tmp34 + P(9, 14) * _tmp36;
const Scalar _tmp84 = P(1, 3) * _tmp18 + P(10, 3) * _tmp29 + P(11, 3) * _tmp34 + P(9, 3) * _tmp36;
const Scalar _tmp85 =
P(10, 12) * _tmp45 + P(11, 12) * _tmp44 + P(2, 12) * _tmp18 + P(9, 12) * _tmp47;
const Scalar _tmp86 = P(10, 1) * _tmp45 + P(11, 1) * _tmp44 + P(2, 1) * _tmp18 + P(9, 1) * _tmp47;
const Scalar _tmp87 =
P(10, 13) * _tmp45 + P(11, 13) * _tmp44 + P(2, 13) * _tmp18 + P(9, 13) * _tmp47;
const Scalar _tmp88 =
P(10, 14) * _tmp45 + P(11, 14) * _tmp44 + P(2, 14) * _tmp18 + P(9, 14) * _tmp47;
const Scalar _tmp89 = P(10, 3) * _tmp45 + P(11, 3) * _tmp44 + P(2, 3) * _tmp18 + P(9, 3) * _tmp47;
const Scalar _tmp90 = P(1, 12) * _tmp75 - P(12, 12) * _tmp57 - P(13, 12) * _tmp61 -
P(14, 12) * _tmp64 + P(2, 12) * _tmp79 + P(3, 12);
const Scalar _tmp91 = P(1, 1) * _tmp75 - P(12, 1) * _tmp57 - P(13, 1) * _tmp61 -
P(14, 1) * _tmp64 + P(2, 1) * _tmp79 + P(3, 1);
const Scalar _tmp92 = P(1, 2) * _tmp75 - P(12, 2) * _tmp57 - P(13, 2) * _tmp61 -
P(14, 2) * _tmp64 + P(2, 2) * _tmp79 + P(3, 2);
const Scalar _tmp93 = P(1, 13) * _tmp75 - P(12, 13) * _tmp57 - P(13, 13) * _tmp61 -
P(14, 13) * _tmp64 + P(2, 13) * _tmp79 + P(3, 13);
const Scalar _tmp94 = P(1, 14) * _tmp75 - P(12, 14) * _tmp57 - P(13, 14) * _tmp61 -
P(14, 14) * _tmp64 + P(2, 14) * _tmp79 + P(3, 14);
const Scalar _tmp95 = std::pow(dt, Scalar(2));
const Scalar _tmp96 = _tmp95 * accel_var(0, 0);
const Scalar _tmp97 = _tmp95 * accel_var(1, 0);
const Scalar _tmp98 = _tmp95 * accel_var(2, 0);
const Scalar _tmp99 = P(1, 3) * _tmp75 - P(12, 3) * _tmp57 - P(13, 3) * _tmp61 -
P(14, 3) * _tmp64 + P(2, 3) * _tmp79 + P(3, 3);
const Scalar _tmp100 = 1 - 2 * _tmp13;
const Scalar _tmp101 = _tmp100 + _tmp54;
const Scalar _tmp102 = _tmp101 * dt;
const Scalar _tmp103 = -_tmp7;
const Scalar _tmp104 = _tmp103 + _tmp13;
const Scalar _tmp105 = dt * (_tmp60 * _tmp74 + _tmp63 * _tmp72 + _tmp67 * (_tmp104 + _tmp71));
const Scalar _tmp106 = -_tmp30;
const Scalar _tmp107 = _tmp106 + _tmp32;
const Scalar _tmp108 = _tmp107 * dt;
const Scalar _tmp109 = _tmp19 + _tmp21;
const Scalar _tmp110 = _tmp109 * dt;
const Scalar _tmp111 = -_tmp1;
const Scalar _tmp112 = _tmp11 + _tmp77;
const Scalar _tmp113 =
_tmp67 * (_tmp111 + _tmp4) + _tmp72 * (_tmp104 + _tmp112) + _tmp74 * (_tmp106 + _tmp78);
const Scalar _tmp114 = _tmp26 * dt;
const Scalar _tmp115 = P(0, 4) * _tmp18 + P(10, 4) * _tmp23 + P(11, 4) * _tmp6 + P(9, 4) * _tmp15;
const Scalar _tmp116 =
P(1, 0) * _tmp18 + P(10, 0) * _tmp29 + P(11, 0) * _tmp34 + P(9, 0) * _tmp36;
const Scalar _tmp117 = _tmp113 * dt;
const Scalar _tmp118 =
P(1, 4) * _tmp18 + P(10, 4) * _tmp29 + P(11, 4) * _tmp34 + P(9, 4) * _tmp36;
const Scalar _tmp119 =
P(10, 0) * _tmp45 + P(11, 0) * _tmp44 + P(2, 0) * _tmp18 + P(9, 0) * _tmp47;
const Scalar _tmp120 =
P(10, 4) * _tmp45 + P(11, 4) * _tmp44 + P(2, 4) * _tmp18 + P(9, 4) * _tmp47;
const Scalar _tmp121 = _tmp56 * _tmp96;
const Scalar _tmp122 = _tmp60 * _tmp97;
const Scalar _tmp123 = P(1, 0) * _tmp75 - P(12, 0) * _tmp57 - P(13, 0) * _tmp61 -
P(14, 0) * _tmp64 + P(2, 0) * _tmp79 + P(3, 0);
const Scalar _tmp124 = _tmp63 * _tmp98;
const Scalar _tmp125 = P(1, 4) * _tmp75 - P(12, 4) * _tmp57 - P(13, 4) * _tmp61 -
P(14, 4) * _tmp64 + P(2, 4) * _tmp79 + P(3, 4);
const Scalar _tmp126 = P(0, 0) * _tmp117 - P(12, 0) * _tmp110 - P(13, 0) * _tmp102 -
P(14, 0) * _tmp108 + P(2, 0) * _tmp105 + P(4, 0);
const Scalar _tmp127 = P(0, 13) * _tmp117 - P(12, 13) * _tmp110 - P(13, 13) * _tmp102 -
P(14, 13) * _tmp108 + P(2, 13) * _tmp105 + P(4, 13);
const Scalar _tmp128 = P(0, 14) * _tmp117 - P(12, 14) * _tmp110 - P(13, 14) * _tmp102 -
P(14, 14) * _tmp108 + P(2, 14) * _tmp105 + P(4, 14);
const Scalar _tmp129 = P(0, 12) * _tmp117 - P(12, 12) * _tmp110 - P(13, 12) * _tmp102 -
P(14, 12) * _tmp108 + P(2, 12) * _tmp105 + P(4, 12);
const Scalar _tmp130 = P(0, 4) * _tmp117 - P(12, 4) * _tmp110 - P(13, 4) * _tmp102 -
P(14, 4) * _tmp108 + P(2, 4) * _tmp105 + P(4, 4);
const Scalar _tmp131 = _tmp100 + _tmp55;
const Scalar _tmp132 = _tmp131 * dt;
const Scalar _tmp133 =
dt * (_tmp67 * (_tmp112 + _tmp69) + _tmp72 * (_tmp111 + _tmp65) + _tmp74 * (_tmp21 + _tmp76));
const Scalar _tmp134 = _tmp73 * dt;
const Scalar _tmp135 = _tmp66 * dt;
const Scalar _tmp136 = _tmp107 * _tmp72 + _tmp109 * _tmp67 + _tmp74 * (_tmp103 + _tmp17 + _tmp68);
const Scalar _tmp137 = P(0, 5) * _tmp18 + P(10, 5) * _tmp23 + P(11, 5) * _tmp6 + P(9, 5) * _tmp15;
const Scalar _tmp138 = _tmp136 * dt;
const Scalar _tmp139 =
P(1, 5) * _tmp18 + P(10, 5) * _tmp29 + P(11, 5) * _tmp34 + P(9, 5) * _tmp36;
const Scalar _tmp140 =
P(10, 5) * _tmp45 + P(11, 5) * _tmp44 + P(2, 5) * _tmp18 + P(9, 5) * _tmp47;
const Scalar _tmp141 = P(1, 5) * _tmp75 - P(12, 5) * _tmp57 - P(13, 5) * _tmp61 -
P(14, 5) * _tmp64 + P(2, 5) * _tmp79 + P(3, 5);
const Scalar _tmp142 = P(0, 5) * _tmp117 - P(12, 5) * _tmp110 - P(13, 5) * _tmp102 -
P(14, 5) * _tmp108 + P(2, 5) * _tmp105 + P(4, 5);
const Scalar _tmp143 = P(0, 14) * _tmp138 + P(1, 14) * _tmp133 - P(12, 14) * _tmp135 -
P(13, 14) * _tmp134 - P(14, 14) * _tmp132 + P(5, 14);
const Scalar _tmp144 = P(0, 13) * _tmp138 + P(1, 13) * _tmp133 - P(12, 13) * _tmp135 -
P(13, 13) * _tmp134 - P(14, 13) * _tmp132 + P(5, 13);
const Scalar _tmp145 = P(0, 12) * _tmp138 + P(1, 12) * _tmp133 - P(12, 12) * _tmp135 -
P(13, 12) * _tmp134 - P(14, 12) * _tmp132 + P(5, 12);
const Scalar _tmp146 = P(0, 5) * _tmp138 + P(1, 5) * _tmp133 - P(12, 5) * _tmp135 -
P(13, 5) * _tmp134 - P(14, 5) * _tmp132 + P(5, 5);
// Output terms (1)
matrix::Matrix<Scalar, 23, 23> _res;
_res(0, 0) = _tmp10 + _tmp11 + _tmp2 * _tmp6 + _tmp5 * _tmp7 - _tmp8 * dt;
_res(0, 0) = std::pow(_tmp15, Scalar(2)) * gyro_var + _tmp15 * _tmp27 + _tmp18 * _tmp26 +
std::pow(_tmp23, Scalar(2)) * gyro_var + _tmp23 * _tmp25 + _tmp24 * _tmp6 +
std::pow(_tmp6, Scalar(2)) * gyro_var;
_res(1, 0) = 0;
_res(2, 0) = 0;
_res(3, 0) = 0;
@ -222,8 +261,11 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 0) = 0;
_res(21, 0) = 0;
_res(22, 0) = 0;
_res(0, 1) = _tmp11 * _tmp13 - _tmp12 * dt + _tmp16 * _tmp6 + _tmp7;
_res(1, 1) = _tmp10 + _tmp13 * _tmp18 + _tmp16 * _tmp19 - _tmp17 * dt + _tmp20;
_res(0, 1) = _tmp15 * _tmp38 + _tmp18 * _tmp35 + _tmp24 * _tmp34 + _tmp25 * _tmp29 +
_tmp27 * _tmp36 + _tmp29 * _tmp37 + _tmp34 * _tmp39;
_res(1, 1) = _tmp18 * _tmp43 + std::pow(_tmp29, Scalar(2)) * gyro_var + _tmp29 * _tmp40 +
std::pow(_tmp34, Scalar(2)) * gyro_var + _tmp34 * _tmp41 +
std::pow(_tmp36, Scalar(2)) * gyro_var + _tmp36 * _tmp42;
_res(2, 1) = 0;
_res(3, 1) = 0;
_res(4, 1) = 0;
@ -245,9 +287,13 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 1) = 0;
_res(21, 1) = 0;
_res(22, 1) = 0;
_res(0, 2) = _tmp11 * _tmp22 - _tmp21 * dt + _tmp23 * _tmp7 + _tmp6;
_res(1, 2) = _tmp18 * _tmp22 + _tmp19 + _tmp20 * _tmp23 - _tmp24 * dt;
_res(2, 2) = _tmp10 + _tmp22 * _tmp27 + _tmp23 * _tmp26 - _tmp25 * dt + _tmp28;
_res(0, 2) = _tmp15 * _tmp47 * gyro_var + _tmp18 * _tmp46 + _tmp24 * _tmp44 + _tmp25 * _tmp45 +
_tmp27 * _tmp47 + _tmp37 * _tmp45 + _tmp39 * _tmp44;
_res(1, 2) = _tmp18 * _tmp48 + _tmp29 * _tmp45 * gyro_var + _tmp34 * _tmp44 * gyro_var +
_tmp38 * _tmp47 + _tmp40 * _tmp45 + _tmp41 * _tmp44 + _tmp42 * _tmp47;
_res(2, 2) = _tmp18 * _tmp51 + std::pow(_tmp44, Scalar(2)) * gyro_var + _tmp44 * _tmp50 +
std::pow(_tmp45, Scalar(2)) * gyro_var + _tmp45 * _tmp49 +
std::pow(_tmp47, Scalar(2)) * gyro_var + _tmp47 * _tmp52;
_res(3, 2) = 0;
_res(4, 2) = 0;
_res(5, 2) = 0;
@ -268,16 +314,16 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 2) = 0;
_res(21, 2) = 0;
_res(22, 2) = 0;
_res(0, 3) = _tmp11 * _tmp63 + _tmp45 * _tmp6 - _tmp46 * _tmp50 + _tmp60 * _tmp7 -
_tmp64 * _tmp65 - _tmp66 * _tmp67 + _tmp68;
_res(1, 3) = _tmp18 * _tmp63 + _tmp19 * _tmp45 + _tmp20 * _tmp60 - _tmp50 * _tmp71 -
_tmp65 * _tmp69 - _tmp67 * _tmp70 + _tmp72;
_res(2, 3) = _tmp26 * _tmp60 + _tmp27 * _tmp63 + _tmp28 * _tmp45 - _tmp50 * _tmp75 -
_tmp65 * _tmp74 - _tmp67 * _tmp73 + _tmp76;
_res(3, 3) = std::pow(_tmp34, Scalar(2)) * _tmp83 + _tmp45 * _tmp82 +
std::pow(_tmp49, Scalar(2)) * _tmp81 - _tmp50 * _tmp85 + _tmp60 * _tmp77 +
std::pow(_tmp61, Scalar(2)) * _tmp84 + _tmp63 * _tmp80 - _tmp65 * _tmp79 -
_tmp67 * _tmp78 + _tmp86;
_res(0, 3) = _tmp35 * _tmp75 + _tmp46 * _tmp79 - _tmp53 * _tmp57 - _tmp58 * _tmp61 -
_tmp62 * _tmp64 + _tmp80;
_res(1, 3) = _tmp43 * _tmp75 + _tmp48 * _tmp79 - _tmp57 * _tmp81 - _tmp61 * _tmp82 -
_tmp64 * _tmp83 + _tmp84;
_res(2, 3) = _tmp51 * _tmp79 - _tmp57 * _tmp85 - _tmp61 * _tmp87 - _tmp64 * _tmp88 +
_tmp75 * _tmp86 + _tmp89;
_res(3, 3) = std::pow(_tmp56, Scalar(2)) * _tmp96 - _tmp57 * _tmp90 +
std::pow(_tmp60, Scalar(2)) * _tmp97 - _tmp61 * _tmp93 +
std::pow(_tmp63, Scalar(2)) * _tmp98 - _tmp64 * _tmp94 + _tmp75 * _tmp91 +
_tmp79 * _tmp92 + _tmp99;
_res(4, 3) = 0;
_res(5, 3) = 0;
_res(6, 3) = 0;
@ -297,19 +343,21 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 3) = 0;
_res(21, 3) = 0;
_res(22, 3) = 0;
_res(0, 4) = -_tmp100 * _tmp46 + _tmp101 + _tmp11 * _tmp91 + _tmp6 * _tmp92 - _tmp64 * _tmp95 -
_tmp66 * _tmp96 + _tmp7 * _tmp99;
_res(1, 4) = -_tmp100 * _tmp71 + _tmp102 + _tmp18 * _tmp91 + _tmp19 * _tmp92 + _tmp20 * _tmp99 -
_tmp69 * _tmp95 - _tmp70 * _tmp96;
_res(2, 4) = -_tmp100 * _tmp75 - _tmp103 * _tmp94 + _tmp104 + _tmp26 * _tmp99 + _tmp27 * _tmp91 +
_tmp28 * _tmp92 - _tmp73 * _tmp96;
_res(3, 4) = -_tmp100 * _tmp85 + _tmp105 * _tmp49 + _tmp106 * _tmp61 + _tmp107 +
_tmp34 * _tmp83 * _tmp94 + _tmp77 * _tmp99 - _tmp78 * _tmp96 - _tmp79 * _tmp95 +
_tmp80 * _tmp91 + _tmp82 * _tmp92;
_res(4, 4) = -_tmp100 * _tmp111 - _tmp108 * _tmp96 + _tmp109 * _tmp91 - _tmp110 * _tmp95 +
_tmp112 * _tmp99 + _tmp113 * _tmp92 + _tmp114 +
_tmp81 * std::pow(_tmp97, Scalar(2)) + _tmp83 * std::pow(_tmp94, Scalar(2)) +
_tmp84 * std::pow(_tmp90, Scalar(2));
_res(0, 4) = -_tmp102 * _tmp58 + _tmp105 * _tmp46 - _tmp108 * _tmp62 - _tmp110 * _tmp53 +
_tmp113 * _tmp114 + _tmp115;
_res(1, 4) = -_tmp102 * _tmp82 + _tmp105 * _tmp48 - _tmp108 * _tmp83 - _tmp110 * _tmp81 +
_tmp116 * _tmp117 + _tmp118;
_res(2, 4) = -_tmp102 * _tmp87 + _tmp105 * _tmp51 - _tmp108 * _tmp88 - _tmp110 * _tmp85 +
_tmp117 * _tmp119 + _tmp120;
_res(3, 4) = _tmp101 * _tmp122 - _tmp102 * _tmp93 + _tmp105 * _tmp92 + _tmp107 * _tmp124 -
_tmp108 * _tmp94 + _tmp109 * _tmp121 - _tmp110 * _tmp90 + _tmp117 * _tmp123 +
_tmp125;
_res(4, 4) = std::pow(_tmp101, Scalar(2)) * _tmp97 - _tmp102 * _tmp127 +
_tmp105 * (P(0, 2) * _tmp117 - P(12, 2) * _tmp110 - P(13, 2) * _tmp102 -
P(14, 2) * _tmp108 + P(2, 2) * _tmp105 + P(4, 2)) +
std::pow(_tmp107, Scalar(2)) * _tmp98 - _tmp108 * _tmp128 +
std::pow(_tmp109, Scalar(2)) * _tmp96 - _tmp110 * _tmp129 + _tmp117 * _tmp126 +
_tmp130;
_res(5, 4) = 0;
_res(6, 4) = 0;
_res(7, 4) = 0;
@ -328,28 +376,27 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 4) = 0;
_res(21, 4) = 0;
_res(22, 4) = 0;
_res(0, 5) = _tmp11 * _tmp115 - _tmp117 * _tmp66 - _tmp119 * _tmp64 + _tmp120 * _tmp6 +
_tmp122 * _tmp7 - _tmp123 * _tmp46 + _tmp124;
_res(1, 5) = _tmp115 * _tmp18 - _tmp117 * _tmp70 - _tmp119 * _tmp69 + _tmp120 * _tmp19 +
_tmp122 * _tmp20 - _tmp123 * _tmp71 + _tmp125;
_res(2, 5) = -_tmp103 * _tmp118 + _tmp115 * _tmp27 - _tmp117 * _tmp73 + _tmp120 * _tmp28 +
_tmp122 * _tmp26 - _tmp123 * _tmp75 + _tmp126;
_res(3, 5) = _tmp115 * _tmp80 + _tmp116 * _tmp61 * _tmp84 - _tmp117 * _tmp78 - _tmp119 * _tmp79 +
_tmp120 * _tmp82 + _tmp121 * _tmp49 * _tmp81 + _tmp122 * _tmp77 - _tmp123 * _tmp85 +
_tmp127 * _tmp34 + _tmp128;
_res(4, 5) = _tmp105 * _tmp121 + _tmp106 * _tmp116 - _tmp108 * _tmp117 + _tmp109 * _tmp115 -
_tmp110 * _tmp119 - _tmp111 * _tmp123 + _tmp112 * _tmp122 + _tmp113 * _tmp120 +
_tmp127 * _tmp94 + _tmp129;
_res(5, 5) = _tmp115 * (P(0, 0) * _tmp115 + P(1, 0) * _tmp122 - P(12, 0) * _tmp123 -
P(13, 0) * _tmp119 - P(14, 0) * _tmp117 + P(2, 0) * _tmp120 + P(5, 0)) +
std::pow(_tmp116, Scalar(2)) * _tmp84 - _tmp117 * _tmp131 +
std::pow(_tmp118, Scalar(2)) * _tmp83 - _tmp119 * _tmp130 +
_tmp120 * (P(0, 2) * _tmp115 + P(1, 2) * _tmp122 - P(12, 2) * _tmp123 -
P(13, 2) * _tmp119 - P(14, 2) * _tmp117 + P(2, 2) * _tmp120 + P(5, 2)) +
std::pow(_tmp121, Scalar(2)) * _tmp81 +
_tmp122 * (P(0, 1) * _tmp115 + P(1, 1) * _tmp122 - P(12, 1) * _tmp123 -
P(13, 1) * _tmp119 - P(14, 1) * _tmp117 + P(2, 1) * _tmp120 + P(5, 1)) -
_tmp123 * _tmp132 + _tmp133;
_res(0, 5) = _tmp114 * _tmp136 - _tmp132 * _tmp62 + _tmp133 * _tmp35 - _tmp134 * _tmp58 -
_tmp135 * _tmp53 + _tmp137;
_res(1, 5) = _tmp116 * _tmp138 - _tmp132 * _tmp83 + _tmp133 * _tmp43 - _tmp134 * _tmp82 -
_tmp135 * _tmp81 + _tmp139;
_res(2, 5) = _tmp119 * _tmp138 - _tmp132 * _tmp88 + _tmp133 * _tmp86 - _tmp134 * _tmp87 -
_tmp135 * _tmp85 + _tmp140;
_res(3, 5) = _tmp121 * _tmp66 + _tmp122 * _tmp73 + _tmp123 * _tmp138 + _tmp124 * _tmp131 -
_tmp132 * _tmp94 + _tmp133 * _tmp91 - _tmp134 * _tmp93 - _tmp135 * _tmp90 + _tmp141;
_res(4, 5) = _tmp101 * _tmp73 * _tmp97 + _tmp107 * _tmp131 * _tmp98 + _tmp109 * _tmp66 * _tmp96 +
_tmp126 * _tmp138 - _tmp127 * _tmp134 - _tmp128 * _tmp132 - _tmp129 * _tmp135 +
_tmp133 * (P(0, 1) * _tmp117 - P(12, 1) * _tmp110 - P(13, 1) * _tmp102 -
P(14, 1) * _tmp108 + P(2, 1) * _tmp105 + P(4, 1)) +
_tmp142;
_res(5, 5) = std::pow(_tmp131, Scalar(2)) * _tmp98 - _tmp132 * _tmp143 +
_tmp133 * (P(0, 1) * _tmp138 + P(1, 1) * _tmp133 - P(12, 1) * _tmp135 -
P(13, 1) * _tmp134 - P(14, 1) * _tmp132 + P(5, 1)) -
_tmp134 * _tmp144 - _tmp135 * _tmp145 +
_tmp138 * (P(0, 0) * _tmp138 + P(1, 0) * _tmp133 - P(12, 0) * _tmp135 -
P(13, 0) * _tmp134 - P(14, 0) * _tmp132 + P(5, 0)) +
_tmp146 + std::pow(_tmp66, Scalar(2)) * _tmp96 +
std::pow(_tmp73, Scalar(2)) * _tmp97;
_res(6, 5) = 0;
_res(7, 5) = 0;
_res(8, 5) = 0;
@ -367,19 +414,22 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 5) = 0;
_res(21, 5) = 0;
_res(22, 5) = 0;
_res(0, 6) = P(0, 6) + P(1, 6) * _tmp5 + P(2, 6) * _tmp2 - P(9, 6) * dt + _tmp68 * dt;
_res(1, 6) = P(0, 6) * _tmp13 + P(1, 6) - P(10, 6) * dt + P(2, 6) * _tmp16 + _tmp72 * dt;
_res(2, 6) = P(0, 6) * _tmp22 + P(1, 6) * _tmp23 - P(11, 6) * dt + P(2, 6) + _tmp76 * dt;
_res(3, 6) = P(0, 6) * _tmp63 + P(1, 6) * _tmp60 - P(12, 6) * _tmp50 - P(13, 6) * _tmp65 -
P(14, 6) * _tmp67 + P(2, 6) * _tmp45 + P(3, 6) + _tmp86 * dt;
_res(4, 6) = P(0, 6) * _tmp91 + P(1, 6) * _tmp99 - P(12, 6) * _tmp100 - P(13, 6) * _tmp95 -
P(14, 6) * _tmp96 + P(2, 6) * _tmp92 + P(4, 6) +
dt * (P(0, 3) * _tmp91 + P(1, 3) * _tmp99 - P(12, 3) * _tmp100 - P(13, 3) * _tmp95 -
P(14, 3) * _tmp96 + P(2, 3) * _tmp92 + P(4, 3));
_res(5, 6) = P(0, 6) * _tmp115 + P(1, 6) * _tmp122 - P(12, 6) * _tmp123 - P(13, 6) * _tmp119 -
P(14, 6) * _tmp117 + P(2, 6) * _tmp120 + P(5, 6) +
dt * (P(0, 3) * _tmp115 + P(1, 3) * _tmp122 - P(12, 3) * _tmp123 -
P(13, 3) * _tmp119 - P(14, 3) * _tmp117 + P(2, 3) * _tmp120 + P(5, 3));
_res(0, 6) =
P(0, 6) * _tmp18 + P(10, 6) * _tmp23 + P(11, 6) * _tmp6 + P(9, 6) * _tmp15 + _tmp80 * dt;
_res(1, 6) =
P(1, 6) * _tmp18 + P(10, 6) * _tmp29 + P(11, 6) * _tmp34 + P(9, 6) * _tmp36 + _tmp84 * dt;
_res(2, 6) =
P(10, 6) * _tmp45 + P(11, 6) * _tmp44 + P(2, 6) * _tmp18 + P(9, 6) * _tmp47 + _tmp89 * dt;
_res(3, 6) = P(1, 6) * _tmp75 - P(12, 6) * _tmp57 - P(13, 6) * _tmp61 - P(14, 6) * _tmp64 +
P(2, 6) * _tmp79 + P(3, 6) + _tmp99 * dt;
_res(4, 6) = P(0, 6) * _tmp117 - P(12, 6) * _tmp110 - P(13, 6) * _tmp102 - P(14, 6) * _tmp108 +
P(2, 6) * _tmp105 + P(4, 6) +
dt * (P(0, 3) * _tmp117 - P(12, 3) * _tmp110 - P(13, 3) * _tmp102 -
P(14, 3) * _tmp108 + P(2, 3) * _tmp105 + P(4, 3));
_res(5, 6) = P(0, 6) * _tmp138 + P(1, 6) * _tmp133 - P(12, 6) * _tmp135 - P(13, 6) * _tmp134 -
P(14, 6) * _tmp132 + P(5, 6) +
dt * (P(0, 3) * _tmp138 + P(1, 3) * _tmp133 - P(12, 3) * _tmp135 -
P(13, 3) * _tmp134 - P(14, 3) * _tmp132 + P(5, 3));
_res(6, 6) = P(3, 6) * dt + P(6, 6) + dt * (P(3, 3) * dt + P(6, 3));
_res(7, 6) = 0;
_res(8, 6) = 0;
@ -397,17 +447,20 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 6) = 0;
_res(21, 6) = 0;
_res(22, 6) = 0;
_res(0, 7) = P(0, 7) + P(1, 7) * _tmp5 + P(2, 7) * _tmp2 - P(9, 7) * dt + _tmp101 * dt;
_res(1, 7) = P(0, 7) * _tmp13 + P(1, 7) - P(10, 7) * dt + P(2, 7) * _tmp16 + _tmp102 * dt;
_res(2, 7) = P(0, 7) * _tmp22 + P(1, 7) * _tmp23 - P(11, 7) * dt + P(2, 7) + _tmp104 * dt;
_res(3, 7) = P(0, 7) * _tmp63 + P(1, 7) * _tmp60 - P(12, 7) * _tmp50 - P(13, 7) * _tmp65 -
P(14, 7) * _tmp67 + P(2, 7) * _tmp45 + P(3, 7) + _tmp107 * dt;
_res(4, 7) = P(0, 7) * _tmp91 + P(1, 7) * _tmp99 - P(12, 7) * _tmp100 - P(13, 7) * _tmp95 -
P(14, 7) * _tmp96 + P(2, 7) * _tmp92 + P(4, 7) + _tmp114 * dt;
_res(5, 7) = P(0, 7) * _tmp115 + P(1, 7) * _tmp122 - P(12, 7) * _tmp123 - P(13, 7) * _tmp119 -
P(14, 7) * _tmp117 + P(2, 7) * _tmp120 + P(5, 7) +
dt * (P(0, 4) * _tmp115 + P(1, 4) * _tmp122 - P(12, 4) * _tmp123 -
P(13, 4) * _tmp119 - P(14, 4) * _tmp117 + P(2, 4) * _tmp120 + P(5, 4));
_res(0, 7) =
P(0, 7) * _tmp18 + P(10, 7) * _tmp23 + P(11, 7) * _tmp6 + P(9, 7) * _tmp15 + _tmp115 * dt;
_res(1, 7) =
P(1, 7) * _tmp18 + P(10, 7) * _tmp29 + P(11, 7) * _tmp34 + P(9, 7) * _tmp36 + _tmp118 * dt;
_res(2, 7) =
P(10, 7) * _tmp45 + P(11, 7) * _tmp44 + P(2, 7) * _tmp18 + P(9, 7) * _tmp47 + _tmp120 * dt;
_res(3, 7) = P(1, 7) * _tmp75 - P(12, 7) * _tmp57 - P(13, 7) * _tmp61 - P(14, 7) * _tmp64 +
P(2, 7) * _tmp79 + P(3, 7) + _tmp125 * dt;
_res(4, 7) = P(0, 7) * _tmp117 - P(12, 7) * _tmp110 - P(13, 7) * _tmp102 - P(14, 7) * _tmp108 +
P(2, 7) * _tmp105 + P(4, 7) + _tmp130 * dt;
_res(5, 7) = P(0, 7) * _tmp138 + P(1, 7) * _tmp133 - P(12, 7) * _tmp135 - P(13, 7) * _tmp134 -
P(14, 7) * _tmp132 + P(5, 7) +
dt * (P(0, 4) * _tmp138 + P(1, 4) * _tmp133 - P(12, 4) * _tmp135 -
P(13, 4) * _tmp134 - P(14, 4) * _tmp132 + P(5, 4));
_res(6, 7) = P(3, 7) * dt + P(6, 7) + dt * (P(3, 4) * dt + P(6, 4));
_res(7, 7) = P(4, 7) * dt + P(7, 7) + dt * (P(4, 4) * dt + P(7, 4));
_res(8, 7) = 0;
@ -425,15 +478,18 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 7) = 0;
_res(21, 7) = 0;
_res(22, 7) = 0;
_res(0, 8) = P(0, 8) + P(1, 8) * _tmp5 + P(2, 8) * _tmp2 - P(9, 8) * dt + _tmp124 * dt;
_res(1, 8) = P(0, 8) * _tmp13 + P(1, 8) - P(10, 8) * dt + P(2, 8) * _tmp16 + _tmp125 * dt;
_res(2, 8) = P(0, 8) * _tmp22 + P(1, 8) * _tmp23 - P(11, 8) * dt + P(2, 8) + _tmp126 * dt;
_res(3, 8) = P(0, 8) * _tmp63 + P(1, 8) * _tmp60 - P(12, 8) * _tmp50 - P(13, 8) * _tmp65 -
P(14, 8) * _tmp67 + P(2, 8) * _tmp45 + P(3, 8) + _tmp128 * dt;
_res(4, 8) = P(0, 8) * _tmp91 + P(1, 8) * _tmp99 - P(12, 8) * _tmp100 - P(13, 8) * _tmp95 -
P(14, 8) * _tmp96 + P(2, 8) * _tmp92 + P(4, 8) + _tmp129 * dt;
_res(5, 8) = P(0, 8) * _tmp115 + P(1, 8) * _tmp122 - P(12, 8) * _tmp123 - P(13, 8) * _tmp119 -
P(14, 8) * _tmp117 + P(2, 8) * _tmp120 + P(5, 8) + _tmp133 * dt;
_res(0, 8) =
P(0, 8) * _tmp18 + P(10, 8) * _tmp23 + P(11, 8) * _tmp6 + P(9, 8) * _tmp15 + _tmp137 * dt;
_res(1, 8) =
P(1, 8) * _tmp18 + P(10, 8) * _tmp29 + P(11, 8) * _tmp34 + P(9, 8) * _tmp36 + _tmp139 * dt;
_res(2, 8) =
P(10, 8) * _tmp45 + P(11, 8) * _tmp44 + P(2, 8) * _tmp18 + P(9, 8) * _tmp47 + _tmp140 * dt;
_res(3, 8) = P(1, 8) * _tmp75 - P(12, 8) * _tmp57 - P(13, 8) * _tmp61 - P(14, 8) * _tmp64 +
P(2, 8) * _tmp79 + P(3, 8) + _tmp141 * dt;
_res(4, 8) = P(0, 8) * _tmp117 - P(12, 8) * _tmp110 - P(13, 8) * _tmp102 - P(14, 8) * _tmp108 +
P(2, 8) * _tmp105 + P(4, 8) + _tmp142 * dt;
_res(5, 8) = P(0, 8) * _tmp138 + P(1, 8) * _tmp133 - P(12, 8) * _tmp135 - P(13, 8) * _tmp134 -
P(14, 8) * _tmp132 + P(5, 8) + _tmp146 * dt;
_res(6, 8) = P(3, 8) * dt + P(6, 8) + dt * (P(3, 5) * dt + P(6, 5));
_res(7, 8) = P(4, 8) * dt + P(7, 8) + dt * (P(4, 5) * dt + P(7, 5));
_res(8, 8) = P(5, 8) * dt + P(8, 8) + dt * (P(5, 5) * dt + P(8, 5));
@ -451,15 +507,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 8) = 0;
_res(21, 8) = 0;
_res(22, 8) = 0;
_res(0, 9) = _tmp8;
_res(1, 9) = P(0, 9) * _tmp13 + P(1, 9) - P(10, 9) * dt + P(2, 9) * _tmp16;
_res(2, 9) = P(0, 9) * _tmp22 + P(1, 9) * _tmp23 - P(11, 9) * dt + P(2, 9);
_res(3, 9) = P(0, 9) * _tmp63 + P(1, 9) * _tmp60 - P(12, 9) * _tmp50 - P(13, 9) * _tmp65 -
P(14, 9) * _tmp67 + P(2, 9) * _tmp45 + P(3, 9);
_res(4, 9) = P(0, 9) * _tmp91 + P(1, 9) * _tmp99 - P(12, 9) * _tmp100 - P(13, 9) * _tmp95 -
P(14, 9) * _tmp96 + P(2, 9) * _tmp92 + P(4, 9);
_res(5, 9) = P(0, 9) * _tmp115 + P(1, 9) * _tmp122 - P(12, 9) * _tmp123 - P(13, 9) * _tmp119 -
P(14, 9) * _tmp117 + P(2, 9) * _tmp120 + P(5, 9);
_res(0, 9) = _tmp27;
_res(1, 9) = _tmp42;
_res(2, 9) = _tmp52;
_res(3, 9) = P(1, 9) * _tmp75 - P(12, 9) * _tmp57 - P(13, 9) * _tmp61 - P(14, 9) * _tmp64 +
P(2, 9) * _tmp79 + P(3, 9);
_res(4, 9) = P(0, 9) * _tmp117 - P(12, 9) * _tmp110 - P(13, 9) * _tmp102 - P(14, 9) * _tmp108 +
P(2, 9) * _tmp105 + P(4, 9);
_res(5, 9) = P(0, 9) * _tmp138 + P(1, 9) * _tmp133 - P(12, 9) * _tmp135 - P(13, 9) * _tmp134 -
P(14, 9) * _tmp132 + P(5, 9);
_res(6, 9) = P(3, 9) * dt + P(6, 9);
_res(7, 9) = P(4, 9) * dt + P(7, 9);
_res(8, 9) = P(5, 9) * dt + P(8, 9);
@ -477,15 +533,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 9) = 0;
_res(21, 9) = 0;
_res(22, 9) = 0;
_res(0, 10) = _tmp12;
_res(1, 10) = _tmp17;
_res(2, 10) = P(0, 10) * _tmp22 + P(1, 10) * _tmp23 - P(11, 10) * dt + P(2, 10);
_res(3, 10) = P(0, 10) * _tmp63 + P(1, 10) * _tmp60 - P(12, 10) * _tmp50 - P(13, 10) * _tmp65 -
P(14, 10) * _tmp67 + P(2, 10) * _tmp45 + P(3, 10);
_res(4, 10) = P(0, 10) * _tmp91 + P(1, 10) * _tmp99 - P(12, 10) * _tmp100 - P(13, 10) * _tmp95 -
P(14, 10) * _tmp96 + P(2, 10) * _tmp92 + P(4, 10);
_res(5, 10) = P(0, 10) * _tmp115 + P(1, 10) * _tmp122 - P(12, 10) * _tmp123 -
P(13, 10) * _tmp119 - P(14, 10) * _tmp117 + P(2, 10) * _tmp120 + P(5, 10);
_res(0, 10) = _tmp25;
_res(1, 10) = _tmp40;
_res(2, 10) = _tmp49;
_res(3, 10) = P(1, 10) * _tmp75 - P(12, 10) * _tmp57 - P(13, 10) * _tmp61 - P(14, 10) * _tmp64 +
P(2, 10) * _tmp79 + P(3, 10);
_res(4, 10) = P(0, 10) * _tmp117 - P(12, 10) * _tmp110 - P(13, 10) * _tmp102 -
P(14, 10) * _tmp108 + P(2, 10) * _tmp105 + P(4, 10);
_res(5, 10) = P(0, 10) * _tmp138 + P(1, 10) * _tmp133 - P(12, 10) * _tmp135 -
P(13, 10) * _tmp134 - P(14, 10) * _tmp132 + P(5, 10);
_res(6, 10) = P(3, 10) * dt + P(6, 10);
_res(7, 10) = P(4, 10) * dt + P(7, 10);
_res(8, 10) = P(5, 10) * dt + P(8, 10);
@ -503,15 +559,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 10) = 0;
_res(21, 10) = 0;
_res(22, 10) = 0;
_res(0, 11) = _tmp21;
_res(1, 11) = _tmp24;
_res(2, 11) = _tmp25;
_res(3, 11) = P(0, 11) * _tmp63 + P(1, 11) * _tmp60 - P(12, 11) * _tmp50 - P(13, 11) * _tmp65 -
P(14, 11) * _tmp67 + P(2, 11) * _tmp45 + P(3, 11);
_res(4, 11) = P(0, 11) * _tmp91 + P(1, 11) * _tmp99 - P(12, 11) * _tmp100 - P(13, 11) * _tmp95 -
P(14, 11) * _tmp96 + P(2, 11) * _tmp92 + P(4, 11);
_res(5, 11) = P(0, 11) * _tmp115 + P(1, 11) * _tmp122 - P(12, 11) * _tmp123 -
P(13, 11) * _tmp119 - P(14, 11) * _tmp117 + P(2, 11) * _tmp120 + P(5, 11);
_res(0, 11) = _tmp24;
_res(1, 11) = _tmp41;
_res(2, 11) = _tmp50;
_res(3, 11) = P(1, 11) * _tmp75 - P(12, 11) * _tmp57 - P(13, 11) * _tmp61 - P(14, 11) * _tmp64 +
P(2, 11) * _tmp79 + P(3, 11);
_res(4, 11) = P(0, 11) * _tmp117 - P(12, 11) * _tmp110 - P(13, 11) * _tmp102 -
P(14, 11) * _tmp108 + P(2, 11) * _tmp105 + P(4, 11);
_res(5, 11) = P(0, 11) * _tmp138 + P(1, 11) * _tmp133 - P(12, 11) * _tmp135 -
P(13, 11) * _tmp134 - P(14, 11) * _tmp132 + P(5, 11);
_res(6, 11) = P(3, 11) * dt + P(6, 11);
_res(7, 11) = P(4, 11) * dt + P(7, 11);
_res(8, 11) = P(5, 11) * dt + P(8, 11);
@ -529,12 +585,12 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 11) = 0;
_res(21, 11) = 0;
_res(22, 11) = 0;
_res(0, 12) = _tmp46;
_res(1, 12) = _tmp71;
_res(2, 12) = _tmp75;
_res(3, 12) = _tmp85;
_res(4, 12) = _tmp111;
_res(5, 12) = _tmp132;
_res(0, 12) = _tmp53;
_res(1, 12) = _tmp81;
_res(2, 12) = _tmp85;
_res(3, 12) = _tmp90;
_res(4, 12) = _tmp129;
_res(5, 12) = _tmp145;
_res(6, 12) = P(3, 12) * dt + P(6, 12);
_res(7, 12) = P(4, 12) * dt + P(7, 12);
_res(8, 12) = P(5, 12) * dt + P(8, 12);
@ -552,12 +608,12 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 12) = 0;
_res(21, 12) = 0;
_res(22, 12) = 0;
_res(0, 13) = _tmp64;
_res(1, 13) = _tmp69;
_res(2, 13) = _tmp74;
_res(3, 13) = _tmp79;
_res(4, 13) = _tmp110;
_res(5, 13) = _tmp130;
_res(0, 13) = _tmp58;
_res(1, 13) = _tmp82;
_res(2, 13) = _tmp87;
_res(3, 13) = _tmp93;
_res(4, 13) = _tmp127;
_res(5, 13) = _tmp144;
_res(6, 13) = P(3, 13) * dt + P(6, 13);
_res(7, 13) = P(4, 13) * dt + P(7, 13);
_res(8, 13) = P(5, 13) * dt + P(8, 13);
@ -575,12 +631,12 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 13) = 0;
_res(21, 13) = 0;
_res(22, 13) = 0;
_res(0, 14) = _tmp66;
_res(1, 14) = _tmp70;
_res(2, 14) = _tmp73;
_res(3, 14) = _tmp78;
_res(4, 14) = _tmp108;
_res(5, 14) = _tmp131;
_res(0, 14) = _tmp62;
_res(1, 14) = _tmp83;
_res(2, 14) = _tmp88;
_res(3, 14) = _tmp94;
_res(4, 14) = _tmp128;
_res(5, 14) = _tmp143;
_res(6, 14) = P(3, 14) * dt + P(6, 14);
_res(7, 14) = P(4, 14) * dt + P(7, 14);
_res(8, 14) = P(5, 14) * dt + P(8, 14);
@ -598,15 +654,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 14) = 0;
_res(21, 14) = 0;
_res(22, 14) = 0;
_res(0, 15) = P(0, 15) + P(1, 15) * _tmp5 + P(2, 15) * _tmp2 - P(9, 15) * dt;
_res(1, 15) = P(0, 15) * _tmp13 + P(1, 15) - P(10, 15) * dt + P(2, 15) * _tmp16;
_res(2, 15) = P(0, 15) * _tmp22 + P(1, 15) * _tmp23 - P(11, 15) * dt + P(2, 15);
_res(3, 15) = P(0, 15) * _tmp63 + P(1, 15) * _tmp60 - P(12, 15) * _tmp50 - P(13, 15) * _tmp65 -
P(14, 15) * _tmp67 + P(2, 15) * _tmp45 + P(3, 15);
_res(4, 15) = P(0, 15) * _tmp91 + P(1, 15) * _tmp99 - P(12, 15) * _tmp100 - P(13, 15) * _tmp95 -
P(14, 15) * _tmp96 + P(2, 15) * _tmp92 + P(4, 15);
_res(5, 15) = P(0, 15) * _tmp115 + P(1, 15) * _tmp122 - P(12, 15) * _tmp123 -
P(13, 15) * _tmp119 - P(14, 15) * _tmp117 + P(2, 15) * _tmp120 + P(5, 15);
_res(0, 15) = P(0, 15) * _tmp18 + P(10, 15) * _tmp23 + P(11, 15) * _tmp6 + P(9, 15) * _tmp15;
_res(1, 15) = P(1, 15) * _tmp18 + P(10, 15) * _tmp29 + P(11, 15) * _tmp34 + P(9, 15) * _tmp36;
_res(2, 15) = P(10, 15) * _tmp45 + P(11, 15) * _tmp44 + P(2, 15) * _tmp18 + P(9, 15) * _tmp47;
_res(3, 15) = P(1, 15) * _tmp75 - P(12, 15) * _tmp57 - P(13, 15) * _tmp61 - P(14, 15) * _tmp64 +
P(2, 15) * _tmp79 + P(3, 15);
_res(4, 15) = P(0, 15) * _tmp117 - P(12, 15) * _tmp110 - P(13, 15) * _tmp102 -
P(14, 15) * _tmp108 + P(2, 15) * _tmp105 + P(4, 15);
_res(5, 15) = P(0, 15) * _tmp138 + P(1, 15) * _tmp133 - P(12, 15) * _tmp135 -
P(13, 15) * _tmp134 - P(14, 15) * _tmp132 + P(5, 15);
_res(6, 15) = P(3, 15) * dt + P(6, 15);
_res(7, 15) = P(4, 15) * dt + P(7, 15);
_res(8, 15) = P(5, 15) * dt + P(8, 15);
@ -624,15 +680,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 15) = 0;
_res(21, 15) = 0;
_res(22, 15) = 0;
_res(0, 16) = P(0, 16) + P(1, 16) * _tmp5 + P(2, 16) * _tmp2 - P(9, 16) * dt;
_res(1, 16) = P(0, 16) * _tmp13 + P(1, 16) - P(10, 16) * dt + P(2, 16) * _tmp16;
_res(2, 16) = P(0, 16) * _tmp22 + P(1, 16) * _tmp23 - P(11, 16) * dt + P(2, 16);
_res(3, 16) = P(0, 16) * _tmp63 + P(1, 16) * _tmp60 - P(12, 16) * _tmp50 - P(13, 16) * _tmp65 -
P(14, 16) * _tmp67 + P(2, 16) * _tmp45 + P(3, 16);
_res(4, 16) = P(0, 16) * _tmp91 + P(1, 16) * _tmp99 - P(12, 16) * _tmp100 - P(13, 16) * _tmp95 -
P(14, 16) * _tmp96 + P(2, 16) * _tmp92 + P(4, 16);
_res(5, 16) = P(0, 16) * _tmp115 + P(1, 16) * _tmp122 - P(12, 16) * _tmp123 -
P(13, 16) * _tmp119 - P(14, 16) * _tmp117 + P(2, 16) * _tmp120 + P(5, 16);
_res(0, 16) = P(0, 16) * _tmp18 + P(10, 16) * _tmp23 + P(11, 16) * _tmp6 + P(9, 16) * _tmp15;
_res(1, 16) = P(1, 16) * _tmp18 + P(10, 16) * _tmp29 + P(11, 16) * _tmp34 + P(9, 16) * _tmp36;
_res(2, 16) = P(10, 16) * _tmp45 + P(11, 16) * _tmp44 + P(2, 16) * _tmp18 + P(9, 16) * _tmp47;
_res(3, 16) = P(1, 16) * _tmp75 - P(12, 16) * _tmp57 - P(13, 16) * _tmp61 - P(14, 16) * _tmp64 +
P(2, 16) * _tmp79 + P(3, 16);
_res(4, 16) = P(0, 16) * _tmp117 - P(12, 16) * _tmp110 - P(13, 16) * _tmp102 -
P(14, 16) * _tmp108 + P(2, 16) * _tmp105 + P(4, 16);
_res(5, 16) = P(0, 16) * _tmp138 + P(1, 16) * _tmp133 - P(12, 16) * _tmp135 -
P(13, 16) * _tmp134 - P(14, 16) * _tmp132 + P(5, 16);
_res(6, 16) = P(3, 16) * dt + P(6, 16);
_res(7, 16) = P(4, 16) * dt + P(7, 16);
_res(8, 16) = P(5, 16) * dt + P(8, 16);
@ -650,15 +706,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 16) = 0;
_res(21, 16) = 0;
_res(22, 16) = 0;
_res(0, 17) = P(0, 17) + P(1, 17) * _tmp5 + P(2, 17) * _tmp2 - P(9, 17) * dt;
_res(1, 17) = P(0, 17) * _tmp13 + P(1, 17) - P(10, 17) * dt + P(2, 17) * _tmp16;
_res(2, 17) = P(0, 17) * _tmp22 + P(1, 17) * _tmp23 - P(11, 17) * dt + P(2, 17);
_res(3, 17) = P(0, 17) * _tmp63 + P(1, 17) * _tmp60 - P(12, 17) * _tmp50 - P(13, 17) * _tmp65 -
P(14, 17) * _tmp67 + P(2, 17) * _tmp45 + P(3, 17);
_res(4, 17) = P(0, 17) * _tmp91 + P(1, 17) * _tmp99 - P(12, 17) * _tmp100 - P(13, 17) * _tmp95 -
P(14, 17) * _tmp96 + P(2, 17) * _tmp92 + P(4, 17);
_res(5, 17) = P(0, 17) * _tmp115 + P(1, 17) * _tmp122 - P(12, 17) * _tmp123 -
P(13, 17) * _tmp119 - P(14, 17) * _tmp117 + P(2, 17) * _tmp120 + P(5, 17);
_res(0, 17) = P(0, 17) * _tmp18 + P(10, 17) * _tmp23 + P(11, 17) * _tmp6 + P(9, 17) * _tmp15;
_res(1, 17) = P(1, 17) * _tmp18 + P(10, 17) * _tmp29 + P(11, 17) * _tmp34 + P(9, 17) * _tmp36;
_res(2, 17) = P(10, 17) * _tmp45 + P(11, 17) * _tmp44 + P(2, 17) * _tmp18 + P(9, 17) * _tmp47;
_res(3, 17) = P(1, 17) * _tmp75 - P(12, 17) * _tmp57 - P(13, 17) * _tmp61 - P(14, 17) * _tmp64 +
P(2, 17) * _tmp79 + P(3, 17);
_res(4, 17) = P(0, 17) * _tmp117 - P(12, 17) * _tmp110 - P(13, 17) * _tmp102 -
P(14, 17) * _tmp108 + P(2, 17) * _tmp105 + P(4, 17);
_res(5, 17) = P(0, 17) * _tmp138 + P(1, 17) * _tmp133 - P(12, 17) * _tmp135 -
P(13, 17) * _tmp134 - P(14, 17) * _tmp132 + P(5, 17);
_res(6, 17) = P(3, 17) * dt + P(6, 17);
_res(7, 17) = P(4, 17) * dt + P(7, 17);
_res(8, 17) = P(5, 17) * dt + P(8, 17);
@ -676,15 +732,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 17) = 0;
_res(21, 17) = 0;
_res(22, 17) = 0;
_res(0, 18) = P(0, 18) + P(1, 18) * _tmp5 + P(2, 18) * _tmp2 - P(9, 18) * dt;
_res(1, 18) = P(0, 18) * _tmp13 + P(1, 18) - P(10, 18) * dt + P(2, 18) * _tmp16;
_res(2, 18) = P(0, 18) * _tmp22 + P(1, 18) * _tmp23 - P(11, 18) * dt + P(2, 18);
_res(3, 18) = P(0, 18) * _tmp63 + P(1, 18) * _tmp60 - P(12, 18) * _tmp50 - P(13, 18) * _tmp65 -
P(14, 18) * _tmp67 + P(2, 18) * _tmp45 + P(3, 18);
_res(4, 18) = P(0, 18) * _tmp91 + P(1, 18) * _tmp99 - P(12, 18) * _tmp100 - P(13, 18) * _tmp95 -
P(14, 18) * _tmp96 + P(2, 18) * _tmp92 + P(4, 18);
_res(5, 18) = P(0, 18) * _tmp115 + P(1, 18) * _tmp122 - P(12, 18) * _tmp123 -
P(13, 18) * _tmp119 - P(14, 18) * _tmp117 + P(2, 18) * _tmp120 + P(5, 18);
_res(0, 18) = P(0, 18) * _tmp18 + P(10, 18) * _tmp23 + P(11, 18) * _tmp6 + P(9, 18) * _tmp15;
_res(1, 18) = P(1, 18) * _tmp18 + P(10, 18) * _tmp29 + P(11, 18) * _tmp34 + P(9, 18) * _tmp36;
_res(2, 18) = P(10, 18) * _tmp45 + P(11, 18) * _tmp44 + P(2, 18) * _tmp18 + P(9, 18) * _tmp47;
_res(3, 18) = P(1, 18) * _tmp75 - P(12, 18) * _tmp57 - P(13, 18) * _tmp61 - P(14, 18) * _tmp64 +
P(2, 18) * _tmp79 + P(3, 18);
_res(4, 18) = P(0, 18) * _tmp117 - P(12, 18) * _tmp110 - P(13, 18) * _tmp102 -
P(14, 18) * _tmp108 + P(2, 18) * _tmp105 + P(4, 18);
_res(5, 18) = P(0, 18) * _tmp138 + P(1, 18) * _tmp133 - P(12, 18) * _tmp135 -
P(13, 18) * _tmp134 - P(14, 18) * _tmp132 + P(5, 18);
_res(6, 18) = P(3, 18) * dt + P(6, 18);
_res(7, 18) = P(4, 18) * dt + P(7, 18);
_res(8, 18) = P(5, 18) * dt + P(8, 18);
@ -702,15 +758,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 18) = 0;
_res(21, 18) = 0;
_res(22, 18) = 0;
_res(0, 19) = P(0, 19) + P(1, 19) * _tmp5 + P(2, 19) * _tmp2 - P(9, 19) * dt;
_res(1, 19) = P(0, 19) * _tmp13 + P(1, 19) - P(10, 19) * dt + P(2, 19) * _tmp16;
_res(2, 19) = P(0, 19) * _tmp22 + P(1, 19) * _tmp23 - P(11, 19) * dt + P(2, 19);
_res(3, 19) = P(0, 19) * _tmp63 + P(1, 19) * _tmp60 - P(12, 19) * _tmp50 - P(13, 19) * _tmp65 -
P(14, 19) * _tmp67 + P(2, 19) * _tmp45 + P(3, 19);
_res(4, 19) = P(0, 19) * _tmp91 + P(1, 19) * _tmp99 - P(12, 19) * _tmp100 - P(13, 19) * _tmp95 -
P(14, 19) * _tmp96 + P(2, 19) * _tmp92 + P(4, 19);
_res(5, 19) = P(0, 19) * _tmp115 + P(1, 19) * _tmp122 - P(12, 19) * _tmp123 -
P(13, 19) * _tmp119 - P(14, 19) * _tmp117 + P(2, 19) * _tmp120 + P(5, 19);
_res(0, 19) = P(0, 19) * _tmp18 + P(10, 19) * _tmp23 + P(11, 19) * _tmp6 + P(9, 19) * _tmp15;
_res(1, 19) = P(1, 19) * _tmp18 + P(10, 19) * _tmp29 + P(11, 19) * _tmp34 + P(9, 19) * _tmp36;
_res(2, 19) = P(10, 19) * _tmp45 + P(11, 19) * _tmp44 + P(2, 19) * _tmp18 + P(9, 19) * _tmp47;
_res(3, 19) = P(1, 19) * _tmp75 - P(12, 19) * _tmp57 - P(13, 19) * _tmp61 - P(14, 19) * _tmp64 +
P(2, 19) * _tmp79 + P(3, 19);
_res(4, 19) = P(0, 19) * _tmp117 - P(12, 19) * _tmp110 - P(13, 19) * _tmp102 -
P(14, 19) * _tmp108 + P(2, 19) * _tmp105 + P(4, 19);
_res(5, 19) = P(0, 19) * _tmp138 + P(1, 19) * _tmp133 - P(12, 19) * _tmp135 -
P(13, 19) * _tmp134 - P(14, 19) * _tmp132 + P(5, 19);
_res(6, 19) = P(3, 19) * dt + P(6, 19);
_res(7, 19) = P(4, 19) * dt + P(7, 19);
_res(8, 19) = P(5, 19) * dt + P(8, 19);
@ -728,15 +784,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 19) = 0;
_res(21, 19) = 0;
_res(22, 19) = 0;
_res(0, 20) = P(0, 20) + P(1, 20) * _tmp5 + P(2, 20) * _tmp2 - P(9, 20) * dt;
_res(1, 20) = P(0, 20) * _tmp13 + P(1, 20) - P(10, 20) * dt + P(2, 20) * _tmp16;
_res(2, 20) = P(0, 20) * _tmp22 + P(1, 20) * _tmp23 - P(11, 20) * dt + P(2, 20);
_res(3, 20) = P(0, 20) * _tmp63 + P(1, 20) * _tmp60 - P(12, 20) * _tmp50 - P(13, 20) * _tmp65 -
P(14, 20) * _tmp67 + P(2, 20) * _tmp45 + P(3, 20);
_res(4, 20) = P(0, 20) * _tmp91 + P(1, 20) * _tmp99 - P(12, 20) * _tmp100 - P(13, 20) * _tmp95 -
P(14, 20) * _tmp96 + P(2, 20) * _tmp92 + P(4, 20);
_res(5, 20) = P(0, 20) * _tmp115 + P(1, 20) * _tmp122 - P(12, 20) * _tmp123 -
P(13, 20) * _tmp119 - P(14, 20) * _tmp117 + P(2, 20) * _tmp120 + P(5, 20);
_res(0, 20) = P(0, 20) * _tmp18 + P(10, 20) * _tmp23 + P(11, 20) * _tmp6 + P(9, 20) * _tmp15;
_res(1, 20) = P(1, 20) * _tmp18 + P(10, 20) * _tmp29 + P(11, 20) * _tmp34 + P(9, 20) * _tmp36;
_res(2, 20) = P(10, 20) * _tmp45 + P(11, 20) * _tmp44 + P(2, 20) * _tmp18 + P(9, 20) * _tmp47;
_res(3, 20) = P(1, 20) * _tmp75 - P(12, 20) * _tmp57 - P(13, 20) * _tmp61 - P(14, 20) * _tmp64 +
P(2, 20) * _tmp79 + P(3, 20);
_res(4, 20) = P(0, 20) * _tmp117 - P(12, 20) * _tmp110 - P(13, 20) * _tmp102 -
P(14, 20) * _tmp108 + P(2, 20) * _tmp105 + P(4, 20);
_res(5, 20) = P(0, 20) * _tmp138 + P(1, 20) * _tmp133 - P(12, 20) * _tmp135 -
P(13, 20) * _tmp134 - P(14, 20) * _tmp132 + P(5, 20);
_res(6, 20) = P(3, 20) * dt + P(6, 20);
_res(7, 20) = P(4, 20) * dt + P(7, 20);
_res(8, 20) = P(5, 20) * dt + P(8, 20);
@ -754,15 +810,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 20) = P(20, 20);
_res(21, 20) = 0;
_res(22, 20) = 0;
_res(0, 21) = P(0, 21) + P(1, 21) * _tmp5 + P(2, 21) * _tmp2 - P(9, 21) * dt;
_res(1, 21) = P(0, 21) * _tmp13 + P(1, 21) - P(10, 21) * dt + P(2, 21) * _tmp16;
_res(2, 21) = P(0, 21) * _tmp22 + P(1, 21) * _tmp23 - P(11, 21) * dt + P(2, 21);
_res(3, 21) = P(0, 21) * _tmp63 + P(1, 21) * _tmp60 - P(12, 21) * _tmp50 - P(13, 21) * _tmp65 -
P(14, 21) * _tmp67 + P(2, 21) * _tmp45 + P(3, 21);
_res(4, 21) = P(0, 21) * _tmp91 + P(1, 21) * _tmp99 - P(12, 21) * _tmp100 - P(13, 21) * _tmp95 -
P(14, 21) * _tmp96 + P(2, 21) * _tmp92 + P(4, 21);
_res(5, 21) = P(0, 21) * _tmp115 + P(1, 21) * _tmp122 - P(12, 21) * _tmp123 -
P(13, 21) * _tmp119 - P(14, 21) * _tmp117 + P(2, 21) * _tmp120 + P(5, 21);
_res(0, 21) = P(0, 21) * _tmp18 + P(10, 21) * _tmp23 + P(11, 21) * _tmp6 + P(9, 21) * _tmp15;
_res(1, 21) = P(1, 21) * _tmp18 + P(10, 21) * _tmp29 + P(11, 21) * _tmp34 + P(9, 21) * _tmp36;
_res(2, 21) = P(10, 21) * _tmp45 + P(11, 21) * _tmp44 + P(2, 21) * _tmp18 + P(9, 21) * _tmp47;
_res(3, 21) = P(1, 21) * _tmp75 - P(12, 21) * _tmp57 - P(13, 21) * _tmp61 - P(14, 21) * _tmp64 +
P(2, 21) * _tmp79 + P(3, 21);
_res(4, 21) = P(0, 21) * _tmp117 - P(12, 21) * _tmp110 - P(13, 21) * _tmp102 -
P(14, 21) * _tmp108 + P(2, 21) * _tmp105 + P(4, 21);
_res(5, 21) = P(0, 21) * _tmp138 + P(1, 21) * _tmp133 - P(12, 21) * _tmp135 -
P(13, 21) * _tmp134 - P(14, 21) * _tmp132 + P(5, 21);
_res(6, 21) = P(3, 21) * dt + P(6, 21);
_res(7, 21) = P(4, 21) * dt + P(7, 21);
_res(8, 21) = P(5, 21) * dt + P(8, 21);
@ -780,15 +836,15 @@ matrix::Matrix<Scalar, 23, 23> PredictCovariance(const matrix::Matrix<Scalar, 24
_res(20, 21) = P(20, 21);
_res(21, 21) = P(21, 21);
_res(22, 21) = 0;
_res(0, 22) = P(0, 22) + P(1, 22) * _tmp5 + P(2, 22) * _tmp2 - P(9, 22) * dt;
_res(1, 22) = P(0, 22) * _tmp13 + P(1, 22) - P(10, 22) * dt + P(2, 22) * _tmp16;
_res(2, 22) = P(0, 22) * _tmp22 + P(1, 22) * _tmp23 - P(11, 22) * dt + P(2, 22);
_res(3, 22) = P(0, 22) * _tmp63 + P(1, 22) * _tmp60 - P(12, 22) * _tmp50 - P(13, 22) * _tmp65 -
P(14, 22) * _tmp67 + P(2, 22) * _tmp45 + P(3, 22);
_res(4, 22) = P(0, 22) * _tmp91 + P(1, 22) * _tmp99 - P(12, 22) * _tmp100 - P(13, 22) * _tmp95 -
P(14, 22) * _tmp96 + P(2, 22) * _tmp92 + P(4, 22);
_res(5, 22) = P(0, 22) * _tmp115 + P(1, 22) * _tmp122 - P(12, 22) * _tmp123 -
P(13, 22) * _tmp119 - P(14, 22) * _tmp117 + P(2, 22) * _tmp120 + P(5, 22);
_res(0, 22) = P(0, 22) * _tmp18 + P(10, 22) * _tmp23 + P(11, 22) * _tmp6 + P(9, 22) * _tmp15;
_res(1, 22) = P(1, 22) * _tmp18 + P(10, 22) * _tmp29 + P(11, 22) * _tmp34 + P(9, 22) * _tmp36;
_res(2, 22) = P(10, 22) * _tmp45 + P(11, 22) * _tmp44 + P(2, 22) * _tmp18 + P(9, 22) * _tmp47;
_res(3, 22) = P(1, 22) * _tmp75 - P(12, 22) * _tmp57 - P(13, 22) * _tmp61 - P(14, 22) * _tmp64 +
P(2, 22) * _tmp79 + P(3, 22);
_res(4, 22) = P(0, 22) * _tmp117 - P(12, 22) * _tmp110 - P(13, 22) * _tmp102 -
P(14, 22) * _tmp108 + P(2, 22) * _tmp105 + P(4, 22);
_res(5, 22) = P(0, 22) * _tmp138 + P(1, 22) * _tmp133 - P(12, 22) * _tmp135 -
P(13, 22) * _tmp134 - P(14, 22) * _tmp132 + P(5, 22);
_res(6, 22) = P(3, 22) * dt + P(6, 22);
_res(7, 22) = P(4, 22) * dt + P(7, 22);
_res(8, 22) = P(5, 22) * dt + P(8, 22);

View File

@ -335,7 +335,6 @@ bool EKF2::multi_init(int imu, int mag)
// mag advertise
if (_param_ekf2_mag_type.get() != MagFuseType::NONE) {
_estimator_aid_src_mag_heading_pub.advertise();
_estimator_aid_src_mag_pub.advertise();
}
@ -874,9 +873,6 @@ void EKF2::PublishAidSourceStatus(const hrt_abstime &timestamp)
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_MAGNETOMETER)
// mag heading
PublishAidSourceStatus(_ekf.aid_src_mag_heading(), _status_mag_heading_pub_last, _estimator_aid_src_mag_heading_pub);
// mag 3d
PublishAidSourceStatus(_ekf.aid_src_mag(), _status_mag_pub_last, _estimator_aid_src_mag_pub);
#endif // CONFIG_EKF2_MAGNETOMETER
@ -1658,7 +1654,7 @@ void EKF2::PublishOdometry(const hrt_abstime &timestamp, const imuSample &imu_sa
_ekf.getPositionVariance().copyTo(odom.position_variance);
// orientation covariance
_ekf.getQuaternionVariance().copyTo(odom.orientation_variance);
_ekf.getRotVarBody().copyTo(odom.orientation_variance);
odom.reset_counter = _ekf.get_quat_reset_count()
+ _ekf.get_velNE_reset_count() + _ekf.get_velD_reset_count()

View File

@ -307,11 +307,9 @@ private:
Vector3f _last_mag_bias_published{};
hrt_abstime _status_mag_pub_last{0};
hrt_abstime _status_mag_heading_pub_last{0};
uORB::Subscription _magnetometer_sub{ORB_ID(vehicle_magnetometer)};
uORB::PublicationMulti<estimator_aid_source1d_s> _estimator_aid_src_mag_heading_pub{ORB_ID(estimator_aid_src_mag_heading)};
uORB::PublicationMulti<estimator_aid_source3d_s> _estimator_aid_src_mag_pub{ORB_ID(estimator_aid_src_mag)};
#endif // CONFIG_EKF2_MAGNETOMETER

View File

@ -1,391 +1,391 @@
Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00055,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00048,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00038,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00034,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2190000,1,-0.011,-0.014,5.8e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2590000,1,-0.011,-0.013,5.8e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2790000,1,-0.011,-0.013,4.8e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2890000,1,-0.011,-0.013,-1.8e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3090000,1,-0.011,-0.013,4.8e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3190000,1,-0.011,-0.013,-8.9e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00021,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3290000,1,-0.011,-0.013,3.1e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3390000,1,-0.011,-0.012,2.5e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3490000,1,-0.011,-0.013,-5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3590000,1,-0.011,-0.012,1.8e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00018,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4290000,1,-0.01,-0.012,8.2e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00016,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00017,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4690000,1,-0.01,-0.012,0.0002,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4790000,1,-0.01,-0.012,0.00019,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00015,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00013,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5690000,1,-0.0096,-0.011,0.00034,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00012,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6090000,1,-0.0094,-0.011,0.00032,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6290000,1,-0.0094,-0.011,0.00022,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6390000,1,-0.0093,-0.011,0.00024,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6590000,1,-0.0094,-0.011,0.00017,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6690000,1,-0.0093,-0.011,9.6e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6790000,0.78,-0.024,0.0049,-0.63,-0.0056,0.0015,-0.11,0.0015,0.00055,-3.7e+02,-0.0014,-0.0057,-8.2e-05,0,0,-5.8e-05,-0.092,-0.02,0.51,-0.00081,-0.075,-0.061,0,0,0.0013,0.0013,0.072,0.18,0.18,0.6,0.11,0.11,0.2,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1
6890000,0.78,-0.025,0.0057,-0.63,-0.03,-0.0077,-0.12,-9e-05,-0.0018,-3.7e+02,-0.0013,-0.0057,-8.3e-05,0,0,-0.00011,-0.1,-0.022,0.51,-0.0011,-0.083,-0.067,0,0,0.0013,0.0013,0.057,0.18,0.18,0.46,0.14,0.14,0.18,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00094,0.0014,0.0013,1,1
6990000,0.78,-0.025,0.0058,-0.63,-0.059,-0.018,-0.12,-0.0053,-0.0061,-3.7e+02,-0.0012,-0.0057,-8.7e-05,-2.7e-05,-6.9e-05,-0.00041,-0.1,-0.022,0.5,-0.0015,-0.084,-0.067,0,0,0.0013,0.0013,0.053,0.19,0.18,0.36,0.17,0.17,0.16,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.0009,0.0014,0.0013,1,1
7090000,0.78,-0.025,0.0059,-0.63,-0.087,-0.028,-0.12,-0.014,-0.012,-3.7e+02,-0.0011,-0.0057,-9.1e-05,-8.3e-05,-0.00024,-0.00077,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.052,0.19,0.19,0.29,0.2,0.2,0.16,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00089,0.0013,0.0013,1,1
7190000,0.78,-0.025,0.006,-0.63,-0.11,-0.037,-0.15,-0.024,-0.018,-3.7e+02,-0.001,-0.0057,-9.3e-05,-7.7e-05,-0.00036,-0.00056,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.051,0.21,0.21,0.24,0.23,0.23,0.15,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00088,0.0013,0.0013,1,1
7290000,0.78,-0.025,0.0059,-0.63,-0.14,-0.04,-0.14,-0.035,-0.019,-3.7e+02,-0.0011,-0.0057,-9e-05,-4.6e-05,-0.00024,-0.0012,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.22,0.22,0.2,0.28,0.28,0.14,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00087,0.0013,0.0013,1,1
7390000,0.78,-0.025,0.0059,-0.63,-0.16,-0.048,-0.16,-0.049,-0.025,-3.7e+02,-0.0011,-0.0057,-9e-05,8.1e-07,-0.00028,-0.0014,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.24,0.24,0.18,0.32,0.32,0.13,7.8e-05,7.9e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00087,0.0013,0.0013,1,1
7490000,0.78,-0.025,0.0059,-0.63,-0.19,-0.061,-0.16,-0.066,-0.038,-3.7e+02,-0.00093,-0.0057,-9.3e-05,1.6e-05,-0.0005,-0.0022,-0.1,-0.023,0.5,-0.0017,-0.085,-0.069,0,0,0.0013,0.0013,0.049,0.27,0.26,0.15,0.37,0.37,0.12,7.8e-05,7.8e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1
7590000,0.78,-0.025,0.0059,-0.63,-0.21,-0.067,-0.16,-0.082,-0.044,-3.7e+02,-0.00093,-0.0056,-9e-05,0.00011,-0.00047,-0.003,-0.1,-0.023,0.5,-0.0016,-0.085,-0.068,0,0,0.0013,0.0013,0.049,0.29,0.29,0.14,0.43,0.43,0.12,7.7e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1
7690000,0.78,-0.025,0.0059,-0.63,-0.24,-0.079,-0.16,-0.1,-0.058,-3.7e+02,-0.00082,-0.0056,-9.3e-05,8.3e-05,-0.00057,-0.005,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.32,0.32,0.13,0.49,0.49,0.11,7.6e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.00086,0.0013,0.0013,1,1
7790000,0.78,-0.025,0.006,-0.63,-0.27,-0.088,-0.16,-0.14,-0.072,-3.7e+02,-0.00074,-0.0057,-9.9e-05,-0.00013,-0.00063,-0.007,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.35,0.35,0.12,0.56,0.55,0.11,7.5e-05,7.5e-05,4.9e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00086,0.0013,0.0013,1,1
7890000,0.78,-0.025,0.006,-0.63,-0.29,-0.099,-0.15,-0.16,-0.086,-3.7e+02,-0.00067,-0.0056,-9.8e-05,-8.1e-05,-0.00064,-0.0095,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.39,0.38,0.11,0.63,0.63,0.1,7.4e-05,7.4e-05,4.9e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00086,0.0013,0.0013,1,1
7990000,0.78,-0.025,0.006,-0.63,-0.32,-0.11,-0.16,-0.19,-0.098,-3.7e+02,-0.00064,-0.0056,-9.7e-05,2.6e-06,-0.00064,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.43,0.42,0.1,0.71,0.71,0.099,7.2e-05,7.3e-05,4.9e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00086,0.0013,0.0013,1,1
8090000,0.78,-0.025,0.006,-0.63,-0.34,-0.12,-0.17,-0.21,-0.11,-3.7e+02,-0.00058,-0.0054,-9.5e-05,0.00017,-0.00074,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.47,0.46,0.1,0.8,0.8,0.097,7e-05,7.1e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00086,0.0013,0.0013,1,1
8190000,0.78,-0.025,0.0061,-0.63,-0.37,-0.13,-0.17,-0.25,-0.13,-3.7e+02,-0.00056,-0.0055,-9.8e-05,-2.7e-05,-0.00068,-0.013,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.52,0.51,0.099,0.9,0.89,0.094,6.8e-05,6.9e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.5e-05,0.0013,0.00085,0.0013,0.0013,1,1
8290000,0.78,-0.025,0.0061,-0.63,-0.019,-0.0046,-0.17,-0.27,-0.13,-3.7e+02,-0.00042,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.017,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.6e-05,6.7e-05,4.9e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00085,0.0013,0.0013,1,1
8390000,0.78,-0.025,0.0061,-0.63,-0.046,-0.012,-0.17,-0.27,-0.13,-3.7e+02,-0.00038,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.021,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,6.5e-05,4.9e-06,0.04,0.04,0.035,0.0013,8.2e-05,0.0013,0.00085,0.0013,0.0013,1,1
8490000,0.78,-0.026,0.0062,-0.63,-0.073,-0.02,-0.17,-0.27,-0.13,-3.7e+02,-0.00033,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.025,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,51,51,0.089,6.2e-05,6.3e-05,4.9e-06,0.04,0.04,0.034,0.0013,8.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
8590000,0.78,-0.025,0.0062,-0.63,-0.099,-0.028,-0.16,-0.28,-0.14,-3.7e+02,-0.00051,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.029,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.095,52,52,0.088,5.9e-05,6.1e-05,4.9e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00085,0.0013,0.0013,1,1
8690000,0.78,-0.025,0.0061,-0.63,-0.12,-0.036,-0.16,-0.28,-0.14,-3.7e+02,-0.00047,-0.0055,-9.9e-05,-6.1e-05,-0.00064,-0.034,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.096,35,35,0.088,5.7e-05,5.9e-05,4.9e-06,0.04,0.04,0.033,0.0013,7.9e-05,0.0013,0.00085,0.0013,0.0013,1,1
8790000,0.78,-0.026,0.0062,-0.63,-0.15,-0.044,-0.15,-0.3,-0.14,-3.7e+02,-0.0004,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.04,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,37,37,0.087,5.5e-05,5.6e-05,4.9e-06,0.04,0.04,0.032,0.0013,7.8e-05,0.0013,0.00085,0.0013,0.0013,1,1
8890000,0.78,-0.026,0.0063,-0.63,-0.18,-0.05,-0.15,-0.3,-0.14,-3.7e+02,-0.00037,-0.0056,-0.00011,-6.1e-05,-0.00064,-0.044,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.095,28,28,0.086,5.2e-05,5.4e-05,4.9e-06,0.04,0.04,0.03,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1
8990000,0.78,-0.026,0.0064,-0.63,-0.21,-0.056,-0.14,-0.32,-0.15,-3.7e+02,-0.00029,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.05,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.096,30,30,0.087,5e-05,5.1e-05,4.9e-06,0.04,0.04,0.029,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1
9090000,0.78,-0.026,0.0065,-0.63,-0.23,-0.06,-0.14,-0.33,-0.15,-3.7e+02,-0.00033,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.052,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.095,25,25,0.086,4.7e-05,4.9e-05,4.9e-06,0.04,0.04,0.028,0.0013,7.6e-05,0.0013,0.00085,0.0013,0.0013,1,1
9190000,0.78,-0.026,0.0063,-0.63,-0.25,-0.071,-0.14,-0.35,-0.16,-3.7e+02,-0.00029,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.056,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.094,27,27,0.085,4.5e-05,4.6e-05,4.9e-06,0.04,0.04,0.027,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1
9290000,0.78,-0.026,0.0063,-0.63,-0.27,-0.077,-0.13,-0.35,-0.16,-3.7e+02,-0.00023,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.06,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,23,23,0.085,4.2e-05,4.4e-05,4.9e-06,0.04,0.04,0.025,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1
9390000,0.78,-0.026,0.0065,-0.63,-0.3,-0.086,-0.13,-0.38,-0.17,-3.7e+02,-0.00018,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.063,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,21,21,0.093,25,25,0.086,4e-05,4.2e-05,4.9e-06,0.04,0.04,0.024,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1
9490000,0.78,-0.026,0.0064,-0.63,-0.31,-0.092,-0.13,-0.38,-0.17,-3.7e+02,-0.00011,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.067,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.091,22,22,0.085,3.8e-05,4e-05,4.9e-06,0.04,0.04,0.023,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1
9590000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.18,-3.7e+02,-0.00024,-0.0053,-0.0001,-6.1e-05,-0.00064,-0.07,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.09,25,25,0.085,3.6e-05,3.7e-05,4.9e-06,0.04,0.04,0.022,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1
9690000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.17,-3.7e+02,-0.0003,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.075,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.089,22,22,0.086,3.4e-05,3.6e-05,4.9e-06,0.04,0.04,0.02,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1
9790000,0.78,-0.026,0.0063,-0.63,-0.38,-0.11,-0.1,-0.45,-0.19,-3.7e+02,-0.00026,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.08,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.087,24,24,0.085,3.2e-05,3.4e-05,4.9e-06,0.04,0.04,0.019,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1
9890000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.1,-0.48,-0.2,-3.7e+02,-0.00033,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.083,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.084,28,28,0.085,3e-05,3.2e-05,4.9e-06,0.04,0.04,0.018,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1
9990000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.096,-0.47,-0.19,-3.7e+02,-0.00035,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.086,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.083,24,24,0.086,2.8e-05,3e-05,4.9e-06,0.04,0.04,0.017,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1
10090000,0.78,-0.026,0.0062,-0.63,-0.43,-0.12,-0.092,-0.51,-0.2,-3.7e+02,-0.00043,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.089,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.081,27,27,0.085,2.7e-05,2.8e-05,4.9e-06,0.04,0.04,0.016,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1
10190000,0.78,-0.026,0.0065,-0.63,-0.43,-0.12,-0.092,-0.5,-0.2,-3.7e+02,-0.00044,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.09,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,13,0.078,24,24,0.084,2.5e-05,2.7e-05,4.9e-06,0.04,0.04,0.015,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
10290000,0.78,-0.026,0.0067,-0.63,-0.46,-0.12,-0.08,-0.55,-0.21,-3.7e+02,-0.00045,-0.0058,-0.00011,-6.1e-05,-0.00064,-0.096,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,14,0.076,27,27,0.085,2.4e-05,2.5e-05,4.9e-06,0.04,0.04,0.014,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
10390000,0.78,-0.026,0.0068,-0.63,-0.017,-0.027,0.0097,-0.00031,-0.0021,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00013,-0.00061,-0.099,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,4.9e-06,0.04,0.04,0.013,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
10490000,0.78,-0.026,0.0069,-0.63,-0.047,-0.034,0.023,-0.0035,-0.0051,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00035,-0.00043,-0.1,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.26,0.26,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,4.9e-06,0.04,0.04,0.012,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
10590000,0.78,-0.026,0.0066,-0.63,-0.045,-0.023,0.026,0.0012,-0.0011,-3.7e+02,-0.00059,-0.0058,-0.00011,-3.5e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.1e-05,4.9e-06,0.04,0.04,0.012,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1
10690000,0.78,-0.026,0.0066,-0.63,-0.073,-0.029,0.03,-0.0048,-0.0037,-3.7e+02,-0.00059,-0.0059,-0.00011,-9.8e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.14,0.14,0.26,0.14,0.14,0.078,1.9e-05,2e-05,4.9e-06,0.04,0.04,0.011,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1
10790000,0.78,-0.025,0.0064,-0.63,-0.069,-0.024,0.024,-0.0001,-0.0015,-3.7e+02,-0.00063,-0.0058,-0.00011,0.00028,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.096,0.096,0.17,0.09,0.09,0.072,1.8e-05,1.9e-05,4.8e-06,0.04,0.039,0.011,0.0013,7e-05,0.0013,0.00084,0.0013,0.0013,1,1
10890000,0.78,-0.025,0.0064,-0.63,-0.097,-0.03,0.02,-0.0084,-0.0042,-3.7e+02,-0.00063,-0.0058,-0.00011,0.0003,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0015,0.048,0.11,0.11,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00084,0.0013,0.0013,1,1
10990000,0.78,-0.025,0.0059,-0.63,-0.085,-0.024,0.014,-0.0037,-0.0024,-3.7e+02,-0.00066,-0.0058,-0.0001,0.0011,-0.009,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.086,0.086,0.12,0.099,0.099,0.071,1.6e-05,1.7e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
11090000,0.78,-0.025,0.0057,-0.63,-0.11,-0.032,0.019,-0.013,-0.0054,-3.7e+02,-0.00069,-0.0057,-9.6e-05,0.0013,-0.0089,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.1,0.1,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
11190000,0.78,-0.024,0.0051,-0.63,-0.095,-0.025,0.0078,-0.0051,-0.0021,-3.7e+02,-0.00079,-0.0057,-9.3e-05,0.0019,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.084,0.084,0.084,0.11,0.11,0.069,1.4e-05,1.5e-05,4.8e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1
11290000,0.78,-0.024,0.0052,-0.63,-0.12,-0.029,0.0076,-0.016,-0.0046,-3.7e+02,-0.00074,-0.0058,-9.7e-05,0.0016,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.099,0.099,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,4.8e-06,0.038,0.038,0.01,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1
11390000,0.78,-0.022,0.0045,-0.63,-0.1,-0.024,0.002,-0.0027,-0.00099,-3.7e+02,-0.00084,-0.0059,-9.5e-05,0.0015,-0.022,-0.11,-0.11,-0.023,0.5,-0.0013,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.08,0.08,0.063,0.082,0.082,0.068,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1
11490000,0.78,-0.022,0.0047,-0.63,-0.12,-0.026,0.0029,-0.014,-0.0031,-3.7e+02,-0.0008,-0.006,-0.0001,0.0009,-0.022,-0.11,-0.11,-0.023,0.5,-0.0014,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.095,0.095,0.058,0.089,0.089,0.069,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1
11590000,0.78,-0.022,0.0041,-0.63,-0.1,-0.022,-0.003,-0.0044,-0.00098,-3.7e+02,-0.00085,-0.006,-9.8e-05,0.00079,-0.029,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.078,0.078,0.049,0.068,0.068,0.066,1.1e-05,1.2e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1
11690000,0.78,-0.022,0.0042,-0.63,-0.12,-0.026,-0.0074,-0.016,-0.0033,-3.7e+02,-0.00079,-0.006,-0.0001,0.00062,-0.03,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.093,0.093,0.046,0.075,0.075,0.066,1.1e-05,1.1e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1
11790000,0.78,-0.021,0.0037,-0.63,-0.1,-0.017,-0.0092,-0.0082,0.00018,-3.7e+02,-0.00082,-0.006,-9.7e-05,0.0012,-0.036,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.077,0.076,0.039,0.06,0.06,0.063,1e-05,1.1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1
11890000,0.78,-0.021,0.0038,-0.63,-0.12,-0.019,-0.01,-0.019,-0.0015,-3.7e+02,-0.0008,-0.0061,-9.9e-05,0.00091,-0.036,-0.11,-0.11,-0.023,0.5,-0.0015,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.09,0.09,0.037,0.067,0.067,0.063,9.5e-06,1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1
11990000,0.78,-0.02,0.003,-0.63,-0.095,-0.012,-0.015,-0.011,0.0012,-3.7e+02,-0.00095,-0.0061,-9.3e-05,0.0013,-0.04,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.074,0.074,0.033,0.055,0.055,0.061,9e-06,9.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1
12090000,0.78,-0.02,0.0029,-0.63,-0.11,-0.016,-0.021,-0.021,-0.00045,-3.7e+02,-0.00099,-0.006,-9e-05,0.0018,-0.04,-0.11,-0.11,-0.023,0.5,-0.0013,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.087,0.086,0.031,0.063,0.063,0.061,8.6e-06,9.2e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1
12190000,0.78,-0.019,0.0023,-0.63,-0.084,-0.015,-0.016,-0.01,0.00028,-3.7e+02,-0.00098,-0.006,-8.9e-05,0.0016,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.071,0.071,0.028,0.052,0.052,0.059,8.1e-06,8.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1
12290000,0.78,-0.019,0.0024,-0.63,-0.092,-0.017,-0.015,-0.019,-0.0014,-3.7e+02,-0.00094,-0.006,-8.9e-05,0.0017,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.082,0.082,0.028,0.06,0.06,0.059,7.8e-06,8.4e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1
12390000,0.78,-0.019,0.0019,-0.63,-0.073,-0.014,-0.013,-0.0094,-0.00012,-3.7e+02,-0.00099,-0.006,-8.8e-05,0.0011,-0.05,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.067,0.067,0.026,0.05,0.05,0.057,7.4e-06,8e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1
12490000,0.78,-0.019,0.0021,-0.63,-0.08,-0.016,-0.016,-0.017,-0.0014,-3.7e+02,-0.00096,-0.0061,-9.1e-05,0.00059,-0.05,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.077,0.076,0.026,0.058,0.058,0.057,7.1e-06,7.6e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1
12590000,0.78,-0.018,0.0018,-0.63,-0.073,-0.014,-0.022,-0.014,-0.00033,-3.7e+02,-0.001,-0.0061,-8.8e-05,0.00072,-0.052,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.063,0.063,0.025,0.049,0.049,0.055,6.8e-06,7.3e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.5e-05,0.0012,0.00072,0.0013,0.0012,1,1
12690000,0.78,-0.018,0.0018,-0.63,-0.079,-0.015,-0.025,-0.021,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.8e-05,0.00038,-0.051,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.071,0.071,0.025,0.057,0.057,0.055,6.5e-06,7e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1
12790000,0.78,-0.018,0.0016,-0.63,-0.072,-0.012,-0.028,-0.018,-0.0006,-3.7e+02,-0.0011,-0.0061,-8.7e-05,0.00058,-0.053,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00054,0.00056,0.046,0.059,0.058,0.024,0.048,0.048,0.053,6.2e-06,6.7e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
12890000,0.78,-0.018,0.0017,-0.63,-0.079,-0.013,-0.027,-0.026,-0.0019,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00062,-0.054,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00055,0.00056,0.046,0.066,0.066,0.025,0.056,0.056,0.054,6e-06,6.5e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
12990000,0.78,-0.018,0.0013,-0.63,-0.064,-0.012,-0.028,-0.019,-0.0015,-3.7e+02,-0.0011,-0.006,-8.6e-05,0.0009,-0.056,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.059,0.058,0.025,0.058,0.058,0.052,5.7e-06,6.2e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
13090000,0.78,-0.018,0.0014,-0.63,-0.069,-0.011,-0.028,-0.026,-0.0023,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00025,-0.057,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.065,0.065,0.025,0.066,0.066,0.052,5.5e-06,6e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1
13190000,0.78,-0.018,0.0011,-0.63,-0.055,-0.011,-0.025,-0.017,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.7e-05,-1.3e-05,-0.058,-0.11,-0.11,-0.024,0.5,-0.0016,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.058,0.058,0.025,0.067,0.067,0.051,5.2e-06,5.7e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1
13290000,0.78,-0.018,0.0011,-0.63,-0.06,-0.013,-0.021,-0.024,-0.003,-3.7e+02,-0.001,-0.006,-8.8e-05,0.00039,-0.059,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.064,0.064,0.027,0.077,0.077,0.051,5.1e-06,5.5e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1
13390000,0.78,-0.017,0.00099,-0.63,-0.049,-0.012,-0.017,-0.016,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00065,-0.06,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.056,0.056,0.026,0.077,0.077,0.05,4.9e-06,5.3e-06,4.8e-06,0.032,0.032,0.0088,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13490000,0.78,-0.017,0.00096,-0.63,-0.053,-0.013,-0.016,-0.022,-0.0034,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00089,-0.061,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.062,0.062,0.028,0.088,0.088,0.05,4.7e-06,5.1e-06,4.8e-06,0.031,0.032,0.0087,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13590000,0.78,-0.017,0.00083,-0.63,-0.043,-0.012,-0.018,-0.014,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00051,-0.062,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.054,0.054,0.028,0.087,0.087,0.05,4.5e-06,5e-06,4.8e-06,0.031,0.032,0.0084,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13690000,0.78,-0.017,0.00081,-0.63,-0.046,-0.015,-0.022,-0.019,-0.0035,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00095,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.06,0.06,0.029,0.098,0.098,0.05,4.3e-06,4.8e-06,4.8e-06,0.031,0.032,0.0083,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13790000,0.78,-0.017,0.00063,-0.63,-0.033,-0.013,-0.024,-0.0063,-0.003,-3.7e+02,-0.0011,-0.006,-8.3e-05,0.00068,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.045,0.045,0.029,0.072,0.072,0.049,4.2e-06,4.6e-06,4.8e-06,0.031,0.031,0.0079,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1
13890000,0.78,-0.017,0.00069,-0.63,-0.037,-0.015,-0.028,-0.01,-0.0045,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00091,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.049,0.049,0.03,0.081,0.081,0.05,4e-06,4.5e-06,4.8e-06,0.031,0.031,0.0078,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1
13990000,0.78,-0.017,0.00054,-0.63,-0.029,-0.014,-0.027,-0.0032,-0.004,-3.7e+02,-0.0011,-0.006,-8.4e-05,0.00078,-0.064,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.04,0.04,0.03,0.063,0.063,0.05,3.9e-06,4.3e-06,4.8e-06,0.031,0.031,0.0074,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
14090000,0.78,-0.017,0.00048,-0.63,-0.03,-0.015,-0.028,-0.006,-0.0056,-3.7e+02,-0.0011,-0.006,-8.1e-05,0.0012,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.044,0.044,0.031,0.07,0.07,0.05,3.8e-06,4.2e-06,4.8e-06,0.031,0.031,0.0073,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
14190000,0.78,-0.017,0.00041,-0.63,-0.024,-0.013,-0.03,-8.4e-05,-0.0036,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0015,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.036,0.036,0.03,0.057,0.057,0.05,3.6e-06,4.1e-06,4.8e-06,0.031,0.031,0.0069,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14290000,0.78,-0.017,0.00037,-0.63,-0.025,-0.015,-0.029,-0.0025,-0.0051,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0016,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.04,0.04,0.032,0.064,0.064,0.051,3.5e-06,3.9e-06,4.8e-06,0.031,0.031,0.0067,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14390000,0.78,-0.017,0.00033,-0.63,-0.02,-0.015,-0.031,0.0017,-0.0037,-3.7e+02,-0.0011,-0.0059,-7.8e-05,0.0021,-0.065,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.034,0.034,0.031,0.053,0.053,0.05,3.4e-06,3.8e-06,4.8e-06,0.031,0.031,0.0063,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14490000,0.78,-0.017,0.0004,-0.63,-0.022,-0.018,-0.034,-0.00071,-0.0054,-3.7e+02,-0.001,-0.0059,-7.9e-05,0.0022,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.037,0.037,0.032,0.06,0.06,0.051,3.3e-06,3.7e-06,4.8e-06,0.031,0.031,0.0062,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14590000,0.78,-0.017,0.00048,-0.63,-0.023,-0.018,-0.034,-0.0013,-0.0052,-3.7e+02,-0.001,-0.0059,-8e-05,0.0021,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.032,0.032,0.031,0.051,0.051,0.051,3.2e-06,3.6e-06,4.8e-06,0.031,0.031,0.0058,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14690000,0.78,-0.017,0.0005,-0.63,-0.026,-0.017,-0.031,-0.0038,-0.0071,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0024,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.035,0.035,0.032,0.056,0.056,0.051,3.1e-06,3.5e-06,4.8e-06,0.031,0.031,0.0057,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14790000,0.78,-0.017,0.00051,-0.63,-0.025,-0.016,-0.027,-0.0038,-0.0066,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0023,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.03,0.03,0.031,0.049,0.049,0.051,3e-06,3.3e-06,4.8e-06,0.031,0.031,0.0053,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14890000,0.78,-0.017,0.00052,-0.63,-0.028,-0.019,-0.03,-0.0065,-0.0085,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0025,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.033,0.033,0.031,0.054,0.054,0.052,2.9e-06,3.3e-06,4.8e-06,0.031,0.031,0.0051,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14990000,0.78,-0.017,0.00057,-0.63,-0.026,-0.016,-0.026,-0.0049,-0.0065,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.029,0.029,0.03,0.047,0.047,0.051,2.8e-06,3.2e-06,4.8e-06,0.031,0.031,0.0048,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15090000,0.78,-0.017,0.00066,-0.63,-0.028,-0.017,-0.029,-0.0076,-0.0081,-3.7e+02,-0.00097,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.031,0.031,0.031,0.052,0.052,0.052,2.7e-06,3.1e-06,4.8e-06,0.031,0.031,0.0046,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15190000,0.78,-0.017,0.00069,-0.63,-0.026,-0.016,-0.026,-0.006,-0.0064,-3.7e+02,-0.00096,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.00041,0.046,0.027,0.028,0.03,0.046,0.046,0.052,2.6e-06,3e-06,4.8e-06,0.031,0.031,0.0043,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15290000,0.78,-0.017,0.00069,-0.63,-0.028,-0.018,-0.024,-0.0086,-0.0082,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0023,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.03,0.03,0.03,0.051,0.051,0.052,2.5e-06,2.9e-06,4.8e-06,0.031,0.031,0.0042,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15390000,0.78,-0.017,0.00064,-0.63,-0.027,-0.018,-0.022,-0.0082,-0.0083,-3.7e+02,-0.00099,-0.0059,-7.4e-05,0.0028,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.029,0.029,0.029,0.054,0.054,0.051,2.4e-06,2.8e-06,4.8e-06,0.031,0.031,0.0039,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15490000,0.78,-0.017,0.00066,-0.63,-0.03,-0.018,-0.022,-0.011,-0.0098,-3.7e+02,-0.00099,-0.0059,-7.6e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.031,0.031,0.029,0.06,0.06,0.053,2.4e-06,2.7e-06,4.8e-06,0.031,0.031,0.0037,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15590000,0.78,-0.017,0.0007,-0.63,-0.028,-0.017,-0.021,-0.01,-0.0091,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0022,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.029,0.03,0.028,0.062,0.062,0.052,2.3e-06,2.7e-06,4.8e-06,0.031,0.031,0.0035,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15690000,0.78,-0.017,0.00067,-0.63,-0.029,-0.017,-0.021,-0.013,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0021,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.032,0.032,0.028,0.069,0.069,0.052,2.2e-06,2.6e-06,4.8e-06,0.03,0.031,0.0033,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15790000,0.78,-0.017,0.00067,-0.63,-0.026,-0.016,-0.024,-0.009,-0.009,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.026,0.027,0.027,0.056,0.057,0.051,2.2e-06,2.5e-06,4.8e-06,0.03,0.031,0.0031,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
15890000,0.78,-0.017,0.00068,-0.63,-0.028,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.028,0.029,0.027,0.063,0.063,0.052,2.1e-06,2.5e-06,4.8e-06,0.03,0.031,0.003,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
15990000,0.78,-0.017,0.00066,-0.63,-0.025,-0.017,-0.017,-0.0084,-0.0095,-3.7e+02,-0.001,-0.0059,-7.3e-05,0.0023,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.026,0.053,0.053,0.051,2e-06,2.4e-06,4.8e-06,0.03,0.031,0.0028,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
16090000,0.78,-0.017,0.00058,-0.63,-0.027,-0.019,-0.014,-0.011,-0.012,-3.7e+02,-0.0011,-0.0059,-7.1e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.026,0.026,0.025,0.058,0.058,0.052,2e-06,2.3e-06,4.8e-06,0.03,0.031,0.0027,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
16190000,0.78,-0.017,0.00056,-0.63,-0.025,-0.017,-0.013,-0.008,-0.009,-3.7e+02,-0.0011,-0.0059,-6.9e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.023,0.025,0.05,0.05,0.051,1.9e-06,2.3e-06,4.8e-06,0.03,0.031,0.0025,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
16290000,0.78,-0.017,0.00049,-0.63,-0.028,-0.019,-0.014,-0.011,-0.011,-3.7e+02,-0.0011,-0.0059,-6.7e-05,0.0031,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.024,0.055,0.055,0.052,1.9e-06,2.2e-06,4.8e-06,0.03,0.031,0.0024,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16390000,0.78,-0.017,0.00051,-0.63,-0.024,-0.015,-0.013,-0.0081,-0.0086,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.022,0.022,0.023,0.047,0.047,0.051,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16490000,0.78,-0.016,0.00047,-0.63,-0.024,-0.017,-0.016,-0.01,-0.01,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.024,0.023,0.052,0.052,0.052,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16590000,0.78,-0.016,0.00043,-0.63,-0.024,-0.013,-0.017,-0.01,-0.0062,-3.7e+02,-0.0011,-0.0059,-5.9e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.00095,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.021,0.022,0.046,0.046,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.002,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16690000,0.78,-0.016,0.00048,-0.63,-0.025,-0.014,-0.013,-0.013,-0.0073,-3.7e+02,-0.0011,-0.0059,-6.1e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.00096,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.022,0.023,0.022,0.05,0.051,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.0019,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16790000,0.78,-0.016,0.00052,-0.63,-0.024,-0.01,-0.012,-0.013,-0.004,-3.7e+02,-0.0011,-0.006,-5.6e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.0009,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.02,0.021,0.044,0.044,0.05,1.6e-06,2e-06,4.8e-06,0.03,0.031,0.0018,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16890000,0.78,-0.016,0.00051,-0.63,-0.025,-0.011,-0.0096,-0.015,-0.0049,-3.7e+02,-0.0011,-0.006,-5.7e-05,0.0027,-0.066,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.022,0.021,0.049,0.049,0.051,1.6e-06,1.9e-06,4.8e-06,0.03,0.031,0.0017,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16990000,0.78,-0.016,0.00055,-0.63,-0.024,-0.011,-0.0091,-0.014,-0.0048,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.019,0.02,0.02,0.043,0.043,0.05,1.5e-06,1.9e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17090000,0.78,-0.016,0.00054,-0.63,-0.025,-0.013,-0.009,-0.016,-0.0059,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.021,0.02,0.048,0.048,0.05,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17190000,0.78,-0.016,0.00048,-0.63,-0.024,-0.015,-0.0099,-0.014,-0.0062,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.019,0.042,0.043,0.049,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0015,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17290000,0.78,-0.016,0.00051,-0.63,-0.027,-0.017,-0.0054,-0.017,-0.0074,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0024,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.019,0.047,0.047,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0014,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17390000,0.78,-0.016,0.00044,-0.63,-0.024,-0.018,-0.0035,-0.014,-0.0076,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.018,0.018,0.042,0.042,0.048,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17490000,0.78,-0.016,0.00046,-0.63,-0.026,-0.019,-0.0018,-0.017,-0.0095,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.018,0.046,0.046,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17590000,0.78,-0.016,0.00047,-0.63,-0.024,-0.019,0.0036,-0.014,-0.0091,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.017,0.041,0.041,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17690000,0.78,-0.016,0.00049,-0.63,-0.026,-0.021,0.003,-0.017,-0.011,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.0027,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.019,0.017,0.045,0.045,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17790000,0.78,-0.016,0.00043,-0.63,-0.024,-0.022,0.0016,-0.015,-0.012,-3.7e+02,-0.0012,-0.0059,-4.8e-05,0.0031,-0.065,-0.13,-0.11,-0.024,0.5,-0.00088,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.016,0.048,0.048,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17890000,0.78,-0.016,0.00042,-0.63,-0.027,-0.023,0.0017,-0.018,-0.015,-3.7e+02,-0.0012,-0.0059,-4.6e-05,0.0033,-0.065,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.016,0.053,0.053,0.048,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17990000,0.78,-0.016,0.00045,-0.63,-0.026,-0.021,0.0029,-0.016,-0.015,-3.7e+02,-0.0012,-0.0059,-4.5e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00086,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.016,0.055,0.055,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.001,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1
18090000,0.78,-0.016,0.00049,-0.63,-0.027,-0.021,0.0053,-0.019,-0.016,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.021,0.021,0.016,0.06,0.061,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.00098,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1
18190000,0.78,-0.016,0.00049,-0.63,-0.024,-0.02,0.0066,-0.014,-0.013,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.015,0.051,0.051,0.047,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00093,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18290000,0.78,-0.016,0.00059,-0.63,-0.025,-0.02,0.0078,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.015,0.056,0.056,0.046,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00089,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18390000,0.78,-0.016,0.00055,-0.63,-0.024,-0.021,0.009,-0.013,-0.012,-3.7e+02,-0.0012,-0.006,-3.8e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.014,0.048,0.048,0.046,1.1e-06,1.4e-06,4.7e-06,0.03,0.03,0.00085,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18490000,0.78,-0.016,0.00051,-0.63,-0.024,-0.023,0.0086,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3.7e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.014,0.053,0.053,0.046,1.1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00082,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18590000,0.78,-0.016,0.00049,-0.63,-0.022,-0.022,0.0067,-0.012,-0.013,-3.7e+02,-0.0013,-0.0059,-2.8e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.016,0.017,0.014,0.046,0.046,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00078,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18690000,0.78,-0.016,0.00055,-0.63,-0.024,-0.023,0.0048,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3e-05,0.0033,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.013,0.05,0.05,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00076,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18790000,0.78,-0.016,0.00057,-0.63,-0.022,-0.021,0.0045,-0.012,-0.012,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.013,0.044,0.044,0.045,1e-06,1.2e-06,4.7e-06,0.03,0.03,0.00073,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18890000,0.78,-0.016,0.00048,-0.63,-0.022,-0.024,0.0051,-0.014,-0.015,-3.7e+02,-0.0013,-0.0059,-2.2e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.013,0.048,0.048,0.045,9.8e-07,1.2e-06,4.7e-06,0.03,0.03,0.0007,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18990000,0.78,-0.016,0.00042,-0.63,-0.019,-0.024,0.0037,-0.0098,-0.013,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.012,0.043,0.043,0.044,9.5e-07,1.2e-06,4.7e-06,0.03,0.03,0.00067,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19090000,0.78,-0.016,0.00041,-0.63,-0.019,-0.025,0.0067,-0.011,-0.015,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.012,0.046,0.047,0.044,9.4e-07,1.2e-06,4.7e-06,0.03,0.03,0.00065,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19190000,0.78,-0.016,0.00036,-0.63,-0.015,-0.024,0.0067,-0.0077,-0.013,-3.7e+02,-0.0013,-0.0059,-8.2e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00068,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.015,0.012,0.041,0.042,0.044,9.1e-07,1.2e-06,4.7e-06,0.03,0.03,0.00063,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19290000,0.78,-0.016,0.00037,-0.63,-0.016,-0.024,0.0094,-0.0095,-0.016,-3.7e+02,-0.0013,-0.006,-1.1e-05,0.0034,-0.065,-0.13,-0.11,-0.024,0.5,-0.00069,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.012,0.045,0.046,0.044,9e-07,1.1e-06,4.7e-06,0.03,0.03,0.00061,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19390000,0.78,-0.016,0.0004,-0.63,-0.015,-0.022,0.013,-0.0084,-0.014,-3.7e+02,-0.0013,-0.006,-2.4e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.012,0.04,0.041,0.043,8.8e-07,1.1e-06,4.6e-06,0.03,0.03,0.00058,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19490000,0.78,-0.016,0.00035,-0.63,-0.015,-0.024,0.0096,-0.01,-0.017,-3.7e+02,-0.0013,-0.0059,1.4e-06,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00064,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.044,0.045,0.043,8.6e-07,1.1e-06,4.6e-06,0.03,0.03,0.00057,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19590000,0.78,-0.015,0.0003,-0.63,-0.013,-0.022,0.0088,-0.0085,-0.015,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.0039,-0.065,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.04,0.04,0.042,8.4e-07,1.1e-06,4.6e-06,0.03,0.03,0.00055,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19690000,0.78,-0.015,0.00028,-0.63,-0.014,-0.021,0.01,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00061,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.044,0.042,8.3e-07,1.1e-06,4.6e-06,0.03,0.03,0.00053,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19790000,0.78,-0.015,0.00024,-0.63,-0.012,-0.018,0.011,-0.0079,-0.015,-3.7e+02,-0.0013,-0.006,1.8e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00058,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.039,0.039,0.042,8.1e-07,1e-06,4.6e-06,0.03,0.03,0.00051,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19890000,0.78,-0.015,0.00028,-0.63,-0.011,-0.02,0.012,-0.0096,-0.017,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.004,-0.065,-0.13,-0.11,-0.024,0.5,-0.00056,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.043,0.042,8e-07,1e-06,4.6e-06,0.03,0.03,0.0005,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19990000,0.78,-0.016,0.00028,-0.63,-0.0096,-0.02,0.015,-0.0084,-0.016,-3.7e+02,-0.0013,-0.0059,3.9e-05,0.0043,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.039,0.039,0.041,7.7e-07,9.9e-07,4.6e-06,0.03,0.03,0.00048,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
20090000,0.78,-0.016,0.00023,-0.63,-0.0096,-0.02,0.015,-0.0091,-0.019,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.01,0.042,0.043,0.042,7.7e-07,9.8e-07,4.6e-06,0.03,0.03,0.00047,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
20190000,0.78,-0.016,0.00019,-0.63,-0.01,-0.019,0.017,-0.0092,-0.017,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00046,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.038,0.039,0.041,7.4e-07,9.5e-07,4.6e-06,0.03,0.03,0.00045,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20290000,0.78,-0.016,0.00019,-0.63,-0.0089,-0.019,0.015,-0.0096,-0.019,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0099,0.042,0.042,0.041,7.4e-07,9.4e-07,4.6e-06,0.03,0.03,0.00044,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20390000,0.78,-0.016,0.00024,-0.63,-0.0085,-0.016,0.017,-0.0095,-0.017,-3.7e+02,-0.0013,-0.0059,6.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0097,0.038,0.038,0.041,7.2e-07,9.2e-07,4.5e-06,0.03,0.03,0.00043,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20490000,0.78,-0.016,0.0002,-0.63,-0.0087,-0.016,0.017,-0.01,-0.018,-3.7e+02,-0.0013,-0.0059,6.5e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0096,0.041,0.042,0.041,7.1e-07,9.1e-07,4.5e-06,0.03,0.03,0.00042,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20590000,0.78,-0.016,0.0002,-0.63,-0.0081,-0.014,0.014,-0.0089,-0.016,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0093,0.038,0.038,0.04,6.9e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20690000,0.78,-0.016,0.00015,-0.63,-0.0089,-0.014,0.015,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,7.2e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0093,0.041,0.042,0.04,6.8e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20790000,0.78,-0.016,0.00013,-0.63,-0.0065,-0.013,0.016,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0091,0.037,0.038,0.04,6.6e-07,8.5e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20890000,0.78,-0.016,0.00011,-0.63,-0.0067,-0.013,0.015,-0.0088,-0.017,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.009,0.041,0.041,0.04,6.6e-07,8.4e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20990000,0.78,-0.016,9.5e-05,-0.63,-0.0051,-0.011,0.015,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,9e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00038,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0088,0.043,0.044,0.039,6.4e-07,8.3e-07,4.4e-06,0.03,0.03,0.00037,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21090000,0.78,-0.016,8.8e-05,-0.63,-0.0062,-0.011,0.016,-0.0094,-0.019,-3.7e+02,-0.0013,-0.0059,9.3e-05,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00037,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0088,0.047,0.048,0.039,6.4e-07,8.2e-07,4.4e-06,0.03,0.03,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21190000,0.78,-0.016,8.4e-05,-0.63,-0.0063,-0.011,0.015,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,9.4e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00036,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0086,0.049,0.05,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00035,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21290000,0.78,-0.016,-6.5e-06,-0.63,-0.0059,-0.011,0.017,-0.0099,-0.021,-3.7e+02,-0.0013,-0.0059,0.0001,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00035,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0085,0.054,0.055,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00034,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21390000,0.78,-0.016,4.3e-05,-0.63,-0.0052,-0.0064,0.016,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,0.00011,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0084,0.046,0.047,0.039,6e-07,7.7e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21490000,0.78,-0.016,3.3e-05,-0.63,-0.0059,-0.0073,0.016,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,0.00011,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0083,0.05,0.052,0.038,5.9e-07,7.6e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21590000,0.78,-0.016,7.2e-05,-0.63,-0.0045,-0.0056,0.016,-0.0082,-0.013,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00029,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0081,0.044,0.045,0.038,5.8e-07,7.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21690000,0.78,-0.016,6.5e-05,-0.63,-0.0061,-0.0065,0.017,-0.0095,-0.015,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0081,0.048,0.049,0.038,5.7e-07,7.4e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21790000,0.78,-0.016,0.00016,-0.63,-0.0051,-0.0043,0.016,-0.0083,-0.0092,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.008,0.042,0.043,0.038,5.6e-07,7.1e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21890000,0.78,-0.015,0.00016,-0.63,-0.0058,-0.005,0.016,-0.009,-0.0097,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0079,0.046,0.047,0.038,5.5e-07,7.1e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21990000,0.78,-0.015,0.00019,-0.63,-0.0057,-0.0022,0.017,-0.0084,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0078,0.041,0.042,0.038,5.4e-07,6.9e-07,4.3e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
22090000,0.78,-0.015,0.00018,-0.63,-0.0054,-0.0037,0.015,-0.0088,-0.006,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0078,0.045,0.046,0.037,5.4e-07,6.9e-07,4.2e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
22190000,0.78,-0.015,0.00019,-0.63,-0.004,-0.0043,0.016,-0.0073,-0.0054,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0076,0.04,0.041,0.037,5.2e-07,6.7e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
22290000,0.78,-0.015,0.00016,-0.63,-0.0036,-0.0039,0.016,-0.008,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0076,0.043,0.045,0.037,5.2e-07,6.6e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
22390000,0.78,-0.015,0.00015,-0.63,-0.0011,-0.0039,0.017,-0.0062,-0.0051,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.012,0.014,0.0075,0.039,0.04,0.037,5.1e-07,6.5e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22490000,0.78,-0.015,0.00013,-0.63,7e-05,-0.0045,0.018,-0.0056,-0.0054,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0074,0.042,0.044,0.037,5e-07,6.4e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22590000,0.78,-0.015,0.00013,-0.63,0.0019,-0.0034,0.018,-0.0039,-0.0047,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0073,0.045,0.046,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22690000,0.78,-0.015,6.1e-05,-0.63,0.0035,-0.0046,0.019,-0.0032,-0.0056,-3.7e+02,-0.0014,-0.0059,0.00016,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0073,0.048,0.05,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22790000,0.78,-0.015,0.0001,-0.63,0.0045,-0.004,0.02,-0.0026,-0.0042,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0072,0.051,0.052,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22890000,0.78,-0.015,0.00011,-0.63,0.0052,-0.0049,0.021,-0.0028,-0.0048,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0072,0.055,0.057,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22990000,0.78,-0.015,0.00012,-0.63,0.0049,-0.0049,0.022,-0.0029,-0.0055,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0071,0.058,0.06,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23090000,0.78,-0.015,0.00018,-0.63,0.0051,-0.0046,0.023,-0.0027,-0.0052,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.007,0.062,0.065,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23190000,0.78,-0.015,0.00017,-0.63,0.0027,-0.0034,0.024,-0.0055,-0.005,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0069,0.065,0.067,0.035,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23290000,0.78,-0.015,0.00023,-0.63,0.0023,-0.0031,0.025,-0.0058,-0.0057,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.017,0.019,0.0069,0.07,0.073,0.036,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23390000,0.78,-0.015,0.00021,-0.63,-0.0011,-0.0028,0.022,-0.01,-0.0058,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.0068,0.072,0.075,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23490000,0.78,-0.013,-0.0019,-0.63,0.0044,-0.0021,-0.011,-0.011,-0.007,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00014,-0.091,-0.068,0,0,0.00036,0.00036,0.046,0.017,0.019,0.0068,0.078,0.081,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23590000,0.78,-0.0042,-0.0062,-0.63,0.015,0.0017,-0.043,-0.0099,-0.0038,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.066,-0.13,-0.11,-0.024,0.5,-0.00012,-0.091,-0.068,0,0,0.00035,0.00034,0.046,0.014,0.016,0.0067,0.062,0.064,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23690000,0.78,0.0014,-0.0052,-0.63,0.042,0.016,-0.093,-0.0075,-0.0033,-3.7e+02,-0.0013,-0.0059,0.00018,0.0046,-0.066,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00034,0.00034,0.046,0.015,0.017,0.0067,0.067,0.069,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23790000,0.78,-0.0022,-0.0027,-0.63,0.063,0.033,-0.15,-0.0074,-0.0017,-3.7e+02,-0.0013,-0.0059,0.00018,0.0049,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.014,0.015,0.0066,0.055,0.056,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23890000,0.78,-0.0085,-0.0007,-0.63,0.077,0.045,-0.2,2.8e-05,0.0023,-3.7e+02,-0.0013,-0.0059,0.00019,0.005,-0.066,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00034,0.00035,0.046,0.014,0.016,0.0066,0.059,0.061,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23990000,0.78,-0.013,0.00021,-0.63,0.072,0.045,-0.25,-0.0055,0.00083,-3.7e+02,-0.0013,-0.0059,0.00018,0.0052,-0.067,-0.13,-0.11,-0.024,0.5,-0.00029,-0.09,-0.067,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0066,0.062,0.063,0.035,4.1e-07,5.2e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
24090000,0.78,-0.012,-0.00093,-0.63,0.072,0.044,-0.3,0.00081,0.0045,-3.7e+02,-0.0013,-0.0059,0.00019,0.0053,-0.067,-0.13,-0.11,-0.024,0.5,-0.00034,-0.09,-0.067,0,0,0.00035,0.00036,0.046,0.015,0.017,0.0065,0.066,0.069,0.035,4.1e-07,5.2e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
24190000,0.78,-0.0097,-0.0017,-0.63,0.069,0.043,-0.35,-0.0065,0.0022,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00031,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.015,0.017,0.0065,0.069,0.071,0.034,4.1e-07,5.1e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24290000,0.78,-0.0089,-0.0021,-0.63,0.077,0.048,-0.4,-0.00011,0.0069,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0065,0.074,0.077,0.034,4e-07,5.1e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24390000,0.78,-0.0093,-0.0022,-0.63,0.074,0.047,-0.46,-0.013,0.00027,-3.7e+02,-0.0012,-0.0059,0.00015,0.0062,-0.069,-0.13,-0.11,-0.024,0.5,-0.0003,-0.089,-0.068,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0064,0.076,0.079,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24490000,0.78,-0.0051,-0.0026,-0.63,0.085,0.054,-0.51,-0.0046,0.0052,-3.7e+02,-0.0012,-0.0059,0.00015,0.0063,-0.069,-0.13,-0.11,-0.024,0.5,-0.00033,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.02,0.0064,0.082,0.085,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24590000,0.78,-0.0016,-0.0027,-0.63,0.089,0.057,-0.56,-0.018,-0.0039,-3.7e+02,-0.0012,-0.0059,0.00014,0.0069,-0.071,-0.13,-0.11,-0.024,0.5,-0.00037,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.019,0.0063,0.084,0.088,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24690000,0.78,-0.00074,-0.0027,-0.63,0.11,0.073,-0.64,-0.0089,0.0014,-3.7e+02,-0.0012,-0.0059,0.00015,0.0072,-0.071,-0.13,-0.11,-0.024,0.5,-0.00055,-0.089,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0063,0.09,0.094,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24790000,0.78,-0.0023,-0.0024,-0.63,0.11,0.082,-0.73,-0.028,-0.0034,-3.7e+02,-0.0012,-0.0059,0.00013,0.0079,-0.073,-0.13,-0.11,-0.025,0.5,-0.00036,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0062,0.093,0.096,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1
24890000,0.78,-0.00046,-0.004,-0.63,0.13,0.097,-0.75,-0.017,0.0055,-3.7e+02,-0.0012,-0.0059,0.00012,0.0081,-0.074,-0.13,-0.11,-0.025,0.5,-0.00045,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.099,0.1,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00062,0.0012,0.0012,1,1
24990000,0.78,0.0012,-0.0055,-0.63,0.13,0.1,-0.81,-0.039,-0.001,-3.7e+02,-0.0011,-0.0059,9e-05,0.0092,-0.076,-0.13,-0.11,-0.025,0.5,-0.00024,-0.087,-0.069,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.1,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1
25090000,0.78,0.00063,-0.0059,-0.63,0.16,0.12,-0.86,-0.025,0.011,-3.7e+02,-0.0011,-0.0059,8.4e-05,0.0094,-0.076,-0.13,-0.11,-0.025,0.5,-0.00025,-0.087,-0.068,0,0,0.00034,0.00034,0.044,0.02,0.023,0.0062,0.11,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0011,0.0012,1,1
25190000,0.78,-0.0015,-0.0054,-0.62,0.15,0.11,-0.91,-0.069,-0.012,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00022,-0.086,-0.069,0,0,0.00034,0.00033,0.044,0.02,0.023,0.0061,0.11,0.11,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1
25290000,0.78,0.0055,-0.0066,-0.62,0.17,0.13,-0.96,-0.053,-0.00075,-3.7e+02,-0.0011,-0.0059,4.8e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00034,-0.086,-0.069,0,0,0.00033,0.00034,0.044,0.021,0.024,0.0061,0.12,0.12,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.0006,0.0011,0.0012,1,1
25390000,0.78,0.011,-0.0071,-0.62,0.18,0.13,-1,-0.1,-0.025,-3.7e+02,-0.001,-0.0058,8.1e-06,0.014,-0.086,-0.13,-0.11,-0.025,0.5,-0.00037,-0.085,-0.069,0,0,0.00033,0.00036,0.043,0.021,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.00059,0.0011,0.0012,1,1
25490000,0.78,0.013,-0.0072,-0.63,0.22,0.16,-1.1,-0.082,-0.012,-3.7e+02,-0.001,-0.0058,2.3e-05,0.014,-0.087,-0.13,-0.11,-0.025,0.5,-0.00072,-0.084,-0.069,0,0,0.00033,0.00036,0.042,0.022,0.026,0.0061,0.13,0.13,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0012,0.00058,0.0011,0.0012,1,1
25590000,0.78,0.011,-0.007,-0.63,0.25,0.19,-1.1,-0.059,0.0041,-3.7e+02,-0.001,-0.0058,3.2e-05,0.014,-0.087,-0.13,-0.12,-0.025,0.5,-0.00098,-0.084,-0.068,0,0,0.00033,0.00035,0.042,0.024,0.028,0.0061,0.14,0.14,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0011,0.00058,0.0011,0.0011,1,1
25690000,0.78,0.018,-0.0099,-0.63,0.29,0.21,-1.2,-0.032,0.022,-3.7e+02,-0.001,-0.0058,4.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0013,-0.082,-0.068,0,0,0.00034,0.00039,0.042,0.025,0.03,0.0061,0.14,0.15,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00017,0.001,5.2e-05,0.0011,0.00057,0.0011,0.0011,1,1
25790000,0.78,0.024,-0.012,-0.63,0.35,0.25,-1.2,-0.00023,0.043,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0019,-0.081,-0.067,0,0,0.00034,0.00043,0.041,0.027,0.033,0.0061,0.15,0.16,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5.1e-05,0.0011,0.00057,0.0011,0.0011,1,1
25890000,0.77,0.025,-0.012,-0.63,0.41,0.28,-1.3,0.039,0.066,-3.7e+02,-0.00099,-0.0058,8.6e-05,0.015,-0.089,-0.13,-0.12,-0.026,0.5,-0.0025,-0.079,-0.066,0,0,0.00034,0.00043,0.04,0.029,0.037,0.0061,0.17,0.17,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5e-05,0.0011,0.00056,0.0011,0.0011,1,1
25990000,0.77,0.021,-0.012,-0.63,0.47,0.31,-1.3,0.083,0.093,-3.7e+02,-0.00099,-0.0058,9.9e-05,0.015,-0.089,-0.13,-0.12,-0.027,0.5,-0.0029,-0.078,-0.065,0,0,0.00034,0.00041,0.04,0.032,0.04,0.0061,0.18,0.19,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00099,5e-05,0.0011,0.00055,0.001,0.0011,1,1
26090000,0.78,0.032,-0.016,-0.63,0.52,0.35,-1.3,0.13,0.13,-3.7e+02,-0.00098,-0.0058,8.8e-05,0.016,-0.089,-0.13,-0.12,-0.027,0.5,-0.0028,-0.077,-0.065,0,0,0.00035,0.00049,0.039,0.034,0.043,0.0061,0.19,0.2,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00097,4.8e-05,0.0011,0.00054,0.001,0.0011,1,1
26190000,0.78,0.041,-0.017,-0.63,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,9.6e-05,0.018,-0.09,-0.13,-0.13,-0.028,0.5,-0.0035,-0.074,-0.063,0,0,0.00036,0.00058,0.037,0.036,0.047,0.0061,0.2,0.22,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00093,4.7e-05,0.001,0.00053,0.00098,0.001,1,1
26290000,0.78,0.044,-0.018,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,9.2e-05,0.019,-0.091,-0.13,-0.13,-0.028,0.49,-0.0037,-0.071,-0.061,0,0,0.00036,0.0006,0.036,0.039,0.052,0.0061,0.21,0.23,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00091,4.6e-05,0.001,0.00052,0.00094,0.001,1,1
26390000,0.77,0.04,-0.018,-0.63,0.76,0.5,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,0.0001,0.02,-0.091,-0.13,-0.13,-0.028,0.49,-0.0042,-0.069,-0.06,0,0,0.00036,0.00055,0.034,0.042,0.056,0.0061,0.23,0.25,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00088,4.4e-05,0.00098,0.0005,0.00091,0.00097,1,1
26490000,0.77,0.056,-0.024,-0.63,0.84,0.55,-1.3,0.4,0.3,-3.7e+02,-0.00096,-0.0058,0.0001,0.02,-0.092,-0.13,-0.13,-0.029,0.49,-0.0043,-0.067,-0.058,0,0,0.00038,0.00075,0.033,0.044,0.061,0.0061,0.24,0.27,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00084,4.2e-05,0.00094,0.00048,0.00088,0.00094,1,1
26590000,0.77,0.073,-0.029,-0.63,0.95,0.63,-1.3,0.48,0.36,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.023,-0.092,-0.13,-0.13,-0.03,0.49,-0.0039,-0.064,-0.057,0,0,0.00041,0.00098,0.031,0.048,0.067,0.0061,0.26,0.29,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0008,4e-05,0.00089,0.00046,0.00083,0.00089,1,1
26690000,0.77,0.076,-0.03,-0.64,1.1,0.71,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.024,-0.093,-0.13,-0.14,-0.031,0.49,-0.0049,-0.059,-0.052,0,0,0.00041,0.00097,0.028,0.052,0.073,0.0061,0.28,0.31,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00074,3.8e-05,0.00083,0.00044,0.00077,0.00083,1,1
26790000,0.77,0.07,-0.029,-0.64,1.2,0.79,-1.3,0.7,0.5,-3.7e+02,-0.00095,-0.0058,6.9e-05,0.025,-0.093,-0.13,-0.14,-0.032,0.48,-0.0047,-0.055,-0.049,0,0,0.00039,0.00084,0.026,0.055,0.079,0.0061,0.3,0.33,0.033,3.7e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0007,3.6e-05,0.00079,0.00041,0.00073,0.00078,1,1
26890000,0.76,0.093,-0.036,-0.64,1.3,0.86,-1.3,0.83,0.58,-3.7e+02,-0.00095,-0.0058,7.2e-05,0.026,-0.093,-0.13,-0.15,-0.032,0.48,-0.0052,-0.052,-0.047,0,0,0.00044,0.0011,0.024,0.058,0.085,0.0061,0.32,0.35,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00066,3.4e-05,0.00074,0.00039,0.00068,0.00074,1,1
26990000,0.76,0.12,-0.041,-0.64,1.5,0.97,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,6.1e-05,0.029,-0.094,-0.13,-0.15,-0.034,0.48,-0.0055,-0.046,-0.043,0,0,0.00049,0.0014,0.021,0.061,0.091,0.0061,0.34,0.37,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.0006,3.1e-05,0.00067,0.00036,0.00062,0.00067,1,1
27090000,0.76,0.12,-0.041,-0.64,1.7,1.1,-1.2,1.1,0.78,-3.7e+02,-0.00095,-0.0058,4.5e-05,0.03,-0.093,-0.13,-0.16,-0.035,0.47,-0.0055,-0.041,-0.038,0,0,0.00049,0.0013,0.018,0.065,0.098,0.0061,0.36,0.4,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00055,2.8e-05,0.0006,0.00033,0.00056,0.0006,1,1
27190000,0.76,0.11,-0.039,-0.64,1.9,1.2,-1.2,1.3,0.9,-3.7e+02,-0.00096,-0.0058,2.8e-05,0.032,-0.092,-0.13,-0.16,-0.035,0.47,-0.0053,-0.038,-0.035,0,0,0.00045,0.0011,0.017,0.068,0.1,0.0062,0.38,0.43,0.034,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00051,2.6e-05,0.00056,0.00031,0.00052,0.00056,1,1
27290000,0.76,0.093,-0.035,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,2.2e-05,0.032,-0.091,-0.13,-0.16,-0.036,0.47,-0.0054,-0.035,-0.033,0,0,0.00041,0.00083,0.015,0.07,0.11,0.0062,0.4,0.46,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00048,2.5e-05,0.00053,0.00029,0.00049,0.00052,1,1
27390000,0.76,0.077,-0.03,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00095,-0.0058,1.7e-05,0.033,-0.089,-0.13,-0.17,-0.036,0.47,-0.0054,-0.033,-0.032,0,0,0.00038,0.00064,0.014,0.071,0.11,0.0062,0.43,0.49,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00046,2.4e-05,0.00051,0.00027,0.00047,0.00051,1,1
27490000,0.76,0.061,-0.025,-0.64,2.2,1.4,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,9e-06,0.033,-0.087,-0.13,-0.17,-0.037,0.47,-0.0052,-0.032,-0.032,0,0,0.00036,0.00052,0.012,0.072,0.11,0.0062,0.46,0.52,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00044,2.3e-05,0.0005,0.00025,0.00046,0.0005,1,1
27590000,0.77,0.049,-0.022,-0.64,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,-8.8e-07,0.034,-0.084,-0.13,-0.17,-0.037,0.47,-0.0048,-0.031,-0.031,0,0,0.00035,0.00045,0.012,0.073,0.11,0.0062,0.48,0.55,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.3e-05,0.00049,0.00024,0.00045,0.00049,1,1
27690000,0.77,0.047,-0.021,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,-9.9e-06,0.034,-0.083,-0.13,-0.17,-0.037,0.47,-0.0044,-0.031,-0.031,0,0,0.00035,0.00044,0.011,0.073,0.11,0.0063,0.51,0.59,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.2e-05,0.00049,0.00023,0.00045,0.00049,1,1
27790000,0.77,0.049,-0.021,-0.64,2.3,1.5,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,-2.3e-05,0.035,-0.081,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.031,0,0,0.00035,0.00044,0.0098,0.074,0.1,0.0063,0.54,0.62,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00042,2.2e-05,0.00049,0.00022,0.00044,0.00048,1,1
27890000,0.77,0.047,-0.021,-0.64,2.4,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,-2.4e-05,0.034,-0.079,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00043,0.0093,0.075,0.1,0.0063,0.58,0.66,0.034,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00041,2.2e-05,0.00048,0.00022,0.00044,0.00048,1,1
27990000,0.77,0.043,-0.02,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,-2.7e-05,0.034,-0.078,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00041,0.0087,0.076,0.1,0.0064,0.61,0.7,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00041,2.1e-05,0.00048,0.00021,0.00043,0.00048,1,1
28090000,0.77,0.057,-0.025,-0.64,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,-3.8e-05,0.035,-0.076,-0.13,-0.17,-0.038,0.47,-0.0035,-0.029,-0.03,0,0,0.00035,0.00045,0.0081,0.077,0.1,0.0064,0.65,0.74,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.0004,2.1e-05,0.00048,0.00021,0.00042,0.00048,1,1
28190000,0.77,0.071,-0.028,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,-4e-05,0.035,-0.074,-0.13,-0.17,-0.038,0.46,-0.0035,-0.029,-0.03,0,0,0.00036,0.00049,0.0077,0.078,0.1,0.0065,0.68,0.79,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00039,2.1e-05,0.00047,0.0002,0.00042,0.00047,1,1
28290000,0.77,0.053,-0.022,-0.64,2.5,1.7,-0.065,3.8,2.6,-3.7e+02,-0.00095,-0.0058,-4.9e-05,0.035,-0.071,-0.13,-0.17,-0.038,0.46,-0.0033,-0.028,-0.029,0,0,0.00035,0.00043,0.0074,0.077,0.1,0.0066,0.72,0.83,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.0002,0.00041,0.00046,1,1
28390000,0.77,0.02,-0.0094,-0.64,2.5,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,-5.7e-05,0.035,-0.068,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00035,0.00037,0.0071,0.076,0.1,0.0066,0.76,0.88,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1
28490000,0.77,0.0014,-0.0026,-0.64,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,-6.3e-05,0.035,-0.065,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0068,0.077,0.099,0.0067,0.8,0.93,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1
28590000,0.77,-0.0022,-0.0011,-0.64,2.4,1.6,0.99,4.5,3.1,-3.7e+02,-0.00096,-0.0058,-6.4e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0065,0.077,0.098,0.0067,0.84,0.98,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1
28690000,0.77,-0.0032,-0.00057,-0.64,2.3,1.6,0.99,4.8,3.3,-3.7e+02,-0.00097,-0.0058,-7.1e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.003,-0.027,-0.029,0,0,0.00034,0.00036,0.0063,0.078,0.098,0.0067,0.88,1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1
28790000,0.77,-0.0034,-0.00035,-0.63,2.2,1.6,1,5,3.4,-3.7e+02,-0.00098,-0.0058,-7.9e-05,0.034,-0.061,-0.12,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00034,0.00037,0.0061,0.079,0.098,0.0068,0.92,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
28890000,0.77,-0.0032,-0.00036,-0.63,2.2,1.5,0.99,5.2,3.6,-3.7e+02,-0.00099,-0.0058,-8.6e-05,0.033,-0.06,-0.12,-0.17,-0.038,0.46,-0.0028,-0.027,-0.029,0,0,0.00034,0.00037,0.0059,0.08,0.1,0.0068,0.97,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
28990000,0.77,-0.0027,-0.00054,-0.63,2.1,1.5,0.98,5.5,3.8,-3.7e+02,-0.001,-0.0058,-9.8e-05,0.033,-0.058,-0.12,-0.17,-0.038,0.46,-0.0026,-0.027,-0.028,0,0,0.00034,0.00037,0.0057,0.081,0.1,0.0069,1,1.2,0.034,3.6e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
29090000,0.78,-0.0022,-0.0007,-0.63,2.1,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.056,-0.12,-0.17,-0.038,0.46,-0.0025,-0.027,-0.028,0,0,0.00034,0.00037,0.0055,0.083,0.1,0.0069,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00037,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
29190000,0.77,-0.0019,-0.00078,-0.63,2,1.5,0.97,5.9,4.1,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.055,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.028,0,0,0.00034,0.00037,0.0054,0.084,0.1,0.007,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1
29290000,0.78,-0.00093,-0.0011,-0.63,1.9,1.4,1,6.1,4.2,-3.7e+02,-0.001,-0.0058,-0.00011,0.031,-0.053,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.028,0,0,0.00033,0.00037,0.0053,0.086,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00044,1,1
29390000,0.78,0.00051,-0.0014,-0.63,1.9,1.4,1,6.3,4.4,-3.7e+02,-0.001,-0.0058,-0.00012,0.03,-0.051,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.0051,0.087,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29490000,0.78,0.0017,-0.0018,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,-0.00013,0.03,-0.05,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.005,0.089,0.11,0.0071,1.3,1.5,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29590000,0.78,0.0028,-0.002,-0.63,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,-0.00013,0.028,-0.048,-0.12,-0.17,-0.038,0.46,-0.002,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.091,0.12,0.0071,1.3,1.6,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29690000,0.78,0.0036,-0.0023,-0.63,1.8,1.4,0.99,6.8,4.8,-3.7e+02,-0.001,-0.0058,-0.00014,0.028,-0.045,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.093,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29790000,0.78,0.0041,-0.0025,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0058,-0.00014,0.027,-0.042,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0048,0.095,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29890000,0.78,0.0045,-0.0026,-0.63,1.7,1.3,0.97,7.2,5.1,-3.7e+02,-0.001,-0.0058,-0.00015,0.026,-0.038,-0.12,-0.17,-0.038,0.46,-0.0017,-0.028,-0.028,0,0,0.00033,0.00038,0.0047,0.097,0.13,0.0072,1.5,1.8,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1
29990000,0.78,0.0046,-0.0027,-0.63,1.7,1.3,0.95,7.3,5.2,-3.7e+02,-0.001,-0.0058,-0.00015,0.025,-0.035,-0.12,-0.17,-0.038,0.46,-0.0016,-0.028,-0.028,0,0,0.00033,0.00038,0.0046,0.099,0.13,0.0072,1.6,1.9,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1
30090000,0.78,0.0046,-0.0027,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0058,-0.00016,0.024,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0046,0.1,0.14,0.0072,1.6,2,0.034,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
30190000,0.78,0.0043,-0.0026,-0.63,1.6,1.3,0.93,7.7,5.5,-3.7e+02,-0.001,-0.0058,-0.00016,0.023,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0045,0.1,0.14,0.0072,1.7,2.1,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
30290000,0.78,0.0042,-0.0026,-0.63,1.5,1.3,0.92,7.8,5.6,-3.7e+02,-0.0011,-0.0058,-0.00016,0.022,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.2,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
30390000,0.78,0.0041,-0.0026,-0.63,1.5,1.2,0.9,8,5.7,-3.7e+02,-0.0011,-0.0058,-0.00017,0.021,-0.028,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.3,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30490000,0.78,0.0039,-0.0025,-0.63,1.5,1.2,0.89,8.2,5.8,-3.7e+02,-0.0011,-0.0058,-0.00017,0.02,-0.026,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.16,0.0072,1.9,2.4,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30590000,0.78,0.0036,-0.0025,-0.63,1.5,1.2,0.85,8.3,6,-3.7e+02,-0.0011,-0.0058,-0.00017,0.019,-0.022,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0043,0.11,0.16,0.0072,2,2.5,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30690000,0.78,0.0034,-0.0024,-0.63,1.4,1.2,0.84,8.5,6.1,-3.7e+02,-0.0011,-0.0058,-0.00017,0.018,-0.019,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00039,0.0043,0.11,0.17,0.0072,2.1,2.6,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30790000,0.78,0.0031,-0.0023,-0.63,1.4,1.2,0.83,8.6,6.2,-3.7e+02,-0.0011,-0.0058,-0.00017,0.017,-0.018,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.8,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30890000,0.78,0.0027,-0.0022,-0.63,1.4,1.2,0.82,8.8,6.3,-3.7e+02,-0.0011,-0.0058,-0.00018,0.016,-0.016,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.9,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30990000,0.78,0.0023,-0.0022,-0.63,1.3,1.2,0.81,8.9,6.4,-3.7e+02,-0.0011,-0.0058,-0.00018,0.015,-0.012,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.19,0.0072,2.3,3,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
31090000,0.78,0.0019,-0.0021,-0.63,1.3,1.1,0.8,9,6.6,-3.7e+02,-0.0011,-0.0058,-0.00018,0.014,-0.0094,-0.12,-0.17,-0.038,0.46,-0.00097,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.12,0.2,0.0072,2.4,3.2,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
31190000,0.78,0.0016,-0.002,-0.63,1.3,1.1,0.79,9.2,6.7,-3.7e+02,-0.0011,-0.0058,-0.00019,0.012,-0.0056,-0.12,-0.17,-0.038,0.46,-0.00088,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.2,0.0072,2.5,3.3,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
31290000,0.78,0.0012,-0.0018,-0.63,1.2,1.1,0.79,9.3,6.8,-3.7e+02,-0.0011,-0.0058,-0.00019,0.011,-0.0028,-0.12,-0.17,-0.038,0.46,-0.00081,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.21,0.0071,2.6,3.5,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
31390000,0.78,0.00059,-0.0016,-0.63,1.2,1.1,0.79,9.4,6.9,-3.7e+02,-0.0011,-0.0058,-0.00019,0.0099,0.0002,-0.12,-0.17,-0.038,0.46,-0.00074,-0.029,-0.027,0,0,0.0003,0.0004,0.0041,0.13,0.22,0.0071,2.7,3.6,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1
31490000,0.78,8.5e-05,-0.0015,-0.63,1.2,1.1,0.79,9.5,7,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0086,0.0029,-0.12,-0.17,-0.038,0.46,-0.00061,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.23,0.0071,2.8,3.8,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1
31590000,0.78,-0.00021,-0.0014,-0.63,1.1,1.1,0.78,9.7,7.1,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0073,0.005,-0.11,-0.17,-0.038,0.46,-0.00056,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.0071,2.9,3.9,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.0001,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1
31690000,0.78,-0.00082,-0.0013,-0.63,1.1,1.1,0.79,9.8,7.2,-3.7e+02,-0.0011,-0.0058,-0.0002,0.006,0.0077,-0.11,-0.17,-0.038,0.46,-0.00049,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.007,3,4.1,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31790000,0.78,-0.0014,-0.0011,-0.63,1.1,1,0.79,9.9,7.3,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0047,0.011,-0.11,-0.17,-0.038,0.46,-0.00042,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.25,0.007,3.1,4.3,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31890000,0.78,-0.002,-0.001,-0.63,1.1,1,0.78,10,7.4,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0033,0.014,-0.11,-0.17,-0.038,0.46,-0.00033,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.15,0.26,0.007,3.2,4.5,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31990000,0.78,-0.0024,-0.0009,-0.63,1,1,0.78,10,7.6,-3.7e+02,-0.0011,-0.0058,-0.00021,0.0018,0.017,-0.11,-0.17,-0.038,0.46,-0.00022,-0.029,-0.027,0,0,0.00029,0.00041,0.004,0.15,0.27,0.007,3.3,4.7,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32090000,0.78,-0.003,-0.0007,-0.63,1,0.99,0.79,10,7.7,-3.7e+02,-0.0012,-0.0058,-0.00021,0.00019,0.02,-0.11,-0.17,-0.038,0.46,-0.00011,-0.029,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.28,0.007,3.5,4.9,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32190000,0.78,-0.0038,-0.00051,-0.63,0.97,0.98,0.78,10,7.8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0015,0.024,-0.11,-0.18,-0.038,0.46,3.2e-05,-0.03,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.29,0.0069,3.6,5.1,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.9e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32290000,0.78,-0.0044,-0.00042,-0.63,0.94,0.96,0.78,11,7.9,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0032,0.028,-0.11,-0.18,-0.038,0.46,0.00014,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.3,0.0069,3.7,5.4,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.8e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32390000,0.78,-0.0049,-0.00032,-0.63,0.91,0.94,0.78,11,8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0041,0.03,-0.11,-0.18,-0.038,0.46,0.00019,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.31,0.0069,3.8,5.6,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32490000,0.78,-0.0051,-0.00027,-0.63,0.88,0.92,0.78,11,8.1,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0056,0.032,-0.11,-0.18,-0.038,0.46,0.00028,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.16,0.32,0.0068,4,5.8,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1
32590000,0.78,-0.0053,-0.00021,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0064,0.033,-0.11,-0.18,-0.038,0.46,0.00034,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.56,0.25,0.25,0.037,3e-07,5.1e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1
32690000,0.78,-0.0053,-0.00025,-0.63,-1.6,-0.85,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0073,0.035,-0.11,-0.18,-0.038,0.46,0.00041,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.55,0.26,0.26,0.048,2.9e-07,5.1e-07,3.2e-06,0.029,0.023,9.5e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
32790000,0.78,-0.0052,-0.00026,-0.63,-1.5,-0.83,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0081,0.036,-0.11,-0.18,-0.038,0.46,0.00047,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.27,0.26,0.26,0.049,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
32890000,0.78,-0.005,-0.00039,-0.63,-1.6,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0089,0.038,-0.11,-0.18,-0.038,0.46,0.00057,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.26,0.27,0.27,0.059,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
32990000,0.78,-0.0049,-0.0005,-0.63,-1.5,-0.84,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0098,0.04,-0.11,-0.18,-0.038,0.46,0.00059,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.085,0.17,0.27,0.27,0.057,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33090000,0.78,-0.005,-0.00048,-0.63,-1.6,-0.86,0.58,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.038,0.46,0.00061,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.086,0.16,0.28,0.28,0.065,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33190000,0.78,-0.0036,-0.0037,-0.62,-1.5,-0.84,0.53,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.01,0.041,-0.11,-0.18,-0.038,0.46,0.0006,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.063,0.065,0.11,0.28,0.28,0.062,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33290000,0.82,-0.0015,-0.016,-0.57,-1.5,-0.86,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.039,0.46,0.00058,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.064,0.066,0.11,0.29,0.29,0.067,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00035,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33390000,0.89,-0.0018,-0.013,-0.46,-1.5,-0.85,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.015,0.038,-0.11,-0.18,-0.039,0.46,0.0012,-0.028,-0.025,0,0,0.00028,0.0004,0.0037,0.051,0.053,0.083,0.29,0.29,0.065,2.9e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00033,1.7e-05,0.00041,0.00015,0.00035,0.00041,1,1
33490000,0.95,-0.00026,-0.0052,-0.31,-1.5,-0.86,0.72,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.018,0.037,-0.11,-0.18,-0.04,0.46,0.0017,-0.02,-0.025,0,0,0.00031,0.00036,0.0034,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00025,1.4e-05,0.00041,0.00013,0.00026,0.00041,1,1
33590000,0.99,-0.003,0.0015,-0.14,-1.5,-0.84,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.0002,-0.018,0.037,-0.11,-0.19,-0.042,0.46,0.0025,-0.013,-0.026,0,0,0.00035,0.00031,0.003,0.044,0.047,0.061,0.3,0.3,0.065,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00017,1e-05,0.00041,9.5e-05,0.00016,0.0004,1,1
33690000,1,-0.0064,0.005,0.024,-1.6,-0.86,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.018,0.037,-0.11,-0.19,-0.043,0.46,0.0018,-0.0093,-0.026,0,0,0.00037,0.00028,0.0026,0.045,0.05,0.056,0.31,0.31,0.068,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00013,7.8e-06,0.0004,6.9e-05,0.0001,0.0004,1,1
33790000,0.98,-0.0073,0.0069,0.19,-1.6,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.002,-0.0068,-0.027,0,0,0.00037,0.00026,0.0023,0.04,0.045,0.047,0.31,0.31,0.064,2.8e-07,4.9e-07,3.1e-06,0.028,0.022,9.3e-05,9.7e-05,6.4e-06,0.0004,4.8e-05,6.3e-05,0.0004,1,1
33890000,0.94,-0.0075,0.0082,0.35,-1.7,-0.9,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.0019,-0.0054,-0.027,0,0,0.00036,0.00026,0.0022,0.044,0.051,0.043,0.32,0.32,0.065,2.8e-07,4.9e-07,3e-06,0.028,0.022,9.3e-05,8.1e-05,5.6e-06,0.0004,3.4e-05,4.2e-05,0.0004,1,1
33990000,0.87,-0.0095,0.0057,0.49,-1.7,-0.91,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.015,0.036,-0.11,-0.2,-0.044,0.46,0.0017,-0.004,-0.027,0,0,0.00032,0.00027,0.002,0.041,0.049,0.036,0.32,0.32,0.062,2.8e-07,4.8e-07,3e-06,0.028,0.022,9.3e-05,7.1e-05,5.1e-06,0.0004,2.6e-05,3e-05,0.0004,1,1
34090000,0.81,-0.011,0.0044,0.59,-1.7,-0.97,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.01,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0034,-0.027,0,0,0.0003,0.00028,0.002,0.047,0.057,0.034,0.33,0.33,0.063,2.8e-07,4.9e-07,3e-06,0.027,0.022,9.3e-05,6.6e-05,4.9e-06,0.0004,2.1e-05,2.4e-05,0.0004,1,1
34190000,0.76,-0.0081,0.0029,0.65,-1.7,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.039,0.052,-0.11,-0.2,-0.044,0.46,0.0012,-0.0028,-0.027,0,0,0.00026,0.00028,0.0018,0.045,0.054,0.029,0.33,0.33,0.06,2.8e-07,4.7e-07,3e-06,0.026,0.021,9.3e-05,6e-05,4.6e-06,0.0004,1.7e-05,1.9e-05,0.0004,1,1
34290000,0.72,-0.0052,0.0041,0.69,-1.7,-1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.038,0.051,-0.11,-0.2,-0.044,0.46,0.0011,-0.0024,-0.027,0,0,0.00025,0.00029,0.0018,0.053,0.064,0.027,0.34,0.34,0.06,2.8e-07,4.7e-07,3e-06,0.025,0.021,9.3e-05,5.7e-05,4.5e-06,0.0004,1.4e-05,1.6e-05,0.0004,1,1
34390000,0.7,-0.0024,0.0054,0.71,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.036,0.05,-0.11,-0.2,-0.044,0.46,0.00092,-0.0022,-0.027,0,0,0.00025,0.00029,0.0018,0.062,0.075,0.025,0.35,0.35,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.5e-05,4.4e-06,0.0004,1.3e-05,1.4e-05,0.0004,1,1
34490000,0.69,-0.00036,0.0066,0.73,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.049,-0.11,-0.2,-0.044,0.46,0.0008,-0.0021,-0.027,0,0,0.00024,0.0003,0.0017,0.073,0.088,0.023,0.36,0.36,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.4e-05,4.3e-06,0.0004,1.1e-05,1.2e-05,0.0004,1,1
34590000,0.68,0.00092,0.0074,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.05,-0.11,-0.2,-0.044,0.46,0.00064,-0.002,-0.027,0,0,0.00024,0.0003,0.0017,0.085,0.1,0.021,0.38,0.38,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.2e-05,4.3e-06,0.0004,1e-05,1.1e-05,0.0004,1,1
34690000,0.67,0.0017,0.0079,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.034,0.049,-0.11,-0.2,-0.044,0.46,0.00068,-0.0018,-0.027,0,0,0.00024,0.0003,0.0017,0.098,0.12,0.019,0.39,0.4,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,9.6e-06,1e-05,0.0004,1,1
34790000,0.67,0.0024,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.036,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00024,0.0003,0.0017,0.11,0.14,0.018,0.41,0.42,0.058,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,8.9e-06,9.2e-06,0.0004,1,1
34890000,0.66,0.0025,0.0082,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00069,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.13,0.16,0.017,0.43,0.44,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5e-05,4.1e-06,0.0004,8.4e-06,8.5e-06,0.0004,1,1
34990000,0.66,-0.00086,0.016,0.75,-3,-2.2,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00024,0.00031,0.0017,0.16,0.22,0.016,0.46,0.47,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.9e-06,8e-06,0.0004,1,1
35090000,0.66,-0.00092,0.016,0.75,-3.1,-2.3,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.18,0.25,0.015,0.49,0.51,0.055,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.5e-06,7.5e-06,0.0004,1,1
35190000,0.66,-0.001,0.015,0.75,-3.1,-2.3,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.2,0.28,0.014,0.52,0.55,0.054,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,7.2e-06,7.1e-06,0.0004,1,1
35290000,0.66,-0.0012,0.015,0.75,-3.2,-2.3,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00084,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.23,0.31,0.013,0.56,0.6,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,6.9e-06,6.7e-06,0.0004,1,1
35390000,0.66,-0.0011,0.015,0.75,-3.2,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00091,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.25,0.34,0.013,0.61,0.66,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.6e-06,6.4e-06,0.0004,1,1
35490000,0.66,-0.0012,0.016,0.75,-3.2,-2.4,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.28,0.37,0.012,0.66,0.73,0.051,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.4e-06,6.2e-06,0.0004,1,1
35590000,0.66,-0.0012,0.016,0.75,-3.3,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00092,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.31,0.4,0.011,0.72,0.81,0.05,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,4e-06,0.0004,6.2e-06,5.9e-06,0.0004,1,1
35690000,0.66,-0.0011,0.016,0.75,-3.3,-2.5,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.046,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.33,0.44,0.011,0.79,0.9,0.049,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.1e-06,5.7e-06,0.0004,1,1
35790000,0.66,-0.0012,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.36,0.48,0.01,0.86,1,0.048,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,5.9e-06,5.5e-06,0.0004,1,1
35890000,0.66,-0.0013,0.016,0.75,-3.4,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.4,0.52,0.01,0.95,1.1,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,5.7e-06,5.3e-06,0.0004,1,1
35990000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.00094,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.43,0.56,0.0097,1,1.2,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.6e-06,5.1e-06,0.0004,1,1
36090000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.044,-0.11,-0.2,-0.044,0.46,0.00096,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.46,0.6,0.0093,1.2,1.4,0.046,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.5e-06,5e-06,0.0004,1,1
36190000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.034,0.043,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.5,0.65,0.009,1.3,1.5,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.4e-06,4.8e-06,0.0004,1,1
36290000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.53,0.69,0.0088,1.4,1.7,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.3e-06,4.7e-06,0.0004,1,1
36390000,0.66,-0.0013,0.016,0.75,-3.5,-2.9,-0.097,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.57,0.74,0.0086,1.6,1.9,0.044,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.2e-06,4.6e-06,0.0004,1,1
36490000,0.66,-0.0014,0.016,0.75,-3.6,-2.9,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.61,0.79,0.0083,1.7,2.1,0.043,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.0004,5.2e-06,4.5e-06,0.0004,1,1
36590000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.08,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.032,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.65,0.84,0.0082,1.9,2.4,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5.1e-06,4.4e-06,0.0004,1,1
36690000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.031,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.69,0.89,0.0081,2.1,2.6,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.3e-06,0.0004,1,1
36790000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00024,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.74,0.94,0.0079,2.3,2.9,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.2e-06,0.0004,1,1
36890000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.78,1,0.0078,2.6,3.2,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4.1e-06,0.0004,1,1
36990000,0.66,-0.0014,0.016,0.75,-3.7,-3.2,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.82,1.1,0.0077,2.8,3.6,0.04,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4e-06,0.0004,1,1
37090000,0.66,-0.0014,0.016,0.75,-3.8,-3.2,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.87,1.1,0.0076,3.1,4,0.04,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1
37190000,0.66,-0.0014,0.016,0.75,-3.8,-3.3,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.92,1.2,0.0076,3.4,4.4,0.039,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1
37290000,0.66,-0.0015,0.017,0.75,-3.8,-3.3,-0.026,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.97,1.2,0.0075,3.7,4.8,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.8e-06,0.0004,1,1
37390000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.029,0.036,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,1,1.3,0.0075,4.1,5.3,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1
37490000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.029,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.4,5.8,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1
37590000,0.66,-0.0014,0.017,0.75,-3.9,-3.5,-0.0032,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.028,0.034,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.9,6.3,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1
37690000,0.66,-0.0015,0.017,0.75,-4,-3.5,0.0061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.033,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.2,1.5,0.0074,5.3,6.9,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.6e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1
37790000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.2,1.5,0.0074,5.8,7.5,0.037,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.5e-06,0.0004,1,1
37890000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.022,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.6,0.0074,6.3,8.2,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
37990000,0.66,-0.0016,0.017,0.75,-4.1,-3.7,0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.026,0.031,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.7,0.0074,6.8,8.9,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
38090000,0.66,-0.0017,0.017,0.75,-4.1,-3.8,0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.7,0.0074,7.4,9.6,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.5e-06,3.4e-06,0.0004,1,1
38190000,0.66,-0.0016,0.017,0.75,-4.2,-3.8,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.8,0.0074,8,10,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1
38290000,0.66,-0.0017,0.017,0.75,-4.2,-3.9,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,8.6,11,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1
38390000,0.66,-0.0016,0.017,0.75,-4.2,-3.9,0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,9.3,12,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1
38490000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.07,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,10,13,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1
38590000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.076,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.1,0.0075,11,14,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1
38690000,0.66,-0.0016,0.017,0.75,-4.3,-4.1,0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.2,0.0075,12,15,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1
38790000,0.66,-0.0016,0.017,0.75,-4.4,-4.1,0.089,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00026,0.0016,1.8,2.3,0.0075,12,16,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1
38890000,0.66,-0.0017,0.017,0.75,-4.4,-4.1,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.9,2.3,0.0075,13,17,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1
10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.00077,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00051,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00062,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00043,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00051,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2190000,1,-0.011,-0.014,5.9e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2590000,1,-0.011,-0.013,5.9e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2790000,1,-0.011,-0.013,4.9e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2890000,1,-0.011,-0.013,-1.1e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3090000,1,-0.011,-0.013,4.9e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3190000,1,-0.011,-0.013,-8e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3290000,1,-0.011,-0.013,3.2e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3390000,1,-0.011,-0.012,3.2e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3490000,1,-0.011,-0.013,-4.5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3590000,1,-0.011,-0.012,1.9e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4290000,1,-0.01,-0.012,8.1e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4690000,1,-0.01,-0.012,0.00019,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4790000,1,-0.01,-0.012,0.00018,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5690000,1,-0.0096,-0.011,0.00033,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6090000,1,-0.0094,-0.011,0.00031,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6290000,1,-0.0094,-0.011,0.00021,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6390000,1,-0.0093,-0.011,0.00023,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6590000,1,-0.0094,-0.011,0.00016,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6690000,1,-0.0093,-0.011,9e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6790000,0.78,-0.024,0.005,-0.63,-0.22,-0.047,-0.11,-0.13,-0.028,-3.7e+02,-0.00035,-0.011,-0.0002,0,0,0.0012,-0.092,-0.02,0.51,-0.00079,-0.075,-0.061,0,0,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1
6890000,0.78,-0.025,0.0059,-0.63,-0.27,-0.062,-0.12,-0.16,-0.038,-3.7e+02,-0.00018,-0.011,-0.00022,0,0,0.0013,-0.1,-0.022,0.51,-0.0012,-0.083,-0.067,0,0,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00089,0.0014,0.0013,1,1
6990000,0.78,-0.025,0.0061,-0.63,-0.3,-0.073,-0.12,-0.2,-0.048,-3.7e+02,-7.9e-05,-0.011,-0.00022,-0.00057,-6.5e-05,0.00098,-0.1,-0.022,0.5,-0.0016,-0.084,-0.067,0,0,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1
7090000,0.78,-0.025,0.0064,-0.63,-0.33,-0.084,-0.12,-0.23,-0.06,-3.7e+02,3.5e-05,-0.011,-0.00023,-0.0013,-0.00028,0.00063,-0.1,-0.023,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00083,0.0014,0.0013,1,1
7190000,0.78,-0.025,0.0066,-0.63,-0.36,-0.093,-0.15,-0.27,-0.071,-3.7e+02,0.0001,-0.011,-0.00023,-0.0017,-0.00044,0.00086,-0.1,-0.023,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00082,0.0013,0.0013,1,1
7290000,0.78,-0.025,0.0068,-0.63,-0.38,-0.094,-0.14,-0.3,-0.078,-3.7e+02,4.4e-05,-0.011,-0.00022,-0.0016,-0.0004,0.00018,-0.1,-0.023,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1
7390000,0.78,-0.024,0.007,-0.63,-0.41,-0.1,-0.16,-0.34,-0.089,-3.7e+02,6.5e-05,-0.011,-0.00022,-0.0017,-0.00044,2.8e-05,-0.1,-0.023,0.5,-0.0018,-0.085,-0.068,0,0,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00081,0.0013,0.0013,1,1
7490000,0.78,-0.024,0.007,-0.63,-0.43,-0.11,-0.16,-0.38,-0.11,-3.7e+02,0.0002,-0.011,-0.00023,-0.0019,-0.00051,-0.00073,-0.1,-0.023,0.5,-0.0019,-0.085,-0.069,0,0,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1
7590000,0.78,-0.024,0.0071,-0.63,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.00019,-0.011,-0.00022,-0.0018,-0.00049,-0.0016,-0.1,-0.023,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1
7690000,0.78,-0.024,0.0072,-0.63,0,0,-0.16,-0.46,-0.14,-3.7e+02,0.00028,-0.011,-0.00022,-0.002,-0.00046,-0.0036,-0.1,-0.023,0.5,-0.002,-0.085,-0.069,0,0,0.0013,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.0008,0.0013,0.0013,1,1
7790000,0.78,-0.024,0.0074,-0.63,-0.028,-0.004,-0.16,-0.46,-0.14,-3.7e+02,0.00034,-0.011,-0.00023,-0.002,-0.00046,-0.0056,-0.1,-0.023,0.5,-0.002,-0.085,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00079,0.0013,0.0013,1,1
7890000,0.78,-0.024,0.0074,-0.63,-0.053,-0.0088,-0.15,-0.46,-0.14,-3.7e+02,0.00038,-0.011,-0.00022,-0.002,-0.00046,-0.0081,-0.1,-0.023,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.11,1e+02,1e+02,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00079,0.0013,0.0013,1,1
7990000,0.78,-0.024,0.0074,-0.63,-0.079,-0.013,-0.16,-0.47,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.002,-0.00046,-0.0093,-0.1,-0.023,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00079,0.0013,0.0013,1,1
8090000,0.78,-0.024,0.0072,-0.63,-0.1,-0.018,-0.17,-0.47,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.002,-0.00046,-0.0095,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,52,52,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00079,0.0013,0.0013,1,1
8190000,0.78,-0.024,0.0074,-0.63,-0.13,-0.021,-0.18,-0.48,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.002,-0.00046,-0.012,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,25,0.099,35,35,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,8.4e-05,0.0013,0.00078,0.0013,0.0013,1,1
8290000,0.78,-0.024,0.0074,-0.63,-0.15,-0.026,-0.17,-0.49,-0.14,-3.7e+02,0.00052,-0.01,-0.00021,-0.002,-0.00046,-0.016,-0.1,-0.023,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,25,25,0.097,37,37,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00078,0.0013,0.0013,1,1
8390000,0.78,-0.024,0.0072,-0.63,-0.17,-0.031,-0.17,-0.5,-0.14,-3.7e+02,0.00054,-0.01,-0.00021,-0.002,-0.00046,-0.019,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.1e-05,0.0013,0.00078,0.0013,0.0013,1,1
8490000,0.78,-0.023,0.0072,-0.63,-0.2,-0.036,-0.17,-0.51,-0.15,-3.7e+02,0.00055,-0.0099,-0.0002,-0.002,-0.00046,-0.024,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.096,31,31,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00077,0.0013,0.0013,1,1
8590000,0.78,-0.023,0.0074,-0.63,-0.21,-0.033,-0.17,-0.52,-0.15,-3.7e+02,0.00036,-0.0099,-0.0002,-0.002,-0.00046,-0.028,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.095,25,25,0.088,5.7e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.9e-05,0.0013,0.00077,0.0013,0.0013,1,1
8690000,0.78,-0.023,0.007,-0.63,-0.23,-0.038,-0.16,-0.54,-0.15,-3.7e+02,0.00037,-0.0096,-0.00019,-0.002,-0.00046,-0.033,-0.1,-0.023,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.096,28,28,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.8e-05,0.0013,0.00077,0.0013,0.0013,1,1
8790000,0.78,-0.023,0.0071,-0.63,-0.24,-0.041,-0.15,-0.54,-0.15,-3.7e+02,0.00039,-0.0095,-0.00019,-0.002,-0.00046,-0.039,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.096,24,24,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,7.7e-05,0.0013,0.00076,0.0013,0.0013,1,1
8890000,0.78,-0.023,0.007,-0.63,-0.26,-0.045,-0.15,-0.56,-0.16,-3.7e+02,0.00039,-0.0094,-0.00018,-0.002,-0.00046,-0.043,-0.1,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.095,26,26,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0013,7.6e-05,0.0013,0.00076,0.0013,0.0013,1,1
8990000,0.78,-0.023,0.007,-0.63,-0.28,-0.05,-0.14,-0.59,-0.16,-3.7e+02,0.00044,-0.0093,-0.00018,-0.0021,-0.00036,-0.049,-0.11,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,21,21,0.096,29,29,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0013,7.6e-05,0.0013,0.00075,0.0013,0.0013,1,1
9090000,0.78,-0.022,0.007,-0.63,-0.3,-0.05,-0.14,-0.61,-0.17,-3.7e+02,0.00036,-0.0092,-0.00018,-0.0021,-0.00019,-0.052,-0.11,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,21,21,0.095,33,33,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0013,7.5e-05,0.0013,0.00075,0.0013,0.0013,1,1
9190000,0.77,-0.022,0.0063,-0.63,-0.3,-0.06,-0.14,-0.63,-0.18,-3.7e+02,0.00037,-0.0088,-0.00017,-0.0019,4e-05,-0.055,-0.11,-0.023,0.5,-0.0027,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.094,37,37,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,7.4e-05,0.0013,0.00074,0.0013,0.0013,1,1
9290000,0.77,-0.022,0.006,-0.63,-0.32,-0.068,-0.14,-0.66,-0.19,-3.7e+02,0.0004,-0.0086,-0.00016,-0.002,0.00028,-0.059,-0.11,-0.023,0.5,-0.0028,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.093,41,41,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,7.3e-05,0.0013,0.00074,0.0013,0.0013,1,1
9390000,0.77,-0.022,0.0059,-0.63,-0.34,-0.077,-0.13,-0.69,-0.2,-3.7e+02,0.00042,-0.0085,-0.00016,-0.0021,0.00046,-0.063,-0.11,-0.023,0.5,-0.0029,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.093,46,46,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,7.3e-05,0.0013,0.00074,0.0013,0.0013,1,1
9490000,0.77,-0.022,0.0054,-0.63,-0.34,-0.09,-0.13,-0.71,-0.21,-3.7e+02,0.00045,-0.0082,-0.00015,-0.002,0.00072,-0.067,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.091,51,51,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,7.2e-05,0.0013,0.00073,0.0013,0.0013,1,1
9590000,0.77,-0.022,0.0051,-0.63,-0.35,-0.089,-0.13,-0.73,-0.22,-3.7e+02,0.0003,-0.008,-0.00014,-0.002,0.001,-0.07,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0013,0.054,21,21,0.09,57,57,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.2e-05,0.0013,0.00073,0.0013,0.0013,1,1
9690000,0.77,-0.022,0.0053,-0.63,-0.37,-0.086,-0.12,-0.77,-0.22,-3.7e+02,0.00022,-0.0081,-0.00014,-0.0022,0.0012,-0.075,-0.11,-0.023,0.5,-0.0029,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,21,0.089,63,63,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.1e-05,0.0013,0.00072,0.0013,0.0013,1,1
9790000,0.77,-0.022,0.0049,-0.63,-0.37,-0.099,-0.11,-0.79,-0.24,-3.7e+02,0.00023,-0.0078,-0.00014,-0.0023,0.0016,-0.081,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,21,0.087,69,69,0.085,3.1e-05,3.4e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.1e-05,0.0013,0.00072,0.0013,0.0013,1,1
9890000,0.77,-0.021,0.0047,-0.63,-0.38,-0.1,-0.11,-0.82,-0.24,-3.7e+02,0.00014,-0.0077,-0.00013,-0.0023,0.0018,-0.083,-0.11,-0.023,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,22,0.084,76,76,0.085,3e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7e-05,0.0013,0.00072,0.0013,0.0013,1,1
9990000,0.77,-0.021,0.0047,-0.63,-0.4,-0.1,-0.1,-0.85,-0.25,-3.7e+02,9.4e-05,-0.0077,-0.00013,-0.0025,0.002,-0.087,-0.11,-0.023,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,22,22,0.083,83,83,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7e-05,0.0013,0.00071,0.0013,0.0013,1,1
10090000,0.77,-0.021,0.0044,-0.63,-0.4,-0.099,-0.096,-0.87,-0.26,-3.7e+02,-1.2e-05,-0.0075,-0.00012,-0.0025,0.0022,-0.09,-0.11,-0.023,0.5,-0.003,-0.088,-0.069,0,0,0.0011,0.0012,0.054,22,22,0.08,91,91,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7e-05,0.0013,0.00071,0.0013,0.0013,1,1
10190000,0.77,-0.021,0.0047,-0.63,-0.42,-0.097,-0.096,-0.92,-0.26,-3.7e+02,-4.4e-05,-0.0076,-0.00012,-0.0025,0.0022,-0.091,-0.11,-0.023,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,22,22,0.078,99,99,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,6.9e-05,0.0013,0.00071,0.0013,0.0013,1,1
10290000,0.77,-0.021,0.0049,-0.63,-0.44,-0.096,-0.083,-0.96,-0.27,-3.7e+02,-7.1e-05,-0.0076,-0.00012,-0.0028,0.0025,-0.097,-0.11,-0.023,0.5,-0.0028,-0.088,-0.069,0,0,0.0011,0.0011,0.054,22,22,0.076,1.1e+02,1.1e+02,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1
10390000,0.77,-0.021,0.0047,-0.63,-0.0086,-0.022,0.0097,7.7e-05,-0.0019,-3.7e+02,-6e-05,-0.0075,-0.00012,-0.0028,0.0027,-0.1,-0.11,-0.023,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1
10490000,0.77,-0.021,0.0048,-0.63,-0.028,-0.024,0.023,-0.0017,-0.0042,-3.7e+02,-8.3e-05,-0.0075,-0.00012,-0.0029,0.0028,-0.1,-0.11,-0.024,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,6.8e-05,0.0013,0.0007,0.0013,0.0013,1,1
10590000,0.77,-0.02,0.0045,-0.63,-0.026,-0.013,0.026,0.0015,-0.0009,-3.7e+02,-0.00027,-0.0074,-0.00011,-0.0021,0.0027,-0.1,-0.11,-0.024,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,6.8e-05,0.0013,0.0007,0.0013,0.0013,1,1
10690000,0.77,-0.02,0.0044,-0.63,-0.043,-0.014,0.03,-0.002,-0.0023,-3.7e+02,-0.00028,-0.0073,-0.00011,-0.0021,0.0028,-0.11,-0.11,-0.024,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,6.8e-05,0.0013,0.00069,0.0013,0.0013,1,1
10790000,0.77,-0.02,0.004,-0.63,-0.04,-0.0098,0.024,0.001,-0.001,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00033,0.0016,-0.11,-0.11,-0.024,0.5,-0.0028,-0.088,-0.069,0,0,0.001,0.001,0.053,0.091,0.092,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,6.8e-05,0.0013,0.00069,0.0013,0.0013,1,1
10890000,0.77,-0.02,0.0039,-0.63,-0.057,-0.012,0.02,-0.0037,-0.0022,-3.7e+02,-0.00035,-0.0071,-0.0001,-0.00027,0.0017,-0.11,-0.11,-0.024,0.5,-0.0028,-0.088,-0.069,0,0,0.00098,0.00098,0.053,0.099,0.1,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,6.7e-05,0.0013,0.00069,0.0013,0.0013,1,1
10990000,0.77,-0.02,0.0031,-0.63,-0.048,-0.0092,0.015,0.00014,-0.0011,-3.7e+02,-0.00038,-0.0069,-9.7e-05,0.0035,-0.0006,-0.11,-0.11,-0.024,0.5,-0.003,-0.089,-0.069,0,0,0.00093,0.00093,0.053,0.078,0.079,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,6.7e-05,0.0013,0.00069,0.0013,0.0013,1,1
11090000,0.77,-0.02,0.0028,-0.63,-0.06,-0.013,0.02,-0.0047,-0.0024,-3.7e+02,-0.00042,-0.0068,-9.2e-05,0.0035,-0.00017,-0.11,-0.11,-0.024,0.5,-0.003,-0.089,-0.069,0,0,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,6.7e-05,0.0013,0.00068,0.0013,0.0013,1,1
11190000,0.77,-0.019,0.0023,-0.63,-0.054,-0.0091,0.0082,0.0007,-0.00036,-3.7e+02,-0.00052,-0.0067,-8.9e-05,0.008,-0.0035,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.07,0,0,0.00085,0.00085,0.053,0.073,0.074,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,6.6e-05,0.0013,0.00068,0.0013,0.0013,1,1
11290000,0.77,-0.019,0.0024,-0.63,-0.069,-0.011,0.008,-0.0057,-0.0014,-3.7e+02,-0.00049,-0.0067,-9.1e-05,0.0081,-0.0036,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.069,0,0,0.00084,0.00084,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,6.6e-05,0.0013,0.00068,0.0013,0.0013,1,1
11390000,0.78,-0.019,0.002,-0.63,-0.064,-0.0096,0.0024,0.00035,-0.00029,-3.7e+02,-0.00058,-0.0067,-8.9e-05,0.012,-0.0074,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.07,0,0,0.00076,0.00077,0.052,0.068,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00068,0.0013,0.0012,1,1
11490000,0.78,-0.019,0.0022,-0.63,-0.078,-0.011,0.0032,-0.0072,-0.0011,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.024,0.5,-0.0032,-0.089,-0.07,0,0,0.00075,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00067,0.0013,0.0012,1,1
11590000,0.78,-0.019,0.0017,-0.63,-0.069,-0.011,-0.0027,-0.0022,-0.00067,-3.7e+02,-0.0006,-0.0067,-9.1e-05,0.017,-0.012,-0.11,-0.11,-0.024,0.5,-0.0033,-0.089,-0.07,0,0,0.00067,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,6.6e-05,0.0013,0.00067,0.0013,0.0012,1,1
11690000,0.78,-0.019,0.0018,-0.63,-0.08,-0.014,-0.0071,-0.0098,-0.0021,-3.7e+02,-0.00056,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.024,0.5,-0.0034,-0.089,-0.07,0,0,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0013,0.00067,0.0013,0.0012,1,1
11790000,0.78,-0.019,0.0012,-0.63,-0.072,-0.0097,-0.0089,-0.0061,-4.1e-05,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.015,-0.11,-0.11,-0.024,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.00061,0.051,0.065,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,6.5e-05,0.0013,0.00067,0.0013,0.0012,1,1
11890000,0.78,-0.019,0.0013,-0.63,-0.084,-0.01,-0.0098,-0.014,-0.001,-3.7e+02,-0.0006,-0.0066,-9.2e-05,0.023,-0.016,-0.11,-0.11,-0.024,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.0006,0.051,0.075,0.076,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,6.5e-05,0.0013,0.00066,0.0013,0.0012,1,1
11990000,0.78,-0.019,0.00071,-0.63,-0.072,-0.0052,-0.015,-0.009,0.0011,-3.7e+02,-0.00075,-0.0065,-8.7e-05,0.027,-0.019,-0.11,-0.11,-0.024,0.5,-0.0034,-0.09,-0.07,0,0,0.00052,0.00053,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8.1e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,6.5e-05,0.0013,0.00066,0.0013,0.0012,1,1
12090000,0.78,-0.018,0.00055,-0.63,-0.078,-0.0073,-0.021,-0.016,0.00038,-3.7e+02,-0.0008,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.024,0.5,-0.0034,-0.09,-0.07,0,0,0.00051,0.00053,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.5e-06,2.3e-06,0.028,0.028,0.01,0.0012,6.5e-05,0.0013,0.00066,0.0013,0.0012,1,1
12190000,0.78,-0.018,-0.00013,-0.63,-0.064,-0.0098,-0.016,-0.0085,-0.00012,-3.7e+02,-0.00081,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00045,0.00047,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,6.4e-05,0.0012,0.00066,0.0013,0.0012,1,1
12290000,0.78,-0.018,-0.00015,-0.63,-0.07,-0.012,-0.015,-0.015,-0.0016,-3.7e+02,-0.00078,-0.0064,-8.3e-05,0.033,-0.022,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.00045,0.00047,0.051,0.071,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.6e-06,2.3e-06,0.026,0.026,0.01,0.0012,6.4e-05,0.0012,0.00066,0.0013,0.0012,1,1
12390000,0.78,-0.018,-0.00055,-0.63,-0.057,-0.01,-0.013,-0.0083,-0.00071,-3.7e+02,-0.00085,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.5e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,6.4e-05,0.0012,0.00065,0.0013,0.0012,1,1
12490000,0.78,-0.018,-0.00042,-0.63,-0.065,-0.012,-0.016,-0.015,-0.0018,-3.7e+02,-0.00083,-0.0064,-8.5e-05,0.037,-0.027,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.0004,0.00041,0.05,0.068,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,6.4e-05,0.0012,0.00065,0.0013,0.0012,1,1
12590000,0.78,-0.018,-0.00062,-0.63,-0.06,-0.01,-0.022,-0.013,-0.00071,-3.7e+02,-0.00091,-0.0063,-8.3e-05,0.038,-0.028,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00036,0.00037,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.9e-06,6.4e-06,2.3e-06,0.022,0.022,0.0099,0.0012,6.4e-05,0.0012,0.00065,0.0013,0.0012,1,1
12690000,0.78,-0.018,-0.00055,-0.63,-0.065,-0.0094,-0.025,-0.019,-0.00092,-3.7e+02,-0.00098,-0.0064,-8.2e-05,0.036,-0.028,-0.11,-0.11,-0.024,0.5,-0.0035,-0.091,-0.07,0,0,0.00035,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.7e-06,6.2e-06,2.3e-06,0.022,0.022,0.0099,0.0012,6.3e-05,0.0012,0.00065,0.0013,0.0012,1,1
12790000,0.78,-0.018,-0.00083,-0.63,-0.061,-0.0086,-0.029,-0.017,-0.00085,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.039,-0.029,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00032,0.00033,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.02,0.021,0.0097,0.0012,6.3e-05,0.0012,0.00065,0.0013,0.0012,1,1
12890000,0.78,-0.018,-0.00082,-0.63,-0.068,-0.0098,-0.028,-0.024,-0.0022,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.041,-0.029,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.00032,0.00033,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.2e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,6.3e-05,0.0012,0.00065,0.0013,0.0012,1,1
12990000,0.78,-0.018,-0.0013,-0.63,-0.055,-0.0092,-0.028,-0.018,-0.0022,-3.7e+02,-0.00096,-0.0062,-8.1e-05,0.044,-0.031,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.054,0.055,0.025,0.057,0.057,0.052,4.9e-06,5.4e-06,2.3e-06,0.019,0.02,0.0094,0.0012,6.3e-05,0.0012,0.00065,0.0013,0.0012,1,1
13090000,0.78,-0.018,-0.0012,-0.63,-0.061,-0.009,-0.028,-0.024,-0.0029,-3.7e+02,-0.00094,-0.0063,-8.3e-05,0.045,-0.033,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,6.3e-05,0.0012,0.00064,0.0012,0.0012,1,1
13190000,0.78,-0.018,-0.0015,-0.63,-0.049,-0.0085,-0.025,-0.017,-0.0023,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.035,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00027,0.00028,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,6.3e-05,0.0012,0.00064,0.0012,0.0012,1,1
13290000,0.78,-0.018,-0.0016,-0.63,-0.053,-0.011,-0.022,-0.022,-0.0043,-3.7e+02,-0.00094,-0.0062,-8.2e-05,0.049,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00026,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.018,0.0091,0.0012,6.3e-05,0.0012,0.00064,0.0012,0.0012,1,1
13390000,0.78,-0.018,-0.0018,-0.63,-0.044,-0.011,-0.018,-0.016,-0.0036,-3.7e+02,-0.00098,-0.0062,-8.1e-05,0.051,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00024,0.00026,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,6.2e-05,0.0012,0.00064,0.0012,0.0012,1,1
13490000,0.78,-0.018,-0.0019,-0.63,-0.047,-0.012,-0.016,-0.021,-0.0051,-3.7e+02,-0.00097,-0.0062,-8e-05,0.051,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00024,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.5e-06,2.3e-06,0.017,0.017,0.0087,0.0012,6.2e-05,0.0012,0.00064,0.0012,0.0012,1,1
13590000,0.78,-0.018,-0.002,-0.63,-0.038,-0.011,-0.019,-0.014,-0.0037,-3.7e+02,-0.001,-0.0062,-8.1e-05,0.053,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00024,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,6.2e-05,0.0012,0.00064,0.0012,0.0012,1,1
13690000,0.78,-0.018,-0.0021,-0.63,-0.041,-0.014,-0.023,-0.018,-0.0054,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.053,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00024,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.8e-06,4.2e-06,2.3e-06,0.016,0.017,0.0083,0.0012,6.2e-05,0.0012,0.00064,0.0012,0.0012,1,1
13790000,0.78,-0.018,-0.0023,-0.63,-0.03,-0.012,-0.024,-0.0067,-0.0043,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.038,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
13890000,0.78,-0.018,-0.0023,-0.63,-0.033,-0.014,-0.029,-0.01,-0.0061,-3.7e+02,-0.00099,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00021,0.00022,0.049,0.048,0.048,0.03,0.079,0.08,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
13990000,0.78,-0.018,-0.0025,-0.63,-0.025,-0.013,-0.028,-0.0036,-0.0053,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.038,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.4e-06,3.7e-06,2.4e-06,0.014,0.015,0.0074,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
14090000,0.78,-0.018,-0.0025,-0.63,-0.026,-0.014,-0.029,-0.0058,-0.0068,-3.7e+02,-0.001,-0.0061,-7.7e-05,0.055,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00019,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.3e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
14190000,0.78,-0.017,-0.0027,-0.63,-0.021,-0.012,-0.031,-0.00022,-0.0047,-3.7e+02,-0.0011,-0.006,-7.6e-05,0.057,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.013,0.014,0.0069,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
14290000,0.78,-0.017,-0.0027,-0.63,-0.022,-0.014,-0.03,-0.0022,-0.006,-3.7e+02,-0.0011,-0.006,-7.5e-05,0.057,-0.036,-0.12,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00018,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3.1e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
14390000,0.78,-0.017,-0.0029,-0.63,-0.017,-0.014,-0.032,0.0018,-0.0047,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.059,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
14490000,0.78,-0.017,-0.0029,-0.63,-0.019,-0.017,-0.035,-0.00047,-0.0066,-3.7e+02,-0.001,-0.006,-7.4e-05,0.061,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.9e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
14590000,0.78,-0.017,-0.0028,-0.63,-0.02,-0.017,-0.035,-0.0013,-0.0063,-3.7e+02,-0.00099,-0.006,-7.5e-05,0.062,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00017,0.00018,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
14690000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.016,-0.032,-0.0035,-0.0082,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.063,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00018,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
14790000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.016,-0.028,-0.0036,-0.0076,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
14890000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.019,-0.031,-0.0061,-0.0095,-3.7e+02,-0.00097,-0.006,-7.3e-05,0.064,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
14990000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.016,-0.027,-0.0047,-0.0074,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.011,0.012,0.0048,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
15090000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.016,-0.03,-0.0072,-0.009,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
15190000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.015,-0.027,-0.0058,-0.0073,-3.7e+02,-0.00096,-0.006,-7.5e-05,0.066,-0.038,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
15290000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.017,-0.025,-0.0081,-0.0089,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
15390000,0.78,-0.017,-0.0029,-0.63,-0.025,-0.017,-0.023,-0.0076,-0.0091,-3.7e+02,-0.00099,-0.006,-7.1e-05,0.066,-0.036,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
15490000,0.78,-0.017,-0.0028,-0.63,-0.028,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.00099,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.5e-06,2.4e-06,0.011,0.011,0.0037,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
15590000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.016,-0.022,-0.0097,-0.0098,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2.1e-06,2.4e-06,2.4e-06,0.01,0.011,0.0035,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
15690000,0.78,-0.017,-0.0027,-0.63,-0.027,-0.016,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
15790000,0.78,-0.017,-0.0028,-0.63,-0.025,-0.015,-0.025,-0.0085,-0.0096,-3.7e+02,-0.001,-0.006,-7.3e-05,0.065,-0.038,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00014,0.00015,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.3e-06,2.4e-06,0.01,0.011,0.0031,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
15890000,0.78,-0.017,-0.0027,-0.63,-0.027,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.0099,0.011,0.003,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
15990000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.016,-0.018,-0.0079,-0.0099,-3.7e+02,-0.001,-0.006,-7.1e-05,0.065,-0.037,-0.13,-0.11,-0.024,0.5,-0.004,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0028,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
16090000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.018,-0.015,-0.01,-0.012,-3.7e+02,-0.0011,-0.006,-6.8e-05,0.065,-0.036,-0.13,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0096,0.01,0.0027,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
16190000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.016,-0.014,-0.0074,-0.0092,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.064,-0.036,-0.13,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0094,0.01,0.0025,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
16290000,0.78,-0.017,-0.003,-0.63,-0.026,-0.018,-0.015,-0.0099,-0.011,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.065,-0.035,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0093,0.01,0.0024,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
16390000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.014,-0.014,-0.0074,-0.0088,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.7e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0022,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
16490000,0.78,-0.017,-0.0029,-0.63,-0.022,-0.016,-0.017,-0.0094,-0.01,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.063,-0.035,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0091,0.01,0.0021,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
16590000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.012,-0.018,-0.0097,-0.0063,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.063,-0.035,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.9e-06,2.4e-06,0.0089,0.0098,0.002,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
16690000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.012,-0.014,-0.012,-0.0073,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.0088,0.0097,0.0019,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
16790000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.0091,-0.013,-0.012,-0.004,-3.7e+02,-0.0011,-0.006,-6e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0087,0.0096,0.0018,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
16890000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.01,-0.01,-0.014,-0.0048,-3.7e+02,-0.0011,-0.006,-6e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0086,0.0095,0.0017,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
16990000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.0099,-0.0099,-0.013,-0.0047,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.062,-0.037,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0085,0.0094,0.0016,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
17090000,0.78,-0.017,-0.0027,-0.63,-0.025,-0.012,-0.0098,-0.015,-0.0057,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.062,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0084,0.0093,0.0015,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
17190000,0.78,-0.017,-0.0028,-0.63,-0.023,-0.014,-0.011,-0.014,-0.006,-3.7e+02,-0.0012,-0.006,-6e-05,0.061,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.4e-06,1.6e-06,2.4e-06,0.0083,0.0092,0.0015,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
17290000,0.78,-0.017,-0.0027,-0.63,-0.026,-0.015,-0.0061,-0.016,-0.0071,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0083,0.0091,0.0014,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
17390000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.017,-0.0042,-0.013,-0.0073,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.091,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0082,0.009,0.0013,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
17490000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.018,-0.0025,-0.016,-0.0091,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0081,0.0089,0.0013,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
17590000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.018,0.003,-0.014,-0.0088,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.008,0.0088,0.0012,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
17690000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.5e-06,2.4e-06,0.0079,0.0087,0.0011,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
17790000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.06,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.0011,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
17890000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.022,0.0012,-0.017,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.001,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
17990000,0.78,-0.017,-0.0028,-0.63,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0077,0.0085,0.00099,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
18090000,0.78,-0.017,-0.0028,-0.63,-0.027,-0.02,0.0047,-0.018,-0.015,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00096,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
18190000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0083,0.0009,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
18290000,0.78,-0.017,-0.0027,-0.63,-0.025,-0.019,0.0072,-0.016,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0075,0.0082,0.00087,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
18390000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.02,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.9e-05,0.062,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0074,0.0082,0.00083,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
18490000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.022,0.0081,-0.014,-0.014,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0074,0.0081,0.0008,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
18590000,0.78,-0.016,-0.0028,-0.63,-0.022,-0.022,0.0062,-0.011,-0.012,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0073,0.008,0.00076,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
18690000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.062,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0072,0.008,0.00074,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
18790000,0.78,-0.017,-0.0027,-0.63,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.0007,0.0012,5.9e-05,0.0012,0.0006,0.0012,0.0012,1,1
18890000,0.78,-0.016,-0.0028,-0.63,-0.022,-0.023,0.0046,-0.014,-0.015,-3.7e+02,-0.0013,-0.006,-3.9e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.00068,0.0012,5.9e-05,0.0012,0.0006,0.0012,0.0012,1,1
18990000,0.78,-0.016,-0.0029,-0.63,-0.019,-0.023,0.0033,-0.0094,-0.013,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.007,0.0078,0.00065,0.0012,5.9e-05,0.0012,0.0006,0.0012,0.0012,1,1
19090000,0.78,-0.016,-0.0028,-0.63,-0.019,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.5e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.007,0.0077,0.00063,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
19190000,0.78,-0.016,-0.0029,-0.63,-0.015,-0.024,0.0063,-0.0074,-0.013,-3.7e+02,-0.0013,-0.006,-3.1e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0069,0.0076,0.0006,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
19290000,0.78,-0.016,-0.0029,-0.63,-0.016,-0.024,0.0091,-0.0091,-0.015,-3.7e+02,-0.0013,-0.006,-3.3e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.0069,0.0076,0.00058,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
19390000,0.78,-0.016,-0.0028,-0.63,-0.015,-0.022,0.013,-0.0081,-0.014,-3.7e+02,-0.0013,-0.006,-2.9e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.0068,0.0075,0.00056,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
19490000,0.78,-0.016,-0.0029,-0.63,-0.015,-0.023,0.0093,-0.0097,-0.017,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0068,0.0075,0.00055,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
19590000,0.78,-0.016,-0.003,-0.63,-0.014,-0.022,0.0085,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,-1.9e-05,0.06,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,8e-07,9.7e-07,2.3e-06,0.0067,0.0074,0.00052,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
19690000,0.78,-0.016,-0.003,-0.63,-0.014,-0.02,0.01,-0.0091,-0.017,-3.7e+02,-0.0013,-0.006,-2.1e-05,0.059,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.9e-07,9.6e-07,2.3e-06,0.0067,0.0074,0.00051,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
19790000,0.78,-0.016,-0.003,-0.63,-0.012,-0.018,0.01,-0.0077,-0.015,-3.7e+02,-0.0013,-0.006,-1.7e-05,0.058,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0066,0.0073,0.00049,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
19890000,0.78,-0.016,-0.003,-0.63,-0.012,-0.02,0.012,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,-1.4e-05,0.059,-0.032,-0.13,-0.11,-0.024,0.5,-0.0031,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0066,0.0073,0.00048,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
19990000,0.78,-0.016,-0.0031,-0.63,-0.0098,-0.02,0.014,-0.0081,-0.016,-3.7e+02,-0.0013,-0.0059,-4.7e-06,0.06,-0.031,-0.13,-0.11,-0.024,0.5,-0.003,-0.092,-0.068,0,0,9.8e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0066,0.0072,0.00046,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20090000,0.78,-0.016,-0.0031,-0.63,-0.0098,-0.021,0.015,-0.0088,-0.019,-3.7e+02,-0.0013,-0.0059,7.1e-08,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.8e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0065,0.0072,0.00045,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20190000,0.78,-0.016,-0.0032,-0.63,-0.01,-0.019,0.017,-0.009,-0.018,-3.7e+02,-0.0013,-0.0059,6e-06,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0065,0.0071,0.00043,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20290000,0.78,-0.016,-0.0032,-0.63,-0.0091,-0.019,0.015,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,7.8e-06,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0064,0.0071,0.00042,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20390000,0.78,-0.016,-0.0032,-0.63,-0.0087,-0.016,0.017,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0064,0.007,0.00041,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20490000,0.78,-0.016,-0.0032,-0.63,-0.0089,-0.017,0.017,-0.01,-0.019,-3.7e+02,-0.0013,-0.0059,1e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0064,0.007,0.0004,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20590000,0.78,-0.016,-0.0032,-0.63,-0.0084,-0.014,0.014,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0063,0.0069,0.00038,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20690000,0.78,-0.016,-0.0032,-0.63,-0.0091,-0.015,0.015,-0.0096,-0.018,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0063,0.0069,0.00037,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20790000,0.78,-0.016,-0.0032,-0.63,-0.0068,-0.014,0.015,-0.008,-0.016,-3.7e+02,-0.0013,-0.0059,1.8e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0062,0.0068,0.00036,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20890000,0.78,-0.016,-0.0033,-0.63,-0.007,-0.014,0.014,-0.0086,-0.018,-3.7e+02,-0.0013,-0.0059,2.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0062,0.0068,0.00035,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
20990000,0.78,-0.016,-0.0033,-0.63,-0.0054,-0.012,0.015,-0.0083,-0.018,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.3e-05,9.9e-05,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0062,0.0067,0.00034,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
21090000,0.78,-0.016,-0.0033,-0.63,-0.0065,-0.012,0.015,-0.0092,-0.02,-3.7e+02,-0.0013,-0.0059,2.6e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.3e-05,9.9e-05,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0061,0.0067,0.00034,0.0011,5.8e-05,0.0012,0.00059,0.0012,0.0012,1,1
21190000,0.78,-0.016,-0.0033,-0.63,-0.0066,-0.011,0.014,-0.0097,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.4e-07,2.3e-06,0.0061,0.0067,0.00033,0.0011,5.8e-05,0.0012,0.00059,0.0012,0.0012,1,1
21290000,0.78,-0.016,-0.0034,-0.63,-0.0061,-0.012,0.016,-0.0097,-0.022,-3.7e+02,-0.0013,-0.0059,3.2e-05,0.061,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,9.3e-05,9.8e-05,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0061,0.0066,0.00032,0.0011,5.8e-05,0.0012,0.00059,0.0012,0.0012,1,1
21390000,0.78,-0.016,-0.0034,-0.63,-0.0055,-0.0073,0.016,-0.0085,-0.017,-3.7e+02,-0.0013,-0.0059,3.5e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.006,0.0066,0.00031,0.0011,5.8e-05,0.0012,0.00059,0.0012,0.0012,1,1
21490000,0.78,-0.016,-0.0034,-0.63,-0.0061,-0.0083,0.016,-0.0096,-0.018,-3.7e+02,-0.0013,-0.0059,3.7e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.006,0.0065,0.0003,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
21590000,0.78,-0.016,-0.0034,-0.63,-0.0047,-0.0066,0.016,-0.008,-0.014,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.5e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.006,0.0065,0.0003,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
21690000,0.78,-0.016,-0.0034,-0.63,-0.0063,-0.0077,0.017,-0.0093,-0.016,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.5e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.0059,0.0065,0.00029,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
21790000,0.78,-0.016,-0.0032,-0.63,-0.0053,-0.0054,0.016,-0.0081,-0.01,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
21890000,0.78,-0.016,-0.0033,-0.63,-0.006,-0.0063,0.016,-0.0088,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
21990000,0.78,-0.016,-0.0032,-0.63,-0.0059,-0.0035,0.017,-0.0082,-0.0069,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0058,0.0064,0.00027,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22090000,0.78,-0.016,-0.0032,-0.63,-0.0056,-0.0051,0.015,-0.0086,-0.0073,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0058,0.0063,0.00027,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22190000,0.78,-0.016,-0.0032,-0.63,-0.0042,-0.0057,0.015,-0.0072,-0.0066,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0058,0.0063,0.00026,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22290000,0.78,-0.016,-0.0032,-0.63,-0.0038,-0.0053,0.016,-0.0079,-0.007,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0058,0.0063,0.00025,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22390000,0.78,-0.016,-0.0032,-0.63,-0.0013,-0.0053,0.017,-0.0061,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0057,0.0062,0.00025,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22490000,0.78,-0.016,-0.0033,-0.63,-0.00015,-0.006,0.018,-0.0055,-0.0067,-3.7e+02,-0.0014,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22590000,0.78,-0.016,-0.0032,-0.63,0.0017,-0.0049,0.017,-0.0038,-0.0061,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22690000,0.78,-0.016,-0.0033,-0.63,0.0032,-0.0063,0.019,-0.0031,-0.0072,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.059,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22790000,0.78,-0.016,-0.0032,-0.63,0.0043,-0.0055,0.02,-0.0026,-0.0058,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0061,0.00023,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22890000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0065,0.021,-0.0027,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0056,0.0061,0.00023,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
22990000,0.78,-0.016,-0.0032,-0.63,0.0047,-0.0067,0.022,-0.0028,-0.0074,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
23090000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0064,0.023,-0.0026,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
23190000,0.78,-0.016,-0.0032,-0.63,0.0025,-0.0052,0.024,-0.0053,-0.0071,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
23290000,0.78,-0.016,-0.0031,-0.63,0.0021,-0.005,0.025,-0.0056,-0.008,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
23390000,0.78,-0.016,-0.0032,-0.63,-0.0012,-0.0047,0.022,-0.0098,-0.0083,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0055,0.006,0.00021,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
23490000,0.78,-0.013,-0.0053,-0.63,0.0044,-0.0044,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0055,0.006,0.0002,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
23590000,0.78,-0.0046,-0.0096,-0.63,0.015,-0.00043,-0.043,-0.0096,-0.0059,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,5.7e-05,0.0012,0.00058,0.0012,0.0012,1,1
23690000,0.78,0.001,-0.0086,-0.63,0.043,0.013,-0.093,-0.0072,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
23790000,0.78,-0.0026,-0.0061,-0.63,0.064,0.031,-0.15,-0.0072,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
23890000,0.78,-0.0089,-0.0042,-0.63,0.078,0.042,-0.2,0.00038,-9.2e-05,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.091,-0.067,0,0,8.1e-05,8.6e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
23990000,0.78,-0.014,-0.0033,-0.63,0.073,0.042,-0.25,-0.0051,-0.0016,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
24090000,0.78,-0.012,-0.0045,-0.63,0.073,0.041,-0.3,0.0013,0.0017,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0058,0.00019,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
24190000,0.78,-0.01,-0.0053,-0.62,0.071,0.04,-0.35,-0.0059,-0.00051,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
24290000,0.78,-0.0092,-0.0057,-0.62,0.079,0.045,-0.4,0.00061,0.0038,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
24390000,0.78,-0.0096,-0.0058,-0.62,0.076,0.043,-0.46,-0.012,-0.0026,-3.7e+02,-0.0012,-0.0059,6.8e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
24490000,0.78,-0.0054,-0.0062,-0.62,0.087,0.05,-0.51,-0.0037,0.002,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.5e-05,0.0012,0.00058,0.0012,0.0012,1,1
24590000,0.78,-0.0019,-0.0064,-0.62,0.091,0.054,-0.56,-0.017,-0.0068,-3.7e+02,-0.0012,-0.0059,6.3e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.5e-05,0.0012,0.00058,0.0011,0.0012,1,1
24690000,0.78,-0.001,-0.0064,-0.62,0.11,0.069,-0.64,-0.0078,-0.002,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0028,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.5e-05,0.0012,0.00058,0.0011,0.0012,1,1
24790000,0.78,-0.0025,-0.0063,-0.62,0.11,0.078,-0.73,-0.027,-0.0066,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0026,-0.09,-0.068,0,0,8e-05,8.4e-05,0.047,0.018,0.019,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.5e-05,0.0012,0.00058,0.0011,0.0012,1,1
24890000,0.78,-0.00067,-0.0078,-0.62,0.13,0.092,-0.75,-0.016,0.0019,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0027,-0.089,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.5e-05,0.0012,0.00058,0.0011,0.0012,1,1
24990000,0.78,0.0011,-0.0094,-0.62,0.14,0.1,-0.81,-0.038,-0.0043,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0024,-0.089,-0.069,0,0,8e-05,8.4e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.4e-05,0.0012,0.00058,0.0011,0.0012,1,1
25090000,0.78,0.00051,-0.0098,-0.62,0.16,0.12,-0.86,-0.023,0.0069,-3.7e+02,-0.0011,-0.0059,4.1e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0025,-0.088,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.4e-05,0.0012,0.00058,0.0011,0.0012,1,1
25190000,0.78,-0.0014,-0.0095,-0.62,0.15,0.11,-0.91,-0.067,-0.015,-3.7e+02,-0.0011,-0.0058,2.1e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0022,-0.088,-0.069,0,0,8e-05,8.3e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.4e-05,0.0012,0.00057,0.0011,0.0012,1,1
25290000,0.78,0.0055,-0.011,-0.62,0.18,0.12,-0.96,-0.051,-0.0042,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.3e-05,0.0012,0.00057,0.0011,0.0012,1,1
25390000,0.79,0.012,-0.011,-0.62,0.18,0.13,-1,-0.099,-0.028,-3.7e+02,-0.001,-0.0058,4.8e-06,0.078,-0.03,-0.13,-0.12,-0.025,0.5,-0.0021,-0.087,-0.069,0,0,8e-05,8.3e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00016,0.0011,5.3e-05,0.0012,0.00057,0.0011,0.0012,1,1
25490000,0.78,0.013,-0.011,-0.62,0.22,0.16,-1.1,-0.08,-0.015,-3.7e+02,-0.001,-0.0058,1.4e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0024,-0.086,-0.069,0,0,8.1e-05,8.4e-05,0.046,0.022,0.023,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.2e-05,0.0012,0.00056,0.0011,0.0011,1,1
25590000,0.78,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.057,0.00066,-3.7e+02,-0.001,-0.0058,1.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.4e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.2e-05,0.0011,0.00056,0.0011,0.0011,1,1
25690000,0.78,0.018,-0.014,-0.62,0.3,0.21,-1.2,-0.03,0.019,-3.7e+02,-0.00099,-0.0058,2.7e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0031,-0.084,-0.068,0,0,8.2e-05,8.5e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.1e-05,0.0011,0.00056,0.0011,0.0011,1,1
25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0028,0.039,-3.7e+02,-0.00099,-0.0058,3.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0035,-0.083,-0.067,0,0,8.3e-05,8.5e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5e-05,0.0011,0.00056,0.001,0.0011,1,1
25890000,0.78,0.025,-0.016,-0.63,0.41,0.28,-1.3,0.042,0.062,-3.7e+02,-0.00099,-0.0058,5.3e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.6e-05,0.045,0.029,0.031,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.00098,4.9e-05,0.0011,0.00056,0.001,0.0011,1,1
25990000,0.78,0.022,-0.016,-0.63,0.47,0.32,-1.3,0.086,0.089,-3.7e+02,-0.00099,-0.0058,6.2e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0045,-0.08,-0.065,0,0,8.4e-05,8.6e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00096,4.8e-05,0.0011,0.00055,0.001,0.0011,1,1
26090000,0.78,0.032,-0.02,-0.62,0.53,0.35,-1.3,0.14,0.12,-3.7e+02,-0.00098,-0.0058,6e-05,0.079,-0.031,-0.13,-0.12,-0.027,0.5,-0.0046,-0.079,-0.065,0,0,8.5e-05,8.7e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00094,4.7e-05,0.0011,0.00054,0.00098,0.0011,1,1
26190000,0.78,0.042,-0.021,-0.62,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.1e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.5,-0.0054,-0.075,-0.063,0,0,8.6e-05,8.7e-05,0.043,0.035,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00014,0.00091,4.6e-05,0.001,0.00053,0.00094,0.001,1,1
26290000,0.78,0.044,-0.022,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.4e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.49,-0.0057,-0.073,-0.061,0,0,8.7e-05,8.8e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00088,4.4e-05,0.001,0.00052,0.00091,0.00099,1,1
26390000,0.78,0.041,-0.022,-0.63,0.76,0.5,-1.3,0.33,0.24,-3.7e+02,-0.00097,-0.0058,8.2e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,8.9e-05,0.041,0.041,0.047,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00085,4.3e-05,0.00097,0.00051,0.00088,0.00096,1,1
26490000,0.77,0.057,-0.028,-0.63,0.84,0.55,-1.3,0.41,0.29,-3.7e+02,-0.00097,-0.0058,8.7e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0065,-0.069,-0.058,0,0,8.9e-05,8.9e-05,0.039,0.044,0.051,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00081,4.1e-05,0.00093,0.00049,0.00084,0.00093,1,1
26590000,0.77,0.074,-0.033,-0.63,0.96,0.63,-1.3,0.49,0.35,-3.7e+02,-0.00096,-0.0058,8.1e-05,0.08,-0.032,-0.13,-0.14,-0.03,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9e-05,0.038,0.048,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00077,3.9e-05,0.00088,0.00047,0.0008,0.00088,1,1
26690000,0.77,0.077,-0.034,-0.64,1.1,0.71,-1.3,0.6,0.41,-3.7e+02,-0.00096,-0.0058,9.7e-05,0.08,-0.032,-0.13,-0.14,-0.031,0.49,-0.0073,-0.061,-0.052,0,0,9e-05,9.1e-05,0.035,0.052,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00071,3.6e-05,0.00082,0.00045,0.00074,0.00082,1,1
26790000,0.77,0.071,-0.033,-0.64,1.2,0.79,-1.3,0.71,0.48,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.08,-0.032,-0.13,-0.14,-0.032,0.48,-0.0071,-0.057,-0.049,0,0,9.1e-05,9.1e-05,0.032,0.055,0.068,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00067,3.4e-05,0.00078,0.00041,0.00069,0.00077,1,1
26890000,0.76,0.093,-0.04,-0.64,1.4,0.86,-1.3,0.85,0.56,-3.7e+02,-0.00095,-0.0058,0.0001,0.08,-0.032,-0.13,-0.15,-0.033,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.2e-05,0.03,0.059,0.073,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00063,3.2e-05,0.00073,0.00039,0.00065,0.00073,1,1
26990000,0.76,0.12,-0.045,-0.64,1.5,0.97,-1.3,0.99,0.65,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.034,0.48,-0.0079,-0.047,-0.043,0,0,9.2e-05,9.2e-05,0.027,0.062,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00057,3e-05,0.00066,0.00035,0.00059,0.00066,1,1
27090000,0.76,0.12,-0.045,-0.64,1.7,1.1,-1.3,1.2,0.75,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.035,0.47,-0.0078,-0.043,-0.038,0,0,9.3e-05,9.3e-05,0.024,0.066,0.086,0.0061,0.36,0.37,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00052,2.7e-05,0.00059,0.00031,0.00053,0.00059,1,1
27190000,0.76,0.11,-0.043,-0.64,1.9,1.2,-1.2,1.3,0.87,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.16,-0.036,0.47,-0.0074,-0.04,-0.035,0,0,9.3e-05,9.3e-05,0.021,0.07,0.092,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00048,2.5e-05,0.00055,0.00028,0.00049,0.00054,1,1
27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,0.99,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.036,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.4e-05,0.019,0.071,0.095,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00045,2.4e-05,0.00052,0.00026,0.00046,0.00051,1,1
27390000,0.76,0.078,-0.034,-0.64,2.2,1.4,-1.2,1.7,1.1,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.037,0.47,-0.0074,-0.035,-0.032,0,0,9.4e-05,9.4e-05,0.017,0.072,0.095,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00043,2.3e-05,0.0005,0.00023,0.00044,0.00049,1,1
27490000,0.76,0.062,-0.029,-0.64,2.2,1.4,-1.2,2,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.029,-0.13,-0.17,-0.037,0.47,-0.0071,-0.034,-0.032,0,0,9.5e-05,9.5e-05,0.015,0.073,0.094,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00042,2.2e-05,0.00049,0.00021,0.00043,0.00048,1,1
27590000,0.77,0.049,-0.025,-0.64,2.3,1.5,-1.2,2.2,1.4,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.028,-0.13,-0.17,-0.037,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.5e-05,0.014,0.073,0.093,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00041,2.2e-05,0.00048,0.0002,0.00042,0.00048,1,1
27690000,0.77,0.048,-0.025,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.081,-0.027,-0.13,-0.17,-0.037,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.013,0.073,0.091,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00013,0.0004,2.1e-05,0.00048,0.00018,0.00042,0.00047,1,1
27790000,0.77,0.05,-0.025,-0.64,2.3,1.5,-1.2,2.6,1.7,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.037,0.47,-0.0055,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.012,0.073,0.09,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.0004,2.1e-05,0.00047,0.00017,0.00041,0.00047,1,1
27890000,0.77,0.048,-0.024,-0.64,2.4,1.6,-1.2,2.9,1.9,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.46,-0.0055,-0.031,-0.031,0,0,9.8e-05,9.7e-05,0.011,0.074,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.1e-05,0.00047,0.00016,0.0004,0.00047,1,1
27990000,0.77,0.044,-0.024,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.1e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0055,-0.031,-0.031,0,0,9.9e-05,9.7e-05,0.01,0.075,0.089,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00038,2e-05,0.00047,0.00015,0.0004,0.00046,1,1
28090000,0.77,0.057,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.2,-3.7e+02,-0.00095,-0.0058,8.6e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.8e-05,0.0096,0.076,0.089,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00038,2e-05,0.00046,0.00015,0.00039,0.00046,1,1
28190000,0.77,0.071,-0.032,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,8.5e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0091,0.077,0.089,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00037,2e-05,0.00046,0.00014,0.00038,0.00045,1,1
28290000,0.77,0.053,-0.026,-0.63,2.5,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.1e-05,0.083,-0.024,-0.13,-0.17,-0.038,0.46,-0.0047,-0.029,-0.029,0,0,0.0001,9.9e-05,0.0086,0.076,0.087,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00014,0.00038,0.00045,1,1
28390000,0.77,0.02,-0.013,-0.64,2.4,1.7,0.79,4,2.7,-3.7e+02,-0.00095,-0.0058,7.6e-05,0.083,-0.023,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00013,0.00037,0.00045,1,1
28490000,0.77,0.0015,-0.0059,-0.64,2.4,1.7,1.1,4.3,2.9,-3.7e+02,-0.00096,-0.0058,7.1e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.076,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00013,0.00037,0.00045,1,1
28590000,0.77,-0.0022,-0.0045,-0.63,2.3,1.6,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00012,0.00037,0.00044,1,1
28690000,0.77,-0.0032,-0.0039,-0.63,2.3,1.6,0.99,4.8,3.2,-3.7e+02,-0.00097,-0.0058,6.6e-05,0.082,-0.022,-0.12,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00012,0.00037,0.00044,1,1
28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.4,-3.7e+02,-0.00097,-0.0058,6.1e-05,0.082,-0.021,-0.12,-0.17,-0.038,0.46,-0.0041,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00044,0.00011,0.00037,0.00044,1,1
28890000,0.78,-0.0033,-0.0037,-0.63,2.2,1.5,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,5.8e-05,0.081,-0.021,-0.12,-0.17,-0.038,0.46,-0.0041,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.006,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.00011,0.00037,0.00044,1,1
28990000,0.78,-0.0029,-0.0038,-0.63,2.1,1.5,0.98,5.4,3.7,-3.7e+02,-0.00099,-0.0058,5.1e-05,0.08,-0.02,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.00011,0.00037,0.00044,1,1
29090000,0.78,-0.0024,-0.004,-0.63,2,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.086,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.00011,0.00037,0.00043,1,1
29190000,0.78,-0.0022,-0.004,-0.63,2,1.5,0.97,5.9,4,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.082,0.088,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.0001,0.00037,0.00043,1,1
29290000,0.78,-0.0013,-0.0043,-0.63,1.9,1.4,0.99,6.1,4.2,-3.7e+02,-0.001,-0.0058,4.2e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0036,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.0001,0.00037,0.00043,1,1
29390000,0.78,7.3e-05,-0.0046,-0.63,1.9,1.4,1,6.2,4.3,-3.7e+02,-0.001,-0.0058,3.5e-05,0.079,-0.018,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,1.9e-05,0.00043,0.0001,0.00037,0.00043,1,1
29490000,0.78,0.0012,-0.005,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,1.9e-05,0.00043,0.0001,0.00037,0.00043,1,1
29590000,0.78,0.0023,-0.0052,-0.63,1.8,1.4,1,6.6,4.6,-3.7e+02,-0.001,-0.0057,3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.8e-05,0.00037,0.00043,1,1
29690000,0.78,0.0029,-0.0055,-0.63,1.7,1.3,0.99,6.8,4.7,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.016,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.7e-05,0.00037,0.00043,1,1
29790000,0.78,0.0034,-0.0056,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0057,2.2e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.027,0,0,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.6e-05,0.00037,0.00042,1,1
29890000,0.78,0.0035,-0.0057,-0.63,1.7,1.3,0.97,7.2,5,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.4e-05,0.00037,0.00042,1,1
29990000,0.78,0.0036,-0.0057,-0.63,1.6,1.3,0.95,7.3,5.1,-3.7e+02,-0.001,-0.0057,1.2e-05,0.077,-0.014,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.3e-05,0.00036,0.00042,1,1
30090000,0.78,0.0035,-0.0057,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0057,8.4e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00043,9.2e-05,0.00036,0.00042,1,1
30190000,0.78,0.0032,-0.0057,-0.63,1.6,1.3,0.93,7.6,5.4,-3.7e+02,-0.001,-0.0057,9.5e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00043,9.2e-05,0.00036,0.00042,1,1
30290000,0.78,0.003,-0.0056,-0.63,1.5,1.2,0.92,7.8,5.5,-3.7e+02,-0.001,-0.0057,6.5e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00043,9.1e-05,0.00036,0.00042,1,1
30390000,0.78,0.0028,-0.0056,-0.63,1.5,1.2,0.9,8,5.6,-3.7e+02,-0.0011,-0.0057,2.3e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,9e-05,0.00036,0.00042,1,1
30490000,0.78,0.0025,-0.0055,-0.63,1.5,1.2,0.89,8.1,5.8,-3.7e+02,-0.0011,-0.0057,1.2e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,8.9e-05,0.00036,0.00042,1,1
30590000,0.78,0.002,-0.0054,-0.63,1.4,1.2,0.85,8.3,5.9,-3.7e+02,-0.0011,-0.0057,-8.9e-07,0.076,-0.011,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,8.9e-05,0.00036,0.00042,1,1
30690000,0.78,0.0017,-0.0053,-0.63,1.4,1.2,0.84,8.4,6,-3.7e+02,-0.0011,-0.0057,-4.2e-06,0.075,-0.0099,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.0059,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,8.8e-05,0.00036,0.00042,1,1
30790000,0.78,0.0013,-0.0052,-0.63,1.4,1.2,0.84,8.6,6.1,-3.7e+02,-0.0011,-0.0057,-7.3e-06,0.075,-0.0096,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,8.8e-05,0.00036,0.00042,1,1
30890000,0.78,0.00088,-0.0051,-0.63,1.4,1.1,0.82,8.7,6.2,-3.7e+02,-0.0011,-0.0057,-1e-05,0.074,-0.0089,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00035,1.8e-05,0.00042,8.7e-05,0.00036,0.00042,1,1
30990000,0.78,0.00029,-0.005,-0.63,1.3,1.1,0.82,8.9,6.3,-3.7e+02,-0.0011,-0.0057,-1.4e-05,0.074,-0.0081,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0052,9.9e-05,0.00035,1.8e-05,0.00042,8.7e-05,0.00036,0.00041,1,1
31090000,0.78,-0.00026,-0.0048,-0.63,1.3,1.1,0.81,9,6.5,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0074,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0048,0.0052,9.8e-05,0.00035,1.8e-05,0.00042,8.6e-05,0.00036,0.00041,1,1
31190000,0.78,-0.00067,-0.0047,-0.63,1.3,1.1,0.8,9.1,6.6,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.074,-0.0066,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00034,1.8e-05,0.00042,8.6e-05,0.00036,0.00041,1,1
31290000,0.78,-0.0013,-0.0046,-0.63,1.2,1.1,0.8,9.3,6.7,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.073,-0.0059,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00034,1.8e-05,0.00042,8.5e-05,0.00036,0.00041,1,1
31390000,0.78,-0.002,-0.0044,-0.63,1.2,1.1,0.8,9.4,6.8,-3.7e+02,-0.0011,-0.0057,-2.6e-05,0.073,-0.0053,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.027,0,0,0.00013,0.0001,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.6e-05,0.00034,1.8e-05,0.00042,8.5e-05,0.00036,0.00041,1,1
31490000,0.78,-0.0026,-0.0042,-0.63,1.2,1,0.79,9.5,6.9,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.073,-0.0045,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,1.8e-05,0.00042,8.5e-05,0.00036,0.00041,1,1
31590000,0.78,-0.003,-0.0042,-0.63,1.1,1,0.79,9.6,7,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.072,-0.0038,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,1.8e-05,0.00041,8.4e-05,0.00036,0.00041,1,1
31690000,0.78,-0.0037,-0.004,-0.63,1.1,1,0.8,9.8,7.1,-3.7e+02,-0.0011,-0.0057,-3.5e-05,0.072,-0.0032,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,1.8e-05,0.00041,8.4e-05,0.00036,0.00041,1,1
31790000,0.78,-0.0044,-0.0038,-0.63,1.1,0.99,0.8,9.9,7.2,-3.7e+02,-0.0011,-0.0057,-3.7e-05,0.071,-0.0023,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,1.8e-05,0.00041,8.4e-05,0.00036,0.00041,1,1
31890000,0.78,-0.0051,-0.0037,-0.63,1.1,0.97,0.79,10,7.3,-3.7e+02,-0.0011,-0.0057,-4.1e-05,0.071,-0.0014,-0.12,-0.17,-0.038,0.46,-0.0019,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,1.8e-05,0.00041,8.4e-05,0.00036,0.00041,1,1
31990000,0.78,-0.0057,-0.0035,-0.63,1,0.96,0.79,10,7.4,-3.7e+02,-0.0011,-0.0057,-4.7e-05,0.07,-0.00053,-0.12,-0.17,-0.038,0.46,-0.0018,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.14,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.00041,1,1
32090000,0.78,-0.0064,-0.0033,-0.63,1,0.94,0.8,10,7.5,-3.7e+02,-0.0012,-0.0057,-5.1e-05,0.07,0.00016,-0.11,-0.17,-0.038,0.46,-0.0018,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.2e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.0004,1,1
32190000,0.78,-0.0074,-0.0031,-0.63,0.97,0.92,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-6e-05,0.069,0.0011,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.0004,1,1
32290000,0.78,-0.0081,-0.003,-0.63,0.94,0.9,0.79,10,7.7,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.069,0.0021,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.0004,1,1
32390000,0.78,-0.0087,-0.0029,-0.63,0.91,0.88,0.79,11,7.8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.068,0.0027,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.0004,1,1
32490000,0.78,-0.009,-0.0028,-0.62,0.88,0.86,0.8,11,7.9,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0035,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,9e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.0004,1,1
32590000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.067,0.0038,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.0004,1,1
32690000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0044,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.0004,1,1
32790000,0.78,-0.0093,-0.0028,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0048,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00014,0.0001,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.0004,1,1
32890000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.5e-05,0.066,0.0053,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.00039,1,1
32990000,0.78,-0.0092,-0.003,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.9e-05,0.065,0.0058,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.00039,1,1
33090000,0.78,-0.0092,-0.003,-0.62,-1.6,-0.86,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.00039,1,1
33190000,0.78,-0.0079,-0.0062,-0.62,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0061,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.1e-05,0.00036,0.00039,1,1
33290000,0.83,-0.0058,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.8e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.1e-05,0.00035,0.00039,1,1
33390000,0.89,-0.0065,-0.015,-0.45,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.064,0.0057,-0.11,-0.18,-0.039,0.46,-0.00088,-0.027,-0.024,0,0,0.00015,0.0001,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00031,1.7e-05,0.0004,7.9e-05,0.00032,0.00039,1,1
33490000,0.95,-0.0051,-0.0068,-0.3,-1.5,-0.87,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.6e-05,0.064,0.0057,-0.11,-0.18,-0.04,0.46,-0.00039,-0.02,-0.024,0,0,0.00015,0.0001,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00023,1.3e-05,0.00039,7.1e-05,0.00024,0.00039,1,1
33590000,0.99,-0.0082,-3e-05,-0.14,-1.5,-0.85,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.5e-05,0.064,0.0057,-0.11,-0.19,-0.042,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00015,9e-06,0.00039,5.9e-05,0.00015,0.00039,1,1
33690000,1,-0.012,0.0042,0.031,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2e-05,0.064,0.0057,-0.11,-0.19,-0.043,0.46,0.00019,-0.0091,-0.025,0,0,0.00015,0.0001,0.0027,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0047,0.0051,8.8e-05,0.0001,6.7e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1
33790000,0.98,-0.013,0.0066,0.2,-1.6,-0.89,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.6e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00053,-0.0066,-0.025,0,0,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,6.9e-05,5.1e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1
33890000,0.93,-0.013,0.0087,0.36,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.9e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00074,-0.0053,-0.025,0,0,0.00015,9.9e-05,0.0019,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,5e-05,4.2e-06,0.00038,2.6e-05,4.2e-05,0.00038,1,1
33990000,0.87,-0.015,0.0073,0.5,-1.7,-0.97,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0055,-0.11,-0.2,-0.044,0.46,0.00052,-0.0039,-0.025,0,0,0.00014,9.7e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,4e-05,3.7e-06,0.00038,2.1e-05,3e-05,0.00038,1,1
34090000,0.8,-0.016,0.0065,0.6,-1.7,-1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.065,0.0049,-0.11,-0.2,-0.044,0.46,0.00019,-0.0032,-0.025,0,0,0.00014,9.7e-05,0.0015,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3.4e-05,3.4e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1
34190000,0.75,-0.014,0.0072,0.66,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0047,-0.11,-0.2,-0.044,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.7e-05,0.0014,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3e-05,3.2e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1
34290000,0.71,-0.011,0.0086,0.7,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0044,-0.11,-0.2,-0.044,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.6e-05,0.0013,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,2.7e-05,3.1e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1
34390000,0.69,-0.0076,0.01,0.72,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,9.2e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0013,0.047,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.8e-06,0.0047,0.005,8.8e-05,2.5e-05,3e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1
34490000,0.67,-0.0054,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,5e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0012,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.3e-05,2.9e-06,0.00038,9.8e-06,1.2e-05,0.00038,1,1
34590000,0.67,-0.004,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0039,-0.11,-0.2,-0.044,0.46,-4.6e-05,-0.0019,-0.025,0,0,0.00014,9.5e-05,0.0012,0.056,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.2e-05,2.9e-06,0.00038,8.9e-06,1.1e-05,0.00038,1,1
34690000,0.66,-0.0032,0.013,0.75,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0038,-0.11,-0.2,-0.044,0.46,1.6e-05,-0.0016,-0.025,0,0,0.00014,9.5e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.1e-05,2.8e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1
34790000,0.66,-0.0027,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0038,-0.11,-0.2,-0.044,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0012,0.067,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,2.8e-06,0.00038,7.7e-06,9.1e-06,0.00038,1,1
34890000,0.65,-0.0025,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0036,-0.11,-0.2,-0.044,0.46,8.7e-05,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0011,0.074,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,2.7e-06,0.00038,7.2e-06,8.4e-06,0.00038,1,1
34990000,0.65,-0.006,0.02,0.76,-3.1,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0002,-0.0016,-0.025,0,0,0.00014,9.3e-05,0.0011,0.09,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,2.7e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1
35090000,0.65,-0.006,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00021,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0011,0.098,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,2.7e-06,0.00038,6.5e-06,7.4e-06,0.00038,1,1
35190000,0.65,-0.0061,0.02,0.76,-3.2,-2.7,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00025,-0.0015,-0.025,0,0,0.00013,9.3e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,2.7e-06,0.00038,6.2e-06,7e-06,0.00038,1,1
35290000,0.65,-0.0063,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,2.7e-06,0.00038,5.9e-06,6.6e-06,0.00037,1,1
35390000,0.65,-0.0063,0.02,0.76,-3.3,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.12,0.18,0.012,0.57,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,2.6e-06,0.00038,5.7e-06,6.3e-06,0.00037,1,1
35490000,0.65,-0.0063,0.02,0.76,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00044,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.13,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5.5e-06,6e-06,0.00037,1,1
35590000,0.65,-0.0064,0.02,0.76,-3.3,-3,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00041,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.14,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1
35690000,0.65,-0.0063,0.02,0.76,-3.4,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00047,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5.2e-06,5.6e-06,0.00037,1,1
35790000,0.65,-0.0064,0.02,0.76,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.0011,0.17,0.23,0.01,0.73,0.84,0.049,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1
35890000,0.65,-0.0065,0.02,0.76,-3.4,-3.2,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.001,0.18,0.25,0.0096,0.78,0.9,0.048,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5e-06,5.2e-06,0.00037,1,1
35990000,0.65,-0.0065,0.02,0.76,-3.5,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00046,-0.0015,-0.025,0,0,0.00013,9e-05,0.001,0.19,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.6e-05,2.6e-06,0.00038,4.8e-06,5e-06,0.00037,1,1
36090000,0.65,-0.0065,0.02,0.76,-3.5,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.001,0.2,0.28,0.0089,0.9,1.1,0.046,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.6e-05,2.6e-06,0.00038,4.7e-06,4.8e-06,0.00037,1,1
36190000,0.65,-0.0066,0.02,0.76,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0037,-0.11,-0.2,-0.044,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.001,0.22,0.3,0.0086,0.96,1.1,0.045,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,8.9e-05,1.6e-05,2.6e-06,0.00038,4.6e-06,4.7e-06,0.00037,1,1
36290000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.001,0.23,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,8.9e-05,1.6e-05,2.5e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1
36390000,0.65,-0.0066,0.02,0.76,-3.6,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00057,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.001,0.24,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,8.9e-05,1.6e-05,2.5e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1
36490000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.058,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00054,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.001,0.26,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.6e-05,2.5e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1
36590000,0.65,-0.0066,0.02,0.76,-3.6,-3.8,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.001,0.27,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.3e-06,4.2e-06,0.00037,1,1
36690000,0.65,-0.0067,0.02,0.76,-3.7,-3.8,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.001,0.29,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1
36790000,0.65,-0.0067,0.021,0.76,-3.7,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0036,-0.11,-0.2,-0.044,0.46,0.00064,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.001,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.2e-06,4e-06,0.00037,1,1
36890000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00067,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.001,0.32,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1
36990000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0039,-0.11,-0.2,-0.044,0.46,0.00068,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.001,0.34,0.45,0.0071,1.7,2.2,0.04,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.1e-06,3.9e-06,0.00037,1,1
37090000,0.65,-0.0067,0.021,0.76,-3.8,-4.1,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.9e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.001,0.36,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1
37190000,0.65,-0.0067,0.021,0.76,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00068,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.37,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1
37290000,0.65,-0.0068,0.021,0.76,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.5e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.39,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4e-06,3.7e-06,0.00037,1,1
37390000,0.65,-0.0067,0.021,0.76,-3.9,-4.3,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00071,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.41,0.54,0.0067,2.3,3,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4e-06,3.6e-06,0.00037,1,1
37490000,0.65,-0.0067,0.021,0.76,-3.9,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.6e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.43,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4e-06,3.5e-06,0.00037,1,1
37590000,0.65,-0.0067,0.021,0.76,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.2e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.45,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.4e-05,2.5e-06,0.00038,3.9e-06,3.5e-06,0.00037,1,1
37690000,0.65,-0.0068,0.021,0.76,-3.9,-4.6,0.043,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.7e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.47,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.4e-05,2.5e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1
37790000,0.65,-0.0069,0.021,0.76,-4,-4.6,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.00099,0.49,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,2.5e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1
37890000,0.65,-0.0069,0.021,0.76,-4,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.00099,0.51,0.65,0.0065,3.3,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,2.4e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1
37990000,0.65,-0.0069,0.021,0.76,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.00099,0.53,0.67,0.0065,3.5,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.3e-06,0.00037,1,1
38090000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.078,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.00099,0.55,0.7,0.0065,3.8,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1
38190000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.00098,0.57,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1
38290000,0.65,-0.0069,0.021,0.76,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.00098,0.6,0.75,0.0065,4.3,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1
38390000,0.65,-0.0069,0.021,0.76,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00098,0.62,0.77,0.0065,4.6,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1
38490000,0.65,-0.0069,0.021,0.76,-4.2,-5.1,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00098,0.64,0.8,0.0065,4.9,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3e-06,0.00037,1,1
38590000,0.65,-0.0068,0.021,0.76,-4.2,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00097,0.67,0.82,0.0065,5.3,6.9,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3e-06,0.00037,1,1
38690000,0.65,-0.0068,0.021,0.76,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0045,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00097,0.69,0.85,0.0065,5.6,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.7e-06,3e-06,0.00037,1,1
38790000,0.65,-0.0068,0.021,0.76,-4.3,-5.3,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00097,0.71,0.88,0.0065,6,7.8,0.035,3.1e-07,4.3e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.7e-06,2.9e-06,0.00037,1,1
38890000,0.65,-0.0069,0.021,0.76,-4.3,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0044,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.3e-05,0.00097,0.73,0.89,0.0065,6.4,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.7e-06,2.9e-06,0.00037,1,1

1 Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
2 10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3 90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4 190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5 290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6 390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
7 490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8 590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9 690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10 790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.00077,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11 890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00051,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
12 990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00062,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13 1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00043,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14 1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00055,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00051,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15 1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16 1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00048,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17 1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18 1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19 1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20 1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00038,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21 1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22 1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00034,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23 2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24 2190000,1,-0.011,-0.014,5.8e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2190000,1,-0.011,-0.014,5.9e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25 2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26 2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27 2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28 2590000,1,-0.011,-0.013,5.8e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2590000,1,-0.011,-0.013,5.9e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29 2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30 2790000,1,-0.011,-0.013,4.8e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2790000,1,-0.011,-0.013,4.9e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31 2890000,1,-0.011,-0.013,-1.8e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2890000,1,-0.011,-0.013,-1.1e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32 2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33 3090000,1,-0.011,-0.013,4.8e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3090000,1,-0.011,-0.013,4.9e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34 3190000,1,-0.011,-0.013,-8.9e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00021,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3190000,1,-0.011,-0.013,-8e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
35 3290000,1,-0.011,-0.013,3.1e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3290000,1,-0.011,-0.013,3.2e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
36 3390000,1,-0.011,-0.012,2.5e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3390000,1,-0.011,-0.012,3.2e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
37 3490000,1,-0.011,-0.013,-5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3490000,1,-0.011,-0.013,-4.5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
38 3590000,1,-0.011,-0.012,1.8e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3590000,1,-0.011,-0.012,1.9e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
39 3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
40 3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
41 3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
42 3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
43 4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
44 4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00018,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
45 4290000,1,-0.01,-0.012,8.2e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4290000,1,-0.01,-0.012,8.1e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
46 4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
47 4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00016,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
48 4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00017,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
49 4690000,1,-0.01,-0.012,0.0002,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4690000,1,-0.01,-0.012,0.00019,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
50 4790000,1,-0.01,-0.012,0.00019,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4790000,1,-0.01,-0.012,0.00018,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
51 4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
52 4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00015,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
53 5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
54 5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
55 5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
56 5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
57 5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00013,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
58 5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
59 5690000,1,-0.0096,-0.011,0.00034,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00012,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5690000,1,-0.0096,-0.011,0.00033,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
60 5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
61 5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
62 5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
63 6090000,1,-0.0094,-0.011,0.00032,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6090000,1,-0.0094,-0.011,0.00031,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
64 6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
65 6290000,1,-0.0094,-0.011,0.00022,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6290000,1,-0.0094,-0.011,0.00021,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
66 6390000,1,-0.0093,-0.011,0.00024,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6390000,1,-0.0093,-0.011,0.00023,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
67 6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
68 6590000,1,-0.0094,-0.011,0.00017,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6590000,1,-0.0094,-0.011,0.00016,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
69 6690000,1,-0.0093,-0.011,9.6e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6690000,1,-0.0093,-0.011,9e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.6e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
70 6790000,0.78,-0.024,0.0049,-0.63,-0.0056,0.0015,-0.11,0.0015,0.00055,-3.7e+02,-0.0014,-0.0057,-8.2e-05,0,0,-5.8e-05,-0.092,-0.02,0.51,-0.00081,-0.075,-0.061,0,0,0.0013,0.0013,0.072,0.18,0.18,0.6,0.11,0.11,0.2,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1 6790000,0.78,-0.024,0.005,-0.63,-0.22,-0.047,-0.11,-0.13,-0.028,-3.7e+02,-0.00035,-0.011,-0.0002,0,0,0.0012,-0.092,-0.02,0.51,-0.00079,-0.075,-0.061,0,0,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1
71 6890000,0.78,-0.025,0.0057,-0.63,-0.03,-0.0077,-0.12,-9e-05,-0.0018,-3.7e+02,-0.0013,-0.0057,-8.3e-05,0,0,-0.00011,-0.1,-0.022,0.51,-0.0011,-0.083,-0.067,0,0,0.0013,0.0013,0.057,0.18,0.18,0.46,0.14,0.14,0.18,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00094,0.0014,0.0013,1,1 6890000,0.78,-0.025,0.0059,-0.63,-0.27,-0.062,-0.12,-0.16,-0.038,-3.7e+02,-0.00018,-0.011,-0.00022,0,0,0.0013,-0.1,-0.022,0.51,-0.0012,-0.083,-0.067,0,0,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00089,0.0014,0.0013,1,1
72 6990000,0.78,-0.025,0.0058,-0.63,-0.059,-0.018,-0.12,-0.0053,-0.0061,-3.7e+02,-0.0012,-0.0057,-8.7e-05,-2.7e-05,-6.9e-05,-0.00041,-0.1,-0.022,0.5,-0.0015,-0.084,-0.067,0,0,0.0013,0.0013,0.053,0.19,0.18,0.36,0.17,0.17,0.16,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.0009,0.0014,0.0013,1,1 6990000,0.78,-0.025,0.0061,-0.63,-0.3,-0.073,-0.12,-0.2,-0.048,-3.7e+02,-7.9e-05,-0.011,-0.00022,-0.00057,-6.5e-05,0.00098,-0.1,-0.022,0.5,-0.0016,-0.084,-0.067,0,0,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1
73 7090000,0.78,-0.025,0.0059,-0.63,-0.087,-0.028,-0.12,-0.014,-0.012,-3.7e+02,-0.0011,-0.0057,-9.1e-05,-8.3e-05,-0.00024,-0.00077,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.052,0.19,0.19,0.29,0.2,0.2,0.16,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00089,0.0013,0.0013,1,1 7090000,0.78,-0.025,0.0064,-0.63,-0.33,-0.084,-0.12,-0.23,-0.06,-3.7e+02,3.5e-05,-0.011,-0.00023,-0.0013,-0.00028,0.00063,-0.1,-0.023,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00083,0.0014,0.0013,1,1
74 7190000,0.78,-0.025,0.006,-0.63,-0.11,-0.037,-0.15,-0.024,-0.018,-3.7e+02,-0.001,-0.0057,-9.3e-05,-7.7e-05,-0.00036,-0.00056,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.051,0.21,0.21,0.24,0.23,0.23,0.15,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00088,0.0013,0.0013,1,1 7190000,0.78,-0.025,0.0066,-0.63,-0.36,-0.093,-0.15,-0.27,-0.071,-3.7e+02,0.0001,-0.011,-0.00023,-0.0017,-0.00044,0.00086,-0.1,-0.023,0.5,-0.002,-0.085,-0.068,0,0,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00082,0.0013,0.0013,1,1
75 7290000,0.78,-0.025,0.0059,-0.63,-0.14,-0.04,-0.14,-0.035,-0.019,-3.7e+02,-0.0011,-0.0057,-9e-05,-4.6e-05,-0.00024,-0.0012,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.22,0.22,0.2,0.28,0.28,0.14,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00087,0.0013,0.0013,1,1 7290000,0.78,-0.025,0.0068,-0.63,-0.38,-0.094,-0.14,-0.3,-0.078,-3.7e+02,4.4e-05,-0.011,-0.00022,-0.0016,-0.0004,0.00018,-0.1,-0.023,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1
76 7390000,0.78,-0.025,0.0059,-0.63,-0.16,-0.048,-0.16,-0.049,-0.025,-3.7e+02,-0.0011,-0.0057,-9e-05,8.1e-07,-0.00028,-0.0014,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.24,0.24,0.18,0.32,0.32,0.13,7.8e-05,7.9e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00087,0.0013,0.0013,1,1 7390000,0.78,-0.024,0.007,-0.63,-0.41,-0.1,-0.16,-0.34,-0.089,-3.7e+02,6.5e-05,-0.011,-0.00022,-0.0017,-0.00044,2.8e-05,-0.1,-0.023,0.5,-0.0018,-0.085,-0.068,0,0,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00081,0.0013,0.0013,1,1
77 7490000,0.78,-0.025,0.0059,-0.63,-0.19,-0.061,-0.16,-0.066,-0.038,-3.7e+02,-0.00093,-0.0057,-9.3e-05,1.6e-05,-0.0005,-0.0022,-0.1,-0.023,0.5,-0.0017,-0.085,-0.069,0,0,0.0013,0.0013,0.049,0.27,0.26,0.15,0.37,0.37,0.12,7.8e-05,7.8e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1 7490000,0.78,-0.024,0.007,-0.63,-0.43,-0.11,-0.16,-0.38,-0.11,-3.7e+02,0.0002,-0.011,-0.00023,-0.0019,-0.00051,-0.00073,-0.1,-0.023,0.5,-0.0019,-0.085,-0.069,0,0,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1
78 7590000,0.78,-0.025,0.0059,-0.63,-0.21,-0.067,-0.16,-0.082,-0.044,-3.7e+02,-0.00093,-0.0056,-9e-05,0.00011,-0.00047,-0.003,-0.1,-0.023,0.5,-0.0016,-0.085,-0.068,0,0,0.0013,0.0013,0.049,0.29,0.29,0.14,0.43,0.43,0.12,7.7e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1 7590000,0.78,-0.024,0.0071,-0.63,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.00019,-0.011,-0.00022,-0.0018,-0.00049,-0.0016,-0.1,-0.023,0.5,-0.0019,-0.085,-0.068,0,0,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1
79 7690000,0.78,-0.025,0.0059,-0.63,-0.24,-0.079,-0.16,-0.1,-0.058,-3.7e+02,-0.00082,-0.0056,-9.3e-05,8.3e-05,-0.00057,-0.005,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.32,0.32,0.13,0.49,0.49,0.11,7.6e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.00086,0.0013,0.0013,1,1 7690000,0.78,-0.024,0.0072,-0.63,0,0,-0.16,-0.46,-0.14,-3.7e+02,0.00028,-0.011,-0.00022,-0.002,-0.00046,-0.0036,-0.1,-0.023,0.5,-0.002,-0.085,-0.069,0,0,0.0013,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.0008,0.0013,0.0013,1,1
80 7790000,0.78,-0.025,0.006,-0.63,-0.27,-0.088,-0.16,-0.14,-0.072,-3.7e+02,-0.00074,-0.0057,-9.9e-05,-0.00013,-0.00063,-0.007,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.35,0.35,0.12,0.56,0.55,0.11,7.5e-05,7.5e-05,4.9e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00086,0.0013,0.0013,1,1 7790000,0.78,-0.024,0.0074,-0.63,-0.028,-0.004,-0.16,-0.46,-0.14,-3.7e+02,0.00034,-0.011,-0.00023,-0.002,-0.00046,-0.0056,-0.1,-0.023,0.5,-0.002,-0.085,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00079,0.0013,0.0013,1,1
81 7890000,0.78,-0.025,0.006,-0.63,-0.29,-0.099,-0.15,-0.16,-0.086,-3.7e+02,-0.00067,-0.0056,-9.8e-05,-8.1e-05,-0.00064,-0.0095,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.39,0.38,0.11,0.63,0.63,0.1,7.4e-05,7.4e-05,4.9e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00086,0.0013,0.0013,1,1 7890000,0.78,-0.024,0.0074,-0.63,-0.053,-0.0088,-0.15,-0.46,-0.14,-3.7e+02,0.00038,-0.011,-0.00022,-0.002,-0.00046,-0.0081,-0.1,-0.023,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.11,1e+02,1e+02,0.1,6.9e-05,7.1e-05,2.4e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00079,0.0013,0.0013,1,1
82 7990000,0.78,-0.025,0.006,-0.63,-0.32,-0.11,-0.16,-0.19,-0.098,-3.7e+02,-0.00064,-0.0056,-9.7e-05,2.6e-06,-0.00064,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.43,0.42,0.1,0.71,0.71,0.099,7.2e-05,7.3e-05,4.9e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00086,0.0013,0.0013,1,1 7990000,0.78,-0.024,0.0074,-0.63,-0.079,-0.013,-0.16,-0.47,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.002,-0.00046,-0.0093,-0.1,-0.023,0.5,-0.0021,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00079,0.0013,0.0013,1,1
83 8090000,0.78,-0.025,0.006,-0.63,-0.34,-0.12,-0.17,-0.21,-0.11,-3.7e+02,-0.00058,-0.0054,-9.5e-05,0.00017,-0.00074,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.47,0.46,0.1,0.8,0.8,0.097,7e-05,7.1e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00086,0.0013,0.0013,1,1 8090000,0.78,-0.024,0.0072,-0.63,-0.1,-0.018,-0.17,-0.47,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.002,-0.00046,-0.0095,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.055,25,25,0.1,52,52,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00079,0.0013,0.0013,1,1
84 8190000,0.78,-0.025,0.0061,-0.63,-0.37,-0.13,-0.17,-0.25,-0.13,-3.7e+02,-0.00056,-0.0055,-9.8e-05,-2.7e-05,-0.00068,-0.013,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.52,0.51,0.099,0.9,0.89,0.094,6.8e-05,6.9e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 8190000,0.78,-0.024,0.0074,-0.63,-0.13,-0.021,-0.18,-0.48,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.002,-0.00046,-0.012,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,25,0.099,35,35,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,8.4e-05,0.0013,0.00078,0.0013,0.0013,1,1
85 8290000,0.78,-0.025,0.0061,-0.63,-0.019,-0.0046,-0.17,-0.27,-0.13,-3.7e+02,-0.00042,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.017,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.6e-05,6.7e-05,4.9e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 8290000,0.78,-0.024,0.0074,-0.63,-0.15,-0.026,-0.17,-0.49,-0.14,-3.7e+02,0.00052,-0.01,-0.00021,-0.002,-0.00046,-0.016,-0.1,-0.023,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,25,25,0.097,37,37,0.091,6.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00078,0.0013,0.0013,1,1
86 8390000,0.78,-0.025,0.0061,-0.63,-0.046,-0.012,-0.17,-0.27,-0.13,-3.7e+02,-0.00038,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.021,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,6.5e-05,4.9e-06,0.04,0.04,0.035,0.0013,8.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 8390000,0.78,-0.024,0.0072,-0.63,-0.17,-0.031,-0.17,-0.5,-0.14,-3.7e+02,0.00054,-0.01,-0.00021,-0.002,-0.00046,-0.019,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.1e-05,0.0013,0.00078,0.0013,0.0013,1,1
87 8490000,0.78,-0.026,0.0062,-0.63,-0.073,-0.02,-0.17,-0.27,-0.13,-3.7e+02,-0.00033,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.025,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,51,51,0.089,6.2e-05,6.3e-05,4.9e-06,0.04,0.04,0.034,0.0013,8.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 8490000,0.78,-0.023,0.0072,-0.63,-0.2,-0.036,-0.17,-0.51,-0.15,-3.7e+02,0.00055,-0.0099,-0.0002,-0.002,-0.00046,-0.024,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,24,24,0.096,31,31,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00077,0.0013,0.0013,1,1
88 8590000,0.78,-0.025,0.0062,-0.63,-0.099,-0.028,-0.16,-0.28,-0.14,-3.7e+02,-0.00051,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.029,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.095,52,52,0.088,5.9e-05,6.1e-05,4.9e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00085,0.0013,0.0013,1,1 8590000,0.78,-0.023,0.0074,-0.63,-0.21,-0.033,-0.17,-0.52,-0.15,-3.7e+02,0.00036,-0.0099,-0.0002,-0.002,-0.00046,-0.028,-0.1,-0.023,0.5,-0.0022,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.095,25,25,0.088,5.7e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.9e-05,0.0013,0.00077,0.0013,0.0013,1,1
89 8690000,0.78,-0.025,0.0061,-0.63,-0.12,-0.036,-0.16,-0.28,-0.14,-3.7e+02,-0.00047,-0.0055,-9.9e-05,-6.1e-05,-0.00064,-0.034,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.096,35,35,0.088,5.7e-05,5.9e-05,4.9e-06,0.04,0.04,0.033,0.0013,7.9e-05,0.0013,0.00085,0.0013,0.0013,1,1 8690000,0.78,-0.023,0.007,-0.63,-0.23,-0.038,-0.16,-0.54,-0.15,-3.7e+02,0.00037,-0.0096,-0.00019,-0.002,-0.00046,-0.033,-0.1,-0.023,0.5,-0.0023,-0.086,-0.069,0,0,0.0014,0.0014,0.054,23,23,0.096,28,28,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.8e-05,0.0013,0.00077,0.0013,0.0013,1,1
90 8790000,0.78,-0.026,0.0062,-0.63,-0.15,-0.044,-0.15,-0.3,-0.14,-3.7e+02,-0.0004,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.04,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,37,37,0.087,5.5e-05,5.6e-05,4.9e-06,0.04,0.04,0.032,0.0013,7.8e-05,0.0013,0.00085,0.0013,0.0013,1,1 8790000,0.78,-0.023,0.0071,-0.63,-0.24,-0.041,-0.15,-0.54,-0.15,-3.7e+02,0.00039,-0.0095,-0.00019,-0.002,-0.00046,-0.039,-0.1,-0.023,0.5,-0.0024,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.096,24,24,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,7.7e-05,0.0013,0.00076,0.0013,0.0013,1,1
91 8890000,0.78,-0.026,0.0063,-0.63,-0.18,-0.05,-0.15,-0.3,-0.14,-3.7e+02,-0.00037,-0.0056,-0.00011,-6.1e-05,-0.00064,-0.044,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.095,28,28,0.086,5.2e-05,5.4e-05,4.9e-06,0.04,0.04,0.03,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1 8890000,0.78,-0.023,0.007,-0.63,-0.26,-0.045,-0.15,-0.56,-0.16,-3.7e+02,0.00039,-0.0094,-0.00018,-0.002,-0.00046,-0.043,-0.1,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0014,0.0014,0.054,21,21,0.095,26,26,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0013,7.6e-05,0.0013,0.00076,0.0013,0.0013,1,1
92 8990000,0.78,-0.026,0.0064,-0.63,-0.21,-0.056,-0.14,-0.32,-0.15,-3.7e+02,-0.00029,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.05,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.096,30,30,0.087,5e-05,5.1e-05,4.9e-06,0.04,0.04,0.029,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1 8990000,0.78,-0.023,0.007,-0.63,-0.28,-0.05,-0.14,-0.59,-0.16,-3.7e+02,0.00044,-0.0093,-0.00018,-0.0021,-0.00036,-0.049,-0.11,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,21,21,0.096,29,29,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0013,7.6e-05,0.0013,0.00075,0.0013,0.0013,1,1
93 9090000,0.78,-0.026,0.0065,-0.63,-0.23,-0.06,-0.14,-0.33,-0.15,-3.7e+02,-0.00033,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.052,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.095,25,25,0.086,4.7e-05,4.9e-05,4.9e-06,0.04,0.04,0.028,0.0013,7.6e-05,0.0013,0.00085,0.0013,0.0013,1,1 9090000,0.78,-0.022,0.007,-0.63,-0.3,-0.05,-0.14,-0.61,-0.17,-3.7e+02,0.00036,-0.0092,-0.00018,-0.0021,-0.00019,-0.052,-0.11,-0.023,0.5,-0.0025,-0.086,-0.069,0,0,0.0013,0.0014,0.054,21,21,0.095,33,33,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0013,7.5e-05,0.0013,0.00075,0.0013,0.0013,1,1
94 9190000,0.78,-0.026,0.0063,-0.63,-0.25,-0.071,-0.14,-0.35,-0.16,-3.7e+02,-0.00029,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.056,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.094,27,27,0.085,4.5e-05,4.6e-05,4.9e-06,0.04,0.04,0.027,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 9190000,0.77,-0.022,0.0063,-0.63,-0.3,-0.06,-0.14,-0.63,-0.18,-3.7e+02,0.00037,-0.0088,-0.00017,-0.0019,4e-05,-0.055,-0.11,-0.023,0.5,-0.0027,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.094,37,37,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,7.4e-05,0.0013,0.00074,0.0013,0.0013,1,1
95 9290000,0.78,-0.026,0.0063,-0.63,-0.27,-0.077,-0.13,-0.35,-0.16,-3.7e+02,-0.00023,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.06,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,23,23,0.085,4.2e-05,4.4e-05,4.9e-06,0.04,0.04,0.025,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 9290000,0.77,-0.022,0.006,-0.63,-0.32,-0.068,-0.14,-0.66,-0.19,-3.7e+02,0.0004,-0.0086,-0.00016,-0.002,0.00028,-0.059,-0.11,-0.023,0.5,-0.0028,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.093,41,41,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,7.3e-05,0.0013,0.00074,0.0013,0.0013,1,1
96 9390000,0.78,-0.026,0.0065,-0.63,-0.3,-0.086,-0.13,-0.38,-0.17,-3.7e+02,-0.00018,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.063,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,21,21,0.093,25,25,0.086,4e-05,4.2e-05,4.9e-06,0.04,0.04,0.024,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1 9390000,0.77,-0.022,0.0059,-0.63,-0.34,-0.077,-0.13,-0.69,-0.2,-3.7e+02,0.00042,-0.0085,-0.00016,-0.0021,0.00046,-0.063,-0.11,-0.023,0.5,-0.0029,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.093,46,46,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,7.3e-05,0.0013,0.00074,0.0013,0.0013,1,1
97 9490000,0.78,-0.026,0.0064,-0.63,-0.31,-0.092,-0.13,-0.38,-0.17,-3.7e+02,-0.00011,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.067,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.091,22,22,0.085,3.8e-05,4e-05,4.9e-06,0.04,0.04,0.023,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1 9490000,0.77,-0.022,0.0054,-0.63,-0.34,-0.09,-0.13,-0.71,-0.21,-3.7e+02,0.00045,-0.0082,-0.00015,-0.002,0.00072,-0.067,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0013,0.0013,0.054,21,21,0.091,51,51,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,7.2e-05,0.0013,0.00073,0.0013,0.0013,1,1
98 9590000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.18,-3.7e+02,-0.00024,-0.0053,-0.0001,-6.1e-05,-0.00064,-0.07,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.09,25,25,0.085,3.6e-05,3.7e-05,4.9e-06,0.04,0.04,0.022,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 9590000,0.77,-0.022,0.0051,-0.63,-0.35,-0.089,-0.13,-0.73,-0.22,-3.7e+02,0.0003,-0.008,-0.00014,-0.002,0.001,-0.07,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0013,0.054,21,21,0.09,57,57,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.2e-05,0.0013,0.00073,0.0013,0.0013,1,1
99 9690000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.17,-3.7e+02,-0.0003,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.075,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.089,22,22,0.086,3.4e-05,3.6e-05,4.9e-06,0.04,0.04,0.02,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 9690000,0.77,-0.022,0.0053,-0.63,-0.37,-0.086,-0.12,-0.77,-0.22,-3.7e+02,0.00022,-0.0081,-0.00014,-0.0022,0.0012,-0.075,-0.11,-0.023,0.5,-0.0029,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,21,0.089,63,63,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.1e-05,0.0013,0.00072,0.0013,0.0013,1,1
100 9790000,0.78,-0.026,0.0063,-0.63,-0.38,-0.11,-0.1,-0.45,-0.19,-3.7e+02,-0.00026,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.08,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.087,24,24,0.085,3.2e-05,3.4e-05,4.9e-06,0.04,0.04,0.019,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 9790000,0.77,-0.022,0.0049,-0.63,-0.37,-0.099,-0.11,-0.79,-0.24,-3.7e+02,0.00023,-0.0078,-0.00014,-0.0023,0.0016,-0.081,-0.11,-0.023,0.5,-0.0031,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,21,0.087,69,69,0.085,3.1e-05,3.4e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.1e-05,0.0013,0.00072,0.0013,0.0013,1,1
101 9890000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.1,-0.48,-0.2,-3.7e+02,-0.00033,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.083,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.084,28,28,0.085,3e-05,3.2e-05,4.9e-06,0.04,0.04,0.018,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 9890000,0.77,-0.021,0.0047,-0.63,-0.38,-0.1,-0.11,-0.82,-0.24,-3.7e+02,0.00014,-0.0077,-0.00013,-0.0023,0.0018,-0.083,-0.11,-0.023,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,21,22,0.084,76,76,0.085,3e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7e-05,0.0013,0.00072,0.0013,0.0013,1,1
102 9990000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.096,-0.47,-0.19,-3.7e+02,-0.00035,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.086,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.083,24,24,0.086,2.8e-05,3e-05,4.9e-06,0.04,0.04,0.017,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 9990000,0.77,-0.021,0.0047,-0.63,-0.4,-0.1,-0.1,-0.85,-0.25,-3.7e+02,9.4e-05,-0.0077,-0.00013,-0.0025,0.002,-0.087,-0.11,-0.023,0.5,-0.003,-0.087,-0.069,0,0,0.0012,0.0012,0.054,22,22,0.083,83,83,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7e-05,0.0013,0.00071,0.0013,0.0013,1,1
103 10090000,0.78,-0.026,0.0062,-0.63,-0.43,-0.12,-0.092,-0.51,-0.2,-3.7e+02,-0.00043,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.089,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.081,27,27,0.085,2.7e-05,2.8e-05,4.9e-06,0.04,0.04,0.016,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 10090000,0.77,-0.021,0.0044,-0.63,-0.4,-0.099,-0.096,-0.87,-0.26,-3.7e+02,-1.2e-05,-0.0075,-0.00012,-0.0025,0.0022,-0.09,-0.11,-0.023,0.5,-0.003,-0.088,-0.069,0,0,0.0011,0.0012,0.054,22,22,0.08,91,91,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7e-05,0.0013,0.00071,0.0013,0.0013,1,1
104 10190000,0.78,-0.026,0.0065,-0.63,-0.43,-0.12,-0.092,-0.5,-0.2,-3.7e+02,-0.00044,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.09,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,13,0.078,24,24,0.084,2.5e-05,2.7e-05,4.9e-06,0.04,0.04,0.015,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 10190000,0.77,-0.021,0.0047,-0.63,-0.42,-0.097,-0.096,-0.92,-0.26,-3.7e+02,-4.4e-05,-0.0076,-0.00012,-0.0025,0.0022,-0.091,-0.11,-0.023,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,22,22,0.078,99,99,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,6.9e-05,0.0013,0.00071,0.0013,0.0013,1,1
105 10290000,0.78,-0.026,0.0067,-0.63,-0.46,-0.12,-0.08,-0.55,-0.21,-3.7e+02,-0.00045,-0.0058,-0.00011,-6.1e-05,-0.00064,-0.096,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,14,0.076,27,27,0.085,2.4e-05,2.5e-05,4.9e-06,0.04,0.04,0.014,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 10290000,0.77,-0.021,0.0049,-0.63,-0.44,-0.096,-0.083,-0.96,-0.27,-3.7e+02,-7.1e-05,-0.0076,-0.00012,-0.0028,0.0025,-0.097,-0.11,-0.023,0.5,-0.0028,-0.088,-0.069,0,0,0.0011,0.0011,0.054,22,22,0.076,1.1e+02,1.1e+02,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1
106 10390000,0.78,-0.026,0.0068,-0.63,-0.017,-0.027,0.0097,-0.00031,-0.0021,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00013,-0.00061,-0.099,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,4.9e-06,0.04,0.04,0.013,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 10390000,0.77,-0.021,0.0047,-0.63,-0.0086,-0.022,0.0097,7.7e-05,-0.0019,-3.7e+02,-6e-05,-0.0075,-0.00012,-0.0028,0.0027,-0.1,-0.11,-0.023,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,6.9e-05,0.0013,0.0007,0.0013,0.0013,1,1
107 10490000,0.78,-0.026,0.0069,-0.63,-0.047,-0.034,0.023,-0.0035,-0.0051,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00035,-0.00043,-0.1,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.26,0.26,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,4.9e-06,0.04,0.04,0.012,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 10490000,0.77,-0.021,0.0048,-0.63,-0.028,-0.024,0.023,-0.0017,-0.0042,-3.7e+02,-8.3e-05,-0.0075,-0.00012,-0.0029,0.0028,-0.1,-0.11,-0.024,0.5,-0.0029,-0.088,-0.069,0,0,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,6.8e-05,0.0013,0.0007,0.0013,0.0013,1,1
108 10590000,0.78,-0.026,0.0066,-0.63,-0.045,-0.023,0.026,0.0012,-0.0011,-3.7e+02,-0.00059,-0.0058,-0.00011,-3.5e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.1e-05,4.9e-06,0.04,0.04,0.012,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1 10590000,0.77,-0.02,0.0045,-0.63,-0.026,-0.013,0.026,0.0015,-0.0009,-3.7e+02,-0.00027,-0.0074,-0.00011,-0.0021,0.0027,-0.1,-0.11,-0.024,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,6.8e-05,0.0013,0.0007,0.0013,0.0013,1,1
109 10690000,0.78,-0.026,0.0066,-0.63,-0.073,-0.029,0.03,-0.0048,-0.0037,-3.7e+02,-0.00059,-0.0059,-0.00011,-9.8e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.14,0.14,0.26,0.14,0.14,0.078,1.9e-05,2e-05,4.9e-06,0.04,0.04,0.011,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1 10690000,0.77,-0.02,0.0044,-0.63,-0.043,-0.014,0.03,-0.002,-0.0023,-3.7e+02,-0.00028,-0.0073,-0.00011,-0.0021,0.0028,-0.11,-0.11,-0.024,0.5,-0.0027,-0.088,-0.069,0,0,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,6.8e-05,0.0013,0.00069,0.0013,0.0013,1,1
110 10790000,0.78,-0.025,0.0064,-0.63,-0.069,-0.024,0.024,-0.0001,-0.0015,-3.7e+02,-0.00063,-0.0058,-0.00011,0.00028,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.096,0.096,0.17,0.09,0.09,0.072,1.8e-05,1.9e-05,4.8e-06,0.04,0.039,0.011,0.0013,7e-05,0.0013,0.00084,0.0013,0.0013,1,1 10790000,0.77,-0.02,0.004,-0.63,-0.04,-0.0098,0.024,0.001,-0.001,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00033,0.0016,-0.11,-0.11,-0.024,0.5,-0.0028,-0.088,-0.069,0,0,0.001,0.001,0.053,0.091,0.092,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,6.8e-05,0.0013,0.00069,0.0013,0.0013,1,1
111 10890000,0.78,-0.025,0.0064,-0.63,-0.097,-0.03,0.02,-0.0084,-0.0042,-3.7e+02,-0.00063,-0.0058,-0.00011,0.0003,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0015,0.048,0.11,0.11,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00084,0.0013,0.0013,1,1 10890000,0.77,-0.02,0.0039,-0.63,-0.057,-0.012,0.02,-0.0037,-0.0022,-3.7e+02,-0.00035,-0.0071,-0.0001,-0.00027,0.0017,-0.11,-0.11,-0.024,0.5,-0.0028,-0.088,-0.069,0,0,0.00098,0.00098,0.053,0.099,0.1,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,6.7e-05,0.0013,0.00069,0.0013,0.0013,1,1
112 10990000,0.78,-0.025,0.0059,-0.63,-0.085,-0.024,0.014,-0.0037,-0.0024,-3.7e+02,-0.00066,-0.0058,-0.0001,0.0011,-0.009,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.086,0.086,0.12,0.099,0.099,0.071,1.6e-05,1.7e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 10990000,0.77,-0.02,0.0031,-0.63,-0.048,-0.0092,0.015,0.00014,-0.0011,-3.7e+02,-0.00038,-0.0069,-9.7e-05,0.0035,-0.0006,-0.11,-0.11,-0.024,0.5,-0.003,-0.089,-0.069,0,0,0.00093,0.00093,0.053,0.078,0.079,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,6.7e-05,0.0013,0.00069,0.0013,0.0013,1,1
113 11090000,0.78,-0.025,0.0057,-0.63,-0.11,-0.032,0.019,-0.013,-0.0054,-3.7e+02,-0.00069,-0.0057,-9.6e-05,0.0013,-0.0089,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.1,0.1,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 11090000,0.77,-0.02,0.0028,-0.63,-0.06,-0.013,0.02,-0.0047,-0.0024,-3.7e+02,-0.00042,-0.0068,-9.2e-05,0.0035,-0.00017,-0.11,-0.11,-0.024,0.5,-0.003,-0.089,-0.069,0,0,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,6.7e-05,0.0013,0.00068,0.0013,0.0013,1,1
114 11190000,0.78,-0.024,0.0051,-0.63,-0.095,-0.025,0.0078,-0.0051,-0.0021,-3.7e+02,-0.00079,-0.0057,-9.3e-05,0.0019,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.084,0.084,0.084,0.11,0.11,0.069,1.4e-05,1.5e-05,4.8e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 11190000,0.77,-0.019,0.0023,-0.63,-0.054,-0.0091,0.0082,0.0007,-0.00036,-3.7e+02,-0.00052,-0.0067,-8.9e-05,0.008,-0.0035,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.07,0,0,0.00085,0.00085,0.053,0.073,0.074,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,6.6e-05,0.0013,0.00068,0.0013,0.0013,1,1
115 11290000,0.78,-0.024,0.0052,-0.63,-0.12,-0.029,0.0076,-0.016,-0.0046,-3.7e+02,-0.00074,-0.0058,-9.7e-05,0.0016,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.099,0.099,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,4.8e-06,0.038,0.038,0.01,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 11290000,0.77,-0.019,0.0024,-0.63,-0.069,-0.011,0.008,-0.0057,-0.0014,-3.7e+02,-0.00049,-0.0067,-9.1e-05,0.0081,-0.0036,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.069,0,0,0.00084,0.00084,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,6.6e-05,0.0013,0.00068,0.0013,0.0013,1,1
116 11390000,0.78,-0.022,0.0045,-0.63,-0.1,-0.024,0.002,-0.0027,-0.00099,-3.7e+02,-0.00084,-0.0059,-9.5e-05,0.0015,-0.022,-0.11,-0.11,-0.023,0.5,-0.0013,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.08,0.08,0.063,0.082,0.082,0.068,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1 11390000,0.78,-0.019,0.002,-0.63,-0.064,-0.0096,0.0024,0.00035,-0.00029,-3.7e+02,-0.00058,-0.0067,-8.9e-05,0.012,-0.0074,-0.11,-0.11,-0.024,0.5,-0.0031,-0.089,-0.07,0,0,0.00076,0.00077,0.052,0.068,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00068,0.0013,0.0012,1,1
117 11490000,0.78,-0.022,0.0047,-0.63,-0.12,-0.026,0.0029,-0.014,-0.0031,-3.7e+02,-0.0008,-0.006,-0.0001,0.0009,-0.022,-0.11,-0.11,-0.023,0.5,-0.0014,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.095,0.095,0.058,0.089,0.089,0.069,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1 11490000,0.78,-0.019,0.0022,-0.63,-0.078,-0.011,0.0032,-0.0072,-0.0011,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.024,0.5,-0.0032,-0.089,-0.07,0,0,0.00075,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00067,0.0013,0.0012,1,1
118 11590000,0.78,-0.022,0.0041,-0.63,-0.1,-0.022,-0.003,-0.0044,-0.00098,-3.7e+02,-0.00085,-0.006,-9.8e-05,0.00079,-0.029,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.078,0.078,0.049,0.068,0.068,0.066,1.1e-05,1.2e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1 11590000,0.78,-0.019,0.0017,-0.63,-0.069,-0.011,-0.0027,-0.0022,-0.00067,-3.7e+02,-0.0006,-0.0067,-9.1e-05,0.017,-0.012,-0.11,-0.11,-0.024,0.5,-0.0033,-0.089,-0.07,0,0,0.00067,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,6.6e-05,0.0013,0.00067,0.0013,0.0012,1,1
119 11690000,0.78,-0.022,0.0042,-0.63,-0.12,-0.026,-0.0074,-0.016,-0.0033,-3.7e+02,-0.00079,-0.006,-0.0001,0.00062,-0.03,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.093,0.093,0.046,0.075,0.075,0.066,1.1e-05,1.1e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1 11690000,0.78,-0.019,0.0018,-0.63,-0.08,-0.014,-0.0071,-0.0098,-0.0021,-3.7e+02,-0.00056,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.024,0.5,-0.0034,-0.089,-0.07,0,0,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0013,0.00067,0.0013,0.0012,1,1
120 11790000,0.78,-0.021,0.0037,-0.63,-0.1,-0.017,-0.0092,-0.0082,0.00018,-3.7e+02,-0.00082,-0.006,-9.7e-05,0.0012,-0.036,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.077,0.076,0.039,0.06,0.06,0.063,1e-05,1.1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 11790000,0.78,-0.019,0.0012,-0.63,-0.072,-0.0097,-0.0089,-0.0061,-4.1e-05,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.015,-0.11,-0.11,-0.024,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.00061,0.051,0.065,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,6.5e-05,0.0013,0.00067,0.0013,0.0012,1,1
121 11890000,0.78,-0.021,0.0038,-0.63,-0.12,-0.019,-0.01,-0.019,-0.0015,-3.7e+02,-0.0008,-0.0061,-9.9e-05,0.00091,-0.036,-0.11,-0.11,-0.023,0.5,-0.0015,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.09,0.09,0.037,0.067,0.067,0.063,9.5e-06,1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 11890000,0.78,-0.019,0.0013,-0.63,-0.084,-0.01,-0.0098,-0.014,-0.001,-3.7e+02,-0.0006,-0.0066,-9.2e-05,0.023,-0.016,-0.11,-0.11,-0.024,0.5,-0.0035,-0.09,-0.07,0,0,0.00059,0.0006,0.051,0.075,0.076,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,6.5e-05,0.0013,0.00066,0.0013,0.0012,1,1
122 11990000,0.78,-0.02,0.003,-0.63,-0.095,-0.012,-0.015,-0.011,0.0012,-3.7e+02,-0.00095,-0.0061,-9.3e-05,0.0013,-0.04,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.074,0.074,0.033,0.055,0.055,0.061,9e-06,9.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 11990000,0.78,-0.019,0.00071,-0.63,-0.072,-0.0052,-0.015,-0.009,0.0011,-3.7e+02,-0.00075,-0.0065,-8.7e-05,0.027,-0.019,-0.11,-0.11,-0.024,0.5,-0.0034,-0.09,-0.07,0,0,0.00052,0.00053,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8.1e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,6.5e-05,0.0013,0.00066,0.0013,0.0012,1,1
123 12090000,0.78,-0.02,0.0029,-0.63,-0.11,-0.016,-0.021,-0.021,-0.00045,-3.7e+02,-0.00099,-0.006,-9e-05,0.0018,-0.04,-0.11,-0.11,-0.023,0.5,-0.0013,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.087,0.086,0.031,0.063,0.063,0.061,8.6e-06,9.2e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 12090000,0.78,-0.018,0.00055,-0.63,-0.078,-0.0073,-0.021,-0.016,0.00038,-3.7e+02,-0.0008,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.024,0.5,-0.0034,-0.09,-0.07,0,0,0.00051,0.00053,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.5e-06,2.3e-06,0.028,0.028,0.01,0.0012,6.5e-05,0.0013,0.00066,0.0013,0.0012,1,1
124 12190000,0.78,-0.019,0.0023,-0.63,-0.084,-0.015,-0.016,-0.01,0.00028,-3.7e+02,-0.00098,-0.006,-8.9e-05,0.0016,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.071,0.071,0.028,0.052,0.052,0.059,8.1e-06,8.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 12190000,0.78,-0.018,-0.00013,-0.63,-0.064,-0.0098,-0.016,-0.0085,-0.00012,-3.7e+02,-0.00081,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00045,0.00047,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,6.4e-05,0.0012,0.00066,0.0013,0.0012,1,1
125 12290000,0.78,-0.019,0.0024,-0.63,-0.092,-0.017,-0.015,-0.019,-0.0014,-3.7e+02,-0.00094,-0.006,-8.9e-05,0.0017,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.082,0.082,0.028,0.06,0.06,0.059,7.8e-06,8.4e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 12290000,0.78,-0.018,-0.00015,-0.63,-0.07,-0.012,-0.015,-0.015,-0.0016,-3.7e+02,-0.00078,-0.0064,-8.3e-05,0.033,-0.022,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.00045,0.00047,0.051,0.071,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.6e-06,2.3e-06,0.026,0.026,0.01,0.0012,6.4e-05,0.0012,0.00066,0.0013,0.0012,1,1
126 12390000,0.78,-0.019,0.0019,-0.63,-0.073,-0.014,-0.013,-0.0094,-0.00012,-3.7e+02,-0.00099,-0.006,-8.8e-05,0.0011,-0.05,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.067,0.067,0.026,0.05,0.05,0.057,7.4e-06,8e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1 12390000,0.78,-0.018,-0.00055,-0.63,-0.057,-0.01,-0.013,-0.0083,-0.00071,-3.7e+02,-0.00085,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.5e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,6.4e-05,0.0012,0.00065,0.0013,0.0012,1,1
127 12490000,0.78,-0.019,0.0021,-0.63,-0.08,-0.016,-0.016,-0.017,-0.0014,-3.7e+02,-0.00096,-0.0061,-9.1e-05,0.00059,-0.05,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.077,0.076,0.026,0.058,0.058,0.057,7.1e-06,7.6e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1 12490000,0.78,-0.018,-0.00042,-0.63,-0.065,-0.012,-0.016,-0.015,-0.0018,-3.7e+02,-0.00083,-0.0064,-8.5e-05,0.037,-0.027,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.0004,0.00041,0.05,0.068,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,6.4e-05,0.0012,0.00065,0.0013,0.0012,1,1
128 12590000,0.78,-0.018,0.0018,-0.63,-0.073,-0.014,-0.022,-0.014,-0.00033,-3.7e+02,-0.001,-0.0061,-8.8e-05,0.00072,-0.052,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.063,0.063,0.025,0.049,0.049,0.055,6.8e-06,7.3e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.5e-05,0.0012,0.00072,0.0013,0.0012,1,1 12590000,0.78,-0.018,-0.00062,-0.63,-0.06,-0.01,-0.022,-0.013,-0.00071,-3.7e+02,-0.00091,-0.0063,-8.3e-05,0.038,-0.028,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00036,0.00037,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.9e-06,6.4e-06,2.3e-06,0.022,0.022,0.0099,0.0012,6.4e-05,0.0012,0.00065,0.0013,0.0012,1,1
129 12690000,0.78,-0.018,0.0018,-0.63,-0.079,-0.015,-0.025,-0.021,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.8e-05,0.00038,-0.051,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.071,0.071,0.025,0.057,0.057,0.055,6.5e-06,7e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1 12690000,0.78,-0.018,-0.00055,-0.63,-0.065,-0.0094,-0.025,-0.019,-0.00092,-3.7e+02,-0.00098,-0.0064,-8.2e-05,0.036,-0.028,-0.11,-0.11,-0.024,0.5,-0.0035,-0.091,-0.07,0,0,0.00035,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.7e-06,6.2e-06,2.3e-06,0.022,0.022,0.0099,0.0012,6.3e-05,0.0012,0.00065,0.0013,0.0012,1,1
130 12790000,0.78,-0.018,0.0016,-0.63,-0.072,-0.012,-0.028,-0.018,-0.0006,-3.7e+02,-0.0011,-0.0061,-8.7e-05,0.00058,-0.053,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00054,0.00056,0.046,0.059,0.058,0.024,0.048,0.048,0.053,6.2e-06,6.7e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 12790000,0.78,-0.018,-0.00083,-0.63,-0.061,-0.0086,-0.029,-0.017,-0.00085,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.039,-0.029,-0.11,-0.11,-0.024,0.5,-0.0036,-0.091,-0.07,0,0,0.00032,0.00033,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.02,0.021,0.0097,0.0012,6.3e-05,0.0012,0.00065,0.0013,0.0012,1,1
131 12890000,0.78,-0.018,0.0017,-0.63,-0.079,-0.013,-0.027,-0.026,-0.0019,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00062,-0.054,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00055,0.00056,0.046,0.066,0.066,0.025,0.056,0.056,0.054,6e-06,6.5e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 12890000,0.78,-0.018,-0.00082,-0.63,-0.068,-0.0098,-0.028,-0.024,-0.0022,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.041,-0.029,-0.11,-0.11,-0.024,0.5,-0.0037,-0.091,-0.07,0,0,0.00032,0.00033,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.2e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,6.3e-05,0.0012,0.00065,0.0013,0.0012,1,1
132 12990000,0.78,-0.018,0.0013,-0.63,-0.064,-0.012,-0.028,-0.019,-0.0015,-3.7e+02,-0.0011,-0.006,-8.6e-05,0.0009,-0.056,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.059,0.058,0.025,0.058,0.058,0.052,5.7e-06,6.2e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 12990000,0.78,-0.018,-0.0013,-0.63,-0.055,-0.0092,-0.028,-0.018,-0.0022,-3.7e+02,-0.00096,-0.0062,-8.1e-05,0.044,-0.031,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.054,0.055,0.025,0.057,0.057,0.052,4.9e-06,5.4e-06,2.3e-06,0.019,0.02,0.0094,0.0012,6.3e-05,0.0012,0.00065,0.0013,0.0012,1,1
133 13090000,0.78,-0.018,0.0014,-0.63,-0.069,-0.011,-0.028,-0.026,-0.0023,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00025,-0.057,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.065,0.065,0.025,0.066,0.066,0.052,5.5e-06,6e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1 13090000,0.78,-0.018,-0.0012,-0.63,-0.061,-0.009,-0.028,-0.024,-0.0029,-3.7e+02,-0.00094,-0.0063,-8.3e-05,0.045,-0.033,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,6.3e-05,0.0012,0.00064,0.0012,0.0012,1,1
134 13190000,0.78,-0.018,0.0011,-0.63,-0.055,-0.011,-0.025,-0.017,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.7e-05,-1.3e-05,-0.058,-0.11,-0.11,-0.024,0.5,-0.0016,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.058,0.058,0.025,0.067,0.067,0.051,5.2e-06,5.7e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1 13190000,0.78,-0.018,-0.0015,-0.63,-0.049,-0.0085,-0.025,-0.017,-0.0023,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.035,-0.11,-0.11,-0.024,0.5,-0.0038,-0.091,-0.07,0,0,0.00027,0.00028,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,6.3e-05,0.0012,0.00064,0.0012,0.0012,1,1
135 13290000,0.78,-0.018,0.0011,-0.63,-0.06,-0.013,-0.021,-0.024,-0.003,-3.7e+02,-0.001,-0.006,-8.8e-05,0.00039,-0.059,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.064,0.064,0.027,0.077,0.077,0.051,5.1e-06,5.5e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1 13290000,0.78,-0.018,-0.0016,-0.63,-0.053,-0.011,-0.022,-0.022,-0.0043,-3.7e+02,-0.00094,-0.0062,-8.2e-05,0.049,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00026,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.018,0.0091,0.0012,6.3e-05,0.0012,0.00064,0.0012,0.0012,1,1
136 13390000,0.78,-0.017,0.00099,-0.63,-0.049,-0.012,-0.017,-0.016,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00065,-0.06,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.056,0.056,0.026,0.077,0.077,0.05,4.9e-06,5.3e-06,4.8e-06,0.032,0.032,0.0088,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 13390000,0.78,-0.018,-0.0018,-0.63,-0.044,-0.011,-0.018,-0.016,-0.0036,-3.7e+02,-0.00098,-0.0062,-8.1e-05,0.051,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00024,0.00026,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,6.2e-05,0.0012,0.00064,0.0012,0.0012,1,1
137 13490000,0.78,-0.017,0.00096,-0.63,-0.053,-0.013,-0.016,-0.022,-0.0034,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00089,-0.061,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.062,0.062,0.028,0.088,0.088,0.05,4.7e-06,5.1e-06,4.8e-06,0.031,0.032,0.0087,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 13490000,0.78,-0.018,-0.0019,-0.63,-0.047,-0.012,-0.016,-0.021,-0.0051,-3.7e+02,-0.00097,-0.0062,-8e-05,0.051,-0.035,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00024,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.5e-06,2.3e-06,0.017,0.017,0.0087,0.0012,6.2e-05,0.0012,0.00064,0.0012,0.0012,1,1
138 13590000,0.78,-0.017,0.00083,-0.63,-0.043,-0.012,-0.018,-0.014,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00051,-0.062,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.054,0.054,0.028,0.087,0.087,0.05,4.5e-06,5e-06,4.8e-06,0.031,0.032,0.0084,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 13590000,0.78,-0.018,-0.002,-0.63,-0.038,-0.011,-0.019,-0.014,-0.0037,-3.7e+02,-0.001,-0.0062,-8.1e-05,0.053,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00024,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,6.2e-05,0.0012,0.00064,0.0012,0.0012,1,1
139 13690000,0.78,-0.017,0.00081,-0.63,-0.046,-0.015,-0.022,-0.019,-0.0035,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00095,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.06,0.06,0.029,0.098,0.098,0.05,4.3e-06,4.8e-06,4.8e-06,0.031,0.032,0.0083,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 13690000,0.78,-0.018,-0.0021,-0.63,-0.041,-0.014,-0.023,-0.018,-0.0054,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.053,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00023,0.00024,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.8e-06,4.2e-06,2.3e-06,0.016,0.017,0.0083,0.0012,6.2e-05,0.0012,0.00064,0.0012,0.0012,1,1
140 13790000,0.78,-0.017,0.00063,-0.63,-0.033,-0.013,-0.024,-0.0063,-0.003,-3.7e+02,-0.0011,-0.006,-8.3e-05,0.00068,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.045,0.045,0.029,0.072,0.072,0.049,4.2e-06,4.6e-06,4.8e-06,0.031,0.031,0.0079,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1 13790000,0.78,-0.018,-0.0023,-0.63,-0.03,-0.012,-0.024,-0.0067,-0.0043,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.038,-0.12,-0.11,-0.024,0.5,-0.004,-0.091,-0.07,0,0,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
141 13890000,0.78,-0.017,0.00069,-0.63,-0.037,-0.015,-0.028,-0.01,-0.0045,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00091,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.049,0.049,0.03,0.081,0.081,0.05,4e-06,4.5e-06,4.8e-06,0.031,0.031,0.0078,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1 13890000,0.78,-0.018,-0.0023,-0.63,-0.033,-0.014,-0.029,-0.01,-0.0061,-3.7e+02,-0.00099,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00021,0.00022,0.049,0.048,0.048,0.03,0.079,0.08,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
142 13990000,0.78,-0.017,0.00054,-0.63,-0.029,-0.014,-0.027,-0.0032,-0.004,-3.7e+02,-0.0011,-0.006,-8.4e-05,0.00078,-0.064,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.04,0.04,0.03,0.063,0.063,0.05,3.9e-06,4.3e-06,4.8e-06,0.031,0.031,0.0074,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 13990000,0.78,-0.018,-0.0025,-0.63,-0.025,-0.013,-0.028,-0.0036,-0.0053,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.038,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.4e-06,3.7e-06,2.4e-06,0.014,0.015,0.0074,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
143 14090000,0.78,-0.017,0.00048,-0.63,-0.03,-0.015,-0.028,-0.006,-0.0056,-3.7e+02,-0.0011,-0.006,-8.1e-05,0.0012,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.044,0.044,0.031,0.07,0.07,0.05,3.8e-06,4.2e-06,4.8e-06,0.031,0.031,0.0073,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 14090000,0.78,-0.018,-0.0025,-0.63,-0.026,-0.014,-0.029,-0.0058,-0.0068,-3.7e+02,-0.001,-0.0061,-7.7e-05,0.055,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00019,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.3e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
144 14190000,0.78,-0.017,0.00041,-0.63,-0.024,-0.013,-0.03,-8.4e-05,-0.0036,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0015,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.036,0.036,0.03,0.057,0.057,0.05,3.6e-06,4.1e-06,4.8e-06,0.031,0.031,0.0069,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 14190000,0.78,-0.017,-0.0027,-0.63,-0.021,-0.012,-0.031,-0.00022,-0.0047,-3.7e+02,-0.0011,-0.006,-7.6e-05,0.057,-0.037,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.013,0.014,0.0069,0.0012,6.2e-05,0.0012,0.00063,0.0012,0.0012,1,1
145 14290000,0.78,-0.017,0.00037,-0.63,-0.025,-0.015,-0.029,-0.0025,-0.0051,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0016,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.04,0.04,0.032,0.064,0.064,0.051,3.5e-06,3.9e-06,4.8e-06,0.031,0.031,0.0067,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 14290000,0.78,-0.017,-0.0027,-0.63,-0.022,-0.014,-0.03,-0.0022,-0.006,-3.7e+02,-0.0011,-0.006,-7.5e-05,0.057,-0.036,-0.12,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00018,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3.1e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
146 14390000,0.78,-0.017,0.00033,-0.63,-0.02,-0.015,-0.031,0.0017,-0.0037,-3.7e+02,-0.0011,-0.0059,-7.8e-05,0.0021,-0.065,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.034,0.034,0.031,0.053,0.053,0.05,3.4e-06,3.8e-06,4.8e-06,0.031,0.031,0.0063,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 14390000,0.78,-0.017,-0.0029,-0.63,-0.017,-0.014,-0.032,0.0018,-0.0047,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.059,-0.036,-0.12,-0.11,-0.024,0.5,-0.004,-0.092,-0.069,0,0,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
147 14490000,0.78,-0.017,0.0004,-0.63,-0.022,-0.018,-0.034,-0.00071,-0.0054,-3.7e+02,-0.001,-0.0059,-7.9e-05,0.0022,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.037,0.037,0.032,0.06,0.06,0.051,3.3e-06,3.7e-06,4.8e-06,0.031,0.031,0.0062,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 14490000,0.78,-0.017,-0.0029,-0.63,-0.019,-0.017,-0.035,-0.00047,-0.0066,-3.7e+02,-0.001,-0.006,-7.4e-05,0.061,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.9e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
148 14590000,0.78,-0.017,0.00048,-0.63,-0.023,-0.018,-0.034,-0.0013,-0.0052,-3.7e+02,-0.001,-0.0059,-8e-05,0.0021,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.032,0.032,0.031,0.051,0.051,0.051,3.2e-06,3.6e-06,4.8e-06,0.031,0.031,0.0058,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 14590000,0.78,-0.017,-0.0028,-0.63,-0.02,-0.017,-0.035,-0.0013,-0.0063,-3.7e+02,-0.00099,-0.006,-7.5e-05,0.062,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00017,0.00018,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
149 14690000,0.78,-0.017,0.0005,-0.63,-0.026,-0.017,-0.031,-0.0038,-0.0071,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0024,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.035,0.035,0.032,0.056,0.056,0.051,3.1e-06,3.5e-06,4.8e-06,0.031,0.031,0.0057,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 14690000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.016,-0.032,-0.0035,-0.0082,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.063,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00017,0.00018,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
150 14790000,0.78,-0.017,0.00051,-0.63,-0.025,-0.016,-0.027,-0.0038,-0.0066,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0023,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.03,0.03,0.031,0.049,0.049,0.051,3e-06,3.3e-06,4.8e-06,0.031,0.031,0.0053,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 14790000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.016,-0.028,-0.0036,-0.0076,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.064,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,6.1e-05,0.0012,0.00063,0.0012,0.0012,1,1
151 14890000,0.78,-0.017,0.00052,-0.63,-0.028,-0.019,-0.03,-0.0065,-0.0085,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0025,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.033,0.033,0.031,0.054,0.054,0.052,2.9e-06,3.3e-06,4.8e-06,0.031,0.031,0.0051,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 14890000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.019,-0.031,-0.0061,-0.0095,-3.7e+02,-0.00097,-0.006,-7.3e-05,0.064,-0.036,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
152 14990000,0.78,-0.017,0.00057,-0.63,-0.026,-0.016,-0.026,-0.0049,-0.0065,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.029,0.029,0.03,0.047,0.047,0.051,2.8e-06,3.2e-06,4.8e-06,0.031,0.031,0.0048,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 14990000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.016,-0.027,-0.0047,-0.0074,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.011,0.012,0.0048,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
153 15090000,0.78,-0.017,0.00066,-0.63,-0.028,-0.017,-0.029,-0.0076,-0.0081,-3.7e+02,-0.00097,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.031,0.031,0.031,0.052,0.052,0.052,2.7e-06,3.1e-06,4.8e-06,0.031,0.031,0.0046,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15090000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.016,-0.03,-0.0072,-0.009,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.065,-0.037,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
154 15190000,0.78,-0.017,0.00069,-0.63,-0.026,-0.016,-0.026,-0.006,-0.0064,-3.7e+02,-0.00096,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.00041,0.046,0.027,0.028,0.03,0.046,0.046,0.052,2.6e-06,3e-06,4.8e-06,0.031,0.031,0.0043,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15190000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.015,-0.027,-0.0058,-0.0073,-3.7e+02,-0.00096,-0.006,-7.5e-05,0.066,-0.038,-0.12,-0.11,-0.024,0.5,-0.0042,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
155 15290000,0.78,-0.017,0.00069,-0.63,-0.028,-0.018,-0.024,-0.0086,-0.0082,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0023,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.03,0.03,0.03,0.051,0.051,0.052,2.5e-06,2.9e-06,4.8e-06,0.031,0.031,0.0042,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15290000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.017,-0.025,-0.0081,-0.0089,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.066,-0.037,-0.12,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
156 15390000,0.78,-0.017,0.00064,-0.63,-0.027,-0.018,-0.022,-0.0082,-0.0083,-3.7e+02,-0.00099,-0.0059,-7.4e-05,0.0028,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.029,0.029,0.029,0.054,0.054,0.051,2.4e-06,2.8e-06,4.8e-06,0.031,0.031,0.0039,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15390000,0.78,-0.017,-0.0029,-0.63,-0.025,-0.017,-0.023,-0.0076,-0.0091,-3.7e+02,-0.00099,-0.006,-7.1e-05,0.066,-0.036,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,6.1e-05,0.0012,0.00062,0.0012,0.0012,1,1
157 15490000,0.78,-0.017,0.00066,-0.63,-0.03,-0.018,-0.022,-0.011,-0.0098,-3.7e+02,-0.00099,-0.0059,-7.6e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.031,0.031,0.029,0.06,0.06,0.053,2.4e-06,2.7e-06,4.8e-06,0.031,0.031,0.0037,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15490000,0.78,-0.017,-0.0028,-0.63,-0.028,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.00099,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.5e-06,2.4e-06,0.011,0.011,0.0037,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
158 15590000,0.78,-0.017,0.0007,-0.63,-0.028,-0.017,-0.021,-0.01,-0.0091,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0022,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.029,0.03,0.028,0.062,0.062,0.052,2.3e-06,2.7e-06,4.8e-06,0.031,0.031,0.0035,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15590000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.016,-0.022,-0.0097,-0.0098,-3.7e+02,-0.001,-0.006,-7.3e-05,0.066,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2.1e-06,2.4e-06,2.4e-06,0.01,0.011,0.0035,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
159 15690000,0.78,-0.017,0.00067,-0.63,-0.029,-0.017,-0.021,-0.013,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0021,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.032,0.032,0.028,0.069,0.069,0.052,2.2e-06,2.6e-06,4.8e-06,0.03,0.031,0.0033,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15690000,0.78,-0.017,-0.0027,-0.63,-0.027,-0.016,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
160 15790000,0.78,-0.017,0.00067,-0.63,-0.026,-0.016,-0.024,-0.009,-0.009,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.026,0.027,0.027,0.056,0.057,0.051,2.2e-06,2.5e-06,4.8e-06,0.03,0.031,0.0031,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 15790000,0.78,-0.017,-0.0028,-0.63,-0.025,-0.015,-0.025,-0.0085,-0.0096,-3.7e+02,-0.001,-0.006,-7.3e-05,0.065,-0.038,-0.12,-0.11,-0.024,0.5,-0.0041,-0.092,-0.069,0,0,0.00014,0.00015,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.3e-06,2.4e-06,0.01,0.011,0.0031,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
161 15890000,0.78,-0.017,0.00068,-0.63,-0.028,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.028,0.029,0.027,0.063,0.063,0.052,2.1e-06,2.5e-06,4.8e-06,0.03,0.031,0.003,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 15890000,0.78,-0.017,-0.0027,-0.63,-0.027,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.065,-0.038,-0.13,-0.11,-0.024,0.5,-0.0041,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.0099,0.011,0.003,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
162 15990000,0.78,-0.017,0.00066,-0.63,-0.025,-0.017,-0.017,-0.0084,-0.0095,-3.7e+02,-0.001,-0.0059,-7.3e-05,0.0023,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.026,0.053,0.053,0.051,2e-06,2.4e-06,4.8e-06,0.03,0.031,0.0028,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 15990000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.016,-0.018,-0.0079,-0.0099,-3.7e+02,-0.001,-0.006,-7.1e-05,0.065,-0.037,-0.13,-0.11,-0.024,0.5,-0.004,-0.091,-0.069,0,0,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0028,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
163 16090000,0.78,-0.017,0.00058,-0.63,-0.027,-0.019,-0.014,-0.011,-0.012,-3.7e+02,-0.0011,-0.0059,-7.1e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.026,0.026,0.025,0.058,0.058,0.052,2e-06,2.3e-06,4.8e-06,0.03,0.031,0.0027,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 16090000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.018,-0.015,-0.01,-0.012,-3.7e+02,-0.0011,-0.006,-6.8e-05,0.065,-0.036,-0.13,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0096,0.01,0.0027,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
164 16190000,0.78,-0.017,0.00056,-0.63,-0.025,-0.017,-0.013,-0.008,-0.009,-3.7e+02,-0.0011,-0.0059,-6.9e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.023,0.025,0.05,0.05,0.051,1.9e-06,2.3e-06,4.8e-06,0.03,0.031,0.0025,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 16190000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.016,-0.014,-0.0074,-0.0092,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.064,-0.036,-0.13,-0.11,-0.024,0.5,-0.0039,-0.092,-0.069,0,0,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0094,0.01,0.0025,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
165 16290000,0.78,-0.017,0.00049,-0.63,-0.028,-0.019,-0.014,-0.011,-0.011,-3.7e+02,-0.0011,-0.0059,-6.7e-05,0.0031,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.024,0.055,0.055,0.052,1.9e-06,2.2e-06,4.8e-06,0.03,0.031,0.0024,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16290000,0.78,-0.017,-0.003,-0.63,-0.026,-0.018,-0.015,-0.0099,-0.011,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.065,-0.035,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0093,0.01,0.0024,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
166 16390000,0.78,-0.017,0.00051,-0.63,-0.024,-0.015,-0.013,-0.0081,-0.0086,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.022,0.022,0.023,0.047,0.047,0.051,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16390000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.014,-0.014,-0.0074,-0.0088,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.064,-0.035,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.7e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0022,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
167 16490000,0.78,-0.016,0.00047,-0.63,-0.024,-0.017,-0.016,-0.01,-0.01,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.024,0.023,0.052,0.052,0.052,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16490000,0.78,-0.017,-0.0029,-0.63,-0.022,-0.016,-0.017,-0.0094,-0.01,-3.7e+02,-0.0011,-0.006,-6.4e-05,0.063,-0.035,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0091,0.01,0.0021,0.0012,6e-05,0.0012,0.00062,0.0012,0.0012,1,1
168 16590000,0.78,-0.016,0.00043,-0.63,-0.024,-0.013,-0.017,-0.01,-0.0062,-3.7e+02,-0.0011,-0.0059,-5.9e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.00095,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.021,0.022,0.046,0.046,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.002,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16590000,0.78,-0.017,-0.0029,-0.63,-0.023,-0.012,-0.018,-0.0097,-0.0063,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.063,-0.035,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.9e-06,2.4e-06,0.0089,0.0098,0.002,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
169 16690000,0.78,-0.016,0.00048,-0.63,-0.025,-0.014,-0.013,-0.013,-0.0073,-3.7e+02,-0.0011,-0.0059,-6.1e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.00096,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.022,0.023,0.022,0.05,0.051,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.0019,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16690000,0.78,-0.017,-0.0029,-0.63,-0.024,-0.012,-0.014,-0.012,-0.0073,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.0088,0.0097,0.0019,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
170 16790000,0.78,-0.016,0.00052,-0.63,-0.024,-0.01,-0.012,-0.013,-0.004,-3.7e+02,-0.0011,-0.006,-5.6e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.0009,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.02,0.021,0.044,0.044,0.05,1.6e-06,2e-06,4.8e-06,0.03,0.031,0.0018,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16790000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.0091,-0.013,-0.012,-0.004,-3.7e+02,-0.0011,-0.006,-6e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0087,0.0096,0.0018,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
171 16890000,0.78,-0.016,0.00051,-0.63,-0.025,-0.011,-0.0096,-0.015,-0.0049,-3.7e+02,-0.0011,-0.006,-5.7e-05,0.0027,-0.066,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.022,0.021,0.049,0.049,0.051,1.6e-06,1.9e-06,4.8e-06,0.03,0.031,0.0017,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16890000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.01,-0.01,-0.014,-0.0048,-3.7e+02,-0.0011,-0.006,-6e-05,0.063,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0086,0.0095,0.0017,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
172 16990000,0.78,-0.016,0.00055,-0.63,-0.024,-0.011,-0.0091,-0.014,-0.0048,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.019,0.02,0.02,0.043,0.043,0.05,1.5e-06,1.9e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16990000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.0099,-0.0099,-0.013,-0.0047,-3.7e+02,-0.0011,-0.006,-6.2e-05,0.062,-0.037,-0.13,-0.11,-0.024,0.5,-0.0038,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0085,0.0094,0.0016,0.0012,6e-05,0.0012,0.00061,0.0012,0.0012,1,1
173 17090000,0.78,-0.016,0.00054,-0.63,-0.025,-0.013,-0.009,-0.016,-0.0059,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.021,0.02,0.048,0.048,0.05,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17090000,0.78,-0.017,-0.0027,-0.63,-0.025,-0.012,-0.0098,-0.015,-0.0057,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.062,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0084,0.0093,0.0015,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
174 17190000,0.78,-0.016,0.00048,-0.63,-0.024,-0.015,-0.0099,-0.014,-0.0062,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.019,0.042,0.043,0.049,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0015,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17190000,0.78,-0.017,-0.0028,-0.63,-0.023,-0.014,-0.011,-0.014,-0.006,-3.7e+02,-0.0012,-0.006,-6e-05,0.061,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.4e-06,1.6e-06,2.4e-06,0.0083,0.0092,0.0015,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
175 17290000,0.78,-0.016,0.00051,-0.63,-0.027,-0.017,-0.0054,-0.017,-0.0074,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0024,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.019,0.047,0.047,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0014,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17290000,0.78,-0.017,-0.0027,-0.63,-0.026,-0.015,-0.0061,-0.016,-0.0071,-3.7e+02,-0.0012,-0.006,-6.1e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0037,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0083,0.0091,0.0014,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
176 17390000,0.78,-0.016,0.00044,-0.63,-0.024,-0.018,-0.0035,-0.014,-0.0076,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.018,0.018,0.042,0.042,0.048,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17390000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.017,-0.0042,-0.013,-0.0073,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.091,-0.069,0,0,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0082,0.009,0.0013,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
177 17490000,0.78,-0.016,0.00046,-0.63,-0.026,-0.019,-0.0018,-0.017,-0.0095,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.018,0.046,0.046,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17490000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.018,-0.0025,-0.016,-0.0091,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.061,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0081,0.0089,0.0013,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
178 17590000,0.78,-0.016,0.00047,-0.63,-0.024,-0.019,0.0036,-0.014,-0.0091,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.017,0.041,0.041,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17590000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.018,0.003,-0.014,-0.0088,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.06,-0.036,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.008,0.0088,0.0012,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
179 17690000,0.78,-0.016,0.00049,-0.63,-0.026,-0.021,0.003,-0.017,-0.011,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.0027,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.019,0.017,0.045,0.045,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17690000,0.78,-0.017,-0.0028,-0.63,-0.026,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.5e-06,2.4e-06,0.0079,0.0087,0.0011,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
180 17790000,0.78,-0.016,0.00043,-0.63,-0.024,-0.022,0.0016,-0.015,-0.012,-3.7e+02,-0.0012,-0.0059,-4.8e-05,0.0031,-0.065,-0.13,-0.11,-0.024,0.5,-0.00088,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.016,0.048,0.048,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17790000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.021,0.0011,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.06,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.0011,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
181 17890000,0.78,-0.016,0.00042,-0.63,-0.027,-0.023,0.0017,-0.018,-0.015,-3.7e+02,-0.0012,-0.0059,-4.6e-05,0.0033,-0.065,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.016,0.053,0.053,0.048,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17890000,0.78,-0.017,-0.0029,-0.63,-0.026,-0.022,0.0012,-0.017,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.001,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
182 17990000,0.78,-0.016,0.00045,-0.63,-0.026,-0.021,0.0029,-0.016,-0.015,-3.7e+02,-0.0012,-0.0059,-4.5e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00086,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.016,0.055,0.055,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.001,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1 17990000,0.78,-0.017,-0.0028,-0.63,-0.025,-0.02,0.0024,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0077,0.0085,0.00099,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
183 18090000,0.78,-0.016,0.00049,-0.63,-0.027,-0.021,0.0053,-0.019,-0.016,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.021,0.021,0.016,0.06,0.061,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.00098,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1 18090000,0.78,-0.017,-0.0028,-0.63,-0.027,-0.02,0.0047,-0.018,-0.015,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00096,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
184 18190000,0.78,-0.016,0.00049,-0.63,-0.024,-0.02,0.0066,-0.014,-0.013,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.015,0.051,0.051,0.047,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00093,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18190000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0083,0.0009,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
185 18290000,0.78,-0.016,0.00059,-0.63,-0.025,-0.02,0.0078,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.015,0.056,0.056,0.046,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00089,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18290000,0.78,-0.017,-0.0027,-0.63,-0.025,-0.019,0.0072,-0.016,-0.014,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0036,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0075,0.0082,0.00087,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
186 18390000,0.78,-0.016,0.00055,-0.63,-0.024,-0.021,0.009,-0.013,-0.012,-3.7e+02,-0.0012,-0.006,-3.8e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.014,0.048,0.048,0.046,1.1e-06,1.4e-06,4.7e-06,0.03,0.03,0.00085,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18390000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.02,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.9e-05,0.062,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0074,0.0082,0.00083,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
187 18490000,0.78,-0.016,0.00051,-0.63,-0.024,-0.023,0.0086,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3.7e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.014,0.053,0.053,0.046,1.1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00082,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18490000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.022,0.0081,-0.014,-0.014,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0074,0.0081,0.0008,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
188 18590000,0.78,-0.016,0.00049,-0.63,-0.022,-0.022,0.0067,-0.012,-0.013,-3.7e+02,-0.0013,-0.0059,-2.8e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.016,0.017,0.014,0.046,0.046,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00078,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18590000,0.78,-0.016,-0.0028,-0.63,-0.022,-0.022,0.0062,-0.011,-0.012,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0073,0.008,0.00076,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
189 18690000,0.78,-0.016,0.00055,-0.63,-0.024,-0.023,0.0048,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3e-05,0.0033,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.013,0.05,0.05,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00076,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18690000,0.78,-0.017,-0.0028,-0.63,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.062,-0.034,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0072,0.008,0.00074,0.0012,5.9e-05,0.0012,0.00061,0.0012,0.0012,1,1
190 18790000,0.78,-0.016,0.00057,-0.63,-0.022,-0.021,0.0045,-0.012,-0.012,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.013,0.044,0.044,0.045,1e-06,1.2e-06,4.7e-06,0.03,0.03,0.00073,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18790000,0.78,-0.017,-0.0027,-0.63,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.061,-0.035,-0.13,-0.11,-0.024,0.5,-0.0035,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.0007,0.0012,5.9e-05,0.0012,0.0006,0.0012,0.0012,1,1
191 18890000,0.78,-0.016,0.00048,-0.63,-0.022,-0.024,0.0051,-0.014,-0.015,-3.7e+02,-0.0013,-0.0059,-2.2e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.013,0.048,0.048,0.045,9.8e-07,1.2e-06,4.7e-06,0.03,0.03,0.0007,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18890000,0.78,-0.016,-0.0028,-0.63,-0.022,-0.023,0.0046,-0.014,-0.015,-3.7e+02,-0.0013,-0.006,-3.9e-05,0.061,-0.034,-0.13,-0.11,-0.024,0.5,-0.0034,-0.092,-0.069,0,0,0.00011,0.00011,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.00068,0.0012,5.9e-05,0.0012,0.0006,0.0012,0.0012,1,1
192 18990000,0.78,-0.016,0.00042,-0.63,-0.019,-0.024,0.0037,-0.0098,-0.013,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.012,0.043,0.043,0.044,9.5e-07,1.2e-06,4.7e-06,0.03,0.03,0.00067,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18990000,0.78,-0.016,-0.0029,-0.63,-0.019,-0.023,0.0033,-0.0094,-0.013,-3.7e+02,-0.0013,-0.006,-3.6e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.007,0.0078,0.00065,0.0012,5.9e-05,0.0012,0.0006,0.0012,0.0012,1,1
193 19090000,0.78,-0.016,0.00041,-0.63,-0.019,-0.025,0.0067,-0.011,-0.015,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.012,0.046,0.047,0.044,9.4e-07,1.2e-06,4.7e-06,0.03,0.03,0.00065,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19090000,0.78,-0.016,-0.0028,-0.63,-0.019,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.5e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.007,0.0077,0.00063,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
194 19190000,0.78,-0.016,0.00036,-0.63,-0.015,-0.024,0.0067,-0.0077,-0.013,-3.7e+02,-0.0013,-0.0059,-8.2e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00068,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.015,0.012,0.041,0.042,0.044,9.1e-07,1.2e-06,4.7e-06,0.03,0.03,0.00063,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19190000,0.78,-0.016,-0.0029,-0.63,-0.015,-0.024,0.0063,-0.0074,-0.013,-3.7e+02,-0.0013,-0.006,-3.1e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0069,0.0076,0.0006,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
195 19290000,0.78,-0.016,0.00037,-0.63,-0.016,-0.024,0.0094,-0.0095,-0.016,-3.7e+02,-0.0013,-0.006,-1.1e-05,0.0034,-0.065,-0.13,-0.11,-0.024,0.5,-0.00069,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.012,0.045,0.046,0.044,9e-07,1.1e-06,4.7e-06,0.03,0.03,0.00061,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19290000,0.78,-0.016,-0.0029,-0.63,-0.016,-0.024,0.0091,-0.0091,-0.015,-3.7e+02,-0.0013,-0.006,-3.3e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.0069,0.0076,0.00058,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
196 19390000,0.78,-0.016,0.0004,-0.63,-0.015,-0.022,0.013,-0.0084,-0.014,-3.7e+02,-0.0013,-0.006,-2.4e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.012,0.04,0.041,0.043,8.8e-07,1.1e-06,4.6e-06,0.03,0.03,0.00058,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19390000,0.78,-0.016,-0.0028,-0.63,-0.015,-0.022,0.013,-0.0081,-0.014,-3.7e+02,-0.0013,-0.006,-2.9e-05,0.059,-0.033,-0.13,-0.11,-0.024,0.5,-0.0033,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.0068,0.0075,0.00056,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
197 19490000,0.78,-0.016,0.00035,-0.63,-0.015,-0.024,0.0096,-0.01,-0.017,-3.7e+02,-0.0013,-0.0059,1.4e-06,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00064,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.044,0.045,0.043,8.6e-07,1.1e-06,4.6e-06,0.03,0.03,0.00057,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19490000,0.78,-0.016,-0.0029,-0.63,-0.015,-0.023,0.0093,-0.0097,-0.017,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.06,-0.033,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0068,0.0075,0.00055,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
198 19590000,0.78,-0.015,0.0003,-0.63,-0.013,-0.022,0.0088,-0.0085,-0.015,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.0039,-0.065,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.04,0.04,0.042,8.4e-07,1.1e-06,4.6e-06,0.03,0.03,0.00055,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19590000,0.78,-0.016,-0.003,-0.63,-0.014,-0.022,0.0085,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,-1.9e-05,0.06,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,8e-07,9.7e-07,2.3e-06,0.0067,0.0074,0.00052,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
199 19690000,0.78,-0.015,0.00028,-0.63,-0.014,-0.021,0.01,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00061,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.044,0.042,8.3e-07,1.1e-06,4.6e-06,0.03,0.03,0.00053,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19690000,0.78,-0.016,-0.003,-0.63,-0.014,-0.02,0.01,-0.0091,-0.017,-3.7e+02,-0.0013,-0.006,-2.1e-05,0.059,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.9e-07,9.6e-07,2.3e-06,0.0067,0.0074,0.00051,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
200 19790000,0.78,-0.015,0.00024,-0.63,-0.012,-0.018,0.011,-0.0079,-0.015,-3.7e+02,-0.0013,-0.006,1.8e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00058,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.039,0.039,0.042,8.1e-07,1e-06,4.6e-06,0.03,0.03,0.00051,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19790000,0.78,-0.016,-0.003,-0.63,-0.012,-0.018,0.01,-0.0077,-0.015,-3.7e+02,-0.0013,-0.006,-1.7e-05,0.058,-0.032,-0.13,-0.11,-0.024,0.5,-0.0032,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0066,0.0073,0.00049,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
201 19890000,0.78,-0.015,0.00028,-0.63,-0.011,-0.02,0.012,-0.0096,-0.017,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.004,-0.065,-0.13,-0.11,-0.024,0.5,-0.00056,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.043,0.042,8e-07,1e-06,4.6e-06,0.03,0.03,0.0005,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19890000,0.78,-0.016,-0.003,-0.63,-0.012,-0.02,0.012,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,-1.4e-05,0.059,-0.032,-0.13,-0.11,-0.024,0.5,-0.0031,-0.092,-0.068,0,0,9.9e-05,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0066,0.0073,0.00048,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
202 19990000,0.78,-0.016,0.00028,-0.63,-0.0096,-0.02,0.015,-0.0084,-0.016,-3.7e+02,-0.0013,-0.0059,3.9e-05,0.0043,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.039,0.039,0.041,7.7e-07,9.9e-07,4.6e-06,0.03,0.03,0.00048,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19990000,0.78,-0.016,-0.0031,-0.63,-0.0098,-0.02,0.014,-0.0081,-0.016,-3.7e+02,-0.0013,-0.0059,-4.7e-06,0.06,-0.031,-0.13,-0.11,-0.024,0.5,-0.003,-0.092,-0.068,0,0,9.8e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0066,0.0072,0.00046,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
203 20090000,0.78,-0.016,0.00023,-0.63,-0.0096,-0.02,0.015,-0.0091,-0.019,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.01,0.042,0.043,0.042,7.7e-07,9.8e-07,4.6e-06,0.03,0.03,0.00047,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 20090000,0.78,-0.016,-0.0031,-0.63,-0.0098,-0.021,0.015,-0.0088,-0.019,-3.7e+02,-0.0013,-0.0059,7.1e-08,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.8e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0065,0.0072,0.00045,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
204 20190000,0.78,-0.016,0.00019,-0.63,-0.01,-0.019,0.017,-0.0092,-0.017,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00046,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.038,0.039,0.041,7.4e-07,9.5e-07,4.6e-06,0.03,0.03,0.00045,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20190000,0.78,-0.016,-0.0032,-0.63,-0.01,-0.019,0.017,-0.009,-0.018,-3.7e+02,-0.0013,-0.0059,6e-06,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0065,0.0071,0.00043,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
205 20290000,0.78,-0.016,0.00019,-0.63,-0.0089,-0.019,0.015,-0.0096,-0.019,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0099,0.042,0.042,0.041,7.4e-07,9.4e-07,4.6e-06,0.03,0.03,0.00044,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20290000,0.78,-0.016,-0.0032,-0.63,-0.0091,-0.019,0.015,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,7.8e-06,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.7e-05,0.0001,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0064,0.0071,0.00042,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
206 20390000,0.78,-0.016,0.00024,-0.63,-0.0085,-0.016,0.017,-0.0095,-0.017,-3.7e+02,-0.0013,-0.0059,6.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0097,0.038,0.038,0.041,7.2e-07,9.2e-07,4.5e-06,0.03,0.03,0.00043,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20390000,0.78,-0.016,-0.0032,-0.63,-0.0087,-0.016,0.017,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0064,0.007,0.00041,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
207 20490000,0.78,-0.016,0.0002,-0.63,-0.0087,-0.016,0.017,-0.01,-0.018,-3.7e+02,-0.0013,-0.0059,6.5e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0096,0.041,0.042,0.041,7.1e-07,9.1e-07,4.5e-06,0.03,0.03,0.00042,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20490000,0.78,-0.016,-0.0032,-0.63,-0.0089,-0.017,0.017,-0.01,-0.019,-3.7e+02,-0.0013,-0.0059,1e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.6e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0064,0.007,0.0004,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
208 20590000,0.78,-0.016,0.0002,-0.63,-0.0081,-0.014,0.014,-0.0089,-0.016,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0093,0.038,0.038,0.04,6.9e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20590000,0.78,-0.016,-0.0032,-0.63,-0.0084,-0.014,0.014,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,1.2e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0063,0.0069,0.00038,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
209 20690000,0.78,-0.016,0.00015,-0.63,-0.0089,-0.014,0.015,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,7.2e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0093,0.041,0.042,0.04,6.8e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20690000,0.78,-0.016,-0.0032,-0.63,-0.0091,-0.015,0.015,-0.0096,-0.018,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.5e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0063,0.0069,0.00037,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
210 20790000,0.78,-0.016,0.00013,-0.63,-0.0065,-0.013,0.016,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0091,0.037,0.038,0.04,6.6e-07,8.5e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20790000,0.78,-0.016,-0.0032,-0.63,-0.0068,-0.014,0.015,-0.008,-0.016,-3.7e+02,-0.0013,-0.0059,1.8e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0062,0.0068,0.00036,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
211 20890000,0.78,-0.016,0.00011,-0.63,-0.0067,-0.013,0.015,-0.0088,-0.017,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.009,0.041,0.041,0.04,6.6e-07,8.4e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20890000,0.78,-0.016,-0.0033,-0.63,-0.007,-0.014,0.014,-0.0086,-0.018,-3.7e+02,-0.0013,-0.0059,2.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,9.4e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0062,0.0068,0.00035,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
212 20990000,0.78,-0.016,9.5e-05,-0.63,-0.0051,-0.011,0.015,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,9e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00038,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0088,0.043,0.044,0.039,6.4e-07,8.3e-07,4.4e-06,0.03,0.03,0.00037,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20990000,0.78,-0.016,-0.0033,-0.63,-0.0054,-0.012,0.015,-0.0083,-0.018,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.3e-05,9.9e-05,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0062,0.0067,0.00034,0.0011,5.8e-05,0.0012,0.0006,0.0012,0.0012,1,1
213 21090000,0.78,-0.016,8.8e-05,-0.63,-0.0062,-0.011,0.016,-0.0094,-0.019,-3.7e+02,-0.0013,-0.0059,9.3e-05,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00037,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0088,0.047,0.048,0.039,6.4e-07,8.2e-07,4.4e-06,0.03,0.03,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21090000,0.78,-0.016,-0.0033,-0.63,-0.0065,-0.012,0.015,-0.0092,-0.02,-3.7e+02,-0.0013,-0.0059,2.6e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.3e-05,9.9e-05,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0061,0.0067,0.00034,0.0011,5.8e-05,0.0012,0.00059,0.0012,0.0012,1,1
214 21190000,0.78,-0.016,8.4e-05,-0.63,-0.0063,-0.011,0.015,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,9.4e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00036,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0086,0.049,0.05,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00035,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21190000,0.78,-0.016,-0.0033,-0.63,-0.0066,-0.011,0.014,-0.0097,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.4e-07,2.3e-06,0.0061,0.0067,0.00033,0.0011,5.8e-05,0.0012,0.00059,0.0012,0.0012,1,1
215 21290000,0.78,-0.016,-6.5e-06,-0.63,-0.0059,-0.011,0.017,-0.0099,-0.021,-3.7e+02,-0.0013,-0.0059,0.0001,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00035,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0085,0.054,0.055,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00034,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21290000,0.78,-0.016,-0.0034,-0.63,-0.0061,-0.012,0.016,-0.0097,-0.022,-3.7e+02,-0.0013,-0.0059,3.2e-05,0.061,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,9.3e-05,9.8e-05,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0061,0.0066,0.00032,0.0011,5.8e-05,0.0012,0.00059,0.0012,0.0012,1,1
216 21390000,0.78,-0.016,4.3e-05,-0.63,-0.0052,-0.0064,0.016,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,0.00011,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0084,0.046,0.047,0.039,6e-07,7.7e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21390000,0.78,-0.016,-0.0034,-0.63,-0.0055,-0.0073,0.016,-0.0085,-0.017,-3.7e+02,-0.0013,-0.0059,3.5e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.006,0.0066,0.00031,0.0011,5.8e-05,0.0012,0.00059,0.0012,0.0012,1,1
217 21490000,0.78,-0.016,3.3e-05,-0.63,-0.0059,-0.0073,0.016,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,0.00011,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0083,0.05,0.052,0.038,5.9e-07,7.6e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21490000,0.78,-0.016,-0.0034,-0.63,-0.0061,-0.0083,0.016,-0.0096,-0.018,-3.7e+02,-0.0013,-0.0059,3.7e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9.1e-05,9.7e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.006,0.0065,0.0003,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
218 21590000,0.78,-0.016,7.2e-05,-0.63,-0.0045,-0.0056,0.016,-0.0082,-0.013,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00029,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0081,0.044,0.045,0.038,5.8e-07,7.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21590000,0.78,-0.016,-0.0034,-0.63,-0.0047,-0.0066,0.016,-0.008,-0.014,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.5e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.006,0.0065,0.0003,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
219 21690000,0.78,-0.016,6.5e-05,-0.63,-0.0061,-0.0065,0.017,-0.0095,-0.015,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0081,0.048,0.049,0.038,5.7e-07,7.4e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21690000,0.78,-0.016,-0.0034,-0.63,-0.0063,-0.0077,0.017,-0.0093,-0.016,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,9e-05,9.5e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.0059,0.0065,0.00029,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
220 21790000,0.78,-0.016,0.00016,-0.63,-0.0051,-0.0043,0.016,-0.0083,-0.0092,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.008,0.042,0.043,0.038,5.6e-07,7.1e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21790000,0.78,-0.016,-0.0032,-0.63,-0.0053,-0.0054,0.016,-0.0081,-0.01,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
221 21890000,0.78,-0.015,0.00016,-0.63,-0.0058,-0.005,0.016,-0.009,-0.0097,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0079,0.046,0.047,0.038,5.5e-07,7.1e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21890000,0.78,-0.016,-0.0033,-0.63,-0.006,-0.0063,0.016,-0.0088,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
222 21990000,0.78,-0.015,0.00019,-0.63,-0.0057,-0.0022,0.017,-0.0084,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0078,0.041,0.042,0.038,5.4e-07,6.9e-07,4.3e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21990000,0.78,-0.016,-0.0032,-0.63,-0.0059,-0.0035,0.017,-0.0082,-0.0069,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0058,0.0064,0.00027,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
223 22090000,0.78,-0.015,0.00018,-0.63,-0.0054,-0.0037,0.015,-0.0088,-0.006,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0078,0.045,0.046,0.037,5.4e-07,6.9e-07,4.2e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 22090000,0.78,-0.016,-0.0032,-0.63,-0.0056,-0.0051,0.015,-0.0086,-0.0073,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0058,0.0063,0.00027,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
224 22190000,0.78,-0.015,0.00019,-0.63,-0.004,-0.0043,0.016,-0.0073,-0.0054,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0076,0.04,0.041,0.037,5.2e-07,6.7e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 22190000,0.78,-0.016,-0.0032,-0.63,-0.0042,-0.0057,0.015,-0.0072,-0.0066,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0058,0.0063,0.00026,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
225 22290000,0.78,-0.015,0.00016,-0.63,-0.0036,-0.0039,0.016,-0.008,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0076,0.043,0.045,0.037,5.2e-07,6.6e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 22290000,0.78,-0.016,-0.0032,-0.63,-0.0038,-0.0053,0.016,-0.0079,-0.007,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0058,0.0063,0.00025,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
226 22390000,0.78,-0.015,0.00015,-0.63,-0.0011,-0.0039,0.017,-0.0062,-0.0051,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.012,0.014,0.0075,0.039,0.04,0.037,5.1e-07,6.5e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22390000,0.78,-0.016,-0.0032,-0.63,-0.0013,-0.0053,0.017,-0.0061,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0057,0.0062,0.00025,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
227 22490000,0.78,-0.015,0.00013,-0.63,7e-05,-0.0045,0.018,-0.0056,-0.0054,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0074,0.042,0.044,0.037,5e-07,6.4e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22490000,0.78,-0.016,-0.0033,-0.63,-0.00015,-0.006,0.018,-0.0055,-0.0067,-3.7e+02,-0.0014,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
228 22590000,0.78,-0.015,0.00013,-0.63,0.0019,-0.0034,0.018,-0.0039,-0.0047,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0073,0.045,0.046,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22590000,0.78,-0.016,-0.0032,-0.63,0.0017,-0.0049,0.017,-0.0038,-0.0061,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
229 22690000,0.78,-0.015,6.1e-05,-0.63,0.0035,-0.0046,0.019,-0.0032,-0.0056,-3.7e+02,-0.0014,-0.0059,0.00016,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0073,0.048,0.05,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22690000,0.78,-0.016,-0.0033,-0.63,0.0032,-0.0063,0.019,-0.0031,-0.0072,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.059,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
230 22790000,0.78,-0.015,0.0001,-0.63,0.0045,-0.004,0.02,-0.0026,-0.0042,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0072,0.051,0.052,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22790000,0.78,-0.016,-0.0032,-0.63,0.0043,-0.0055,0.02,-0.0026,-0.0058,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0061,0.00023,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
231 22890000,0.78,-0.015,0.00011,-0.63,0.0052,-0.0049,0.021,-0.0028,-0.0048,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0072,0.055,0.057,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22890000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0065,0.021,-0.0027,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0056,0.0061,0.00023,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
232 22990000,0.78,-0.015,0.00012,-0.63,0.0049,-0.0049,0.022,-0.0029,-0.0055,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0071,0.058,0.06,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22990000,0.78,-0.016,-0.0032,-0.63,0.0047,-0.0067,0.022,-0.0028,-0.0074,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
233 23090000,0.78,-0.015,0.00018,-0.63,0.0051,-0.0046,0.023,-0.0027,-0.0052,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.007,0.062,0.065,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 23090000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0064,0.023,-0.0026,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
234 23190000,0.78,-0.015,0.00017,-0.63,0.0027,-0.0034,0.024,-0.0055,-0.005,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0069,0.065,0.067,0.035,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 23190000,0.78,-0.016,-0.0032,-0.63,0.0025,-0.0052,0.024,-0.0053,-0.0071,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
235 23290000,0.78,-0.015,0.00023,-0.63,0.0023,-0.0031,0.025,-0.0058,-0.0057,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.017,0.019,0.0069,0.07,0.073,0.036,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 23290000,0.78,-0.016,-0.0031,-0.63,0.0021,-0.005,0.025,-0.0056,-0.008,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
236 23390000,0.78,-0.015,0.00021,-0.63,-0.0011,-0.0028,0.022,-0.01,-0.0058,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.0068,0.072,0.075,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23390000,0.78,-0.016,-0.0032,-0.63,-0.0012,-0.0047,0.022,-0.0098,-0.0083,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0055,0.006,0.00021,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
237 23490000,0.78,-0.013,-0.0019,-0.63,0.0044,-0.0021,-0.011,-0.011,-0.007,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00014,-0.091,-0.068,0,0,0.00036,0.00036,0.046,0.017,0.019,0.0068,0.078,0.081,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23490000,0.78,-0.013,-0.0053,-0.63,0.0044,-0.0044,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0055,0.006,0.0002,0.0011,5.7e-05,0.0012,0.00059,0.0012,0.0012,1,1
238 23590000,0.78,-0.0042,-0.0062,-0.63,0.015,0.0017,-0.043,-0.0099,-0.0038,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.066,-0.13,-0.11,-0.024,0.5,-0.00012,-0.091,-0.068,0,0,0.00035,0.00034,0.046,0.014,0.016,0.0067,0.062,0.064,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23590000,0.78,-0.0046,-0.0096,-0.63,0.015,-0.00043,-0.043,-0.0096,-0.0059,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,5.7e-05,0.0012,0.00058,0.0012,0.0012,1,1
239 23690000,0.78,0.0014,-0.0052,-0.63,0.042,0.016,-0.093,-0.0075,-0.0033,-3.7e+02,-0.0013,-0.0059,0.00018,0.0046,-0.066,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00034,0.00034,0.046,0.015,0.017,0.0067,0.067,0.069,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23690000,0.78,0.001,-0.0086,-0.63,0.043,0.013,-0.093,-0.0072,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
240 23790000,0.78,-0.0022,-0.0027,-0.63,0.063,0.033,-0.15,-0.0074,-0.0017,-3.7e+02,-0.0013,-0.0059,0.00018,0.0049,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.014,0.015,0.0066,0.055,0.056,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23790000,0.78,-0.0026,-0.0061,-0.63,0.064,0.031,-0.15,-0.0072,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
241 23890000,0.78,-0.0085,-0.0007,-0.63,0.077,0.045,-0.2,2.8e-05,0.0023,-3.7e+02,-0.0013,-0.0059,0.00019,0.005,-0.066,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00034,0.00035,0.046,0.014,0.016,0.0066,0.059,0.061,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23890000,0.78,-0.0089,-0.0042,-0.63,0.078,0.042,-0.2,0.00038,-9.2e-05,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.091,-0.067,0,0,8.1e-05,8.6e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
242 23990000,0.78,-0.013,0.00021,-0.63,0.072,0.045,-0.25,-0.0055,0.00083,-3.7e+02,-0.0013,-0.0059,0.00018,0.0052,-0.067,-0.13,-0.11,-0.024,0.5,-0.00029,-0.09,-0.067,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0066,0.062,0.063,0.035,4.1e-07,5.2e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23990000,0.78,-0.014,-0.0033,-0.63,0.073,0.042,-0.25,-0.0051,-0.0016,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
243 24090000,0.78,-0.012,-0.00093,-0.63,0.072,0.044,-0.3,0.00081,0.0045,-3.7e+02,-0.0013,-0.0059,0.00019,0.0053,-0.067,-0.13,-0.11,-0.024,0.5,-0.00034,-0.09,-0.067,0,0,0.00035,0.00036,0.046,0.015,0.017,0.0065,0.066,0.069,0.035,4.1e-07,5.2e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 24090000,0.78,-0.012,-0.0045,-0.63,0.073,0.041,-0.3,0.0013,0.0017,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0058,0.00019,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
244 24190000,0.78,-0.0097,-0.0017,-0.63,0.069,0.043,-0.35,-0.0065,0.0022,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00031,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.015,0.017,0.0065,0.069,0.071,0.034,4.1e-07,5.1e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24190000,0.78,-0.01,-0.0053,-0.62,0.071,0.04,-0.35,-0.0059,-0.00051,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
245 24290000,0.78,-0.0089,-0.0021,-0.63,0.077,0.048,-0.4,-0.00011,0.0069,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0065,0.074,0.077,0.034,4e-07,5.1e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24290000,0.78,-0.0092,-0.0057,-0.62,0.079,0.045,-0.4,0.00061,0.0038,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
246 24390000,0.78,-0.0093,-0.0022,-0.63,0.074,0.047,-0.46,-0.013,0.00027,-3.7e+02,-0.0012,-0.0059,0.00015,0.0062,-0.069,-0.13,-0.11,-0.024,0.5,-0.0003,-0.089,-0.068,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0064,0.076,0.079,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24390000,0.78,-0.0096,-0.0058,-0.62,0.076,0.043,-0.46,-0.012,-0.0026,-3.7e+02,-0.0012,-0.0059,6.8e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.6e-05,0.0012,0.00058,0.0012,0.0012,1,1
247 24490000,0.78,-0.0051,-0.0026,-0.63,0.085,0.054,-0.51,-0.0046,0.0052,-3.7e+02,-0.0012,-0.0059,0.00015,0.0063,-0.069,-0.13,-0.11,-0.024,0.5,-0.00033,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.02,0.0064,0.082,0.085,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24490000,0.78,-0.0054,-0.0062,-0.62,0.087,0.05,-0.51,-0.0037,0.002,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.5e-05,0.0012,0.00058,0.0012,0.0012,1,1
248 24590000,0.78,-0.0016,-0.0027,-0.63,0.089,0.057,-0.56,-0.018,-0.0039,-3.7e+02,-0.0012,-0.0059,0.00014,0.0069,-0.071,-0.13,-0.11,-0.024,0.5,-0.00037,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.019,0.0063,0.084,0.088,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24590000,0.78,-0.0019,-0.0064,-0.62,0.091,0.054,-0.56,-0.017,-0.0068,-3.7e+02,-0.0012,-0.0059,6.3e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.5e-05,0.0012,0.00058,0.0011,0.0012,1,1
249 24690000,0.78,-0.00074,-0.0027,-0.63,0.11,0.073,-0.64,-0.0089,0.0014,-3.7e+02,-0.0012,-0.0059,0.00015,0.0072,-0.071,-0.13,-0.11,-0.024,0.5,-0.00055,-0.089,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0063,0.09,0.094,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24690000,0.78,-0.001,-0.0064,-0.62,0.11,0.069,-0.64,-0.0078,-0.002,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0028,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.5e-05,0.0012,0.00058,0.0011,0.0012,1,1
250 24790000,0.78,-0.0023,-0.0024,-0.63,0.11,0.082,-0.73,-0.028,-0.0034,-3.7e+02,-0.0012,-0.0059,0.00013,0.0079,-0.073,-0.13,-0.11,-0.025,0.5,-0.00036,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0062,0.093,0.096,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 24790000,0.78,-0.0025,-0.0063,-0.62,0.11,0.078,-0.73,-0.027,-0.0066,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0026,-0.09,-0.068,0,0,8e-05,8.4e-05,0.047,0.018,0.019,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.5e-05,0.0012,0.00058,0.0011,0.0012,1,1
251 24890000,0.78,-0.00046,-0.004,-0.63,0.13,0.097,-0.75,-0.017,0.0055,-3.7e+02,-0.0012,-0.0059,0.00012,0.0081,-0.074,-0.13,-0.11,-0.025,0.5,-0.00045,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.099,0.1,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00062,0.0012,0.0012,1,1 24890000,0.78,-0.00067,-0.0078,-0.62,0.13,0.092,-0.75,-0.016,0.0019,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0027,-0.089,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.5e-05,0.0012,0.00058,0.0011,0.0012,1,1
252 24990000,0.78,0.0012,-0.0055,-0.63,0.13,0.1,-0.81,-0.039,-0.001,-3.7e+02,-0.0011,-0.0059,9e-05,0.0092,-0.076,-0.13,-0.11,-0.025,0.5,-0.00024,-0.087,-0.069,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.1,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 24990000,0.78,0.0011,-0.0094,-0.62,0.14,0.1,-0.81,-0.038,-0.0043,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0024,-0.089,-0.069,0,0,8e-05,8.4e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.4e-05,0.0012,0.00058,0.0011,0.0012,1,1
253 25090000,0.78,0.00063,-0.0059,-0.63,0.16,0.12,-0.86,-0.025,0.011,-3.7e+02,-0.0011,-0.0059,8.4e-05,0.0094,-0.076,-0.13,-0.11,-0.025,0.5,-0.00025,-0.087,-0.068,0,0,0.00034,0.00034,0.044,0.02,0.023,0.0062,0.11,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0011,0.0012,1,1 25090000,0.78,0.00051,-0.0098,-0.62,0.16,0.12,-0.86,-0.023,0.0069,-3.7e+02,-0.0011,-0.0059,4.1e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0025,-0.088,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.4e-05,0.0012,0.00058,0.0011,0.0012,1,1
254 25190000,0.78,-0.0015,-0.0054,-0.62,0.15,0.11,-0.91,-0.069,-0.012,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00022,-0.086,-0.069,0,0,0.00034,0.00033,0.044,0.02,0.023,0.0061,0.11,0.11,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1 25190000,0.78,-0.0014,-0.0095,-0.62,0.15,0.11,-0.91,-0.067,-0.015,-3.7e+02,-0.0011,-0.0058,2.1e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0022,-0.088,-0.069,0,0,8e-05,8.3e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.4e-05,0.0012,0.00057,0.0011,0.0012,1,1
255 25290000,0.78,0.0055,-0.0066,-0.62,0.17,0.13,-0.96,-0.053,-0.00075,-3.7e+02,-0.0011,-0.0059,4.8e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00034,-0.086,-0.069,0,0,0.00033,0.00034,0.044,0.021,0.024,0.0061,0.12,0.12,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.0006,0.0011,0.0012,1,1 25290000,0.78,0.0055,-0.011,-0.62,0.18,0.12,-0.96,-0.051,-0.0042,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.3e-05,0.0012,0.00057,0.0011,0.0012,1,1
256 25390000,0.78,0.011,-0.0071,-0.62,0.18,0.13,-1,-0.1,-0.025,-3.7e+02,-0.001,-0.0058,8.1e-06,0.014,-0.086,-0.13,-0.11,-0.025,0.5,-0.00037,-0.085,-0.069,0,0,0.00033,0.00036,0.043,0.021,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.00059,0.0011,0.0012,1,1 25390000,0.79,0.012,-0.011,-0.62,0.18,0.13,-1,-0.099,-0.028,-3.7e+02,-0.001,-0.0058,4.8e-06,0.078,-0.03,-0.13,-0.12,-0.025,0.5,-0.0021,-0.087,-0.069,0,0,8e-05,8.3e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00016,0.0011,5.3e-05,0.0012,0.00057,0.0011,0.0012,1,1
257 25490000,0.78,0.013,-0.0072,-0.63,0.22,0.16,-1.1,-0.082,-0.012,-3.7e+02,-0.001,-0.0058,2.3e-05,0.014,-0.087,-0.13,-0.11,-0.025,0.5,-0.00072,-0.084,-0.069,0,0,0.00033,0.00036,0.042,0.022,0.026,0.0061,0.13,0.13,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0012,0.00058,0.0011,0.0012,1,1 25490000,0.78,0.013,-0.011,-0.62,0.22,0.16,-1.1,-0.08,-0.015,-3.7e+02,-0.001,-0.0058,1.4e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0024,-0.086,-0.069,0,0,8.1e-05,8.4e-05,0.046,0.022,0.023,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.2e-05,0.0012,0.00056,0.0011,0.0011,1,1
258 25590000,0.78,0.011,-0.007,-0.63,0.25,0.19,-1.1,-0.059,0.0041,-3.7e+02,-0.001,-0.0058,3.2e-05,0.014,-0.087,-0.13,-0.12,-0.025,0.5,-0.00098,-0.084,-0.068,0,0,0.00033,0.00035,0.042,0.024,0.028,0.0061,0.14,0.14,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0011,0.00058,0.0011,0.0011,1,1 25590000,0.78,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.057,0.00066,-3.7e+02,-0.001,-0.0058,1.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.4e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.2e-05,0.0011,0.00056,0.0011,0.0011,1,1
259 25690000,0.78,0.018,-0.0099,-0.63,0.29,0.21,-1.2,-0.032,0.022,-3.7e+02,-0.001,-0.0058,4.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0013,-0.082,-0.068,0,0,0.00034,0.00039,0.042,0.025,0.03,0.0061,0.14,0.15,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00017,0.001,5.2e-05,0.0011,0.00057,0.0011,0.0011,1,1 25690000,0.78,0.018,-0.014,-0.62,0.3,0.21,-1.2,-0.03,0.019,-3.7e+02,-0.00099,-0.0058,2.7e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0031,-0.084,-0.068,0,0,8.2e-05,8.5e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.1e-05,0.0011,0.00056,0.0011,0.0011,1,1
260 25790000,0.78,0.024,-0.012,-0.63,0.35,0.25,-1.2,-0.00023,0.043,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0019,-0.081,-0.067,0,0,0.00034,0.00043,0.041,0.027,0.033,0.0061,0.15,0.16,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5.1e-05,0.0011,0.00057,0.0011,0.0011,1,1 25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0028,0.039,-3.7e+02,-0.00099,-0.0058,3.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0035,-0.083,-0.067,0,0,8.3e-05,8.5e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5e-05,0.0011,0.00056,0.001,0.0011,1,1
261 25890000,0.77,0.025,-0.012,-0.63,0.41,0.28,-1.3,0.039,0.066,-3.7e+02,-0.00099,-0.0058,8.6e-05,0.015,-0.089,-0.13,-0.12,-0.026,0.5,-0.0025,-0.079,-0.066,0,0,0.00034,0.00043,0.04,0.029,0.037,0.0061,0.17,0.17,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5e-05,0.0011,0.00056,0.0011,0.0011,1,1 25890000,0.78,0.025,-0.016,-0.63,0.41,0.28,-1.3,0.042,0.062,-3.7e+02,-0.00099,-0.0058,5.3e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.6e-05,0.045,0.029,0.031,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.00098,4.9e-05,0.0011,0.00056,0.001,0.0011,1,1
262 25990000,0.77,0.021,-0.012,-0.63,0.47,0.31,-1.3,0.083,0.093,-3.7e+02,-0.00099,-0.0058,9.9e-05,0.015,-0.089,-0.13,-0.12,-0.027,0.5,-0.0029,-0.078,-0.065,0,0,0.00034,0.00041,0.04,0.032,0.04,0.0061,0.18,0.19,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00099,5e-05,0.0011,0.00055,0.001,0.0011,1,1 25990000,0.78,0.022,-0.016,-0.63,0.47,0.32,-1.3,0.086,0.089,-3.7e+02,-0.00099,-0.0058,6.2e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0045,-0.08,-0.065,0,0,8.4e-05,8.6e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00096,4.8e-05,0.0011,0.00055,0.001,0.0011,1,1
263 26090000,0.78,0.032,-0.016,-0.63,0.52,0.35,-1.3,0.13,0.13,-3.7e+02,-0.00098,-0.0058,8.8e-05,0.016,-0.089,-0.13,-0.12,-0.027,0.5,-0.0028,-0.077,-0.065,0,0,0.00035,0.00049,0.039,0.034,0.043,0.0061,0.19,0.2,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00097,4.8e-05,0.0011,0.00054,0.001,0.0011,1,1 26090000,0.78,0.032,-0.02,-0.62,0.53,0.35,-1.3,0.14,0.12,-3.7e+02,-0.00098,-0.0058,6e-05,0.079,-0.031,-0.13,-0.12,-0.027,0.5,-0.0046,-0.079,-0.065,0,0,8.5e-05,8.7e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00094,4.7e-05,0.0011,0.00054,0.00098,0.0011,1,1
264 26190000,0.78,0.041,-0.017,-0.63,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,9.6e-05,0.018,-0.09,-0.13,-0.13,-0.028,0.5,-0.0035,-0.074,-0.063,0,0,0.00036,0.00058,0.037,0.036,0.047,0.0061,0.2,0.22,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00093,4.7e-05,0.001,0.00053,0.00098,0.001,1,1 26190000,0.78,0.042,-0.021,-0.62,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.1e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.5,-0.0054,-0.075,-0.063,0,0,8.6e-05,8.7e-05,0.043,0.035,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00014,0.00091,4.6e-05,0.001,0.00053,0.00094,0.001,1,1
265 26290000,0.78,0.044,-0.018,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,9.2e-05,0.019,-0.091,-0.13,-0.13,-0.028,0.49,-0.0037,-0.071,-0.061,0,0,0.00036,0.0006,0.036,0.039,0.052,0.0061,0.21,0.23,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00091,4.6e-05,0.001,0.00052,0.00094,0.001,1,1 26290000,0.78,0.044,-0.022,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.4e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.49,-0.0057,-0.073,-0.061,0,0,8.7e-05,8.8e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00088,4.4e-05,0.001,0.00052,0.00091,0.00099,1,1
266 26390000,0.77,0.04,-0.018,-0.63,0.76,0.5,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,0.0001,0.02,-0.091,-0.13,-0.13,-0.028,0.49,-0.0042,-0.069,-0.06,0,0,0.00036,0.00055,0.034,0.042,0.056,0.0061,0.23,0.25,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00088,4.4e-05,0.00098,0.0005,0.00091,0.00097,1,1 26390000,0.78,0.041,-0.022,-0.63,0.76,0.5,-1.3,0.33,0.24,-3.7e+02,-0.00097,-0.0058,8.2e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,8.9e-05,0.041,0.041,0.047,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00085,4.3e-05,0.00097,0.00051,0.00088,0.00096,1,1
267 26490000,0.77,0.056,-0.024,-0.63,0.84,0.55,-1.3,0.4,0.3,-3.7e+02,-0.00096,-0.0058,0.0001,0.02,-0.092,-0.13,-0.13,-0.029,0.49,-0.0043,-0.067,-0.058,0,0,0.00038,0.00075,0.033,0.044,0.061,0.0061,0.24,0.27,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00084,4.2e-05,0.00094,0.00048,0.00088,0.00094,1,1 26490000,0.77,0.057,-0.028,-0.63,0.84,0.55,-1.3,0.41,0.29,-3.7e+02,-0.00097,-0.0058,8.7e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0065,-0.069,-0.058,0,0,8.9e-05,8.9e-05,0.039,0.044,0.051,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00081,4.1e-05,0.00093,0.00049,0.00084,0.00093,1,1
268 26590000,0.77,0.073,-0.029,-0.63,0.95,0.63,-1.3,0.48,0.36,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.023,-0.092,-0.13,-0.13,-0.03,0.49,-0.0039,-0.064,-0.057,0,0,0.00041,0.00098,0.031,0.048,0.067,0.0061,0.26,0.29,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0008,4e-05,0.00089,0.00046,0.00083,0.00089,1,1 26590000,0.77,0.074,-0.033,-0.63,0.96,0.63,-1.3,0.49,0.35,-3.7e+02,-0.00096,-0.0058,8.1e-05,0.08,-0.032,-0.13,-0.14,-0.03,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9e-05,0.038,0.048,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00077,3.9e-05,0.00088,0.00047,0.0008,0.00088,1,1
269 26690000,0.77,0.076,-0.03,-0.64,1.1,0.71,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.024,-0.093,-0.13,-0.14,-0.031,0.49,-0.0049,-0.059,-0.052,0,0,0.00041,0.00097,0.028,0.052,0.073,0.0061,0.28,0.31,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00074,3.8e-05,0.00083,0.00044,0.00077,0.00083,1,1 26690000,0.77,0.077,-0.034,-0.64,1.1,0.71,-1.3,0.6,0.41,-3.7e+02,-0.00096,-0.0058,9.7e-05,0.08,-0.032,-0.13,-0.14,-0.031,0.49,-0.0073,-0.061,-0.052,0,0,9e-05,9.1e-05,0.035,0.052,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00071,3.6e-05,0.00082,0.00045,0.00074,0.00082,1,1
270 26790000,0.77,0.07,-0.029,-0.64,1.2,0.79,-1.3,0.7,0.5,-3.7e+02,-0.00095,-0.0058,6.9e-05,0.025,-0.093,-0.13,-0.14,-0.032,0.48,-0.0047,-0.055,-0.049,0,0,0.00039,0.00084,0.026,0.055,0.079,0.0061,0.3,0.33,0.033,3.7e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0007,3.6e-05,0.00079,0.00041,0.00073,0.00078,1,1 26790000,0.77,0.071,-0.033,-0.64,1.2,0.79,-1.3,0.71,0.48,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.08,-0.032,-0.13,-0.14,-0.032,0.48,-0.0071,-0.057,-0.049,0,0,9.1e-05,9.1e-05,0.032,0.055,0.068,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00067,3.4e-05,0.00078,0.00041,0.00069,0.00077,1,1
271 26890000,0.76,0.093,-0.036,-0.64,1.3,0.86,-1.3,0.83,0.58,-3.7e+02,-0.00095,-0.0058,7.2e-05,0.026,-0.093,-0.13,-0.15,-0.032,0.48,-0.0052,-0.052,-0.047,0,0,0.00044,0.0011,0.024,0.058,0.085,0.0061,0.32,0.35,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00066,3.4e-05,0.00074,0.00039,0.00068,0.00074,1,1 26890000,0.76,0.093,-0.04,-0.64,1.4,0.86,-1.3,0.85,0.56,-3.7e+02,-0.00095,-0.0058,0.0001,0.08,-0.032,-0.13,-0.15,-0.033,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.2e-05,0.03,0.059,0.073,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00063,3.2e-05,0.00073,0.00039,0.00065,0.00073,1,1
272 26990000,0.76,0.12,-0.041,-0.64,1.5,0.97,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,6.1e-05,0.029,-0.094,-0.13,-0.15,-0.034,0.48,-0.0055,-0.046,-0.043,0,0,0.00049,0.0014,0.021,0.061,0.091,0.0061,0.34,0.37,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.0006,3.1e-05,0.00067,0.00036,0.00062,0.00067,1,1 26990000,0.76,0.12,-0.045,-0.64,1.5,0.97,-1.3,0.99,0.65,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.034,0.48,-0.0079,-0.047,-0.043,0,0,9.2e-05,9.2e-05,0.027,0.062,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00057,3e-05,0.00066,0.00035,0.00059,0.00066,1,1
273 27090000,0.76,0.12,-0.041,-0.64,1.7,1.1,-1.2,1.1,0.78,-3.7e+02,-0.00095,-0.0058,4.5e-05,0.03,-0.093,-0.13,-0.16,-0.035,0.47,-0.0055,-0.041,-0.038,0,0,0.00049,0.0013,0.018,0.065,0.098,0.0061,0.36,0.4,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00055,2.8e-05,0.0006,0.00033,0.00056,0.0006,1,1 27090000,0.76,0.12,-0.045,-0.64,1.7,1.1,-1.3,1.2,0.75,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.035,0.47,-0.0078,-0.043,-0.038,0,0,9.3e-05,9.3e-05,0.024,0.066,0.086,0.0061,0.36,0.37,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00052,2.7e-05,0.00059,0.00031,0.00053,0.00059,1,1
274 27190000,0.76,0.11,-0.039,-0.64,1.9,1.2,-1.2,1.3,0.9,-3.7e+02,-0.00096,-0.0058,2.8e-05,0.032,-0.092,-0.13,-0.16,-0.035,0.47,-0.0053,-0.038,-0.035,0,0,0.00045,0.0011,0.017,0.068,0.1,0.0062,0.38,0.43,0.034,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00051,2.6e-05,0.00056,0.00031,0.00052,0.00056,1,1 27190000,0.76,0.11,-0.043,-0.64,1.9,1.2,-1.2,1.3,0.87,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.16,-0.036,0.47,-0.0074,-0.04,-0.035,0,0,9.3e-05,9.3e-05,0.021,0.07,0.092,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00048,2.5e-05,0.00055,0.00028,0.00049,0.00054,1,1
275 27290000,0.76,0.093,-0.035,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,2.2e-05,0.032,-0.091,-0.13,-0.16,-0.036,0.47,-0.0054,-0.035,-0.033,0,0,0.00041,0.00083,0.015,0.07,0.11,0.0062,0.4,0.46,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00048,2.5e-05,0.00053,0.00029,0.00049,0.00052,1,1 27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,0.99,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.036,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.4e-05,0.019,0.071,0.095,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00045,2.4e-05,0.00052,0.00026,0.00046,0.00051,1,1
276 27390000,0.76,0.077,-0.03,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00095,-0.0058,1.7e-05,0.033,-0.089,-0.13,-0.17,-0.036,0.47,-0.0054,-0.033,-0.032,0,0,0.00038,0.00064,0.014,0.071,0.11,0.0062,0.43,0.49,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00046,2.4e-05,0.00051,0.00027,0.00047,0.00051,1,1 27390000,0.76,0.078,-0.034,-0.64,2.2,1.4,-1.2,1.7,1.1,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.037,0.47,-0.0074,-0.035,-0.032,0,0,9.4e-05,9.4e-05,0.017,0.072,0.095,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00043,2.3e-05,0.0005,0.00023,0.00044,0.00049,1,1
277 27490000,0.76,0.061,-0.025,-0.64,2.2,1.4,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,9e-06,0.033,-0.087,-0.13,-0.17,-0.037,0.47,-0.0052,-0.032,-0.032,0,0,0.00036,0.00052,0.012,0.072,0.11,0.0062,0.46,0.52,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00044,2.3e-05,0.0005,0.00025,0.00046,0.0005,1,1 27490000,0.76,0.062,-0.029,-0.64,2.2,1.4,-1.2,2,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.029,-0.13,-0.17,-0.037,0.47,-0.0071,-0.034,-0.032,0,0,9.5e-05,9.5e-05,0.015,0.073,0.094,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00042,2.2e-05,0.00049,0.00021,0.00043,0.00048,1,1
278 27590000,0.77,0.049,-0.022,-0.64,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,-8.8e-07,0.034,-0.084,-0.13,-0.17,-0.037,0.47,-0.0048,-0.031,-0.031,0,0,0.00035,0.00045,0.012,0.073,0.11,0.0062,0.48,0.55,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.3e-05,0.00049,0.00024,0.00045,0.00049,1,1 27590000,0.77,0.049,-0.025,-0.64,2.3,1.5,-1.2,2.2,1.4,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.028,-0.13,-0.17,-0.037,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.5e-05,0.014,0.073,0.093,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00041,2.2e-05,0.00048,0.0002,0.00042,0.00048,1,1
279 27690000,0.77,0.047,-0.021,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,-9.9e-06,0.034,-0.083,-0.13,-0.17,-0.037,0.47,-0.0044,-0.031,-0.031,0,0,0.00035,0.00044,0.011,0.073,0.11,0.0063,0.51,0.59,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.2e-05,0.00049,0.00023,0.00045,0.00049,1,1 27690000,0.77,0.048,-0.025,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.081,-0.027,-0.13,-0.17,-0.037,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.013,0.073,0.091,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00013,0.0004,2.1e-05,0.00048,0.00018,0.00042,0.00047,1,1
280 27790000,0.77,0.049,-0.021,-0.64,2.3,1.5,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,-2.3e-05,0.035,-0.081,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.031,0,0,0.00035,0.00044,0.0098,0.074,0.1,0.0063,0.54,0.62,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00042,2.2e-05,0.00049,0.00022,0.00044,0.00048,1,1 27790000,0.77,0.05,-0.025,-0.64,2.3,1.5,-1.2,2.6,1.7,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.037,0.47,-0.0055,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.012,0.073,0.09,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.0004,2.1e-05,0.00047,0.00017,0.00041,0.00047,1,1
281 27890000,0.77,0.047,-0.021,-0.64,2.4,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,-2.4e-05,0.034,-0.079,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00043,0.0093,0.075,0.1,0.0063,0.58,0.66,0.034,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00041,2.2e-05,0.00048,0.00022,0.00044,0.00048,1,1 27890000,0.77,0.048,-0.024,-0.64,2.4,1.6,-1.2,2.9,1.9,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.46,-0.0055,-0.031,-0.031,0,0,9.8e-05,9.7e-05,0.011,0.074,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.1e-05,0.00047,0.00016,0.0004,0.00047,1,1
282 27990000,0.77,0.043,-0.02,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,-2.7e-05,0.034,-0.078,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00041,0.0087,0.076,0.1,0.0064,0.61,0.7,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00041,2.1e-05,0.00048,0.00021,0.00043,0.00048,1,1 27990000,0.77,0.044,-0.024,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.1e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0055,-0.031,-0.031,0,0,9.9e-05,9.7e-05,0.01,0.075,0.089,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00038,2e-05,0.00047,0.00015,0.0004,0.00046,1,1
283 28090000,0.77,0.057,-0.025,-0.64,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,-3.8e-05,0.035,-0.076,-0.13,-0.17,-0.038,0.47,-0.0035,-0.029,-0.03,0,0,0.00035,0.00045,0.0081,0.077,0.1,0.0064,0.65,0.74,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.0004,2.1e-05,0.00048,0.00021,0.00042,0.00048,1,1 28090000,0.77,0.057,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.2,-3.7e+02,-0.00095,-0.0058,8.6e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.8e-05,0.0096,0.076,0.089,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00038,2e-05,0.00046,0.00015,0.00039,0.00046,1,1
284 28190000,0.77,0.071,-0.028,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,-4e-05,0.035,-0.074,-0.13,-0.17,-0.038,0.46,-0.0035,-0.029,-0.03,0,0,0.00036,0.00049,0.0077,0.078,0.1,0.0065,0.68,0.79,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00039,2.1e-05,0.00047,0.0002,0.00042,0.00047,1,1 28190000,0.77,0.071,-0.032,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,8.5e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0091,0.077,0.089,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00037,2e-05,0.00046,0.00014,0.00038,0.00045,1,1
285 28290000,0.77,0.053,-0.022,-0.64,2.5,1.7,-0.065,3.8,2.6,-3.7e+02,-0.00095,-0.0058,-4.9e-05,0.035,-0.071,-0.13,-0.17,-0.038,0.46,-0.0033,-0.028,-0.029,0,0,0.00035,0.00043,0.0074,0.077,0.1,0.0066,0.72,0.83,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.0002,0.00041,0.00046,1,1 28290000,0.77,0.053,-0.026,-0.63,2.5,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.1e-05,0.083,-0.024,-0.13,-0.17,-0.038,0.46,-0.0047,-0.029,-0.029,0,0,0.0001,9.9e-05,0.0086,0.076,0.087,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00014,0.00038,0.00045,1,1
286 28390000,0.77,0.02,-0.0094,-0.64,2.5,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,-5.7e-05,0.035,-0.068,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00035,0.00037,0.0071,0.076,0.1,0.0066,0.76,0.88,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 28390000,0.77,0.02,-0.013,-0.64,2.4,1.7,0.79,4,2.7,-3.7e+02,-0.00095,-0.0058,7.6e-05,0.083,-0.023,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00013,0.00037,0.00045,1,1
287 28490000,0.77,0.0014,-0.0026,-0.64,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,-6.3e-05,0.035,-0.065,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0068,0.077,0.099,0.0067,0.8,0.93,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 28490000,0.77,0.0015,-0.0059,-0.64,2.4,1.7,1.1,4.3,2.9,-3.7e+02,-0.00096,-0.0058,7.1e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.076,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00013,0.00037,0.00045,1,1
288 28590000,0.77,-0.0022,-0.0011,-0.64,2.4,1.6,0.99,4.5,3.1,-3.7e+02,-0.00096,-0.0058,-6.4e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0065,0.077,0.098,0.0067,0.84,0.98,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 28590000,0.77,-0.0022,-0.0045,-0.63,2.3,1.6,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00012,0.00037,0.00044,1,1
289 28690000,0.77,-0.0032,-0.00057,-0.64,2.3,1.6,0.99,4.8,3.3,-3.7e+02,-0.00097,-0.0058,-7.1e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.003,-0.027,-0.029,0,0,0.00034,0.00036,0.0063,0.078,0.098,0.0067,0.88,1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1 28690000,0.77,-0.0032,-0.0039,-0.63,2.3,1.6,0.99,4.8,3.2,-3.7e+02,-0.00097,-0.0058,6.6e-05,0.082,-0.022,-0.12,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00045,0.00012,0.00037,0.00044,1,1
290 28790000,0.77,-0.0034,-0.00035,-0.63,2.2,1.6,1,5,3.4,-3.7e+02,-0.00098,-0.0058,-7.9e-05,0.034,-0.061,-0.12,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00034,0.00037,0.0061,0.079,0.098,0.0068,0.92,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.4,-3.7e+02,-0.00097,-0.0058,6.1e-05,0.082,-0.021,-0.12,-0.17,-0.038,0.46,-0.0041,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,1.9e-05,0.00044,0.00011,0.00037,0.00044,1,1
291 28890000,0.77,-0.0032,-0.00036,-0.63,2.2,1.5,0.99,5.2,3.6,-3.7e+02,-0.00099,-0.0058,-8.6e-05,0.033,-0.06,-0.12,-0.17,-0.038,0.46,-0.0028,-0.027,-0.029,0,0,0.00034,0.00037,0.0059,0.08,0.1,0.0068,0.97,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 28890000,0.78,-0.0033,-0.0037,-0.63,2.2,1.5,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,5.8e-05,0.081,-0.021,-0.12,-0.17,-0.038,0.46,-0.0041,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.006,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.00011,0.00037,0.00044,1,1
292 28990000,0.77,-0.0027,-0.00054,-0.63,2.1,1.5,0.98,5.5,3.8,-3.7e+02,-0.001,-0.0058,-9.8e-05,0.033,-0.058,-0.12,-0.17,-0.038,0.46,-0.0026,-0.027,-0.028,0,0,0.00034,0.00037,0.0057,0.081,0.1,0.0069,1,1.2,0.034,3.6e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 28990000,0.78,-0.0029,-0.0038,-0.63,2.1,1.5,0.98,5.4,3.7,-3.7e+02,-0.00099,-0.0058,5.1e-05,0.08,-0.02,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.00011,0.00037,0.00044,1,1
293 29090000,0.78,-0.0022,-0.0007,-0.63,2.1,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.056,-0.12,-0.17,-0.038,0.46,-0.0025,-0.027,-0.028,0,0,0.00034,0.00037,0.0055,0.083,0.1,0.0069,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00037,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 29090000,0.78,-0.0024,-0.004,-0.63,2,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.086,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.00011,0.00037,0.00043,1,1
294 29190000,0.77,-0.0019,-0.00078,-0.63,2,1.5,0.97,5.9,4.1,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.055,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.028,0,0,0.00034,0.00037,0.0054,0.084,0.1,0.007,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1 29190000,0.78,-0.0022,-0.004,-0.63,2,1.5,0.97,5.9,4,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.082,0.088,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.0001,0.00037,0.00043,1,1
295 29290000,0.78,-0.00093,-0.0011,-0.63,1.9,1.4,1,6.1,4.2,-3.7e+02,-0.001,-0.0058,-0.00011,0.031,-0.053,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.028,0,0,0.00033,0.00037,0.0053,0.086,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00044,1,1 29290000,0.78,-0.0013,-0.0043,-0.63,1.9,1.4,0.99,6.1,4.2,-3.7e+02,-0.001,-0.0058,4.2e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0036,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,1.9e-05,0.00044,0.0001,0.00037,0.00043,1,1
296 29390000,0.78,0.00051,-0.0014,-0.63,1.9,1.4,1,6.3,4.4,-3.7e+02,-0.001,-0.0058,-0.00012,0.03,-0.051,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.0051,0.087,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29390000,0.78,7.3e-05,-0.0046,-0.63,1.9,1.4,1,6.2,4.3,-3.7e+02,-0.001,-0.0058,3.5e-05,0.079,-0.018,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,1.9e-05,0.00043,0.0001,0.00037,0.00043,1,1
297 29490000,0.78,0.0017,-0.0018,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,-0.00013,0.03,-0.05,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.005,0.089,0.11,0.0071,1.3,1.5,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29490000,0.78,0.0012,-0.005,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,1.9e-05,0.00043,0.0001,0.00037,0.00043,1,1
298 29590000,0.78,0.0028,-0.002,-0.63,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,-0.00013,0.028,-0.048,-0.12,-0.17,-0.038,0.46,-0.002,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.091,0.12,0.0071,1.3,1.6,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29590000,0.78,0.0023,-0.0052,-0.63,1.8,1.4,1,6.6,4.6,-3.7e+02,-0.001,-0.0057,3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.8e-05,0.00037,0.00043,1,1
299 29690000,0.78,0.0036,-0.0023,-0.63,1.8,1.4,0.99,6.8,4.8,-3.7e+02,-0.001,-0.0058,-0.00014,0.028,-0.045,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.093,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29690000,0.78,0.0029,-0.0055,-0.63,1.7,1.3,0.99,6.8,4.7,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.016,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.7e-05,0.00037,0.00043,1,1
300 29790000,0.78,0.0041,-0.0025,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0058,-0.00014,0.027,-0.042,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0048,0.095,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29790000,0.78,0.0034,-0.0056,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0057,2.2e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.027,0,0,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.6e-05,0.00037,0.00042,1,1
301 29890000,0.78,0.0045,-0.0026,-0.63,1.7,1.3,0.97,7.2,5.1,-3.7e+02,-0.001,-0.0058,-0.00015,0.026,-0.038,-0.12,-0.17,-0.038,0.46,-0.0017,-0.028,-0.028,0,0,0.00033,0.00038,0.0047,0.097,0.13,0.0072,1.5,1.8,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1 29890000,0.78,0.0035,-0.0057,-0.63,1.7,1.3,0.97,7.2,5,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.4e-05,0.00037,0.00042,1,1
302 29990000,0.78,0.0046,-0.0027,-0.63,1.7,1.3,0.95,7.3,5.2,-3.7e+02,-0.001,-0.0058,-0.00015,0.025,-0.035,-0.12,-0.17,-0.038,0.46,-0.0016,-0.028,-0.028,0,0,0.00033,0.00038,0.0046,0.099,0.13,0.0072,1.6,1.9,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1 29990000,0.78,0.0036,-0.0057,-0.63,1.6,1.3,0.95,7.3,5.1,-3.7e+02,-0.001,-0.0057,1.2e-05,0.077,-0.014,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.00011,0.00035,1.9e-05,0.00043,9.3e-05,0.00036,0.00042,1,1
303 30090000,0.78,0.0046,-0.0027,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0058,-0.00016,0.024,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0046,0.1,0.14,0.0072,1.6,2,0.034,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 30090000,0.78,0.0035,-0.0057,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0057,8.4e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00043,9.2e-05,0.00036,0.00042,1,1
304 30190000,0.78,0.0043,-0.0026,-0.63,1.6,1.3,0.93,7.7,5.5,-3.7e+02,-0.001,-0.0058,-0.00016,0.023,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0045,0.1,0.14,0.0072,1.7,2.1,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 30190000,0.78,0.0032,-0.0057,-0.63,1.6,1.3,0.93,7.6,5.4,-3.7e+02,-0.001,-0.0057,9.5e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00043,9.2e-05,0.00036,0.00042,1,1
305 30290000,0.78,0.0042,-0.0026,-0.63,1.5,1.3,0.92,7.8,5.6,-3.7e+02,-0.0011,-0.0058,-0.00016,0.022,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.2,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 30290000,0.78,0.003,-0.0056,-0.63,1.5,1.2,0.92,7.8,5.5,-3.7e+02,-0.001,-0.0057,6.5e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00043,9.1e-05,0.00036,0.00042,1,1
306 30390000,0.78,0.0041,-0.0026,-0.63,1.5,1.2,0.9,8,5.7,-3.7e+02,-0.0011,-0.0058,-0.00017,0.021,-0.028,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.3,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30390000,0.78,0.0028,-0.0056,-0.63,1.5,1.2,0.9,8,5.6,-3.7e+02,-0.0011,-0.0057,2.3e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,9e-05,0.00036,0.00042,1,1
307 30490000,0.78,0.0039,-0.0025,-0.63,1.5,1.2,0.89,8.2,5.8,-3.7e+02,-0.0011,-0.0058,-0.00017,0.02,-0.026,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.16,0.0072,1.9,2.4,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30490000,0.78,0.0025,-0.0055,-0.63,1.5,1.2,0.89,8.1,5.8,-3.7e+02,-0.0011,-0.0057,1.2e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,8.9e-05,0.00036,0.00042,1,1
308 30590000,0.78,0.0036,-0.0025,-0.63,1.5,1.2,0.85,8.3,6,-3.7e+02,-0.0011,-0.0058,-0.00017,0.019,-0.022,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0043,0.11,0.16,0.0072,2,2.5,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30590000,0.78,0.002,-0.0054,-0.63,1.4,1.2,0.85,8.3,5.9,-3.7e+02,-0.0011,-0.0057,-8.9e-07,0.076,-0.011,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,8.9e-05,0.00036,0.00042,1,1
309 30690000,0.78,0.0034,-0.0024,-0.63,1.4,1.2,0.84,8.5,6.1,-3.7e+02,-0.0011,-0.0058,-0.00017,0.018,-0.019,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00039,0.0043,0.11,0.17,0.0072,2.1,2.6,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30690000,0.78,0.0017,-0.0053,-0.63,1.4,1.2,0.84,8.4,6,-3.7e+02,-0.0011,-0.0057,-4.2e-06,0.075,-0.0099,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.0059,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,8.8e-05,0.00036,0.00042,1,1
310 30790000,0.78,0.0031,-0.0023,-0.63,1.4,1.2,0.83,8.6,6.2,-3.7e+02,-0.0011,-0.0058,-0.00017,0.017,-0.018,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.8,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30790000,0.78,0.0013,-0.0052,-0.63,1.4,1.2,0.84,8.6,6.1,-3.7e+02,-0.0011,-0.0057,-7.3e-06,0.075,-0.0096,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,1.8e-05,0.00042,8.8e-05,0.00036,0.00042,1,1
311 30890000,0.78,0.0027,-0.0022,-0.63,1.4,1.2,0.82,8.8,6.3,-3.7e+02,-0.0011,-0.0058,-0.00018,0.016,-0.016,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.9,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30890000,0.78,0.00088,-0.0051,-0.63,1.4,1.1,0.82,8.7,6.2,-3.7e+02,-0.0011,-0.0057,-1e-05,0.074,-0.0089,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00035,1.8e-05,0.00042,8.7e-05,0.00036,0.00042,1,1
312 30990000,0.78,0.0023,-0.0022,-0.63,1.3,1.2,0.81,8.9,6.4,-3.7e+02,-0.0011,-0.0058,-0.00018,0.015,-0.012,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.19,0.0072,2.3,3,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30990000,0.78,0.00029,-0.005,-0.63,1.3,1.1,0.82,8.9,6.3,-3.7e+02,-0.0011,-0.0057,-1.4e-05,0.074,-0.0081,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0052,9.9e-05,0.00035,1.8e-05,0.00042,8.7e-05,0.00036,0.00041,1,1
313 31090000,0.78,0.0019,-0.0021,-0.63,1.3,1.1,0.8,9,6.6,-3.7e+02,-0.0011,-0.0058,-0.00018,0.014,-0.0094,-0.12,-0.17,-0.038,0.46,-0.00097,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.12,0.2,0.0072,2.4,3.2,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 31090000,0.78,-0.00026,-0.0048,-0.63,1.3,1.1,0.81,9,6.5,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0074,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0048,0.0052,9.8e-05,0.00035,1.8e-05,0.00042,8.6e-05,0.00036,0.00041,1,1
314 31190000,0.78,0.0016,-0.002,-0.63,1.3,1.1,0.79,9.2,6.7,-3.7e+02,-0.0011,-0.0058,-0.00019,0.012,-0.0056,-0.12,-0.17,-0.038,0.46,-0.00088,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.2,0.0072,2.5,3.3,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 31190000,0.78,-0.00067,-0.0047,-0.63,1.3,1.1,0.8,9.1,6.6,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.074,-0.0066,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00034,1.8e-05,0.00042,8.6e-05,0.00036,0.00041,1,1
315 31290000,0.78,0.0012,-0.0018,-0.63,1.2,1.1,0.79,9.3,6.8,-3.7e+02,-0.0011,-0.0058,-0.00019,0.011,-0.0028,-0.12,-0.17,-0.038,0.46,-0.00081,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.21,0.0071,2.6,3.5,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 31290000,0.78,-0.0013,-0.0046,-0.63,1.2,1.1,0.8,9.3,6.7,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.073,-0.0059,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00034,1.8e-05,0.00042,8.5e-05,0.00036,0.00041,1,1
316 31390000,0.78,0.00059,-0.0016,-0.63,1.2,1.1,0.79,9.4,6.9,-3.7e+02,-0.0011,-0.0058,-0.00019,0.0099,0.0002,-0.12,-0.17,-0.038,0.46,-0.00074,-0.029,-0.027,0,0,0.0003,0.0004,0.0041,0.13,0.22,0.0071,2.7,3.6,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 31390000,0.78,-0.002,-0.0044,-0.63,1.2,1.1,0.8,9.4,6.8,-3.7e+02,-0.0011,-0.0057,-2.6e-05,0.073,-0.0053,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.027,0,0,0.00013,0.0001,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.6e-05,0.00034,1.8e-05,0.00042,8.5e-05,0.00036,0.00041,1,1
317 31490000,0.78,8.5e-05,-0.0015,-0.63,1.2,1.1,0.79,9.5,7,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0086,0.0029,-0.12,-0.17,-0.038,0.46,-0.00061,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.23,0.0071,2.8,3.8,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 31490000,0.78,-0.0026,-0.0042,-0.63,1.2,1,0.79,9.5,6.9,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.073,-0.0045,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,1.8e-05,0.00042,8.5e-05,0.00036,0.00041,1,1
318 31590000,0.78,-0.00021,-0.0014,-0.63,1.1,1.1,0.78,9.7,7.1,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0073,0.005,-0.11,-0.17,-0.038,0.46,-0.00056,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.0071,2.9,3.9,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.0001,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 31590000,0.78,-0.003,-0.0042,-0.63,1.1,1,0.79,9.6,7,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.072,-0.0038,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,1.8e-05,0.00041,8.4e-05,0.00036,0.00041,1,1
319 31690000,0.78,-0.00082,-0.0013,-0.63,1.1,1.1,0.79,9.8,7.2,-3.7e+02,-0.0011,-0.0058,-0.0002,0.006,0.0077,-0.11,-0.17,-0.038,0.46,-0.00049,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.007,3,4.1,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 31690000,0.78,-0.0037,-0.004,-0.63,1.1,1,0.8,9.8,7.1,-3.7e+02,-0.0011,-0.0057,-3.5e-05,0.072,-0.0032,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,1.8e-05,0.00041,8.4e-05,0.00036,0.00041,1,1
320 31790000,0.78,-0.0014,-0.0011,-0.63,1.1,1,0.79,9.9,7.3,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0047,0.011,-0.11,-0.17,-0.038,0.46,-0.00042,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.25,0.007,3.1,4.3,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 31790000,0.78,-0.0044,-0.0038,-0.63,1.1,0.99,0.8,9.9,7.2,-3.7e+02,-0.0011,-0.0057,-3.7e-05,0.071,-0.0023,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,1.8e-05,0.00041,8.4e-05,0.00036,0.00041,1,1
321 31890000,0.78,-0.002,-0.001,-0.63,1.1,1,0.78,10,7.4,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0033,0.014,-0.11,-0.17,-0.038,0.46,-0.00033,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.15,0.26,0.007,3.2,4.5,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 31890000,0.78,-0.0051,-0.0037,-0.63,1.1,0.97,0.79,10,7.3,-3.7e+02,-0.0011,-0.0057,-4.1e-05,0.071,-0.0014,-0.12,-0.17,-0.038,0.46,-0.0019,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,1.8e-05,0.00041,8.4e-05,0.00036,0.00041,1,1
322 31990000,0.78,-0.0024,-0.0009,-0.63,1,1,0.78,10,7.6,-3.7e+02,-0.0011,-0.0058,-0.00021,0.0018,0.017,-0.11,-0.17,-0.038,0.46,-0.00022,-0.029,-0.027,0,0,0.00029,0.00041,0.004,0.15,0.27,0.007,3.3,4.7,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 31990000,0.78,-0.0057,-0.0035,-0.63,1,0.96,0.79,10,7.4,-3.7e+02,-0.0011,-0.0057,-4.7e-05,0.07,-0.00053,-0.12,-0.17,-0.038,0.46,-0.0018,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.14,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.00041,1,1
323 32090000,0.78,-0.003,-0.0007,-0.63,1,0.99,0.79,10,7.7,-3.7e+02,-0.0012,-0.0058,-0.00021,0.00019,0.02,-0.11,-0.17,-0.038,0.46,-0.00011,-0.029,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.28,0.007,3.5,4.9,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 32090000,0.78,-0.0064,-0.0033,-0.63,1,0.94,0.8,10,7.5,-3.7e+02,-0.0012,-0.0057,-5.1e-05,0.07,0.00016,-0.11,-0.17,-0.038,0.46,-0.0018,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.2e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.0004,1,1
324 32190000,0.78,-0.0038,-0.00051,-0.63,0.97,0.98,0.78,10,7.8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0015,0.024,-0.11,-0.18,-0.038,0.46,3.2e-05,-0.03,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.29,0.0069,3.6,5.1,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.9e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 32190000,0.78,-0.0074,-0.0031,-0.63,0.97,0.92,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-6e-05,0.069,0.0011,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.0004,1,1
325 32290000,0.78,-0.0044,-0.00042,-0.63,0.94,0.96,0.78,11,7.9,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0032,0.028,-0.11,-0.18,-0.038,0.46,0.00014,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.3,0.0069,3.7,5.4,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.8e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 32290000,0.78,-0.0081,-0.003,-0.63,0.94,0.9,0.79,10,7.7,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.069,0.0021,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.0004,1,1
326 32390000,0.78,-0.0049,-0.00032,-0.63,0.91,0.94,0.78,11,8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0041,0.03,-0.11,-0.18,-0.038,0.46,0.00019,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.31,0.0069,3.8,5.6,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 32390000,0.78,-0.0087,-0.0029,-0.63,0.91,0.88,0.79,11,7.8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.068,0.0027,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9e-05,0.00034,1.8e-05,0.00041,8.3e-05,0.00036,0.0004,1,1
327 32490000,0.78,-0.0051,-0.00027,-0.63,0.88,0.92,0.78,11,8.1,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0056,0.032,-0.11,-0.18,-0.038,0.46,0.00028,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.16,0.32,0.0068,4,5.8,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 32490000,0.78,-0.009,-0.0028,-0.62,0.88,0.86,0.8,11,7.9,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0035,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,9e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.0004,1,1
328 32590000,0.78,-0.0053,-0.00021,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0064,0.033,-0.11,-0.18,-0.038,0.46,0.00034,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.56,0.25,0.25,0.037,3e-07,5.1e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 32590000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.1e-05,0.067,0.0038,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.0004,1,1
329 32690000,0.78,-0.0053,-0.00025,-0.63,-1.6,-0.85,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0073,0.035,-0.11,-0.18,-0.038,0.46,0.00041,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.55,0.26,0.26,0.048,2.9e-07,5.1e-07,3.2e-06,0.029,0.023,9.5e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 32690000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0044,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.0004,1,1
330 32790000,0.78,-0.0052,-0.00026,-0.63,-1.5,-0.83,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0081,0.036,-0.11,-0.18,-0.038,0.46,0.00047,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.27,0.26,0.26,0.049,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 32790000,0.78,-0.0093,-0.0028,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0048,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00014,0.0001,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.0004,1,1
331 32890000,0.78,-0.005,-0.00039,-0.63,-1.6,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0089,0.038,-0.11,-0.18,-0.038,0.46,0.00057,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.26,0.27,0.27,0.059,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 32890000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.5e-05,0.066,0.0053,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.00039,1,1
332 32990000,0.78,-0.0049,-0.0005,-0.63,-1.5,-0.84,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0098,0.04,-0.11,-0.18,-0.038,0.46,0.00059,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.085,0.17,0.27,0.27,0.057,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 32990000,0.78,-0.0092,-0.003,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.9e-05,0.065,0.0058,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.00039,1,1
333 33090000,0.78,-0.005,-0.00048,-0.63,-1.6,-0.86,0.58,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.038,0.46,0.00061,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.086,0.16,0.28,0.28,0.065,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 33090000,0.78,-0.0092,-0.003,-0.62,-1.6,-0.86,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.2e-05,0.00036,0.00039,1,1
334 33190000,0.78,-0.0036,-0.0037,-0.62,-1.5,-0.84,0.53,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.01,0.041,-0.11,-0.18,-0.038,0.46,0.0006,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.063,0.065,0.11,0.28,0.28,0.062,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 33190000,0.78,-0.0079,-0.0062,-0.62,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0061,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.1e-05,0.00036,0.00039,1,1
335 33290000,0.82,-0.0015,-0.016,-0.57,-1.5,-0.86,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.039,0.46,0.00058,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.064,0.066,0.11,0.29,0.29,0.067,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00035,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 33290000,0.83,-0.0058,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.8e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0012,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,1.8e-05,0.0004,8.1e-05,0.00035,0.00039,1,1
336 33390000,0.89,-0.0018,-0.013,-0.46,-1.5,-0.85,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.015,0.038,-0.11,-0.18,-0.039,0.46,0.0012,-0.028,-0.025,0,0,0.00028,0.0004,0.0037,0.051,0.053,0.083,0.29,0.29,0.065,2.9e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00033,1.7e-05,0.00041,0.00015,0.00035,0.00041,1,1 33390000,0.89,-0.0065,-0.015,-0.45,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.064,0.0057,-0.11,-0.18,-0.039,0.46,-0.00088,-0.027,-0.024,0,0,0.00015,0.0001,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00031,1.7e-05,0.0004,7.9e-05,0.00032,0.00039,1,1
337 33490000,0.95,-0.00026,-0.0052,-0.31,-1.5,-0.86,0.72,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.018,0.037,-0.11,-0.18,-0.04,0.46,0.0017,-0.02,-0.025,0,0,0.00031,0.00036,0.0034,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00025,1.4e-05,0.00041,0.00013,0.00026,0.00041,1,1 33490000,0.95,-0.0051,-0.0068,-0.3,-1.5,-0.87,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.6e-05,0.064,0.0057,-0.11,-0.18,-0.04,0.46,-0.00039,-0.02,-0.024,0,0,0.00015,0.0001,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00023,1.3e-05,0.00039,7.1e-05,0.00024,0.00039,1,1
338 33590000,0.99,-0.003,0.0015,-0.14,-1.5,-0.84,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.0002,-0.018,0.037,-0.11,-0.19,-0.042,0.46,0.0025,-0.013,-0.026,0,0,0.00035,0.00031,0.003,0.044,0.047,0.061,0.3,0.3,0.065,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00017,1e-05,0.00041,9.5e-05,0.00016,0.0004,1,1 33590000,0.99,-0.0082,-3e-05,-0.14,-1.5,-0.85,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.5e-05,0.064,0.0057,-0.11,-0.19,-0.042,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00015,9e-06,0.00039,5.9e-05,0.00015,0.00039,1,1
339 33690000,1,-0.0064,0.005,0.024,-1.6,-0.86,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.018,0.037,-0.11,-0.19,-0.043,0.46,0.0018,-0.0093,-0.026,0,0,0.00037,0.00028,0.0026,0.045,0.05,0.056,0.31,0.31,0.068,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00013,7.8e-06,0.0004,6.9e-05,0.0001,0.0004,1,1 33690000,1,-0.012,0.0042,0.031,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2e-05,0.064,0.0057,-0.11,-0.19,-0.043,0.46,0.00019,-0.0091,-0.025,0,0,0.00015,0.0001,0.0027,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0047,0.0051,8.8e-05,0.0001,6.7e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1
340 33790000,0.98,-0.0073,0.0069,0.19,-1.6,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.002,-0.0068,-0.027,0,0,0.00037,0.00026,0.0023,0.04,0.045,0.047,0.31,0.31,0.064,2.8e-07,4.9e-07,3.1e-06,0.028,0.022,9.3e-05,9.7e-05,6.4e-06,0.0004,4.8e-05,6.3e-05,0.0004,1,1 33790000,0.98,-0.013,0.0066,0.2,-1.6,-0.89,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.6e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00053,-0.0066,-0.025,0,0,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,6.9e-05,5.1e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1
341 33890000,0.94,-0.0075,0.0082,0.35,-1.7,-0.9,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.0019,-0.0054,-0.027,0,0,0.00036,0.00026,0.0022,0.044,0.051,0.043,0.32,0.32,0.065,2.8e-07,4.9e-07,3e-06,0.028,0.022,9.3e-05,8.1e-05,5.6e-06,0.0004,3.4e-05,4.2e-05,0.0004,1,1 33890000,0.93,-0.013,0.0087,0.36,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.9e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00074,-0.0053,-0.025,0,0,0.00015,9.9e-05,0.0019,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,5e-05,4.2e-06,0.00038,2.6e-05,4.2e-05,0.00038,1,1
342 33990000,0.87,-0.0095,0.0057,0.49,-1.7,-0.91,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.015,0.036,-0.11,-0.2,-0.044,0.46,0.0017,-0.004,-0.027,0,0,0.00032,0.00027,0.002,0.041,0.049,0.036,0.32,0.32,0.062,2.8e-07,4.8e-07,3e-06,0.028,0.022,9.3e-05,7.1e-05,5.1e-06,0.0004,2.6e-05,3e-05,0.0004,1,1 33990000,0.87,-0.015,0.0073,0.5,-1.7,-0.97,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0055,-0.11,-0.2,-0.044,0.46,0.00052,-0.0039,-0.025,0,0,0.00014,9.7e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,4e-05,3.7e-06,0.00038,2.1e-05,3e-05,0.00038,1,1
343 34090000,0.81,-0.011,0.0044,0.59,-1.7,-0.97,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.01,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0034,-0.027,0,0,0.0003,0.00028,0.002,0.047,0.057,0.034,0.33,0.33,0.063,2.8e-07,4.9e-07,3e-06,0.027,0.022,9.3e-05,6.6e-05,4.9e-06,0.0004,2.1e-05,2.4e-05,0.0004,1,1 34090000,0.8,-0.016,0.0065,0.6,-1.7,-1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.065,0.0049,-0.11,-0.2,-0.044,0.46,0.00019,-0.0032,-0.025,0,0,0.00014,9.7e-05,0.0015,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3.4e-05,3.4e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1
344 34190000,0.76,-0.0081,0.0029,0.65,-1.7,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.039,0.052,-0.11,-0.2,-0.044,0.46,0.0012,-0.0028,-0.027,0,0,0.00026,0.00028,0.0018,0.045,0.054,0.029,0.33,0.33,0.06,2.8e-07,4.7e-07,3e-06,0.026,0.021,9.3e-05,6e-05,4.6e-06,0.0004,1.7e-05,1.9e-05,0.0004,1,1 34190000,0.75,-0.014,0.0072,0.66,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0047,-0.11,-0.2,-0.044,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.7e-05,0.0014,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3e-05,3.2e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1
345 34290000,0.72,-0.0052,0.0041,0.69,-1.7,-1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.038,0.051,-0.11,-0.2,-0.044,0.46,0.0011,-0.0024,-0.027,0,0,0.00025,0.00029,0.0018,0.053,0.064,0.027,0.34,0.34,0.06,2.8e-07,4.7e-07,3e-06,0.025,0.021,9.3e-05,5.7e-05,4.5e-06,0.0004,1.4e-05,1.6e-05,0.0004,1,1 34290000,0.71,-0.011,0.0086,0.7,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0044,-0.11,-0.2,-0.044,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.6e-05,0.0013,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,2.7e-05,3.1e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1
346 34390000,0.7,-0.0024,0.0054,0.71,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.036,0.05,-0.11,-0.2,-0.044,0.46,0.00092,-0.0022,-0.027,0,0,0.00025,0.00029,0.0018,0.062,0.075,0.025,0.35,0.35,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.5e-05,4.4e-06,0.0004,1.3e-05,1.4e-05,0.0004,1,1 34390000,0.69,-0.0076,0.01,0.72,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,9.2e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0013,0.047,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.8e-06,0.0047,0.005,8.8e-05,2.5e-05,3e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1
347 34490000,0.69,-0.00036,0.0066,0.73,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.049,-0.11,-0.2,-0.044,0.46,0.0008,-0.0021,-0.027,0,0,0.00024,0.0003,0.0017,0.073,0.088,0.023,0.36,0.36,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.4e-05,4.3e-06,0.0004,1.1e-05,1.2e-05,0.0004,1,1 34490000,0.67,-0.0054,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,5e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0012,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.3e-05,2.9e-06,0.00038,9.8e-06,1.2e-05,0.00038,1,1
348 34590000,0.68,0.00092,0.0074,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.05,-0.11,-0.2,-0.044,0.46,0.00064,-0.002,-0.027,0,0,0.00024,0.0003,0.0017,0.085,0.1,0.021,0.38,0.38,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.2e-05,4.3e-06,0.0004,1e-05,1.1e-05,0.0004,1,1 34590000,0.67,-0.004,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0039,-0.11,-0.2,-0.044,0.46,-4.6e-05,-0.0019,-0.025,0,0,0.00014,9.5e-05,0.0012,0.056,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.2e-05,2.9e-06,0.00038,8.9e-06,1.1e-05,0.00038,1,1
349 34690000,0.67,0.0017,0.0079,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.034,0.049,-0.11,-0.2,-0.044,0.46,0.00068,-0.0018,-0.027,0,0,0.00024,0.0003,0.0017,0.098,0.12,0.019,0.39,0.4,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,9.6e-06,1e-05,0.0004,1,1 34690000,0.66,-0.0032,0.013,0.75,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0038,-0.11,-0.2,-0.044,0.46,1.6e-05,-0.0016,-0.025,0,0,0.00014,9.5e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.1e-05,2.8e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1
350 34790000,0.67,0.0024,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.036,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00024,0.0003,0.0017,0.11,0.14,0.018,0.41,0.42,0.058,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,8.9e-06,9.2e-06,0.0004,1,1 34790000,0.66,-0.0027,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0038,-0.11,-0.2,-0.044,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0012,0.067,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,2.8e-06,0.00038,7.7e-06,9.1e-06,0.00038,1,1
351 34890000,0.66,0.0025,0.0082,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00069,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.13,0.16,0.017,0.43,0.44,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5e-05,4.1e-06,0.0004,8.4e-06,8.5e-06,0.0004,1,1 34890000,0.65,-0.0025,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0036,-0.11,-0.2,-0.044,0.46,8.7e-05,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0011,0.074,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,2.7e-06,0.00038,7.2e-06,8.4e-06,0.00038,1,1
352 34990000,0.66,-0.00086,0.016,0.75,-3,-2.2,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00024,0.00031,0.0017,0.16,0.22,0.016,0.46,0.47,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.9e-06,8e-06,0.0004,1,1 34990000,0.65,-0.006,0.02,0.76,-3.1,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0002,-0.0016,-0.025,0,0,0.00014,9.3e-05,0.0011,0.09,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,2.7e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1
353 35090000,0.66,-0.00092,0.016,0.75,-3.1,-2.3,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.18,0.25,0.015,0.49,0.51,0.055,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.5e-06,7.5e-06,0.0004,1,1 35090000,0.65,-0.006,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00021,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0011,0.098,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,2.7e-06,0.00038,6.5e-06,7.4e-06,0.00038,1,1
354 35190000,0.66,-0.001,0.015,0.75,-3.1,-2.3,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.2,0.28,0.014,0.52,0.55,0.054,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,7.2e-06,7.1e-06,0.0004,1,1 35190000,0.65,-0.0061,0.02,0.76,-3.2,-2.7,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00025,-0.0015,-0.025,0,0,0.00013,9.3e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,2.7e-06,0.00038,6.2e-06,7e-06,0.00038,1,1
355 35290000,0.66,-0.0012,0.015,0.75,-3.2,-2.3,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00084,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.23,0.31,0.013,0.56,0.6,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,6.9e-06,6.7e-06,0.0004,1,1 35290000,0.65,-0.0063,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,2.7e-06,0.00038,5.9e-06,6.6e-06,0.00037,1,1
356 35390000,0.66,-0.0011,0.015,0.75,-3.2,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00091,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.25,0.34,0.013,0.61,0.66,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.6e-06,6.4e-06,0.0004,1,1 35390000,0.65,-0.0063,0.02,0.76,-3.3,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.12,0.18,0.012,0.57,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,2.6e-06,0.00038,5.7e-06,6.3e-06,0.00037,1,1
357 35490000,0.66,-0.0012,0.016,0.75,-3.2,-2.4,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.28,0.37,0.012,0.66,0.73,0.051,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.4e-06,6.2e-06,0.0004,1,1 35490000,0.65,-0.0063,0.02,0.76,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00044,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.13,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5.5e-06,6e-06,0.00037,1,1
358 35590000,0.66,-0.0012,0.016,0.75,-3.3,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00092,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.31,0.4,0.011,0.72,0.81,0.05,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,4e-06,0.0004,6.2e-06,5.9e-06,0.0004,1,1 35590000,0.65,-0.0064,0.02,0.76,-3.3,-3,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00041,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.14,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1
359 35690000,0.66,-0.0011,0.016,0.75,-3.3,-2.5,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.046,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.33,0.44,0.011,0.79,0.9,0.049,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.1e-06,5.7e-06,0.0004,1,1 35690000,0.65,-0.0063,0.02,0.76,-3.4,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00047,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5.2e-06,5.6e-06,0.00037,1,1
360 35790000,0.66,-0.0012,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.36,0.48,0.01,0.86,1,0.048,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,5.9e-06,5.5e-06,0.0004,1,1 35790000,0.65,-0.0064,0.02,0.76,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.0011,0.17,0.23,0.01,0.73,0.84,0.049,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1
361 35890000,0.66,-0.0013,0.016,0.75,-3.4,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.4,0.52,0.01,0.95,1.1,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,5.7e-06,5.3e-06,0.0004,1,1 35890000,0.65,-0.0065,0.02,0.76,-3.4,-3.2,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.001,0.18,0.25,0.0096,0.78,0.9,0.048,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,2.6e-06,0.00038,5e-06,5.2e-06,0.00037,1,1
362 35990000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.00094,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.43,0.56,0.0097,1,1.2,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.6e-06,5.1e-06,0.0004,1,1 35990000,0.65,-0.0065,0.02,0.76,-3.5,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00046,-0.0015,-0.025,0,0,0.00013,9e-05,0.001,0.19,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.6e-05,2.6e-06,0.00038,4.8e-06,5e-06,0.00037,1,1
363 36090000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.044,-0.11,-0.2,-0.044,0.46,0.00096,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.46,0.6,0.0093,1.2,1.4,0.046,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.5e-06,5e-06,0.0004,1,1 36090000,0.65,-0.0065,0.02,0.76,-3.5,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.001,0.2,0.28,0.0089,0.9,1.1,0.046,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.6e-05,2.6e-06,0.00038,4.7e-06,4.8e-06,0.00037,1,1
364 36190000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.034,0.043,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.5,0.65,0.009,1.3,1.5,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.4e-06,4.8e-06,0.0004,1,1 36190000,0.65,-0.0066,0.02,0.76,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0037,-0.11,-0.2,-0.044,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.001,0.22,0.3,0.0086,0.96,1.1,0.045,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,8.9e-05,1.6e-05,2.6e-06,0.00038,4.6e-06,4.7e-06,0.00037,1,1
365 36290000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.53,0.69,0.0088,1.4,1.7,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.3e-06,4.7e-06,0.0004,1,1 36290000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.001,0.23,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,8.9e-05,1.6e-05,2.5e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1
366 36390000,0.66,-0.0013,0.016,0.75,-3.5,-2.9,-0.097,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.57,0.74,0.0086,1.6,1.9,0.044,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.2e-06,4.6e-06,0.0004,1,1 36390000,0.65,-0.0066,0.02,0.76,-3.6,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00057,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.001,0.24,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,8.9e-05,1.6e-05,2.5e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1
367 36490000,0.66,-0.0014,0.016,0.75,-3.6,-2.9,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.61,0.79,0.0083,1.7,2.1,0.043,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.0004,5.2e-06,4.5e-06,0.0004,1,1 36490000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.058,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00054,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.001,0.26,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.6e-05,2.5e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1
368 36590000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.08,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.032,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.65,0.84,0.0082,1.9,2.4,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5.1e-06,4.4e-06,0.0004,1,1 36590000,0.65,-0.0066,0.02,0.76,-3.6,-3.8,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.001,0.27,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.3e-06,4.2e-06,0.00037,1,1
369 36690000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.031,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.69,0.89,0.0081,2.1,2.6,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.3e-06,0.0004,1,1 36690000,0.65,-0.0067,0.02,0.76,-3.7,-3.8,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.001,0.29,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1
370 36790000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00024,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.74,0.94,0.0079,2.3,2.9,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.2e-06,0.0004,1,1 36790000,0.65,-0.0067,0.021,0.76,-3.7,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0036,-0.11,-0.2,-0.044,0.46,0.00064,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.001,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.2e-06,4e-06,0.00037,1,1
371 36890000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.78,1,0.0078,2.6,3.2,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4.1e-06,0.0004,1,1 36890000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00067,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.001,0.32,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1
372 36990000,0.66,-0.0014,0.016,0.75,-3.7,-3.2,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.82,1.1,0.0077,2.8,3.6,0.04,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4e-06,0.0004,1,1 36990000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0039,-0.11,-0.2,-0.044,0.46,0.00068,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.001,0.34,0.45,0.0071,1.7,2.2,0.04,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.1e-06,3.9e-06,0.00037,1,1
373 37090000,0.66,-0.0014,0.016,0.75,-3.8,-3.2,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.87,1.1,0.0076,3.1,4,0.04,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1 37090000,0.65,-0.0067,0.021,0.76,-3.8,-4.1,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.9e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.001,0.36,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1
374 37190000,0.66,-0.0014,0.016,0.75,-3.8,-3.3,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.92,1.2,0.0076,3.4,4.4,0.039,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1 37190000,0.65,-0.0067,0.021,0.76,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00068,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.37,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1
375 37290000,0.66,-0.0015,0.017,0.75,-3.8,-3.3,-0.026,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.97,1.2,0.0075,3.7,4.8,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.8e-06,0.0004,1,1 37290000,0.65,-0.0068,0.021,0.76,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.5e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.39,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4e-06,3.7e-06,0.00037,1,1
376 37390000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.029,0.036,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,1,1.3,0.0075,4.1,5.3,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1 37390000,0.65,-0.0067,0.021,0.76,-3.9,-4.3,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00071,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.41,0.54,0.0067,2.3,3,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4e-06,3.6e-06,0.00037,1,1
377 37490000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.029,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.4,5.8,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1 37490000,0.65,-0.0067,0.021,0.76,-3.9,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.6e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.43,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,2.5e-06,0.00038,4e-06,3.5e-06,0.00037,1,1
378 37590000,0.66,-0.0014,0.017,0.75,-3.9,-3.5,-0.0032,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.028,0.034,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.9,6.3,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1 37590000,0.65,-0.0067,0.021,0.76,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.2e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.45,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.4e-05,2.5e-06,0.00038,3.9e-06,3.5e-06,0.00037,1,1
379 37690000,0.66,-0.0015,0.017,0.75,-4,-3.5,0.0061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.033,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.2,1.5,0.0074,5.3,6.9,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.6e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1 37690000,0.65,-0.0068,0.021,0.76,-3.9,-4.6,0.043,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.7e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.47,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.4e-05,2.5e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1
380 37790000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.2,1.5,0.0074,5.8,7.5,0.037,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.5e-06,0.0004,1,1 37790000,0.65,-0.0069,0.021,0.76,-4,-4.6,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.00099,0.49,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,2.5e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1
381 37890000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.022,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.6,0.0074,6.3,8.2,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 37890000,0.65,-0.0069,0.021,0.76,-4,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.00099,0.51,0.65,0.0065,3.3,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,2.4e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1
382 37990000,0.66,-0.0016,0.017,0.75,-4.1,-3.7,0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.026,0.031,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.7,0.0074,6.8,8.9,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 37990000,0.65,-0.0069,0.021,0.76,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.00099,0.53,0.67,0.0065,3.5,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.3e-06,0.00037,1,1
383 38090000,0.66,-0.0017,0.017,0.75,-4.1,-3.8,0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.7,0.0074,7.4,9.6,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.5e-06,3.4e-06,0.0004,1,1 38090000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.078,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.00099,0.55,0.7,0.0065,3.8,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1
384 38190000,0.66,-0.0016,0.017,0.75,-4.2,-3.8,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.8,0.0074,8,10,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1 38190000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.00098,0.57,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1
385 38290000,0.66,-0.0017,0.017,0.75,-4.2,-3.9,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,8.6,11,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1 38290000,0.65,-0.0069,0.021,0.76,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.00098,0.6,0.75,0.0065,4.3,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1
386 38390000,0.66,-0.0016,0.017,0.75,-4.2,-3.9,0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,9.3,12,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 38390000,0.65,-0.0069,0.021,0.76,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00098,0.62,0.77,0.0065,4.6,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1
387 38490000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.07,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,10,13,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 38490000,0.65,-0.0069,0.021,0.76,-4.2,-5.1,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00098,0.64,0.8,0.0065,4.9,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3e-06,0.00037,1,1
388 38590000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.076,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.1,0.0075,11,14,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 38590000,0.65,-0.0068,0.021,0.76,-4.2,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00097,0.67,0.82,0.0065,5.3,6.9,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.8e-06,3e-06,0.00037,1,1
389 38690000,0.66,-0.0016,0.017,0.75,-4.3,-4.1,0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.2,0.0075,12,15,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1 38690000,0.65,-0.0068,0.021,0.76,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.067,0.0045,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00097,0.69,0.85,0.0065,5.6,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.7e-06,3e-06,0.00037,1,1
390 38790000,0.66,-0.0016,0.017,0.75,-4.4,-4.1,0.089,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00026,0.0016,1.8,2.3,0.0075,12,16,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1 38790000,0.65,-0.0068,0.021,0.76,-4.3,-5.3,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.00097,0.71,0.88,0.0065,6,7.8,0.035,3.1e-07,4.3e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.7e-06,2.9e-06,0.00037,1,1
391 38890000,0.66,-0.0017,0.017,0.75,-4.4,-4.1,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.9,2.3,0.0075,13,17,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1 38890000,0.65,-0.0069,0.021,0.76,-4.3,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0044,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.3e-05,0.00097,0.73,0.89,0.0065,6.4,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,2.4e-06,0.00038,3.7e-06,2.9e-06,0.00037,1,1

View File

@ -1,351 +1,351 @@
Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00094,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00054,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,5e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00066,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.9e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.7e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00056,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00049,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.3e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.3e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-7.7e-08,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3.3e-08,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00039,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-7e-09,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.1e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00035,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00039,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-7.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-7.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.3e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2490000,1,-0.011,-0.014,0.00047,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.3e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-1.9e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-1.8e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2790000,1,-0.01,-0.013,0.00037,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2990000,1,-0.01,-0.013,0.00031,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-2.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-2.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3190000,1,-0.01,-0.013,0.00056,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.2e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00021,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,3.4e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.2e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,3.4e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,2.9e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3490000,1,-0.0097,-0.013,0.00058,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,2.9e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.007,0.0071,0.00018,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,2.5e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3690000,1,-0.0095,-0.013,0.00052,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,2.5e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.3e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00017,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3890000,1,-0.0094,-0.013,0.00063,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,2.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4090000,1,-0.0093,-0.012,0.00076,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-4.8e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1.9e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-4.8e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00018,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1.9e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4290000,1,-0.0095,-0.012,0.00074,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.3e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,1.7e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,1.7e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4490000,1,-0.0094,-0.012,0.00076,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-5.7e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,1.5e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-5.7e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00016,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,1.5e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4690000,1,-0.0094,-0.012,0.00076,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.1e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4790000,1,-0.0093,-0.012,0.00086,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.1e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4890000,1,-0.0092,-0.012,0.0009,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-6.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-6.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5090000,1,-0.0091,-0.011,0.00096,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-6.8e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-6.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.3e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,9.3e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00013,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.4e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5590000,1,-0.0088,-0.012,0.00099,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.4e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5690000,1,-0.0089,-0.011,0.00089,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.6e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5790000,1,-0.0088,-0.011,0.00085,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.6e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5890000,1,-0.0088,-0.011,0.00088,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5990000,1,-0.0088,-0.012,0.00086,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6090000,1,-0.0088,-0.011,0.00067,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6190000,1,-0.0089,-0.011,0.00068,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6290000,1,-0.0089,-0.011,0.00071,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6390000,1,-0.0089,-0.011,0.00072,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6590000,1,-0.009,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6690000,1,-0.0089,-0.011,0.0005,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6790000,1,-0.009,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6890000,1,-0.0088,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6990000,-0.29,0.024,-0.0065,0.96,-0.0055,0.0091,-0.037,0.0023,0.0053,-0.055,-0.0016,-0.0056,-8.7e-05,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0012,0.0012,0.072,0.16,0.16,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1
7090000,-0.28,0.025,-0.0064,0.96,-0.026,-0.00083,-0.037,0.0022,0.0052,-0.056,-0.0015,-0.0055,-8.7e-05,0,0,-0.13,-0.099,-0.021,0.51,0.075,-0.029,-0.065,0,0,0.0012,0.0012,0.058,0.16,0.16,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00099,0.0013,1,1
7190000,-0.28,0.026,-0.0064,0.96,-0.047,-0.0082,-0.036,0.00063,0.0038,-0.058,-0.0015,-0.0055,-8.6e-05,3.9e-05,-1e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.054,0.17,0.17,0.029,0.16,0.16,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.00094,0.0013,1,1
7290000,-0.28,0.026,-0.0064,0.96,-0.07,-0.017,-0.033,-0.0034,0.0023,-0.054,-0.0015,-0.0054,-8.5e-05,0.00011,-5e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.053,0.18,0.18,0.028,0.19,0.19,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00093,0.0013,1,1
7390000,-0.28,0.026,-0.0062,0.96,-0.091,-0.024,-0.031,-0.0098,-8.5e-05,-0.052,-0.0015,-0.0054,-8.4e-05,0.00016,-4e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.052,0.19,0.19,0.027,0.22,0.22,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00092,0.0013,1,1
7490000,-0.28,0.026,-0.0062,0.96,-0.11,-0.032,-0.025,-0.015,-0.0034,-0.046,-0.0015,-0.0053,-8.1e-05,0.00033,7.2e-07,-0.13,-0.1,-0.022,0.5,0.077,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.2,0.2,0.026,0.26,0.26,0.063,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00091,0.0013,1,1
7590000,-0.28,0.026,-0.0063,0.96,-0.13,-0.041,-0.021,-0.024,-0.0083,-0.04,-0.0015,-0.0052,-8e-05,0.00045,-2.7e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.22,0.21,0.025,0.3,0.3,0.062,6.6e-05,6.5e-05,4.6e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00091,0.0013,1,1
7690000,-0.28,0.026,-0.0063,0.96,-0.16,-0.051,-0.02,-0.034,-0.015,-0.036,-0.0014,-0.0051,-7.9e-05,0.00056,-6.8e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.23,0.23,0.025,0.34,0.34,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.0009,0.0013,1,1
7790000,-0.28,0.026,-0.0062,0.96,-0.18,-0.061,-0.022,-0.041,-0.025,-0.041,-0.0014,-0.005,-7.8e-05,0.00088,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.26,0.25,0.024,0.39,0.39,0.061,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.0009,0.0013,1,1
7890000,-0.28,0.026,-0.0062,0.96,-0.2,-0.071,-0.022,-0.057,-0.033,-0.044,-0.0013,-0.0049,-7.7e-05,0.00099,-0.00028,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.28,0.28,0.023,0.45,0.45,0.06,6.4e-05,6.4e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.0009,0.0013,1,1
7990000,-0.28,0.026,-0.0061,0.96,-0.22,-0.078,-0.018,-0.08,-0.039,-0.04,-0.0013,-0.0049,-7.7e-05,0.00089,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.3,0.3,0.022,0.51,0.51,0.059,6.3e-05,6.3e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0013,0.0009,0.0013,1,1
8090000,-0.28,0.026,-0.006,0.96,-0.25,-0.09,-0.019,-0.1,-0.053,-0.043,-0.0013,-0.0049,-8e-05,0.00093,-0.00038,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.33,0.33,0.022,0.57,0.57,0.059,6.2e-05,6.2e-05,4.6e-06,0.04,0.04,0.0014,0.0013,8.9e-05,0.0013,0.0013,0.0009,0.0013,1,1
8190000,-0.28,0.026,-0.0061,0.96,-0.27,-0.1,-0.014,-0.12,-0.069,-0.036,-0.0012,-0.0048,-8.2e-05,0.00096,-0.0005,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.36,0.36,0.021,0.64,0.64,0.058,6.1e-05,6.1e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.7e-05,0.0013,0.0013,0.0009,0.0013,1,1
8290000,-0.28,0.026,-0.0061,0.96,-0.3,-0.11,-0.013,-0.16,-0.077,-0.036,-0.0012,-0.005,-8.4e-05,0.0007,-0.00042,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.4,0.39,0.02,0.72,0.72,0.057,6e-05,6e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.5e-05,0.0013,0.0013,0.0009,0.0013,1,1
8390000,-0.28,0.026,-0.0061,0.96,-0.33,-0.12,-0.011,-0.2,-0.089,-0.034,-0.0012,-0.005,-8.5e-05,0.00063,-0.00041,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.43,0.43,0.02,0.81,0.8,0.057,5.9e-05,5.9e-05,4.6e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
8490000,-0.28,0.026,-0.0059,0.96,-0.35,-0.12,-0.012,-0.23,-0.094,-0.039,-0.0013,-0.005,-8.2e-05,0.00062,-0.00029,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.47,0.46,0.019,0.9,0.9,0.056,5.8e-05,5.7e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
8590000,-0.28,0.027,-0.0059,0.96,-0.38,-0.14,-0.0073,-0.26,-0.12,-0.034,-0.0012,-0.0049,-8.2e-05,0.00079,-0.00042,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.51,0.51,0.019,1,1,0.055,5.6e-05,5.5e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
8690000,-0.28,0.027,-0.0059,0.96,-0.4,-0.14,-0.0089,-0.3,-0.13,-0.035,-0.0012,-0.0049,-8.2e-05,0.00071,-0.00035,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.56,0.55,0.018,1.1,1.1,0.055,5.5e-05,5.4e-05,4.6e-06,0.04,0.04,0.001,0.0013,8e-05,0.0013,0.0013,0.00089,0.0013,1,1
8790000,-0.28,0.027,-0.0059,0.96,-0.43,-0.15,-0.0084,-0.35,-0.14,-0.032,-0.0012,-0.005,-8.5e-05,0.00052,-0.0004,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.61,0.6,0.018,1.2,1.2,0.055,5.3e-05,5.2e-05,4.6e-06,0.04,0.04,0.00099,0.0013,7.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
8890000,-0.28,0.027,-0.0059,0.96,-0.46,-0.16,-0.0039,-0.38,-0.16,-0.026,-0.0012,-0.0049,-8.1e-05,0.00064,-0.00031,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.66,0.65,0.017,1.4,1.4,0.054,5.1e-05,5e-05,4.5e-06,0.04,0.04,0.00095,0.0013,7.8e-05,0.0013,0.0013,0.00089,0.0013,1,1
8990000,-0.28,0.027,-0.0058,0.96,-0.47,-0.17,-0.0028,-0.41,-0.17,-0.029,-0.0013,-0.0047,-7.5e-05,0.001,-0.0003,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.72,0.7,0.017,1.5,1.5,0.054,4.9e-05,4.8e-05,4.5e-06,0.04,0.04,0.00091,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1
9090000,-0.28,0.027,-0.0056,0.96,-0.5,-0.18,-0.0038,-0.47,-0.17,-0.029,-0.0014,-0.0048,-7.2e-05,0.00081,-2.1e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.77,0.76,0.016,1.7,1.7,0.053,4.7e-05,4.6e-05,4.5e-06,0.04,0.04,0.00087,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1
9190000,-0.28,0.027,-0.0055,0.96,-0.53,-0.18,-0.0029,-0.52,-0.18,-0.029,-0.0015,-0.0048,-6.9e-05,0.0008,0.00012,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.84,0.82,0.016,1.9,1.9,0.052,4.5e-05,4.4e-05,4.5e-06,0.04,0.04,0.00084,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1
9290000,-0.28,0.027,-0.0054,0.96,-0.56,-0.19,-0.0011,-0.56,-0.21,-0.026,-0.0014,-0.0047,-6.7e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.9,0.88,0.016,2.1,2.1,0.052,4.3e-05,4.2e-05,4.5e-06,0.04,0.04,0.0008,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1
9390000,-0.28,0.027,-0.0054,0.96,-0.023,-0.0084,0.0003,-0.57,-0.21,-0.026,-0.0013,-0.0047,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.052,4.2e-05,4e-05,4.5e-06,0.04,0.04,0.00077,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
9490000,-0.28,0.027,-0.0053,0.96,-0.049,-0.017,0.0021,-0.58,-0.21,-0.023,-0.0014,-0.0048,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.051,4e-05,3.8e-05,4.5e-06,0.04,0.04,0.00074,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
9590000,-0.28,0.027,-0.0056,0.96,-0.076,-0.023,0.0023,-0.58,-0.21,-0.024,-0.0012,-0.0048,-8e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,51,51,0.05,3.8e-05,3.7e-05,4.5e-06,0.04,0.04,0.00072,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
9690000,-0.28,0.027,-0.0057,0.96,-0.1,-0.031,0.0054,-0.59,-0.21,-0.023,-0.0012,-0.0048,-8.2e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,52,52,0.05,3.6e-05,3.5e-05,4.5e-06,0.04,0.04,0.00069,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
9790000,-0.28,0.027,-0.0059,0.96,-0.13,-0.038,0.0041,-0.59,-0.22,-0.023,-0.001,-0.005,-9.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,35,35,0.05,3.4e-05,3.3e-05,4.5e-06,0.04,0.04,0.00067,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
9890000,-0.28,0.027,-0.0058,0.96,-0.16,-0.047,0.0057,-0.61,-0.22,-0.023,-0.0011,-0.0049,-8.9e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,37,37,0.049,3.2e-05,3.1e-05,4.5e-06,0.04,0.04,0.00064,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
9990000,-0.28,0.027,-0.006,0.96,-0.18,-0.051,0.0065,-0.61,-0.22,-0.025,-0.00096,-0.005,-9.6e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.014,28,28,0.049,3.1e-05,3e-05,4.5e-06,0.04,0.04,0.00062,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
10090000,-0.28,0.027,-0.0061,0.96,-0.21,-0.054,0.0078,-0.63,-0.23,-0.023,-0.00084,-0.0051,-0.0001,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.013,30,30,0.049,2.9e-05,2.8e-05,4.5e-06,0.04,0.04,0.0006,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
10190000,-0.28,0.027,-0.0064,0.96,-0.23,-0.056,0.0087,-0.64,-0.23,-0.024,-0.00067,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,25,25,0.048,2.8e-05,2.7e-05,4.5e-06,0.04,0.04,0.00058,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
10290000,-0.28,0.027,-0.0064,0.96,-0.26,-0.065,0.0079,-0.66,-0.23,-0.023,-0.00072,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,27,27,0.048,2.6e-05,2.5e-05,4.5e-06,0.04,0.04,0.00057,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
10390000,-0.28,0.028,-0.0063,0.96,-0.012,-0.0081,-0.0025,-7.9e-05,-0.00028,-0.023,-0.00074,-0.0049,-0.0001,0.001,0.00015,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.25,0.25,0.56,0.25,0.25,0.049,2.5e-05,2.4e-05,4.5e-06,0.04,0.04,0.00055,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
10490000,-0.28,0.027,-0.0064,0.96,-0.041,-0.014,0.0066,-0.0027,-0.0013,-0.018,-0.00066,-0.005,-0.00011,0.00082,2.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.26,0.26,0.55,0.26,0.26,0.058,2.4e-05,2.3e-05,4.5e-06,0.04,0.04,0.00054,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10590000,-0.28,0.027,-0.0063,0.96,-0.052,-0.013,0.012,-0.0032,-0.00096,-0.016,-0.00073,-0.005,-0.0001,0.0014,7.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.13,0.13,0.27,0.26,0.26,0.056,2.2e-05,2.1e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10690000,-0.28,0.027,-0.0063,0.96,-0.081,-0.018,0.015,-0.0099,-0.0025,-0.013,-0.0007,-0.005,-0.00011,0.0014,2.4e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10790000,-0.28,0.027,-0.0062,0.96,-0.079,-0.021,0.013,-7.5e-06,-0.0018,-0.012,-0.00072,-0.005,-0.00011,0.0035,-0.0011,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.095,0.095,0.17,0.13,0.13,0.062,2e-05,1.9e-05,4.5e-06,0.039,0.039,0.00051,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
10890000,-0.28,0.027,-0.006,0.96,-0.11,-0.03,0.0093,-0.0092,-0.0044,-0.015,-0.00083,-0.005,-0.0001,0.0036,-0.00084,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.11,0.11,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
10990000,-0.28,0.026,-0.006,0.96,-0.096,-0.031,0.016,-0.0034,-0.0023,-0.0093,-0.00085,-0.0052,-0.00011,0.0077,-0.0021,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.083,0.083,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
11090000,-0.28,0.027,-0.0064,0.96,-0.12,-0.039,0.019,-0.014,-0.0055,-0.0055,-0.00072,-0.0052,-0.00011,0.0078,-0.0025,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.096,0.097,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,4.5e-06,0.039,0.039,0.00049,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
11190000,-0.28,0.025,-0.0065,0.96,-0.1,-0.034,0.026,-0.0065,-0.0031,0.00085,-0.00071,-0.0053,-0.00011,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.079,0.079,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1
11290000,-0.28,0.025,-0.0066,0.96,-0.13,-0.038,0.025,-0.018,-0.0066,0.00091,-0.00071,-0.0054,-0.00012,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.094,0.094,0.077,0.078,0.078,0.069,1.5e-05,1.4e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1
11390000,-0.28,0.024,-0.0065,0.96,-0.11,-0.032,0.016,-0.01,-0.004,-0.008,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.078,0.078,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.8e-05,0.0013,0.0012,0.00085,0.0013,1,1
11490000,-0.28,0.024,-0.0064,0.96,-0.13,-0.036,0.021,-0.022,-0.0074,-0.002,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.093,0.093,0.057,0.069,0.069,0.067,1.3e-05,1.3e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1
11590000,-0.28,0.023,-0.0065,0.96,-0.11,-0.029,0.019,-0.013,-0.0046,-0.0033,-0.00079,-0.0056,-0.00012,0.027,-0.0085,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00098,0.048,0.077,0.077,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1
11690000,-0.28,0.022,-0.0065,0.96,-0.12,-0.035,0.019,-0.024,-0.0078,-0.0047,-0.00081,-0.0057,-0.00012,0.027,-0.0083,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00099,0.048,0.092,0.092,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1
11790000,-0.28,0.021,-0.0063,0.96,-0.097,-0.033,0.02,-0.014,-0.0064,-0.0019,-0.0009,-0.0057,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00091,0.00087,0.048,0.076,0.076,0.037,0.053,0.053,0.063,1.1e-05,1.1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1
11890000,-0.28,0.021,-0.0065,0.96,-0.11,-0.037,0.018,-0.024,-0.0097,-0.0012,-0.00088,-0.0058,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00091,0.00087,0.048,0.089,0.089,0.034,0.06,0.06,0.063,1.1e-05,1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1
11990000,-0.28,0.02,-0.0066,0.96,-0.091,-0.028,0.015,-0.017,-0.0064,-0.005,-0.0009,-0.0059,-0.00012,0.039,-0.011,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.076,0.076,0.03,0.062,0.062,0.061,1e-05,9.8e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00082,0.0013,1,1
12090000,-0.28,0.02,-0.0066,0.96,-0.1,-0.03,0.019,-0.027,-0.0092,0.0011,-0.00086,-0.0058,-0.00012,0.039,-0.012,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.089,0.088,0.027,0.071,0.071,0.06,9.8e-06,9.3e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00081,0.0013,1,1
12190000,-0.28,0.019,-0.0067,0.96,-0.084,-0.018,0.018,-0.014,-0.0032,0.0029,-0.00082,-0.0059,-0.00012,0.045,-0.013,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.07,0.07,0.024,0.057,0.057,0.058,9.2e-06,8.8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1
12290000,-0.28,0.019,-0.0068,0.96,-0.09,-0.017,0.017,-0.023,-0.0048,0.004,-0.00079,-0.0059,-0.00012,0.045,-0.014,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.081,0.081,0.022,0.065,0.065,0.058,8.9e-06,8.5e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1
12390000,-0.28,0.019,-0.0068,0.96,-0.073,-0.012,0.015,-0.013,-0.0027,-0.002,-0.00078,-0.0059,-0.00012,0.048,-0.015,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00066,0.00063,0.047,0.066,0.065,0.02,0.054,0.054,0.056,8.4e-06,8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1
12490000,-0.28,0.019,-0.0069,0.96,-0.081,-0.013,0.019,-0.021,-0.004,9.6e-05,-0.00076,-0.0059,-0.00013,0.048,-0.016,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00066,0.00064,0.047,0.075,0.075,0.018,0.062,0.062,0.055,8.1e-06,7.7e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1
12590000,-0.28,0.018,-0.0068,0.96,-0.065,-0.011,0.021,-0.01,-0.0039,0.0019,-0.00076,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00058,0.047,0.061,0.061,0.017,0.052,0.052,0.054,7.7e-06,7.4e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
12690000,-0.28,0.018,-0.0067,0.96,-0.072,-0.0098,0.02,-0.017,-0.0049,0.0035,-0.00075,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00059,0.047,0.069,0.069,0.015,0.059,0.059,0.053,7.4e-06,7e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
12790000,-0.28,0.018,-0.0065,0.96,-0.056,-0.015,0.022,-0.01,-0.0078,0.0057,-0.00082,-0.0059,-0.00013,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.061,0.061,0.014,0.061,0.061,0.051,7.1e-06,6.7e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
12890000,-0.28,0.018,-0.0065,0.96,-0.061,-0.016,0.023,-0.016,-0.0096,0.0088,-0.00084,-0.0059,-0.00012,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.069,0.069,0.013,0.07,0.07,0.051,6.8e-06,6.5e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
12990000,-0.28,0.017,-0.0065,0.96,-0.05,-0.013,0.023,-0.008,-0.0066,0.01,-0.00088,-0.0059,-0.00012,0.056,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.047,0.055,0.055,0.012,0.056,0.056,0.05,6.5e-06,6.2e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
13090000,-0.28,0.017,-0.0064,0.96,-0.054,-0.015,0.021,-0.013,-0.0083,0.0089,-0.00091,-0.0059,-0.00012,0.056,-0.018,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.046,0.062,0.062,0.011,0.065,0.065,0.049,6.3e-06,5.9e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
13190000,-0.28,0.017,-0.0063,0.96,-0.046,-0.015,0.02,-0.0097,-0.0091,0.0096,-0.00094,-0.0059,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.055,0.055,0.011,0.066,0.066,0.047,6e-06,5.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13290000,-0.28,0.017,-0.0064,0.96,-0.049,-0.015,0.017,-0.015,-0.011,0.009,-0.00092,-0.0058,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.061,0.061,0.01,0.075,0.075,0.047,5.8e-06,5.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13390000,-0.28,0.017,-0.0064,0.96,-0.04,-0.011,0.017,-0.0074,-0.007,0.0097,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.049,0.049,0.0094,0.06,0.06,0.046,5.6e-06,5.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13490000,-0.28,0.017,-0.0064,0.96,-0.044,-0.014,0.017,-0.012,-0.0083,0.006,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.054,0.054,0.009,0.068,0.068,0.045,5.4e-06,5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13590000,-0.28,0.017,-0.0064,0.96,-0.035,-0.01,0.018,-0.0035,-0.0057,0.0045,-0.00088,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00045,0.046,0.045,0.045,0.0085,0.055,0.055,0.044,5.2e-06,4.9e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
13690000,-0.28,0.017,-0.0063,0.96,-0.037,-0.0095,0.019,-0.0071,-0.0067,0.0072,-0.00089,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00046,0.046,0.049,0.049,0.0082,0.063,0.063,0.044,5e-06,4.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
13790000,-0.28,0.016,-0.0064,0.96,-0.029,-0.0071,0.019,0.00061,-0.0035,0.0068,-0.00089,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.041,0.041,0.0078,0.052,0.052,0.042,4.8e-06,4.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
13890000,-0.28,0.016,-0.0063,0.96,-0.031,-0.0086,0.02,-0.0022,-0.0044,0.0091,-0.00092,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.045,0.045,0.0076,0.059,0.059,0.042,4.7e-06,4.4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00075,0.0012,1,1
13990000,-0.28,0.016,-0.0062,0.96,-0.03,-0.012,0.018,-0.00073,-0.0048,0.008,-0.00094,-0.0059,-0.00012,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.039,0.039,0.0073,0.05,0.05,0.041,4.5e-06,4.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14090000,-0.28,0.016,-0.0064,0.96,-0.031,-0.0062,0.02,-0.004,-0.0053,0.0046,-0.00087,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.042,0.042,0.0072,0.057,0.057,0.041,4.4e-06,4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14190000,-0.28,0.016,-0.0064,0.96,-0.025,-0.0047,0.02,-0.00094,-0.004,0.0049,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.036,0.036,0.007,0.049,0.049,0.04,4.2e-06,3.9e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14290000,-0.28,0.016,-0.0064,0.96,-0.028,-0.0051,0.018,-0.0036,-0.0044,0.0092,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.04,0.04,0.0069,0.055,0.055,0.039,4.1e-06,3.8e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14390000,-0.28,0.016,-0.0064,0.96,-0.026,-0.0045,0.019,-0.00096,-0.0049,0.014,-0.00083,-0.0059,-0.00012,0.064,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.034,0.034,0.0067,0.048,0.048,0.039,4e-06,3.6e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14490000,-0.28,0.016,-0.0066,0.96,-0.026,-0.0039,0.023,-0.0037,-0.005,0.016,-0.00079,-0.0059,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00042,0.046,0.037,0.037,0.0066,0.054,0.054,0.038,3.8e-06,3.5e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14590000,-0.28,0.016,-0.0067,0.96,-0.028,-0.0054,0.021,-0.0038,-0.0053,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.032,0.032,0.0065,0.047,0.047,0.038,3.7e-06,3.4e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14690000,-0.28,0.016,-0.0067,0.96,-0.029,-0.0058,0.021,-0.0067,-0.006,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.035,0.035,0.0065,0.053,0.053,0.037,3.6e-06,3.3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14790000,-0.28,0.016,-0.0068,0.96,-0.03,-0.003,0.021,-0.0052,-0.0014,0.015,-0.0008,-0.0058,-0.00012,0.065,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.031,0.031,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
14890000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0012,0.026,-0.0086,-0.002,0.016,-0.00081,-0.0057,-0.00012,0.066,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.00041,0.046,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
14990000,-0.28,0.016,-0.0067,0.96,-0.031,-0.003,0.028,-0.0069,-0.003,0.018,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15090000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0042,0.032,-0.01,-0.0033,0.021,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.032,0.032,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15190000,-0.28,0.016,-0.0068,0.96,-0.03,-0.0022,0.033,-0.008,-0.0026,0.023,-0.0008,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15290000,-0.28,0.016,-0.0069,0.96,-0.034,-0.0024,0.032,-0.012,-0.0032,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15390000,-0.28,0.016,-0.0069,0.96,-0.032,-0.0042,0.032,-0.0092,-0.0026,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.027,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15490000,-0.28,0.016,-0.007,0.96,-0.034,-0.0018,0.032,-0.012,-0.003,0.021,-0.00082,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.029,0.0065,0.05,0.05,0.034,2.8e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15590000,-0.28,0.016,-0.0069,0.96,-0.03,-0.006,0.032,-0.0077,-0.0061,0.02,-0.00085,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15690000,-0.28,0.016,-0.0068,0.96,-0.032,-0.0041,0.032,-0.01,-0.0067,0.021,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15790000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0028,0.032,-0.0077,-0.0057,0.023,-0.00092,-0.0057,-0.00012,0.068,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.024,0.024,0.0066,0.043,0.044,0.033,2.6e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15890000,-0.28,0.016,-0.0069,0.96,-0.029,-0.0041,0.033,-0.011,-0.0058,0.023,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15990000,-0.28,0.016,-0.0068,0.96,-0.027,-0.0035,0.03,-0.0091,-0.0049,0.022,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
16090000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0023,0.028,-0.012,-0.005,0.022,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.025,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16190000,-0.28,0.016,-0.0068,0.96,-0.026,-0.002,0.027,-0.011,-0.0041,0.019,-0.00086,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16290000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0011,0.027,-0.014,-0.0043,0.021,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.024,0.024,0.007,0.048,0.048,0.033,2.3e-06,2e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16390000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0015,0.027,-0.011,-0.0041,0.021,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16490000,-0.28,0.016,-0.0069,0.96,-0.033,-0.00051,0.029,-0.014,-0.0041,0.025,-0.00086,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.023,0.023,0.0072,0.047,0.047,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16590000,-0.28,0.016,-0.0069,0.96,-0.036,1.4e-05,0.033,-0.012,-0.0035,0.025,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.021,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16690000,-0.28,0.016,-0.0069,0.96,-0.039,0.0036,0.033,-0.016,-0.0035,0.026,-0.00089,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16790000,-0.28,0.016,-0.0068,0.96,-0.039,0.0034,0.032,-0.013,-0.0031,0.026,-0.00091,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0073,0.042,0.042,0.033,2e-06,1.7e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16890000,-0.28,0.016,-0.0067,0.96,-0.039,0.0029,0.033,-0.017,-0.0032,0.025,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16990000,-0.28,0.016,-0.0067,0.96,-0.036,0.0033,0.033,-0.015,-0.0034,0.024,-0.00094,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.049,0.049,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17090000,-0.28,0.016,-0.0068,0.96,-0.041,0.0053,0.033,-0.019,-0.0029,0.023,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0075,0.054,0.054,0.033,1.9e-06,1.6e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17190000,-0.28,0.016,-0.0069,0.96,-0.039,0.0071,0.034,-0.018,-0.0046,0.026,-0.00093,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0076,0.057,0.057,0.033,1.8e-06,1.6e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17290000,-0.28,0.016,-0.0069,0.96,-0.042,0.0077,0.034,-0.022,-0.0035,0.026,-0.00092,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.023,0.024,0.0077,0.062,0.063,0.033,1.8e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17390000,-0.28,0.016,-0.0069,0.96,-0.032,0.013,0.033,-0.014,-0.002,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17490000,-0.28,0.016,-0.0069,0.96,-0.032,0.014,0.033,-0.017,-0.00051,0.028,-0.00094,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.022,0.0078,0.058,0.058,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17590000,-0.28,0.016,-0.0069,0.96,-0.032,0.012,0.032,-0.016,-0.00075,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
17690000,-0.28,0.016,-0.007,0.96,-0.033,0.012,0.033,-0.019,0.0003,0.028,-0.00096,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.02,0.02,0.0078,0.054,0.054,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
17790000,-0.28,0.016,-0.007,0.96,-0.033,0.013,0.033,-0.018,0.0011,0.033,-0.00097,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.019,0.02,0.0078,0.057,0.057,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1
17890000,-0.28,0.016,-0.0069,0.96,-0.037,0.014,0.033,-0.021,0.0022,0.038,-0.00098,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.021,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1
17990000,-0.28,0.016,-0.0069,0.96,-0.035,0.015,0.033,-0.017,0.0047,0.038,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.018,0.0079,0.052,0.052,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1
18090000,-0.28,0.016,-0.007,0.96,-0.037,0.016,0.032,-0.021,0.0061,0.037,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.008,0.057,0.057,0.034,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1
18190000,-0.28,0.016,-0.007,0.96,-0.034,0.013,0.033,-0.016,0.004,0.035,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18290000,-0.28,0.016,-0.007,0.96,-0.037,0.013,0.031,-0.02,0.005,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.019,0.008,0.053,0.054,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18390000,-0.28,0.016,-0.0069,0.96,-0.033,0.013,0.031,-0.014,0.0042,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0079,0.046,0.047,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18490000,-0.28,0.016,-0.0069,0.96,-0.037,0.012,0.03,-0.018,0.005,0.034,-0.001,-0.0057,-0.00013,0.072,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.018,0.008,0.051,0.051,0.034,1.3e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18590000,-0.28,0.016,-0.0068,0.96,-0.035,0.012,0.03,-0.015,0.0045,0.037,-0.001,-0.0057,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18690000,-0.28,0.016,-0.0067,0.96,-0.035,0.011,0.028,-0.017,0.0053,0.035,-0.0011,-0.0058,-0.00013,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.048,0.049,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18790000,-0.28,0.015,-0.0067,0.96,-0.031,0.011,0.028,-0.014,0.0046,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18890000,-0.28,0.015,-0.0067,0.96,-0.032,0.011,0.026,-0.017,0.0057,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.047,0.047,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18990000,-0.28,0.015,-0.0066,0.96,-0.029,0.011,0.027,-0.015,0.005,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.015,0.0079,0.042,0.042,0.034,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19090000,-0.28,0.015,-0.0067,0.96,-0.029,0.012,0.027,-0.017,0.0056,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.016,0.0079,0.045,0.046,0.035,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19190000,-0.28,0.016,-0.0066,0.96,-0.026,0.013,0.027,-0.015,0.0056,0.028,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.8e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19290000,-0.28,0.016,-0.0066,0.96,-0.027,0.013,0.027,-0.018,0.0067,0.027,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.1e-06,9.7e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19390000,-0.28,0.015,-0.0067,0.96,-0.025,0.011,0.028,-0.016,0.0067,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0078,0.04,0.04,0.035,1.1e-06,9.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19490000,-0.28,0.015,-0.0068,0.96,-0.028,0.012,0.028,-0.019,0.008,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.044,0.035,1.1e-06,9.3e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19590000,-0.28,0.015,-0.0067,0.96,-0.024,0.013,0.03,-0.016,0.0063,0.026,-0.0011,-0.0058,-0.00016,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0077,0.039,0.04,0.035,1.1e-06,9e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19690000,-0.28,0.016,-0.0067,0.96,-0.024,0.011,0.028,-0.019,0.007,0.026,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.043,0.035,1e-06,8.9e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19790000,-0.28,0.015,-0.0068,0.96,-0.021,0.011,0.026,-0.019,0.0075,0.022,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0077,0.045,0.046,0.035,1e-06,8.7e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19890000,-0.28,0.016,-0.0068,0.96,-0.023,0.011,0.027,-0.021,0.0087,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0077,0.049,0.05,0.035,1e-06,8.6e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19990000,-0.28,0.016,-0.0068,0.96,-0.02,0.012,0.024,-0.016,0.0081,0.017,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0076,0.043,0.044,0.035,9.7e-07,8.3e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20090000,-0.28,0.016,-0.0068,0.96,-0.022,0.015,0.024,-0.018,0.0093,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0076,0.047,0.048,0.035,9.7e-07,8.2e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20190000,-0.28,0.016,-0.0068,0.96,-0.023,0.013,0.025,-0.019,0.0097,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0075,0.05,0.05,0.035,9.4e-07,8e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20290000,-0.28,0.016,-0.0068,0.96,-0.021,0.015,0.025,-0.022,0.011,0.021,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.054,0.055,0.035,9.3e-07,7.9e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20390000,-0.28,0.016,-0.0067,0.96,-0.019,0.013,0.025,-0.022,0.01,0.022,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.056,0.057,0.035,9.1e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20490000,-0.28,0.016,-0.0067,0.96,-0.017,0.015,0.025,-0.024,0.011,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0075,0.061,0.063,0.035,9e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20590000,-0.28,0.016,-0.0066,0.96,-0.017,0.014,0.025,-0.024,0.01,0.018,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0074,0.064,0.065,0.035,8.8e-07,7.5e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20690000,-0.28,0.016,-0.0066,0.96,-0.016,0.014,0.026,-0.025,0.012,0.019,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.018,0.02,0.0074,0.069,0.071,0.035,8.7e-07,7.4e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20790000,-0.28,0.016,-0.006,0.96,-0.01,0.01,0.01,-0.019,0.0088,0.017,-0.0012,-0.0058,-0.00018,0.072,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.017,0.0073,0.057,0.057,0.035,8.4e-07,7.1e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20890000,-0.28,0.011,0.0027,0.96,-0.0058,-5.9e-05,-0.11,-0.021,0.0092,0.011,-0.0012,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00037,0.00034,0.046,0.017,0.018,0.0073,0.061,0.062,0.035,8.3e-07,7.1e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20990000,-0.28,0.0071,0.0057,0.96,0.0086,-0.017,-0.25,-0.017,0.007,-0.004,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.016,0.0072,0.052,0.052,0.034,8e-07,6.9e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
21090000,-0.28,0.0076,0.0042,0.96,0.022,-0.029,-0.37,-0.016,0.005,-0.035,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.017,0.0072,0.056,0.057,0.035,8e-07,6.8e-07,4.2e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
21190000,-0.28,0.0095,0.0015,0.96,0.028,-0.035,-0.49,-0.013,0.0038,-0.071,-0.0011,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.014,0.016,0.0071,0.048,0.049,0.035,7.7e-07,6.6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1
21290000,-0.28,0.011,-0.00054,0.96,0.026,-0.037,-0.62,-0.011,0.0011,-0.13,-0.0011,-0.0058,-0.00019,0.072,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.0071,0.052,0.053,0.035,7.7e-07,6.5e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1
21390000,-0.28,0.012,-0.002,0.96,0.019,-0.029,-0.75,-0.013,0.0046,-0.19,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.016,0.017,0.007,0.054,0.055,0.035,7.5e-07,6.4e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1
21490000,-0.28,0.012,-0.0028,0.96,0.013,-0.027,-0.88,-0.011,0.0015,-0.28,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.017,0.018,0.007,0.059,0.06,0.035,7.4e-07,6.3e-07,4.1e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21590000,-0.28,0.012,-0.0034,0.96,0.0009,-0.021,-1,-0.015,0.0065,-0.37,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.017,0.018,0.0069,0.061,0.063,0.034,7.3e-07,6.2e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21690000,-0.28,0.012,-0.0037,0.96,-0.0046,-0.017,-1.1,-0.015,0.004,-0.48,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0069,0.066,0.068,0.035,7.2e-07,6.1e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21790000,-0.28,0.012,-0.0041,0.96,-0.011,-0.0087,-1.3,-0.017,0.01,-0.6,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.019,0.0069,0.069,0.07,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21890000,-0.28,0.013,-0.0044,0.96,-0.017,-0.0041,-1.4,-0.018,0.01,-0.74,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0068,0.074,0.076,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21990000,-0.28,0.013,-0.0052,0.96,-0.022,0.0043,-1.4,-0.024,0.018,-0.88,-0.0011,-0.0058,-8.8e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0068,0.077,0.079,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
22090000,-0.28,0.014,-0.0058,0.96,-0.025,0.0075,-1.4,-0.025,0.018,-1,-0.0011,-0.0058,-8.2e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0068,0.083,0.085,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
22190000,-0.28,0.014,-0.0063,0.96,-0.032,0.014,-1.4,-0.03,0.025,-1.2,-0.0011,-0.0058,-5.9e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0067,0.085,0.087,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22290000,-0.28,0.014,-0.007,0.96,-0.04,0.019,-1.4,-0.034,0.027,-1.3,-0.0011,-0.0058,-6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0067,0.091,0.094,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22390000,-0.28,0.015,-0.0073,0.96,-0.047,0.026,-1.4,-0.04,0.031,-1.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0066,0.094,0.096,0.034,6.4e-07,5.5e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22490000,-0.28,0.015,-0.0074,0.96,-0.053,0.032,-1.4,-0.045,0.034,-1.6,-0.0011,-0.0058,-6.4e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0066,0.1,0.1,0.034,6.4e-07,5.4e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22590000,-0.28,0.016,-0.0073,0.96,-0.058,0.038,-1.4,-0.046,0.038,-1.7,-0.0011,-0.0058,-5.7e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.1,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22690000,-0.28,0.016,-0.0072,0.96,-0.062,0.042,-1.4,-0.053,0.042,-1.9,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.11,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22790000,-0.28,0.016,-0.0071,0.96,-0.069,0.047,-1.4,-0.059,0.045,-2,-0.0011,-0.0058,-6.6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.11,0.11,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22890000,-0.28,0.017,-0.0072,0.96,-0.074,0.051,-1.4,-0.065,0.048,-2.2,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.12,0.12,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22990000,-0.28,0.017,-0.007,0.96,-0.076,0.051,-1.4,-0.068,0.047,-2.3,-0.0011,-0.0058,-6.3e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.022,0.0064,0.12,0.12,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23090000,-0.28,0.017,-0.007,0.96,-0.082,0.055,-1.4,-0.075,0.053,-2.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0064,0.13,0.13,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23190000,-0.28,0.017,-0.0069,0.96,-0.084,0.05,-1.4,-0.074,0.049,-2.6,-0.0011,-0.0058,-8.4e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.13,0.13,0.033,5.7e-07,4.9e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23290000,-0.28,0.018,-0.0073,0.96,-0.09,0.054,-1.4,-0.083,0.053,-2.7,-0.0011,-0.0058,-8e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.14,0.14,0.034,5.6e-07,4.8e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23390000,-0.28,0.018,-0.0073,0.96,-0.089,0.056,-1.4,-0.077,0.055,-2.9,-0.0011,-0.0058,-9.8e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.14,0.14,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23490000,-0.28,0.018,-0.0073,0.96,-0.096,0.057,-1.4,-0.088,0.059,-3,-0.0011,-0.0058,-9e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.15,0.15,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23590000,-0.28,0.018,-0.0074,0.96,-0.094,0.051,-1.4,-0.083,0.049,-3.2,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0062,0.15,0.15,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23690000,-0.28,0.019,-0.008,0.96,-0.093,0.053,-1.3,-0.092,0.053,-3.3,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0062,0.16,0.16,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23790000,-0.28,0.021,-0.0095,0.96,-0.077,0.049,-0.95,-0.082,0.049,-3.4,-0.0012,-0.0058,-0.00012,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00039,0.00036,0.045,0.021,0.022,0.0061,0.16,0.16,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23890000,-0.28,0.026,-0.012,0.96,-0.071,0.05,-0.52,-0.089,0.053,-3.5,-0.0012,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00042,0.00038,0.045,0.021,0.023,0.0061,0.17,0.17,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23990000,-0.28,0.028,-0.014,0.96,-0.061,0.048,-0.13,-0.077,0.048,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.02,0.022,0.0061,0.17,0.17,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
24090000,-0.28,0.027,-0.014,0.96,-0.067,0.055,0.1,-0.082,0.053,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.021,0.023,0.0061,0.18,0.18,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
24190000,-0.28,0.023,-0.011,0.96,-0.071,0.052,0.089,-0.069,0.04,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.0004,0.00037,0.045,0.02,0.022,0.006,0.18,0.18,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
24290000,-0.28,0.02,-0.0093,0.96,-0.076,0.055,0.068,-0.076,0.045,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.023,0.006,0.19,0.19,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
24390000,-0.28,0.018,-0.0085,0.96,-0.059,0.048,0.084,-0.058,0.036,-3.6,-0.0013,-0.0058,-0.00016,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.02,0.022,0.006,0.19,0.19,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
24490000,-0.28,0.019,-0.0087,0.96,-0.054,0.044,0.081,-0.063,0.039,-3.6,-0.0013,-0.0058,-0.00014,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.021,0.023,0.006,0.2,0.2,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
24590000,-0.28,0.019,-0.0094,0.96,-0.043,0.042,0.077,-0.045,0.033,-3.6,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.022,0.0059,0.2,0.2,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24690000,-0.28,0.019,-0.0099,0.96,-0.041,0.041,0.076,-0.049,0.037,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.024,0.0059,0.21,0.21,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24790000,-0.28,0.018,-0.01,0.96,-0.034,0.04,0.068,-0.037,0.029,-3.5,-0.0013,-0.0058,-0.00017,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0059,0.21,0.21,0.032,4.7e-07,4.1e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24890000,-0.28,0.017,-0.0099,0.96,-0.033,0.042,0.058,-0.04,0.032,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0059,0.22,0.22,0.032,4.7e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24990000,-0.28,0.017,-0.0097,0.96,-0.021,0.043,0.05,-0.026,0.027,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.22,0.22,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25090000,-0.28,0.017,-0.01,0.96,-0.016,0.043,0.048,-0.027,0.031,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.23,0.23,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25190000,-0.28,0.017,-0.01,0.96,-0.006,0.038,0.048,-0.011,0.021,-3.5,-0.0013,-0.0059,-0.0002,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.23,0.23,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25290000,-0.28,0.016,-0.01,0.96,-0.0013,0.041,0.043,-0.012,0.026,-3.5,-0.0013,-0.0059,-0.00021,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.24,0.24,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25390000,-0.28,0.016,-0.011,0.96,0.0076,0.039,0.041,-0.0022,0.02,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.24,0.24,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25490000,-0.28,0.016,-0.011,0.96,0.012,0.04,0.041,-0.0021,0.024,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.25,0.25,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25590000,-0.28,0.016,-0.011,0.96,0.017,0.035,0.042,0.0049,0.0094,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.25,0.25,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25690000,-0.28,0.015,-0.01,0.96,0.018,0.034,0.031,0.0066,0.013,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.26,0.26,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25790000,-0.28,0.015,-0.01,0.96,0.028,0.029,0.031,0.014,0.0031,-3.5,-0.0014,-0.0058,-0.00025,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.26,0.032,4.2e-07,3.7e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25890000,-0.28,0.015,-0.01,0.96,0.034,0.029,0.033,0.017,0.0067,-3.5,-0.0014,-0.0058,-0.00026,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.27,0.27,0.032,4.2e-07,3.7e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25990000,-0.28,0.015,-0.01,0.96,0.036,0.024,0.027,0.013,-0.004,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.27,0.27,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26090000,-0.28,0.015,-0.0099,0.96,0.041,0.024,0.025,0.017,-0.0023,-3.5,-0.0014,-0.0058,-0.00027,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.28,0.28,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26190000,-0.28,0.015,-0.0098,0.96,0.046,0.015,0.021,0.02,-0.018,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.27,0.28,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26290000,-0.28,0.016,-0.0098,0.96,0.046,0.014,0.015,0.024,-0.016,-3.5,-0.0014,-0.0058,-0.00029,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.29,0.29,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26390000,-0.28,0.016,-0.0092,0.96,0.043,0.0051,0.019,0.015,-0.03,-3.5,-0.0014,-0.0058,-0.0003,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0056,0.28,0.29,0.032,4e-07,3.5e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26490000,-0.28,0.016,-0.009,0.96,0.046,0.0028,0.028,0.02,-0.03,-3.5,-0.0014,-0.0058,-0.00031,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.3,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26590000,-0.28,0.016,-0.0084,0.96,0.045,-0.0071,0.029,0.019,-0.042,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0056,0.29,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26690000,-0.28,0.016,-0.0083,0.96,0.047,-0.011,0.027,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.31,0.31,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26790000,-0.27,0.015,-0.0081,0.96,0.049,-0.017,0.027,0.02,-0.055,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.3,0.31,0.031,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26890000,-0.27,0.015,-0.0074,0.96,0.055,-0.02,0.022,0.026,-0.057,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.32,0.32,0.032,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26990000,-0.27,0.016,-0.0069,0.96,0.056,-0.026,0.021,0.018,-0.064,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.31,0.32,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27090000,-0.27,0.016,-0.0067,0.96,0.058,-0.033,0.025,0.024,-0.067,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0055,0.33,0.33,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27190000,-0.27,0.016,-0.0068,0.96,0.058,-0.036,0.027,0.014,-0.069,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.32,0.33,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27290000,-0.27,0.017,-0.0069,0.96,0.066,-0.041,0.14,0.02,-0.073,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.022,0.024,0.0055,0.33,0.34,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27390000,-0.27,0.019,-0.0081,0.96,0.07,-0.034,0.46,0.0048,-0.026,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27490000,-0.27,0.021,-0.0093,0.96,0.076,-0.037,0.78,0.012,-0.029,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.016,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27590000,-0.27,0.02,-0.0093,0.96,0.067,-0.039,0.87,0.0064,-0.02,-3.4,-0.0014,-0.0058,-0.00032,0.074,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.014,0.015,0.0055,0.096,0.097,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27690000,-0.27,0.017,-0.0084,0.96,0.061,-0.036,0.78,0.013,-0.024,-3.3,-0.0014,-0.0058,-0.00031,0.075,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0055,0.1,0.1,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27790000,-0.27,0.016,-0.0072,0.96,0.058,-0.034,0.77,0.01,-0.019,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.013,0.015,0.0054,0.073,0.074,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
27890000,-0.27,0.016,-0.0068,0.96,0.064,-0.04,0.81,0.016,-0.023,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.014,0.016,0.0055,0.076,0.077,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
27990000,-0.27,0.016,-0.0072,0.96,0.064,-0.042,0.8,0.019,-0.026,-3.1,-0.0014,-0.0058,-0.00029,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0054,0.079,0.079,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28090000,-0.27,0.016,-0.0075,0.96,0.068,-0.043,0.8,0.026,-0.03,-3,-0.0014,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.082,0.083,0.031,3.6e-07,3.1e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28190000,-0.27,0.016,-0.0069,0.96,0.065,-0.041,0.81,0.027,-0.032,-2.9,-0.0013,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.085,0.085,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28290000,-0.27,0.017,-0.0064,0.96,0.069,-0.044,0.81,0.033,-0.037,-2.9,-0.0013,-0.0058,-0.00027,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.016,0.018,0.0054,0.089,0.09,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28390000,-0.27,0.017,-0.0063,0.96,0.07,-0.046,0.81,0.035,-0.038,-2.8,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0054,0.091,0.092,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28490000,-0.27,0.018,-0.0066,0.96,0.073,-0.049,0.81,0.043,-0.042,-2.7,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.095,0.097,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28590000,-0.27,0.018,-0.0066,0.96,0.065,-0.049,0.81,0.043,-0.045,-2.6,-0.0013,-0.0058,-0.00023,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.098,0.099,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28690000,-0.27,0.017,-0.0064,0.96,0.064,-0.05,0.81,0.05,-0.05,-2.6,-0.0013,-0.0058,-0.00024,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.017,0.019,0.0054,0.1,0.1,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28790000,-0.27,0.017,-0.0058,0.96,0.062,-0.049,0.81,0.051,-0.049,-2.5,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.11,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28890000,-0.27,0.016,-0.0056,0.96,0.065,-0.051,0.81,0.057,-0.054,-2.4,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.02,0.0054,0.11,0.11,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28990000,-0.27,0.016,-0.0054,0.96,0.063,-0.048,0.81,0.058,-0.054,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.017,0.019,0.0053,0.11,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29090000,-0.27,0.017,-0.0052,0.96,0.067,-0.05,0.81,0.066,-0.059,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29190000,-0.27,0.017,-0.0051,0.96,0.067,-0.049,0.8,0.067,-0.058,-2.2,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29290000,-0.27,0.017,-0.0054,0.96,0.071,-0.054,0.81,0.076,-0.062,-2.1,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.021,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29390000,-0.27,0.016,-0.0059,0.96,0.067,-0.051,0.81,0.074,-0.059,-2,-0.0013,-0.0058,-0.00014,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29490000,-0.27,0.016,-0.0059,0.96,0.07,-0.052,0.81,0.081,-0.065,-2,-0.0013,-0.0058,-0.00013,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29590000,-0.27,0.016,-0.0058,0.96,0.068,-0.05,0.81,0.08,-0.063,-1.9,-0.0013,-0.0058,-0.00011,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.018,0.021,0.0053,0.14,0.14,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29690000,-0.27,0.016,-0.0058,0.96,0.072,-0.049,0.81,0.087,-0.068,-1.8,-0.0013,-0.0058,-9.8e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.019,0.022,0.0053,0.15,0.15,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29790000,-0.27,0.016,-0.0056,0.96,0.069,-0.042,0.8,0.084,-0.064,-1.7,-0.0013,-0.0058,-6.9e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0053,0.15,0.15,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29890000,-0.27,0.016,-0.005,0.96,0.07,-0.044,0.8,0.092,-0.069,-1.7,-0.0013,-0.0058,-6.2e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0053,0.15,0.16,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29990000,-0.27,0.016,-0.0052,0.96,0.065,-0.041,0.8,0.087,-0.068,-1.6,-0.0013,-0.0058,-4.8e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.16,0.16,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30090000,-0.27,0.017,-0.0053,0.96,0.067,-0.041,0.8,0.094,-0.07,-1.5,-0.0013,-0.0058,-6.2e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.16,0.17,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30190000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.089,-0.061,-1.5,-0.0013,-0.0058,-5e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.17,0.17,0.031,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30290000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.096,-0.065,-1.4,-0.0013,-0.0058,-4.9e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.17,0.18,0.03,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30390000,-0.27,0.016,-0.0054,0.96,0.059,-0.029,0.8,0.095,-0.059,-1.3,-0.0013,-0.0058,-1.9e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.18,0.18,0.03,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30490000,-0.27,0.016,-0.0054,0.96,0.063,-0.028,0.8,0.1,-0.062,-1.2,-0.0013,-0.0058,-1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.18,0.19,0.031,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30590000,-0.27,0.017,-0.0056,0.96,0.061,-0.026,0.8,0.097,-0.058,-1.2,-0.0013,-0.0058,1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.18,0.19,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30690000,-0.27,0.017,-0.006,0.96,0.058,-0.026,0.8,0.1,-0.061,-1.1,-0.0013,-0.0058,1.1e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00035,0.044,0.02,0.023,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30790000,-0.27,0.016,-0.0058,0.96,0.052,-0.016,0.8,0.095,-0.049,-1,-0.0012,-0.0058,3.6e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30890000,-0.27,0.016,-0.0052,0.96,0.051,-0.012,0.79,0.099,-0.05,-0.95,-0.0012,-0.0058,2.6e-05,0.072,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30990000,-0.27,0.016,-0.0054,0.96,0.046,-0.01,0.79,0.095,-0.048,-0.88,-0.0012,-0.0058,3e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31090000,-0.27,0.016,-0.0055,0.96,0.045,-0.0087,0.79,0.099,-0.049,-0.81,-0.0012,-0.0058,2.2e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.21,0.22,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31190000,-0.27,0.017,-0.0057,0.96,0.042,-0.0051,0.8,0.093,-0.044,-0.74,-0.0012,-0.0058,4.6e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31290000,-0.27,0.017,-0.0059,0.96,0.039,-0.0033,0.8,0.096,-0.045,-0.67,-0.0012,-0.0058,5.2e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31390000,-0.27,0.016,-0.0057,0.96,0.035,0.0017,0.8,0.09,-0.042,-0.59,-0.0012,-0.0058,5.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31490000,-0.27,0.017,-0.0054,0.96,0.036,0.0051,0.8,0.095,-0.041,-0.52,-0.0012,-0.0058,4.8e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
31590000,-0.27,0.017,-0.0052,0.96,0.036,0.007,0.8,0.092,-0.037,-0.45,-0.0012,-0.0058,6.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
31690000,-0.27,0.017,-0.0052,0.96,0.04,0.0082,0.8,0.097,-0.037,-0.38,-0.0012,-0.0058,7.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31790000,-0.27,0.018,-0.0054,0.96,0.034,0.014,0.8,0.093,-0.027,-0.3,-0.0012,-0.0058,9e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31890000,-0.27,0.018,-0.0052,0.96,0.032,0.016,0.8,0.097,-0.025,-0.23,-0.0012,-0.0058,9.4e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.25,0.26,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31990000,-0.27,0.017,-0.0055,0.96,0.029,0.017,0.79,0.094,-0.02,-0.17,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32090000,-0.27,0.017,-0.0059,0.96,0.03,0.021,0.8,0.098,-0.018,-0.096,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32190000,-0.27,0.017,-0.0061,0.96,0.027,0.029,0.8,0.093,-0.0092,-0.027,-0.0012,-0.0058,9.7e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32290000,-0.27,0.017,-0.006,0.96,0.027,0.031,0.8,0.096,-0.0063,0.042,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32390000,-0.27,0.017,-0.0062,0.96,0.023,0.033,0.79,0.092,-0.0029,0.12,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32490000,-0.27,0.016,-0.0092,0.96,-0.017,0.092,-0.077,0.091,0.0054,0.12,-0.0012,-0.0058,9.6e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32590000,-0.27,0.016,-0.0092,0.96,-0.014,0.09,-0.08,0.091,-0.0025,0.1,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.021,0.023,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32690000,-0.27,0.016,-0.0092,0.96,-0.01,0.097,-0.081,0.09,0.0069,0.088,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32790000,-0.27,0.016,-0.009,0.96,-0.0062,0.095,-0.082,0.092,-0.0016,0.073,-0.0012,-0.0058,7.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32890000,-0.27,0.016,-0.009,0.96,-0.0066,0.1,-0.084,0.09,0.0078,0.058,-0.0012,-0.0058,8.1e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32990000,-0.27,0.016,-0.0088,0.96,-0.0026,0.095,-0.083,0.091,-0.006,0.044,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33090000,-0.27,0.016,-0.0088,0.96,0.0013,0.1,-0.08,0.091,0.0037,0.037,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.31,0.32,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33190000,-0.27,0.016,-0.0086,0.96,0.0057,0.096,-0.079,0.092,-0.012,0.029,-0.0012,-0.0058,4e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33290000,-0.27,0.016,-0.0087,0.96,0.0098,0.099,-0.079,0.093,-0.0027,0.021,-0.0013,-0.0058,5.7e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33390000,-0.27,0.016,-0.0086,0.96,0.014,0.095,-0.077,0.092,-0.012,0.012,-0.0013,-0.0058,4.6e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33490000,-0.27,0.016,-0.0086,0.96,0.02,0.099,-0.076,0.095,-0.0019,0.0028,-0.0013,-0.0058,5.4e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.33,0.34,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33590000,-0.27,0.016,-0.0084,0.96,0.023,0.096,-0.073,0.094,-0.015,-0.0051,-0.0013,-0.0058,4.8e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.33,0.34,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33690000,-0.27,0.016,-0.0084,0.96,0.026,0.099,-0.074,0.095,-0.0061,-0.013,-0.0013,-0.0058,5.3e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.34,0.35,0.03,2.7e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33790000,-0.27,0.016,-0.0083,0.96,0.029,0.096,-0.068,0.092,-0.02,-0.02,-0.0013,-0.0058,3.3e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.34,0.35,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33890000,-0.27,0.016,-0.0083,0.96,0.033,0.097,-0.068,0.095,-0.01,-0.027,-0.0013,-0.0058,4.8e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33990000,-0.27,0.016,-0.0082,0.96,0.036,0.095,-0.064,0.094,-0.019,-0.03,-0.0013,-0.0057,3.3e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
34090000,-0.27,0.016,-0.0081,0.96,0.039,0.1,-0.063,0.097,-0.0094,-0.035,-0.0013,-0.0057,3.6e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
34190000,-0.27,0.016,-0.0081,0.96,0.04,0.096,-0.06,0.092,-0.021,-0.038,-0.0013,-0.0057,3e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.022,0.005,0.36,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
34290000,-0.26,0.016,-0.0079,0.96,0.041,0.1,-0.059,0.096,-0.012,-0.044,-0.0013,-0.0057,4e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.005,0.37,0.38,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
34390000,-0.26,0.016,-0.0078,0.96,0.043,0.095,-0.054,0.091,-0.023,-0.048,-0.0013,-0.0057,3e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.02,0.022,0.005,0.37,0.37,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00062,0.0012,1,1
34490000,-0.26,0.016,-0.0079,0.96,0.046,0.099,-0.052,0.095,-0.014,-0.051,-0.0013,-0.0057,4.2e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.021,0.023,0.005,0.38,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34590000,-0.26,0.016,-0.0078,0.96,0.049,0.092,0.74,0.09,-0.028,-0.022,-0.0013,-0.0057,3e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.38,0.38,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34690000,-0.26,0.015,-0.0078,0.96,0.058,0.092,1.7,0.095,-0.019,0.097,-0.0013,-0.0057,3.5e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.0051,0.39,0.4,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34790000,-0.26,0.015,-0.0077,0.96,0.063,0.086,2.7,0.088,-0.032,0.28,-0.0013,-0.0057,2.6e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.021,0.005,0.39,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34890000,-0.26,0.015,-0.0077,0.96,0.071,0.086,3.7,0.094,-0.023,0.57,-0.0013,-0.0057,3.2e-05,0.079,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.021,0.023,0.005,0.4,0.41,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.00077,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00051,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,4.9e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00062,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.8e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00043,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.6e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00051,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.1e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.2e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.5e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3e-07,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.7e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.7e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3.5e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-8.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.5e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2490000,1,-0.011,-0.014,0.00048,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.5e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-2.1e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2790000,1,-0.01,-0.013,0.00038,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2990000,1,-0.01,-0.013,0.00032,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-3.1e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-3.1e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3190000,1,-0.01,-0.013,0.00057,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.5e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3490000,1,-0.0097,-0.013,0.00059,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3690000,1,-0.0095,-0.013,0.00053,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.8e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3890000,1,-0.0094,-0.013,0.00064,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4090000,1,-0.0093,-0.012,0.00077,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-5.2e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-5.2e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4290000,1,-0.0095,-0.012,0.00075,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.7e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.7e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4490000,1,-0.0094,-0.012,0.00077,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-6.2e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-6.2e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4690000,1,-0.0094,-0.012,0.00077,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.6e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4790000,1,-0.0093,-0.012,0.00087,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.6e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4890000,1,-0.0092,-0.012,0.00091,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-7e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-7e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5090000,1,-0.0091,-0.011,0.00097,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-7.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-7.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5690000,1,-0.0089,-0.011,0.0009,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5790000,1,-0.0088,-0.011,0.00086,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5890000,1,-0.0088,-0.011,0.00089,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5990000,1,-0.0088,-0.012,0.00087,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6090000,1,-0.0088,-0.011,0.00068,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6190000,1,-0.0089,-0.011,0.00069,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6290000,1,-0.0089,-0.011,0.00072,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6390000,1,-0.0089,-0.011,0.00073,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6490000,1,-0.0089,-0.011,0.00063,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.8e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6590000,1,-0.009,-0.011,0.00056,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6690000,1,-0.0089,-0.011,0.00052,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6790000,1,-0.009,-0.011,0.00048,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6890000,1,-0.0088,-0.011,0.0004,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6990000,-0.29,0.024,-0.0063,0.96,-0.2,-0.03,-0.037,-0.11,-0.017,-0.055,-0.00076,-0.0097,-0.0002,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1
7090000,-0.28,0.025,-0.0064,0.96,-0.24,-0.045,-0.038,-0.15,-0.025,-0.056,-0.00064,-0.01,-0.00021,0,0,-0.13,-0.099,-0.022,0.51,0.075,-0.029,-0.065,0,0,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1
7190000,-0.28,0.025,-0.0064,0.96,-0.26,-0.053,-0.037,-0.17,-0.031,-0.059,-0.0006,-0.01,-0.00021,-0.00035,-7.2e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1
7290000,-0.28,0.025,-0.0065,0.96,-0.29,-0.062,-0.034,-0.2,-0.038,-0.055,-0.00059,-0.01,-0.00021,-0.00088,-0.00017,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1
7390000,-0.28,0.024,-0.0064,0.96,-0.3,-0.068,-0.032,-0.23,-0.044,-0.052,-0.00058,-0.01,-0.00021,-0.0011,-0.00021,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00086,0.0013,1,1
7490000,-0.28,0.024,-0.0065,0.96,-0.32,-0.075,-0.026,-0.26,-0.052,-0.046,-0.00057,-0.0099,-0.00021,-0.0015,-0.00025,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1
7590000,-0.28,0.024,-0.0066,0.96,-0.34,-0.082,-0.022,-0.28,-0.061,-0.041,-0.00055,-0.0098,-0.00021,-0.0016,-0.00021,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00085,0.0013,1,1
7690000,-0.28,0.024,-0.0066,0.96,-0.35,-0.091,-0.022,-0.31,-0.071,-0.036,-0.00053,-0.0097,-0.00021,-0.0017,-0.00019,-0.13,-0.1,-0.022,0.5,0.079,-0.031,-0.068,0,0,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.00084,0.0013,1,1
7790000,-0.28,0.023,-0.0064,0.96,-0.36,-0.1,-0.024,-0.34,-0.085,-0.041,-0.00046,-0.0096,-0.0002,-0.0017,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.00084,0.0013,1,1
7890000,-0.28,0.023,-0.0065,0.96,-0.37,-0.11,-0.025,-0.37,-0.097,-0.045,-0.00044,-0.0095,-0.0002,-0.0016,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00085,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.00083,0.0013,1,1
7990000,-0.28,0.023,-0.0065,0.96,-0.39,-0.11,-0.021,-0.4,-0.11,-0.041,-0.00047,-0.0094,-0.0002,-0.0016,-0.00017,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0012,0.00083,0.0013,1,1
8090000,-0.28,0.023,-0.0064,0.96,-0.41,-0.12,-0.022,-0.44,-0.12,-0.044,-0.0004,-0.0094,-0.0002,-0.0016,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.0008,0.00082,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,8.8e-05,0.0013,0.0012,0.00083,0.0013,1,1
8190000,-0.28,0.022,-0.0064,0.96,-0.41,-0.14,-0.017,-0.46,-0.14,-0.038,-0.00033,-0.0092,-0.0002,-0.0016,-0.00023,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00077,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0013,8.6e-05,0.0013,0.0012,0.00082,0.0013,1,1
8290000,-0.28,0.022,-0.0066,0.96,-0.44,-0.14,-0.016,-0.51,-0.15,-0.038,-0.00039,-0.0093,-0.0002,-0.0017,-0.0002,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00075,0.00077,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0013,8.4e-05,0.0013,0.0012,0.00082,0.0013,1,1
8390000,-0.28,0.022,-0.0066,0.96,-0.45,-0.14,-0.015,-0.55,-0.16,-0.036,-0.00039,-0.0092,-0.0002,-0.0017,-0.00018,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0012,0.00082,0.0013,1,1
8490000,-0.28,0.022,-0.0066,0.96,-0.46,-0.14,-0.016,-0.58,-0.17,-0.041,-0.00048,-0.0091,-0.00019,-0.0016,-9.5e-05,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.0007,0.00072,0.053,0.82,0.82,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0012,0.00082,0.0013,1,1
8590000,-0.28,0.021,-0.0064,0.96,-0.45,-0.15,-0.012,-0.6,-0.19,-0.036,-0.00042,-0.0089,-0.00019,-0.0016,-9.3e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.068,0,0,0.00068,0.0007,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8e-05,0.0013,0.0012,0.00081,0.0013,1,1
8690000,-0.28,0.021,-0.0066,0.96,-0.47,-0.15,-0.014,-0.64,-0.2,-0.037,-0.00048,-0.0088,-0.00019,-0.0016,-5.5e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00066,0.00068,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,7.9e-05,0.0013,0.0012,0.00081,0.0013,1,1
8790000,-0.28,0.021,-0.0066,0.96,-0.48,-0.16,-0.013,-0.68,-0.22,-0.035,-0.00046,-0.0088,-0.00018,-0.0016,-5e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00064,0.00066,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,7.8e-05,0.0013,0.0012,0.00081,0.0013,1,1
8890000,-0.28,0.021,-0.0066,0.96,-0.47,-0.16,-0.0094,-0.68,-0.23,-0.029,-0.00051,-0.0085,-0.00018,-0.0016,5.8e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00063,0.00064,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,7.7e-05,0.0013,0.0012,0.0008,0.0013,1,1
8990000,-0.28,0.02,-0.0064,0.96,-0.45,-0.16,-0.0089,-0.68,-0.24,-0.032,-0.00055,-0.0082,-0.00017,-0.0013,0.00016,-0.13,-0.1,-0.023,0.5,0.08,-0.032,-0.069,0,0,0.00061,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,7.6e-05,0.0013,0.0012,0.0008,0.0013,1,1
9090000,-0.28,0.02,-0.0065,0.96,-0.46,-0.15,-0.01,-0.72,-0.22,-0.032,-0.00071,-0.0082,-0.00016,-0.0012,0.00033,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.0006,0.00061,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,7.5e-05,0.0013,0.0012,0.0008,0.0013,1,1
9190000,-0.28,0.02,-0.0065,0.96,-0.46,-0.15,-0.0096,-0.74,-0.22,-0.033,-0.00081,-0.008,-0.00016,-0.0011,0.00045,-0.13,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00058,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,7.4e-05,0.0013,0.0012,0.00079,0.0013,1,1
9290000,-0.28,0.02,-0.0062,0.96,-0.46,-0.15,-0.0082,-0.74,-0.24,-0.03,-0.00081,-0.0078,-0.00015,-0.001,0.00052,-0.13,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00057,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,7.4e-05,0.0013,0.0012,0.00079,0.0013,1,1
9390000,-0.28,0.019,-0.006,0.96,-0.45,-0.17,-0.0071,-0.75,-0.27,-0.031,-0.00073,-0.0077,-0.00015,-0.00084,0.0005,-0.13,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00056,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,7.3e-05,0.0013,0.0012,0.00079,0.0013,1,1
9490000,-0.28,0.019,-0.0061,0.96,-0.46,-0.16,-0.0055,-0.78,-0.27,-0.028,-0.0008,-0.0076,-0.00015,-0.00092,0.00059,-0.14,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00055,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,7.2e-05,0.0013,0.0012,0.00079,0.0013,1,1
9590000,-0.28,0.019,-0.0061,0.96,-0.47,-0.18,-0.0054,-0.82,-0.32,-0.029,-0.00068,-0.0075,-0.00015,-0.00085,0.00046,-0.14,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.2e-05,0.0013,0.0012,0.00078,0.0013,1,1
9690000,-0.28,0.019,-0.006,0.96,-0.47,-0.19,-0.0026,-0.83,-0.35,-0.028,-0.00064,-0.0074,-0.00015,-0.00077,0.00045,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00055,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.1e-05,0.0013,0.0012,0.00078,0.0013,1,1
9790000,-0.28,0.019,-0.006,0.96,-0.48,-0.2,-0.004,-0.88,-0.39,-0.029,-0.00055,-0.0074,-0.00015,-0.00075,0.00038,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.1e-05,0.0013,0.0012,0.00078,0.0013,1,1
9890000,-0.28,0.019,-0.0059,0.96,-0.47,-0.21,-0.0028,-0.88,-0.41,-0.03,-0.00058,-0.0072,-0.00014,-0.00051,0.00044,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.7,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7e-05,0.0013,0.0012,0.00078,0.0013,1,1
9990000,-0.28,0.019,-0.0059,0.96,-0.49,-0.22,-0.0021,-0.93,-0.44,-0.032,-0.00052,-0.0072,-0.00015,-0.00043,0.00037,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7e-05,0.0013,0.0012,0.00077,0.0013,1,1
10090000,-0.28,0.019,-0.0058,0.96,-0.49,-0.23,-0.00087,-0.96,-0.5,-0.03,-0.00041,-0.0071,-0.00015,-0.00043,0.00029,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7e-05,0.0013,0.0012,0.00077,0.0013,1,1
10190000,-0.28,0.019,-0.0057,0.96,-0.49,-0.25,-3e-05,-0.97,-0.56,-0.031,-0.00028,-0.007,-0.00015,-0.00026,0.00016,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1
10290000,-0.28,0.019,-0.0057,0.96,-0.49,-0.25,-0.0012,-0.98,-0.57,-0.03,-0.00034,-0.0069,-0.00014,-0.00014,0.00022,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1
10390000,-0.28,0.019,-0.0056,0.96,0.0031,-0.0051,-0.0025,0.00058,-0.00014,-0.03,-0.00038,-0.0067,-0.00014,1.3e-05,0.00029,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1
10490000,-0.28,0.019,-0.0056,0.96,-0.01,-0.0085,0.0071,0.00025,-0.0008,-0.024,-0.00032,-0.0067,-0.00014,-0.00013,0.00023,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00051,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,6.8e-05,0.0013,0.0012,0.00076,0.0013,1,1
10590000,-0.28,0.019,-0.0055,0.96,-0.021,-0.0072,0.013,-0.0011,-0.00056,-0.022,-0.00041,-0.0066,-0.00013,0.00012,0.00058,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,6.8e-05,0.0013,0.0012,0.00076,0.0013,1,1
10690000,-0.28,0.019,-0.0054,0.96,-0.033,-0.0096,0.016,-0.0038,-0.0014,-0.018,-0.00039,-0.0065,-0.00013,0.00014,0.00056,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,6.8e-05,0.0013,0.0012,0.00076,0.0013,1,1
10790000,-0.28,0.019,-0.0053,0.96,-0.033,-0.013,0.014,0.00012,-0.0018,-0.016,-0.00042,-0.0064,-0.00013,0.002,2.8e-05,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,6.7e-05,0.0013,0.0012,0.00076,0.0013,1,1
10890000,-0.28,0.019,-0.0052,0.96,-0.043,-0.018,0.01,-0.0036,-0.0034,-0.019,-0.00054,-0.0063,-0.00012,0.0021,0.00017,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,6.7e-05,0.0013,0.0012,0.00076,0.0013,1,1
10990000,-0.28,0.019,-0.0052,0.96,-0.039,-0.021,0.016,-0.0014,-0.0019,-0.012,-0.00057,-0.0064,-0.00012,0.0058,0.00059,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00075,0.0013,1,1
11090000,-0.28,0.019,-0.0053,0.96,-0.05,-0.028,0.02,-0.0059,-0.0044,-0.0081,-0.00046,-0.0063,-0.00013,0.006,0.00059,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00075,0.0013,1,1
11190000,-0.28,0.018,-0.0054,0.96,-0.041,-0.025,0.027,-0.002,-0.0027,-0.0011,-0.00047,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00075,0.0013,1,1
11290000,-0.28,0.018,-0.0054,0.96,-0.05,-0.027,0.026,-0.0065,-0.0052,-0.00073,-0.00048,-0.0063,-0.00013,0.013,0.0014,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00075,0.0013,1,1
11390000,-0.28,0.018,-0.0053,0.96,-0.043,-0.023,0.017,-0.0037,-0.0033,-0.0092,-0.00053,-0.0063,-0.00013,0.019,0.0028,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00036,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00074,0.0013,1,1
11490000,-0.28,0.018,-0.0052,0.96,-0.05,-0.025,0.021,-0.0082,-0.0059,-0.003,-0.00054,-0.0063,-0.00012,0.019,0.003,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00036,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00074,0.0013,1,1
11590000,-0.28,0.018,-0.0053,0.96,-0.044,-0.021,0.019,-0.005,-0.0038,-0.0041,-0.00058,-0.0063,-0.00012,0.025,0.0041,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00031,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,6.5e-05,0.0013,0.0012,0.00074,0.0013,1,1
11690000,-0.28,0.017,-0.0053,0.96,-0.051,-0.025,0.019,-0.0097,-0.0061,-0.0053,-0.00062,-0.0063,-0.00012,0.024,0.0041,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00032,0.00032,0.052,0.088,0.088,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,6.5e-05,0.0013,0.0012,0.00074,0.0013,1,1
11790000,-0.28,0.017,-0.0052,0.96,-0.041,-0.025,0.02,-0.0056,-0.0054,-0.0023,-0.00071,-0.0063,-0.00012,0.03,0.0045,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,6.5e-05,0.0013,0.0012,0.00073,0.0013,1,1
11890000,-0.28,0.017,-0.0054,0.96,-0.049,-0.027,0.018,-0.01,-0.0079,-0.0016,-0.0007,-0.0063,-0.00012,0.03,0.0044,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,6.5e-05,0.0013,0.0012,0.00073,0.0013,1,1
11990000,-0.28,0.017,-0.0054,0.96,-0.039,-0.021,0.015,-0.0064,-0.0052,-0.0052,-0.00073,-0.0063,-0.00012,0.036,0.0065,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,6.5e-05,0.0013,0.0012,0.00073,0.0013,1,1
12090000,-0.28,0.017,-0.0053,0.96,-0.045,-0.022,0.018,-0.011,-0.0074,0.00087,-0.0007,-0.0062,-0.00012,0.037,0.0067,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,6.4e-05,0.0013,0.0012,0.00073,0.0013,1,1
12190000,-0.28,0.017,-0.0053,0.96,-0.038,-0.013,0.017,-0.0054,-0.0028,0.0028,-0.00066,-0.0062,-0.00012,0.042,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00072,0.0013,1,1
12290000,-0.28,0.017,-0.0054,0.96,-0.04,-0.011,0.016,-0.0094,-0.004,0.0038,-0.00064,-0.0062,-0.00012,0.043,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00072,0.0013,1,1
12390000,-0.28,0.016,-0.0054,0.96,-0.033,-0.0082,0.014,-0.0051,-0.0026,-0.0022,-0.00063,-0.0062,-0.00012,0.046,0.0086,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.012,0.013,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00072,0.0013,1,1
12490000,-0.28,0.016,-0.0054,0.96,-0.036,-0.0092,0.018,-0.0087,-0.0035,-0.00015,-0.00061,-0.0061,-0.00012,0.047,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.012,0.013,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00072,0.0013,1,1
12590000,-0.28,0.016,-0.0053,0.96,-0.03,-0.008,0.019,-0.0035,-0.0039,0.0017,-0.00062,-0.0061,-0.00012,0.05,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00071,0.0013,1,1
12690000,-0.28,0.016,-0.0053,0.96,-0.033,-0.0061,0.019,-0.0066,-0.0046,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
12790000,-0.28,0.016,-0.0051,0.96,-0.023,-0.012,0.02,-0.0016,-0.0076,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.0067,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.069,0,0,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.5e-06,7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
12890000,-0.28,0.016,-0.0051,0.96,-0.025,-0.012,0.021,-0.0039,-0.0089,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0071,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.069,0,0,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
12990000,-0.28,0.016,-0.0051,0.96,-0.021,-0.0096,0.022,-0.0012,-0.0062,0.0096,-0.00076,-0.0061,-0.00012,0.054,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
13090000,-0.28,0.016,-0.0051,0.96,-0.023,-0.011,0.019,-0.0033,-0.0075,0.0084,-0.0008,-0.006,-0.00011,0.054,0.0082,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.0079,0.0082,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
13190000,-0.28,0.016,-0.005,0.96,-0.019,-0.011,0.018,-0.0017,-0.0085,0.009,-0.00082,-0.006,-0.00011,0.055,0.0082,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
13290000,-0.28,0.016,-0.005,0.96,-0.02,-0.011,0.016,-0.0037,-0.0097,0.0083,-0.00081,-0.006,-0.00011,0.055,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0073,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0012,1,1
13390000,-0.28,0.016,-0.005,0.96,-0.017,-0.0081,0.015,-0.0014,-0.0067,0.0089,-0.00079,-0.006,-0.00011,0.057,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,9.9e-05,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.0007,0.0012,1,1
13490000,-0.28,0.016,-0.005,0.96,-0.019,-0.011,0.015,-0.0032,-0.0078,0.0051,-0.00079,-0.006,-0.00011,0.057,0.0087,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,0.0001,0.0001,0.051,0.053,0.053,0.009,0.068,0.068,0.045,5.6e-06,5.2e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
13590000,-0.28,0.016,-0.005,0.96,-0.014,-0.0072,0.016,0.0017,-0.0055,0.0036,-0.00077,-0.006,-0.00011,0.059,0.0088,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,9.2e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
13690000,-0.28,0.016,-0.0049,0.96,-0.015,-0.0064,0.016,0.00027,-0.0063,0.0062,-0.0008,-0.0059,-0.00011,0.059,0.0091,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,9.3e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0055,0.0058,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
13790000,-0.28,0.015,-0.0049,0.96,-0.011,-0.0044,0.016,0.0054,-0.0033,0.0057,-0.00079,-0.006,-0.00011,0.06,0.0089,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,8.7e-05,8.6e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.005,0.0053,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
13890000,-0.28,0.015,-0.0048,0.96,-0.012,-0.0055,0.017,0.0044,-0.0038,0.0078,-0.00083,-0.006,-0.00011,0.06,0.0091,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,8.8e-05,8.7e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.005,0.0053,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
13990000,-0.28,0.015,-0.0048,0.96,-0.014,-0.0093,0.016,0.0039,-0.0045,0.0067,-0.00085,-0.006,-0.00011,0.06,0.0095,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.07,0,0,8.3e-05,8.2e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
14090000,-0.28,0.015,-0.0049,0.96,-0.013,-0.0034,0.017,0.0023,-0.0048,0.0031,-0.00078,-0.006,-0.00011,0.061,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
14190000,-0.28,0.015,-0.005,0.96,-0.01,-0.0023,0.017,0.0036,-0.0038,0.0033,-0.00074,-0.0059,-0.00011,0.062,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
14290000,-0.28,0.015,-0.0049,0.96,-0.013,-0.0026,0.015,0.0025,-0.0041,0.0075,-0.00073,-0.0059,-0.00011,0.062,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0042,0.0045,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
14390000,-0.28,0.015,-0.0049,0.96,-0.012,-0.0022,0.017,0.0036,-0.0046,0.012,-0.00075,-0.0059,-0.00011,0.063,0.0088,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
14490000,-0.28,0.015,-0.0051,0.96,-0.012,-0.0015,0.02,0.0023,-0.0046,0.014,-0.00071,-0.0059,-0.00012,0.063,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
14590000,-0.28,0.015,-0.0051,0.96,-0.015,-0.0032,0.018,0.0007,-0.0051,0.01,-0.00069,-0.0059,-0.00012,0.064,0.0085,-0.14,-0.11,-0.024,0.5,0.083,-0.034,-0.07,0,0,7.4e-05,7.3e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
14690000,-0.28,0.015,-0.0051,0.96,-0.016,-0.0035,0.018,-0.00089,-0.0056,0.01,-0.0007,-0.0059,-0.00011,0.064,0.0088,-0.14,-0.11,-0.024,0.5,0.083,-0.034,-0.07,0,0,7.5e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
14790000,-0.28,0.015,-0.0052,0.96,-0.019,-0.00093,0.018,-0.00059,-0.0012,0.013,-0.00073,-0.0058,-0.00011,0.065,0.01,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
14890000,-0.28,0.015,-0.0051,0.96,-0.02,0.00099,0.022,-0.0027,-0.0015,0.014,-0.00074,-0.0058,-0.00011,0.065,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.3e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
14990000,-0.28,0.015,-0.0051,0.96,-0.02,-0.001,0.025,-0.0022,-0.0027,0.016,-0.00074,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.1e-05,6.9e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0033,0.0036,0.00044,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15090000,-0.28,0.015,-0.005,0.96,-0.021,-0.0021,0.029,-0.0043,-0.0028,0.018,-0.00075,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15190000,-0.28,0.016,-0.0052,0.96,-0.021,-0.00028,0.029,-0.0034,-0.0022,0.02,-0.00073,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0034,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15290000,-0.28,0.016,-0.0052,0.96,-0.024,-0.00035,0.029,-0.0059,-0.0026,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.8e-06,2.2e-06,0.0032,0.0034,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15390000,-0.28,0.016,-0.0053,0.96,-0.023,-0.0023,0.028,-0.0046,-0.0022,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15490000,-0.28,0.016,-0.0053,0.96,-0.025,0.00021,0.028,-0.007,-0.0024,0.018,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.003,0.0033,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15590000,-0.28,0.016,-0.0053,0.96,-0.022,-0.0041,0.028,-0.0033,-0.0056,0.017,-0.00079,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15690000,-0.28,0.016,-0.0052,0.96,-0.024,-0.0021,0.028,-0.0049,-0.0059,0.018,-0.00083,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15790000,-0.28,0.015,-0.0052,0.96,-0.021,-0.00088,0.028,-0.0035,-0.0051,0.019,-0.00087,-0.0058,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15890000,-0.28,0.016,-0.0053,0.96,-0.021,-0.0021,0.029,-0.0059,-0.005,0.019,-0.00084,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
15990000,-0.28,0.015,-0.0052,0.96,-0.02,-0.0017,0.026,-0.0049,-0.0043,0.018,-0.00083,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
16090000,-0.28,0.016,-0.0052,0.96,-0.022,-0.00036,0.024,-0.0072,-0.0042,0.018,-0.00082,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.3e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
16190000,-0.28,0.016,-0.0052,0.96,-0.02,-0.0002,0.023,-0.0071,-0.0035,0.015,-0.0008,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
16290000,-0.28,0.015,-0.0052,0.96,-0.022,0.00077,0.022,-0.009,-0.0035,0.016,-0.00081,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00042,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
16390000,-0.28,0.015,-0.0051,0.96,-0.023,0.00023,0.023,-0.007,-0.0034,0.017,-0.00082,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
16490000,-0.28,0.016,-0.0052,0.96,-0.027,0.0013,0.025,-0.0098,-0.0033,0.021,-0.00081,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
16590000,-0.28,0.016,-0.0052,0.96,-0.031,0.0017,0.029,-0.0085,-0.0028,0.021,-0.00082,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
16690000,-0.28,0.015,-0.0053,0.96,-0.034,0.0053,0.029,-0.011,-0.0026,0.021,-0.00084,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
16790000,-0.28,0.015,-0.0051,0.96,-0.035,0.005,0.028,-0.0096,-0.0024,0.021,-0.00086,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
16890000,-0.28,0.015,-0.005,0.96,-0.035,0.0046,0.029,-0.013,-0.0023,0.02,-0.00089,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
16990000,-0.28,0.015,-0.0051,0.96,-0.032,0.005,0.029,-0.011,-0.0025,0.019,-0.0009,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0024,0.0027,0.0004,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
17090000,-0.28,0.015,-0.0052,0.96,-0.037,0.007,0.028,-0.015,-0.0019,0.018,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
17190000,-0.28,0.015,-0.0053,0.96,-0.036,0.0088,0.03,-0.014,-0.0036,0.021,-0.00089,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
17290000,-0.28,0.015,-0.0053,0.96,-0.039,0.0095,0.029,-0.017,-0.0023,0.021,-0.00087,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00039,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
17390000,-0.28,0.015,-0.0052,0.96,-0.029,0.014,0.029,-0.01,-0.001,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
17490000,-0.28,0.015,-0.0053,0.96,-0.029,0.016,0.029,-0.013,0.00056,0.023,-0.0009,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0023,0.0026,0.00038,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
17590000,-0.28,0.015,-0.0053,0.96,-0.029,0.014,0.028,-0.012,0.0001,0.02,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.7e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
17690000,-0.28,0.015,-0.0054,0.96,-0.03,0.014,0.029,-0.015,0.0013,0.023,-0.00092,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
17790000,-0.28,0.015,-0.0054,0.96,-0.031,0.014,0.029,-0.015,0.0021,0.028,-0.00093,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
17890000,-0.28,0.015,-0.0053,0.96,-0.034,0.016,0.029,-0.017,0.0033,0.032,-0.00094,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
17990000,-0.28,0.015,-0.0053,0.96,-0.034,0.016,0.029,-0.014,0.0055,0.033,-0.00094,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0022,0.0025,0.00036,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18090000,-0.28,0.015,-0.0054,0.96,-0.035,0.017,0.028,-0.018,0.0071,0.031,-0.00094,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18190000,-0.28,0.015,-0.0053,0.96,-0.032,0.015,0.028,-0.013,0.0048,0.029,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18290000,-0.28,0.015,-0.0053,0.96,-0.036,0.015,0.027,-0.017,0.006,0.028,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18390000,-0.28,0.015,-0.0052,0.96,-0.032,0.014,0.027,-0.012,0.005,0.027,-0.00099,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0024,0.00034,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18490000,-0.28,0.015,-0.0052,0.96,-0.036,0.013,0.026,-0.015,0.006,0.029,-0.001,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.5e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18590000,-0.28,0.015,-0.0051,0.96,-0.034,0.013,0.026,-0.013,0.0053,0.031,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18690000,-0.28,0.015,-0.0051,0.96,-0.034,0.012,0.024,-0.015,0.0063,0.03,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18790000,-0.28,0.015,-0.0051,0.96,-0.031,0.012,0.024,-0.012,0.0054,0.028,-0.001,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0021,0.0024,0.00032,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18890000,-0.28,0.015,-0.005,0.96,-0.031,0.012,0.022,-0.015,0.0067,0.024,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
18990000,-0.28,0.015,-0.005,0.96,-0.029,0.013,0.023,-0.013,0.0058,0.027,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
19090000,-0.28,0.015,-0.005,0.96,-0.028,0.013,0.023,-0.016,0.0066,0.024,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.05,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
19190000,-0.28,0.015,-0.005,0.96,-0.026,0.014,0.023,-0.014,0.0065,0.023,-0.0011,-0.0058,-0.00012,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
19290000,-0.28,0.015,-0.0049,0.96,-0.027,0.014,0.024,-0.016,0.0078,0.022,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
19390000,-0.28,0.015,-0.0051,0.96,-0.025,0.013,0.025,-0.014,0.0076,0.021,-0.0011,-0.0058,-0.00012,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
19490000,-0.28,0.015,-0.0052,0.96,-0.028,0.014,0.024,-0.018,0.0091,0.021,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
19590000,-0.28,0.015,-0.005,0.96,-0.024,0.015,0.026,-0.015,0.0073,0.021,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
19690000,-0.28,0.015,-0.005,0.96,-0.025,0.013,0.025,-0.018,0.0081,0.02,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
19790000,-0.28,0.015,-0.0051,0.96,-0.022,0.013,0.023,-0.018,0.0088,0.017,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
19890000,-0.28,0.015,-0.0052,0.96,-0.023,0.013,0.023,-0.02,0.01,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
19990000,-0.28,0.015,-0.0052,0.96,-0.02,0.014,0.021,-0.015,0.0093,0.012,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,5.9e-05,0.0012,0.0012,0.00067,0.0012,1,1
20090000,-0.28,0.015,-0.0052,0.96,-0.023,0.017,0.021,-0.018,0.011,0.015,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,5.9e-05,0.0012,0.0012,0.00067,0.0012,1,1
20190000,-0.28,0.015,-0.0052,0.96,-0.023,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,5.9e-05,0.0012,0.0012,0.00067,0.0012,1,1
20290000,-0.28,0.015,-0.0052,0.96,-0.022,0.017,0.022,-0.021,0.013,0.016,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,5.9e-05,0.0012,0.0012,0.00067,0.0012,1,1
20390000,-0.28,0.015,-0.0051,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
20490000,-0.28,0.015,-0.0051,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
20590000,-0.28,0.015,-0.005,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.3e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
20690000,-0.28,0.015,-0.0049,0.96,-0.017,0.017,0.023,-0.024,0.014,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
20790000,-0.28,0.015,-0.0043,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
20890000,-0.29,0.01,0.0044,0.96,-0.0062,0.0017,-0.11,-0.02,0.011,0.0065,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
20990000,-0.29,0.0064,0.0073,0.96,0.0087,-0.015,-0.25,-0.017,0.0083,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
21090000,-0.29,0.0069,0.0058,0.96,0.022,-0.028,-0.37,-0.015,0.0064,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.8e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
21190000,-0.29,0.0088,0.0032,0.96,0.028,-0.034,-0.5,-0.013,0.0048,-0.076,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
21290000,-0.29,0.01,0.0011,0.96,0.027,-0.036,-0.63,-0.01,0.0022,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
21390000,-0.29,0.011,-0.00034,0.96,0.021,-0.029,-0.75,-0.012,0.0054,-0.2,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
21490000,-0.29,0.012,-0.0011,0.96,0.014,-0.028,-0.89,-0.0097,0.0023,-0.28,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
21590000,-0.29,0.012,-0.0016,0.96,0.0024,-0.022,-1,-0.014,0.0069,-0.37,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
21690000,-0.29,0.012,-0.0019,0.96,-0.0028,-0.019,-1.1,-0.014,0.0042,-0.49,-0.0011,-0.0058,-0.00011,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,5.8e-05,0.0012,0.0011,0.00067,0.0012,1,1
21790000,-0.29,0.012,-0.0023,0.96,-0.0086,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,5.8e-05,0.0012,0.0011,0.00067,0.0012,1,1
21890000,-0.29,0.012,-0.0026,0.96,-0.014,-0.007,-1.4,-0.016,0.0099,-0.75,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
21990000,-0.29,0.012,-0.0033,0.96,-0.02,0.0012,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22090000,-0.29,0.013,-0.004,0.96,-0.023,0.0045,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22190000,-0.29,0.013,-0.0044,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0021,0.00019,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22290000,-0.29,0.014,-0.0051,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22390000,-0.29,0.014,-0.0054,0.96,-0.045,0.023,-1.4,-0.038,0.03,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22490000,-0.29,0.014,-0.0055,0.96,-0.052,0.029,-1.4,-0.043,0.033,-1.6,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22590000,-0.29,0.015,-0.0054,0.96,-0.056,0.035,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22690000,-0.29,0.015,-0.0053,0.96,-0.061,0.04,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22790000,-0.29,0.016,-0.0052,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22890000,-0.29,0.016,-0.0053,0.96,-0.073,0.049,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
22990000,-0.29,0.016,-0.0051,0.96,-0.076,0.049,-1.4,-0.066,0.045,-2.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23090000,-0.29,0.017,-0.0051,0.96,-0.082,0.053,-1.4,-0.073,0.05,-2.5,-0.0011,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.049,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23190000,-0.29,0.017,-0.005,0.96,-0.083,0.048,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23290000,-0.29,0.017,-0.0055,0.96,-0.09,0.052,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23390000,-0.28,0.017,-0.0054,0.96,-0.089,0.055,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.9e-05,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23490000,-0.28,0.017,-0.0055,0.96,-0.096,0.055,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23590000,-0.29,0.017,-0.0056,0.96,-0.094,0.049,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23690000,-0.29,0.018,-0.0062,0.96,-0.093,0.052,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.3e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23790000,-0.29,0.021,-0.0077,0.96,-0.079,0.049,-0.95,-0.08,0.048,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23890000,-0.29,0.025,-0.011,0.96,-0.073,0.052,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
23990000,-0.29,0.028,-0.012,0.96,-0.064,0.051,-0.13,-0.074,0.047,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
24090000,-0.29,0.027,-0.012,0.96,-0.071,0.059,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
24190000,-0.29,0.022,-0.0094,0.96,-0.075,0.055,0.088,-0.067,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
24290000,-0.29,0.019,-0.0074,0.96,-0.08,0.057,0.066,-0.074,0.045,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
24390000,-0.29,0.018,-0.0065,0.96,-0.064,0.051,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
24490000,-0.29,0.018,-0.0067,0.96,-0.058,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
24590000,-0.29,0.018,-0.0073,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
24690000,-0.29,0.018,-0.0078,0.96,-0.045,0.045,0.075,-0.047,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
24790000,-0.29,0.017,-0.0079,0.96,-0.038,0.043,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.1e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
24890000,-0.29,0.017,-0.0078,0.96,-0.037,0.046,0.056,-0.038,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
24990000,-0.29,0.016,-0.0076,0.96,-0.025,0.046,0.049,-0.023,0.027,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25090000,-0.29,0.016,-0.0079,0.96,-0.02,0.046,0.047,-0.024,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25190000,-0.29,0.016,-0.0081,0.96,-0.01,0.042,0.047,-0.0082,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25290000,-0.29,0.015,-0.0083,0.96,-0.0055,0.045,0.042,-0.0088,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25390000,-0.29,0.015,-0.0084,0.96,0.0035,0.043,0.04,0.0011,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25490000,-0.29,0.015,-0.0085,0.96,0.0079,0.044,0.04,0.00085,0.025,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25590000,-0.29,0.015,-0.0086,0.96,0.013,0.04,0.041,0.0083,0.01,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25690000,-0.29,0.014,-0.0081,0.96,0.014,0.039,0.03,0.0097,0.014,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25790000,-0.29,0.014,-0.008,0.96,0.024,0.034,0.03,0.017,0.0038,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25890000,-0.29,0.014,-0.008,0.96,0.03,0.034,0.033,0.02,0.008,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
25990000,-0.29,0.014,-0.008,0.96,0.033,0.029,0.026,0.017,-0.0032,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
26090000,-0.29,0.014,-0.0077,0.96,0.038,0.029,0.025,0.02,-0.0011,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
26190000,-0.29,0.014,-0.0075,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
26290000,-0.29,0.015,-0.0075,0.96,0.043,0.019,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
26390000,-0.29,0.015,-0.0069,0.96,0.04,0.01,0.019,0.019,-0.029,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
26490000,-0.29,0.015,-0.0067,0.96,0.043,0.0084,0.028,0.023,-0.028,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
26590000,-0.29,0.015,-0.0061,0.96,0.042,-0.0016,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
26690000,-0.29,0.015,-0.006,0.96,0.044,-0.0052,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
26790000,-0.29,0.014,-0.0058,0.96,0.047,-0.011,0.026,0.024,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
26890000,-0.29,0.014,-0.0052,0.96,0.053,-0.014,0.022,0.029,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
26990000,-0.29,0.014,-0.0046,0.96,0.054,-0.02,0.021,0.022,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27090000,-0.29,0.015,-0.0044,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27190000,-0.29,0.015,-0.0045,0.96,0.057,-0.031,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27290000,-0.29,0.016,-0.0045,0.96,0.064,-0.034,0.14,0.024,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27390000,-0.29,0.018,-0.0057,0.96,0.067,-0.026,0.46,0.0069,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27490000,-0.29,0.02,-0.0069,0.96,0.072,-0.029,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27590000,-0.29,0.019,-0.0069,0.96,0.063,-0.031,0.87,0.0076,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27690000,-0.29,0.016,-0.006,0.96,0.057,-0.028,0.78,0.014,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27790000,-0.29,0.015,-0.0048,0.96,0.054,-0.027,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27890000,-0.29,0.015,-0.0045,0.96,0.06,-0.032,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
27990000,-0.29,0.015,-0.0048,0.96,0.061,-0.035,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28090000,-0.29,0.015,-0.0051,0.96,0.064,-0.035,0.8,0.026,-0.028,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28190000,-0.29,0.015,-0.0045,0.96,0.062,-0.034,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28290000,-0.29,0.016,-0.0039,0.96,0.066,-0.037,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28390000,-0.29,0.016,-0.0039,0.96,0.067,-0.039,0.81,0.035,-0.035,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28490000,-0.29,0.017,-0.0041,0.96,0.07,-0.042,0.81,0.042,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28590000,-0.29,0.017,-0.0041,0.96,0.063,-0.043,0.81,0.043,-0.042,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28690000,-0.29,0.016,-0.004,0.96,0.062,-0.044,0.81,0.049,-0.046,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28790000,-0.29,0.016,-0.0034,0.96,0.06,-0.043,0.81,0.05,-0.045,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28890000,-0.29,0.015,-0.0032,0.96,0.063,-0.045,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
28990000,-0.29,0.016,-0.0029,0.96,0.062,-0.043,0.81,0.057,-0.049,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29090000,-0.29,0.016,-0.0028,0.96,0.065,-0.044,0.81,0.065,-0.054,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29190000,-0.29,0.016,-0.0027,0.96,0.066,-0.043,0.8,0.066,-0.053,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29290000,-0.29,0.016,-0.0029,0.96,0.07,-0.049,0.81,0.075,-0.057,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29390000,-0.29,0.015,-0.0035,0.96,0.067,-0.046,0.81,0.073,-0.054,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29490000,-0.29,0.015,-0.0034,0.96,0.07,-0.047,0.81,0.081,-0.06,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29590000,-0.29,0.015,-0.0033,0.96,0.067,-0.046,0.81,0.079,-0.058,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29690000,-0.29,0.015,-0.0034,0.96,0.072,-0.045,0.81,0.087,-0.063,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29790000,-0.29,0.015,-0.0031,0.96,0.069,-0.039,0.8,0.084,-0.06,-1.7,-0.0013,-0.0058,-9.8e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29890000,-0.29,0.015,-0.0025,0.96,0.071,-0.04,0.8,0.092,-0.064,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
29990000,-0.29,0.016,-0.0027,0.96,0.065,-0.038,0.8,0.086,-0.063,-1.6,-0.0013,-0.0058,-8.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
30090000,-0.29,0.016,-0.0028,0.96,0.067,-0.038,0.8,0.094,-0.065,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
30190000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.088,-0.057,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
30290000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.096,-0.06,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
30390000,-0.29,0.015,-0.0028,0.96,0.06,-0.026,0.8,0.095,-0.054,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
30490000,-0.29,0.015,-0.0028,0.96,0.063,-0.026,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
30590000,-0.29,0.016,-0.0031,0.96,0.062,-0.025,0.8,0.097,-0.054,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
30690000,-0.29,0.016,-0.0034,0.96,0.059,-0.024,0.8,0.1,-0.057,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
30790000,-0.29,0.016,-0.0032,0.96,0.053,-0.014,0.79,0.096,-0.045,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
30890000,-0.29,0.015,-0.0026,0.96,0.051,-0.011,0.79,0.1,-0.046,-0.95,-0.0012,-0.0058,-4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
30990000,-0.29,0.015,-0.0027,0.96,0.047,-0.0093,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31090000,-0.29,0.015,-0.0029,0.96,0.046,-0.008,0.79,0.099,-0.045,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31190000,-0.29,0.016,-0.003,0.96,0.043,-0.0048,0.8,0.093,-0.041,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31290000,-0.29,0.016,-0.0032,0.96,0.04,-0.0032,0.8,0.097,-0.042,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31390000,-0.29,0.015,-0.003,0.96,0.036,0.0017,0.8,0.091,-0.038,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31490000,-0.29,0.016,-0.0027,0.96,0.037,0.0051,0.8,0.096,-0.037,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31590000,-0.29,0.016,-0.0025,0.96,0.037,0.0069,0.8,0.093,-0.034,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31690000,-0.29,0.016,-0.0025,0.96,0.041,0.0079,0.8,0.098,-0.033,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31790000,-0.29,0.017,-0.0027,0.96,0.035,0.013,0.8,0.094,-0.024,-0.3,-0.0012,-0.0058,-6.2e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31890000,-0.29,0.017,-0.0024,0.96,0.034,0.015,0.8,0.099,-0.022,-0.24,-0.0012,-0.0058,1.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
31990000,-0.29,0.016,-0.0027,0.96,0.03,0.016,0.79,0.095,-0.017,-0.17,-0.0012,-0.0058,9.2e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
32090000,-0.29,0.016,-0.0032,0.96,0.031,0.02,0.8,0.099,-0.015,-0.096,-0.0012,-0.0058,4.9e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
32190000,-0.28,0.016,-0.0034,0.96,0.028,0.027,0.8,0.094,-0.0059,-0.028,-0.0012,-0.0058,3.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
32290000,-0.28,0.016,-0.0033,0.96,0.028,0.03,0.79,0.098,-0.0032,0.042,-0.0012,-0.0058,7.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
32390000,-0.28,0.016,-0.0034,0.96,0.025,0.032,0.79,0.094,0.00049,0.12,-0.0012,-0.0058,5.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
32490000,-0.28,0.015,-0.0065,0.96,-0.015,0.085,-0.078,0.092,0.0082,0.12,-0.0012,-0.0058,3.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
32590000,-0.29,0.015,-0.0065,0.96,-0.013,0.084,-0.081,0.092,0.0012,0.1,-0.0012,-0.0058,-1.7e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
32690000,-0.29,0.015,-0.0065,0.96,-0.0086,0.091,-0.082,0.091,0.01,0.087,-0.0012,-0.0058,-1.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
32790000,-0.29,0.015,-0.0063,0.96,-0.0047,0.09,-0.083,0.093,0.0025,0.072,-0.0012,-0.0058,-7.2e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
32890000,-0.29,0.015,-0.0063,0.96,-0.0051,0.096,-0.085,0.091,0.011,0.057,-0.0012,-0.0058,-2.7e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
32990000,-0.29,0.015,-0.0062,0.96,-0.0013,0.091,-0.084,0.092,-0.0018,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33090000,-0.29,0.015,-0.0061,0.96,0.0026,0.097,-0.081,0.092,0.0075,0.036,-0.0013,-0.0058,-9.7e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33190000,-0.29,0.015,-0.0061,0.96,0.0067,0.093,-0.08,0.092,-0.0072,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33290000,-0.29,0.015,-0.0061,0.96,0.011,0.096,-0.08,0.094,0.0016,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33390000,-0.29,0.015,-0.006,0.96,0.015,0.092,-0.078,0.093,-0.0066,0.011,-0.0013,-0.0058,-2.6e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33490000,-0.29,0.015,-0.006,0.96,0.021,0.097,-0.077,0.097,0.0027,0.0017,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33590000,-0.29,0.014,-0.0058,0.96,0.024,0.094,-0.074,0.096,-0.01,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33690000,-0.29,0.015,-0.0058,0.96,0.027,0.098,-0.075,0.097,-0.0012,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33790000,-0.29,0.015,-0.0058,0.96,0.029,0.095,-0.069,0.093,-0.014,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33890000,-0.29,0.014,-0.0057,0.96,0.034,0.097,-0.069,0.097,-0.0053,-0.028,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
33990000,-0.29,0.015,-0.0056,0.96,0.036,0.095,-0.065,0.095,-0.013,-0.032,-0.0013,-0.0057,-3.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
34090000,-0.29,0.015,-0.0056,0.96,0.039,0.1,-0.064,0.098,-0.004,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
34190000,-0.29,0.015,-0.0055,0.96,0.041,0.097,-0.061,0.093,-0.016,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
34290000,-0.29,0.015,-0.0054,0.96,0.042,0.1,-0.06,0.098,-0.006,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
34390000,-0.29,0.015,-0.0053,0.96,0.043,0.097,-0.055,0.093,-0.017,-0.049,-0.0013,-0.0057,-3.9e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
34490000,-0.29,0.015,-0.0053,0.96,0.046,0.1,-0.053,0.097,-0.0081,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.085,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
34590000,-0.29,0.014,-0.0052,0.96,0.046,0.097,0.74,0.092,-0.022,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
34690000,-0.29,0.014,-0.0052,0.96,0.051,0.1,1.7,0.097,-0.012,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
34790000,-0.29,0.014,-0.0052,0.96,0.053,0.098,2.7,0.09,-0.026,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
34890000,-0.29,0.014,-0.0052,0.96,0.057,0.1,3.7,0.096,-0.016,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1

1 Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
2 10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3 90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4 190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00094,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5 290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6 390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
7 490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8 590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9 690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10 790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.00077,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11 890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00054,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00051,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
12 990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,5e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00066,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,4.9e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00062,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13 1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.9e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.8e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00043,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14 1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.7e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00056,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.6e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00051,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15 1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16 1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00049,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17 1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.3e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.1e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18 1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.3e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.2e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19 1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-7.7e-08,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.5e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20 1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3.3e-08,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00039,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3e-07,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21 1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-7e-09,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.7e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22 1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.1e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00035,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.7e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23 2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00039,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3.5e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24 2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-7.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-8.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25 2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-7.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26 2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.3e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.5e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27 2490000,1,-0.011,-0.014,0.00047,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.3e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2490000,1,-0.011,-0.014,0.00048,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.5e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28 2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-1.9e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-2.1e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29 2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-1.8e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30 2790000,1,-0.01,-0.013,0.00037,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2790000,1,-0.01,-0.013,0.00038,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31 2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.6e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32 2990000,1,-0.01,-0.013,0.00031,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-2.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2990000,1,-0.01,-0.013,0.00032,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-3.1e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33 3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-2.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-3.1e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34 3190000,1,-0.01,-0.013,0.00056,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.2e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00021,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,3.4e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3190000,1,-0.01,-0.013,0.00057,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
35 3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.2e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,3.4e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.5e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
36 3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,2.9e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
37 3490000,1,-0.0097,-0.013,0.00058,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,2.9e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3490000,1,-0.0097,-0.013,0.00059,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
38 3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.007,0.0071,0.00018,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,2.5e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
39 3690000,1,-0.0095,-0.013,0.00052,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,2.5e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3690000,1,-0.0095,-0.013,0.00053,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-4.3e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
40 3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.3e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00017,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.8e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
41 3890000,1,-0.0094,-0.013,0.00063,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3890000,1,-0.0094,-0.013,0.00064,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
42 3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,2.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
43 4090000,1,-0.0093,-0.012,0.00076,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-4.8e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1.9e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4090000,1,-0.0093,-0.012,0.00077,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-5.2e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
44 4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-4.8e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00018,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1.9e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-5.2e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
45 4290000,1,-0.0095,-0.012,0.00074,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.3e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,1.7e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4290000,1,-0.0095,-0.012,0.00075,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.7e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
46 4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,1.7e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.7e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
47 4490000,1,-0.0094,-0.012,0.00076,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-5.7e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,1.5e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4490000,1,-0.0094,-0.012,0.00077,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-6.2e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
48 4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-5.7e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00016,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,1.5e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-6.2e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
49 4690000,1,-0.0094,-0.012,0.00076,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.1e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4690000,1,-0.0094,-0.012,0.00077,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.6e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
50 4790000,1,-0.0093,-0.012,0.00086,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.1e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4790000,1,-0.0093,-0.012,0.00087,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.6e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
51 4890000,1,-0.0092,-0.012,0.0009,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-6.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4890000,1,-0.0092,-0.012,0.00091,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-7e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
52 4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-6.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-7e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
53 5090000,1,-0.0091,-0.011,0.00096,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-6.8e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5090000,1,-0.0091,-0.011,0.00097,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-7.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
54 5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-6.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-7.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
55 5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.3e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
56 5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,9.3e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
57 5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00013,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.4e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
58 5590000,1,-0.0088,-0.012,0.00099,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.4e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
59 5690000,1,-0.0089,-0.011,0.00089,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.6e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5690000,1,-0.0089,-0.011,0.0009,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
60 5790000,1,-0.0088,-0.011,0.00085,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.6e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5790000,1,-0.0088,-0.011,0.00086,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
61 5890000,1,-0.0088,-0.011,0.00088,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5890000,1,-0.0088,-0.011,0.00089,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
62 5990000,1,-0.0088,-0.012,0.00086,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5990000,1,-0.0088,-0.012,0.00087,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
63 6090000,1,-0.0088,-0.011,0.00067,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6090000,1,-0.0088,-0.011,0.00068,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
64 6190000,1,-0.0089,-0.011,0.00068,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6190000,1,-0.0089,-0.011,0.00069,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
65 6290000,1,-0.0089,-0.011,0.00071,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6290000,1,-0.0089,-0.011,0.00072,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
66 6390000,1,-0.0089,-0.011,0.00072,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6390000,1,-0.0089,-0.011,0.00073,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
67 6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6490000,1,-0.0089,-0.011,0.00063,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.8e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
68 6590000,1,-0.009,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6590000,1,-0.009,-0.011,0.00056,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
69 6690000,1,-0.0089,-0.011,0.0005,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6690000,1,-0.0089,-0.011,0.00052,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
70 6790000,1,-0.009,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6790000,1,-0.009,-0.011,0.00048,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
71 6890000,1,-0.0088,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6890000,1,-0.0088,-0.011,0.0004,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
72 6990000,-0.29,0.024,-0.0065,0.96,-0.0055,0.0091,-0.037,0.0023,0.0053,-0.055,-0.0016,-0.0056,-8.7e-05,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0012,0.0012,0.072,0.16,0.16,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1 6990000,-0.29,0.024,-0.0063,0.96,-0.2,-0.03,-0.037,-0.11,-0.017,-0.055,-0.00076,-0.0097,-0.0002,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1
73 7090000,-0.28,0.025,-0.0064,0.96,-0.026,-0.00083,-0.037,0.0022,0.0052,-0.056,-0.0015,-0.0055,-8.7e-05,0,0,-0.13,-0.099,-0.021,0.51,0.075,-0.029,-0.065,0,0,0.0012,0.0012,0.058,0.16,0.16,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00099,0.0013,1,1 7090000,-0.28,0.025,-0.0064,0.96,-0.24,-0.045,-0.038,-0.15,-0.025,-0.056,-0.00064,-0.01,-0.00021,0,0,-0.13,-0.099,-0.022,0.51,0.075,-0.029,-0.065,0,0,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1
74 7190000,-0.28,0.026,-0.0064,0.96,-0.047,-0.0082,-0.036,0.00063,0.0038,-0.058,-0.0015,-0.0055,-8.6e-05,3.9e-05,-1e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.054,0.17,0.17,0.029,0.16,0.16,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.00094,0.0013,1,1 7190000,-0.28,0.025,-0.0064,0.96,-0.26,-0.053,-0.037,-0.17,-0.031,-0.059,-0.0006,-0.01,-0.00021,-0.00035,-7.2e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1
75 7290000,-0.28,0.026,-0.0064,0.96,-0.07,-0.017,-0.033,-0.0034,0.0023,-0.054,-0.0015,-0.0054,-8.5e-05,0.00011,-5e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.053,0.18,0.18,0.028,0.19,0.19,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00093,0.0013,1,1 7290000,-0.28,0.025,-0.0065,0.96,-0.29,-0.062,-0.034,-0.2,-0.038,-0.055,-0.00059,-0.01,-0.00021,-0.00088,-0.00017,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1
76 7390000,-0.28,0.026,-0.0062,0.96,-0.091,-0.024,-0.031,-0.0098,-8.5e-05,-0.052,-0.0015,-0.0054,-8.4e-05,0.00016,-4e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.052,0.19,0.19,0.027,0.22,0.22,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00092,0.0013,1,1 7390000,-0.28,0.024,-0.0064,0.96,-0.3,-0.068,-0.032,-0.23,-0.044,-0.052,-0.00058,-0.01,-0.00021,-0.0011,-0.00021,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00086,0.0013,1,1
77 7490000,-0.28,0.026,-0.0062,0.96,-0.11,-0.032,-0.025,-0.015,-0.0034,-0.046,-0.0015,-0.0053,-8.1e-05,0.00033,7.2e-07,-0.13,-0.1,-0.022,0.5,0.077,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.2,0.2,0.026,0.26,0.26,0.063,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00091,0.0013,1,1 7490000,-0.28,0.024,-0.0065,0.96,-0.32,-0.075,-0.026,-0.26,-0.052,-0.046,-0.00057,-0.0099,-0.00021,-0.0015,-0.00025,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1
78 7590000,-0.28,0.026,-0.0063,0.96,-0.13,-0.041,-0.021,-0.024,-0.0083,-0.04,-0.0015,-0.0052,-8e-05,0.00045,-2.7e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.22,0.21,0.025,0.3,0.3,0.062,6.6e-05,6.5e-05,4.6e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00091,0.0013,1,1 7590000,-0.28,0.024,-0.0066,0.96,-0.34,-0.082,-0.022,-0.28,-0.061,-0.041,-0.00055,-0.0098,-0.00021,-0.0016,-0.00021,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00085,0.0013,1,1
79 7690000,-0.28,0.026,-0.0063,0.96,-0.16,-0.051,-0.02,-0.034,-0.015,-0.036,-0.0014,-0.0051,-7.9e-05,0.00056,-6.8e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.23,0.23,0.025,0.34,0.34,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.0009,0.0013,1,1 7690000,-0.28,0.024,-0.0066,0.96,-0.35,-0.091,-0.022,-0.31,-0.071,-0.036,-0.00053,-0.0097,-0.00021,-0.0017,-0.00019,-0.13,-0.1,-0.022,0.5,0.079,-0.031,-0.068,0,0,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.00084,0.0013,1,1
80 7790000,-0.28,0.026,-0.0062,0.96,-0.18,-0.061,-0.022,-0.041,-0.025,-0.041,-0.0014,-0.005,-7.8e-05,0.00088,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.26,0.25,0.024,0.39,0.39,0.061,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.0009,0.0013,1,1 7790000,-0.28,0.023,-0.0064,0.96,-0.36,-0.1,-0.024,-0.34,-0.085,-0.041,-0.00046,-0.0096,-0.0002,-0.0017,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.00084,0.0013,1,1
81 7890000,-0.28,0.026,-0.0062,0.96,-0.2,-0.071,-0.022,-0.057,-0.033,-0.044,-0.0013,-0.0049,-7.7e-05,0.00099,-0.00028,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.28,0.28,0.023,0.45,0.45,0.06,6.4e-05,6.4e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.0009,0.0013,1,1 7890000,-0.28,0.023,-0.0065,0.96,-0.37,-0.11,-0.025,-0.37,-0.097,-0.045,-0.00044,-0.0095,-0.0002,-0.0016,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00085,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.00083,0.0013,1,1
82 7990000,-0.28,0.026,-0.0061,0.96,-0.22,-0.078,-0.018,-0.08,-0.039,-0.04,-0.0013,-0.0049,-7.7e-05,0.00089,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.3,0.3,0.022,0.51,0.51,0.059,6.3e-05,6.3e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0013,0.0009,0.0013,1,1 7990000,-0.28,0.023,-0.0065,0.96,-0.39,-0.11,-0.021,-0.4,-0.11,-0.041,-0.00047,-0.0094,-0.0002,-0.0016,-0.00017,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0012,0.00083,0.0013,1,1
83 8090000,-0.28,0.026,-0.006,0.96,-0.25,-0.09,-0.019,-0.1,-0.053,-0.043,-0.0013,-0.0049,-8e-05,0.00093,-0.00038,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.33,0.33,0.022,0.57,0.57,0.059,6.2e-05,6.2e-05,4.6e-06,0.04,0.04,0.0014,0.0013,8.9e-05,0.0013,0.0013,0.0009,0.0013,1,1 8090000,-0.28,0.023,-0.0064,0.96,-0.41,-0.12,-0.022,-0.44,-0.12,-0.044,-0.0004,-0.0094,-0.0002,-0.0016,-0.00022,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.0008,0.00082,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,8.8e-05,0.0013,0.0012,0.00083,0.0013,1,1
84 8190000,-0.28,0.026,-0.0061,0.96,-0.27,-0.1,-0.014,-0.12,-0.069,-0.036,-0.0012,-0.0048,-8.2e-05,0.00096,-0.0005,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.36,0.36,0.021,0.64,0.64,0.058,6.1e-05,6.1e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.7e-05,0.0013,0.0013,0.0009,0.0013,1,1 8190000,-0.28,0.022,-0.0064,0.96,-0.41,-0.14,-0.017,-0.46,-0.14,-0.038,-0.00033,-0.0092,-0.0002,-0.0016,-0.00023,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00077,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0013,8.6e-05,0.0013,0.0012,0.00082,0.0013,1,1
85 8290000,-0.28,0.026,-0.0061,0.96,-0.3,-0.11,-0.013,-0.16,-0.077,-0.036,-0.0012,-0.005,-8.4e-05,0.0007,-0.00042,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.4,0.39,0.02,0.72,0.72,0.057,6e-05,6e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.5e-05,0.0013,0.0013,0.0009,0.0013,1,1 8290000,-0.28,0.022,-0.0066,0.96,-0.44,-0.14,-0.016,-0.51,-0.15,-0.038,-0.00039,-0.0093,-0.0002,-0.0017,-0.0002,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00075,0.00077,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0013,8.4e-05,0.0013,0.0012,0.00082,0.0013,1,1
86 8390000,-0.28,0.026,-0.0061,0.96,-0.33,-0.12,-0.011,-0.2,-0.089,-0.034,-0.0012,-0.005,-8.5e-05,0.00063,-0.00041,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.43,0.43,0.02,0.81,0.8,0.057,5.9e-05,5.9e-05,4.6e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 8390000,-0.28,0.022,-0.0066,0.96,-0.45,-0.14,-0.015,-0.55,-0.16,-0.036,-0.00039,-0.0092,-0.0002,-0.0017,-0.00018,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0012,0.00082,0.0013,1,1
87 8490000,-0.28,0.026,-0.0059,0.96,-0.35,-0.12,-0.012,-0.23,-0.094,-0.039,-0.0013,-0.005,-8.2e-05,0.00062,-0.00029,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.47,0.46,0.019,0.9,0.9,0.056,5.8e-05,5.7e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 8490000,-0.28,0.022,-0.0066,0.96,-0.46,-0.14,-0.016,-0.58,-0.17,-0.041,-0.00048,-0.0091,-0.00019,-0.0016,-9.5e-05,-0.13,-0.1,-0.023,0.5,0.079,-0.031,-0.068,0,0,0.0007,0.00072,0.053,0.82,0.82,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0012,0.00082,0.0013,1,1
88 8590000,-0.28,0.027,-0.0059,0.96,-0.38,-0.14,-0.0073,-0.26,-0.12,-0.034,-0.0012,-0.0049,-8.2e-05,0.00079,-0.00042,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.51,0.51,0.019,1,1,0.055,5.6e-05,5.5e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 8590000,-0.28,0.021,-0.0064,0.96,-0.45,-0.15,-0.012,-0.6,-0.19,-0.036,-0.00042,-0.0089,-0.00019,-0.0016,-9.3e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.068,0,0,0.00068,0.0007,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8e-05,0.0013,0.0012,0.00081,0.0013,1,1
89 8690000,-0.28,0.027,-0.0059,0.96,-0.4,-0.14,-0.0089,-0.3,-0.13,-0.035,-0.0012,-0.0049,-8.2e-05,0.00071,-0.00035,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.56,0.55,0.018,1.1,1.1,0.055,5.5e-05,5.4e-05,4.6e-06,0.04,0.04,0.001,0.0013,8e-05,0.0013,0.0013,0.00089,0.0013,1,1 8690000,-0.28,0.021,-0.0066,0.96,-0.47,-0.15,-0.014,-0.64,-0.2,-0.037,-0.00048,-0.0088,-0.00019,-0.0016,-5.5e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00066,0.00068,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,7.9e-05,0.0013,0.0012,0.00081,0.0013,1,1
90 8790000,-0.28,0.027,-0.0059,0.96,-0.43,-0.15,-0.0084,-0.35,-0.14,-0.032,-0.0012,-0.005,-8.5e-05,0.00052,-0.0004,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.61,0.6,0.018,1.2,1.2,0.055,5.3e-05,5.2e-05,4.6e-06,0.04,0.04,0.00099,0.0013,7.9e-05,0.0013,0.0013,0.00089,0.0013,1,1 8790000,-0.28,0.021,-0.0066,0.96,-0.48,-0.16,-0.013,-0.68,-0.22,-0.035,-0.00046,-0.0088,-0.00018,-0.0016,-5e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00064,0.00066,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,7.8e-05,0.0013,0.0012,0.00081,0.0013,1,1
91 8890000,-0.28,0.027,-0.0059,0.96,-0.46,-0.16,-0.0039,-0.38,-0.16,-0.026,-0.0012,-0.0049,-8.1e-05,0.00064,-0.00031,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.66,0.65,0.017,1.4,1.4,0.054,5.1e-05,5e-05,4.5e-06,0.04,0.04,0.00095,0.0013,7.8e-05,0.0013,0.0013,0.00089,0.0013,1,1 8890000,-0.28,0.021,-0.0066,0.96,-0.47,-0.16,-0.0094,-0.68,-0.23,-0.029,-0.00051,-0.0085,-0.00018,-0.0016,5.8e-05,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.00063,0.00064,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,7.7e-05,0.0013,0.0012,0.0008,0.0013,1,1
92 8990000,-0.28,0.027,-0.0058,0.96,-0.47,-0.17,-0.0028,-0.41,-0.17,-0.029,-0.0013,-0.0047,-7.5e-05,0.001,-0.0003,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.72,0.7,0.017,1.5,1.5,0.054,4.9e-05,4.8e-05,4.5e-06,0.04,0.04,0.00091,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1 8990000,-0.28,0.02,-0.0064,0.96,-0.45,-0.16,-0.0089,-0.68,-0.24,-0.032,-0.00055,-0.0082,-0.00017,-0.0013,0.00016,-0.13,-0.1,-0.023,0.5,0.08,-0.032,-0.069,0,0,0.00061,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,7.6e-05,0.0013,0.0012,0.0008,0.0013,1,1
93 9090000,-0.28,0.027,-0.0056,0.96,-0.5,-0.18,-0.0038,-0.47,-0.17,-0.029,-0.0014,-0.0048,-7.2e-05,0.00081,-2.1e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.77,0.76,0.016,1.7,1.7,0.053,4.7e-05,4.6e-05,4.5e-06,0.04,0.04,0.00087,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1 9090000,-0.28,0.02,-0.0065,0.96,-0.46,-0.15,-0.01,-0.72,-0.22,-0.032,-0.00071,-0.0082,-0.00016,-0.0012,0.00033,-0.13,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.0006,0.00061,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,7.5e-05,0.0013,0.0012,0.0008,0.0013,1,1
94 9190000,-0.28,0.027,-0.0055,0.96,-0.53,-0.18,-0.0029,-0.52,-0.18,-0.029,-0.0015,-0.0048,-6.9e-05,0.0008,0.00012,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.84,0.82,0.016,1.9,1.9,0.052,4.5e-05,4.4e-05,4.5e-06,0.04,0.04,0.00084,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1 9190000,-0.28,0.02,-0.0065,0.96,-0.46,-0.15,-0.0096,-0.74,-0.22,-0.033,-0.00081,-0.008,-0.00016,-0.0011,0.00045,-0.13,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00058,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,7.4e-05,0.0013,0.0012,0.00079,0.0013,1,1
95 9290000,-0.28,0.027,-0.0054,0.96,-0.56,-0.19,-0.0011,-0.56,-0.21,-0.026,-0.0014,-0.0047,-6.7e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.9,0.88,0.016,2.1,2.1,0.052,4.3e-05,4.2e-05,4.5e-06,0.04,0.04,0.0008,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1 9290000,-0.28,0.02,-0.0062,0.96,-0.46,-0.15,-0.0082,-0.74,-0.24,-0.03,-0.00081,-0.0078,-0.00015,-0.001,0.00052,-0.13,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00057,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,7.4e-05,0.0013,0.0012,0.00079,0.0013,1,1
96 9390000,-0.28,0.027,-0.0054,0.96,-0.023,-0.0084,0.0003,-0.57,-0.21,-0.026,-0.0013,-0.0047,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.052,4.2e-05,4e-05,4.5e-06,0.04,0.04,0.00077,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 9390000,-0.28,0.019,-0.006,0.96,-0.45,-0.17,-0.0071,-0.75,-0.27,-0.031,-0.00073,-0.0077,-0.00015,-0.00084,0.0005,-0.13,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00056,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,7.3e-05,0.0013,0.0012,0.00079,0.0013,1,1
97 9490000,-0.28,0.027,-0.0053,0.96,-0.049,-0.017,0.0021,-0.58,-0.21,-0.023,-0.0014,-0.0048,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.051,4e-05,3.8e-05,4.5e-06,0.04,0.04,0.00074,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 9490000,-0.28,0.019,-0.0061,0.96,-0.46,-0.16,-0.0055,-0.78,-0.27,-0.028,-0.0008,-0.0076,-0.00015,-0.00092,0.00059,-0.14,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00055,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,7.2e-05,0.0013,0.0012,0.00079,0.0013,1,1
98 9590000,-0.28,0.027,-0.0056,0.96,-0.076,-0.023,0.0023,-0.58,-0.21,-0.024,-0.0012,-0.0048,-8e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,51,51,0.05,3.8e-05,3.7e-05,4.5e-06,0.04,0.04,0.00072,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 9590000,-0.28,0.019,-0.0061,0.96,-0.47,-0.18,-0.0054,-0.82,-0.32,-0.029,-0.00068,-0.0075,-0.00015,-0.00085,0.00046,-0.14,-0.1,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.2e-05,0.0013,0.0012,0.00078,0.0013,1,1
99 9690000,-0.28,0.027,-0.0057,0.96,-0.1,-0.031,0.0054,-0.59,-0.21,-0.023,-0.0012,-0.0048,-8.2e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,52,52,0.05,3.6e-05,3.5e-05,4.5e-06,0.04,0.04,0.00069,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 9690000,-0.28,0.019,-0.006,0.96,-0.47,-0.19,-0.0026,-0.83,-0.35,-0.028,-0.00064,-0.0074,-0.00015,-0.00077,0.00045,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00054,0.00055,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.1e-05,0.0013,0.0012,0.00078,0.0013,1,1
100 9790000,-0.28,0.027,-0.0059,0.96,-0.13,-0.038,0.0041,-0.59,-0.22,-0.023,-0.001,-0.005,-9.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,35,35,0.05,3.4e-05,3.3e-05,4.5e-06,0.04,0.04,0.00067,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 9790000,-0.28,0.019,-0.006,0.96,-0.48,-0.2,-0.004,-0.88,-0.39,-0.029,-0.00055,-0.0074,-0.00015,-0.00075,0.00038,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.1e-05,0.0013,0.0012,0.00078,0.0013,1,1
101 9890000,-0.28,0.027,-0.0058,0.96,-0.16,-0.047,0.0057,-0.61,-0.22,-0.023,-0.0011,-0.0049,-8.9e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,37,37,0.049,3.2e-05,3.1e-05,4.5e-06,0.04,0.04,0.00064,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 9890000,-0.28,0.019,-0.0059,0.96,-0.47,-0.21,-0.0028,-0.88,-0.41,-0.03,-0.00058,-0.0072,-0.00014,-0.00051,0.00044,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.7,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7e-05,0.0013,0.0012,0.00078,0.0013,1,1
102 9990000,-0.28,0.027,-0.006,0.96,-0.18,-0.051,0.0065,-0.61,-0.22,-0.025,-0.00096,-0.005,-9.6e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.014,28,28,0.049,3.1e-05,3e-05,4.5e-06,0.04,0.04,0.00062,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 9990000,-0.28,0.019,-0.0059,0.96,-0.49,-0.22,-0.0021,-0.93,-0.44,-0.032,-0.00052,-0.0072,-0.00015,-0.00043,0.00037,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7e-05,0.0013,0.0012,0.00077,0.0013,1,1
103 10090000,-0.28,0.027,-0.0061,0.96,-0.21,-0.054,0.0078,-0.63,-0.23,-0.023,-0.00084,-0.0051,-0.0001,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.013,30,30,0.049,2.9e-05,2.8e-05,4.5e-06,0.04,0.04,0.0006,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 10090000,-0.28,0.019,-0.0058,0.96,-0.49,-0.23,-0.00087,-0.96,-0.5,-0.03,-0.00041,-0.0071,-0.00015,-0.00043,0.00029,-0.14,-0.11,-0.023,0.5,0.081,-0.032,-0.069,0,0,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7e-05,0.0013,0.0012,0.00077,0.0013,1,1
104 10190000,-0.28,0.027,-0.0064,0.96,-0.23,-0.056,0.0087,-0.64,-0.23,-0.024,-0.00067,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,25,25,0.048,2.8e-05,2.7e-05,4.5e-06,0.04,0.04,0.00058,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 10190000,-0.28,0.019,-0.0057,0.96,-0.49,-0.25,-3e-05,-0.97,-0.56,-0.031,-0.00028,-0.007,-0.00015,-0.00026,0.00016,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1
105 10290000,-0.28,0.027,-0.0064,0.96,-0.26,-0.065,0.0079,-0.66,-0.23,-0.023,-0.00072,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,27,27,0.048,2.6e-05,2.5e-05,4.5e-06,0.04,0.04,0.00057,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 10290000,-0.28,0.019,-0.0057,0.96,-0.49,-0.25,-0.0012,-0.98,-0.57,-0.03,-0.00034,-0.0069,-0.00014,-0.00014,0.00022,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1
106 10390000,-0.28,0.028,-0.0063,0.96,-0.012,-0.0081,-0.0025,-7.9e-05,-0.00028,-0.023,-0.00074,-0.0049,-0.0001,0.001,0.00015,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.25,0.25,0.56,0.25,0.25,0.049,2.5e-05,2.4e-05,4.5e-06,0.04,0.04,0.00055,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 10390000,-0.28,0.019,-0.0056,0.96,0.0031,-0.0051,-0.0025,0.00058,-0.00014,-0.03,-0.00038,-0.0067,-0.00014,1.3e-05,0.00029,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,6.9e-05,0.0013,0.0012,0.00077,0.0013,1,1
107 10490000,-0.28,0.027,-0.0064,0.96,-0.041,-0.014,0.0066,-0.0027,-0.0013,-0.018,-0.00066,-0.005,-0.00011,0.00082,2.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.26,0.26,0.55,0.26,0.26,0.058,2.4e-05,2.3e-05,4.5e-06,0.04,0.04,0.00054,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 10490000,-0.28,0.019,-0.0056,0.96,-0.01,-0.0085,0.0071,0.00025,-0.0008,-0.024,-0.00032,-0.0067,-0.00014,-0.00013,0.00023,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00051,0.00051,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,6.8e-05,0.0013,0.0012,0.00076,0.0013,1,1
108 10590000,-0.28,0.027,-0.0063,0.96,-0.052,-0.013,0.012,-0.0032,-0.00096,-0.016,-0.00073,-0.005,-0.0001,0.0014,7.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.13,0.13,0.27,0.26,0.26,0.056,2.2e-05,2.1e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 10590000,-0.28,0.019,-0.0055,0.96,-0.021,-0.0072,0.013,-0.0011,-0.00056,-0.022,-0.00041,-0.0066,-0.00013,0.00012,0.00058,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,6.8e-05,0.0013,0.0012,0.00076,0.0013,1,1
109 10690000,-0.28,0.027,-0.0063,0.96,-0.081,-0.018,0.015,-0.0099,-0.0025,-0.013,-0.0007,-0.005,-0.00011,0.0014,2.4e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 10690000,-0.28,0.019,-0.0054,0.96,-0.033,-0.0096,0.016,-0.0038,-0.0014,-0.018,-0.00039,-0.0065,-0.00013,0.00014,0.00056,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,6.8e-05,0.0013,0.0012,0.00076,0.0013,1,1
110 10790000,-0.28,0.027,-0.0062,0.96,-0.079,-0.021,0.013,-7.5e-06,-0.0018,-0.012,-0.00072,-0.005,-0.00011,0.0035,-0.0011,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.095,0.095,0.17,0.13,0.13,0.062,2e-05,1.9e-05,4.5e-06,0.039,0.039,0.00051,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 10790000,-0.28,0.019,-0.0053,0.96,-0.033,-0.013,0.014,0.00012,-0.0018,-0.016,-0.00042,-0.0064,-0.00013,0.002,2.8e-05,-0.14,-0.11,-0.023,0.5,0.081,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,6.7e-05,0.0013,0.0012,0.00076,0.0013,1,1
111 10890000,-0.28,0.027,-0.006,0.96,-0.11,-0.03,0.0093,-0.0092,-0.0044,-0.015,-0.00083,-0.005,-0.0001,0.0036,-0.00084,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.11,0.11,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 10890000,-0.28,0.019,-0.0052,0.96,-0.043,-0.018,0.01,-0.0036,-0.0034,-0.019,-0.00054,-0.0063,-0.00012,0.0021,0.00017,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,6.7e-05,0.0013,0.0012,0.00076,0.0013,1,1
112 10990000,-0.28,0.026,-0.006,0.96,-0.096,-0.031,0.016,-0.0034,-0.0023,-0.0093,-0.00085,-0.0052,-0.00011,0.0077,-0.0021,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.083,0.083,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 10990000,-0.28,0.019,-0.0052,0.96,-0.039,-0.021,0.016,-0.0014,-0.0019,-0.012,-0.00057,-0.0064,-0.00012,0.0058,0.00059,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00075,0.0013,1,1
113 11090000,-0.28,0.027,-0.0064,0.96,-0.12,-0.039,0.019,-0.014,-0.0055,-0.0055,-0.00072,-0.0052,-0.00011,0.0078,-0.0025,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.096,0.097,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,4.5e-06,0.039,0.039,0.00049,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 11090000,-0.28,0.019,-0.0053,0.96,-0.05,-0.028,0.02,-0.0059,-0.0044,-0.0081,-0.00046,-0.0063,-0.00013,0.006,0.00059,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00075,0.0013,1,1
114 11190000,-0.28,0.025,-0.0065,0.96,-0.1,-0.034,0.026,-0.0065,-0.0031,0.00085,-0.00071,-0.0053,-0.00011,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.079,0.079,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1 11190000,-0.28,0.018,-0.0054,0.96,-0.041,-0.025,0.027,-0.002,-0.0027,-0.0011,-0.00047,-0.0063,-0.00013,0.013,0.0015,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00075,0.0013,1,1
115 11290000,-0.28,0.025,-0.0066,0.96,-0.13,-0.038,0.025,-0.018,-0.0066,0.00091,-0.00071,-0.0054,-0.00012,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.094,0.094,0.077,0.078,0.078,0.069,1.5e-05,1.4e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1 11290000,-0.28,0.018,-0.0054,0.96,-0.05,-0.027,0.026,-0.0065,-0.0052,-0.00073,-0.00048,-0.0063,-0.00013,0.013,0.0014,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00075,0.0013,1,1
116 11390000,-0.28,0.024,-0.0065,0.96,-0.11,-0.032,0.016,-0.01,-0.004,-0.008,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.078,0.078,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.8e-05,0.0013,0.0012,0.00085,0.0013,1,1 11390000,-0.28,0.018,-0.0053,0.96,-0.043,-0.023,0.017,-0.0037,-0.0033,-0.0092,-0.00053,-0.0063,-0.00013,0.019,0.0028,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00036,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00074,0.0013,1,1
117 11490000,-0.28,0.024,-0.0064,0.96,-0.13,-0.036,0.021,-0.022,-0.0074,-0.002,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.093,0.093,0.057,0.069,0.069,0.067,1.3e-05,1.3e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1 11490000,-0.28,0.018,-0.0052,0.96,-0.05,-0.025,0.021,-0.0082,-0.0059,-0.003,-0.00054,-0.0063,-0.00012,0.019,0.003,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00036,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00074,0.0013,1,1
118 11590000,-0.28,0.023,-0.0065,0.96,-0.11,-0.029,0.019,-0.013,-0.0046,-0.0033,-0.00079,-0.0056,-0.00012,0.027,-0.0085,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00098,0.048,0.077,0.077,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1 11590000,-0.28,0.018,-0.0053,0.96,-0.044,-0.021,0.019,-0.005,-0.0038,-0.0041,-0.00058,-0.0063,-0.00012,0.025,0.0041,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00031,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,6.5e-05,0.0013,0.0012,0.00074,0.0013,1,1
119 11690000,-0.28,0.022,-0.0065,0.96,-0.12,-0.035,0.019,-0.024,-0.0078,-0.0047,-0.00081,-0.0057,-0.00012,0.027,-0.0083,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00099,0.048,0.092,0.092,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1 11690000,-0.28,0.017,-0.0053,0.96,-0.051,-0.025,0.019,-0.0097,-0.0061,-0.0053,-0.00062,-0.0063,-0.00012,0.024,0.0041,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00032,0.00032,0.052,0.088,0.088,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,6.5e-05,0.0013,0.0012,0.00074,0.0013,1,1
120 11790000,-0.28,0.021,-0.0063,0.96,-0.097,-0.033,0.02,-0.014,-0.0064,-0.0019,-0.0009,-0.0057,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00091,0.00087,0.048,0.076,0.076,0.037,0.053,0.053,0.063,1.1e-05,1.1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 11790000,-0.28,0.017,-0.0052,0.96,-0.041,-0.025,0.02,-0.0056,-0.0054,-0.0023,-0.00071,-0.0063,-0.00012,0.03,0.0045,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,6.5e-05,0.0013,0.0012,0.00073,0.0013,1,1
121 11890000,-0.28,0.021,-0.0065,0.96,-0.11,-0.037,0.018,-0.024,-0.0097,-0.0012,-0.00088,-0.0058,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00091,0.00087,0.048,0.089,0.089,0.034,0.06,0.06,0.063,1.1e-05,1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 11890000,-0.28,0.017,-0.0054,0.96,-0.049,-0.027,0.018,-0.01,-0.0079,-0.0016,-0.0007,-0.0063,-0.00012,0.03,0.0044,-0.14,-0.11,-0.023,0.5,0.082,-0.033,-0.069,0,0,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,6.5e-05,0.0013,0.0012,0.00073,0.0013,1,1
122 11990000,-0.28,0.02,-0.0066,0.96,-0.091,-0.028,0.015,-0.017,-0.0064,-0.005,-0.0009,-0.0059,-0.00012,0.039,-0.011,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.076,0.076,0.03,0.062,0.062,0.061,1e-05,9.8e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00082,0.0013,1,1 11990000,-0.28,0.017,-0.0054,0.96,-0.039,-0.021,0.015,-0.0064,-0.0052,-0.0052,-0.00073,-0.0063,-0.00012,0.036,0.0065,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,6.5e-05,0.0013,0.0012,0.00073,0.0013,1,1
123 12090000,-0.28,0.02,-0.0066,0.96,-0.1,-0.03,0.019,-0.027,-0.0092,0.0011,-0.00086,-0.0058,-0.00012,0.039,-0.012,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.089,0.088,0.027,0.071,0.071,0.06,9.8e-06,9.3e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00081,0.0013,1,1 12090000,-0.28,0.017,-0.0053,0.96,-0.045,-0.022,0.018,-0.011,-0.0074,0.00087,-0.0007,-0.0062,-0.00012,0.037,0.0067,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,6.4e-05,0.0013,0.0012,0.00073,0.0013,1,1
124 12190000,-0.28,0.019,-0.0067,0.96,-0.084,-0.018,0.018,-0.014,-0.0032,0.0029,-0.00082,-0.0059,-0.00012,0.045,-0.013,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.07,0.07,0.024,0.057,0.057,0.058,9.2e-06,8.8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 12190000,-0.28,0.017,-0.0053,0.96,-0.038,-0.013,0.017,-0.0054,-0.0028,0.0028,-0.00066,-0.0062,-0.00012,0.042,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00072,0.0013,1,1
125 12290000,-0.28,0.019,-0.0068,0.96,-0.09,-0.017,0.017,-0.023,-0.0048,0.004,-0.00079,-0.0059,-0.00012,0.045,-0.014,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.081,0.081,0.022,0.065,0.065,0.058,8.9e-06,8.5e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 12290000,-0.28,0.017,-0.0054,0.96,-0.04,-0.011,0.016,-0.0094,-0.004,0.0038,-0.00064,-0.0062,-0.00012,0.043,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00072,0.0013,1,1
126 12390000,-0.28,0.019,-0.0068,0.96,-0.073,-0.012,0.015,-0.013,-0.0027,-0.002,-0.00078,-0.0059,-0.00012,0.048,-0.015,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00066,0.00063,0.047,0.066,0.065,0.02,0.054,0.054,0.056,8.4e-06,8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1 12390000,-0.28,0.016,-0.0054,0.96,-0.033,-0.0082,0.014,-0.0051,-0.0026,-0.0022,-0.00063,-0.0062,-0.00012,0.046,0.0086,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.012,0.013,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00072,0.0013,1,1
127 12490000,-0.28,0.019,-0.0069,0.96,-0.081,-0.013,0.019,-0.021,-0.004,9.6e-05,-0.00076,-0.0059,-0.00013,0.048,-0.016,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00066,0.00064,0.047,0.075,0.075,0.018,0.062,0.062,0.055,8.1e-06,7.7e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1 12490000,-0.28,0.016,-0.0054,0.96,-0.036,-0.0092,0.018,-0.0087,-0.0035,-0.00015,-0.00061,-0.0061,-0.00012,0.047,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.012,0.013,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00072,0.0013,1,1
128 12590000,-0.28,0.018,-0.0068,0.96,-0.065,-0.011,0.021,-0.01,-0.0039,0.0019,-0.00076,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00058,0.047,0.061,0.061,0.017,0.052,0.052,0.054,7.7e-06,7.4e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 12590000,-0.28,0.016,-0.0053,0.96,-0.03,-0.008,0.019,-0.0035,-0.0039,0.0017,-0.00062,-0.0061,-0.00012,0.05,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,6.4e-05,0.0012,0.0012,0.00071,0.0013,1,1
129 12690000,-0.28,0.018,-0.0067,0.96,-0.072,-0.0098,0.02,-0.017,-0.0049,0.0035,-0.00075,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00059,0.047,0.069,0.069,0.015,0.059,0.059,0.053,7.4e-06,7e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 12690000,-0.28,0.016,-0.0053,0.96,-0.033,-0.0061,0.019,-0.0066,-0.0046,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.069,0,0,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
130 12790000,-0.28,0.018,-0.0065,0.96,-0.056,-0.015,0.022,-0.01,-0.0078,0.0057,-0.00082,-0.0059,-0.00013,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.061,0.061,0.014,0.061,0.061,0.051,7.1e-06,6.7e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 12790000,-0.28,0.016,-0.0051,0.96,-0.023,-0.012,0.02,-0.0016,-0.0076,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.0067,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.069,0,0,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.5e-06,7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
131 12890000,-0.28,0.018,-0.0065,0.96,-0.061,-0.016,0.023,-0.016,-0.0096,0.0088,-0.00084,-0.0059,-0.00012,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.069,0.069,0.013,0.07,0.07,0.051,6.8e-06,6.5e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 12890000,-0.28,0.016,-0.0051,0.96,-0.025,-0.012,0.021,-0.0039,-0.0089,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0071,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.069,0,0,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
132 12990000,-0.28,0.017,-0.0065,0.96,-0.05,-0.013,0.023,-0.008,-0.0066,0.01,-0.00088,-0.0059,-0.00012,0.056,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.047,0.055,0.055,0.012,0.056,0.056,0.05,6.5e-06,6.2e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 12990000,-0.28,0.016,-0.0051,0.96,-0.021,-0.0096,0.022,-0.0012,-0.0062,0.0096,-0.00076,-0.0061,-0.00012,0.054,0.0077,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
133 13090000,-0.28,0.017,-0.0064,0.96,-0.054,-0.015,0.021,-0.013,-0.0083,0.0089,-0.00091,-0.0059,-0.00012,0.056,-0.018,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.046,0.062,0.062,0.011,0.065,0.065,0.049,6.3e-06,5.9e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 13090000,-0.28,0.016,-0.0051,0.96,-0.023,-0.011,0.019,-0.0033,-0.0075,0.0084,-0.0008,-0.006,-0.00011,0.054,0.0082,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.0079,0.0082,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
134 13190000,-0.28,0.017,-0.0063,0.96,-0.046,-0.015,0.02,-0.0097,-0.0091,0.0096,-0.00094,-0.0059,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.055,0.055,0.011,0.066,0.066,0.047,6e-06,5.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 13190000,-0.28,0.016,-0.005,0.96,-0.019,-0.011,0.018,-0.0017,-0.0085,0.009,-0.00082,-0.006,-0.00011,0.055,0.0082,-0.14,-0.11,-0.023,0.5,0.083,-0.033,-0.07,0,0,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0013,1,1
135 13290000,-0.28,0.017,-0.0064,0.96,-0.049,-0.015,0.017,-0.015,-0.011,0.009,-0.00092,-0.0058,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.061,0.061,0.01,0.075,0.075,0.047,5.8e-06,5.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 13290000,-0.28,0.016,-0.005,0.96,-0.02,-0.011,0.016,-0.0037,-0.0097,0.0083,-0.00081,-0.006,-0.00011,0.055,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0073,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.00071,0.0012,1,1
136 13390000,-0.28,0.017,-0.0064,0.96,-0.04,-0.011,0.017,-0.0074,-0.007,0.0097,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.049,0.049,0.0094,0.06,0.06,0.046,5.6e-06,5.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 13390000,-0.28,0.016,-0.005,0.96,-0.017,-0.0081,0.015,-0.0014,-0.0067,0.0089,-0.00079,-0.006,-0.00011,0.057,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,9.9e-05,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,6.3e-05,0.0012,0.0012,0.0007,0.0012,1,1
137 13490000,-0.28,0.017,-0.0064,0.96,-0.044,-0.014,0.017,-0.012,-0.0083,0.006,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.054,0.054,0.009,0.068,0.068,0.045,5.4e-06,5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 13490000,-0.28,0.016,-0.005,0.96,-0.019,-0.011,0.015,-0.0032,-0.0078,0.0051,-0.00079,-0.006,-0.00011,0.057,0.0087,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,0.0001,0.0001,0.051,0.053,0.053,0.009,0.068,0.068,0.045,5.6e-06,5.2e-06,2.2e-06,0.0062,0.0065,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
138 13590000,-0.28,0.017,-0.0064,0.96,-0.035,-0.01,0.018,-0.0035,-0.0057,0.0045,-0.00088,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00045,0.046,0.045,0.045,0.0085,0.055,0.055,0.044,5.2e-06,4.9e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 13590000,-0.28,0.016,-0.005,0.96,-0.014,-0.0072,0.016,0.0017,-0.0055,0.0036,-0.00077,-0.006,-0.00011,0.059,0.0088,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,9.2e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
139 13690000,-0.28,0.017,-0.0063,0.96,-0.037,-0.0095,0.019,-0.0071,-0.0067,0.0072,-0.00089,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00046,0.046,0.049,0.049,0.0082,0.063,0.063,0.044,5e-06,4.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 13690000,-0.28,0.016,-0.0049,0.96,-0.015,-0.0064,0.016,0.00027,-0.0063,0.0062,-0.0008,-0.0059,-0.00011,0.059,0.0091,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,9.3e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0055,0.0058,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
140 13790000,-0.28,0.016,-0.0064,0.96,-0.029,-0.0071,0.019,0.00061,-0.0035,0.0068,-0.00089,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.041,0.041,0.0078,0.052,0.052,0.042,4.8e-06,4.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 13790000,-0.28,0.015,-0.0049,0.96,-0.011,-0.0044,0.016,0.0054,-0.0033,0.0057,-0.00079,-0.006,-0.00011,0.06,0.0089,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,8.7e-05,8.6e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.005,0.0053,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
141 13890000,-0.28,0.016,-0.0063,0.96,-0.031,-0.0086,0.02,-0.0022,-0.0044,0.0091,-0.00092,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.045,0.045,0.0076,0.059,0.059,0.042,4.7e-06,4.4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00075,0.0012,1,1 13890000,-0.28,0.015,-0.0048,0.96,-0.012,-0.0055,0.017,0.0044,-0.0038,0.0078,-0.00083,-0.006,-0.00011,0.06,0.0091,-0.14,-0.11,-0.023,0.5,0.084,-0.034,-0.07,0,0,8.8e-05,8.7e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.005,0.0053,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
142 13990000,-0.28,0.016,-0.0062,0.96,-0.03,-0.012,0.018,-0.00073,-0.0048,0.008,-0.00094,-0.0059,-0.00012,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.039,0.039,0.0073,0.05,0.05,0.041,4.5e-06,4.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 13990000,-0.28,0.015,-0.0048,0.96,-0.014,-0.0093,0.016,0.0039,-0.0045,0.0067,-0.00085,-0.006,-0.00011,0.06,0.0095,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.07,0,0,8.3e-05,8.2e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
143 14090000,-0.28,0.016,-0.0064,0.96,-0.031,-0.0062,0.02,-0.004,-0.0053,0.0046,-0.00087,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.042,0.042,0.0072,0.057,0.057,0.041,4.4e-06,4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14090000,-0.28,0.015,-0.0049,0.96,-0.013,-0.0034,0.017,0.0023,-0.0048,0.0031,-0.00078,-0.006,-0.00011,0.061,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
144 14190000,-0.28,0.016,-0.0064,0.96,-0.025,-0.0047,0.02,-0.00094,-0.004,0.0049,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.036,0.036,0.007,0.049,0.049,0.04,4.2e-06,3.9e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14190000,-0.28,0.015,-0.005,0.96,-0.01,-0.0023,0.017,0.0036,-0.0038,0.0033,-0.00074,-0.0059,-0.00011,0.062,0.0085,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
145 14290000,-0.28,0.016,-0.0064,0.96,-0.028,-0.0051,0.018,-0.0036,-0.0044,0.0092,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.04,0.04,0.0069,0.055,0.055,0.039,4.1e-06,3.8e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14290000,-0.28,0.015,-0.0049,0.96,-0.013,-0.0026,0.015,0.0025,-0.0041,0.0075,-0.00073,-0.0059,-0.00011,0.062,0.0087,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,8e-05,7.9e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0042,0.0045,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
146 14390000,-0.28,0.016,-0.0064,0.96,-0.026,-0.0045,0.019,-0.00096,-0.0049,0.014,-0.00083,-0.0059,-0.00012,0.064,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.034,0.034,0.0067,0.048,0.048,0.039,4e-06,3.6e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14390000,-0.28,0.015,-0.0049,0.96,-0.012,-0.0022,0.017,0.0036,-0.0046,0.012,-0.00075,-0.0059,-0.00011,0.063,0.0088,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
147 14490000,-0.28,0.016,-0.0066,0.96,-0.026,-0.0039,0.023,-0.0037,-0.005,0.016,-0.00079,-0.0059,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00042,0.046,0.037,0.037,0.0066,0.054,0.054,0.038,3.8e-06,3.5e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14490000,-0.28,0.015,-0.0051,0.96,-0.012,-0.0015,0.02,0.0023,-0.0046,0.014,-0.00071,-0.0059,-0.00012,0.063,0.0084,-0.14,-0.11,-0.023,0.5,0.083,-0.034,-0.07,0,0,7.7e-05,7.6e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
148 14590000,-0.28,0.016,-0.0067,0.96,-0.028,-0.0054,0.021,-0.0038,-0.0053,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.032,0.032,0.0065,0.047,0.047,0.038,3.7e-06,3.4e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14590000,-0.28,0.015,-0.0051,0.96,-0.015,-0.0032,0.018,0.0007,-0.0051,0.01,-0.00069,-0.0059,-0.00012,0.064,0.0085,-0.14,-0.11,-0.024,0.5,0.083,-0.034,-0.07,0,0,7.4e-05,7.3e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,6.2e-05,0.0012,0.0012,0.0007,0.0012,1,1
149 14690000,-0.28,0.016,-0.0067,0.96,-0.029,-0.0058,0.021,-0.0067,-0.006,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.035,0.035,0.0065,0.053,0.053,0.037,3.6e-06,3.3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14690000,-0.28,0.015,-0.0051,0.96,-0.016,-0.0035,0.018,-0.00089,-0.0056,0.01,-0.0007,-0.0059,-0.00011,0.064,0.0088,-0.14,-0.11,-0.024,0.5,0.083,-0.034,-0.07,0,0,7.5e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
150 14790000,-0.28,0.016,-0.0068,0.96,-0.03,-0.003,0.021,-0.0052,-0.0014,0.015,-0.0008,-0.0058,-0.00012,0.065,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.031,0.031,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 14790000,-0.28,0.015,-0.0052,0.96,-0.019,-0.00093,0.018,-0.00059,-0.0012,0.013,-0.00073,-0.0058,-0.00011,0.065,0.01,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
151 14890000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0012,0.026,-0.0086,-0.002,0.016,-0.00081,-0.0057,-0.00012,0.066,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.00041,0.046,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 14890000,-0.28,0.015,-0.0051,0.96,-0.02,0.00099,0.022,-0.0027,-0.0015,0.014,-0.00074,-0.0058,-0.00011,0.065,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.3e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
152 14990000,-0.28,0.016,-0.0067,0.96,-0.031,-0.003,0.028,-0.0069,-0.003,0.018,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 14990000,-0.28,0.015,-0.0051,0.96,-0.02,-0.001,0.025,-0.0022,-0.0027,0.016,-0.00074,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.1e-05,6.9e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0033,0.0036,0.00044,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
153 15090000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0042,0.032,-0.01,-0.0033,0.021,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.032,0.032,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15090000,-0.28,0.015,-0.005,0.96,-0.021,-0.0021,0.029,-0.0043,-0.0028,0.018,-0.00075,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
154 15190000,-0.28,0.016,-0.0068,0.96,-0.03,-0.0022,0.033,-0.008,-0.0026,0.023,-0.0008,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15190000,-0.28,0.016,-0.0052,0.96,-0.021,-0.00028,0.029,-0.0034,-0.0022,0.02,-0.00073,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0034,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
155 15290000,-0.28,0.016,-0.0069,0.96,-0.034,-0.0024,0.032,-0.012,-0.0032,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15290000,-0.28,0.016,-0.0052,0.96,-0.024,-0.00035,0.029,-0.0059,-0.0026,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,7e-05,6.8e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.8e-06,2.2e-06,0.0032,0.0034,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
156 15390000,-0.28,0.016,-0.0069,0.96,-0.032,-0.0042,0.032,-0.0092,-0.0026,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.027,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15390000,-0.28,0.016,-0.0053,0.96,-0.023,-0.0023,0.028,-0.0046,-0.0022,0.017,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.7e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
157 15490000,-0.28,0.016,-0.007,0.96,-0.034,-0.0018,0.032,-0.012,-0.003,0.021,-0.00082,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.029,0.0065,0.05,0.05,0.034,2.8e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15490000,-0.28,0.016,-0.0053,0.96,-0.025,0.00021,0.028,-0.007,-0.0024,0.018,-0.00075,-0.0057,-0.00011,0.067,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.003,0.0033,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
158 15590000,-0.28,0.016,-0.0069,0.96,-0.03,-0.006,0.032,-0.0077,-0.0061,0.02,-0.00085,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15590000,-0.28,0.016,-0.0053,0.96,-0.022,-0.0041,0.028,-0.0033,-0.0056,0.017,-0.00079,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
159 15690000,-0.28,0.016,-0.0068,0.96,-0.032,-0.0041,0.032,-0.01,-0.0067,0.021,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15690000,-0.28,0.016,-0.0052,0.96,-0.024,-0.0021,0.028,-0.0049,-0.0059,0.018,-0.00083,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
160 15790000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0028,0.032,-0.0077,-0.0057,0.023,-0.00092,-0.0057,-0.00012,0.068,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.024,0.024,0.0066,0.043,0.044,0.033,2.6e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15790000,-0.28,0.015,-0.0052,0.96,-0.021,-0.00088,0.028,-0.0035,-0.0051,0.019,-0.00087,-0.0058,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
161 15890000,-0.28,0.016,-0.0069,0.96,-0.029,-0.0041,0.033,-0.011,-0.0058,0.023,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15890000,-0.28,0.016,-0.0053,0.96,-0.021,-0.0021,0.029,-0.0059,-0.005,0.019,-0.00084,-0.0057,-0.00011,0.066,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
162 15990000,-0.28,0.016,-0.0068,0.96,-0.027,-0.0035,0.03,-0.0091,-0.0049,0.022,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1 15990000,-0.28,0.015,-0.0052,0.96,-0.02,-0.0017,0.026,-0.0049,-0.0043,0.018,-0.00083,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
163 16090000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0023,0.028,-0.012,-0.005,0.022,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.025,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16090000,-0.28,0.016,-0.0052,0.96,-0.022,-0.00036,0.024,-0.0072,-0.0042,0.018,-0.00082,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.6e-05,6.3e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
164 16190000,-0.28,0.016,-0.0068,0.96,-0.026,-0.002,0.027,-0.011,-0.0041,0.019,-0.00086,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16190000,-0.28,0.016,-0.0052,0.96,-0.02,-0.0002,0.023,-0.0071,-0.0035,0.015,-0.0008,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
165 16290000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0011,0.027,-0.014,-0.0043,0.021,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.024,0.024,0.007,0.048,0.048,0.033,2.3e-06,2e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16290000,-0.28,0.015,-0.0052,0.96,-0.022,0.00077,0.022,-0.009,-0.0035,0.016,-0.00081,-0.0057,-0.00011,0.067,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00042,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
166 16390000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0015,0.027,-0.011,-0.0041,0.021,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16390000,-0.28,0.015,-0.0051,0.96,-0.023,0.00023,0.023,-0.007,-0.0034,0.017,-0.00082,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,6.1e-05,0.0012,0.0012,0.00069,0.0012,1,1
167 16490000,-0.28,0.016,-0.0069,0.96,-0.033,-0.00051,0.029,-0.014,-0.0041,0.025,-0.00086,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.023,0.023,0.0072,0.047,0.047,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16490000,-0.28,0.016,-0.0052,0.96,-0.027,0.0013,0.025,-0.0098,-0.0033,0.021,-0.00081,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
168 16590000,-0.28,0.016,-0.0069,0.96,-0.036,1.4e-05,0.033,-0.012,-0.0035,0.025,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.021,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16590000,-0.28,0.016,-0.0052,0.96,-0.031,0.0017,0.029,-0.0085,-0.0028,0.021,-0.00082,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
169 16690000,-0.28,0.016,-0.0069,0.96,-0.039,0.0036,0.033,-0.016,-0.0035,0.026,-0.00089,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16690000,-0.28,0.015,-0.0053,0.96,-0.034,0.0053,0.029,-0.011,-0.0026,0.021,-0.00084,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
170 16790000,-0.28,0.016,-0.0068,0.96,-0.039,0.0034,0.032,-0.013,-0.0031,0.026,-0.00091,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0073,0.042,0.042,0.033,2e-06,1.7e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16790000,-0.28,0.015,-0.0051,0.96,-0.035,0.005,0.028,-0.0096,-0.0024,0.021,-0.00086,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
171 16890000,-0.28,0.016,-0.0067,0.96,-0.039,0.0029,0.033,-0.017,-0.0032,0.025,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16890000,-0.28,0.015,-0.005,0.96,-0.035,0.0046,0.029,-0.013,-0.0023,0.02,-0.00089,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
172 16990000,-0.28,0.016,-0.0067,0.96,-0.036,0.0033,0.033,-0.015,-0.0034,0.024,-0.00094,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.049,0.049,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16990000,-0.28,0.015,-0.0051,0.96,-0.032,0.005,0.029,-0.011,-0.0025,0.019,-0.0009,-0.0057,-0.00011,0.068,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0024,0.0027,0.0004,0.0012,6e-05,0.0012,0.0012,0.00069,0.0012,1,1
173 17090000,-0.28,0.016,-0.0068,0.96,-0.041,0.0053,0.033,-0.019,-0.0029,0.023,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0075,0.054,0.054,0.033,1.9e-06,1.6e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17090000,-0.28,0.015,-0.0052,0.96,-0.037,0.007,0.028,-0.015,-0.0019,0.018,-0.00089,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
174 17190000,-0.28,0.016,-0.0069,0.96,-0.039,0.0071,0.034,-0.018,-0.0046,0.026,-0.00093,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0076,0.057,0.057,0.033,1.8e-06,1.6e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17190000,-0.28,0.015,-0.0053,0.96,-0.036,0.0088,0.03,-0.014,-0.0036,0.021,-0.00089,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
175 17290000,-0.28,0.016,-0.0069,0.96,-0.042,0.0077,0.034,-0.022,-0.0035,0.026,-0.00092,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.023,0.024,0.0077,0.062,0.063,0.033,1.8e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17290000,-0.28,0.015,-0.0053,0.96,-0.039,0.0095,0.029,-0.017,-0.0023,0.021,-0.00087,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00039,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
176 17390000,-0.28,0.016,-0.0069,0.96,-0.032,0.013,0.033,-0.014,-0.002,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17390000,-0.28,0.015,-0.0052,0.96,-0.029,0.014,0.029,-0.01,-0.001,0.021,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
177 17490000,-0.28,0.016,-0.0069,0.96,-0.032,0.014,0.033,-0.017,-0.00051,0.028,-0.00094,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.022,0.0078,0.058,0.058,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17490000,-0.28,0.015,-0.0053,0.96,-0.029,0.016,0.029,-0.013,0.00056,0.023,-0.0009,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0023,0.0026,0.00038,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
178 17590000,-0.28,0.016,-0.0069,0.96,-0.032,0.012,0.032,-0.016,-0.00075,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 17590000,-0.28,0.015,-0.0053,0.96,-0.029,0.014,0.028,-0.012,0.0001,0.02,-0.00091,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.07,0,0,6.1e-05,5.7e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
179 17690000,-0.28,0.016,-0.007,0.96,-0.033,0.012,0.033,-0.019,0.0003,0.028,-0.00096,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.02,0.02,0.0078,0.054,0.054,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 17690000,-0.28,0.015,-0.0054,0.96,-0.03,0.014,0.029,-0.015,0.0013,0.023,-0.00092,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
180 17790000,-0.28,0.016,-0.007,0.96,-0.033,0.013,0.033,-0.018,0.0011,0.033,-0.00097,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.019,0.02,0.0078,0.057,0.057,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 17790000,-0.28,0.015,-0.0054,0.96,-0.031,0.014,0.029,-0.015,0.0021,0.028,-0.00093,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
181 17890000,-0.28,0.016,-0.0069,0.96,-0.037,0.014,0.033,-0.021,0.0022,0.038,-0.00098,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.021,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 17890000,-0.28,0.015,-0.0053,0.96,-0.034,0.016,0.029,-0.017,0.0033,0.032,-0.00094,-0.0057,-0.00011,0.068,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
182 17990000,-0.28,0.016,-0.0069,0.96,-0.035,0.015,0.033,-0.017,0.0047,0.038,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.018,0.0079,0.052,0.052,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 17990000,-0.28,0.015,-0.0053,0.96,-0.034,0.016,0.029,-0.014,0.0055,0.033,-0.00094,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0022,0.0025,0.00036,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
183 18090000,-0.28,0.016,-0.007,0.96,-0.037,0.016,0.032,-0.021,0.0061,0.037,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.008,0.057,0.057,0.034,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 18090000,-0.28,0.015,-0.0054,0.96,-0.035,0.017,0.028,-0.018,0.0071,0.031,-0.00094,-0.0057,-0.00011,0.069,0.011,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
184 18190000,-0.28,0.016,-0.007,0.96,-0.034,0.013,0.033,-0.016,0.004,0.035,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18190000,-0.28,0.015,-0.0053,0.96,-0.032,0.015,0.028,-0.013,0.0048,0.029,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
185 18290000,-0.28,0.016,-0.007,0.96,-0.037,0.013,0.031,-0.02,0.005,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.019,0.008,0.053,0.054,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18290000,-0.28,0.015,-0.0053,0.96,-0.036,0.015,0.027,-0.017,0.006,0.028,-0.00098,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
186 18390000,-0.28,0.016,-0.0069,0.96,-0.033,0.013,0.031,-0.014,0.0042,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0079,0.046,0.047,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18390000,-0.28,0.015,-0.0052,0.96,-0.032,0.014,0.027,-0.012,0.005,0.027,-0.00099,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0024,0.00034,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
187 18490000,-0.28,0.016,-0.0069,0.96,-0.037,0.012,0.03,-0.018,0.005,0.034,-0.001,-0.0057,-0.00013,0.072,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.018,0.008,0.051,0.051,0.034,1.3e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18490000,-0.28,0.015,-0.0052,0.96,-0.036,0.013,0.026,-0.015,0.006,0.029,-0.001,-0.0057,-0.00011,0.069,0.012,-0.14,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.9e-05,5.5e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
188 18590000,-0.28,0.016,-0.0068,0.96,-0.035,0.012,0.03,-0.015,0.0045,0.037,-0.001,-0.0057,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18590000,-0.28,0.015,-0.0051,0.96,-0.034,0.013,0.026,-0.013,0.0053,0.031,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
189 18690000,-0.28,0.016,-0.0067,0.96,-0.035,0.011,0.028,-0.017,0.0053,0.035,-0.0011,-0.0058,-0.00013,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.048,0.049,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18690000,-0.28,0.015,-0.0051,0.96,-0.034,0.012,0.024,-0.015,0.0063,0.03,-0.001,-0.0057,-0.00011,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
190 18790000,-0.28,0.015,-0.0067,0.96,-0.031,0.011,0.028,-0.014,0.0046,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18790000,-0.28,0.015,-0.0051,0.96,-0.031,0.012,0.024,-0.012,0.0054,0.028,-0.001,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0021,0.0024,0.00032,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
191 18890000,-0.28,0.015,-0.0067,0.96,-0.032,0.011,0.026,-0.017,0.0057,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.047,0.047,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18890000,-0.28,0.015,-0.005,0.96,-0.031,0.012,0.022,-0.015,0.0067,0.024,-0.001,-0.0058,-0.00012,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
192 18990000,-0.28,0.015,-0.0066,0.96,-0.029,0.011,0.027,-0.015,0.005,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.015,0.0079,0.042,0.042,0.034,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 18990000,-0.28,0.015,-0.005,0.96,-0.029,0.013,0.023,-0.013,0.0058,0.027,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
193 19090000,-0.28,0.015,-0.0067,0.96,-0.029,0.012,0.027,-0.017,0.0056,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.016,0.0079,0.045,0.046,0.035,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19090000,-0.28,0.015,-0.005,0.96,-0.028,0.013,0.023,-0.016,0.0066,0.024,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.8e-05,5.4e-05,0.05,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
194 19190000,-0.28,0.016,-0.0066,0.96,-0.026,0.013,0.027,-0.015,0.0056,0.028,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.8e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19190000,-0.28,0.015,-0.005,0.96,-0.026,0.014,0.023,-0.014,0.0065,0.023,-0.0011,-0.0058,-0.00012,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,6e-05,0.0012,0.0012,0.00068,0.0012,1,1
195 19290000,-0.28,0.016,-0.0066,0.96,-0.027,0.013,0.027,-0.018,0.0067,0.027,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.1e-06,9.7e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19290000,-0.28,0.015,-0.0049,0.96,-0.027,0.014,0.024,-0.016,0.0078,0.022,-0.0011,-0.0058,-0.00012,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
196 19390000,-0.28,0.015,-0.0067,0.96,-0.025,0.011,0.028,-0.016,0.0067,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0078,0.04,0.04,0.035,1.1e-06,9.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19390000,-0.28,0.015,-0.0051,0.96,-0.025,0.013,0.025,-0.014,0.0076,0.021,-0.0011,-0.0058,-0.00012,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
197 19490000,-0.28,0.015,-0.0068,0.96,-0.028,0.012,0.028,-0.019,0.008,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.044,0.035,1.1e-06,9.3e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19490000,-0.28,0.015,-0.0052,0.96,-0.028,0.014,0.024,-0.018,0.0091,0.021,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
198 19590000,-0.28,0.015,-0.0067,0.96,-0.024,0.013,0.03,-0.016,0.0063,0.026,-0.0011,-0.0058,-0.00016,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0077,0.039,0.04,0.035,1.1e-06,9e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19590000,-0.28,0.015,-0.005,0.96,-0.024,0.015,0.026,-0.015,0.0073,0.021,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
199 19690000,-0.28,0.016,-0.0067,0.96,-0.024,0.011,0.028,-0.019,0.007,0.026,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.043,0.035,1e-06,8.9e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19690000,-0.28,0.015,-0.005,0.96,-0.025,0.013,0.025,-0.018,0.0081,0.02,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
200 19790000,-0.28,0.015,-0.0068,0.96,-0.021,0.011,0.026,-0.019,0.0075,0.022,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0077,0.045,0.046,0.035,1e-06,8.7e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19790000,-0.28,0.015,-0.0051,0.96,-0.022,0.013,0.023,-0.018,0.0088,0.017,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
201 19890000,-0.28,0.016,-0.0068,0.96,-0.023,0.011,0.027,-0.021,0.0087,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0077,0.049,0.05,0.035,1e-06,8.6e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19890000,-0.28,0.015,-0.0052,0.96,-0.023,0.013,0.023,-0.02,0.01,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,5.9e-05,0.0012,0.0012,0.00068,0.0012,1,1
202 19990000,-0.28,0.016,-0.0068,0.96,-0.02,0.012,0.024,-0.016,0.0081,0.017,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0076,0.043,0.044,0.035,9.7e-07,8.3e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 19990000,-0.28,0.015,-0.0052,0.96,-0.02,0.014,0.021,-0.015,0.0093,0.012,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,5.9e-05,0.0012,0.0012,0.00067,0.0012,1,1
203 20090000,-0.28,0.016,-0.0068,0.96,-0.022,0.015,0.024,-0.018,0.0093,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0076,0.047,0.048,0.035,9.7e-07,8.2e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20090000,-0.28,0.015,-0.0052,0.96,-0.023,0.017,0.021,-0.018,0.011,0.015,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,5.9e-05,0.0012,0.0012,0.00067,0.0012,1,1
204 20190000,-0.28,0.016,-0.0068,0.96,-0.023,0.013,0.025,-0.019,0.0097,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0075,0.05,0.05,0.035,9.4e-07,8e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20190000,-0.28,0.015,-0.0052,0.96,-0.023,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,5.9e-05,0.0012,0.0012,0.00067,0.0012,1,1
205 20290000,-0.28,0.016,-0.0068,0.96,-0.021,0.015,0.025,-0.022,0.011,0.021,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.054,0.055,0.035,9.3e-07,7.9e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20290000,-0.28,0.015,-0.0052,0.96,-0.022,0.017,0.022,-0.021,0.013,0.016,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,5.9e-05,0.0012,0.0012,0.00067,0.0012,1,1
206 20390000,-0.28,0.016,-0.0067,0.96,-0.019,0.013,0.025,-0.022,0.01,0.022,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.056,0.057,0.035,9.1e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20390000,-0.28,0.015,-0.0051,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
207 20490000,-0.28,0.016,-0.0067,0.96,-0.017,0.015,0.025,-0.024,0.011,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0075,0.061,0.063,0.035,9e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20490000,-0.28,0.015,-0.0051,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
208 20590000,-0.28,0.016,-0.0066,0.96,-0.017,0.014,0.025,-0.024,0.01,0.018,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0074,0.064,0.065,0.035,8.8e-07,7.5e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20590000,-0.28,0.015,-0.005,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.3e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
209 20690000,-0.28,0.016,-0.0066,0.96,-0.016,0.014,0.026,-0.025,0.012,0.019,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.018,0.02,0.0074,0.069,0.071,0.035,8.7e-07,7.4e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20690000,-0.28,0.015,-0.0049,0.96,-0.017,0.017,0.023,-0.024,0.014,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
210 20790000,-0.28,0.016,-0.006,0.96,-0.01,0.01,0.01,-0.019,0.0088,0.017,-0.0012,-0.0058,-0.00018,0.072,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.017,0.0073,0.057,0.057,0.035,8.4e-07,7.1e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20790000,-0.28,0.015,-0.0043,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
211 20890000,-0.28,0.011,0.0027,0.96,-0.0058,-5.9e-05,-0.11,-0.021,0.0092,0.011,-0.0012,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00037,0.00034,0.046,0.017,0.018,0.0073,0.061,0.062,0.035,8.3e-07,7.1e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20890000,-0.29,0.01,0.0044,0.96,-0.0062,0.0017,-0.11,-0.02,0.011,0.0065,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
212 20990000,-0.28,0.0071,0.0057,0.96,0.0086,-0.017,-0.25,-0.017,0.007,-0.004,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.016,0.0072,0.052,0.052,0.034,8e-07,6.9e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20990000,-0.29,0.0064,0.0073,0.96,0.0087,-0.015,-0.25,-0.017,0.0083,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
213 21090000,-0.28,0.0076,0.0042,0.96,0.022,-0.029,-0.37,-0.016,0.005,-0.035,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.017,0.0072,0.056,0.057,0.035,8e-07,6.8e-07,4.2e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 21090000,-0.29,0.0069,0.0058,0.96,0.022,-0.028,-0.37,-0.015,0.0064,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.8e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
214 21190000,-0.28,0.0095,0.0015,0.96,0.028,-0.035,-0.49,-0.013,0.0038,-0.071,-0.0011,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.014,0.016,0.0071,0.048,0.049,0.035,7.7e-07,6.6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 21190000,-0.29,0.0088,0.0032,0.96,0.028,-0.034,-0.5,-0.013,0.0048,-0.076,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
215 21290000,-0.28,0.011,-0.00054,0.96,0.026,-0.037,-0.62,-0.011,0.0011,-0.13,-0.0011,-0.0058,-0.00019,0.072,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.0071,0.052,0.053,0.035,7.7e-07,6.5e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 21290000,-0.29,0.01,0.0011,0.96,0.027,-0.036,-0.63,-0.01,0.0022,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
216 21390000,-0.28,0.012,-0.002,0.96,0.019,-0.029,-0.75,-0.013,0.0046,-0.19,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.016,0.017,0.007,0.054,0.055,0.035,7.5e-07,6.4e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 21390000,-0.29,0.011,-0.00034,0.96,0.021,-0.029,-0.75,-0.012,0.0054,-0.2,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
217 21490000,-0.28,0.012,-0.0028,0.96,0.013,-0.027,-0.88,-0.011,0.0015,-0.28,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.017,0.018,0.007,0.059,0.06,0.035,7.4e-07,6.3e-07,4.1e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21490000,-0.29,0.012,-0.0011,0.96,0.014,-0.028,-0.89,-0.0097,0.0023,-0.28,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
218 21590000,-0.28,0.012,-0.0034,0.96,0.0009,-0.021,-1,-0.015,0.0065,-0.37,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.017,0.018,0.0069,0.061,0.063,0.034,7.3e-07,6.2e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21590000,-0.29,0.012,-0.0016,0.96,0.0024,-0.022,-1,-0.014,0.0069,-0.37,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,5.9e-05,0.0012,0.0011,0.00067,0.0012,1,1
219 21690000,-0.28,0.012,-0.0037,0.96,-0.0046,-0.017,-1.1,-0.015,0.004,-0.48,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0069,0.066,0.068,0.035,7.2e-07,6.1e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21690000,-0.29,0.012,-0.0019,0.96,-0.0028,-0.019,-1.1,-0.014,0.0042,-0.49,-0.0011,-0.0058,-0.00011,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,5.8e-05,0.0012,0.0011,0.00067,0.0012,1,1
220 21790000,-0.28,0.012,-0.0041,0.96,-0.011,-0.0087,-1.3,-0.017,0.01,-0.6,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.019,0.0069,0.069,0.07,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21790000,-0.29,0.012,-0.0023,0.96,-0.0086,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,5.8e-05,0.0012,0.0011,0.00067,0.0012,1,1
221 21890000,-0.28,0.013,-0.0044,0.96,-0.017,-0.0041,-1.4,-0.018,0.01,-0.74,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0068,0.074,0.076,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21890000,-0.29,0.012,-0.0026,0.96,-0.014,-0.007,-1.4,-0.016,0.0099,-0.75,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
222 21990000,-0.28,0.013,-0.0052,0.96,-0.022,0.0043,-1.4,-0.024,0.018,-0.88,-0.0011,-0.0058,-8.8e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0068,0.077,0.079,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21990000,-0.29,0.012,-0.0033,0.96,-0.02,0.0012,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
223 22090000,-0.28,0.014,-0.0058,0.96,-0.025,0.0075,-1.4,-0.025,0.018,-1,-0.0011,-0.0058,-8.2e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0068,0.083,0.085,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 22090000,-0.29,0.013,-0.004,0.96,-0.023,0.0045,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
224 22190000,-0.28,0.014,-0.0063,0.96,-0.032,0.014,-1.4,-0.03,0.025,-1.2,-0.0011,-0.0058,-5.9e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0067,0.085,0.087,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22190000,-0.29,0.013,-0.0044,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0021,0.00019,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
225 22290000,-0.28,0.014,-0.007,0.96,-0.04,0.019,-1.4,-0.034,0.027,-1.3,-0.0011,-0.0058,-6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0067,0.091,0.094,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22290000,-0.29,0.014,-0.0051,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
226 22390000,-0.28,0.015,-0.0073,0.96,-0.047,0.026,-1.4,-0.04,0.031,-1.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0066,0.094,0.096,0.034,6.4e-07,5.5e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22390000,-0.29,0.014,-0.0054,0.96,-0.045,0.023,-1.4,-0.038,0.03,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
227 22490000,-0.28,0.015,-0.0074,0.96,-0.053,0.032,-1.4,-0.045,0.034,-1.6,-0.0011,-0.0058,-6.4e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0066,0.1,0.1,0.034,6.4e-07,5.4e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22490000,-0.29,0.014,-0.0055,0.96,-0.052,0.029,-1.4,-0.043,0.033,-1.6,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
228 22590000,-0.28,0.016,-0.0073,0.96,-0.058,0.038,-1.4,-0.046,0.038,-1.7,-0.0011,-0.0058,-5.7e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.1,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22590000,-0.29,0.015,-0.0054,0.96,-0.056,0.035,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
229 22690000,-0.28,0.016,-0.0072,0.96,-0.062,0.042,-1.4,-0.053,0.042,-1.9,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.11,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22690000,-0.29,0.015,-0.0053,0.96,-0.061,0.04,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
230 22790000,-0.28,0.016,-0.0071,0.96,-0.069,0.047,-1.4,-0.059,0.045,-2,-0.0011,-0.0058,-6.6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.11,0.11,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22790000,-0.29,0.016,-0.0052,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
231 22890000,-0.28,0.017,-0.0072,0.96,-0.074,0.051,-1.4,-0.065,0.048,-2.2,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.12,0.12,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22890000,-0.29,0.016,-0.0053,0.96,-0.073,0.049,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
232 22990000,-0.28,0.017,-0.007,0.96,-0.076,0.051,-1.4,-0.068,0.047,-2.3,-0.0011,-0.0058,-6.3e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.022,0.0064,0.12,0.12,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22990000,-0.29,0.016,-0.0051,0.96,-0.076,0.049,-1.4,-0.066,0.045,-2.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
233 23090000,-0.28,0.017,-0.007,0.96,-0.082,0.055,-1.4,-0.075,0.053,-2.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0064,0.13,0.13,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23090000,-0.29,0.017,-0.0051,0.96,-0.082,0.053,-1.4,-0.073,0.05,-2.5,-0.0011,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.049,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
234 23190000,-0.28,0.017,-0.0069,0.96,-0.084,0.05,-1.4,-0.074,0.049,-2.6,-0.0011,-0.0058,-8.4e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.13,0.13,0.033,5.7e-07,4.9e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23190000,-0.29,0.017,-0.005,0.96,-0.083,0.048,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
235 23290000,-0.28,0.018,-0.0073,0.96,-0.09,0.054,-1.4,-0.083,0.053,-2.7,-0.0011,-0.0058,-8e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.14,0.14,0.034,5.6e-07,4.8e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23290000,-0.29,0.017,-0.0055,0.96,-0.09,0.052,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
236 23390000,-0.28,0.018,-0.0073,0.96,-0.089,0.056,-1.4,-0.077,0.055,-2.9,-0.0011,-0.0058,-9.8e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.14,0.14,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23390000,-0.28,0.017,-0.0054,0.96,-0.089,0.055,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.9e-05,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
237 23490000,-0.28,0.018,-0.0073,0.96,-0.096,0.057,-1.4,-0.088,0.059,-3,-0.0011,-0.0058,-9e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.15,0.15,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23490000,-0.28,0.017,-0.0055,0.96,-0.096,0.055,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
238 23590000,-0.28,0.018,-0.0074,0.96,-0.094,0.051,-1.4,-0.083,0.049,-3.2,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0062,0.15,0.15,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23590000,-0.29,0.017,-0.0056,0.96,-0.094,0.049,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
239 23690000,-0.28,0.019,-0.008,0.96,-0.093,0.053,-1.3,-0.092,0.053,-3.3,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0062,0.16,0.16,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23690000,-0.29,0.018,-0.0062,0.96,-0.093,0.052,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.3e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
240 23790000,-0.28,0.021,-0.0095,0.96,-0.077,0.049,-0.95,-0.082,0.049,-3.4,-0.0012,-0.0058,-0.00012,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00039,0.00036,0.045,0.021,0.022,0.0061,0.16,0.16,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23790000,-0.29,0.021,-0.0077,0.96,-0.079,0.049,-0.95,-0.08,0.048,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
241 23890000,-0.28,0.026,-0.012,0.96,-0.071,0.05,-0.52,-0.089,0.053,-3.5,-0.0012,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00042,0.00038,0.045,0.021,0.023,0.0061,0.17,0.17,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23890000,-0.29,0.025,-0.011,0.96,-0.073,0.052,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
242 23990000,-0.28,0.028,-0.014,0.96,-0.061,0.048,-0.13,-0.077,0.048,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.02,0.022,0.0061,0.17,0.17,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23990000,-0.29,0.028,-0.012,0.96,-0.064,0.051,-0.13,-0.074,0.047,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00066,0.0012,1,1
243 24090000,-0.28,0.027,-0.014,0.96,-0.067,0.055,0.1,-0.082,0.053,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.021,0.023,0.0061,0.18,0.18,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 24090000,-0.29,0.027,-0.012,0.96,-0.071,0.059,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
244 24190000,-0.28,0.023,-0.011,0.96,-0.071,0.052,0.089,-0.069,0.04,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.0004,0.00037,0.045,0.02,0.022,0.006,0.18,0.18,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 24190000,-0.29,0.022,-0.0094,0.96,-0.075,0.055,0.088,-0.067,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
245 24290000,-0.28,0.02,-0.0093,0.96,-0.076,0.055,0.068,-0.076,0.045,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.023,0.006,0.19,0.19,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 24290000,-0.29,0.019,-0.0074,0.96,-0.08,0.057,0.066,-0.074,0.045,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
246 24390000,-0.28,0.018,-0.0085,0.96,-0.059,0.048,0.084,-0.058,0.036,-3.6,-0.0013,-0.0058,-0.00016,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.02,0.022,0.006,0.19,0.19,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 24390000,-0.29,0.018,-0.0065,0.96,-0.064,0.051,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
247 24490000,-0.28,0.019,-0.0087,0.96,-0.054,0.044,0.081,-0.063,0.039,-3.6,-0.0013,-0.0058,-0.00014,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.021,0.023,0.006,0.2,0.2,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 24490000,-0.29,0.018,-0.0067,0.96,-0.058,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
248 24590000,-0.28,0.019,-0.0094,0.96,-0.043,0.042,0.077,-0.045,0.033,-3.6,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.022,0.0059,0.2,0.2,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24590000,-0.29,0.018,-0.0073,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
249 24690000,-0.28,0.019,-0.0099,0.96,-0.041,0.041,0.076,-0.049,0.037,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.024,0.0059,0.21,0.21,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24690000,-0.29,0.018,-0.0078,0.96,-0.045,0.045,0.075,-0.047,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
250 24790000,-0.28,0.018,-0.01,0.96,-0.034,0.04,0.068,-0.037,0.029,-3.5,-0.0013,-0.0058,-0.00017,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0059,0.21,0.21,0.032,4.7e-07,4.1e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24790000,-0.29,0.017,-0.0079,0.96,-0.038,0.043,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.1e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.8e-05,0.0012,0.0011,0.00065,0.0012,1,1
251 24890000,-0.28,0.017,-0.0099,0.96,-0.033,0.042,0.058,-0.04,0.032,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0059,0.22,0.22,0.032,4.7e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24890000,-0.29,0.017,-0.0078,0.96,-0.037,0.046,0.056,-0.038,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
252 24990000,-0.28,0.017,-0.0097,0.96,-0.021,0.043,0.05,-0.026,0.027,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.22,0.22,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24990000,-0.29,0.016,-0.0076,0.96,-0.025,0.046,0.049,-0.023,0.027,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
253 25090000,-0.28,0.017,-0.01,0.96,-0.016,0.043,0.048,-0.027,0.031,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.23,0.23,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25090000,-0.29,0.016,-0.0079,0.96,-0.02,0.046,0.047,-0.024,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
254 25190000,-0.28,0.017,-0.01,0.96,-0.006,0.038,0.048,-0.011,0.021,-3.5,-0.0013,-0.0059,-0.0002,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.23,0.23,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25190000,-0.29,0.016,-0.0081,0.96,-0.01,0.042,0.047,-0.0082,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
255 25290000,-0.28,0.016,-0.01,0.96,-0.0013,0.041,0.043,-0.012,0.026,-3.5,-0.0013,-0.0059,-0.00021,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.24,0.24,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25290000,-0.29,0.015,-0.0083,0.96,-0.0055,0.045,0.042,-0.0088,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
256 25390000,-0.28,0.016,-0.011,0.96,0.0076,0.039,0.041,-0.0022,0.02,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.24,0.24,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25390000,-0.29,0.015,-0.0084,0.96,0.0035,0.043,0.04,0.0011,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
257 25490000,-0.28,0.016,-0.011,0.96,0.012,0.04,0.041,-0.0021,0.024,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.25,0.25,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25490000,-0.29,0.015,-0.0085,0.96,0.0079,0.044,0.04,0.00085,0.025,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
258 25590000,-0.28,0.016,-0.011,0.96,0.017,0.035,0.042,0.0049,0.0094,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.25,0.25,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25590000,-0.29,0.015,-0.0086,0.96,0.013,0.04,0.041,0.0083,0.01,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
259 25690000,-0.28,0.015,-0.01,0.96,0.018,0.034,0.031,0.0066,0.013,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.26,0.26,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25690000,-0.29,0.014,-0.0081,0.96,0.014,0.039,0.03,0.0097,0.014,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
260 25790000,-0.28,0.015,-0.01,0.96,0.028,0.029,0.031,0.014,0.0031,-3.5,-0.0014,-0.0058,-0.00025,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.26,0.032,4.2e-07,3.7e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25790000,-0.29,0.014,-0.008,0.96,0.024,0.034,0.03,0.017,0.0038,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
261 25890000,-0.28,0.015,-0.01,0.96,0.034,0.029,0.033,0.017,0.0067,-3.5,-0.0014,-0.0058,-0.00026,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.27,0.27,0.032,4.2e-07,3.7e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25890000,-0.29,0.014,-0.008,0.96,0.03,0.034,0.033,0.02,0.008,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
262 25990000,-0.28,0.015,-0.01,0.96,0.036,0.024,0.027,0.013,-0.004,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.27,0.27,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25990000,-0.29,0.014,-0.008,0.96,0.033,0.029,0.026,0.017,-0.0032,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
263 26090000,-0.28,0.015,-0.0099,0.96,0.041,0.024,0.025,0.017,-0.0023,-3.5,-0.0014,-0.0058,-0.00027,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.28,0.28,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26090000,-0.29,0.014,-0.0077,0.96,0.038,0.029,0.025,0.02,-0.0011,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
264 26190000,-0.28,0.015,-0.0098,0.96,0.046,0.015,0.021,0.02,-0.018,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.27,0.28,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26190000,-0.29,0.014,-0.0075,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
265 26290000,-0.28,0.016,-0.0098,0.96,0.046,0.014,0.015,0.024,-0.016,-3.5,-0.0014,-0.0058,-0.00029,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.29,0.29,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26290000,-0.29,0.015,-0.0075,0.96,0.043,0.019,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
266 26390000,-0.28,0.016,-0.0092,0.96,0.043,0.0051,0.019,0.015,-0.03,-3.5,-0.0014,-0.0058,-0.0003,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0056,0.28,0.29,0.032,4e-07,3.5e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26390000,-0.29,0.015,-0.0069,0.96,0.04,0.01,0.019,0.019,-0.029,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
267 26490000,-0.28,0.016,-0.009,0.96,0.046,0.0028,0.028,0.02,-0.03,-3.5,-0.0014,-0.0058,-0.00031,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.3,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26490000,-0.29,0.015,-0.0067,0.96,0.043,0.0084,0.028,0.023,-0.028,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
268 26590000,-0.28,0.016,-0.0084,0.96,0.045,-0.0071,0.029,0.019,-0.042,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0056,0.29,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26590000,-0.29,0.015,-0.0061,0.96,0.042,-0.0016,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
269 26690000,-0.28,0.016,-0.0083,0.96,0.047,-0.011,0.027,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.31,0.31,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26690000,-0.29,0.015,-0.006,0.96,0.044,-0.0052,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00065,0.0012,1,1
270 26790000,-0.27,0.015,-0.0081,0.96,0.049,-0.017,0.027,0.02,-0.055,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.3,0.31,0.031,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26790000,-0.29,0.014,-0.0058,0.96,0.047,-0.011,0.026,0.024,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
271 26890000,-0.27,0.015,-0.0074,0.96,0.055,-0.02,0.022,0.026,-0.057,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.32,0.32,0.032,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26890000,-0.29,0.014,-0.0052,0.96,0.053,-0.014,0.022,0.029,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
272 26990000,-0.27,0.016,-0.0069,0.96,0.056,-0.026,0.021,0.018,-0.064,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.31,0.32,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26990000,-0.29,0.014,-0.0046,0.96,0.054,-0.02,0.021,0.022,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
273 27090000,-0.27,0.016,-0.0067,0.96,0.058,-0.033,0.025,0.024,-0.067,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0055,0.33,0.33,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27090000,-0.29,0.015,-0.0044,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
274 27190000,-0.27,0.016,-0.0068,0.96,0.058,-0.036,0.027,0.014,-0.069,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.32,0.33,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27190000,-0.29,0.015,-0.0045,0.96,0.057,-0.031,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
275 27290000,-0.27,0.017,-0.0069,0.96,0.066,-0.041,0.14,0.02,-0.073,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.022,0.024,0.0055,0.33,0.34,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27290000,-0.29,0.016,-0.0045,0.96,0.064,-0.034,0.14,0.024,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
276 27390000,-0.27,0.019,-0.0081,0.96,0.07,-0.034,0.46,0.0048,-0.026,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27390000,-0.29,0.018,-0.0057,0.96,0.067,-0.026,0.46,0.0069,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
277 27490000,-0.27,0.021,-0.0093,0.96,0.076,-0.037,0.78,0.012,-0.029,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.016,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27490000,-0.29,0.02,-0.0069,0.96,0.072,-0.029,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
278 27590000,-0.27,0.02,-0.0093,0.96,0.067,-0.039,0.87,0.0064,-0.02,-3.4,-0.0014,-0.0058,-0.00032,0.074,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.014,0.015,0.0055,0.096,0.097,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27590000,-0.29,0.019,-0.0069,0.96,0.063,-0.031,0.87,0.0076,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
279 27690000,-0.27,0.017,-0.0084,0.96,0.061,-0.036,0.78,0.013,-0.024,-3.3,-0.0014,-0.0058,-0.00031,0.075,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0055,0.1,0.1,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27690000,-0.29,0.016,-0.006,0.96,0.057,-0.028,0.78,0.014,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
280 27790000,-0.27,0.016,-0.0072,0.96,0.058,-0.034,0.77,0.01,-0.019,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.013,0.015,0.0054,0.073,0.074,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 27790000,-0.29,0.015,-0.0048,0.96,0.054,-0.027,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
281 27890000,-0.27,0.016,-0.0068,0.96,0.064,-0.04,0.81,0.016,-0.023,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.014,0.016,0.0055,0.076,0.077,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 27890000,-0.29,0.015,-0.0045,0.96,0.06,-0.032,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
282 27990000,-0.27,0.016,-0.0072,0.96,0.064,-0.042,0.8,0.019,-0.026,-3.1,-0.0014,-0.0058,-0.00029,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0054,0.079,0.079,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 27990000,-0.29,0.015,-0.0048,0.96,0.061,-0.035,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
283 28090000,-0.27,0.016,-0.0075,0.96,0.068,-0.043,0.8,0.026,-0.03,-3,-0.0014,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.082,0.083,0.031,3.6e-07,3.1e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28090000,-0.29,0.015,-0.0051,0.96,0.064,-0.035,0.8,0.026,-0.028,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
284 28190000,-0.27,0.016,-0.0069,0.96,0.065,-0.041,0.81,0.027,-0.032,-2.9,-0.0013,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.085,0.085,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28190000,-0.29,0.015,-0.0045,0.96,0.062,-0.034,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
285 28290000,-0.27,0.017,-0.0064,0.96,0.069,-0.044,0.81,0.033,-0.037,-2.9,-0.0013,-0.0058,-0.00027,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.016,0.018,0.0054,0.089,0.09,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28290000,-0.29,0.016,-0.0039,0.96,0.066,-0.037,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
286 28390000,-0.27,0.017,-0.0063,0.96,0.07,-0.046,0.81,0.035,-0.038,-2.8,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0054,0.091,0.092,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28390000,-0.29,0.016,-0.0039,0.96,0.067,-0.039,0.81,0.035,-0.035,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
287 28490000,-0.27,0.018,-0.0066,0.96,0.073,-0.049,0.81,0.043,-0.042,-2.7,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.095,0.097,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28490000,-0.29,0.017,-0.0041,0.96,0.07,-0.042,0.81,0.042,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
288 28590000,-0.27,0.018,-0.0066,0.96,0.065,-0.049,0.81,0.043,-0.045,-2.6,-0.0013,-0.0058,-0.00023,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.098,0.099,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28590000,-0.29,0.017,-0.0041,0.96,0.063,-0.043,0.81,0.043,-0.042,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
289 28690000,-0.27,0.017,-0.0064,0.96,0.064,-0.05,0.81,0.05,-0.05,-2.6,-0.0013,-0.0058,-0.00024,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.017,0.019,0.0054,0.1,0.1,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28690000,-0.29,0.016,-0.004,0.96,0.062,-0.044,0.81,0.049,-0.046,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
290 28790000,-0.27,0.017,-0.0058,0.96,0.062,-0.049,0.81,0.051,-0.049,-2.5,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.11,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28790000,-0.29,0.016,-0.0034,0.96,0.06,-0.043,0.81,0.05,-0.045,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
291 28890000,-0.27,0.016,-0.0056,0.96,0.065,-0.051,0.81,0.057,-0.054,-2.4,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.02,0.0054,0.11,0.11,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28890000,-0.29,0.015,-0.0032,0.96,0.063,-0.045,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
292 28990000,-0.27,0.016,-0.0054,0.96,0.063,-0.048,0.81,0.058,-0.054,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.017,0.019,0.0053,0.11,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28990000,-0.29,0.016,-0.0029,0.96,0.062,-0.043,0.81,0.057,-0.049,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
293 29090000,-0.27,0.017,-0.0052,0.96,0.067,-0.05,0.81,0.066,-0.059,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29090000,-0.29,0.016,-0.0028,0.96,0.065,-0.044,0.81,0.065,-0.054,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
294 29190000,-0.27,0.017,-0.0051,0.96,0.067,-0.049,0.8,0.067,-0.058,-2.2,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29190000,-0.29,0.016,-0.0027,0.96,0.066,-0.043,0.8,0.066,-0.053,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
295 29290000,-0.27,0.017,-0.0054,0.96,0.071,-0.054,0.81,0.076,-0.062,-2.1,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.021,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29290000,-0.29,0.016,-0.0029,0.96,0.07,-0.049,0.81,0.075,-0.057,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
296 29390000,-0.27,0.016,-0.0059,0.96,0.067,-0.051,0.81,0.074,-0.059,-2,-0.0013,-0.0058,-0.00014,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29390000,-0.29,0.015,-0.0035,0.96,0.067,-0.046,0.81,0.073,-0.054,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
297 29490000,-0.27,0.016,-0.0059,0.96,0.07,-0.052,0.81,0.081,-0.065,-2,-0.0013,-0.0058,-0.00013,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29490000,-0.29,0.015,-0.0034,0.96,0.07,-0.047,0.81,0.081,-0.06,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
298 29590000,-0.27,0.016,-0.0058,0.96,0.068,-0.05,0.81,0.08,-0.063,-1.9,-0.0013,-0.0058,-0.00011,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.018,0.021,0.0053,0.14,0.14,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29590000,-0.29,0.015,-0.0033,0.96,0.067,-0.046,0.81,0.079,-0.058,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
299 29690000,-0.27,0.016,-0.0058,0.96,0.072,-0.049,0.81,0.087,-0.068,-1.8,-0.0013,-0.0058,-9.8e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.019,0.022,0.0053,0.15,0.15,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 29690000,-0.29,0.015,-0.0034,0.96,0.072,-0.045,0.81,0.087,-0.063,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
300 29790000,-0.27,0.016,-0.0056,0.96,0.069,-0.042,0.8,0.084,-0.064,-1.7,-0.0013,-0.0058,-6.9e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0053,0.15,0.15,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 29790000,-0.29,0.015,-0.0031,0.96,0.069,-0.039,0.8,0.084,-0.06,-1.7,-0.0013,-0.0058,-9.8e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
301 29890000,-0.27,0.016,-0.005,0.96,0.07,-0.044,0.8,0.092,-0.069,-1.7,-0.0013,-0.0058,-6.2e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0053,0.15,0.16,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 29890000,-0.29,0.015,-0.0025,0.96,0.071,-0.04,0.8,0.092,-0.064,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
302 29990000,-0.27,0.016,-0.0052,0.96,0.065,-0.041,0.8,0.087,-0.068,-1.6,-0.0013,-0.0058,-4.8e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.16,0.16,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 29990000,-0.29,0.016,-0.0027,0.96,0.065,-0.038,0.8,0.086,-0.063,-1.6,-0.0013,-0.0058,-8.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
303 30090000,-0.27,0.017,-0.0053,0.96,0.067,-0.041,0.8,0.094,-0.07,-1.5,-0.0013,-0.0058,-6.2e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.16,0.17,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30090000,-0.29,0.016,-0.0028,0.96,0.067,-0.038,0.8,0.094,-0.065,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
304 30190000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.089,-0.061,-1.5,-0.0013,-0.0058,-5e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.17,0.17,0.031,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30190000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.088,-0.057,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
305 30290000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.096,-0.065,-1.4,-0.0013,-0.0058,-4.9e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.17,0.18,0.03,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30290000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.096,-0.06,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
306 30390000,-0.27,0.016,-0.0054,0.96,0.059,-0.029,0.8,0.095,-0.059,-1.3,-0.0013,-0.0058,-1.9e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.18,0.18,0.03,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30390000,-0.29,0.015,-0.0028,0.96,0.06,-0.026,0.8,0.095,-0.054,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
307 30490000,-0.27,0.016,-0.0054,0.96,0.063,-0.028,0.8,0.1,-0.062,-1.2,-0.0013,-0.0058,-1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.18,0.19,0.031,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30490000,-0.29,0.015,-0.0028,0.96,0.063,-0.026,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
308 30590000,-0.27,0.017,-0.0056,0.96,0.061,-0.026,0.8,0.097,-0.058,-1.2,-0.0013,-0.0058,1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.18,0.19,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30590000,-0.29,0.016,-0.0031,0.96,0.062,-0.025,0.8,0.097,-0.054,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
309 30690000,-0.27,0.017,-0.006,0.96,0.058,-0.026,0.8,0.1,-0.061,-1.1,-0.0013,-0.0058,1.1e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00035,0.044,0.02,0.023,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30690000,-0.29,0.016,-0.0034,0.96,0.059,-0.024,0.8,0.1,-0.057,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
310 30790000,-0.27,0.016,-0.0058,0.96,0.052,-0.016,0.8,0.095,-0.049,-1,-0.0012,-0.0058,3.6e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30790000,-0.29,0.016,-0.0032,0.96,0.053,-0.014,0.79,0.096,-0.045,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
311 30890000,-0.27,0.016,-0.0052,0.96,0.051,-0.012,0.79,0.099,-0.05,-0.95,-0.0012,-0.0058,2.6e-05,0.072,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30890000,-0.29,0.015,-0.0026,0.96,0.051,-0.011,0.79,0.1,-0.046,-0.95,-0.0012,-0.0058,-4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
312 30990000,-0.27,0.016,-0.0054,0.96,0.046,-0.01,0.79,0.095,-0.048,-0.88,-0.0012,-0.0058,3e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30990000,-0.29,0.015,-0.0027,0.96,0.047,-0.0093,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
313 31090000,-0.27,0.016,-0.0055,0.96,0.045,-0.0087,0.79,0.099,-0.049,-0.81,-0.0012,-0.0058,2.2e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.21,0.22,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 31090000,-0.29,0.015,-0.0029,0.96,0.046,-0.008,0.79,0.099,-0.045,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
314 31190000,-0.27,0.017,-0.0057,0.96,0.042,-0.0051,0.8,0.093,-0.044,-0.74,-0.0012,-0.0058,4.6e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 31190000,-0.29,0.016,-0.003,0.96,0.043,-0.0048,0.8,0.093,-0.041,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
315 31290000,-0.27,0.017,-0.0059,0.96,0.039,-0.0033,0.8,0.096,-0.045,-0.67,-0.0012,-0.0058,5.2e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 31290000,-0.29,0.016,-0.0032,0.96,0.04,-0.0032,0.8,0.097,-0.042,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
316 31390000,-0.27,0.016,-0.0057,0.96,0.035,0.0017,0.8,0.09,-0.042,-0.59,-0.0012,-0.0058,5.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 31390000,-0.29,0.015,-0.003,0.96,0.036,0.0017,0.8,0.091,-0.038,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
317 31490000,-0.27,0.017,-0.0054,0.96,0.036,0.0051,0.8,0.095,-0.041,-0.52,-0.0012,-0.0058,4.8e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 31490000,-0.29,0.016,-0.0027,0.96,0.037,0.0051,0.8,0.096,-0.037,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
318 31590000,-0.27,0.017,-0.0052,0.96,0.036,0.007,0.8,0.092,-0.037,-0.45,-0.0012,-0.0058,6.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 31590000,-0.29,0.016,-0.0025,0.96,0.037,0.0069,0.8,0.093,-0.034,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
319 31690000,-0.27,0.017,-0.0052,0.96,0.04,0.0082,0.8,0.097,-0.037,-0.38,-0.0012,-0.0058,7.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 31690000,-0.29,0.016,-0.0025,0.96,0.041,0.0079,0.8,0.098,-0.033,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
320 31790000,-0.27,0.018,-0.0054,0.96,0.034,0.014,0.8,0.093,-0.027,-0.3,-0.0012,-0.0058,9e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 31790000,-0.29,0.017,-0.0027,0.96,0.035,0.013,0.8,0.094,-0.024,-0.3,-0.0012,-0.0058,-6.2e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
321 31890000,-0.27,0.018,-0.0052,0.96,0.032,0.016,0.8,0.097,-0.025,-0.23,-0.0012,-0.0058,9.4e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.25,0.26,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 31890000,-0.29,0.017,-0.0024,0.96,0.034,0.015,0.8,0.099,-0.022,-0.24,-0.0012,-0.0058,1.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
322 31990000,-0.27,0.017,-0.0055,0.96,0.029,0.017,0.79,0.094,-0.02,-0.17,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 31990000,-0.29,0.016,-0.0027,0.96,0.03,0.016,0.79,0.095,-0.017,-0.17,-0.0012,-0.0058,9.2e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
323 32090000,-0.27,0.017,-0.0059,0.96,0.03,0.021,0.8,0.098,-0.018,-0.096,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32090000,-0.29,0.016,-0.0032,0.96,0.031,0.02,0.8,0.099,-0.015,-0.096,-0.0012,-0.0058,4.9e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
324 32190000,-0.27,0.017,-0.0061,0.96,0.027,0.029,0.8,0.093,-0.0092,-0.027,-0.0012,-0.0058,9.7e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32190000,-0.28,0.016,-0.0034,0.96,0.028,0.027,0.8,0.094,-0.0059,-0.028,-0.0012,-0.0058,3.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.6e-05,0.0012,0.0011,0.00064,0.0012,1,1
325 32290000,-0.27,0.017,-0.006,0.96,0.027,0.031,0.8,0.096,-0.0063,0.042,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32290000,-0.28,0.016,-0.0033,0.96,0.028,0.03,0.79,0.098,-0.0032,0.042,-0.0012,-0.0058,7.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
326 32390000,-0.27,0.017,-0.0062,0.96,0.023,0.033,0.79,0.092,-0.0029,0.12,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32390000,-0.28,0.016,-0.0034,0.96,0.025,0.032,0.79,0.094,0.00049,0.12,-0.0012,-0.0058,5.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
327 32490000,-0.27,0.016,-0.0092,0.96,-0.017,0.092,-0.077,0.091,0.0054,0.12,-0.0012,-0.0058,9.6e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32490000,-0.28,0.015,-0.0065,0.96,-0.015,0.085,-0.078,0.092,0.0082,0.12,-0.0012,-0.0058,3.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
328 32590000,-0.27,0.016,-0.0092,0.96,-0.014,0.09,-0.08,0.091,-0.0025,0.1,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.021,0.023,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32590000,-0.29,0.015,-0.0065,0.96,-0.013,0.084,-0.081,0.092,0.0012,0.1,-0.0012,-0.0058,-1.7e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
329 32690000,-0.27,0.016,-0.0092,0.96,-0.01,0.097,-0.081,0.09,0.0069,0.088,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32690000,-0.29,0.015,-0.0065,0.96,-0.0086,0.091,-0.082,0.091,0.01,0.087,-0.0012,-0.0058,-1.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
330 32790000,-0.27,0.016,-0.009,0.96,-0.0062,0.095,-0.082,0.092,-0.0016,0.073,-0.0012,-0.0058,7.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32790000,-0.29,0.015,-0.0063,0.96,-0.0047,0.09,-0.083,0.093,0.0025,0.072,-0.0012,-0.0058,-7.2e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
331 32890000,-0.27,0.016,-0.009,0.96,-0.0066,0.1,-0.084,0.09,0.0078,0.058,-0.0012,-0.0058,8.1e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32890000,-0.29,0.015,-0.0063,0.96,-0.0051,0.096,-0.085,0.091,0.011,0.057,-0.0012,-0.0058,-2.7e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
332 32990000,-0.27,0.016,-0.0088,0.96,-0.0026,0.095,-0.083,0.091,-0.006,0.044,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32990000,-0.29,0.015,-0.0062,0.96,-0.0013,0.091,-0.084,0.092,-0.0018,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
333 33090000,-0.27,0.016,-0.0088,0.96,0.0013,0.1,-0.08,0.091,0.0037,0.037,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.31,0.32,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33090000,-0.29,0.015,-0.0061,0.96,0.0026,0.097,-0.081,0.092,0.0075,0.036,-0.0013,-0.0058,-9.7e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
334 33190000,-0.27,0.016,-0.0086,0.96,0.0057,0.096,-0.079,0.092,-0.012,0.029,-0.0012,-0.0058,4e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33190000,-0.29,0.015,-0.0061,0.96,0.0067,0.093,-0.08,0.092,-0.0072,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
335 33290000,-0.27,0.016,-0.0087,0.96,0.0098,0.099,-0.079,0.093,-0.0027,0.021,-0.0013,-0.0058,5.7e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33290000,-0.29,0.015,-0.0061,0.96,0.011,0.096,-0.08,0.094,0.0016,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
336 33390000,-0.27,0.016,-0.0086,0.96,0.014,0.095,-0.077,0.092,-0.012,0.012,-0.0013,-0.0058,4.6e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33390000,-0.29,0.015,-0.006,0.96,0.015,0.092,-0.078,0.093,-0.0066,0.011,-0.0013,-0.0058,-2.6e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
337 33490000,-0.27,0.016,-0.0086,0.96,0.02,0.099,-0.076,0.095,-0.0019,0.0028,-0.0013,-0.0058,5.4e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.33,0.34,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33490000,-0.29,0.015,-0.006,0.96,0.021,0.097,-0.077,0.097,0.0027,0.0017,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
338 33590000,-0.27,0.016,-0.0084,0.96,0.023,0.096,-0.073,0.094,-0.015,-0.0051,-0.0013,-0.0058,4.8e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.33,0.34,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33590000,-0.29,0.014,-0.0058,0.96,0.024,0.094,-0.074,0.096,-0.01,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
339 33690000,-0.27,0.016,-0.0084,0.96,0.026,0.099,-0.074,0.095,-0.0061,-0.013,-0.0013,-0.0058,5.3e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.34,0.35,0.03,2.7e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33690000,-0.29,0.015,-0.0058,0.96,0.027,0.098,-0.075,0.097,-0.0012,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
340 33790000,-0.27,0.016,-0.0083,0.96,0.029,0.096,-0.068,0.092,-0.02,-0.02,-0.0013,-0.0058,3.3e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.34,0.35,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33790000,-0.29,0.015,-0.0058,0.96,0.029,0.095,-0.069,0.093,-0.014,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
341 33890000,-0.27,0.016,-0.0083,0.96,0.033,0.097,-0.068,0.095,-0.01,-0.027,-0.0013,-0.0058,4.8e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33890000,-0.29,0.014,-0.0057,0.96,0.034,0.097,-0.069,0.097,-0.0053,-0.028,-0.0013,-0.0058,-2.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
342 33990000,-0.27,0.016,-0.0082,0.96,0.036,0.095,-0.064,0.094,-0.019,-0.03,-0.0013,-0.0057,3.3e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33990000,-0.29,0.015,-0.0056,0.96,0.036,0.095,-0.065,0.095,-0.013,-0.032,-0.0013,-0.0057,-3.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
343 34090000,-0.27,0.016,-0.0081,0.96,0.039,0.1,-0.063,0.097,-0.0094,-0.035,-0.0013,-0.0057,3.6e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 34090000,-0.29,0.015,-0.0056,0.96,0.039,0.1,-0.064,0.098,-0.004,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00063,0.0012,1,1
344 34190000,-0.27,0.016,-0.0081,0.96,0.04,0.096,-0.06,0.092,-0.021,-0.038,-0.0013,-0.0057,3e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.022,0.005,0.36,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 34190000,-0.29,0.015,-0.0055,0.96,0.041,0.097,-0.061,0.093,-0.016,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
345 34290000,-0.26,0.016,-0.0079,0.96,0.041,0.1,-0.059,0.096,-0.012,-0.044,-0.0013,-0.0057,4e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.005,0.37,0.38,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 34290000,-0.29,0.015,-0.0054,0.96,0.042,0.1,-0.06,0.098,-0.006,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
346 34390000,-0.26,0.016,-0.0078,0.96,0.043,0.095,-0.054,0.091,-0.023,-0.048,-0.0013,-0.0057,3e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.02,0.022,0.005,0.37,0.37,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 34390000,-0.29,0.015,-0.0053,0.96,0.043,0.097,-0.055,0.093,-0.017,-0.049,-0.0013,-0.0057,-3.9e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
347 34490000,-0.26,0.016,-0.0079,0.96,0.046,0.099,-0.052,0.095,-0.014,-0.051,-0.0013,-0.0057,4.2e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.021,0.023,0.005,0.38,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34490000,-0.29,0.015,-0.0053,0.96,0.046,0.1,-0.053,0.097,-0.0081,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.085,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
348 34590000,-0.26,0.016,-0.0078,0.96,0.049,0.092,0.74,0.09,-0.028,-0.022,-0.0013,-0.0057,3e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.38,0.38,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34590000,-0.29,0.014,-0.0052,0.96,0.046,0.097,0.74,0.092,-0.022,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
349 34690000,-0.26,0.015,-0.0078,0.96,0.058,0.092,1.7,0.095,-0.019,0.097,-0.0013,-0.0057,3.5e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.0051,0.39,0.4,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34690000,-0.29,0.014,-0.0052,0.96,0.051,0.1,1.7,0.097,-0.012,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
350 34790000,-0.26,0.015,-0.0077,0.96,0.063,0.086,2.7,0.088,-0.032,0.28,-0.0013,-0.0057,2.6e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.021,0.005,0.39,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34790000,-0.29,0.014,-0.0052,0.96,0.053,0.098,2.7,0.09,-0.026,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1
351 34890000,-0.26,0.015,-0.0077,0.96,0.071,0.086,3.7,0.094,-0.023,0.57,-0.0013,-0.0057,3.2e-05,0.079,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.021,0.023,0.005,0.4,0.41,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34890000,-0.29,0.014,-0.0052,0.96,0.057,0.1,3.7,0.096,-0.016,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.6e-05,0.0012,0.0011,0.00062,0.0012,1,1

View File

@ -258,10 +258,11 @@ TEST_F(EkfFlowTest, yawMotionCorrectionWithAutopilotGyroData)
// THEN: the flow due to the yaw rotation and the offsets is canceled
// and the velocity estimate stays 0
// FIXME: the estimate isn't perfect 0 mainly because the mag simulated measurement isn't rotating
const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity());
EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.01f)
EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.02f)
<< "estimated vel = " << estimated_horz_velocity(0);
EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.01f)
EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.02f)
<< "estimated vel = " << estimated_horz_velocity(1);
}
@ -296,10 +297,11 @@ TEST_F(EkfFlowTest, yawMotionCorrectionWithFlowGyroData)
// THEN: the flow due to the yaw rotation and the offsets is canceled
// and the velocity estimate stays 0
// FIXME: the estimate isn't perfect 0 mainly because the mag simulated measurement isn't rotating
const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity());
EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.01f)
EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.02f)
<< "estimated vel = " << estimated_horz_velocity(0);
EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.01f)
EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.02f)
<< "estimated vel = " << estimated_horz_velocity(1);
_ekf->state().vector().print();
_ekf->covariances().print();

View File

@ -78,7 +78,7 @@ public:
void quaternionVarianceBigEnoughAfterOrientationInitialization(float quat_variance_limit = 0.00001f)
{
const matrix::Vector3f quat_variance = _ekf->getQuaternionVariance();
const matrix::Vector3f quat_variance = _ekf->getRotVarBody();
EXPECT_TRUE(quat_variance(0) > quat_variance_limit) << "quat_variance(3): " << quat_variance(0);
EXPECT_TRUE(quat_variance(1) > quat_variance_limit) << "quat_variance(1): " << quat_variance(1);
EXPECT_TRUE(quat_variance(2) > quat_variance_limit) << "quat_variance(2): " << quat_variance(2);

View File

@ -42,9 +42,8 @@ using namespace matrix;
Vector3f getRotVarNed(const Quatf &q, const SquareMatrixState &P)
{
constexpr auto S = State::quat_nominal;
matrix::SquareMatrix3f rot_cov_body = P.slice<S.dof, S.dof>(S.idx, S.idx);
auto R_to_earth = Dcmf(q);
return matrix::SquareMatrix<float, State::quat_nominal.dof>(R_to_earth * rot_cov_body * R_to_earth.T()).diag();
matrix::SquareMatrix3f rot_cov_ned = P.slice<S.dof, S.dof>(S.idx, S.idx);
return rot_cov_ned.diag();
}
TEST(YawFusionGenerated, positiveVarianceAllOrientations)

View File

@ -204,7 +204,6 @@ void LoggedTopics::add_default_topics()
// add_optional_topic_multi("estimator_aid_src_gnss_yaw", 100, MAX_ESTIMATOR_INSTANCES);
// add_optional_topic_multi("estimator_aid_src_gnss_vel", 100, MAX_ESTIMATOR_INSTANCES);
// add_optional_topic_multi("estimator_aid_src_gnss_pos", 100, MAX_ESTIMATOR_INSTANCES);
// add_optional_topic_multi("estimator_aid_src_mag_heading", 100, MAX_ESTIMATOR_INSTANCES);
// add_optional_topic_multi("estimator_aid_src_mag", 100, MAX_ESTIMATOR_INSTANCES);
// add_optional_topic_multi("estimator_aid_src_optical_flow", 100, MAX_ESTIMATOR_INSTANCES);
// add_optional_topic_multi("estimator_aid_src_terrain_optical_flow", 100, MAX_ESTIMATOR_INSTANCES);
@ -297,7 +296,6 @@ void LoggedTopics::add_default_topics()
add_optional_topic_multi("estimator_aid_src_gnss_vel", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_gnss_yaw", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_gravity", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_mag_heading", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_mag", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_optical_flow", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_terrain_optical_flow", 0, MAX_ESTIMATOR_INSTANCES);