ekf2: height aid source consistency (#20405)

- working towards keeping all height source (baro/ev/gnss/rng) handling as consistent as possible, possibly refactoring these out into separate classes later
This commit is contained in:
Daniel Agar 2022-10-19 15:35:07 -04:00 committed by GitHub
parent 870229ef49
commit f9509b442c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
21 changed files with 890 additions and 1083 deletions

View File

@ -100,7 +100,6 @@ px4_add_module(
EKF/gps_fusion.cpp
EKF/gps_yaw_fusion.cpp
EKF/height_control.cpp
EKF/height_fusion.cpp
EKF/imu_down_sampler.cpp
EKF/mag_control.cpp
EKF/mag_fusion.cpp

View File

@ -51,7 +51,6 @@ add_library(ecl_EKF
gps_fusion.cpp
gps_yaw_fusion.cpp
height_control.cpp
height_fusion.cpp
imu_down_sampler.cpp
mag_control.cpp
mag_fusion.cpp

View File

@ -40,117 +40,154 @@
void Ekf::controlBaroHeightFusion()
{
if (!_baro_buffer) {
return;
}
static constexpr const char *HGT_SRC_NAME = "baro";
auto &aid_src = _aid_src_baro_hgt;
HeightBiasEstimator &bias_est = _baro_b_est;
bias_est.predict(_dt_ekf_avg);
baroSample baro_sample;
const bool baro_data_ready = _baro_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &baro_sample);
if (baro_data_ready) {
if (_baro_counter == 0) {
_baro_lpf.reset(baro_sample.hgt);
if (_baro_buffer && _baro_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &baro_sample)) {
} else {
_baro_lpf.update(baro_sample.hgt);
const float measurement = baro_sample.hgt;
const float measurement_var = sq(_params.baro_noise);
const float innov_gate = fmaxf(_params.baro_innov_gate, 1.f);
const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var);
if (measurement_valid) {
if (_baro_counter == 0) {
_baro_lpf.reset(baro_sample.hgt);
} else {
_baro_lpf.update(baro_sample.hgt);
}
if (_baro_counter <= _obs_buffer_length) {
// Initialize the pressure offset (included in the baro bias)
bias_est.setBias(_state.pos(2) + _baro_lpf.getState());
_baro_counter++;
}
}
if (_baro_counter < _obs_buffer_length) {
// Initialize the pressure offset (included in the baro bias)
_baro_b_est.setBias(_state.pos(2) + _baro_lpf.getState());
_baro_counter++;
// vertical position innovation - baro measurement has opposite sign to earth z axis
updateVerticalPositionAidSrcStatus(baro_sample.time_us,
-(measurement - bias_est.getBias()),
measurement_var + bias_est.getBiasVar(),
innov_gate,
aid_src);
// Compensate for positive static pressure transients (negative vertical position innovations)
// caused by rotor wash ground interaction by applying a temporary deadzone to baro innovations.
if (_control_status.flags.gnd_effect && (_params.gnd_effect_deadzone > 0.f)) {
const float deadzone_start = 0.0f;
const float deadzone_end = deadzone_start + _params.gnd_effect_deadzone;
if (aid_src.innovation < -deadzone_start) {
if (aid_src.innovation <= -deadzone_end) {
aid_src.innovation += deadzone_end;
} else {
aid_src.innovation = -deadzone_start;
}
}
}
}
if (!(_params.baro_ctrl == 1)) {
stopBaroHgtFusion();
return;
}
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
if (measurement_valid) {
bias_est.setMaxStateNoise(sqrtf(measurement_var));
bias_est.setProcessNoiseSpectralDensity(_params.baro_bias_nsd);
bias_est.fuseBias(measurement - (-_state.pos(2)), measurement_var + P(9, 9));
}
_baro_b_est.predict(_dt_ekf_avg);
// determine if we should use height aiding
const bool continuing_conditions_passing = (_params.baro_ctrl == 1)
&& measurement_valid
&& !_baro_hgt_faulty;
// check for intermittent data
const bool baro_hgt_intermittent = !isNewestSampleRecent(_time_last_baro_buffer_push, 2 * BARO_MAX_INTERVAL);
if (baro_data_ready) {
updateBaroHgt(baro_sample, _aid_src_baro_hgt);
const bool continuing_conditions_passing = !_baro_hgt_faulty && !baro_hgt_intermittent;
const bool starting_conditions_passing = continuing_conditions_passing && (_baro_counter >= _obs_buffer_length);
const bool starting_conditions_passing = continuing_conditions_passing
&& (_baro_counter > _obs_buffer_length)
&& isNewestSampleRecent(_time_last_baro_buffer_push, 2 * BARO_MAX_INTERVAL);
if (_control_status.flags.baro_hgt) {
if (continuing_conditions_passing) {
fuseBaroHgt(_aid_src_baro_hgt);
aid_src.fusion_enabled = true;
const bool is_fusion_failing = isTimedOut(_aid_src_baro_hgt.time_last_fuse, _params.hgt_fusion_timeout_max);
if (continuing_conditions_passing) {
fuseVerticalPosition(aid_src);
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max);
if (isHeightResetRequired()) {
// All height sources are failing
resetHeightToBaro(baro_sample);
ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME);
_information_events.flags.reset_hgt_to_baro = true;
resetVerticalPositionTo(-(_baro_lpf.getState() - bias_est.getBias()), measurement_var);
bias_est.setBias(_state.pos(2) + _baro_lpf.getState());
// reset vertical velocity
resetVerticalVelocityToZero();
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else if (is_fusion_failing) {
// Some other height source is still working
ECL_WARN("stopping %s height fusion, fusion failing", HGT_SRC_NAME);
stopBaroHgtFusion();
_baro_hgt_faulty = true;
}
} else {
ECL_WARN("stopping %s height fusion, continuing conditions failing", HGT_SRC_NAME);
stopBaroHgtFusion();
}
} else {
if (starting_conditions_passing) {
startBaroHgtFusion(baro_sample);
if (_params.height_sensor_ref == HeightSensor::BARO) {
ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME);
_height_sensor_ref = HeightSensor::BARO;
_information_events.flags.reset_hgt_to_baro = true;
resetVerticalPositionTo(-(_baro_lpf.getState() - bias_est.getBias()), measurement_var);
bias_est.setBias(_state.pos(2) + _baro_lpf.getState());
} else {
ECL_INFO("starting %s height fusion", HGT_SRC_NAME);
bias_est.setBias(_state.pos(2) + _baro_lpf.getState());
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
bias_est.setFusionActive();
_control_status.flags.baro_hgt = true;
}
}
} else if (_control_status.flags.baro_hgt && baro_hgt_intermittent) {
// No baro data anymore. Stop until it comes back.
} else if (_control_status.flags.baro_hgt
&& !isNewestSampleRecent(_time_last_baro_buffer_push, 2 * BARO_MAX_INTERVAL)) {
// No data anymore. Stop until it comes back.
ECL_WARN("stopping %s height fusion, no data", HGT_SRC_NAME);
stopBaroHgtFusion();
}
}
void Ekf::startBaroHgtFusion(const baroSample &baro_sample)
{
if (!_control_status.flags.baro_hgt) {
if (_params.height_sensor_ref == HeightSensor::BARO) {
_height_sensor_ref = HeightSensor::BARO;
resetHeightToBaro(baro_sample);
} else {
_baro_b_est.setBias(_state.pos(2) + _baro_lpf.getState());
}
_control_status.flags.baro_hgt = true;
_baro_b_est.setFusionActive();
ECL_INFO("starting baro height fusion");
}
}
void Ekf::resetHeightToBaro(const baroSample &baro_sample)
{
ECL_INFO("reset height to baro");
_information_events.flags.reset_hgt_to_baro = true;
resetVerticalPositionTo(-(baro_sample.hgt - _baro_b_est.getBias()));
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(9, sq(_params.baro_noise));
_gps_hgt_b_est.setBias(_gps_hgt_b_est.getBias() + _state_reset_status.posD_change);
_rng_hgt_b_est.setBias(_rng_hgt_b_est.getBias() + _state_reset_status.posD_change);
_ev_hgt_b_est.setBias(_ev_hgt_b_est.getBias() - _state_reset_status.posD_change);
}
void Ekf::stopBaroHgtFusion()
{
if (_control_status.flags.baro_hgt) {
if (_height_sensor_ref == HeightSensor::BARO) {
_height_sensor_ref = HeightSensor::UNKNOWN;
}
_control_status.flags.baro_hgt = false;
_baro_b_est.setFusionInactive();
ECL_INFO("stopping baro height fusion");
resetEstimatorAidStatus(_aid_src_baro_hgt);
_control_status.flags.baro_hgt = false;
}
}

View File

@ -69,7 +69,7 @@ void BiasEstimator::constrainStateVar()
void BiasEstimator::fuseBias(const float measurement, const float measurement_var)
{
const float innov_var = _state_var + measurement_var;
const float innov_var = _state_var + math::max(sq(0.01f), measurement_var);
const float innov = measurement - _state;
const float K = _state_var / innov_var;
const float innov_test_ratio = computeInnovTestRatio(innov, innov_var);

View File

@ -87,7 +87,7 @@ public:
void setBiasStdDev(float state_noise) { _state_var = state_noise * state_noise; }
void setInnovGate(float gate_size) { _gate_size = gate_size; }
void setMaxStateNoise(float max_noise) { _state_var_max = max_noise * max_noise; }
void setMaxStateNoise(float max_noise) { _state_var_max = math::max(sq(0.01f), max_noise * max_noise); }
float getBias() const { return _state; }
float getBiasVar() const { return _state_var; }

View File

@ -129,8 +129,23 @@ void Ekf::controlFusionModes()
// Run the kinematic consistency check when not moving horizontally
if (_control_status.flags.in_air && !_control_status.flags.fixed_wing
&& (sq(_state.vel(0)) + sq(_state.vel(1)) < fmaxf(P(4, 4) + P(5, 5), 0.1f))) {
const float dist_dependant_var = sq(_params.range_noise_scaler * _range_sensor.getDistBottom());
const float var = sq(_params.range_noise) + dist_dependant_var;
_rng_consistency_check.setGate(_params.range_kin_consistency_gate);
_rng_consistency_check.update(_range_sensor.getDistBottom(), getRngHeightVariance(), _state.vel(2), P(6, 6), _imu_sample_delayed.time_us);
_rng_consistency_check.update(_range_sensor.getDistBottom(), math::max(var, 0.001f), _state.vel(2), P(6, 6), _imu_sample_delayed.time_us);
}
} else {
// If we are supposed to be using range finder data as the primary height sensor, have bad range measurements
// and are on the ground, then synthesise a measurement at the expected on ground value
if (!_control_status.flags.in_air
&& _range_sensor.isRegularlySendingData()
&& _range_sensor.isDataReady()) {
_range_sensor.setRange(_params.rng_gnd_clearance);
_range_sensor.setValidity(true); // bypass the checks
}
}

View File

@ -693,19 +693,12 @@ private:
// fuse body frame drag specific forces for multi-rotor wind estimation
void fuseDrag(const dragSample &drag_sample);
void fuseBaroHgt(estimator_aid_source_1d_s &baro_hgt);
void fuseRngHgt(estimator_aid_source_1d_s &range_hgt);
void fuseEvHgt();
void updateBaroHgt(const baroSample &baro_sample, estimator_aid_source_1d_s &baro_hgt);
void updateRngHgt(estimator_aid_source_1d_s &rng_hgt);
// fuse single velocity and position measurement
bool fuseVelPosHeight(const float innov, const float innov_var, const int obs_index);
void resetVelocityTo(const Vector3f &vel);
void resetHorizontalVelocityTo(const Vector2f &new_horz_vel);
void resetVerticalVelocityTo(float new_vert_vel);
void resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var = NAN);
void resetVelocityToGps(const gpsSample &gps_sample);
void resetHorizontalVelocityToOpticalFlow(const flowSample &flow_sample);
@ -720,15 +713,8 @@ private:
bool isHeightResetRequired() const;
void resetVerticalPositionTo(float new_vert_pos);
void resetVerticalPositionTo(float new_vert_pos, float new_vert_pos_var = NAN);
void resetHeightToBaro(const baroSample &baro_sample);
void resetHeightToGps(const gpsSample &gps_sample);
void resetHeightToRng();
void resetHeightToEv();
void resetVerticalVelocityToGps(const gpsSample &gps_sample);
void resetVerticalVelocityToEv(const extVisionSample &ev_sample);
void resetVerticalVelocityToZero();
// fuse optical flow line of sight rate measurements
@ -942,11 +928,9 @@ private:
void controlFakePosFusion();
void controlFakeHgtFusion();
void startFakeHgtFusion();
void resetFakeHgtFusion();
void resetHeightToLastKnown();
void stopFakeHgtFusion();
void fuseFakeHgt();
void controlZeroVelocityUpdate();
@ -964,7 +948,7 @@ private:
void controlBaroHeightFusion();
void controlGnssHeightFusion(const gpsSample &gps_sample);
void controlRangeHeightFusion();
void controlEvHeightFusion();
void controlEvHeightFusion(const extVisionSample &ev_sample);
bool isConditionalRangeAidSuitable();
@ -974,24 +958,13 @@ private:
void startMagHdgFusion();
void startMag3DFusion();
void startBaroHgtFusion(const baroSample &baro_sample);
void stopBaroHgtFusion();
void startGpsHgtFusion(const gpsSample &gps_sample);
void stopGpsHgtFusion();
void startRngHgtFusion();
void stopRngHgtFusion();
void startRngAidHgtFusion();
void startEvHgtFusion();
void stopEvHgtFusion();
void updateGroundEffect();
// return an estimation of the sensor altitude variance
float getGpsHeightVariance(const gpsSample &gps_sample);
float getRngHeightVariance() const;
// calculate the measurement variance for the optical flow sensor
float calcOptFlowMeasVar(const flowSample &flow_sample);
@ -1078,10 +1051,8 @@ private:
void stopFlowFusion();
void startFakePosFusion();
void resetFakePosFusion();
void stopFakePosFusion();
void fuseFakePosition();
void setVelPosStatus(const int index, const bool healthy);

View File

@ -124,11 +124,15 @@ void Ekf::resetHorizontalVelocityTo(const Vector2f &new_horz_vel)
_time_last_hor_vel_fuse = _imu_sample_delayed.time_us;
}
void Ekf::resetVerticalVelocityTo(float new_vert_vel)
void Ekf::resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var)
{
const float delta_vert_vel = new_vert_vel - _state.vel(2);
_state.vel(2) = new_vert_vel;
if (PX4_ISFINITE(new_vert_vel_var)) {
P.uncorrelateCovarianceSetVariance<1>(6, math::max(sq(0.01f), new_vert_vel_var));
}
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
_output_buffer[index].vel(2) += delta_vert_vel;
_output_vert_buffer[index].vert_vel += delta_vert_vel;
@ -226,11 +230,16 @@ bool Ekf::isHeightResetRequired() const
}
void Ekf::resetVerticalPositionTo(const float new_vert_pos)
void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_var)
{
const float old_vert_pos = _state.pos(2);
_state.pos(2) = new_vert_pos;
if (PX4_ISFINITE(new_vert_pos_var)) {
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(9, math::max(sq(0.01f), new_vert_pos_var));
}
// store the reset amount and time to be published
_state_reset_status.posD_change = new_vert_pos - old_vert_pos;
_state_reset_status.posD_counter++;
@ -248,34 +257,21 @@ void Ekf::resetVerticalPositionTo(const float new_vert_pos)
// add the reset amount to the output observer vertical position state
_output_vert_new.vert_vel_integ = _state.pos(2);
_baro_b_est.setBias(_baro_b_est.getBias() + _state_reset_status.posD_change);
_ev_hgt_b_est.setBias(_ev_hgt_b_est.getBias() - _state_reset_status.posD_change);
_gps_hgt_b_est.setBias(_gps_hgt_b_est.getBias() + _state_reset_status.posD_change);
_rng_hgt_b_est.setBias(_rng_hgt_b_est.getBias() + _state_reset_status.posD_change);
// Reset the timout timer
_time_last_hgt_fuse = _imu_sample_delayed.time_us;
}
void Ekf::resetVerticalVelocityToGps(const gpsSample &gps_sample)
{
resetVerticalVelocityTo(gps_sample.vel(2));
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(6, sq(1.5f * gps_sample.sacc));
}
void Ekf::resetVerticalVelocityToEv(const extVisionSample &ev_sample)
{
resetVerticalVelocityTo(ev_sample.vel(2));
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(6, ev_sample.velVar(2));
}
void Ekf::resetVerticalVelocityToZero()
{
// we don't know what the vertical velocity is, so set it to zero
resetVerticalVelocityTo(0.0f);
// Set the variance to a value large enough to allow the state to converge quickly
// that does not destabilise the filter
P.uncorrelateCovarianceSetVariance<1>(6, 10.0f);
resetVerticalVelocityTo(0.0f, 10.f);
}
// align output filter states to match EKF states at the fusion time horizon
@ -700,11 +696,11 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons
// determine current z
float current_alt = -_state.pos(2) + gps_alt_ref_prev;
const float gps_hgt_bias = _gps_hgt_b_est.getBias();
resetVerticalPositionTo(_gps_alt_ref - current_alt);
_baro_b_est.setBias(_baro_b_est.getBias() + _state_reset_status.posD_change);
_rng_hgt_b_est.setBias(_rng_hgt_b_est.getBias() + _state_reset_status.posD_change);
_ev_hgt_b_est.setBias(_ev_hgt_b_est.getBias() - _state_reset_status.posD_change);
// preserve GPS height bias
_gps_hgt_b_est.setBias(gps_hgt_bias);
}
return true;
@ -1299,24 +1295,6 @@ void Ekf::startMag3DFusion()
}
}
float Ekf::getGpsHeightVariance(const gpsSample &gps_sample)
{
// observation variance - receiver defined and parameter limited
// use 1.5 as a typical ratio of vacc/hacc
const float lower_limit = fmaxf(1.5f * _params.gps_pos_noise, 0.01f);
const float upper_limit = fmaxf(1.5f * _params.pos_noaid_noise, lower_limit);
const float gps_alt_var = sq(math::constrain(gps_sample.vacc, lower_limit, upper_limit));
return gps_alt_var;
}
float Ekf::getRngHeightVariance() const
{
const float dist_dependant_var = sq(_params.range_noise_scaler * _range_sensor.getDistBottom());
const float var = sq(_params.range_noise) + dist_dependant_var;
const float var_sat = fmaxf(var, 0.001f);
return var_sat;
}
void Ekf::updateGroundEffect()
{
if (_control_status.flags.in_air && !_control_status.flags.fixed_wing) {

View File

@ -38,95 +38,137 @@
#include "ekf.h"
void Ekf::controlEvHeightFusion()
void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample)
{
if (!(_params.height_sensor_ref == HeightSensor::EV)) { // TODO: replace by EV control parameter
stopEvHgtFusion();
return;
}
static constexpr const char *HGT_SRC_NAME = "EV";
_ev_hgt_b_est.predict(_dt_ekf_avg);
auto &aid_src = _aid_src_ev_hgt;
HeightBiasEstimator &bias_est = _ev_hgt_b_est;
const bool ev_intermittent = !isNewestSampleRecent(_time_last_ext_vision_buffer_push, 2 * EV_MAX_INTERVAL);
bias_est.predict(_dt_ekf_avg);
if (_ev_data_ready) {
const bool position_valid = PX4_ISFINITE(_ev_sample_delayed.pos(2));
const bool continuing_conditions_passing = !ev_intermittent && position_valid;
const bool starting_conditions_passing = continuing_conditions_passing;
const float measurement = ev_sample.pos(2);
const float measurement_var = ev_sample.posVar(2);
const float innov_gate = math::max(_params.ev_pos_innov_gate, 1.f);
const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var);
updateVerticalPositionAidSrcStatus(ev_sample.time_us,
measurement - bias_est.getBias(),
measurement_var + bias_est.getBiasVar(),
innov_gate,
aid_src);
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
if (measurement_valid) {
bias_est.setMaxStateNoise(sqrtf(measurement_var));
bias_est.setProcessNoiseSpectralDensity(_params.ev_hgt_bias_nsd);
bias_est.fuseBias(measurement - _state.pos(2), measurement_var + P(9, 9));
}
const bool continuing_conditions_passing = ((_params.fusion_mode & SensorFusionMask::USE_EXT_VIS_POS) || (_params.height_sensor_ref == HeightSensor::EV)) // TODO: (_params.ev_ctrl & EvCtrl::VPOS)
&& measurement_valid;
const bool starting_conditions_passing = continuing_conditions_passing
&& isNewestSampleRecent(_time_last_ext_vision_buffer_push, 2 * EV_MAX_INTERVAL);
if (_control_status.flags.ev_hgt) {
aid_src.fusion_enabled = true;
if (continuing_conditions_passing) {
fuseEvHgt();
const bool reset = (_ev_sample_delayed.reset_counter != _ev_sample_delayed_prev.reset_counter);
if (isHeightResetRequired() || reset ) {
resetHeightToEv();
fuseVerticalPosition(aid_src);
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max);
if (isHeightResetRequired()) {
// All height sources are failing
ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME);
_information_events.flags.reset_hgt_to_ev = true;
resetVerticalPositionTo(measurement - bias_est.getBias(), measurement_var);
bias_est.setBias(-_state.pos(2) + measurement);
// reset vertical velocity
if (PX4_ISFINITE(ev_sample.vel(2)) && (_params.fusion_mode & SensorFusionMask::USE_EXT_VIS_POS)) {
resetVerticalVelocityTo(ev_sample.vel(2), ev_sample.velVar(2));
// If the sample has a valid vertical velocity estimate, use it
if (PX4_ISFINITE(_ev_sample_delayed.vel(2))) {
resetVerticalVelocityToEv(_ev_sample_delayed);
} else {
resetVerticalVelocityToZero();
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else if ((_ev_sample_delayed.reset_counter != _ev_sample_delayed_prev.reset_counter) && !aid_src.fused) {
// fusion failed and EV sample indicates reset
ECL_INFO("%s height reset", HGT_SRC_NAME);
if (_height_sensor_ref == HeightSensor::EV) {
_information_events.flags.reset_hgt_to_ev = true;
resetVerticalPositionTo(measurement, measurement_var);
bias_est.reset();
} else {
bias_est.setBias(-_state.pos(2) + measurement);
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else if (is_fusion_failing) {
// Some other height source is still working
ECL_WARN("stopping %s height fusion, fusion failing", HGT_SRC_NAME);
stopEvHgtFusion();
}
} else {
ECL_WARN("stopping %s height fusion, continuing conditions failing", HGT_SRC_NAME);
stopEvHgtFusion();
}
} else {
if (starting_conditions_passing) {
startEvHgtFusion();
if (_params.height_sensor_ref == HeightSensor::EV) {
ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME);
_height_sensor_ref = HeightSensor::EV;
_information_events.flags.reset_hgt_to_ev = true;
resetVerticalPositionTo(measurement, measurement_var);
bias_est.reset();
} else {
ECL_INFO("starting %s height fusion", HGT_SRC_NAME);
bias_est.setBias(-_state.pos(2) + measurement);
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
bias_est.setFusionActive();
_control_status.flags.ev_hgt = true;
}
}
} else if (_control_status.flags.ev_hgt && ev_intermittent) {
} else if (_control_status.flags.ev_hgt
&& !isNewestSampleRecent(_time_last_ext_vision_buffer_push, 2 * EV_MAX_INTERVAL)) {
// No data anymore. Stop until it comes back.
ECL_WARN("stopping %s height fusion, no data", HGT_SRC_NAME);
stopEvHgtFusion();
}
}
void Ekf::startEvHgtFusion()
{
if (!_control_status.flags.ev_hgt) {
if (_params.height_sensor_ref == HeightSensor::EV) {
_ev_hgt_b_est.reset();
_height_sensor_ref = HeightSensor::EV;
resetHeightToEv();
} else {
_ev_hgt_b_est.setBias(-_state.pos(2) + _ev_sample_delayed.pos(2));
}
_control_status.flags.ev_hgt = true;
_ev_hgt_b_est.setFusionActive();
ECL_INFO("starting EV height fusion");
}
}
void Ekf::resetHeightToEv()
{
ECL_INFO("reset height to EV");
_information_events.flags.reset_hgt_to_ev = true;
resetVerticalPositionTo(_ev_sample_delayed.pos(2) - _ev_hgt_b_est.getBias());
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(9, fmaxf(_ev_sample_delayed.posVar(2), sq(0.01f)));
_baro_b_est.setBias(_baro_b_est.getBias() + _state_reset_status.posD_change);
_gps_hgt_b_est.setBias(_gps_hgt_b_est.getBias() + _state_reset_status.posD_change);
_rng_hgt_b_est.setBias(_rng_hgt_b_est.getBias() + _state_reset_status.posD_change);
}
void Ekf::stopEvHgtFusion()
{
if (_control_status.flags.ev_hgt) {
if (_height_sensor_ref == HeightSensor::EV) {
_height_sensor_ref = HeightSensor::UNKNOWN;
}
_control_status.flags.ev_hgt = false;
_ev_hgt_b_est.setFusionInactive();
ECL_INFO("stopping EV height fusion");
resetEstimatorAidStatus(_aid_src_ev_hgt);
_control_status.flags.ev_hgt = false;
}
}

View File

@ -40,25 +40,34 @@
void Ekf::controlFakeHgtFusion()
{
auto &fake_hgt = _aid_src_fake_hgt;
// clear
resetEstimatorAidStatus(fake_hgt);
auto &aid_src = _aid_src_fake_hgt;
// If we aren't doing any aiding, fake position measurements at the last known vertical position to constrain drift
const bool fake_hgt_data_ready = isTimedOut(fake_hgt.time_last_fuse, (uint64_t)2e5); // Fuse fake height at a limited rate
const bool fake_hgt_data_ready = !isVerticalAidingActive()
&& isTimedOut(aid_src.time_last_fuse, (uint64_t)2e5); // Fuse fake height at a limited rate
if (fake_hgt_data_ready) {
const float obs_var = sq(_params.pos_noaid_noise);
const float innov_gate = 3.f;
updateVerticalPositionAidSrcStatus(_imu_sample_delayed.time_us, _last_known_pos(2), obs_var, innov_gate, aid_src);
const bool continuing_conditions_passing = !isVerticalAidingActive();
const bool starting_conditions_passing = continuing_conditions_passing
&& _vertical_velocity_deadreckon_time_exceeded
&& _vertical_position_deadreckon_time_exceeded;
&& _vertical_velocity_deadreckon_time_exceeded
&& _vertical_position_deadreckon_time_exceeded;
if (_control_status.flags.fake_hgt) {
if (continuing_conditions_passing) {
fuseFakeHgt();
const bool is_fusion_failing = isTimedOut(fake_hgt.time_last_fuse, (uint64_t)4e5);
// always protect against extreme values that could result in a NaN
aid_src.fusion_enabled = aid_src.test_ratio < sq(100.0f / innov_gate);
fuseVerticalPosition(aid_src);
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, (uint64_t)4e5);
if (is_fusion_failing) {
resetFakeHgtFusion();
@ -70,18 +79,14 @@ void Ekf::controlFakeHgtFusion()
} else {
if (starting_conditions_passing) {
startFakeHgtFusion();
ECL_INFO("start fake height fusion");
_control_status.flags.fake_hgt = true;
resetFakeHgtFusion();
}
}
}
}
void Ekf::startFakeHgtFusion()
{
if (!_control_status.flags.fake_hgt) {
ECL_INFO("start fake height fusion");
_control_status.flags.fake_hgt = true;
resetFakeHgtFusion();
} else if (_control_status.flags.fake_hgt && isVerticalAidingActive()) {
stopFakeHgtFusion();
}
}
@ -100,8 +105,7 @@ void Ekf::resetHeightToLastKnown()
{
_information_events.flags.reset_pos_to_last_known = true;
ECL_INFO("reset height to last known");
resetVerticalPositionTo(_last_known_pos(2));
P.uncorrelateCovarianceSetVariance<1>(9, sq(_params.pos_noaid_noise));
resetVerticalPositionTo(_last_known_pos(2), sq(_params.pos_noaid_noise));
}
void Ekf::stopFakeHgtFusion()
@ -113,33 +117,3 @@ void Ekf::stopFakeHgtFusion()
resetEstimatorAidStatus(_aid_src_fake_hgt);
}
}
void Ekf::fuseFakeHgt()
{
const float obs_var = sq(_params.pos_noaid_noise);
const float innov_gate = 3.f;
auto &fake_hgt = _aid_src_fake_hgt;
fake_hgt.observation = _last_known_pos(2);
fake_hgt.observation_variance = obs_var;
fake_hgt.innovation = _state.pos(2) - _last_known_pos(2);
fake_hgt.innovation_variance = P(9, 9) + obs_var;
setEstimatorAidStatusTestRatio(fake_hgt, innov_gate);
// always protect against extreme values that could result in a NaN
fake_hgt.fusion_enabled = fake_hgt.test_ratio < sq(100.0f / innov_gate);
// fuse
if (fake_hgt.fusion_enabled && !fake_hgt.innovation_rejected) {
if (fuseVelPosHeight(fake_hgt.innovation, fake_hgt.innovation_variance, 5)) {
fake_hgt.fused = true;
fake_hgt.time_last_fuse = _imu_sample_delayed.time_us;
}
}
fake_hgt.timestamp_sample = _imu_sample_delayed.time_us;
}

View File

@ -40,25 +40,48 @@
void Ekf::controlFakePosFusion()
{
auto &fake_pos = _aid_src_fake_pos;
// clear
resetEstimatorAidStatus(fake_pos);
auto &aid_src = _aid_src_fake_pos;
// If we aren't doing any aiding, fake position measurements at the last known position to constrain drift
// During intial tilt aligment, fake position is used to perform a "quasi-stationary" leveling of the EKF
const bool fake_pos_data_ready = isTimedOut(fake_pos.time_last_fuse, (uint64_t)2e5); // Fuse fake position at a limited rate
const bool fake_pos_data_ready = !isHorizontalAidingActive()
&& isTimedOut(aid_src.time_last_fuse, (uint64_t)2e5); // Fuse fake position at a limited rate
if (fake_pos_data_ready) {
Vector2f obs_var;
if (_control_status.flags.in_air && _control_status.flags.tilt_align) {
obs_var(0) = obs_var(1) = sq(fmaxf(_params.pos_noaid_noise, _params.gps_pos_noise));
} else if (!_control_status.flags.in_air && _control_status.flags.vehicle_at_rest) {
// Accelerate tilt fine alignment by fusing more
// aggressively when the vehicle is at rest
obs_var(0) = obs_var(1) = sq(0.01f);
} else {
obs_var(0) = obs_var(1) = sq(0.5f);
}
const float innov_gate = 3.f;
updateHorizontalPositionAidSrcStatus(_imu_sample_delayed.time_us, Vector2f(_last_known_pos), obs_var, innov_gate, aid_src);
const bool continuing_conditions_passing = !isHorizontalAidingActive();
const bool starting_conditions_passing = continuing_conditions_passing
&& _horizontal_deadreckon_time_exceeded;
&& _horizontal_deadreckon_time_exceeded;
if (_control_status.flags.fake_pos) {
if (continuing_conditions_passing) {
fuseFakePosition();
const bool is_fusion_failing = isTimedOut(fake_pos.time_last_fuse, (uint64_t)4e5);
// always protect against extreme values that could result in a NaN
aid_src.fusion_enabled = (aid_src.test_ratio[0] < sq(100.0f / innov_gate))
&& (aid_src.test_ratio[1] < sq(100.0f / innov_gate));
fuseHorizontalPosition(aid_src);
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, (uint64_t)4e5);
if (is_fusion_failing) {
resetFakePosFusion();
@ -70,7 +93,10 @@ void Ekf::controlFakePosFusion()
} else {
if (starting_conditions_passing) {
startFakePosFusion();
ECL_INFO("start fake position fusion");
_control_status.flags.fake_pos = true;
_fuse_hpos_as_odom = false; // TODO: needed?
resetFakePosFusion();
if (_control_status.flags.tilt_align) {
// The fake position fusion is not started for initial alignement
@ -85,16 +111,6 @@ void Ekf::controlFakePosFusion()
}
}
void Ekf::startFakePosFusion()
{
if (!_control_status.flags.fake_pos) {
ECL_INFO("start fake position fusion");
_control_status.flags.fake_pos = true;
_fuse_hpos_as_odom = false; // TODO: needed?
resetFakePosFusion();
}
}
void Ekf::resetFakePosFusion()
{
ECL_INFO("reset fake position fusion");
@ -115,58 +131,3 @@ void Ekf::stopFakePosFusion()
resetEstimatorAidStatus(_aid_src_fake_pos);
}
}
void Ekf::fuseFakePosition()
{
Vector2f obs_var;
if (_control_status.flags.in_air && _control_status.flags.tilt_align) {
obs_var(0) = obs_var(1) = sq(fmaxf(_params.pos_noaid_noise, _params.gps_pos_noise));
} else if (!_control_status.flags.in_air && _control_status.flags.vehicle_at_rest) {
// Accelerate tilt fine alignment by fusing more
// aggressively when the vehicle is at rest
obs_var(0) = obs_var(1) = sq(0.01f);
} else {
obs_var(0) = obs_var(1) = sq(0.5f);
}
const float innov_gate = 3.f;
auto &fake_pos = _aid_src_fake_pos;
for (int i = 0; i < 2; i++) {
fake_pos.observation[i] = _last_known_pos(i);
fake_pos.observation_variance[i] = obs_var(i);
fake_pos.innovation[i] = _state.pos(i) - _last_known_pos(i);
fake_pos.innovation_variance[i] = P(7 + i, 7 + i) + obs_var(i);
}
setEstimatorAidStatusTestRatio(fake_pos, innov_gate);
fake_pos.fusion_enabled = true;
// always protect against extreme values that could result in a NaN
if (!fake_pos.innovation_rejected) {
if ((fake_pos.test_ratio[0] > sq(100.0f / innov_gate)) || (fake_pos.test_ratio[1] > sq(100.0f / innov_gate))) {
fake_pos.innovation_rejected = true;
}
}
// fuse
if (fake_pos.fusion_enabled && !fake_pos.innovation_rejected) {
if (fuseVelPosHeight(fake_pos.innovation[0], fake_pos.innovation_variance[0], 3)
&& fuseVelPosHeight(fake_pos.innovation[1], fake_pos.innovation_variance[1], 4)
) {
fake_pos.fused = true;
fake_pos.time_last_fuse = _imu_sample_delayed.time_us;
} else {
fake_pos.fused = false;
}
}
fake_pos.timestamp_sample = _imu_sample_delayed.time_us;
}

View File

@ -40,10 +40,7 @@
void Ekf::controlGnssHeightFusion(const gpsSample &gps_sample)
{
if (!(_params.gnss_ctrl & GnssCtrl::VPOS)) {
stopGpsHgtFusion();
return;
}
static constexpr const char *HGT_SRC_NAME = "GNSS";
auto &aid_src = _aid_src_gnss_hgt;
HeightBiasEstimator &bias_est = _gps_hgt_b_est;
@ -52,13 +49,23 @@ void Ekf::controlGnssHeightFusion(const gpsSample &gps_sample)
if (_gps_data_ready) {
const bool gps_checks_passing = isTimedOut(_last_gps_fail_us, (uint64_t)5e6);
const bool gps_checks_failing = isTimedOut(_last_gps_pass_us, (uint64_t)5e6);
// relax the upper observation noise limit which prevents bad GPS perturbing the position estimate
float noise = math::max(gps_sample.vacc, 1.5f * _params.gps_pos_noise); // use 1.5 as a typical ratio of vacc/hacc
const float innov_gate = fmaxf(_params.gps_pos_innov_gate, 1.f);
if (!isOnlyActiveSourceOfVerticalPositionAiding(_control_status.flags.gps_hgt)) {
// if we are not using another source of aiding, then we are reliant on the GPS
// observations to constrain attitude errors and must limit the observation noise value.
if (noise > _params.pos_noaid_noise) {
noise = _params.pos_noaid_noise;
}
}
const float measurement = gps_sample.hgt - getEkfGlobalOriginAltitude();
const float measurement_var = getGpsHeightVariance(gps_sample);
const float measurement_var = sq(noise);
const float innov_gate = math::max(_params.gps_pos_innov_gate, 1.f);
const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var);
// GNSS position, vertical position GNSS measurement has opposite sign to earth z axis
updateVerticalPositionAidSrcStatus(gps_sample.time_us,
@ -67,28 +74,28 @@ void Ekf::controlGnssHeightFusion(const gpsSample &gps_sample)
innov_gate,
aid_src);
const bool gps_checks_passing = isTimedOut(_last_gps_fail_us, (uint64_t)5e6);
const bool gps_checks_failing = isTimedOut(_last_gps_pass_us, (uint64_t)5e6);
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
if (gps_checks_passing && !gps_checks_failing
&& PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var)
) {
const float noise = sqrtf(measurement_var);
bias_est.setMaxStateNoise(noise);
if (measurement_valid && gps_checks_passing && !gps_checks_failing) {
bias_est.setMaxStateNoise(sqrtf(measurement_var));
bias_est.setProcessNoiseSpectralDensity(_params.gps_hgt_bias_nsd);
bias_est.fuseBias(measurement - (-_state.pos(2)), measurement_var + P(9, 9));
}
// determine if we should use GNSS height aiding
// determine if we should use height aiding
const bool continuing_conditions_passing = (_params.gnss_ctrl & GnssCtrl::VPOS)
&& PX4_ISFINITE(gps_sample.hgt)
&& measurement_valid
&& _NED_origin_initialised
&& _gps_checks_passed;
const bool starting_conditions_passing = continuing_conditions_passing
&& isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GPS_MAX_INTERVAL)
&& _gps_checks_passed
&& gps_checks_passing
&& !gps_checks_failing
&& isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GPS_MAX_INTERVAL);
&& !gps_checks_failing;
if (_control_status.flags.gps_hgt) {
aid_src.fusion_enabled = true;
@ -101,68 +108,63 @@ void Ekf::controlGnssHeightFusion(const gpsSample &gps_sample)
if (isHeightResetRequired()) {
// All height sources are failing
resetHeightToGps(gps_sample);
resetVerticalVelocityToGps(gps_sample);
ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME);
_information_events.flags.reset_hgt_to_gps = true;
resetVerticalPositionTo(-(measurement - bias_est.getBias()), measurement_var);
bias_est.setBias(_state.pos(2) + measurement);
// reset vertical velocity
if (PX4_ISFINITE(gps_sample.vel(2)) && (_params.gnss_ctrl & GnssCtrl::VEL)) {
// use 1.5 as a typical ratio of vacc/hacc
resetVerticalVelocityTo(gps_sample.vel(2), sq(1.5f * gps_sample.sacc));
} else {
resetVerticalVelocityToZero();
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else if (is_fusion_failing) {
// Some other height source is still working
ECL_WARN("stopping %s height fusion, fusion failing", HGT_SRC_NAME);
stopGpsHgtFusion();
}
} else {
ECL_WARN("stopping %s height fusion, continuing conditions failing", HGT_SRC_NAME);
stopGpsHgtFusion();
}
} else {
if (starting_conditions_passing) {
startGpsHgtFusion(gps_sample);
if (_params.height_sensor_ref == HeightSensor::GNSS) {
ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME);
_height_sensor_ref = HeightSensor::GNSS;
_information_events.flags.reset_hgt_to_gps = true;
resetVerticalPositionTo(-measurement, measurement_var);
bias_est.reset();
} else {
ECL_INFO("starting %s height fusion", HGT_SRC_NAME);
bias_est.setBias(_state.pos(2) + measurement);
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
bias_est.setFusionActive();
_control_status.flags.gps_hgt = true;
}
}
} else if (_control_status.flags.gps_hgt && _gps_intermittent) {
} else if (_control_status.flags.gps_hgt
&& !isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GPS_MAX_INTERVAL)) {
// No data anymore. Stop until it comes back.
ECL_WARN("stopping %s height fusion, no data", HGT_SRC_NAME);
stopGpsHgtFusion();
}
}
void Ekf::startGpsHgtFusion(const gpsSample &gps_sample)
{
if (!_control_status.flags.gps_hgt) {
if (_params.height_sensor_ref == HeightSensor::GNSS) {
_gps_hgt_b_est.reset();
_height_sensor_ref = HeightSensor::GNSS;
resetHeightToGps(gps_sample);
} else {
_gps_hgt_b_est.setBias(_state.pos(2) + (gps_sample.hgt - getEkfGlobalOriginAltitude()));
// Reset the timeout value here because the fusion isn't done at the same place and would immediately trigger a timeout
_aid_src_gnss_hgt.time_last_fuse = _imu_sample_delayed.time_us;
}
_control_status.flags.gps_hgt = true;
_gps_hgt_b_est.setFusionActive();
ECL_INFO("starting GPS height fusion");
}
}
void Ekf::resetHeightToGps(const gpsSample &gps_sample)
{
ECL_INFO("reset height to GPS");
_information_events.flags.reset_hgt_to_gps = true;
resetVerticalPositionTo(-(gps_sample.hgt - getEkfGlobalOriginAltitude() - _gps_hgt_b_est.getBias()));
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(9, getGpsHeightVariance(gps_sample));
_baro_b_est.setBias(_baro_b_est.getBias() + _state_reset_status.posD_change);
_rng_hgt_b_est.setBias(_rng_hgt_b_est.getBias() + _state_reset_status.posD_change);
_ev_hgt_b_est.setBias(_ev_hgt_b_est.getBias() - _state_reset_status.posD_change);
_aid_src_gnss_hgt.time_last_fuse = _imu_sample_delayed.time_us;
}
void Ekf::stopGpsHgtFusion()
{
if (_control_status.flags.gps_hgt) {
@ -171,8 +173,9 @@ void Ekf::stopGpsHgtFusion()
_height_sensor_ref = HeightSensor::UNKNOWN;
}
_control_status.flags.gps_hgt = false;
_gps_hgt_b_est.setFusionInactive();
ECL_INFO("stopping GPS height fusion");
resetEstimatorAidStatus(_aid_src_gnss_hgt);
_control_status.flags.gps_hgt = false;
}
}

View File

@ -59,29 +59,37 @@ void Ekf::controlGpsFusion()
controlGpsYawFusion(gps_sample, gps_checks_passing, gps_checks_failing);
// GNSS velocity
const Vector3f velocity{gps_sample.vel};
const float vel_var = sq(gps_sample.sacc);
const Vector3f vel_obs_var{vel_var, vel_var, vel_var * sq(1.5f)};
updateVelocityAidSrcStatus(gps_sample.time_us, velocity, vel_obs_var, fmaxf(_params.gps_vel_innov_gate, 1.f), _aid_src_gnss_vel);
const float vel_obs_var = sq(math::max(gps_sample.sacc, _params.gps_vel_noise));
updateVelocityAidSrcStatus(gps_sample.time_us,
gps_sample.vel, // observation
Vector3f(vel_obs_var, vel_obs_var, vel_obs_var * sq(1.5f)), // observation variance
math::max(_params.gps_vel_innov_gate, 1.f), // innovation gate
_aid_src_gnss_vel);
_aid_src_gnss_vel.fusion_enabled = (_params.gnss_ctrl & GnssCtrl::VEL);
// GNSS position
const float pos_var_lower_limit = fmaxf(_params.gps_pos_noise, 0.01f);
float pos_var = sq(fmaxf(gps_sample.hacc, pos_var_lower_limit));
// relax the upper observation noise limit which prevents bad GPS perturbing the position estimate
float pos_noise = math::max(gps_sample.hacc, _params.gps_pos_noise);
if (!isOtherSourceOfHorizontalAidingThan(_control_status.flags.gps)) {
// if we are not using another source of aiding, then we are reliant on the GPS
// observations to constrain attitude errors and must limit the observation noise value.
float upper_limit = fmaxf(_params.pos_noaid_noise, pos_var_lower_limit);
pos_var = fminf(pos_var, upper_limit);
if (pos_noise > _params.pos_noaid_noise) {
pos_noise = _params.pos_noaid_noise;
}
}
updateHorizontalPositionAidSrcStatus(gps_sample.time_us, gps_sample.pos, Vector2f(pos_var, pos_var), fmaxf(_params.gps_pos_innov_gate, 1.f), _aid_src_gnss_pos);
const float pos_obs_var = sq(pos_noise);
updateHorizontalPositionAidSrcStatus(gps_sample.time_us,
gps_sample.pos, // observation
Vector2f(pos_obs_var, pos_obs_var), // observation variance
math::max(_params.gps_pos_innov_gate, 1.f), // innovation gate
_aid_src_gnss_pos);
_aid_src_gnss_pos.fusion_enabled = (_params.gnss_ctrl & GnssCtrl::HPOS);
// update GSF yaw estimator velocity (basic sanity check on GNSS velocity data)
if (gps_checks_passing && !gps_checks_failing) {
_yawEstimator.setVelocity(velocity.xy(), gps_sample.sacc);
_yawEstimator.setVelocity(gps_sample.vel.xy(), gps_sample.sacc);
}
// Determine if we should use GPS aiding for velocity and horizontal position

View File

@ -46,7 +46,7 @@ void Ekf::controlHeightFusion()
controlBaroHeightFusion();
controlGnssHeightFusion(_gps_sample_delayed);
controlRangeHeightFusion();
controlEvHeightFusion();
controlEvHeightFusion(_ev_sample_delayed);
checkHeightSensorRefFallback();
}
@ -211,14 +211,14 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const
// Check all the sources agains each other
for (unsigned i = 0; i < 6; i++) {
if (checks[i].failed_lim) {
// There is a chance that the interial nav is falling if one source is failing the test
// There is a chance that the inertial nav is falling if one source is failing the test
likelihood_medium = true;
}
for (unsigned j = 0; j < 6; j++) {
if ((checks[i].ref_type != checks[j].ref_type) && checks[i].failed_lim && checks[j].failed_min) {
// There is a high chance that the interial nav is falling if two sources are failing the test
// There is a high chance that the inertial nav is failing if two sources are failing the test
likelihood_high = true;
}
}

View File

@ -1,186 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4. 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 height_fusion.cpp
* Function for fusing height (range, baro, GNSS alt, ...) measurements
*/
#include "ekf.h"
void Ekf::updateBaroHgt(const baroSample &baro_sample, estimator_aid_source_1d_s &baro_hgt)
{
// reset flags
resetEstimatorAidStatus(baro_hgt);
// innovation gate size
const float innov_gate = fmaxf(_params.baro_innov_gate, 1.f);
// measurement variance - user parameter defined
const float measurement_var = sq(fmaxf(_params.baro_noise, 0.01f));
const float measurement = baro_sample.hgt;
// vertical position innovation - baro measurement has opposite sign to earth z axis
baro_hgt.observation = -(measurement - _baro_b_est.getBias());
baro_hgt.observation_variance = measurement_var + _baro_b_est.getBiasVar();
baro_hgt.innovation = _state.pos(2) - baro_hgt.observation;
baro_hgt.innovation_variance = P(9, 9) + baro_hgt.observation_variance;
// Compensate for positive static pressure transients (negative vertical position innovations)
// caused by rotor wash ground interaction by applying a temporary deadzone to baro innovations.
if (_control_status.flags.gnd_effect && (_params.gnd_effect_deadzone > 0.f)) {
const float deadzone_start = 0.0f;
const float deadzone_end = deadzone_start + _params.gnd_effect_deadzone;
if (baro_hgt.innovation < -deadzone_start) {
if (baro_hgt.innovation <= -deadzone_end) {
baro_hgt.innovation += deadzone_end;
} else {
baro_hgt.innovation = -deadzone_start;
}
}
}
setEstimatorAidStatusTestRatio(baro_hgt, innov_gate);
// special case if there is bad vertical acceleration data, then don't reject measurement,
// but limit innovation to prevent spikes that could destabilise the filter
if (_fault_status.flags.bad_acc_vertical && baro_hgt.innovation_rejected) {
const float innov_limit = innov_gate * sqrtf(baro_hgt.innovation_variance);
baro_hgt.innovation = math::constrain(baro_hgt.innovation, -innov_limit, innov_limit);
baro_hgt.innovation_rejected = false;
}
baro_hgt.fusion_enabled = _control_status.flags.baro_hgt;
baro_hgt.timestamp_sample = baro_sample.time_us;
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
_baro_b_est.setMaxStateNoise(_params.baro_noise);
_baro_b_est.setProcessNoiseSpectralDensity(_params.baro_bias_nsd);
_baro_b_est.fuseBias(measurement - (-_state.pos(2)) , measurement_var + P(9, 9));
}
void Ekf::fuseBaroHgt(estimator_aid_source_1d_s &baro_hgt)
{
if (baro_hgt.fusion_enabled
&& !baro_hgt.innovation_rejected
&& fuseVelPosHeight(baro_hgt.innovation, baro_hgt.innovation_variance, 5)) {
baro_hgt.fused = true;
baro_hgt.time_last_fuse = _imu_sample_delayed.time_us;
}
}
void Ekf::updateRngHgt(estimator_aid_source_1d_s &rng_hgt)
{
// reset flags
resetEstimatorAidStatus(rng_hgt);
// measurement variance - user parameter defined
const float measurement_var = fmaxf(sq(_params.range_noise) + sq(_params.range_noise_scaler * _range_sensor.getDistBottom()), 0.01f);
const float measurement = math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance);
// innovation gate size
const float innov_gate = fmaxf(_params.range_innov_gate, 1.f);
// vertical position innovation, use range finder with tilt correction
rng_hgt.observation = -(measurement - _rng_hgt_b_est.getBias());
rng_hgt.observation_variance = measurement_var + _rng_hgt_b_est.getBiasVar();
rng_hgt.innovation = _state.pos(2) - rng_hgt.observation;
rng_hgt.innovation_variance = P(9, 9) + rng_hgt.observation_variance;
setEstimatorAidStatusTestRatio(rng_hgt, innov_gate);
// special case if there is bad vertical acceleration data, then don't reject measurement,
// but limit innovation to prevent spikes that could destabilise the filter
if (_fault_status.flags.bad_acc_vertical && rng_hgt.innovation_rejected) {
const float innov_limit = innov_gate * sqrtf(rng_hgt.innovation_variance);
rng_hgt.innovation = math::constrain(rng_hgt.innovation, -innov_limit, innov_limit);
rng_hgt.innovation_rejected = false;
}
rng_hgt.fusion_enabled = _control_status.flags.rng_hgt;
rng_hgt.timestamp_sample = _range_sensor.getSampleAddress()->time_us;
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
const float rng_noise = sqrtf(measurement_var);
_rng_hgt_b_est.setMaxStateNoise(rng_noise);
_rng_hgt_b_est.setProcessNoiseSpectralDensity(_params.rng_hgt_bias_nsd);
_rng_hgt_b_est.fuseBias(measurement - (-_state.pos(2)) , measurement_var + P(9, 9));
}
void Ekf::fuseRngHgt(estimator_aid_source_1d_s &rng_hgt)
{
if (rng_hgt.fusion_enabled
&& !rng_hgt.innovation_rejected
&& fuseVelPosHeight(rng_hgt.innovation, rng_hgt.innovation_variance, 5)) {
rng_hgt.fused = true;
rng_hgt.time_last_fuse = _imu_sample_delayed.time_us;
}
}
void Ekf::fuseEvHgt()
{
const float measurement = _ev_sample_delayed.pos(2);
const float measurement_var = fmaxf(_ev_sample_delayed.posVar(2), sq(0.01f));
const float bias = _ev_hgt_b_est.getBias();
const float bias_var = _ev_hgt_b_est.getBiasVar();
_ev_hgt_b_est.setMaxStateNoise(sqrtf(measurement_var));
_ev_hgt_b_est.setProcessNoiseSpectralDensity(_params.ev_hgt_bias_nsd);
_ev_hgt_b_est.fuseBias(measurement - _state.pos(2), measurement_var + P(9, 9));
// calculate the innovation assuming the external vision observation is in local NED frame
const float obs = measurement - bias;
const float obs_var = measurement_var + bias_var;
// innovation gate size
float innov_gate = fmaxf(_params.ev_pos_innov_gate, 1.f);
updateVerticalPositionAidSrcStatus(_ev_sample_delayed.time_us, obs, obs_var, innov_gate, _aid_src_ev_hgt);
_aid_src_ev_hgt.fusion_enabled = _control_status.flags.ev_hgt;
fuseVerticalPosition(_aid_src_ev_hgt);
}

View File

@ -32,7 +32,7 @@
****************************************************************************/
/**
* @file gps_control.cpp
* @file range_height_control.cpp
* Control functions for ekf range finder height fusion
*/
@ -40,160 +40,166 @@
void Ekf::controlRangeHeightFusion()
{
if (!((_params.rng_ctrl == RngCtrl::CONDITIONAL) || (_params.rng_ctrl == RngCtrl::ENABLED))) {
stopRngHgtFusion();
return;
}
static constexpr const char *HGT_SRC_NAME = "RNG";
_rng_hgt_b_est.predict(_dt_ekf_avg);
auto &aid_src = _aid_src_rng_hgt;
HeightBiasEstimator &bias_est = _rng_hgt_b_est;
const bool rng_intermittent = !isNewestSampleRecent(_time_last_range_buffer_push, 2 * RNG_MAX_INTERVAL);
bias_est.predict(_dt_ekf_avg);
// If we are supposed to be using range finder data as the primary height sensor, have bad range measurements
// and are on the ground, then synthesise a measurement at the expected on ground value
if (!_control_status.flags.in_air
&& !_range_sensor.isDataHealthy()
&& _range_sensor.isRegularlySendingData()
&& _range_sensor.isDataReady()) {
if (_rng_data_ready && _range_sensor.getSampleAddress()) {
_range_sensor.setRange(_params.rng_gnd_clearance);
_range_sensor.setValidity(true); // bypass the checks
}
const float measurement = math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance);
const float measurement_var = sq(_params.range_noise) + sq(_params.range_noise_scaler * _range_sensor.getDistBottom());
if (_rng_data_ready) {
updateRngHgt(_aid_src_rng_hgt);
const float innov_gate = math::max(_params.range_innov_gate, 1.f);
const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var);
// vertical position innovation - baro measurement has opposite sign to earth z axis
updateVerticalPositionAidSrcStatus(_range_sensor.getSampleAddress()->time_us,
-(measurement - bias_est.getBias()),
measurement_var + bias_est.getBiasVar(),
innov_gate,
aid_src);
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
if (measurement_valid && _range_sensor.isDataHealthy()) {
bias_est.setMaxStateNoise(sqrtf(measurement_var));
bias_est.setProcessNoiseSpectralDensity(_params.rng_hgt_bias_nsd);
bias_est.fuseBias(measurement - (-_state.pos(2)), measurement_var + P(9, 9));
}
// determine if we should use height aiding
const bool do_conditional_range_aid = (_params.rng_ctrl == RngCtrl::CONDITIONAL) && isConditionalRangeAidSuitable();
const bool continuing_conditions_passing = ((_params.rng_ctrl == RngCtrl::ENABLED) || do_conditional_range_aid)
&& measurement_valid
&& _range_sensor.isDataHealthy();
const bool continuing_conditions_passing = _range_sensor.isDataHealthy() && !rng_intermittent
&& ((_params.rng_ctrl == RngCtrl::ENABLED) || do_conditional_range_aid);
const bool starting_conditions_passing = continuing_conditions_passing
&& _range_sensor.isRegularlySendingData();
&& isNewestSampleRecent(_time_last_range_buffer_push, 2 * RNG_MAX_INTERVAL)
&& _range_sensor.isRegularlySendingData();
if (_control_status.flags.rng_hgt) {
if (continuing_conditions_passing) {
fuseRngHgt(_aid_src_rng_hgt);
aid_src.fusion_enabled = true;
const bool is_fusion_failing = isTimedOut(_aid_src_rng_hgt.time_last_fuse, _params.hgt_fusion_timeout_max);
if (continuing_conditions_passing) {
fuseVerticalPosition(aid_src);
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max);
if (isHeightResetRequired()) {
// All height sources are failing
resetHeightToRng();
ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME);
_information_events.flags.reset_hgt_to_rng = true;
resetVerticalPositionTo(-(measurement - bias_est.getBias()));
bias_est.setBias(_state.pos(2) + measurement);
// reset vertical velocity
resetVerticalVelocityToZero();
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else if (is_fusion_failing) {
// Some other height source is still working
ECL_WARN("stopping %s height fusion, fusion failing", HGT_SRC_NAME);
stopRngHgtFusion();
_control_status.flags.rng_fault = true;
_range_sensor.setFaulty();
}
} else {
ECL_WARN("stopping %s height fusion, continuing conditions failing", HGT_SRC_NAME);
stopRngHgtFusion();
}
} else {
if (starting_conditions_passing) {
startRngHgtFusion();
if ((_params.height_sensor_ref == HeightSensor::RANGE) && (_params.rng_ctrl == RngCtrl::CONDITIONAL)) {
// Range finder is used while hovering to stabilize the height estimate. Don't reset but use it as height reference.
ECL_INFO("starting conditional %s height fusion", HGT_SRC_NAME);
_height_sensor_ref = HeightSensor::RANGE;
bias_est.setBias(_state.pos(2) + measurement);
} else if ((_params.height_sensor_ref == HeightSensor::RANGE) && (_params.rng_ctrl != RngCtrl::CONDITIONAL)) {
// Range finder is the primary height source, the ground is now the datum used
// to compute the local vertical position
ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME);
_height_sensor_ref = HeightSensor::RANGE;
_information_events.flags.reset_hgt_to_rng = true;
resetVerticalPositionTo(-measurement, measurement_var);
bias_est.reset();
} else {
ECL_INFO("starting %s height fusion", HGT_SRC_NAME);
bias_est.setBias(_state.pos(2) + measurement);
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
bias_est.setFusionActive();
_control_status.flags.rng_hgt = true;
}
}
} else if (_control_status.flags.rng_hgt && rng_intermittent) {
} else if (_control_status.flags.rng_hgt
&& !isNewestSampleRecent(_time_last_range_buffer_push, 2 * RNG_MAX_INTERVAL)) {
// No data anymore. Stop until it comes back.
ECL_WARN("stopping %s height fusion, no data", HGT_SRC_NAME);
stopRngHgtFusion();
}
}
bool Ekf::isConditionalRangeAidSuitable()
{
bool is_range_aid_suitable = false;
if (_control_status.flags.in_air
&& _range_sensor.isHealthy()
&& isTerrainEstimateValid()) {
// check if we can use range finder measurements to estimate height, use hysteresis to avoid rapid switching
// Note that the 0.7 coefficients and the innovation check are arbitrary values but work well in practice
const float range_hagl = _terrain_vpos - _state.pos(2);
const float range_hagl_max = _control_status.flags.rng_hgt ? _params.max_hagl_for_range_aid : (_params.max_hagl_for_range_aid * 0.7f);
const bool is_in_range = range_hagl < range_hagl_max;
float range_hagl_max = _params.max_hagl_for_range_aid;
float max_vel_xy = _params.max_vel_for_range_aid;
const float hagl_test_ratio = (_hagl_innov * _hagl_innov / (sq(_params.range_aid_innov_gate) * _hagl_innov_var));
const bool is_hagl_stable = _control_status.flags.rng_hgt ? (hagl_test_ratio < 1.f) : (hagl_test_ratio < 0.01f);
bool is_hagl_stable = (hagl_test_ratio < 1.f);
if (!_control_status.flags.rng_hgt) {
range_hagl_max = 0.7f * _params.max_hagl_for_range_aid;
max_vel_xy = 0.7f * _params.max_vel_for_range_aid;
is_hagl_stable = (hagl_test_ratio < 0.01f);
}
const float range_hagl = _terrain_vpos - _state.pos(2);
const bool is_in_range = (range_hagl < range_hagl_max);
bool is_below_max_speed = true;
if (isHorizontalAidingActive()) {
const float max_vel = _control_status.flags.rng_hgt ? _params.max_vel_for_range_aid : (_params.max_vel_for_range_aid * 0.7f);
const bool is_below_max_speed = !_state.vel.xy().longerThan(max_vel);
is_range_aid_suitable = is_in_range && is_hagl_stable && is_below_max_speed;
} else {
is_range_aid_suitable = is_in_range && is_hagl_stable;
is_below_max_speed = !_state.vel.xy().longerThan(max_vel_xy);
}
return is_in_range && is_hagl_stable && is_below_max_speed;
}
return is_range_aid_suitable;
}
void Ekf::startRngHgtFusion()
{
if (!_control_status.flags.rng_hgt) {
if ((_params.height_sensor_ref == HeightSensor::RANGE) && (_params.rng_ctrl == RngCtrl::CONDITIONAL)) {
// Range finder is used while hovering to stabilize the height estimate. Don't reset but use it as height reference.
_rng_hgt_b_est.setBias(_state.pos(2) + _range_sensor.getDistBottom());
_height_sensor_ref = HeightSensor::RANGE;
} else if ((_params.height_sensor_ref == HeightSensor::RANGE) && (_params.rng_ctrl != RngCtrl::CONDITIONAL)) {
// Range finder is the primary height source, the ground is now the datum used
// to compute the local vertical position
_rng_hgt_b_est.reset();
_height_sensor_ref = HeightSensor::RANGE;
resetHeightToRng();
} else {
_rng_hgt_b_est.setBias(_state.pos(2) + _range_sensor.getDistBottom());
}
_control_status.flags.rng_hgt = true;
_rng_hgt_b_est.setFusionActive();
ECL_INFO("starting RNG height fusion");
}
}
void Ekf::resetHeightToRng()
{
ECL_INFO("reset height to RNG");
_information_events.flags.reset_hgt_to_rng = true;
float dist_bottom;
if (_control_status.flags.in_air) {
dist_bottom = _range_sensor.getDistBottom();
} else {
// use the parameter rng_gnd_clearance if on ground to avoid a noisy offset initialization (e.g. sonar)
dist_bottom = _params.rng_gnd_clearance;
}
// update the state and associated variance
resetVerticalPositionTo(-(dist_bottom - _rng_hgt_b_est.getBias()));
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(9, sq(_params.range_noise));
_baro_b_est.setBias(_baro_b_est.getBias() + _state_reset_status.posD_change);
_gps_hgt_b_est.setBias(_gps_hgt_b_est.getBias() + _state_reset_status.posD_change);
_ev_hgt_b_est.setBias(_ev_hgt_b_est.getBias() - _state_reset_status.posD_change);
return false;
}
void Ekf::stopRngHgtFusion()
{
if (_control_status.flags.rng_hgt) {
if (_height_sensor_ref == HeightSensor::RANGE) {
_height_sensor_ref = HeightSensor::UNKNOWN;
}
_control_status.flags.rng_hgt = false;
_rng_hgt_b_est.setFusionInactive();
ECL_INFO("stopping range height fusion");
resetEstimatorAidStatus(_aid_src_rng_hgt);
_control_status.flags.rng_hgt = false;
}
}

View File

@ -106,7 +106,7 @@ public:
float getValidMinVal() const { return _rng_valid_min_val; }
float getValidMaxVal() const { return _rng_valid_max_val; }
void setFaulty() { _is_faulty = true; }
void setFaulty(bool faulty = true) { _is_faulty = faulty; }
private:
void updateSensorToEarthRotation(const matrix::Dcmf &R_to_earth);

View File

@ -118,7 +118,7 @@ void Ekf::controlHaglRngFusion()
// The sensor can probably not detect the ground properly
// declare the sensor faulty and stop the fusion
_control_status.flags.rng_fault = true;
_range_sensor.setFaulty();
_range_sensor.setFaulty(true);
stopHaglRngFusion();
} else {

View File

@ -52,7 +52,7 @@ void Ekf::updateVelocityAidSrcStatus(const uint64_t &time_us, const Vector2f &ob
aid_src.observation[i] = obs(i);
aid_src.innovation[i] = _state.vel(i) - aid_src.observation[i];
aid_src.observation_variance[i] = obs_var(i);
aid_src.observation_variance[i] = math::max(sq(0.01f), obs_var(i));
aid_src.innovation_variance[i] = P(4 + i, 4 + i) + aid_src.observation_variance[i];
}
@ -70,7 +70,7 @@ void Ekf::updateVelocityAidSrcStatus(const uint64_t &time_us, const Vector3f &ob
aid_src.observation[i] = obs(i);
aid_src.innovation[i] = _state.vel(i) - aid_src.observation[i];
aid_src.observation_variance[i] = obs_var(i);
aid_src.observation_variance[i] = math::max(sq(0.01f), obs_var(i));
aid_src.innovation_variance[i] = P(4 + i, 4 + i) + aid_src.observation_variance[i];
}
@ -95,7 +95,7 @@ void Ekf::updateVerticalPositionAidSrcStatus(const uint64_t &time_us, const floa
aid_src.observation = obs;
aid_src.innovation = _state.pos(2) - aid_src.observation;
aid_src.observation_variance = obs_var;
aid_src.observation_variance = math::max(sq(0.01f), obs_var);
aid_src.innovation_variance = P(9, 9) + aid_src.observation_variance;
setEstimatorAidStatusTestRatio(aid_src, innov_gate);
@ -120,7 +120,7 @@ void Ekf::updateHorizontalPositionAidSrcStatus(const uint64_t &time_us, const Ve
aid_src.observation[i] = obs(i);
aid_src.innovation[i] = _state.pos(i) - aid_src.observation[i];
aid_src.observation_variance[i] = obs_var(i);
aid_src.observation_variance[i] = math::max(sq(0.01f), obs_var(i));
aid_src.innovation_variance[i] = P(7 + i, 7 + i) + aid_src.observation_variance[i];
}

View File

@ -1,47 +1,47 @@
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.011,-0.00011,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
90000,1,-0.011,-0.01,-0.022,-0.0011,0.00084,-0.011,-5.7e-05,2.6e-05,-0.00039,0,0,0,0,0,0,0.19,9.3e-10,0.4,0,0,0,0,0,1.5e-06,0.0025,0.0025,0.0021,0.26,0.26,0.56,0.25,0.25,4,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
190000,1,-0.011,-0.01,-0.022,-0.0012,1.8e-05,-0.025,-0.00014,5.9e-05,-0.0022,0,0,0,0,0,0,0.19,9.3e-10,0.4,0,0,0,0,0,1.1e-06,0.0026,0.0026,0.0012,0.28,0.28,0.56,0.26,0.26,1,1e-06,1e-06,9.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
290000,1,-0.011,-0.011,-0.022,0.00047,0.00042,-0.039,1.7e-05,-4.6e-06,-0.0054,0,0,0,0,0,0,0.19,9.3e-10,0.4,0,0,0,0,0,1e-06,0.0027,0.0027,0.00084,25,25,0.56,1e+02,1e+02,0.37,1e-06,1e-06,9.8e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
390000,1,-0.011,-0.011,-0.022,0.0012,0.00016,-0.054,0.0001,4.7e-05,-0.01,0,0,0,0,0,0,0.19,9.3e-10,0.4,0,0,0,0,0,9.8e-07,0.0028,0.0028,0.00069,25,25,0.56,1e+02,1e+02,0.22,1e-06,1e-06,9.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
490000,1,-0.011,-0.011,-0.022,0.003,-0.00086,-0.069,0.00017,-4.7e-05,-0.016,2.6e-12,-7.7e-12,-8.9e-14,0,0,-1.8e-13,0.19,9.3e-10,0.4,0,0,0,0,0,1e-06,0.0031,0.0031,0.00062,25,25,0.55,0.37,0.37,0.16,1e-06,1e-06,9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
590000,1,-0.011,-0.012,-0.022,0.0044,-0.00055,-0.083,0.00055,-0.00012,-0.024,2.6e-12,-7.7e-12,-8.9e-14,0,0,-1.8e-13,0.19,9.3e-10,0.4,0,0,0,0,0,1.1e-06,0.0033,0.0033,0.0006,25,25,0.53,0.97,0.97,0.14,1e-06,1e-06,8.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
190000,1,-0.011,-0.01,-0.022,-0.0012,1.8e-05,-0.025,-0.00014,5.9e-05,-0.0022,0,0,0,0,0,0,0.19,9.3e-10,0.4,0,0,0,0,0,1.1e-06,0.0026,0.0026,0.0012,0.28,0.28,0.56,0.26,0.26,1.3,1e-06,1e-06,9.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
290000,1,-0.011,-0.011,-0.022,0.00047,0.00042,-0.039,1.7e-05,-4.6e-06,-0.0054,0,0,0,0,0,0,0.19,9.3e-10,0.4,0,0,0,0,0,1e-06,0.0027,0.0027,0.00084,25,25,0.56,1e+02,1e+02,0.4,1e-06,1e-06,9.8e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
390000,1,-0.011,-0.011,-0.022,0.0012,0.00016,-0.054,0.0001,4.7e-05,-0.01,0,0,0,0,0,0,0.19,9.3e-10,0.4,0,0,0,0,0,9.8e-07,0.0028,0.0028,0.00069,25,25,0.56,1e+02,1e+02,0.23,1e-06,1e-06,9.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
490000,1,-0.011,-0.011,-0.022,0.003,-0.00086,-0.069,0.00017,-4.7e-05,-0.016,2.6e-12,-7.7e-12,-8.9e-14,0,0,-1.8e-13,0.19,9.3e-10,0.4,0,0,0,0,0,1e-06,0.0031,0.0031,0.00062,25,25,0.55,0.37,0.37,0.17,1e-06,1e-06,9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
590000,1,-0.011,-0.012,-0.022,0.0044,-0.00055,-0.083,0.00055,-0.00012,-0.024,2.6e-12,-7.7e-12,-8.9e-14,0,0,-1.8e-13,0.19,9.3e-10,0.4,0,0,0,0,0,1.1e-06,0.0033,0.0033,0.0006,25,25,0.54,0.97,0.97,0.15,1e-06,1e-06,8.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
690000,1,-0.011,-0.012,-0.022,0.004,-0.0013,-0.098,0.0003,-0.0001,-0.033,-1.7e-09,-1e-08,1.2e-10,0,0,-3.1e-10,0.19,9.3e-10,0.4,0,0,0,0,0,1.2e-06,0.0036,0.0036,0.00059,7.8,7.8,0.51,0.34,0.34,0.13,1e-06,1e-06,7.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
790000,1,-0.011,-0.012,-0.022,0.0056,-0.0014,-0.11,0.00076,-0.00025,-0.043,-1.7e-09,-1e-08,1.2e-10,0,0,-3.1e-10,0.19,9.3e-10,0.4,0,0,0,0,0,1.3e-06,0.004,0.004,0.00059,7.9,7.9,0.48,0.67,0.67,0.13,1e-06,1e-06,6.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
890000,1,-0.011,-0.012,-0.022,0.007,-0.002,-0.13,0.00054,-0.00018,-0.055,-1.2e-08,-4.5e-08,6.3e-10,0,0,-1.1e-09,0.19,9.3e-10,0.4,0,0,0,0,0,1.4e-06,0.0044,0.0044,0.00059,2.7,2.7,0.48,0.26,0.26,0.17,1e-06,1e-06,6.1e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
890000,1,-0.011,-0.012,-0.022,0.007,-0.002,-0.13,0.00054,-0.00018,-0.055,-1.2e-08,-4.5e-08,6.3e-10,0,0,-1.1e-09,0.19,9.3e-10,0.4,0,0,0,0,0,1.4e-06,0.0044,0.0044,0.00059,2.7,2.7,0.49,0.26,0.26,0.17,1e-06,1e-06,6.1e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
990000,1,-0.011,-0.013,-0.022,0.011,-0.0039,-0.14,0.0014,-0.00046,-0.069,-1.2e-08,-4.5e-08,6.3e-10,0,0,-1.1e-09,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-06,0.0048,0.0048,0.00058,2.8,2.8,0.49,0.42,0.42,0.21,1e-06,1e-06,5.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1090000,1,-0.011,-0.013,-0.022,0.011,-0.0046,-0.16,0.0011,-0.0004,-0.084,-6e-08,-2.1e-07,2.9e-09,0,0,-4.1e-09,0.19,9.3e-10,0.4,0,0,0,0,0,1.8e-06,0.0052,0.0052,0.00058,1.3,1.3,0.5,0.2,0.2,0.27,9.9e-07,9.9e-07,4.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1190000,1,-0.011,-0.013,-0.022,0.015,-0.0066,-0.17,0.0024,-0.00096,-0.1,-6e-08,-2.1e-07,2.9e-09,0,0,-4.1e-09,0.19,9.3e-10,0.4,0,0,0,0,0,2e-06,0.0058,0.0058,0.00057,1.5,1.5,0.5,0.3,0.3,0.33,9.9e-07,9.9e-07,4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1290000,1,-0.011,-0.014,-0.022,0.016,-0.0065,-0.18,0.0018,-0.00078,-0.12,-2.6e-07,-7.6e-07,1.1e-08,0,0,-1.3e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.1e-06,0.0062,0.0062,0.00056,0.95,0.95,0.51,0.17,0.17,0.41,9.8e-07,9.8e-07,3.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1390000,1,-0.012,-0.014,-0.022,0.021,-0.0088,-0.2,0.0037,-0.0015,-0.14,-2.6e-07,-7.6e-07,1.1e-08,0,0,-1.3e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.4e-06,0.0068,0.0068,0.00055,1.2,1.2,0.52,0.24,0.24,0.49,9.8e-07,9.8e-07,3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1490000,1,-0.012,-0.014,-0.022,0.021,-0.0083,-0.21,0.0029,-0.0012,-0.16,-7.8e-07,-2.2e-06,3.1e-08,0,0,-3.4e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.5e-06,0.0069,0.0069,0.00053,0.92,0.92,0.53,0.15,0.15,0.59,9.4e-07,9.4e-07,2.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1190000,1,-0.011,-0.013,-0.022,0.015,-0.0066,-0.17,0.0024,-0.00096,-0.1,-6e-08,-2.1e-07,2.9e-09,0,0,-4.1e-09,0.19,9.3e-10,0.4,0,0,0,0,0,2e-06,0.0058,0.0058,0.00057,1.5,1.5,0.51,0.3,0.3,0.33,9.9e-07,9.9e-07,4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1290000,1,-0.011,-0.014,-0.022,0.016,-0.0065,-0.18,0.0018,-0.00078,-0.12,-2.6e-07,-7.6e-07,1.1e-08,0,0,-1.3e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.1e-06,0.0062,0.0062,0.00056,0.95,0.95,0.52,0.17,0.17,0.41,9.8e-07,9.8e-07,3.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1390000,1,-0.012,-0.014,-0.022,0.021,-0.0088,-0.2,0.0037,-0.0015,-0.14,-2.6e-07,-7.6e-07,1.1e-08,0,0,-1.3e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.4e-06,0.0068,0.0068,0.00055,1.2,1.2,0.53,0.24,0.24,0.49,9.8e-07,9.8e-07,3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1490000,1,-0.012,-0.014,-0.022,0.021,-0.0083,-0.21,0.0029,-0.0012,-0.16,-7.8e-07,-2.2e-06,3.1e-08,0,0,-3.4e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.5e-06,0.0069,0.0069,0.00053,0.92,0.92,0.54,0.15,0.15,0.59,9.4e-07,9.4e-07,2.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1590000,1,-0.012,-0.014,-0.022,0.027,-0.0096,-0.23,0.0053,-0.002,-0.18,-7.8e-07,-2.2e-06,3.1e-08,0,0,-3.4e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.7e-06,0.0076,0.0076,0.00051,1.2,1.2,0.55,0.21,0.21,0.7,9.4e-07,9.4e-07,2.2e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1690000,1,-0.012,-0.014,-0.022,0.027,-0.01,-0.24,0.0039,-0.0015,-0.2,-1.8e-06,-5.3e-06,6.9e-08,0,0,-7e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.6e-06,0.0071,0.0071,0.0005,1,1,0.56,0.14,0.14,0.82,8.7e-07,8.7e-07,1.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1790000,1,-0.012,-0.014,-0.022,0.034,-0.014,-0.25,0.0069,-0.0027,-0.23,-1.8e-06,-5.3e-06,6.9e-08,0,0,-7e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.9e-06,0.0078,0.0078,0.00048,1.3,1.3,0.57,0.21,0.21,0.95,8.7e-07,8.7e-07,1.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1790000,1,-0.012,-0.014,-0.022,0.034,-0.014,-0.25,0.0069,-0.0027,-0.23,-1.8e-06,-5.3e-06,6.9e-08,0,0,-7e-08,0.19,9.3e-10,0.4,0,0,0,0,0,2.9e-06,0.0078,0.0078,0.00048,1.3,1.3,0.58,0.21,0.21,0.95,8.7e-07,8.7e-07,1.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1890000,1,-0.011,-0.014,-0.022,0.031,-0.012,-0.27,0.0048,-0.0019,-0.25,-3.5e-06,-1e-05,1.3e-07,0,0,-1.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.5e-06,0.0066,0.0066,0.00046,1.1,1.1,0.59,0.14,0.14,1.1,7.6e-07,7.6e-07,1.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1990000,1,-0.011,-0.014,-0.022,0.037,-0.014,-0.28,0.0082,-0.0032,-0.28,-3.5e-06,-1e-05,1.3e-07,0,0,-1.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.8e-06,0.0072,0.0072,0.00045,1.4,1.4,0.6,0.21,0.21,1.3,7.6e-07,7.6e-07,1.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1990000,1,-0.011,-0.014,-0.022,0.037,-0.014,-0.28,0.0082,-0.0032,-0.28,-3.5e-06,-1e-05,1.3e-07,0,0,-1.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.8e-06,0.0072,0.0072,0.00045,1.4,1.4,0.61,0.21,0.21,1.3,7.6e-07,7.6e-07,1.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2090000,1,-0.011,-0.014,-0.022,0.044,-0.017,-0.29,0.012,-0.0048,-0.31,-3.5e-06,-1e-05,1.3e-07,0,0,-1.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,3e-06,0.0079,0.0079,0.00043,1.8,1.8,0.62,0.31,0.31,1.4,7.6e-07,7.6e-07,1.1e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2190000,1,-0.011,-0.014,-0.022,0.035,-0.013,-0.31,0.0084,-0.0033,-0.34,-5.5e-06,-1.6e-05,1.9e-07,0,0,-1.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.4e-06,0.0061,0.0061,0.00042,1.3,1.3,0.63,0.21,0.21,1.6,6.3e-07,6.3e-07,9.9e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2290000,1,-0.011,-0.014,-0.022,0.042,-0.016,-0.32,0.012,-0.0047,-0.37,-5.5e-06,-1.6e-05,1.9e-07,0,0,-1.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.7e-06,0.0067,0.0067,0.0004,1.7,1.7,0.65,0.31,0.31,1.8,6.3e-07,6.3e-07,8.8e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2190000,1,-0.011,-0.014,-0.022,0.035,-0.013,-0.31,0.0084,-0.0033,-0.34,-5.5e-06,-1.6e-05,1.9e-07,0,0,-1.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.4e-06,0.0061,0.0061,0.00042,1.3,1.3,0.64,0.21,0.21,1.6,6.3e-07,6.3e-07,9.9e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2290000,1,-0.011,-0.014,-0.022,0.042,-0.016,-0.32,0.012,-0.0047,-0.37,-5.5e-06,-1.6e-05,1.9e-07,0,0,-1.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.7e-06,0.0067,0.0067,0.0004,1.7,1.7,0.66,0.31,0.31,1.8,6.3e-07,6.3e-07,8.8e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2390000,1,-0.011,-0.013,-0.022,0.032,-0.011,-0.34,0.008,-0.003,-0.4,-7.4e-06,-2.2e-05,2.5e-07,0,0,-2.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2e-06,0.0049,0.0049,0.00039,1.2,1.2,0.67,0.2,0.2,2,5.2e-07,5.2e-07,7.9e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2490000,1,-0.011,-0.013,-0.022,0.037,-0.013,-0.35,0.011,-0.0042,-0.44,-7.4e-06,-2.2e-05,2.5e-07,0,0,-2.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.2e-06,0.0054,0.0054,0.00038,1.5,1.5,0.69,0.3,0.3,2.3,5.2e-07,5.2e-07,7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2590000,1,-0.011,-0.013,-0.022,0.028,-0.0089,-0.36,0.0072,-0.0026,-0.47,-9e-06,-2.7e-05,3e-07,0,0,-2.5e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-06,0.0039,0.0039,0.00036,1,1,0.71,0.19,0.19,2.5,4.3e-07,4.3e-07,6.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2690000,1,-0.011,-0.013,-0.022,0.032,-0.0099,-0.38,0.01,-0.0036,-0.51,-9e-06,-2.7e-05,3e-07,0,0,-2.5e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.8e-06,0.0043,0.0043,0.00035,1.3,1.3,0.73,0.28,0.28,2.8,4.3e-07,4.3e-07,5.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2790000,1,-0.011,-0.013,-0.022,0.024,-0.0071,-0.39,0.0064,-0.0021,-0.55,-1e-05,-3.1e-05,3.3e-07,0,0,-2.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.3e-06,0.0031,0.0031,0.00034,0.88,0.88,0.75,0.18,0.18,3,3.5e-07,3.5e-07,5.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2890000,1,-0.011,-0.013,-0.022,0.028,-0.0081,-0.4,0.009,-0.0029,-0.59,-1e-05,-3.1e-05,3.3e-07,0,0,-2.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.4e-06,0.0034,0.0034,0.00033,1.1,1.1,0.77,0.25,0.25,3.3,3.5e-07,3.5e-07,4.6e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2990000,1,-0.011,-0.013,-0.022,0.022,-0.0057,-0.41,0.0058,-0.0018,-0.63,-1.1e-05,-3.5e-05,3.5e-07,0,0,-2.5e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.1e-06,0.0026,0.0026,0.00032,0.76,0.76,0.79,0.16,0.16,3.7,3e-07,3e-07,4.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2790000,1,-0.011,-0.013,-0.022,0.024,-0.0071,-0.39,0.0064,-0.0021,-0.55,-1e-05,-3.1e-05,3.3e-07,0,0,-2.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.3e-06,0.0031,0.0031,0.00034,0.88,0.88,0.75,0.18,0.18,3.1,3.5e-07,3.5e-07,5.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2890000,1,-0.011,-0.013,-0.022,0.028,-0.0081,-0.4,0.009,-0.0029,-0.59,-1e-05,-3.1e-05,3.3e-07,0,0,-2.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.4e-06,0.0034,0.0034,0.00033,1.1,1.1,0.77,0.25,0.25,3.4,3.5e-07,3.5e-07,4.6e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2990000,1,-0.011,-0.013,-0.022,0.022,-0.0057,-0.41,0.0058,-0.0018,-0.63,-1.1e-05,-3.5e-05,3.5e-07,0,0,-2.5e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.1e-06,0.0026,0.0026,0.00032,0.76,0.76,0.8,0.16,0.16,3.7,3e-07,3e-07,4.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3090000,1,-0.011,-0.013,-0.022,0.025,-0.0062,-0.43,0.0081,-0.0024,-0.67,-1.1e-05,-3.5e-05,3.5e-07,0,0,-2.5e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.2e-06,0.0028,0.0028,0.00031,0.93,0.93,0.82,0.23,0.23,4,3e-07,3e-07,3.8e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3190000,1,-0.011,-0.012,-0.022,0.02,-0.0038,-0.44,0.0052,-0.0014,-0.72,-1.2e-05,-3.7e-05,3.6e-07,0,0,-2.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,9.2e-07,0.0022,0.0022,0.0003,0.66,0.66,0.84,0.15,0.15,4.3,2.5e-07,2.5e-07,3.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3290000,1,-0.011,-0.012,-0.022,0.023,-0.0047,-0.45,0.0074,-0.0019,-0.76,-1.2e-05,-3.7e-05,3.6e-07,0,0,-2.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,9.9e-07,0.0024,0.0024,0.00029,0.81,0.81,0.86,0.22,0.22,4.7,2.5e-07,2.5e-07,3.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3390000,1,-0.011,-0.012,-0.022,0.018,-0.0036,-0.47,0.0049,-0.0012,-0.81,-1.2e-05,-4e-05,3.7e-07,0,0,-2.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,7.9e-07,0.0019,0.0019,0.00029,0.58,0.58,0.89,0.14,0.14,5.1,2.2e-07,2.2e-07,2.9e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3490000,1,-0.011,-0.012,-0.022,0.022,-0.0052,-0.48,0.0069,-0.0016,-0.85,-1.2e-05,-4e-05,3.7e-07,0,0,-2.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,8.5e-07,0.0021,0.0021,0.00028,0.71,0.71,0.92,0.2,0.2,5.5,2.2e-07,2.2e-07,2.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3590000,1,-0.011,-0.012,-0.022,0.017,-0.0051,-0.49,0.0046,-0.0011,-0.9,-1.3e-05,-4.2e-05,3.7e-07,0,0,-2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,6.8e-07,0.0017,0.0017,0.00027,0.52,0.52,0.94,0.14,0.14,6,1.8e-07,1.8e-07,2.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3690000,1,-0.011,-0.012,-0.022,0.02,-0.007,-0.51,0.0065,-0.0017,-0.95,-1.3e-05,-4.2e-05,3.7e-07,0,0,-2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,7.3e-07,0.0018,0.0018,0.00026,0.64,0.64,0.97,0.19,0.19,6.4,1.8e-07,1.8e-07,2.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3790000,1,-0.011,-0.012,-0.022,0.016,-0.0074,-0.52,0.0044,-0.0013,-1,-1.3e-05,-4.4e-05,3.8e-07,0,0,-1.7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,6e-07,0.0015,0.0015,0.00026,0.47,0.47,1,0.13,0.13,6.9,1.6e-07,1.6e-07,2.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3890000,1,-0.011,-0.012,-0.022,0.017,-0.0074,-0.53,0.006,-0.002,-1.1,-1.3e-05,-4.4e-05,3.8e-07,0,0,-1.7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,6.4e-07,0.0016,0.0016,0.00025,0.58,0.58,1,0.17,0.17,7.4,1.6e-07,1.6e-07,2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3190000,1,-0.011,-0.012,-0.022,0.02,-0.0038,-0.44,0.0052,-0.0014,-0.72,-1.2e-05,-3.7e-05,3.6e-07,0,0,-2.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,9.2e-07,0.0022,0.0022,0.0003,0.66,0.66,0.85,0.15,0.15,4.4,2.5e-07,2.5e-07,3.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3290000,1,-0.011,-0.012,-0.022,0.023,-0.0047,-0.45,0.0074,-0.0019,-0.76,-1.2e-05,-3.7e-05,3.6e-07,0,0,-2.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,9.9e-07,0.0024,0.0024,0.00029,0.81,0.81,0.87,0.22,0.22,4.7,2.5e-07,2.5e-07,3.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3390000,1,-0.011,-0.012,-0.022,0.018,-0.0036,-0.47,0.0049,-0.0012,-0.81,-1.2e-05,-4e-05,3.7e-07,0,0,-2.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,7.9e-07,0.0019,0.0019,0.00029,0.58,0.58,0.9,0.14,0.14,5.1,2.2e-07,2.2e-07,2.9e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3490000,1,-0.011,-0.012,-0.022,0.022,-0.0052,-0.48,0.0069,-0.0016,-0.85,-1.2e-05,-4e-05,3.7e-07,0,0,-2.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,8.5e-07,0.0021,0.0021,0.00028,0.71,0.71,0.92,0.2,0.2,5.6,2.2e-07,2.2e-07,2.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3590000,1,-0.011,-0.012,-0.022,0.017,-0.0051,-0.49,0.0046,-0.0011,-0.9,-1.3e-05,-4.2e-05,3.7e-07,0,0,-2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,6.8e-07,0.0017,0.0017,0.00027,0.52,0.52,0.95,0.14,0.14,6,1.8e-07,1.8e-07,2.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3690000,1,-0.011,-0.012,-0.022,0.02,-0.007,-0.51,0.0065,-0.0017,-0.95,-1.3e-05,-4.2e-05,3.7e-07,0,0,-2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,7.3e-07,0.0018,0.0018,0.00026,0.64,0.64,0.98,0.19,0.19,6.5,1.8e-07,1.8e-07,2.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3790000,1,-0.011,-0.012,-0.022,0.016,-0.0074,-0.52,0.0044,-0.0013,-1,-1.3e-05,-4.4e-05,3.8e-07,0,0,-1.7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,6e-07,0.0015,0.0015,0.00026,0.47,0.47,1,0.13,0.13,7,1.6e-07,1.6e-07,2.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3890000,1,-0.011,-0.012,-0.022,0.017,-0.0074,-0.53,0.006,-0.002,-1.1,-1.3e-05,-4.4e-05,3.8e-07,0,0,-1.7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,6.4e-07,0.0016,0.0016,0.00025,0.58,0.58,1,0.17,0.17,7.5,1.6e-07,1.6e-07,2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3990000,1,-0.01,-0.012,-0.022,0.015,-0.006,-0.55,0.0041,-0.0015,-1.1,-1.4e-05,-4.6e-05,3.9e-07,0,0,-1.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,5.2e-07,0.0013,0.0013,0.00024,0.44,0.44,1.1,0.12,0.12,8,1.3e-07,1.3e-07,1.8e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4090000,1,-0.01,-0.012,-0.022,0.018,-0.0074,-0.56,0.0057,-0.0021,-1.2,-1.4e-05,-4.6e-05,3.9e-07,0,0,-1.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,5.5e-07,0.0015,0.0015,0.00024,0.53,0.53,1.1,0.16,0.16,8.5,1.3e-07,1.3e-07,1.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4190000,1,-0.01,-0.012,-0.022,0.021,-0.0088,-0.58,0.0077,-0.0029,-1.2,-1.4e-05,-4.6e-05,3.9e-07,0,0,-1.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,5.9e-07,0.0016,0.0016,0.00023,0.64,0.64,1.1,0.22,0.22,9.1,1.3e-07,1.3e-07,1.6e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4090000,1,-0.01,-0.012,-0.022,0.018,-0.0074,-0.56,0.0057,-0.0021,-1.2,-1.4e-05,-4.6e-05,3.9e-07,0,0,-1.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,5.5e-07,0.0015,0.0015,0.00024,0.53,0.53,1.1,0.16,0.16,8.6,1.3e-07,1.3e-07,1.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4190000,1,-0.01,-0.012,-0.022,0.021,-0.0088,-0.58,0.0077,-0.0029,-1.2,-1.4e-05,-4.6e-05,3.9e-07,0,0,-1.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,5.9e-07,0.0016,0.0016,0.00023,0.64,0.64,1.1,0.22,0.22,9.2,1.3e-07,1.3e-07,1.6e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4290000,1,-0.01,-0.012,-0.022,0.018,-0.0055,-0.59,0.0056,-0.0021,-1.3,-1.4e-05,-4.7e-05,4e-07,0,0,-9.2e-08,0.19,9.3e-10,0.4,0,0,0,0,0,4.8e-07,0.0013,0.0013,0.00023,0.49,0.49,1.2,0.16,0.16,9.8,1.1e-07,1.1e-07,1.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4390000,1,-0.01,-0.012,-0.022,0.019,-0.0054,-0.6,0.0074,-0.0027,-1.3,-1.4e-05,-4.7e-05,4e-07,0,0,-9.2e-08,0.19,9.3e-10,0.4,0,0,0,0,0,5.1e-07,0.0014,0.0014,0.00022,0.59,0.59,1.2,0.21,0.21,10,1.1e-07,1.1e-07,1.4e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4490000,1,-0.01,-0.012,-0.022,0.016,-0.0037,-0.62,0.0053,-0.0017,-1.4,-1.5e-05,-4.9e-05,4.1e-07,0,0,-5.3e-08,0.19,9.3e-10,0.4,0,0,0,0,0,4.2e-07,0.0012,0.0012,0.00022,0.45,0.45,1.2,0.15,0.15,11,9.3e-08,9.3e-08,1.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
@ -58,19 +58,19 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
5590000,1,-0.0098,-0.011,-0.022,0.008,-0.0022,-0.78,0.0043,-0.0013,-2.2,-1.6e-05,-5.5e-05,4.3e-07,0,0,1.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.3e-07,0.00064,0.00064,0.00018,0.36,0.36,1.7,0.15,0.15,21,3.4e-08,3.4e-08,6.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5690000,1,-0.0097,-0.011,-0.022,0.0057,-0.00028,-0.79,0.0029,-0.00083,-2.2,-1.6e-05,-5.5e-05,4.3e-07,0,0,1.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.9e-07,0.00051,0.00051,0.00017,0.28,0.28,1.7,0.11,0.11,22,2.7e-08,2.7e-08,6.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5790000,1,-0.0096,-0.011,-0.022,0.0063,0.0011,-0.8,0.0035,-0.00079,-2.3,-1.6e-05,-5.5e-05,4.3e-07,0,0,1.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2e-07,0.00055,0.00055,0.00017,0.32,0.32,1.8,0.15,0.15,23,2.7e-08,2.7e-08,6.1e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5890000,1,-0.0095,-0.011,-0.022,0.0054,0.0022,0.0029,0.0024,-0.00038,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,1.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.7e-07,0.00044,0.00044,0.00017,0.25,0.25,9.8,0.11,0.11,0.52,2.2e-08,2.2e-08,5.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5990000,1,-0.0095,-0.011,-0.022,0.0059,0.004,0.015,0.003,-2.2e-05,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,4e-08,0.19,9.3e-10,0.4,0,0,0,0,0,1.8e-07,0.00047,0.00047,0.00017,0.29,0.29,8.8,0.14,0.14,0.33,2.2e-08,2.2e-08,5.5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5890000,1,-0.0095,-0.011,-0.022,0.0054,0.0022,0.0028,0.0024,-0.00038,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,1.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.7e-07,0.00044,0.00044,0.00017,0.25,0.25,9.8,0.11,0.11,0.52,2.2e-08,2.2e-08,5.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5990000,1,-0.0095,-0.011,-0.022,0.0059,0.004,0.015,0.003,-2.2e-05,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,4.1e-08,0.19,9.3e-10,0.4,0,0,0,0,0,1.8e-07,0.00047,0.00047,0.00017,0.29,0.29,8.8,0.14,0.14,0.33,2.2e-08,2.2e-08,5.5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6090000,1,-0.0095,-0.011,-0.022,0.0053,0.0052,-0.011,0.0021,0.00027,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,1.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.5e-07,0.00038,0.00038,0.00016,0.23,0.23,7,0.1,0.1,0.33,1.8e-08,1.8e-08,5.3e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6190000,1,-0.0095,-0.011,-0.022,0.0056,0.0072,-0.0047,0.0027,0.00092,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,-1.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00041,0.00041,0.00016,0.27,0.27,4.9,0.13,0.13,0.32,1.8e-08,1.8e-08,5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6190000,1,-0.0095,-0.011,-0.022,0.0056,0.0072,-0.005,0.0027,0.00092,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,-1.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00041,0.00041,0.00016,0.27,0.27,4.9,0.13,0.13,0.32,1.8e-08,1.8e-08,5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6290000,1,-0.0095,-0.011,-0.022,0.0071,0.0075,-0.012,0.0033,0.0016,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,-1.9e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00043,0.00043,0.00016,0.31,0.31,3.2,0.17,0.17,0.3,1.8e-08,1.8e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6390000,0.71,0.0014,-0.014,0.71,0.0048,0.0076,-0.05,0.0025,0.0017,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,4.1e-07,0.21,0.002,0.44,0,0,0,0,0,0.00076,0.00034,0.00034,0.00085,0.22,0.22,2.3,0.13,0.13,0.29,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6490000,0.71,0.0014,-0.014,0.71,0.0043,0.0083,-0.052,0.0029,0.0025,-3.7e+02,-1.6e-05,-5.6e-05,4.1e-07,0,0,-8.2e-08,0.21,0.002,0.44,0,0,0,0,0,0.00051,0.00034,0.00034,0.00056,0.22,0.22,1.5,0.16,0.16,0.26,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6390000,0.71,0.0014,-0.014,0.71,0.0048,0.0076,-0.05,0.0025,0.0017,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,4e-07,0.21,0.002,0.44,0,0,0,0,0,0.00076,0.00034,0.00034,0.00085,0.22,0.22,2.3,0.13,0.13,0.29,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6490000,0.71,0.0014,-0.014,0.71,0.0043,0.0083,-0.052,0.0029,0.0025,-3.7e+02,-1.6e-05,-5.6e-05,4.1e-07,0,0,-8.7e-08,0.21,0.002,0.44,0,0,0,0,0,0.00051,0.00034,0.00034,0.00056,0.22,0.22,1.5,0.16,0.16,0.26,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6590000,0.71,0.0015,-0.014,0.71,0.0036,0.0085,-0.099,0.0034,0.0033,-3.7e+02,-1.6e-05,-5.6e-05,3.6e-07,0,0,1.7e-06,0.21,0.002,0.44,0,0,0,0,0,0.00039,0.00034,0.00034,0.00043,0.23,0.23,1.1,0.19,0.19,0.23,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6690000,0.7,0.0015,-0.014,0.71,0.0037,0.0095,-0.076,0.0037,0.0042,-3.7e+02,-1.6e-05,-5.6e-05,3e-07,0,0,-1.5e-06,0.21,0.002,0.44,0,0,0,0,0,0.00031,0.00034,0.00034,0.00035,0.24,0.24,0.78,0.23,0.23,0.21,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6790000,0.71,0.0015,-0.014,0.71,0.0021,0.0095,-0.11,0.004,0.0052,-3.7e+02,-1.6e-05,-5.6e-05,3.3e-07,0,0,8.6e-07,0.21,0.002,0.44,0,0,0,0,0,0.00027,0.00034,0.00034,0.0003,0.25,0.25,0.6,0.28,0.28,0.2,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6890000,0.71,0.0015,-0.014,0.71,-0.00021,0.01,-0.12,0.0041,0.0062,-3.7e+02,-1.6e-05,-5.6e-05,3.4e-07,0,0,3.5e-07,0.21,0.002,0.44,0,0,0,0,0,0.00024,0.00035,0.00035,0.00026,0.26,0.26,0.46,0.33,0.33,0.18,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6790000,0.71,0.0015,-0.014,0.71,0.0021,0.0095,-0.11,0.004,0.0052,-3.7e+02,-1.6e-05,-5.6e-05,3.3e-07,0,0,8.5e-07,0.21,0.002,0.44,0,0,0,0,0,0.00027,0.00034,0.00034,0.0003,0.25,0.25,0.6,0.28,0.28,0.2,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6890000,0.71,0.0015,-0.014,0.71,-0.00021,0.01,-0.12,0.0041,0.0062,-3.7e+02,-1.6e-05,-5.6e-05,3.4e-07,0,0,3.4e-07,0.21,0.002,0.44,0,0,0,0,0,0.00024,0.00035,0.00035,0.00026,0.26,0.26,0.46,0.33,0.33,0.18,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6990000,0.7,0.0016,-0.014,0.71,-0.00055,0.011,-0.12,0.004,0.0072,-3.7e+02,-1.6e-05,-5.6e-05,1.6e-07,0,0,-2.7e-06,0.21,0.002,0.44,0,0,0,0,0,0.00021,0.00035,0.00035,0.00023,0.28,0.28,0.36,0.38,0.38,0.16,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7090000,0.7,0.0016,-0.014,0.71,-0.0014,0.011,-0.13,0.0039,0.0083,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-08,0,0,-6.2e-06,0.21,0.002,0.44,0,0,0,0,0,0.0002,0.00036,0.00036,0.00022,0.3,0.3,0.29,0.44,0.44,0.16,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7090000,0.7,0.0016,-0.014,0.71,-0.0014,0.011,-0.13,0.0039,0.0083,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-08,0,0,-6.3e-06,0.21,0.002,0.44,0,0,0,0,0,0.0002,0.00036,0.00036,0.00022,0.3,0.3,0.29,0.44,0.44,0.16,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7190000,0.7,0.0016,-0.014,0.71,-0.0034,0.011,-0.15,0.0037,0.0093,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-07,0,0,-4.1e-06,0.21,0.002,0.44,0,0,0,0,0,0.00018,0.00036,0.00036,0.0002,0.32,0.32,0.24,0.51,0.51,0.15,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7290000,0.7,0.0016,-0.014,0.71,-0.0052,0.011,-0.15,0.0033,0.01,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-1.1e-05,0.21,0.002,0.44,0,0,0,0,0,0.00017,0.00037,0.00037,0.00018,0.34,0.34,0.2,0.58,0.58,0.14,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7390000,0.7,0.0017,-0.014,0.71,-0.0056,0.012,-0.16,0.0027,0.011,-3.7e+02,-1.6e-05,-5.6e-05,-1.3e-07,0,0,-1.2e-05,0.21,0.002,0.44,0,0,0,0,0,0.00016,0.00038,0.00038,0.00017,0.37,0.37,0.18,0.66,0.66,0.13,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
@ -114,8 +114,8 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
11190000,0.7,0.0022,-0.014,0.71,0.0087,0.0081,0.0049,0.0066,-0.0028,-3.7e+02,-1.3e-05,-5.5e-05,-2e-06,-9.6e-06,1.6e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00062,0.00062,9.6e-05,0.1,0.1,0.071,0.063,0.063,0.064,9.4e-09,9.5e-09,3.4e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11290000,0.7,0.0023,-0.014,0.71,0.0082,0.011,0.0045,0.0075,-0.0018,-3.7e+02,-1.3e-05,-5.5e-05,-2.7e-06,-9.6e-06,1.6e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00064,0.00064,9.6e-05,0.13,0.13,0.067,0.071,0.071,0.067,9.4e-09,9.5e-09,3.3e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11390000,0.7,0.0023,-0.014,0.71,0.0037,0.009,-0.00033,0.0054,-0.002,-3.7e+02,-1.4e-05,-5.5e-05,-3.2e-06,-5.4e-06,1.2e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00054,0.00054,9.6e-05,0.1,0.1,0.056,0.058,0.058,0.064,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11490000,0.7,0.0023,-0.014,0.71,0.00095,0.012,0.0004,0.0056,-0.00092,-3.7e+02,-1.4e-05,-5.5e-05,-4.2e-06,-5.5e-06,1.2e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00056,0.00056,9.6e-05,0.13,0.13,0.052,0.066,0.066,0.064,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11590000,0.7,0.0022,-0.014,0.71,-0.0029,0.01,-0.0049,0.0044,-0.0014,-3.7e+02,-1.4e-05,-5.6e-05,-4.4e-06,-1.2e-06,1.1e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00046,0.00046,9.6e-05,0.1,0.1,0.045,0.054,0.054,0.063,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11490000,0.7,0.0023,-0.014,0.71,0.00095,0.012,0.00039,0.0056,-0.00092,-3.7e+02,-1.4e-05,-5.5e-05,-4.2e-06,-5.5e-06,1.2e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00056,0.00056,9.6e-05,0.13,0.13,0.052,0.066,0.066,0.064,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11590000,0.7,0.0022,-0.014,0.71,-0.0029,0.01,-0.005,0.0044,-0.0014,-3.7e+02,-1.4e-05,-5.6e-05,-4.4e-06,-1.2e-06,1.1e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00046,0.00046,9.6e-05,0.1,0.1,0.045,0.054,0.054,0.063,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11690000,0.7,0.0022,-0.014,0.71,-0.006,0.013,-0.0091,0.0039,-0.00027,-3.7e+02,-1.4e-05,-5.6e-05,-4.7e-06,-1.1e-06,1.1e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00047,0.00047,9.6e-05,0.12,0.12,0.042,0.063,0.063,0.063,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,9.9e-07,0,0,0,0,0,0,0,0
11790000,0.7,0.0022,-0.014,0.71,-0.011,0.013,-0.011,0.0017,0.00056,-3.7e+02,-1.4e-05,-5.6e-05,-4.8e-06,-1.6e-08,9.8e-06,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00039,0.00039,9.6e-05,0.096,0.096,0.037,0.052,0.052,0.061,6.6e-09,6.6e-09,3e-09,3.7e-06,3.7e-06,9.9e-07,0,0,0,0,0,0,0,0
11890000,0.7,0.0022,-0.014,0.71,-0.013,0.014,-0.012,0.00052,0.0019,-3.7e+02,-1.4e-05,-5.6e-05,-5.3e-06,-9.2e-08,9.9e-06,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.0004,0.0004,9.6e-05,0.12,0.12,0.035,0.061,0.061,0.061,6.6e-09,6.6e-09,2.9e-09,3.7e-06,3.7e-06,9.9e-07,0,0,0,0,0,0,0,0
@ -153,7 +153,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
15090000,0.7,0.00023,-0.013,0.71,0.0038,-0.0021,-0.031,0.0035,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.1e-06,-1.1e-05,2.4e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.047,0.047,0.03,0.054,0.054,0.052,2.4e-09,2.4e-09,1.4e-09,3.5e-06,3.5e-06,4.4e-07,0,0,0,0,0,0,0,0
15190000,0.7,0.00024,-0.013,0.71,0.0032,-0.00083,-0.029,0.0028,-0.0024,-3.7e+02,-1.2e-05,-6.1e-05,1e-06,-1.1e-05,2.5e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.041,0.041,0.029,0.047,0.047,0.051,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.1e-07,0,0,0,0,0,0,0,0
15290000,0.7,0.0002,-0.013,0.71,0.0038,-0.00068,-0.026,0.0031,-0.0025,-3.7e+02,-1.2e-05,-6.1e-05,1.4e-06,-1.2e-05,2.6e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9e-05,0.046,0.046,0.029,0.054,0.054,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4e-07,0,0,0,0,0,0,0,0
15390000,0.7,0.00021,-0.013,0.71,0.003,-0.00032,-0.024,0.00054,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,2e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00018,0.00018,9e-05,0.04,0.04,0.028,0.047,0.047,0.051,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.7e-07,0,0,0,0,0,0,0,0
15390000,0.7,0.00021,-0.013,0.71,0.003,-0.00033,-0.024,0.00054,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,2e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00018,0.00018,9e-05,0.04,0.04,0.028,0.047,0.047,0.051,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.7e-07,0,0,0,0,0,0,0,0
15490000,0.7,0.00023,-0.013,0.71,0.0043,-0.00071,-0.024,0.00091,-0.0021,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.2e-05,2.8e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9e-05,0.045,0.045,0.028,0.053,0.053,0.052,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.6e-07,0,0,0,0,0,0,0,0
15590000,0.7,0.00024,-0.013,0.71,0.0024,-0.0007,-0.023,-0.0013,-0.0017,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.2e-05,3e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,9e-05,0.039,0.039,0.027,0.046,0.046,0.051,1.9e-09,1.9e-09,1.3e-09,3.5e-06,3.5e-06,3.3e-07,0,0,0,0,0,0,0,0
15690000,0.7,0.00025,-0.013,0.71,0.0027,-0.00088,-0.023,-0.0011,-0.0018,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.3e-05,3e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00018,8.9e-05,0.044,0.044,0.027,0.053,0.053,0.052,1.9e-09,1.9e-09,1.2e-09,3.5e-06,3.5e-06,3.2e-07,0,0,0,0,0,0,0,0
@ -174,30 +174,30 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
17190000,0.71,0.00045,-0.013,0.71,-0.00031,0.0013,-0.011,-0.0057,-0.00054,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.6e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.5e-10,9.6e-10,8.9e-10,3.2e-06,3.2e-06,1.4e-07,0,0,0,0,0,0,0,0
17290000,0.71,0.00043,-0.013,0.71,0.0018,0.0023,-0.0067,-0.0056,-0.00038,-3.7e+02,-1.4e-05,-6e-05,3e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.5e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.5e-10,9.6e-10,8.7e-10,3.2e-06,3.2e-06,1.4e-07,0,0,0,0,0,0,0,0
17390000,0.71,0.0004,-0.013,0.71,0.0024,0.0015,-0.0048,-0.0047,-0.0016,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00014,8.5e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.7e-10,8.7e-10,8.5e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
17490000,0.71,0.00039,-0.013,0.71,0.003,0.001,-0.003,-0.0044,-0.0015,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00015,0.00015,8.5e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.7e-10,8.7e-10,8.3e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
17490000,0.71,0.00039,-0.013,0.71,0.003,0.001,-0.0031,-0.0044,-0.0015,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00015,0.00015,8.5e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.7e-10,8.7e-10,8.3e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
17590000,0.71,0.0003,-0.013,0.71,0.0042,-0.00014,0.0024,-0.0037,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.4e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.5e-05,0.034,0.034,0.017,0.046,0.046,0.048,7.9e-10,7.9e-10,8.1e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
17690000,0.71,0.00027,-0.012,0.71,0.0051,0.00056,0.0018,-0.0032,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.6e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.038,0.038,0.017,0.052,0.052,0.048,7.9e-10,7.9e-10,7.9e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
17790000,0.71,0.00018,-0.013,0.71,0.0077,0.00029,0.00051,-0.0021,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.033,0.033,0.016,0.045,0.045,0.048,7.1e-10,7.1e-10,7.8e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
17890000,0.71,0.00019,-0.013,0.71,0.0092,-0.00047,0.00061,-0.0012,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.4e-05,0.037,0.037,0.016,0.052,0.052,0.048,7.1e-10,7.1e-10,7.6e-10,3.2e-06,3.2e-06,1e-07,0,0,0,0,0,0,0,0
17790000,0.71,0.00018,-0.013,0.71,0.0077,0.00029,0.00048,-0.0021,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.033,0.033,0.016,0.045,0.045,0.048,7.1e-10,7.1e-10,7.8e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
17890000,0.71,0.00019,-0.013,0.71,0.0092,-0.00047,0.00058,-0.0012,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.4e-05,0.037,0.037,0.016,0.052,0.052,0.048,7.1e-10,7.1e-10,7.6e-10,3.2e-06,3.2e-06,1e-07,0,0,0,0,0,0,0,0
17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0022,0.0018,-0.00053,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.4e-05,0.032,0.032,0.015,0.045,0.045,0.047,6.4e-10,6.4e-10,7.5e-10,3.1e-06,3.1e-06,9.8e-08,0,0,0,0,0,0,0,0
18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0024,0.0042,0.00061,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.3e-05,0.036,0.036,0.015,0.051,0.051,0.047,6.4e-10,6.4e-10,7.3e-10,3.1e-06,3.1e-06,9.5e-08,0,0,0,0,0,0,0,0
18190000,0.71,0.00011,-0.013,0.71,0.012,-0.0013,0.0055,0.0015,-0.0017,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.3e-05,0.032,0.032,0.015,0.045,0.045,0.046,5.8e-10,5.8e-10,7.2e-10,3.1e-06,3.1e-06,9e-08,0,0,0,0,0,0,0,0
18290000,0.71,4.8e-05,-0.012,0.71,0.012,-0.0019,0.0067,0.0027,-0.0018,-3.7e+02,-1.3e-05,-6.1e-05,4.1e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,7e-10,3.1e-06,3.1e-06,8.7e-08,0,0,0,0,0,0,0,0
18390000,0.71,6.4e-05,-0.013,0.71,0.014,-0.0002,0.0079,0.0032,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.031,0.031,0.014,0.045,0.045,0.045,5.3e-10,5.3e-10,6.9e-10,3.1e-06,3.1e-06,8.3e-08,0,0,0,0,0,0,0,0
18390000,0.71,6.4e-05,-0.013,0.71,0.014,-0.0002,0.0078,0.0032,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.031,0.031,0.014,0.045,0.045,0.045,5.3e-10,5.3e-10,6.9e-10,3.1e-06,3.1e-06,8.3e-08,0,0,0,0,0,0,0,0
18490000,0.71,7.9e-05,-0.012,0.71,0.014,0.00021,0.0075,0.0047,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.5e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.2e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.3e-10,5.3e-10,6.7e-10,3.1e-06,3.1e-06,8e-08,0,0,0,0,0,0,0,0
18590000,0.71,8.4e-05,-0.012,0.71,0.013,0.00045,0.0057,0.0035,-0.0012,-3.7e+02,-1.4e-05,-6.1e-05,4.9e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.8e-10,4.8e-10,6.6e-10,3.1e-06,3.1e-06,7.6e-08,0,0,0,0,0,0,0,0
18590000,0.71,8.4e-05,-0.012,0.71,0.013,0.00045,0.0056,0.0035,-0.0012,-3.7e+02,-1.4e-05,-6.1e-05,4.9e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.8e-10,4.8e-10,6.6e-10,3.1e-06,3.1e-06,7.6e-08,0,0,0,0,0,0,0,0
18690000,0.71,5.3e-05,-0.012,0.71,0.014,-0.00024,0.0038,0.0049,-0.0011,-3.7e+02,-1.4e-05,-6.1e-05,4.8e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00013,0.00012,8.2e-05,0.034,0.034,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,6.5e-10,3.1e-06,3.1e-06,7.4e-08,0,0,0,0,0,0,0,0
18790000,0.71,8.4e-05,-0.012,0.71,0.012,6.5e-05,0.0035,0.0038,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,4.6e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.4e-10,4.4e-10,6.3e-10,3.1e-06,3.1e-06,7.1e-08,0,0,0,0,0,0,0,0
18890000,0.71,0.00011,-0.012,0.71,0.013,0.00056,0.0041,0.005,-0.00085,-3.7e+02,-1.4e-05,-6.1e-05,5e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.4e-10,4.4e-10,6.2e-10,3.1e-06,3.1e-06,6.9e-08,0,0,0,0,0,0,0,0
18990000,0.71,9.4e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.0007,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.029,0.029,0.012,0.045,0.045,0.044,4e-10,4e-10,6.1e-10,3e-06,3e-06,6.6e-08,0,0,0,0,0,0,0,0
19090000,0.71,7.8e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0078,-0.0005,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.032,0.032,0.012,0.051,0.051,0.044,4e-10,4e-10,6e-10,3e-06,3e-06,6.4e-08,0,0,0,0,0,0,0,0
18790000,0.71,8.4e-05,-0.012,0.71,0.012,6.5e-05,0.0034,0.0038,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,4.6e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.4e-10,4.4e-10,6.3e-10,3.1e-06,3.1e-06,7.1e-08,0,0,0,0,0,0,0,0
18890000,0.71,0.00011,-0.012,0.71,0.013,0.00056,0.004,0.005,-0.00085,-3.7e+02,-1.4e-05,-6.1e-05,5e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.4e-10,4.4e-10,6.2e-10,3.1e-06,3.1e-06,6.9e-08,0,0,0,0,0,0,0,0
18990000,0.71,9.4e-05,-0.012,0.71,0.014,0.0015,0.0027,0.0063,-0.0007,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.029,0.029,0.012,0.045,0.045,0.044,4e-10,4e-10,6.1e-10,3e-06,3e-06,6.6e-08,0,0,0,0,0,0,0,0
19090000,0.71,7.8e-05,-0.012,0.71,0.015,0.0021,0.0057,0.0078,-0.0005,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.032,0.032,0.012,0.051,0.051,0.044,4e-10,4e-10,6e-10,3e-06,3e-06,6.4e-08,0,0,0,0,0,0,0,0
19190000,0.71,8.1e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0086,-0.00045,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00011,8.1e-05,0.028,0.028,0.012,0.045,0.045,0.043,3.6e-10,3.6e-10,5.9e-10,3e-06,3e-06,6.1e-08,0,0,0,0,0,0,0,0
19290000,0.71,0.0001,-0.012,0.71,0.015,0.0013,0.0085,0.01,-0.00027,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00012,8e-05,0.031,0.031,0.012,0.05,0.05,0.043,3.6e-10,3.6e-10,5.7e-10,3e-06,3e-06,5.9e-08,0,0,0,0,0,0,0,0
19390000,0.71,0.00012,-0.012,0.71,0.013,0.00039,0.012,0.008,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.028,0.028,0.011,0.045,0.045,0.043,3.3e-10,3.3e-10,5.6e-10,3e-06,3e-06,5.7e-08,0,0,0,0,0,0,0,0
19490000,0.71,0.00014,-0.012,0.71,0.012,-0.00032,0.0087,0.0092,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.6e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,5.5e-10,3e-06,3e-06,5.5e-08,0,0,0,0,0,0,0,0
19590000,0.71,0.00019,-0.012,0.71,0.0097,-0.0013,0.008,0.0075,-0.0003,-3.7e+02,-1.4e-05,-6.1e-05,5.9e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,5.4e-10,3e-06,3e-06,5.3e-08,0,0,0,0,0,0,0,0
19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0035,0.0095,0.0085,-0.00055,-3.7e+02,-1.4e-05,-6.1e-05,5.7e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,5.3e-10,3e-06,3e-06,5.2e-08,0,0,0,0,0,0,0,0
19790000,0.71,0.00026,-0.012,0.71,0.0078,-0.0044,0.01,0.0068,-0.00044,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19790000,0.71,0.00026,-0.012,0.71,0.0078,-0.0044,0.0099,0.0068,-0.00044,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19890000,0.71,0.0002,-0.012,0.71,0.0065,-0.0047,0.011,0.0076,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,6.2e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,5.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19990000,0.71,0.00019,-0.012,0.71,0.0041,-0.0053,0.014,0.0062,-0.00076,-3.7e+02,-1.4e-05,-6.1e-05,6.7e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20090000,0.71,0.00018,-0.012,0.71,0.0039,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-1.4e-05,-6.1e-05,7.1e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.028,0.028,0.01,0.05,0.05,0.042,2.5e-10,2.5e-10,4.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
@ -209,7 +209,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
20690000,0.71,0.00037,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.3e-05,7.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.026,0.026,0.0093,0.049,0.049,0.04,2e-10,2e-10,4.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20790000,0.71,0.0004,-0.012,0.71,-0.0033,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.7e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20890000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.014,0.001,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,0.0001,0.0001,7.7e-05,0.025,0.025,0.009,0.049,0.049,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.015,0.0027,-0.0031,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-8.6e-06,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.7e-05,0.023,0.023,0.0088,0.043,0.043,0.039,1.7e-10,1.7e-10,4.2e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.014,0.0027,-0.0031,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-8.6e-06,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.7e-05,0.023,0.023,0.0088,0.043,0.043,0.039,1.7e-10,1.7e-10,4.2e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21090000,0.71,0.00039,-0.012,0.71,-0.0041,-0.017,0.015,0.0023,-0.0046,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-8.7e-06,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.9e-05,9.9e-05,7.7e-05,0.025,0.025,0.0088,0.048,0.048,0.039,1.7e-10,1.7e-10,4.1e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21190000,0.71,0.00042,-0.012,0.71,-0.0033,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.6e-06,-6.3e-06,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.7e-05,9.7e-05,7.7e-05,0.022,0.022,0.0086,0.043,0.043,0.039,1.5e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21290000,0.71,0.00046,-0.012,0.71,-0.0039,-0.018,0.016,0.0034,-0.0054,-3.7e+02,-1.4e-05,-6e-05,7.9e-06,-6.2e-06,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.6e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
@ -320,9 +320,9 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
31790000,0.71,0.0011,0.0011,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00028,-5.4e-05,-0.00098,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31890000,0.71,0.00087,0.00037,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00029,-4.1e-05,-0.00098,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31990000,0.71,0.00074,-8.3e-05,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.0003,-2.2e-05,-0.00097,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.71,0.00045,-0.0008,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.0003,-6.7e-06,-0.00096,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.71,0.00045,-0.0008,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.0003,-6.8e-06,-0.00096,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32190000,0.71,0.00024,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00031,1.4e-05,-0.00096,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-11,2.9e-11,9.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.71,6.7e-06,-0.0023,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00032,3e-05,-0.00095,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.3,0.3,0.037,3e-11,2.9e-11,9.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.71,6.6e-06,-0.0023,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00032,3e-05,-0.00095,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.3,0.3,0.037,3e-11,2.9e-11,9.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32390000,0.71,-0.00018,-0.0029,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00032,3.9e-05,-0.00095,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-11,2.9e-11,9.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32490000,0.71,-0.0003,-0.0032,0.71,-1.4,-0.82,0.72,-14,-6.6,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00033,5e-05,-0.00094,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-11,2.9e-11,9.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32590000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,5.8e-05,-0.00094,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0084,0.31,0.31,0.036,2.9e-11,2.9e-11,9.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
@ -343,7 +343,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
34090000,-0.5,-0.0021,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.1e-05,6.9e-05,7.8e-05,6.9e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34190000,-0.57,-0.0014,-0.011,0.82,-0.92,-0.54,0.74,-16,-7.8,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.4e-05,6.5e-05,7.3e-05,6.7e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34290000,-0.61,-0.0023,-0.0086,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,6.5e-05,7.3e-05,6.5e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34390000,-0.64,-0.0025,-0.0061,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00044,0.00019,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,6e-05,6.7e-05,6.4e-05,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34390000,-0.64,-0.0025,-0.0061,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00043,0.00019,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,6e-05,6.7e-05,6.4e-05,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00043,0.00019,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,6.1e-05,6.7e-05,6.3e-05,0.049,0.05,0.0064,0.4,0.4,0.035,2.7e-11,2.7e-11,8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-11,2.7e-11,8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.37,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,7.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
@ -359,7 +359,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
35690000,-0.68,-0.0057,-0.0045,0.73,0.43,0.38,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6e-05,0.073,0.075,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35790000,-0.68,-0.0034,-0.0044,0.73,0.35,0.32,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3e-06,-0.00079,0.00053,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.061,0.062,0.0059,0.49,0.48,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35890000,-0.68,-0.0034,-0.0045,0.73,0.37,0.35,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3.1e-06,-0.00079,0.00053,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.066,0.068,0.0059,0.5,0.5,0.033,2.7e-11,2.7e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35990000,-0.68,-0.0016,-0.0044,0.73,0.3,0.29,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.3e-06,-0.00087,0.0006,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.8e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35990000,-0.68,-0.0016,-0.0044,0.73,0.3,0.29,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.3e-06,-0.00087,0.00059,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.8e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36090000,-0.68,-0.0016,-0.0044,0.73,0.31,0.31,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00087,0.0006,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,7.1e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36190000,-0.68,-0.00015,-0.0043,0.73,0.26,0.27,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00097,0.00068,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,7.1e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36290000,-0.68,-0.00021,-0.0042,0.73,0.27,0.28,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.7e-06,-0.00097,0.00068,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.06,0.062,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0

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.011 -0.00011 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0
3 90000 1 -0.011 -0.01 -0.022 -0.0011 0.00084 -0.011 -5.7e-05 2.6e-05 -0.00039 0 0 0 0 0 0 0.19 9.3e-10 0.4 0 0 0 0 0 1.5e-06 0.0025 0.0025 0.0021 0.26 0.26 0.56 0.25 0.25 4 1e-06 1e-06 1e-06 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
4 190000 1 -0.011 -0.01 -0.022 -0.0012 1.8e-05 -0.025 -0.00014 5.9e-05 -0.0022 0 0 0 0 0 0 0.19 9.3e-10 0.4 0 0 0 0 0 1.1e-06 0.0026 0.0026 0.0012 0.28 0.28 0.56 0.26 0.26 1 1.3 1e-06 1e-06 9.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
5 290000 1 -0.011 -0.011 -0.022 0.00047 0.00042 -0.039 1.7e-05 -4.6e-06 -0.0054 0 0 0 0 0 0 0.19 9.3e-10 0.4 0 0 0 0 0 1e-06 0.0027 0.0027 0.00084 25 25 0.56 1e+02 1e+02 0.37 0.4 1e-06 1e-06 9.8e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
6 390000 1 -0.011 -0.011 -0.022 0.0012 0.00016 -0.054 0.0001 4.7e-05 -0.01 0 0 0 0 0 0 0.19 9.3e-10 0.4 0 0 0 0 0 9.8e-07 0.0028 0.0028 0.00069 25 25 0.56 1e+02 1e+02 0.22 0.23 1e-06 1e-06 9.5e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
7 490000 1 -0.011 -0.011 -0.022 0.003 -0.00086 -0.069 0.00017 -4.7e-05 -0.016 2.6e-12 -7.7e-12 -8.9e-14 0 0 -1.8e-13 0.19 9.3e-10 0.4 0 0 0 0 0 1e-06 0.0031 0.0031 0.00062 25 25 0.55 0.37 0.37 0.16 0.17 1e-06 1e-06 9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
8 590000 1 -0.011 -0.012 -0.022 0.0044 -0.00055 -0.083 0.00055 -0.00012 -0.024 2.6e-12 -7.7e-12 -8.9e-14 0 0 -1.8e-13 0.19 9.3e-10 0.4 0 0 0 0 0 1.1e-06 0.0033 0.0033 0.0006 25 25 0.53 0.54 0.97 0.97 0.14 0.15 1e-06 1e-06 8.4e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
9 690000 1 -0.011 -0.012 -0.022 0.004 -0.0013 -0.098 0.0003 -0.0001 -0.033 -1.7e-09 -1e-08 1.2e-10 0 0 -3.1e-10 0.19 9.3e-10 0.4 0 0 0 0 0 1.2e-06 0.0036 0.0036 0.00059 7.8 7.8 0.51 0.34 0.34 0.13 1e-06 1e-06 7.7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
10 790000 1 -0.011 -0.012 -0.022 0.0056 -0.0014 -0.11 0.00076 -0.00025 -0.043 -1.7e-09 -1e-08 1.2e-10 0 0 -3.1e-10 0.19 9.3e-10 0.4 0 0 0 0 0 1.3e-06 0.004 0.004 0.00059 7.9 7.9 0.48 0.67 0.67 0.13 1e-06 1e-06 6.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
11 890000 1 -0.011 -0.012 -0.022 0.007 -0.002 -0.13 0.00054 -0.00018 -0.055 -1.2e-08 -4.5e-08 6.3e-10 0 0 -1.1e-09 0.19 9.3e-10 0.4 0 0 0 0 0 1.4e-06 0.0044 0.0044 0.00059 2.7 2.7 0.48 0.49 0.26 0.26 0.17 1e-06 1e-06 6.1e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
12 990000 1 -0.011 -0.013 -0.022 0.011 -0.0039 -0.14 0.0014 -0.00046 -0.069 -1.2e-08 -4.5e-08 6.3e-10 0 0 -1.1e-09 0.19 9.3e-10 0.4 0 0 0 0 0 1.6e-06 0.0048 0.0048 0.00058 2.8 2.8 0.49 0.42 0.42 0.21 1e-06 1e-06 5.3e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
13 1090000 1 -0.011 -0.013 -0.022 0.011 -0.0046 -0.16 0.0011 -0.0004 -0.084 -6e-08 -2.1e-07 2.9e-09 0 0 -4.1e-09 0.19 9.3e-10 0.4 0 0 0 0 0 1.8e-06 0.0052 0.0052 0.00058 1.3 1.3 0.5 0.2 0.2 0.27 9.9e-07 9.9e-07 4.6e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
14 1190000 1 -0.011 -0.013 -0.022 0.015 -0.0066 -0.17 0.0024 -0.00096 -0.1 -6e-08 -2.1e-07 2.9e-09 0 0 -4.1e-09 0.19 9.3e-10 0.4 0 0 0 0 0 2e-06 0.0058 0.0058 0.00057 1.5 1.5 0.5 0.51 0.3 0.3 0.33 9.9e-07 9.9e-07 4e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
15 1290000 1 -0.011 -0.014 -0.022 0.016 -0.0065 -0.18 0.0018 -0.00078 -0.12 -2.6e-07 -7.6e-07 1.1e-08 0 0 -1.3e-08 0.19 9.3e-10 0.4 0 0 0 0 0 2.1e-06 0.0062 0.0062 0.00056 0.95 0.95 0.51 0.52 0.17 0.17 0.41 9.8e-07 9.8e-07 3.4e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
16 1390000 1 -0.012 -0.014 -0.022 0.021 -0.0088 -0.2 0.0037 -0.0015 -0.14 -2.6e-07 -7.6e-07 1.1e-08 0 0 -1.3e-08 0.19 9.3e-10 0.4 0 0 0 0 0 2.4e-06 0.0068 0.0068 0.00055 1.2 1.2 0.52 0.53 0.24 0.24 0.49 9.8e-07 9.8e-07 3e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
17 1490000 1 -0.012 -0.014 -0.022 0.021 -0.0083 -0.21 0.0029 -0.0012 -0.16 -7.8e-07 -2.2e-06 3.1e-08 0 0 -3.4e-08 0.19 9.3e-10 0.4 0 0 0 0 0 2.5e-06 0.0069 0.0069 0.00053 0.92 0.92 0.53 0.54 0.15 0.15 0.59 9.4e-07 9.4e-07 2.6e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
18 1590000 1 -0.012 -0.014 -0.022 0.027 -0.0096 -0.23 0.0053 -0.002 -0.18 -7.8e-07 -2.2e-06 3.1e-08 0 0 -3.4e-08 0.19 9.3e-10 0.4 0 0 0 0 0 2.7e-06 0.0076 0.0076 0.00051 1.2 1.2 0.55 0.21 0.21 0.7 9.4e-07 9.4e-07 2.2e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
19 1690000 1 -0.012 -0.014 -0.022 0.027 -0.01 -0.24 0.0039 -0.0015 -0.2 -1.8e-06 -5.3e-06 6.9e-08 0 0 -7e-08 0.19 9.3e-10 0.4 0 0 0 0 0 2.6e-06 0.0071 0.0071 0.0005 1 1 0.56 0.14 0.14 0.82 8.7e-07 8.7e-07 1.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
20 1790000 1 -0.012 -0.014 -0.022 0.034 -0.014 -0.25 0.0069 -0.0027 -0.23 -1.8e-06 -5.3e-06 6.9e-08 0 0 -7e-08 0.19 9.3e-10 0.4 0 0 0 0 0 2.9e-06 0.0078 0.0078 0.00048 1.3 1.3 0.57 0.58 0.21 0.21 0.95 8.7e-07 8.7e-07 1.7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
21 1890000 1 -0.011 -0.014 -0.022 0.031 -0.012 -0.27 0.0048 -0.0019 -0.25 -3.5e-06 -1e-05 1.3e-07 0 0 -1.2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 2.5e-06 0.0066 0.0066 0.00046 1.1 1.1 0.59 0.14 0.14 1.1 7.6e-07 7.6e-07 1.5e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
22 1990000 1 -0.011 -0.014 -0.022 0.037 -0.014 -0.28 0.0082 -0.0032 -0.28 -3.5e-06 -1e-05 1.3e-07 0 0 -1.2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 2.8e-06 0.0072 0.0072 0.00045 1.4 1.4 0.6 0.61 0.21 0.21 1.3 7.6e-07 7.6e-07 1.3e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
23 2090000 1 -0.011 -0.014 -0.022 0.044 -0.017 -0.29 0.012 -0.0048 -0.31 -3.5e-06 -1e-05 1.3e-07 0 0 -1.2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 3e-06 0.0079 0.0079 0.00043 1.8 1.8 0.62 0.31 0.31 1.4 7.6e-07 7.6e-07 1.1e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
24 2190000 1 -0.011 -0.014 -0.022 0.035 -0.013 -0.31 0.0084 -0.0033 -0.34 -5.5e-06 -1.6e-05 1.9e-07 0 0 -1.8e-07 0.19 9.3e-10 0.4 0 0 0 0 0 2.4e-06 0.0061 0.0061 0.00042 1.3 1.3 0.63 0.64 0.21 0.21 1.6 6.3e-07 6.3e-07 9.9e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
25 2290000 1 -0.011 -0.014 -0.022 0.042 -0.016 -0.32 0.012 -0.0047 -0.37 -5.5e-06 -1.6e-05 1.9e-07 0 0 -1.8e-07 0.19 9.3e-10 0.4 0 0 0 0 0 2.7e-06 0.0067 0.0067 0.0004 1.7 1.7 0.65 0.66 0.31 0.31 1.8 6.3e-07 6.3e-07 8.8e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
26 2390000 1 -0.011 -0.013 -0.022 0.032 -0.011 -0.34 0.008 -0.003 -0.4 -7.4e-06 -2.2e-05 2.5e-07 0 0 -2.2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 2e-06 0.0049 0.0049 0.00039 1.2 1.2 0.67 0.2 0.2 2 5.2e-07 5.2e-07 7.9e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
27 2490000 1 -0.011 -0.013 -0.022 0.037 -0.013 -0.35 0.011 -0.0042 -0.44 -7.4e-06 -2.2e-05 2.5e-07 0 0 -2.2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 2.2e-06 0.0054 0.0054 0.00038 1.5 1.5 0.69 0.3 0.3 2.3 5.2e-07 5.2e-07 7e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
28 2590000 1 -0.011 -0.013 -0.022 0.028 -0.0089 -0.36 0.0072 -0.0026 -0.47 -9e-06 -2.7e-05 3e-07 0 0 -2.5e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.6e-06 0.0039 0.0039 0.00036 1 1 0.71 0.19 0.19 2.5 4.3e-07 4.3e-07 6.3e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
29 2690000 1 -0.011 -0.013 -0.022 0.032 -0.0099 -0.38 0.01 -0.0036 -0.51 -9e-06 -2.7e-05 3e-07 0 0 -2.5e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.8e-06 0.0043 0.0043 0.00035 1.3 1.3 0.73 0.28 0.28 2.8 4.3e-07 4.3e-07 5.7e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
30 2790000 1 -0.011 -0.013 -0.022 0.024 -0.0071 -0.39 0.0064 -0.0021 -0.55 -1e-05 -3.1e-05 3.3e-07 0 0 -2.6e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.3e-06 0.0031 0.0031 0.00034 0.88 0.88 0.75 0.18 0.18 3 3.1 3.5e-07 3.5e-07 5.1e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
31 2890000 1 -0.011 -0.013 -0.022 0.028 -0.0081 -0.4 0.009 -0.0029 -0.59 -1e-05 -3.1e-05 3.3e-07 0 0 -2.6e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.4e-06 0.0034 0.0034 0.00033 1.1 1.1 0.77 0.25 0.25 3.3 3.4 3.5e-07 3.5e-07 4.6e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
32 2990000 1 -0.011 -0.013 -0.022 0.022 -0.0057 -0.41 0.0058 -0.0018 -0.63 -1.1e-05 -3.5e-05 3.5e-07 0 0 -2.5e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.1e-06 0.0026 0.0026 0.00032 0.76 0.76 0.79 0.8 0.16 0.16 3.7 3e-07 3e-07 4.2e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
33 3090000 1 -0.011 -0.013 -0.022 0.025 -0.0062 -0.43 0.0081 -0.0024 -0.67 -1.1e-05 -3.5e-05 3.5e-07 0 0 -2.5e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.2e-06 0.0028 0.0028 0.00031 0.93 0.93 0.82 0.23 0.23 4 3e-07 3e-07 3.8e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
34 3190000 1 -0.011 -0.012 -0.022 0.02 -0.0038 -0.44 0.0052 -0.0014 -0.72 -1.2e-05 -3.7e-05 3.6e-07 0 0 -2.4e-07 0.19 9.3e-10 0.4 0 0 0 0 0 9.2e-07 0.0022 0.0022 0.0003 0.66 0.66 0.84 0.85 0.15 0.15 4.3 4.4 2.5e-07 2.5e-07 3.5e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
35 3290000 1 -0.011 -0.012 -0.022 0.023 -0.0047 -0.45 0.0074 -0.0019 -0.76 -1.2e-05 -3.7e-05 3.6e-07 0 0 -2.4e-07 0.19 9.3e-10 0.4 0 0 0 0 0 9.9e-07 0.0024 0.0024 0.00029 0.81 0.81 0.86 0.87 0.22 0.22 4.7 2.5e-07 2.5e-07 3.2e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
36 3390000 1 -0.011 -0.012 -0.022 0.018 -0.0036 -0.47 0.0049 -0.0012 -0.81 -1.2e-05 -4e-05 3.7e-07 0 0 -2.2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 7.9e-07 0.0019 0.0019 0.00029 0.58 0.58 0.89 0.9 0.14 0.14 5.1 2.2e-07 2.2e-07 2.9e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
37 3490000 1 -0.011 -0.012 -0.022 0.022 -0.0052 -0.48 0.0069 -0.0016 -0.85 -1.2e-05 -4e-05 3.7e-07 0 0 -2.2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 8.5e-07 0.0021 0.0021 0.00028 0.71 0.71 0.92 0.2 0.2 5.5 5.6 2.2e-07 2.2e-07 2.7e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
38 3590000 1 -0.011 -0.012 -0.022 0.017 -0.0051 -0.49 0.0046 -0.0011 -0.9 -1.3e-05 -4.2e-05 3.7e-07 0 0 -2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 6.8e-07 0.0017 0.0017 0.00027 0.52 0.52 0.94 0.95 0.14 0.14 6 1.8e-07 1.8e-07 2.5e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
39 3690000 1 -0.011 -0.012 -0.022 0.02 -0.007 -0.51 0.0065 -0.0017 -0.95 -1.3e-05 -4.2e-05 3.7e-07 0 0 -2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 7.3e-07 0.0018 0.0018 0.00026 0.64 0.64 0.97 0.98 0.19 0.19 6.4 6.5 1.8e-07 1.8e-07 2.3e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
40 3790000 1 -0.011 -0.012 -0.022 0.016 -0.0074 -0.52 0.0044 -0.0013 -1 -1.3e-05 -4.4e-05 3.8e-07 0 0 -1.7e-07 0.19 9.3e-10 0.4 0 0 0 0 0 6e-07 0.0015 0.0015 0.00026 0.47 0.47 1 0.13 0.13 6.9 7 1.6e-07 1.6e-07 2.1e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
41 3890000 1 -0.011 -0.012 -0.022 0.017 -0.0074 -0.53 0.006 -0.002 -1.1 -1.3e-05 -4.4e-05 3.8e-07 0 0 -1.7e-07 0.19 9.3e-10 0.4 0 0 0 0 0 6.4e-07 0.0016 0.0016 0.00025 0.58 0.58 1 0.17 0.17 7.4 7.5 1.6e-07 1.6e-07 2e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
42 3990000 1 -0.01 -0.012 -0.022 0.015 -0.006 -0.55 0.0041 -0.0015 -1.1 -1.4e-05 -4.6e-05 3.9e-07 0 0 -1.3e-07 0.19 9.3e-10 0.4 0 0 0 0 0 5.2e-07 0.0013 0.0013 0.00024 0.44 0.44 1.1 0.12 0.12 8 1.3e-07 1.3e-07 1.8e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
43 4090000 1 -0.01 -0.012 -0.022 0.018 -0.0074 -0.56 0.0057 -0.0021 -1.2 -1.4e-05 -4.6e-05 3.9e-07 0 0 -1.3e-07 0.19 9.3e-10 0.4 0 0 0 0 0 5.5e-07 0.0015 0.0015 0.00024 0.53 0.53 1.1 0.16 0.16 8.5 8.6 1.3e-07 1.3e-07 1.7e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
44 4190000 1 -0.01 -0.012 -0.022 0.021 -0.0088 -0.58 0.0077 -0.0029 -1.2 -1.4e-05 -4.6e-05 3.9e-07 0 0 -1.3e-07 0.19 9.3e-10 0.4 0 0 0 0 0 5.9e-07 0.0016 0.0016 0.00023 0.64 0.64 1.1 0.22 0.22 9.1 9.2 1.3e-07 1.3e-07 1.6e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
45 4290000 1 -0.01 -0.012 -0.022 0.018 -0.0055 -0.59 0.0056 -0.0021 -1.3 -1.4e-05 -4.7e-05 4e-07 0 0 -9.2e-08 0.19 9.3e-10 0.4 0 0 0 0 0 4.8e-07 0.0013 0.0013 0.00023 0.49 0.49 1.2 0.16 0.16 9.8 1.1e-07 1.1e-07 1.5e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
46 4390000 1 -0.01 -0.012 -0.022 0.019 -0.0054 -0.6 0.0074 -0.0027 -1.3 -1.4e-05 -4.7e-05 4e-07 0 0 -9.2e-08 0.19 9.3e-10 0.4 0 0 0 0 0 5.1e-07 0.0014 0.0014 0.00022 0.59 0.59 1.2 0.21 0.21 10 1.1e-07 1.1e-07 1.4e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
47 4490000 1 -0.01 -0.012 -0.022 0.016 -0.0037 -0.62 0.0053 -0.0017 -1.4 -1.5e-05 -4.9e-05 4.1e-07 0 0 -5.3e-08 0.19 9.3e-10 0.4 0 0 0 0 0 4.2e-07 0.0012 0.0012 0.00022 0.45 0.45 1.2 0.15 0.15 11 9.3e-08 9.3e-08 1.3e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
58 5590000 1 -0.0098 -0.011 -0.022 0.008 -0.0022 -0.78 0.0043 -0.0013 -2.2 -1.6e-05 -5.5e-05 4.3e-07 0 0 1.2e-07 0.19 9.3e-10 0.4 0 0 0 0 0 2.3e-07 0.00064 0.00064 0.00018 0.36 0.36 1.7 0.15 0.15 21 3.4e-08 3.4e-08 6.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
59 5690000 1 -0.0097 -0.011 -0.022 0.0057 -0.00028 -0.79 0.0029 -0.00083 -2.2 -1.6e-05 -5.5e-05 4.3e-07 0 0 1.4e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.9e-07 0.00051 0.00051 0.00017 0.28 0.28 1.7 0.11 0.11 22 2.7e-08 2.7e-08 6.4e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
60 5790000 1 -0.0096 -0.011 -0.022 0.0063 0.0011 -0.8 0.0035 -0.00079 -2.3 -1.6e-05 -5.5e-05 4.3e-07 0 0 1.4e-07 0.19 9.3e-10 0.4 0 0 0 0 0 2e-07 0.00055 0.00055 0.00017 0.32 0.32 1.8 0.15 0.15 23 2.7e-08 2.7e-08 6.1e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
61 5890000 1 -0.0095 -0.011 -0.022 0.0054 0.0022 0.0029 0.0028 0.0024 -0.00038 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 0 0 1.3e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.7e-07 0.00044 0.00044 0.00017 0.25 0.25 9.8 0.11 0.11 0.52 2.2e-08 2.2e-08 5.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
62 5990000 1 -0.0095 -0.011 -0.022 0.0059 0.004 0.015 0.003 -2.2e-05 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 0 0 4e-08 4.1e-08 0.19 9.3e-10 0.4 0 0 0 0 0 1.8e-07 0.00047 0.00047 0.00017 0.29 0.29 8.8 0.14 0.14 0.33 2.2e-08 2.2e-08 5.5e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
63 6090000 1 -0.0095 -0.011 -0.022 0.0053 0.0052 -0.011 0.0021 0.00027 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 0 0 1.4e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.5e-07 0.00038 0.00038 0.00016 0.23 0.23 7 0.1 0.1 0.33 1.8e-08 1.8e-08 5.3e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
64 6190000 1 -0.0095 -0.011 -0.022 0.0056 0.0072 -0.0047 -0.005 0.0027 0.00092 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 0 0 -1.1e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.6e-07 0.00041 0.00041 0.00016 0.27 0.27 4.9 0.13 0.13 0.32 1.8e-08 1.8e-08 5e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
65 6290000 1 -0.0095 -0.011 -0.022 0.0071 0.0075 -0.012 0.0033 0.0016 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 0 0 -1.9e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.6e-07 0.00043 0.00043 0.00016 0.31 0.31 3.2 0.17 0.17 0.3 1.8e-08 1.8e-08 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
66 6390000 0.71 0.0014 -0.014 0.71 0.0048 0.0076 -0.05 0.0025 0.0017 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 0 0 4.1e-07 4e-07 0.21 0.002 0.44 0 0 0 0 0 0.00076 0.00034 0.00034 0.00085 0.22 0.22 2.3 0.13 0.13 0.29 1.4e-08 1.5e-08 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
67 6490000 0.71 0.0014 -0.014 0.71 0.0043 0.0083 -0.052 0.0029 0.0025 -3.7e+02 -1.6e-05 -5.6e-05 4.1e-07 0 0 -8.2e-08 -8.7e-08 0.21 0.002 0.44 0 0 0 0 0 0.00051 0.00034 0.00034 0.00056 0.22 0.22 1.5 0.16 0.16 0.26 1.4e-08 1.5e-08 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
68 6590000 0.71 0.0015 -0.014 0.71 0.0036 0.0085 -0.099 0.0034 0.0033 -3.7e+02 -1.6e-05 -5.6e-05 3.6e-07 0 0 1.7e-06 0.21 0.002 0.44 0 0 0 0 0 0.00039 0.00034 0.00034 0.00043 0.23 0.23 1.1 0.19 0.19 0.23 1.4e-08 1.4e-08 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
69 6690000 0.7 0.0015 -0.014 0.71 0.0037 0.0095 -0.076 0.0037 0.0042 -3.7e+02 -1.6e-05 -5.6e-05 3e-07 0 0 -1.5e-06 0.21 0.002 0.44 0 0 0 0 0 0.00031 0.00034 0.00034 0.00035 0.24 0.24 0.78 0.23 0.23 0.21 1.4e-08 1.4e-08 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
70 6790000 0.71 0.0015 -0.014 0.71 0.0021 0.0095 -0.11 0.004 0.0052 -3.7e+02 -1.6e-05 -5.6e-05 3.3e-07 0 0 8.6e-07 8.5e-07 0.21 0.002 0.44 0 0 0 0 0 0.00027 0.00034 0.00034 0.0003 0.25 0.25 0.6 0.28 0.28 0.2 1.4e-08 1.4e-08 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
71 6890000 0.71 0.0015 -0.014 0.71 -0.00021 0.01 -0.12 0.0041 0.0062 -3.7e+02 -1.6e-05 -5.6e-05 3.4e-07 0 0 3.5e-07 3.4e-07 0.21 0.002 0.44 0 0 0 0 0 0.00024 0.00035 0.00035 0.00026 0.26 0.26 0.46 0.33 0.33 0.18 1.4e-08 1.4e-08 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
72 6990000 0.7 0.0016 -0.014 0.71 -0.00055 0.011 -0.12 0.004 0.0072 -3.7e+02 -1.6e-05 -5.6e-05 1.6e-07 0 0 -2.7e-06 0.21 0.002 0.44 0 0 0 0 0 0.00021 0.00035 0.00035 0.00023 0.28 0.28 0.36 0.38 0.38 0.16 1.4e-08 1.4e-08 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
73 7090000 0.7 0.0016 -0.014 0.71 -0.0014 0.011 -0.13 0.0039 0.0083 -3.7e+02 -1.6e-05 -5.6e-05 -5.1e-08 0 0 -6.2e-06 -6.3e-06 0.21 0.002 0.44 0 0 0 0 0 0.0002 0.00036 0.00036 0.00022 0.3 0.3 0.29 0.44 0.44 0.16 1.4e-08 1.4e-08 4.7e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
74 7190000 0.7 0.0016 -0.014 0.71 -0.0034 0.011 -0.15 0.0037 0.0093 -3.7e+02 -1.6e-05 -5.6e-05 -1.4e-07 0 0 -4.1e-06 0.21 0.002 0.44 0 0 0 0 0 0.00018 0.00036 0.00036 0.0002 0.32 0.32 0.24 0.51 0.51 0.15 1.4e-08 1.4e-08 4.7e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
75 7290000 0.7 0.0016 -0.014 0.71 -0.0052 0.011 -0.15 0.0033 0.01 -3.7e+02 -1.6e-05 -5.6e-05 -1.5e-07 0 0 -1.1e-05 0.21 0.002 0.44 0 0 0 0 0 0.00017 0.00037 0.00037 0.00018 0.34 0.34 0.2 0.58 0.58 0.14 1.4e-08 1.4e-08 4.7e-09 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
76 7390000 0.7 0.0017 -0.014 0.71 -0.0056 0.012 -0.16 0.0027 0.011 -3.7e+02 -1.6e-05 -5.6e-05 -1.3e-07 0 0 -1.2e-05 0.21 0.002 0.44 0 0 0 0 0 0.00016 0.00038 0.00038 0.00017 0.37 0.37 0.18 0.66 0.66 0.13 1.4e-08 1.4e-08 4.7e-09 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
114 11190000 0.7 0.0022 -0.014 0.71 0.0087 0.0081 0.0049 0.0066 -0.0028 -3.7e+02 -1.3e-05 -5.5e-05 -2e-06 -9.6e-06 1.6e-05 -0.0011 0.21 0.002 0.44 0 0 0 0 0 9.6e-05 0.00062 0.00062 9.6e-05 0.1 0.1 0.071 0.063 0.063 0.064 9.4e-09 9.5e-09 3.4e-09 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
115 11290000 0.7 0.0023 -0.014 0.71 0.0082 0.011 0.0045 0.0075 -0.0018 -3.7e+02 -1.3e-05 -5.5e-05 -2.7e-06 -9.6e-06 1.6e-05 -0.0011 0.21 0.002 0.44 0 0 0 0 0 9.6e-05 0.00064 0.00064 9.6e-05 0.13 0.13 0.067 0.071 0.071 0.067 9.4e-09 9.5e-09 3.3e-09 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
116 11390000 0.7 0.0023 -0.014 0.71 0.0037 0.009 -0.00033 0.0054 -0.002 -3.7e+02 -1.4e-05 -5.5e-05 -3.2e-06 -5.4e-06 1.2e-05 -0.0011 0.21 0.002 0.44 0 0 0 0 0 9.6e-05 0.00054 0.00054 9.6e-05 0.1 0.1 0.056 0.058 0.058 0.064 8.4e-09 8.4e-09 3.2e-09 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
117 11490000 0.7 0.0023 -0.014 0.71 0.00095 0.012 0.0004 0.00039 0.0056 -0.00092 -3.7e+02 -1.4e-05 -5.5e-05 -4.2e-06 -5.5e-06 1.2e-05 -0.0011 0.21 0.002 0.44 0 0 0 0 0 9.6e-05 0.00056 0.00056 9.6e-05 0.13 0.13 0.052 0.066 0.066 0.064 8.4e-09 8.4e-09 3.2e-09 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
118 11590000 0.7 0.0022 -0.014 0.71 -0.0029 0.01 -0.0049 -0.005 0.0044 -0.0014 -3.7e+02 -1.4e-05 -5.6e-05 -4.4e-06 -1.2e-06 1.1e-05 -0.0011 0.21 0.002 0.44 0 0 0 0 0 9.6e-05 0.00046 0.00046 9.6e-05 0.1 0.1 0.045 0.054 0.054 0.063 7.4e-09 7.4e-09 3.1e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
119 11690000 0.7 0.0022 -0.014 0.71 -0.006 0.013 -0.0091 0.0039 -0.00027 -3.7e+02 -1.4e-05 -5.6e-05 -4.7e-06 -1.1e-06 1.1e-05 -0.0011 0.21 0.002 0.44 0 0 0 0 0 9.6e-05 0.00047 0.00047 9.6e-05 0.12 0.12 0.042 0.063 0.063 0.063 7.4e-09 7.4e-09 3.1e-09 3.7e-06 3.7e-06 9.9e-07 0 0 0 0 0 0 0 0
120 11790000 0.7 0.0022 -0.014 0.71 -0.011 0.013 -0.011 0.0017 0.00056 -3.7e+02 -1.4e-05 -5.6e-05 -4.8e-06 -1.6e-08 9.8e-06 -0.0011 0.21 0.002 0.44 0 0 0 0 0 9.6e-05 0.00039 0.00039 9.6e-05 0.096 0.096 0.037 0.052 0.052 0.061 6.6e-09 6.6e-09 3e-09 3.7e-06 3.7e-06 9.9e-07 0 0 0 0 0 0 0 0
121 11890000 0.7 0.0022 -0.014 0.71 -0.013 0.014 -0.012 0.00052 0.0019 -3.7e+02 -1.4e-05 -5.6e-05 -5.3e-06 -9.2e-08 9.9e-06 -0.0011 0.21 0.002 0.44 0 0 0 0 0 9.6e-05 0.0004 0.0004 9.6e-05 0.12 0.12 0.035 0.061 0.061 0.061 6.6e-09 6.6e-09 2.9e-09 3.7e-06 3.7e-06 9.9e-07 0 0 0 0 0 0 0 0
153 15090000 0.7 0.00023 -0.013 0.71 0.0038 -0.0021 -0.031 0.0035 -0.0031 -3.7e+02 -1.2e-05 -6.1e-05 1.1e-06 -1.1e-05 2.4e-05 -0.0012 0.21 0.002 0.44 0 0 0 0 0 9.3e-05 0.00019 0.00019 9.1e-05 0.047 0.047 0.03 0.054 0.054 0.052 2.4e-09 2.4e-09 1.4e-09 3.5e-06 3.5e-06 4.4e-07 0 0 0 0 0 0 0 0
154 15190000 0.7 0.00024 -0.013 0.71 0.0032 -0.00083 -0.029 0.0028 -0.0024 -3.7e+02 -1.2e-05 -6.1e-05 1e-06 -1.1e-05 2.5e-05 -0.0012 0.21 0.002 0.44 0 0 0 0 0 9.3e-05 0.00019 0.00019 9.1e-05 0.041 0.041 0.029 0.047 0.047 0.051 2.3e-09 2.3e-09 1.4e-09 3.5e-06 3.5e-06 4.1e-07 0 0 0 0 0 0 0 0
155 15290000 0.7 0.0002 -0.013 0.71 0.0038 -0.00068 -0.026 0.0031 -0.0025 -3.7e+02 -1.2e-05 -6.1e-05 1.4e-06 -1.2e-05 2.6e-05 -0.0012 0.21 0.002 0.44 0 0 0 0 0 9.3e-05 0.00019 0.00019 9e-05 0.046 0.046 0.029 0.054 0.054 0.052 2.3e-09 2.3e-09 1.4e-09 3.5e-06 3.5e-06 4e-07 0 0 0 0 0 0 0 0
156 15390000 0.7 0.00021 -0.013 0.71 0.003 -0.00032 -0.00033 -0.024 0.00054 -0.002 -3.7e+02 -1.2e-05 -6.1e-05 2e-06 -1.3e-05 2.8e-05 -0.0012 0.21 0.002 0.44 0 0 0 0 0 9.3e-05 0.00018 0.00018 9e-05 0.04 0.04 0.028 0.047 0.047 0.051 2.1e-09 2.1e-09 1.3e-09 3.5e-06 3.5e-06 3.7e-07 0 0 0 0 0 0 0 0
157 15490000 0.7 0.00023 -0.013 0.71 0.0043 -0.00071 -0.024 0.00091 -0.0021 -3.7e+02 -1.2e-05 -6.1e-05 1.7e-06 -1.2e-05 2.8e-05 -0.0012 0.21 0.002 0.44 0 0 0 0 0 9.2e-05 0.00019 0.00019 9e-05 0.045 0.045 0.028 0.053 0.053 0.052 2.1e-09 2.1e-09 1.3e-09 3.5e-06 3.5e-06 3.6e-07 0 0 0 0 0 0 0 0
158 15590000 0.7 0.00024 -0.013 0.71 0.0024 -0.0007 -0.023 -0.0013 -0.0017 -3.7e+02 -1.2e-05 -6.1e-05 1.5e-06 -1.2e-05 3e-05 -0.0012 0.21 0.002 0.44 0 0 0 0 0 9.2e-05 0.00018 0.00018 9e-05 0.039 0.039 0.027 0.046 0.046 0.051 1.9e-09 1.9e-09 1.3e-09 3.5e-06 3.5e-06 3.3e-07 0 0 0 0 0 0 0 0
159 15690000 0.7 0.00025 -0.013 0.71 0.0027 -0.00088 -0.023 -0.0011 -0.0018 -3.7e+02 -1.2e-05 -6.1e-05 1.5e-06 -1.3e-05 3e-05 -0.0012 0.21 0.002 0.44 0 0 0 0 0 9.2e-05 0.00019 0.00018 8.9e-05 0.044 0.044 0.027 0.053 0.053 0.052 1.9e-09 1.9e-09 1.2e-09 3.5e-06 3.5e-06 3.2e-07 0 0 0 0 0 0 0 0
174 17190000 0.71 0.00045 -0.013 0.71 -0.00031 0.0013 -0.011 -0.0057 -0.00054 -3.7e+02 -1.3e-05 -6e-05 3.2e-06 -1.2e-05 5.8e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.8e-05 0.00015 0.00015 8.6e-05 0.035 0.035 0.019 0.046 0.046 0.049 9.5e-10 9.6e-10 8.9e-10 3.2e-06 3.2e-06 1.4e-07 0 0 0 0 0 0 0 0
175 17290000 0.71 0.00043 -0.013 0.71 0.0018 0.0023 -0.0067 -0.0056 -0.00038 -3.7e+02 -1.4e-05 -6e-05 3e-06 -1.2e-05 5.8e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.8e-05 0.00015 0.00015 8.5e-05 0.039 0.039 0.019 0.052 0.052 0.049 9.5e-10 9.6e-10 8.7e-10 3.2e-06 3.2e-06 1.4e-07 0 0 0 0 0 0 0 0
176 17390000 0.71 0.0004 -0.013 0.71 0.0024 0.0015 -0.0048 -0.0047 -0.0016 -3.7e+02 -1.3e-05 -6e-05 3.3e-06 -1.6e-05 5.8e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.8e-05 0.00015 0.00014 8.5e-05 0.034 0.034 0.018 0.046 0.046 0.048 8.7e-10 8.7e-10 8.5e-10 3.2e-06 3.2e-06 1.3e-07 0 0 0 0 0 0 0 0
177 17490000 0.71 0.00039 -0.013 0.71 0.003 0.001 -0.003 -0.0031 -0.0044 -0.0015 -3.7e+02 -1.3e-05 -6e-05 3.3e-06 -1.6e-05 5.8e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.7e-05 0.00015 0.00015 8.5e-05 0.038 0.038 0.018 0.052 0.052 0.049 8.7e-10 8.7e-10 8.3e-10 3.2e-06 3.2e-06 1.3e-07 0 0 0 0 0 0 0 0
178 17590000 0.71 0.0003 -0.013 0.71 0.0042 -0.00014 0.0024 -0.0037 -0.0026 -3.7e+02 -1.4e-05 -6.1e-05 3.4e-06 -1.9e-05 5.9e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.7e-05 0.00014 0.00014 8.5e-05 0.034 0.034 0.017 0.046 0.046 0.048 7.9e-10 7.9e-10 8.1e-10 3.2e-06 3.2e-06 1.2e-07 0 0 0 0 0 0 0 0
179 17690000 0.71 0.00027 -0.012 0.71 0.0051 0.00056 0.0018 -0.0032 -0.0026 -3.7e+02 -1.4e-05 -6.1e-05 3.6e-06 -1.9e-05 5.9e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.7e-05 0.00014 0.00014 8.4e-05 0.038 0.038 0.017 0.052 0.052 0.048 7.9e-10 7.9e-10 7.9e-10 3.2e-06 3.2e-06 1.1e-07 0 0 0 0 0 0 0 0
180 17790000 0.71 0.00018 -0.013 0.71 0.0077 0.00029 0.00051 0.00048 -0.0021 -0.0022 -3.7e+02 -1.3e-05 -6.1e-05 4.2e-06 -1.9e-05 5.5e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.7e-05 0.00014 0.00014 8.4e-05 0.033 0.033 0.016 0.045 0.045 0.048 7.1e-10 7.1e-10 7.8e-10 3.2e-06 3.2e-06 1.1e-07 0 0 0 0 0 0 0 0
181 17890000 0.71 0.00019 -0.013 0.71 0.0092 -0.00047 0.00061 0.00058 -0.0012 -0.0022 -3.7e+02 -1.3e-05 -6.1e-05 4.4e-06 -1.9e-05 5.5e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.6e-05 0.00014 0.00014 8.4e-05 0.037 0.037 0.016 0.052 0.052 0.048 7.1e-10 7.1e-10 7.6e-10 3.2e-06 3.2e-06 1e-07 0 0 0 0 0 0 0 0
182 17990000 0.71 0.00013 -0.013 0.71 0.011 -0.0022 0.0018 -0.00053 -0.0019 -3.7e+02 -1.3e-05 -6.1e-05 4.4e-06 -1.8e-05 5.4e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.6e-05 0.00013 0.00013 8.4e-05 0.032 0.032 0.015 0.045 0.045 0.047 6.4e-10 6.4e-10 7.5e-10 3.1e-06 3.1e-06 9.8e-08 0 0 0 0 0 0 0 0
183 18090000 0.71 0.00014 -0.013 0.71 0.012 -0.0024 0.0042 0.00061 -0.0022 -3.7e+02 -1.3e-05 -6.1e-05 4e-06 -1.8e-05 5.4e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.6e-05 0.00014 0.00014 8.3e-05 0.036 0.036 0.015 0.051 0.051 0.047 6.4e-10 6.4e-10 7.3e-10 3.1e-06 3.1e-06 9.5e-08 0 0 0 0 0 0 0 0
184 18190000 0.71 0.00011 -0.013 0.71 0.012 -0.0013 0.0055 0.0015 -0.0017 -3.7e+02 -1.3e-05 -6.1e-05 4.2e-06 -1.7e-05 5.4e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.6e-05 0.00013 0.00013 8.3e-05 0.032 0.032 0.015 0.045 0.045 0.046 5.8e-10 5.8e-10 7.2e-10 3.1e-06 3.1e-06 9e-08 0 0 0 0 0 0 0 0
185 18290000 0.71 4.8e-05 -0.012 0.71 0.012 -0.0019 0.0067 0.0027 -0.0018 -3.7e+02 -1.3e-05 -6.1e-05 4.1e-06 -1.7e-05 5.4e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.5e-05 0.00013 0.00013 8.3e-05 0.035 0.035 0.015 0.051 0.051 0.046 5.8e-10 5.8e-10 7e-10 3.1e-06 3.1e-06 8.7e-08 0 0 0 0 0 0 0 0
186 18390000 0.71 6.4e-05 -0.013 0.71 0.014 -0.0002 0.0079 0.0078 0.0032 -0.0014 -3.7e+02 -1.3e-05 -6.1e-05 4.4e-06 -1.7e-05 5.5e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.5e-05 0.00013 0.00013 8.3e-05 0.031 0.031 0.014 0.045 0.045 0.045 5.3e-10 5.3e-10 6.9e-10 3.1e-06 3.1e-06 8.3e-08 0 0 0 0 0 0 0 0
187 18490000 0.71 7.9e-05 -0.012 0.71 0.014 0.00021 0.0075 0.0047 -0.0014 -3.7e+02 -1.3e-05 -6.1e-05 4.5e-06 -1.7e-05 5.5e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.5e-05 0.00013 0.00013 8.2e-05 0.034 0.034 0.014 0.051 0.051 0.046 5.3e-10 5.3e-10 6.7e-10 3.1e-06 3.1e-06 8e-08 0 0 0 0 0 0 0 0
188 18590000 0.71 8.4e-05 -0.012 0.71 0.013 0.00045 0.0057 0.0056 0.0035 -0.0012 -3.7e+02 -1.4e-05 -6.1e-05 4.9e-06 -1.7e-05 5.9e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.5e-05 0.00012 0.00012 8.2e-05 0.03 0.03 0.013 0.045 0.045 0.045 4.8e-10 4.8e-10 6.6e-10 3.1e-06 3.1e-06 7.6e-08 0 0 0 0 0 0 0 0
189 18690000 0.71 5.3e-05 -0.012 0.71 0.014 -0.00024 0.0038 0.0049 -0.0011 -3.7e+02 -1.4e-05 -6.1e-05 4.8e-06 -1.7e-05 5.9e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.4e-05 0.00013 0.00012 8.2e-05 0.034 0.034 0.013 0.051 0.051 0.045 4.8e-10 4.8e-10 6.5e-10 3.1e-06 3.1e-06 7.4e-08 0 0 0 0 0 0 0 0
190 18790000 0.71 8.4e-05 -0.012 0.71 0.012 6.5e-05 0.0035 0.0034 0.0038 -0.00091 -3.7e+02 -1.4e-05 -6.1e-05 4.6e-06 -1.7e-05 6.3e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.4e-05 0.00012 0.00012 8.2e-05 0.03 0.03 0.013 0.045 0.045 0.045 4.4e-10 4.4e-10 6.3e-10 3.1e-06 3.1e-06 7.1e-08 0 0 0 0 0 0 0 0
191 18890000 0.71 0.00011 -0.012 0.71 0.013 0.00056 0.0041 0.004 0.005 -0.00085 -3.7e+02 -1.4e-05 -6.1e-05 5e-06 -1.7e-05 6.3e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.4e-05 0.00012 0.00012 8.1e-05 0.033 0.033 0.013 0.051 0.051 0.045 4.4e-10 4.4e-10 6.2e-10 3.1e-06 3.1e-06 6.9e-08 0 0 0 0 0 0 0 0
192 18990000 0.71 9.4e-05 -0.012 0.71 0.014 0.0015 0.0028 0.0027 0.0063 -0.0007 -3.7e+02 -1.4e-05 -6.1e-05 5.2e-06 -1.7e-05 6.2e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.4e-05 0.00012 0.00012 8.1e-05 0.029 0.029 0.012 0.045 0.045 0.044 4e-10 4e-10 6.1e-10 3e-06 3e-06 6.6e-08 0 0 0 0 0 0 0 0
193 19090000 0.71 7.8e-05 -0.012 0.71 0.015 0.0021 0.0058 0.0057 0.0078 -0.0005 -3.7e+02 -1.4e-05 -6.1e-05 5.2e-06 -1.7e-05 6.2e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.4e-05 0.00012 0.00012 8.1e-05 0.032 0.032 0.012 0.051 0.051 0.044 4e-10 4e-10 6e-10 3e-06 3e-06 6.4e-08 0 0 0 0 0 0 0 0
194 19190000 0.71 8.1e-05 -0.012 0.71 0.015 0.0021 0.0058 0.0086 -0.00045 -3.7e+02 -1.4e-05 -6.1e-05 5.3e-06 -1.7e-05 6.1e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.3e-05 0.00012 0.00011 8.1e-05 0.028 0.028 0.012 0.045 0.045 0.043 3.6e-10 3.6e-10 5.9e-10 3e-06 3e-06 6.1e-08 0 0 0 0 0 0 0 0
195 19290000 0.71 0.0001 -0.012 0.71 0.015 0.0013 0.0085 0.01 -0.00027 -3.7e+02 -1.4e-05 -6.1e-05 5.2e-06 -1.7e-05 6.1e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.3e-05 0.00012 0.00012 8e-05 0.031 0.031 0.012 0.05 0.05 0.043 3.6e-10 3.6e-10 5.7e-10 3e-06 3e-06 5.9e-08 0 0 0 0 0 0 0 0
196 19390000 0.71 0.00012 -0.012 0.71 0.013 0.00039 0.012 0.008 -0.00028 -3.7e+02 -1.4e-05 -6.1e-05 5.3e-06 -1.8e-05 6.5e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.3e-05 0.00011 0.00011 8e-05 0.028 0.028 0.011 0.045 0.045 0.043 3.3e-10 3.3e-10 5.6e-10 3e-06 3e-06 5.7e-08 0 0 0 0 0 0 0 0
197 19490000 0.71 0.00014 -0.012 0.71 0.012 -0.00032 0.0087 0.0092 -0.00028 -3.7e+02 -1.4e-05 -6.1e-05 5.6e-06 -1.8e-05 6.5e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.3e-05 0.00011 0.00011 8e-05 0.03 0.03 0.011 0.05 0.05 0.043 3.3e-10 3.3e-10 5.5e-10 3e-06 3e-06 5.5e-08 0 0 0 0 0 0 0 0
198 19590000 0.71 0.00019 -0.012 0.71 0.0097 -0.0013 0.008 0.0075 -0.0003 -3.7e+02 -1.4e-05 -6.1e-05 5.9e-06 -1.8e-05 6.8e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.2e-05 0.00011 0.00011 8e-05 0.027 0.027 0.011 0.044 0.044 0.042 3e-10 3e-10 5.4e-10 3e-06 3e-06 5.3e-08 0 0 0 0 0 0 0 0
199 19690000 0.71 0.00019 -0.012 0.71 0.01 -0.0035 0.0095 0.0085 -0.00055 -3.7e+02 -1.4e-05 -6.1e-05 5.7e-06 -1.8e-05 6.8e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.2e-05 0.00011 0.00011 8e-05 0.029 0.029 0.011 0.05 0.05 0.042 3e-10 3e-10 5.3e-10 3e-06 3e-06 5.2e-08 0 0 0 0 0 0 0 0
200 19790000 0.71 0.00026 -0.012 0.71 0.0078 -0.0044 0.01 0.0099 0.0068 -0.00044 -3.7e+02 -1.4e-05 -6.1e-05 5.8e-06 -1.8e-05 7.1e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.2e-05 0.00011 0.00011 7.9e-05 0.026 0.026 0.011 0.044 0.044 0.042 2.7e-10 2.7e-10 5.2e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
201 19890000 0.71 0.0002 -0.012 0.71 0.0065 -0.0047 0.011 0.0076 -0.00091 -3.7e+02 -1.4e-05 -6.1e-05 6.2e-06 -1.8e-05 7.1e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.2e-05 0.00011 0.00011 7.9e-05 0.029 0.029 0.011 0.05 0.05 0.042 2.7e-10 2.7e-10 5.1e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
202 19990000 0.71 0.00019 -0.012 0.71 0.0041 -0.0053 0.014 0.0062 -0.00076 -3.7e+02 -1.4e-05 -6.1e-05 6.7e-06 -1.7e-05 7.3e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.1e-05 0.00011 0.00011 7.9e-05 0.026 0.026 0.01 0.044 0.044 0.041 2.5e-10 2.5e-10 5e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
203 20090000 0.71 0.00018 -0.012 0.71 0.0039 -0.0073 0.014 0.0065 -0.0014 -3.7e+02 -1.4e-05 -6.1e-05 7.1e-06 -1.7e-05 7.3e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8.1e-05 0.00011 0.00011 7.9e-05 0.028 0.028 0.01 0.05 0.05 0.042 2.5e-10 2.5e-10 4.9e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
209 20690000 0.71 0.00037 -0.012 0.71 -0.0022 -0.012 0.015 0.0016 -0.0032 -3.7e+02 -1.4e-05 -6e-05 7.2e-06 -1.3e-05 7.8e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8e-05 0.0001 0.0001 7.8e-05 0.026 0.026 0.0093 0.049 0.049 0.04 2e-10 2e-10 4.4e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
210 20790000 0.71 0.0004 -0.012 0.71 -0.0033 -0.011 0.015 0.0014 -0.0025 -3.7e+02 -1.4e-05 -6e-05 7.3e-06 -1.1e-05 7.7e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 8e-05 0.0001 0.0001 7.7e-05 0.023 0.023 0.0091 0.043 0.043 0.04 1.8e-10 1.8e-10 4.3e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
211 20890000 0.71 0.00038 -0.012 0.71 -0.0038 -0.014 0.014 0.001 -0.0038 -3.7e+02 -1.4e-05 -6e-05 7.5e-06 -1.1e-05 7.7e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 7.9e-05 0.0001 0.0001 7.7e-05 0.025 0.025 0.009 0.049 0.049 0.04 1.8e-10 1.8e-10 4.3e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
212 20990000 0.71 0.00039 -0.012 0.71 -0.004 -0.014 0.015 0.014 0.0027 -0.0031 -3.7e+02 -1.4e-05 -6e-05 7.5e-06 -8.6e-06 7.6e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 7.9e-05 9.8e-05 9.8e-05 7.7e-05 0.023 0.023 0.0088 0.043 0.043 0.039 1.7e-10 1.7e-10 4.2e-10 2.9e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
213 21090000 0.71 0.00039 -0.012 0.71 -0.0041 -0.017 0.015 0.0023 -0.0046 -3.7e+02 -1.4e-05 -6e-05 7.7e-06 -8.7e-06 7.6e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 7.9e-05 9.9e-05 9.9e-05 7.7e-05 0.025 0.025 0.0088 0.048 0.048 0.039 1.7e-10 1.7e-10 4.1e-10 2.9e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
214 21190000 0.71 0.00042 -0.012 0.71 -0.0033 -0.016 0.014 0.0037 -0.0038 -3.7e+02 -1.4e-05 -6e-05 7.6e-06 -6.3e-06 7.5e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 7.9e-05 9.7e-05 9.7e-05 7.7e-05 0.022 0.022 0.0086 0.043 0.043 0.039 1.5e-10 1.6e-10 4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
215 21290000 0.71 0.00046 -0.012 0.71 -0.0039 -0.018 0.016 0.0034 -0.0054 -3.7e+02 -1.4e-05 -6e-05 7.9e-06 -6.2e-06 7.5e-05 -0.0013 0.21 0.002 0.44 0 0 0 0 0 7.9e-05 9.8e-05 9.8e-05 7.6e-05 0.024 0.024 0.0086 0.048 0.048 0.039 1.6e-10 1.6e-10 4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
320 31790000 0.71 0.0011 0.0011 0.71 -1.7 -0.89 0.72 -13 -6 -3.7e+02 -1.4e-05 -5.7e-05 2.8e-06 -0.00028 -5.4e-05 -0.00098 0.21 0.002 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.6e-05 6.1e-05 0.025 0.025 0.0087 0.27 0.27 0.037 3e-11 3e-11 1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
321 31890000 0.71 0.00087 0.00037 0.71 -1.6 -0.88 0.72 -13 -6.1 -3.7e+02 -1.4e-05 -5.7e-05 2.8e-06 -0.00029 -4.1e-05 -0.00098 0.21 0.002 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.6e-05 6e-05 0.026 0.026 0.0087 0.28 0.28 0.037 3e-11 3e-11 1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
322 31990000 0.71 0.00074 -8.3e-05 0.71 -1.6 -0.87 0.71 -13 -6.2 -3.7e+02 -1.4e-05 -5.7e-05 2.7e-06 -0.0003 -2.2e-05 -0.00097 0.21 0.002 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.6e-05 6e-05 0.025 0.025 0.0086 0.28 0.28 0.036 3e-11 3e-11 9.9e-11 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
323 32090000 0.71 0.00045 -0.0008 0.71 -1.6 -0.86 0.72 -13 -6.3 -3.7e+02 -1.4e-05 -5.7e-05 2.6e-06 -0.0003 -6.7e-06 -6.8e-06 -0.00096 0.21 0.002 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.6e-05 6e-05 0.026 0.026 0.0087 0.29 0.29 0.037 3e-11 3e-11 9.9e-11 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
324 32190000 0.71 0.00024 -0.0016 0.71 -1.5 -0.85 0.72 -13 -6.4 -3.7e+02 -1.4e-05 -5.7e-05 2.5e-06 -0.00031 1.4e-05 -0.00096 0.21 0.002 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.025 0.025 0.0086 0.29 0.29 0.036 2.9e-11 2.9e-11 9.8e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
325 32290000 0.71 6.7e-06 6.6e-06 -0.0023 0.71 -1.5 -0.84 0.71 -13 -6.4 -3.7e+02 -1.4e-05 -5.7e-05 2.4e-06 -0.00032 3e-05 -0.00095 0.21 0.002 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.026 0.026 0.0086 0.3 0.3 0.037 3e-11 2.9e-11 9.7e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
326 32390000 0.71 -0.00018 -0.0029 0.71 -1.5 -0.83 0.71 -14 -6.5 -3.7e+02 -1.4e-05 -5.7e-05 2.5e-06 -0.00032 3.9e-05 -0.00095 0.21 0.002 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.025 0.025 0.0085 0.3 0.3 0.037 2.9e-11 2.9e-11 9.6e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
327 32490000 0.71 -0.0003 -0.0032 0.71 -1.4 -0.82 0.72 -14 -6.6 -3.7e+02 -1.4e-05 -5.7e-05 2.5e-06 -0.00033 5e-05 -0.00094 0.21 0.002 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.026 0.026 0.0086 0.31 0.31 0.037 2.9e-11 2.9e-11 9.5e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
328 32590000 0.71 -0.00029 -0.0034 0.71 -1.4 -0.8 0.71 -14 -6.7 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 -0.00033 5.8e-05 -0.00094 0.21 0.002 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.025 0.025 0.0084 0.31 0.31 0.036 2.9e-11 2.9e-11 9.4e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
343 34090000 -0.5 -0.0021 -0.013 0.87 -0.93 -0.58 0.74 -16 -7.7 -3.7e+02 -1.5e-05 -5.6e-05 2.6e-06 -0.00036 0.00012 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.1e-05 6.9e-05 7.8e-05 6.9e-05 0.036 0.037 0.0069 0.38 0.38 0.036 2.7e-11 2.7e-11 8.3e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
344 34190000 -0.57 -0.0014 -0.011 0.82 -0.92 -0.54 0.74 -16 -7.8 -3.7e+02 -1.5e-05 -5.7e-05 2.6e-06 -0.00039 0.00014 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.4e-05 6.5e-05 7.3e-05 6.7e-05 0.036 0.037 0.0067 0.38 0.38 0.035 2.7e-11 2.7e-11 8.2e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
345 34290000 -0.61 -0.0023 -0.0086 0.79 -0.87 -0.49 0.74 -16 -7.9 -3.7e+02 -1.5e-05 -5.7e-05 2.6e-06 -0.00039 0.00014 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.5e-05 6.5e-05 7.3e-05 6.5e-05 0.042 0.043 0.0066 0.39 0.39 0.035 2.7e-11 2.7e-11 8.2e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
346 34390000 -0.64 -0.0025 -0.0061 0.77 -0.85 -0.46 0.73 -16 -7.9 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00044 -0.00043 0.00019 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.6e-05 6e-05 6.7e-05 6.4e-05 0.042 0.043 0.0065 0.39 0.39 0.035 2.7e-11 2.7e-11 8.1e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
347 34490000 -0.65 -0.0034 -0.0039 0.76 -0.8 -0.42 0.73 -16 -8 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00043 0.00019 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.7e-05 6.1e-05 6.7e-05 6.3e-05 0.049 0.05 0.0064 0.4 0.4 0.035 2.7e-11 2.7e-11 8e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
348 34590000 -0.66 -0.0028 -0.0028 0.75 -0.8 -0.4 0.73 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 -0.00053 0.00027 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.7e-05 5.5e-05 6.1e-05 6.2e-05 0.047 0.048 0.0063 0.4 0.4 0.034 2.6e-11 2.7e-11 8e-11 2.6e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
349 34690000 -0.67 -0.0032 -0.002 0.74 -0.75 -0.37 0.73 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 -0.00053 0.00027 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.7e-05 5.5e-05 6.1e-05 6.2e-05 0.054 0.056 0.0063 0.41 0.41 0.034 2.7e-11 2.7e-11 7.9e-11 2.6e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
359 35690000 -0.68 -0.0057 -0.0045 0.73 0.43 0.38 -0.19 -17 -8.1 -3.7e+02 -1.7e-05 -5.7e-05 2.9e-06 -0.00077 0.00052 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.7e-05 3.9e-05 4.2e-05 6e-05 0.073 0.075 0.0061 0.49 0.49 0.033 2.7e-11 2.7e-11 7.3e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
360 35790000 -0.68 -0.0034 -0.0044 0.73 0.35 0.32 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3e-06 -0.00079 0.00053 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.6e-05 3.4e-05 3.6e-05 6e-05 0.061 0.062 0.0059 0.49 0.48 0.033 2.7e-11 2.7e-11 7.3e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
361 35890000 -0.68 -0.0034 -0.0045 0.73 0.37 0.35 -0.19 -17 -8.1 -3.7e+02 -1.7e-05 -5.7e-05 3.1e-06 -0.00079 0.00053 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.6e-05 3.4e-05 3.6e-05 6e-05 0.066 0.068 0.0059 0.5 0.5 0.033 2.7e-11 2.7e-11 7.2e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
362 35990000 -0.68 -0.0016 -0.0044 0.73 0.3 0.29 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.3e-06 -0.00087 0.0006 0.00059 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.6e-05 3e-05 3.1e-05 6e-05 0.057 0.058 0.0057 0.49 0.49 0.033 2.7e-11 2.8e-11 7.2e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
363 36090000 -0.68 -0.0016 -0.0044 0.73 0.31 0.31 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.5e-06 -0.00087 0.0006 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.6e-05 3e-05 3.1e-05 6e-05 0.062 0.064 0.0057 0.51 0.51 0.032 2.7e-11 2.8e-11 7.1e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
364 36190000 -0.68 -0.00015 -0.0043 0.73 0.26 0.27 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.5e-06 -0.00097 0.00068 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.6e-05 2.6e-05 2.8e-05 6e-05 0.055 0.056 0.0055 0.5 0.5 0.032 2.7e-11 2.8e-11 7.1e-11 2.4e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
365 36290000 -0.68 -0.00021 -0.0042 0.73 0.27 0.28 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.7e-06 -0.00097 0.00068 -0.00092 0.21 0.002 0.44 0 0 0 0 0 5.6e-05 2.6e-05 2.8e-05 6e-05 0.06 0.062 0.0056 0.52 0.52 0.032 2.7e-11 2.8e-11 7e-11 2.4e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0

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

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