forked from Archive/PX4-Autopilot
ekf2: cleanup output predictor init
- output predictor align also init _output_vert_new - output predictor reset handle all fields - output predictor resetQuaternion() normalize - output predictor calculateOutputStates() paranoid timestamp check - output predictor correctOutputStates() paranoid timestamp checks and explicitly pop delayed sample at correct time
This commit is contained in:
parent
ae70f9c640
commit
b1727055f9
|
@ -91,6 +91,8 @@ void Ekf::reset()
|
|||
_output_predictor.reset();
|
||||
|
||||
// Ekf private fields
|
||||
_filter_initialised = false;
|
||||
|
||||
_time_last_horizontal_aiding = 0;
|
||||
_time_last_v_pos_aiding = 0;
|
||||
_time_last_v_vel_aiding = 0;
|
||||
|
@ -161,11 +163,11 @@ void Ekf::reset()
|
|||
|
||||
bool Ekf::update()
|
||||
{
|
||||
if (!_filter_initialised) {
|
||||
_filter_initialised = initialiseFilter();
|
||||
bool updated = false;
|
||||
|
||||
if (!_filter_initialised) {
|
||||
return false;
|
||||
if (!_filter_initialised) {
|
||||
if (initialiseFilter()) {
|
||||
_filter_initialised = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -177,24 +179,26 @@ bool Ekf::update()
|
|||
// TODO: explicitly pop at desired time horizon
|
||||
const imuSample imu_sample_delayed = _imu_buffer.get_oldest();
|
||||
|
||||
// perform state and covariance prediction for the main filter
|
||||
predictCovariance(imu_sample_delayed);
|
||||
predictState(imu_sample_delayed);
|
||||
if (_filter_initialised) {
|
||||
// perform state and covariance prediction for the main filter
|
||||
predictCovariance(imu_sample_delayed);
|
||||
predictState(imu_sample_delayed);
|
||||
|
||||
// control fusion of observation data
|
||||
controlFusionModes(imu_sample_delayed);
|
||||
// control fusion of observation data
|
||||
controlFusionModes(imu_sample_delayed);
|
||||
|
||||
#if defined(CONFIG_EKF2_RANGE_FINDER)
|
||||
// run a separate filter for terrain estimation
|
||||
runTerrainEstimator(imu_sample_delayed);
|
||||
// run a separate filter for terrain estimation
|
||||
runTerrainEstimator(imu_sample_delayed);
|
||||
#endif // CONFIG_EKF2_RANGE_FINDER
|
||||
|
||||
_output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _state.pos, _state.gyro_bias, _state.accel_bias);
|
||||
updated = true;
|
||||
}
|
||||
|
||||
return true;
|
||||
_output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _state.pos, _state.gyro_bias, _state.accel_bias);
|
||||
}
|
||||
|
||||
return false;
|
||||
return updated;
|
||||
}
|
||||
|
||||
bool Ekf::initialiseFilter()
|
||||
|
@ -229,9 +233,6 @@ bool Ekf::initialiseFilter()
|
|||
initHagl();
|
||||
#endif // CONFIG_EKF2_RANGE_FINDER
|
||||
|
||||
// reset the output predictor state history to match the EKF initial values
|
||||
_output_predictor.alignOutputFilter(_state.quat_nominal, _state.vel, _state.pos);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -809,7 +809,7 @@ private:
|
|||
// fuse single velocity and position measurement
|
||||
bool fuseVelPosHeight(const float innov, const float innov_var, const int obs_index);
|
||||
|
||||
void resetVelocityTo(const Vector3f &vel, const Vector3f &new_vel_var);
|
||||
void resetVelocityTo(const Vector3f &vel, const Vector3f &new_vel_var = Vector3f(NAN, NAN, NAN));
|
||||
|
||||
void resetHorizontalVelocityTo(const Vector2f &new_horz_vel, const Vector2f &new_horz_vel_var);
|
||||
void resetHorizontalVelocityTo(const Vector2f &new_horz_vel, float vel_var) { resetHorizontalVelocityTo(new_horz_vel, Vector2f(vel_var, vel_var)); }
|
||||
|
|
|
@ -73,7 +73,7 @@ void Ekf::resetHorizontalVelocityTo(const Vector2f &new_horz_vel, const Vector2f
|
|||
P.uncorrelateCovarianceSetVariance<1>(5, math::max(sq(0.01f), new_horz_vel_var(1)));
|
||||
}
|
||||
|
||||
_output_predictor.resetHorizontalVelocityTo(delta_horz_vel);
|
||||
_output_predictor.resetHorizontalVelocityTo(_time_delayed_us, new_horz_vel);
|
||||
|
||||
// record the state change
|
||||
if (_state_reset_status.reset_count.velNE == _state_reset_count_prev.velNE) {
|
||||
|
@ -99,7 +99,7 @@ void Ekf::resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var)
|
|||
P.uncorrelateCovarianceSetVariance<1>(6, math::max(sq(0.01f), new_vert_vel_var));
|
||||
}
|
||||
|
||||
_output_predictor.resetVerticalVelocityTo(delta_vert_vel);
|
||||
_output_predictor.resetVerticalVelocityTo(_time_delayed_us, new_vert_vel);
|
||||
|
||||
// record the state change
|
||||
if (_state_reset_status.reset_count.velD == _state_reset_count_prev.velD) {
|
||||
|
@ -139,7 +139,7 @@ void Ekf::resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f
|
|||
P.uncorrelateCovarianceSetVariance<1>(8, math::max(sq(0.01f), new_horz_pos_var(1)));
|
||||
}
|
||||
|
||||
_output_predictor.resetHorizontalPositionTo(delta_horz_pos);
|
||||
_output_predictor.resetHorizontalPositionTo(_time_delayed_us, new_horz_pos);
|
||||
|
||||
// record the state change
|
||||
if (_state_reset_status.reset_count.posNE == _state_reset_count_prev.posNE) {
|
||||
|
@ -174,7 +174,7 @@ bool Ekf::isHeightResetRequired() const
|
|||
|
||||
void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_var)
|
||||
{
|
||||
const float old_vert_pos = _state.pos(2);
|
||||
const float delta_z = new_vert_pos - _state.pos(2);
|
||||
_state.pos(2) = new_vert_pos;
|
||||
|
||||
if (PX4_ISFINITE(new_vert_pos_var)) {
|
||||
|
@ -182,11 +182,9 @@ void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_v
|
|||
P.uncorrelateCovarianceSetVariance<1>(9, math::max(sq(0.01f), new_vert_pos_var));
|
||||
}
|
||||
|
||||
const float delta_z = new_vert_pos - old_vert_pos;
|
||||
|
||||
// apply the change in height / height rate to our newest height / height rate estimate
|
||||
// which have already been taken out from the output buffer
|
||||
_output_predictor.resetVerticalPositionTo(new_vert_pos, delta_z);
|
||||
_output_predictor.resetVerticalPositionTo(_time_delayed_us, new_vert_pos);
|
||||
|
||||
// record the state change
|
||||
if (_state_reset_status.reset_count.posD == _state_reset_count_prev.posD) {
|
||||
|
@ -1069,7 +1067,7 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance)
|
|||
}
|
||||
|
||||
// add the reset amount to the output observer buffered data
|
||||
_output_predictor.resetQuaternion(q_error);
|
||||
_output_predictor.resetQuaternion(_time_delayed_us, quat_after_reset);
|
||||
|
||||
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
|
||||
// update EV attitude error filter
|
||||
|
@ -1092,6 +1090,20 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance)
|
|||
_state_reset_status.reset_count.quat++;
|
||||
|
||||
_time_last_heading_fuse = _time_delayed_us;
|
||||
|
||||
|
||||
// apply change to velocity state
|
||||
const Vector3f new_vel = q_error.rotateVector(_state.vel);
|
||||
const Vector3f delta_vel = new_vel - _state.vel;
|
||||
_state.vel = new_vel;
|
||||
|
||||
if (_state_reset_status.reset_count.velNE == _state_reset_count_prev.velNE) {
|
||||
_state_reset_status.velNE_change = delta_vel.xy();
|
||||
|
||||
} else {
|
||||
// there's already a reset this update, accumulate total delta
|
||||
_state_reset_status.velNE_change += delta_vel.xy();
|
||||
}
|
||||
}
|
||||
|
||||
bool Ekf::resetYawToEKFGSF()
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2022 PX4. All rights reserved.
|
||||
* Copyright (c) 2022-2023 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -48,39 +48,11 @@ void OutputPredictor::print_status()
|
|||
|
||||
printf("output buffer: %d/%d (%d Bytes)\n", _output_buffer.entries(), _output_buffer.get_length(),
|
||||
_output_buffer.get_total_size());
|
||||
|
||||
printf("output vert buffer: %d/%d (%d Bytes)\n", _output_vert_buffer.entries(), _output_vert_buffer.get_length(),
|
||||
_output_vert_buffer.get_total_size());
|
||||
}
|
||||
|
||||
void OutputPredictor::alignOutputFilter(const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state)
|
||||
{
|
||||
const outputSample &output_delayed = _output_buffer.get_oldest();
|
||||
|
||||
// calculate the quaternion rotation delta from the EKF to output observer states at the EKF fusion time horizon
|
||||
Quatf q_delta{quat_state * output_delayed.quat_nominal.inversed()};
|
||||
q_delta.normalize();
|
||||
|
||||
// calculate the velocity and position deltas between the output and EKF at the EKF fusion time horizon
|
||||
const Vector3f vel_delta = vel_state - output_delayed.vel;
|
||||
const Vector3f pos_delta = pos_state - output_delayed.pos;
|
||||
|
||||
// loop through the output filter state history and add the deltas
|
||||
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
|
||||
_output_buffer[i].quat_nominal = q_delta * _output_buffer[i].quat_nominal;
|
||||
_output_buffer[i].quat_nominal.normalize();
|
||||
_output_buffer[i].vel += vel_delta;
|
||||
_output_buffer[i].pos += pos_delta;
|
||||
}
|
||||
|
||||
_output_new = _output_buffer.get_newest();
|
||||
}
|
||||
|
||||
void OutputPredictor::reset()
|
||||
{
|
||||
// TODO: who resets the output buffer content?
|
||||
_output_new = {};
|
||||
_output_vert_new = {};
|
||||
_output_buffer.reset();
|
||||
|
||||
_accel_bias.setZero();
|
||||
_gyro_bias.setZero();
|
||||
|
@ -88,86 +60,182 @@ void OutputPredictor::reset()
|
|||
_time_last_update_states_us = 0;
|
||||
_time_last_correct_states_us = 0;
|
||||
|
||||
_output_new = {};
|
||||
_R_to_earth_now.setIdentity();
|
||||
_vel_imu_rel_body_ned.setZero();
|
||||
_vel_deriv.setZero();
|
||||
_vel_imu_rel_body_ned.zero();
|
||||
_vel_deriv.zero();
|
||||
|
||||
_delta_angle_corr.setZero();
|
||||
_delta_angle_corr.zero();
|
||||
_vel_err_integ.zero();
|
||||
_pos_err_integ.zero();
|
||||
|
||||
_vel_err_integ.setZero();
|
||||
_pos_err_integ.setZero();
|
||||
_output_tracking_error.zero();
|
||||
|
||||
_output_tracking_error.setZero();
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index] = {};
|
||||
}
|
||||
|
||||
for (uint8_t index = 0; index < _output_vert_buffer.get_length(); index++) {
|
||||
_output_vert_buffer[index] = {};
|
||||
}
|
||||
_output_filter_aligned = false;
|
||||
}
|
||||
|
||||
void OutputPredictor::resetQuaternion(const Quatf &quat_change)
|
||||
void OutputPredictor::resetQuaternion(const uint64_t time_delayed_us, const Quatf &new_quat)
|
||||
{
|
||||
const outputSample &output_delayed = _output_buffer.get_oldest();
|
||||
const Quatf quat_change{(new_quat * output_delayed.quat_nominal.inversed()).normalized()};
|
||||
const Dcmf rot_change{quat_change};
|
||||
|
||||
// add the reset amount to the output observer buffered data
|
||||
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
|
||||
_output_buffer[i].quat_nominal = quat_change * _output_buffer[i].quat_nominal;
|
||||
_output_buffer[i].quat_nominal = (quat_change * _output_buffer[i].quat_nominal).normalized();
|
||||
|
||||
// apply change to velocity
|
||||
_output_buffer[i].vel = rot_change * _output_buffer[i].vel;
|
||||
_output_buffer[i].vel_alternative = rot_change * _output_buffer[i].vel_alternative;
|
||||
}
|
||||
|
||||
// apply the change in attitude quaternion to our newest quaternion estimate
|
||||
// which was already taken out from the output buffer
|
||||
_output_new.quat_nominal = quat_change * _output_new.quat_nominal;
|
||||
_output_new.quat_nominal = (quat_change * _output_new.quat_nominal).normalized();
|
||||
_R_to_earth_now = Dcmf(_output_new.quat_nominal);
|
||||
|
||||
// apply change to velocity
|
||||
_output_new.vel = rot_change * _output_new.vel;
|
||||
_output_new.vel_alternative = rot_change * _output_new.vel_alternative;
|
||||
|
||||
propagateVelocityUpdateToPosition();
|
||||
}
|
||||
|
||||
void OutputPredictor::resetHorizontalVelocityTo(const Vector2f &delta_horz_vel)
|
||||
void OutputPredictor::resetHorizontalVelocityTo(const uint64_t time_delayed_us, const Vector2f &new_horz_vel)
|
||||
{
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].vel.xy() += delta_horz_vel;
|
||||
// TODO: review time_us
|
||||
|
||||
if (_output_buffer.get_oldest().time_us != time_delayed_us) {
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
_output_new.vel.xy() += delta_horz_vel;
|
||||
}
|
||||
|
||||
void OutputPredictor::resetVerticalVelocityTo(float delta_vert_vel)
|
||||
{
|
||||
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;
|
||||
const outputSample &output_delayed = _output_buffer.get_oldest();
|
||||
|
||||
// horizontal velocity
|
||||
{
|
||||
const Vector2f delta_vxy = new_horz_vel - Vector2f(output_delayed.vel.xy());
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].vel.xy() += delta_vxy;
|
||||
}
|
||||
|
||||
_output_new.vel.xy() += delta_vxy;
|
||||
}
|
||||
|
||||
_output_new.vel(2) += delta_vert_vel;
|
||||
_output_vert_new.vert_vel += delta_vert_vel;
|
||||
}
|
||||
// horizontal velocity (alternative)
|
||||
{
|
||||
const Vector2f delta_vxy = new_horz_vel - Vector2f(output_delayed.vel_alternative.xy());
|
||||
|
||||
void OutputPredictor::resetHorizontalPositionTo(const Vector2f &delta_horz_pos)
|
||||
{
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].pos.xy() += delta_horz_pos;
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].vel_alternative.xy() += delta_vxy;
|
||||
}
|
||||
|
||||
_output_new.vel_alternative.xy() += delta_vxy;
|
||||
}
|
||||
|
||||
_output_new.pos.xy() += delta_horz_pos;
|
||||
// propagate position forward using the reset velocity
|
||||
propagateVelocityUpdateToPosition();
|
||||
}
|
||||
|
||||
void OutputPredictor::resetVerticalPositionTo(const float new_vert_pos, const float vert_pos_change)
|
||||
void OutputPredictor::resetVerticalVelocityTo(const uint64_t time_delayed_us, const float new_vert_vel)
|
||||
{
|
||||
// apply the change in height / height rate to our newest height / height rate estimate
|
||||
// which have already been taken out from the output buffer
|
||||
_output_new.pos(2) += vert_pos_change;
|
||||
const outputSample &output_delayed = _output_buffer.get_oldest();
|
||||
|
||||
// add the reset amount to the output observer buffered data
|
||||
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
|
||||
_output_buffer[i].pos(2) += vert_pos_change;
|
||||
_output_vert_buffer[i].vert_vel_integ += vert_pos_change;
|
||||
// vertical velocity
|
||||
{
|
||||
const float delta_z = new_vert_vel - output_delayed.vel(2);
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].vel(2) += delta_z;
|
||||
}
|
||||
|
||||
_output_new.vel(2) += delta_z;
|
||||
}
|
||||
|
||||
// add the reset amount to the output observer vertical position state
|
||||
_output_vert_new.vert_vel_integ = new_vert_pos;
|
||||
// vertical velocity (alternative)
|
||||
{
|
||||
const float delta_z = new_vert_vel - output_delayed.vel_alternative(2);
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].vel_alternative(2) += delta_z;
|
||||
}
|
||||
|
||||
_output_new.vel_alternative(2) += delta_z;
|
||||
}
|
||||
|
||||
// propagate vertical position forward using the reset velocity
|
||||
propagateVelocityUpdateToPosition();
|
||||
}
|
||||
|
||||
void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector3f &delta_angle,
|
||||
void OutputPredictor::resetHorizontalPositionTo(const uint64_t time_delayed_us, const Vector2f &new_horz_pos)
|
||||
{
|
||||
const outputSample &output_delayed = _output_buffer.get_oldest();
|
||||
|
||||
// horizontal position
|
||||
{
|
||||
const Vector2f delta_xy = new_horz_pos - output_delayed.pos.xy();
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].pos.xy() += delta_xy;
|
||||
}
|
||||
|
||||
_output_new.pos.xy() += delta_xy;
|
||||
}
|
||||
|
||||
// horizontal position (alternative)
|
||||
{
|
||||
const Vector2f delta_xy = new_horz_pos - output_delayed.vel_alternative_integ.xy();
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].vel_alternative_integ.xy() += delta_xy;
|
||||
}
|
||||
|
||||
_output_new.vel_alternative_integ.xy() += delta_xy;
|
||||
}
|
||||
}
|
||||
|
||||
void OutputPredictor::resetVerticalPositionTo(const uint64_t time_delayed_us, const float new_vert_pos)
|
||||
{
|
||||
const outputSample &output_delayed = _output_buffer.get_oldest();
|
||||
|
||||
// vertical position
|
||||
{
|
||||
const float delta_z = new_vert_pos - output_delayed.pos(2);
|
||||
|
||||
// add the reset amount to the output observer buffered data
|
||||
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
|
||||
_output_buffer[i].pos(2) += delta_z;
|
||||
}
|
||||
|
||||
// apply the change in height / height rate to our newest height / height rate estimate
|
||||
// which have already been taken out from the output buffer
|
||||
_output_new.pos(2) += delta_z;
|
||||
}
|
||||
|
||||
// vertical position (alternative)
|
||||
{
|
||||
const float delta_z = new_vert_pos - output_delayed.vel_alternative_integ(2);
|
||||
|
||||
// add the reset amount to the output observer buffered data
|
||||
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
|
||||
_output_buffer[i].vel_alternative_integ(2) += delta_z;
|
||||
}
|
||||
|
||||
// add the reset amount to the output observer vertical position state
|
||||
_output_new.vel_alternative_integ(2) += delta_z;
|
||||
}
|
||||
}
|
||||
|
||||
bool OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector3f &delta_angle,
|
||||
const float delta_angle_dt, const Vector3f &delta_velocity, const float delta_velocity_dt)
|
||||
{
|
||||
if (time_us <= _time_last_update_states_us) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Use full rate IMU data at the current time horizon
|
||||
if (_time_last_update_states_us != 0) {
|
||||
const float dt = math::constrain((time_us - _time_last_update_states_us) * 1e-6f, 0.0001f, 0.03f);
|
||||
|
@ -185,18 +253,11 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector
|
|||
const Vector3f delta_velocity_corrected(delta_velocity - delta_vel_bias_scaled);
|
||||
|
||||
_output_new.time_us = time_us;
|
||||
_output_vert_new.time_us = time_us;
|
||||
|
||||
const Quatf dq(AxisAnglef{delta_angle_corrected});
|
||||
|
||||
// rotate the previous INS quaternion by the delta quaternions
|
||||
_output_new.quat_nominal = _output_new.quat_nominal * dq;
|
||||
|
||||
// the quaternions must always be normalised after modification
|
||||
_output_new.quat_nominal.normalize();
|
||||
|
||||
// calculate the rotation matrix from body to earth frame
|
||||
_R_to_earth_now = Dcmf(_output_new.quat_nominal);
|
||||
const Quatf dq(AxisAnglef{delta_angle_corrected});
|
||||
_output_new.quat_nominal = (_output_new.quat_nominal * dq).normalized();
|
||||
_R_to_earth_now = Dcmf(_output_new.quat_nominal); // calculate the rotation matrix from body to earth frame
|
||||
|
||||
// rotate the delta velocity to earth frame
|
||||
Vector3f delta_vel_earth{_R_to_earth_now * delta_velocity_corrected};
|
||||
|
@ -215,16 +276,16 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector
|
|||
// increment the INS velocity states by the measurement plus corrections
|
||||
// do the same for vertical state used by alternative correction algorithm
|
||||
_output_new.vel += delta_vel_earth;
|
||||
_output_vert_new.vert_vel += delta_vel_earth(2);
|
||||
_output_new.vel_alternative += delta_vel_earth;
|
||||
|
||||
// use trapezoidal integration to calculate the INS position states
|
||||
// do the same for vertical state used by alternative correction algorithm
|
||||
const Vector3f delta_pos_NED = (_output_new.vel + vel_last) * (delta_velocity_dt * 0.5f);
|
||||
_output_new.pos += delta_pos_NED;
|
||||
_output_vert_new.vert_vel_integ += delta_pos_NED(2);
|
||||
_output_new.vel_alternative_integ += delta_pos_NED;
|
||||
|
||||
// accumulate the time for each update
|
||||
_output_vert_new.dt += delta_velocity_dt;
|
||||
_output_new.dt += delta_velocity_dt;
|
||||
|
||||
// correct velocity for IMU offset
|
||||
if (delta_angle_dt > 0.001f) {
|
||||
|
@ -237,137 +298,258 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector
|
|||
// rotate the relative velocity into earth frame
|
||||
_vel_imu_rel_body_ned = _R_to_earth_now * vel_imu_rel_body;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us,
|
||||
const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias)
|
||||
const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state,
|
||||
const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias)
|
||||
{
|
||||
// calculate an average filter update time
|
||||
if (_time_last_correct_states_us != 0) {
|
||||
const float dt = math::constrain((time_delayed_us - _time_last_correct_states_us) * 1e-6f, 0.0001f, 0.03f);
|
||||
_dt_correct_states_avg = 0.8f * _dt_correct_states_avg + 0.2f * dt;
|
||||
const uint64_t time_latest_us = _time_last_update_states_us;
|
||||
|
||||
if (time_latest_us <= time_delayed_us) {
|
||||
return;
|
||||
}
|
||||
|
||||
_time_last_correct_states_us = time_delayed_us;
|
||||
// store the INS states in a ring buffer with the same length and time coordinates as the IMU data buffer
|
||||
if (_output_new.dt > 0.f) {
|
||||
_output_buffer.push(_output_new);
|
||||
_output_new.dt = 0.0f; // reset time delta to zero for the next accumulation of full rate IMU data
|
||||
}
|
||||
|
||||
// store IMU bias for calculateOutputStates
|
||||
_gyro_bias = gyro_bias;
|
||||
_accel_bias = accel_bias;
|
||||
|
||||
// store the INS states in a ring buffer with the same length and time coordinates as the IMU data buffer
|
||||
_output_buffer.push(_output_new);
|
||||
_output_vert_buffer.push(_output_vert_new);
|
||||
// calculate an average filter update time
|
||||
if ((_time_last_correct_states_us != 0) && (time_delayed_us > _time_last_correct_states_us)) {
|
||||
const float dt = math::constrain((time_delayed_us - _time_last_correct_states_us) * 1e-6f, 0.0001f, 0.03f);
|
||||
_dt_correct_states_avg = 0.8f * _dt_correct_states_avg + 0.2f * dt;
|
||||
|
||||
} else {
|
||||
if (!_output_filter_aligned) {
|
||||
resetQuaternion(time_delayed_us, quat_state);
|
||||
resetHorizontalVelocityTo(time_delayed_us, vel_state.xy());
|
||||
resetVerticalVelocityTo(time_delayed_us, vel_state(2));
|
||||
resetHorizontalPositionTo(time_delayed_us, pos_state.xy());
|
||||
resetVerticalPositionTo(time_delayed_us, pos_state(2));
|
||||
}
|
||||
|
||||
_time_last_correct_states_us = time_delayed_us;
|
||||
return;
|
||||
}
|
||||
|
||||
_time_last_correct_states_us = time_delayed_us;
|
||||
|
||||
// get the oldest INS state data from the ring buffer
|
||||
// this data will be at the EKF fusion time horizon
|
||||
// TODO: there is no guarantee that data is at delayed fusion horizon
|
||||
// Shouldnt we use pop_first_older_than?
|
||||
const outputSample &output_delayed = _output_buffer.get_oldest();
|
||||
const outputVert &output_vert_delayed = _output_vert_buffer.get_oldest();
|
||||
outputSample output_delayed;
|
||||
|
||||
// calculate the quaternion delta between the INS and EKF quaternions at the EKF fusion time horizon
|
||||
const Quatf q_error((quat_state.inversed() * output_delayed.quat_nominal).normalized());
|
||||
while (_output_buffer.pop_first_older_than(time_delayed_us, &output_delayed)) {
|
||||
|
||||
// convert the quaternion delta to a delta angle
|
||||
const float scalar = (q_error(0) >= 0.0f) ? -2.f : 2.f;
|
||||
|
||||
const Vector3f delta_ang_error{scalar * q_error(1), scalar * q_error(2), scalar * q_error(3)};
|
||||
|
||||
// calculate a gain that provides tight tracking of the estimator attitude states and
|
||||
// adjust for changes in time delay to maintain consistent damping ratio of ~0.7
|
||||
const uint64_t time_latest_us = _time_last_update_states_us;
|
||||
const float time_delay = fmaxf((time_latest_us - time_delayed_us) * 1e-6f, _dt_update_states_avg);
|
||||
const float att_gain = 0.5f * _dt_update_states_avg / time_delay;
|
||||
|
||||
// calculate a corrrection to the delta angle
|
||||
// that will cause the INS to track the EKF quaternions
|
||||
_delta_angle_corr = delta_ang_error * att_gain;
|
||||
_output_tracking_error(0) = delta_ang_error.norm();
|
||||
|
||||
/*
|
||||
* Loop through the output filter state history and apply the corrections to the velocity and position states.
|
||||
* This method is too expensive to use for the attitude states due to the quaternion operations required
|
||||
* but because it eliminates the time delay in the 'correction loop' it allows higher tracking gains
|
||||
* to be used and reduces tracking error relative to EKF states.
|
||||
*/
|
||||
|
||||
// Complementary filter gains
|
||||
const float vel_gain = _dt_correct_states_avg / math::constrain(_vel_tau, _dt_correct_states_avg, 10.f);
|
||||
const float pos_gain = _dt_correct_states_avg / math::constrain(_pos_tau, _dt_correct_states_avg, 10.f);
|
||||
|
||||
// calculate down velocity and position tracking errors
|
||||
const float vert_vel_err = (vel_state(2) - output_vert_delayed.vert_vel);
|
||||
const float vert_vel_integ_err = (pos_state(2) - output_vert_delayed.vert_vel_integ);
|
||||
|
||||
// calculate a velocity correction that will be applied to the output state history
|
||||
// using a PD feedback tuned to a 5% overshoot
|
||||
const float vert_vel_correction = vert_vel_integ_err * pos_gain + vert_vel_err * vel_gain * 1.1f;
|
||||
|
||||
applyCorrectionToVerticalOutputBuffer(vert_vel_correction);
|
||||
|
||||
// calculate velocity and position tracking errors
|
||||
const Vector3f vel_err(vel_state - output_delayed.vel);
|
||||
const Vector3f pos_err(pos_state - output_delayed.pos);
|
||||
|
||||
_output_tracking_error(1) = vel_err.norm();
|
||||
_output_tracking_error(2) = pos_err.norm();
|
||||
|
||||
// calculate a velocity correction that will be applied to the output state history
|
||||
_vel_err_integ += vel_err;
|
||||
const Vector3f vel_correction = vel_err * vel_gain + _vel_err_integ * sq(vel_gain) * 0.1f;
|
||||
|
||||
// calculate a position correction that will be applied to the output state history
|
||||
_pos_err_integ += pos_err;
|
||||
const Vector3f pos_correction = pos_err * pos_gain + _pos_err_integ * sq(pos_gain) * 0.1f;
|
||||
|
||||
applyCorrectionToOutputBuffer(vel_correction, pos_correction);
|
||||
}
|
||||
|
||||
void OutputPredictor::applyCorrectionToVerticalOutputBuffer(float vert_vel_correction)
|
||||
{
|
||||
// loop through the vertical output filter state history starting at the oldest and apply the corrections to the
|
||||
// vert_vel states and propagate vert_vel_integ forward using the corrected vert_vel
|
||||
uint8_t index = _output_vert_buffer.get_oldest_index();
|
||||
|
||||
const uint8_t size = _output_vert_buffer.get_length();
|
||||
|
||||
for (uint8_t counter = 0; counter < (size - 1); counter++) {
|
||||
const uint8_t index_next = (index + 1) % size;
|
||||
outputVert ¤t_state = _output_vert_buffer[index];
|
||||
outputVert &next_state = _output_vert_buffer[index_next];
|
||||
|
||||
// correct the velocity
|
||||
if (counter == 0) {
|
||||
current_state.vert_vel += vert_vel_correction;
|
||||
if (output_delayed.time_us != time_delayed_us) {
|
||||
continue;
|
||||
}
|
||||
|
||||
next_state.vert_vel += vert_vel_correction;
|
||||
if (!_output_filter_aligned) {
|
||||
|
||||
// position is propagated forward using the corrected velocity and a trapezoidal integrator
|
||||
next_state.vert_vel_integ = current_state.vert_vel_integ + (current_state.vert_vel + next_state.vert_vel) * 0.5f * next_state.dt;
|
||||
// calculate the quaternion rotation delta from the EKF to output observer states at the EKF fusion time horizon
|
||||
const Quatf q_delta((quat_state * output_delayed.quat_nominal.inversed()).normalized());
|
||||
const Dcmf rot_change{q_delta};
|
||||
|
||||
// add the reset amount to the output observer buffered data
|
||||
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
|
||||
|
||||
_output_buffer[i].quat_nominal = (q_delta * _output_buffer[i].quat_nominal).normalized();
|
||||
|
||||
// apply change to velocity
|
||||
_output_buffer[i].vel = rot_change * _output_buffer[i].vel;
|
||||
_output_buffer[i].vel_alternative = rot_change * _output_buffer[i].vel_alternative;
|
||||
}
|
||||
|
||||
// apply the change in attitude quaternion to our newest quaternion estimate
|
||||
_output_new.quat_nominal = (q_delta * _output_new.quat_nominal).normalized();
|
||||
|
||||
|
||||
// apply change to velocity
|
||||
_output_new.vel = rot_change * _output_new.vel;
|
||||
_output_new.vel_alternative = rot_change * _output_new.vel_alternative;
|
||||
|
||||
propagateVelocityUpdateToPosition();
|
||||
|
||||
|
||||
// calculate the velocity and position deltas between the output and EKF at the EKF fusion time horizon
|
||||
output_delayed.vel = q_delta.rotateVectorInverse(output_delayed.vel);
|
||||
const Vector3f vel_err = vel_state - output_delayed.vel;
|
||||
|
||||
output_delayed.vel_alternative = q_delta.rotateVectorInverse(output_delayed.vel_alternative);
|
||||
const Vector3f vel_alternative_err = vel_state - output_delayed.vel_alternative;
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
// a constant velocity correction is applied
|
||||
_output_buffer[index].vel += vel_err;
|
||||
_output_buffer[index].vel_alternative += vel_alternative_err;
|
||||
}
|
||||
|
||||
// manually correct next oldest state
|
||||
// position is propagated forward using the corrected velocity and a trapezoidal integrator
|
||||
uint8_t index = _output_buffer.get_oldest_index();
|
||||
outputSample &next_oldest_state = _output_buffer[index];
|
||||
|
||||
if ((next_oldest_state.time_us > output_delayed.time_us) && (next_oldest_state.dt > 0.f)) {
|
||||
|
||||
next_oldest_state.pos = pos_state + (vel_state + next_oldest_state.vel) * 0.5f * next_oldest_state.dt;
|
||||
next_oldest_state.vel_alternative_integ = pos_state + (vel_state + next_oldest_state.vel_alternative) * 0.5f *
|
||||
next_oldest_state.dt;
|
||||
|
||||
propagateVelocityUpdateToPosition();
|
||||
}
|
||||
|
||||
_output_new = _output_buffer.get_newest();
|
||||
_output_new.dt = 0.0f;
|
||||
|
||||
// reset tracking error, integral, etc
|
||||
_output_tracking_error.zero();
|
||||
_delta_angle_corr.zero();
|
||||
_vel_err_integ.zero();
|
||||
_pos_err_integ.zero();
|
||||
|
||||
_output_filter_aligned = true;
|
||||
|
||||
} else {
|
||||
|
||||
/*
|
||||
* Loop through the output filter state history and apply the corrections to the velocity and position states.
|
||||
* This method is too expensive to use for the attitude states due to the quaternion operations required
|
||||
* but because it eliminates the time delay in the 'correction loop' it allows higher tracking gains
|
||||
* to be used and reduces tracking error relative to EKF states.
|
||||
*/
|
||||
|
||||
// calculate the quaternion delta between the INS and EKF quaternions at the EKF fusion time horizon
|
||||
const Quatf q_error((quat_state.inversed() * output_delayed.quat_nominal).normalized());
|
||||
|
||||
// convert the quaternion delta to a delta angle
|
||||
const float scalar = (q_error(0) >= 0.0f) ? -2.f : 2.f;
|
||||
|
||||
const Vector3f delta_ang_error{scalar * q_error(1), scalar * q_error(2), scalar * q_error(3)};
|
||||
|
||||
// calculate a gain that provides tight tracking of the estimator attitude states and
|
||||
// adjust for changes in time delay to maintain consistent damping ratio of ~0.7
|
||||
|
||||
const float time_delay = fmaxf((time_latest_us - time_delayed_us) * 1e-6f, _dt_update_states_avg);
|
||||
const float att_gain = 0.5f * _dt_update_states_avg / time_delay;
|
||||
|
||||
// calculate a corrrection to the delta angle
|
||||
// that will cause the INS to track the EKF quaternions
|
||||
_delta_angle_corr = delta_ang_error * att_gain;
|
||||
_output_tracking_error(0) = delta_ang_error.norm();
|
||||
|
||||
|
||||
/*
|
||||
* Calculate corrections to be applied to vel and pos output state history.
|
||||
* The vel and pos state history are corrected individually so they track the EKF states at
|
||||
* the fusion time horizon. This option provides the most accurate tracking of EKF states.
|
||||
*/
|
||||
|
||||
// calculate velocity tracking errors
|
||||
const Vector3f vel_err = vel_state - output_delayed.vel;
|
||||
_output_tracking_error(1) = vel_err.norm();
|
||||
// calculate a velocity correction that will be applied to the output state history
|
||||
const float vel_gain = _dt_correct_states_avg / math::constrain(_vel_tau, _dt_correct_states_avg,
|
||||
10.f); // Complementary filter gains
|
||||
_vel_err_integ += vel_err;
|
||||
const Vector3f vel_correction = vel_err * vel_gain + _vel_err_integ * sq(vel_gain) * 0.1f;
|
||||
|
||||
// calculate position tracking errors
|
||||
const Vector3f pos_err = pos_state - output_delayed.pos;
|
||||
_output_tracking_error(2) = pos_err.norm();
|
||||
// calculate a position correction that will be applied to the output state history
|
||||
const float pos_gain = _dt_correct_states_avg / math::constrain(_pos_tau, _dt_correct_states_avg,
|
||||
10.f); // Complementary filter gains
|
||||
_pos_err_integ += pos_err;
|
||||
const Vector3f pos_correction = pos_err * pos_gain + _pos_err_integ * sq(pos_gain) * 0.1f;
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
// a constant velocity correction is applied
|
||||
_output_buffer[index].vel += vel_correction;
|
||||
_output_buffer[index].pos += pos_correction;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Calculate a correction to be applied to vel_alternative that casues vel_alternative_integ to track the EKF
|
||||
* position state at the fusion time horizon using an alternative algorithm to what
|
||||
* is used for the vel and pos state tracking. The algorithm applies a correction to the vel_alternative
|
||||
* state history and propagates vel_alternative_integ forward in time using the corrected vel_alternative history.
|
||||
* This provides an alternative velocity output that is closer to the first derivative
|
||||
* of the position but does degrade tracking relative to the EKF state.
|
||||
*/
|
||||
|
||||
// vel alternative: calculate velocity and position tracking errors
|
||||
const Vector3f vel_alternative_err = (vel_state - output_delayed.vel_alternative);
|
||||
const Vector3f vel_alternative_integ_err = (pos_state - output_delayed.vel_alternative_integ);
|
||||
|
||||
// calculate a velocity correction that will be applied to the output state history
|
||||
// using a PD feedback tuned to a 5% overshoot
|
||||
const Vector3f vel_alternative_correction = vel_alternative_integ_err * pos_gain + vel_alternative_err * vel_gain *
|
||||
1.1f;
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
// a constant velocity correction is applied
|
||||
_output_buffer[index].vel_alternative += vel_alternative_correction;
|
||||
_output_buffer[index].vel_alternative_integ += vel_alternative_integ_err;
|
||||
}
|
||||
|
||||
// recompute position by integrating velocity
|
||||
propagateVelocityUpdateToPosition();
|
||||
}
|
||||
}
|
||||
|
||||
_output_new = _output_buffer.get_newest();
|
||||
_output_new.dt = 0.f;
|
||||
|
||||
_R_to_earth_now = Dcmf(_output_new.quat_nominal);
|
||||
}
|
||||
|
||||
void OutputPredictor::propagateVelocityUpdateToPosition()
|
||||
{
|
||||
// propagate position forward using the reset velocity
|
||||
uint8_t index = _output_buffer.get_oldest_index();
|
||||
const uint8_t size = _output_buffer.get_length();
|
||||
|
||||
for (uint8_t counter = 0; counter < (size - 1); counter++) {
|
||||
|
||||
const outputSample ¤t_state = _output_buffer[index];
|
||||
|
||||
// next state
|
||||
const uint8_t index_next = (index + 1) % size;
|
||||
outputSample &next_state = _output_buffer[index_next];
|
||||
|
||||
if ((next_state.time_us > current_state.time_us) && (next_state.dt > 0.f)) {
|
||||
// position is propagated forward using the corrected velocity and a trapezoidal integrator
|
||||
next_state.pos = current_state.pos + (current_state.vel + next_state.vel) * 0.5f * next_state.dt;
|
||||
next_state.vel_alternative_integ = current_state.vel_alternative_integ + (current_state.vel_alternative +
|
||||
next_state.vel_alternative) * 0.5f * next_state.dt;
|
||||
}
|
||||
|
||||
// advance the index
|
||||
index = (index + 1) % size;
|
||||
}
|
||||
|
||||
// update output state to corrected values
|
||||
_output_vert_new = _output_vert_buffer.get_newest();
|
||||
if ((_output_new.time_us > _output_buffer.get_newest().time_us) && (_output_new.dt > 0.f)) {
|
||||
// position is propagated forward using the corrected velocity and a trapezoidal integrator
|
||||
_output_new.pos = _output_buffer.get_newest().pos
|
||||
+ (_output_buffer.get_newest().vel + _output_new.vel) * 0.5f * _output_new.dt;
|
||||
|
||||
// reset time delta to zero for the next accumulation of full rate IMU data
|
||||
_output_vert_new.dt = 0.0f;
|
||||
}
|
||||
_output_new.vel_alternative_integ = _output_buffer.get_newest().vel_alternative_integ +
|
||||
(_output_buffer.get_newest().vel_alternative + _output_new.vel_alternative) * 0.5f * _output_new.dt;
|
||||
|
||||
void OutputPredictor::applyCorrectionToOutputBuffer(const Vector3f &vel_correction, const Vector3f &pos_correction)
|
||||
{
|
||||
// loop through the output filter state history and apply the corrections to the velocity and position states
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
// a constant velocity correction is applied
|
||||
_output_buffer[index].vel += vel_correction;
|
||||
} else {
|
||||
// update output state to corrected values
|
||||
_output_new = _output_buffer.get_newest();
|
||||
|
||||
// a constant position correction is applied
|
||||
_output_buffer[index].pos += pos_correction;
|
||||
// reset time delta to zero for the next accumulation of full rate IMU data
|
||||
_output_new.dt = 0.0f;
|
||||
}
|
||||
|
||||
// update output state to corrected values
|
||||
_output_new = _output_buffer.get_newest();
|
||||
}
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2022 PX4. All rights reserved.
|
||||
* Copyright (c) 2022-2023 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -51,9 +51,6 @@ public:
|
|||
|
||||
~OutputPredictor() = default;
|
||||
|
||||
// modify output filter to match the the EKF state at the fusion time horizon
|
||||
void alignOutputFilter(const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state,
|
||||
const matrix::Vector3f &pos_state);
|
||||
/*
|
||||
* Implement a strapdown INS algorithm using the latest IMU data at the current time horizon.
|
||||
* Buffer the INS states and calculate the difference with the EKF states at the delayed fusion time horizon.
|
||||
|
@ -64,25 +61,26 @@ public:
|
|||
* “Recursive Attitude Estimation in the Presence of Multi-rate and Multi-delay Vector Measurements”
|
||||
* A Khosravian, J Trumpf, R Mahony, T Hamel, Australian National University
|
||||
*/
|
||||
void calculateOutputStates(const uint64_t time_us, const matrix::Vector3f &delta_angle, const float delta_angle_dt,
|
||||
bool calculateOutputStates(const uint64_t time_us, const matrix::Vector3f &delta_angle, const float delta_angle_dt,
|
||||
const matrix::Vector3f &delta_velocity, const float delta_velocity_dt);
|
||||
|
||||
void correctOutputStates(const uint64_t time_delayed_us,
|
||||
const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const matrix::Vector3f &pos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias);
|
||||
const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const matrix::Vector3f &pos_state,
|
||||
const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias);
|
||||
|
||||
void resetQuaternion(const matrix::Quatf &quat_change);
|
||||
void resetQuaternion(const uint64_t time_delayed_us, const matrix::Quatf &new_quat);
|
||||
|
||||
void resetHorizontalVelocityTo(const matrix::Vector2f &delta_horz_vel);
|
||||
void resetVerticalVelocityTo(float delta_vert_vel);
|
||||
void resetHorizontalVelocityTo(const uint64_t time_delayed_us, const matrix::Vector2f &new_horz_vel);
|
||||
void resetVerticalVelocityTo(const uint64_t time_delayed_us, const float new_vert_vel);
|
||||
|
||||
void resetHorizontalPositionTo(const matrix::Vector2f &delta_horz_pos);
|
||||
void resetVerticalPositionTo(const float new_vert_pos, const float vert_pos_change);
|
||||
void resetHorizontalPositionTo(const uint64_t time_delayed_us, const matrix::Vector2f &new_horz_pos);
|
||||
void resetVerticalPositionTo(const uint64_t time_delayed_us, const float new_vert_pos);
|
||||
|
||||
void print_status();
|
||||
|
||||
bool allocate(uint8_t size)
|
||||
{
|
||||
if (_output_buffer.allocate(size) && _output_vert_buffer.allocate(size)) {
|
||||
if (_output_buffer.allocate(size)) {
|
||||
reset();
|
||||
return true;
|
||||
}
|
||||
|
@ -101,7 +99,7 @@ public:
|
|||
const matrix::Vector3f &getVelocityDerivative() const { return _vel_deriv; }
|
||||
|
||||
// get the derivative of the vertical position of the body frame origin in local NED earth frame
|
||||
float getVerticalPositionDerivative() const { return _output_vert_new.vert_vel - _vel_imu_rel_body_ned(2); }
|
||||
float getVerticalPositionDerivative() const { return _output_new.vel_alternative(2) - _vel_imu_rel_body_ned(2); }
|
||||
|
||||
// get the position of the body frame origin in local earth frame
|
||||
matrix::Vector3f getPosition() const
|
||||
|
@ -116,48 +114,32 @@ public:
|
|||
// error magnitudes (rad), (m/sec), (m)
|
||||
const matrix::Vector3f &getOutputTrackingError() const { return _output_tracking_error; }
|
||||
|
||||
bool aligned() const { return _output_filter_aligned; }
|
||||
|
||||
void set_imu_offset(const matrix::Vector3f &offset) { _imu_pos_body = offset; }
|
||||
void set_pos_correction_tc(const float tau) { _pos_tau = tau; }
|
||||
void set_vel_correction_tc(const float tau) { _vel_tau = tau; }
|
||||
|
||||
private:
|
||||
|
||||
/*
|
||||
* Calculate a correction to be applied to vert_vel that casues vert_vel_integ to track the EKF
|
||||
* down position state at the fusion time horizon using an alternative algorithm to what
|
||||
* is used for the vel and pos state tracking. The algorithm applies a correction to the vert_vel
|
||||
* state history and propagates vert_vel_integ forward in time using the corrected vert_vel history.
|
||||
* This provides an alternative vertical velocity output that is closer to the first derivative
|
||||
* of the position but does degrade tracking relative to the EKF state.
|
||||
*/
|
||||
void applyCorrectionToVerticalOutputBuffer(float vert_vel_correction);
|
||||
|
||||
/*
|
||||
* Calculate corrections to be applied to vel and pos output state history.
|
||||
* The vel and pos state history are corrected individually so they track the EKF states at
|
||||
* the fusion time horizon. This option provides the most accurate tracking of EKF states.
|
||||
*/
|
||||
void applyCorrectionToOutputBuffer(const matrix::Vector3f &vel_correction, const matrix::Vector3f &pos_correction);
|
||||
void propagateVelocityUpdateToPosition();
|
||||
|
||||
// return the square of two floating point numbers - used in auto coded sections
|
||||
static constexpr float sq(float var) { return var * var; }
|
||||
|
||||
struct outputSample {
|
||||
uint64_t time_us{0}; ///< timestamp of the measurement (uSec)
|
||||
matrix::Quatf quat_nominal{1.f, 0.f, 0.f, 0.f}; ///< nominal quaternion describing vehicle attitude
|
||||
matrix::Vector3f vel{0.f, 0.f, 0.f}; ///< NED velocity estimate in earth frame (m/sec)
|
||||
matrix::Vector3f pos{0.f, 0.f, 0.f}; ///< NED position estimate in earth frame (m/sec)
|
||||
};
|
||||
uint64_t time_us{0}; ///< timestamp of the measurement (uSec)
|
||||
matrix::Quatf quat_nominal{1.f, 0.f, 0.f, 0.f}; ///< nominal quaternion describing vehicle attitude
|
||||
matrix::Vector3f vel{0.f, 0.f, 0.f}; ///< NED velocity estimate in earth frame (m/sec)
|
||||
matrix::Vector3f pos{0.f, 0.f, 0.f}; ///< NED position estimate in earth frame (m/sec)
|
||||
|
||||
struct outputVert {
|
||||
uint64_t time_us{0}; ///< timestamp of the measurement (uSec)
|
||||
float vert_vel{0.f}; ///< Vertical velocity calculated using alternative algorithm (m/sec)
|
||||
float vert_vel_integ{0.f}; ///< Integral of vertical velocity (m)
|
||||
float dt{0.f}; ///< delta time (sec)
|
||||
matrix::Vector3f vel_alternative{0.f, 0.f, 0.f}; ///< NED velocity calculated using alternative algorithm (m/sec)
|
||||
matrix::Vector3f vel_alternative_integ{0.f, 0.f, 0.f}; ///< NED integral of velocity (m)
|
||||
|
||||
float dt{0.f}; ///< delta time (sec)
|
||||
};
|
||||
|
||||
RingBuffer<outputSample> _output_buffer{12};
|
||||
RingBuffer<outputVert> _output_vert_buffer{12};
|
||||
|
||||
matrix::Vector3f _accel_bias{};
|
||||
matrix::Vector3f _gyro_bias{};
|
||||
|
@ -170,7 +152,6 @@ private:
|
|||
|
||||
// Output Predictor
|
||||
outputSample _output_new{}; // filter output on the non-delayed time horizon
|
||||
outputVert _output_vert_new{}; // vertical filter output on the non-delayed time horizon
|
||||
matrix::Matrix3f _R_to_earth_now{}; // rotation matrix from body to earth frame at current time
|
||||
matrix::Vector3f _vel_imu_rel_body_ned{}; // velocity of IMU relative to body origin in NED earth frame
|
||||
matrix::Vector3f _vel_deriv{}; // velocity derivative at the IMU in NED earth frame (m/s/s)
|
||||
|
@ -182,6 +163,8 @@ private:
|
|||
|
||||
matrix::Vector3f _output_tracking_error{}; ///< contains the magnitude of the angle, velocity and position track errors (rad, m/s, m)
|
||||
|
||||
bool _output_filter_aligned{false};
|
||||
|
||||
matrix::Vector3f _imu_pos_body{}; ///< xyz position of IMU in body frame (m)
|
||||
|
||||
// output complementary filter tuning
|
||||
|
|
|
@ -690,12 +690,24 @@ void EKF2::Run()
|
|||
if (_ekf.update()) {
|
||||
perf_set_elapsed(_ecl_ekf_update_full_perf, hrt_elapsed_time(&ekf_update_start));
|
||||
|
||||
PublishLocalPosition(now);
|
||||
PublishOdometry(now, imu_sample_new);
|
||||
PublishGlobalPosition(now);
|
||||
if (_ekf.attitude_valid() && _ekf.output_predictor().aligned()) {
|
||||
// publish output predictor output
|
||||
PublishLocalPosition(now);
|
||||
PublishOdometry(now, imu_sample_new);
|
||||
PublishGlobalPosition(now);
|
||||
}
|
||||
|
||||
// online accel/gyro/mag calibration
|
||||
UpdateAccelCalibration(now);
|
||||
UpdateGyroCalibration(now);
|
||||
UpdateMagCalibration(now);
|
||||
|
||||
// publish other state output used by the system not dependent on output predictor
|
||||
PublishSensorBias(now);
|
||||
PublishWindEstimate(now);
|
||||
|
||||
// publish status/logging messages
|
||||
PublishAidSourceStatus(now);
|
||||
PublishBaroBias(now);
|
||||
PublishGnssHgtBias(now);
|
||||
#if defined(CONFIG_EKF2_RANGE_FINDER)
|
||||
|
@ -717,13 +729,6 @@ void EKF2::Run()
|
|||
PublishStatusFlags(now);
|
||||
PublishYawEstimatorStatus(now);
|
||||
|
||||
UpdateAccelCalibration(now);
|
||||
UpdateGyroCalibration(now);
|
||||
UpdateMagCalibration(now);
|
||||
PublishSensorBias(now);
|
||||
|
||||
PublishAidSourceStatus(now);
|
||||
|
||||
} else {
|
||||
// ekf no update
|
||||
perf_set_elapsed(_ecl_ekf_update_perf, hrt_elapsed_time(&ekf_update_start));
|
||||
|
@ -999,7 +1004,7 @@ void EKF2::PublishAidSourceStatus(const hrt_abstime ×tamp)
|
|||
|
||||
void EKF2::PublishAttitude(const hrt_abstime ×tamp)
|
||||
{
|
||||
if (_ekf.attitude_valid()) {
|
||||
if (_ekf.attitude_valid() && _ekf.output_predictor().aligned()) {
|
||||
// generate vehicle attitude quaternion data
|
||||
vehicle_attitude_s att;
|
||||
att.timestamp_sample = timestamp;
|
||||
|
@ -1009,7 +1014,7 @@ void EKF2::PublishAttitude(const hrt_abstime ×tamp)
|
|||
att.timestamp = _replay_mode ? timestamp : hrt_absolute_time();
|
||||
_attitude_pub.publish(att);
|
||||
|
||||
} else if (_replay_mode) {
|
||||
} else if (_replay_mode) {
|
||||
// in replay mode we have to tell the replay module not to wait for an update
|
||||
// we do this by publishing an attitude with zero timestamp
|
||||
vehicle_attitude_s att{};
|
||||
|
|
|
@ -61,331 +61,331 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
|||
5890000,1,-0.0095,-0.011,-5.9e-06,0.0045,-0.0011,0.0028,0.0022,-0.0017,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,9e-08,0.00038,0.00038,3.3e-05,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,1.2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
5990000,1,-0.0094,-0.011,1.2e-05,0.0048,0.00032,0.015,0.0026,-0.0017,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,9.6e-08,0.00041,0.00041,3.5e-05,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,1.2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6090000,1,-0.0094,-0.011,-7.2e-06,0.0059,0.0015,-0.011,0.0031,-0.0016,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,1e-07,0.00044,0.00044,3.7e-05,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,1.2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6190000,0.71,0.0013,-0.015,0.71,0.0035,0.0029,-0.005,0.0023,-0.00066,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-8.8e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.00034,0.00034,0.0016,0.22,0.22,4.9,0.13,0.13,0.32,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6290000,0.71,0.0013,-0.015,0.71,0.0034,0.0043,-0.012,0.0026,-0.00028,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-9.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00034,0.00034,0.00075,0.22,0.22,3.2,0.16,0.16,0.3,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6390000,0.71,0.0013,-0.014,0.71,0.0024,0.0048,-0.05,0.0029,0.00018,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-3.7e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00054,0.00034,0.00034,0.00051,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6490000,0.71,0.0014,-0.014,0.71,0.0022,0.0056,-0.052,0.0031,0.00072,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-8.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00034,0.00034,0.00037,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6590000,0.71,0.0014,-0.014,0.71,0.0017,0.0057,-0.099,0.0033,0.0013,-3.7e+02,-0.0015,-0.0057,4.4e-05,0,0,9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00034,0.00034,0.00029,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6690000,0.7,0.0014,-0.014,0.71,0.0021,0.0068,-0.076,0.0035,0.0019,-3.7e+02,-0.0015,-0.0057,4.2e-05,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00035,0.00035,0.00024,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6790000,0.71,0.0014,-0.014,0.71,0.00076,0.0067,-0.11,0.0036,0.0026,-3.7e+02,-0.0015,-0.0057,4.3e-05,0,0,8.1e-06,0.37,0.0037,0.025,0,0,0,0,0,0.00025,0.00035,0.00035,0.00021,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6890000,0.71,0.0014,-0.014,0.71,-0.0013,0.0073,-0.12,0.0036,0.0033,-3.7e+02,-0.0015,-0.0057,4.3e-05,0,0,-4.3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00022,0.00036,0.00036,0.00018,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6990000,0.7,0.0015,-0.014,0.71,-0.0013,0.0082,-0.12,0.0034,0.0041,-3.7e+02,-0.0015,-0.0057,3.8e-05,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.00016,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
7090000,0.7,0.0015,-0.014,0.71,-0.0019,0.0078,-0.13,0.0033,0.0048,-3.7e+02,-0.0015,-0.0057,3.3e-05,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00037,0.00037,0.00015,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
7190000,0.7,0.0015,-0.014,0.71,-0.0036,0.008,-0.15,0.003,0.0056,-3.7e+02,-0.0015,-0.0057,3.1e-05,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00038,0.00038,0.00013,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
7290000,0.7,0.0015,-0.014,0.71,-0.0051,0.0082,-0.15,0.0026,0.0064,-3.7e+02,-0.0015,-0.0057,3e-05,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00039,0.00039,0.00012,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
7390000,0.7,0.0016,-0.014,0.71,-0.0052,0.0097,-0.16,0.002,0.0073,-3.7e+02,-0.0015,-0.0057,3.1e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00015,0.00039,0.00039,0.00011,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7490000,0.7,0.0016,-0.014,0.71,-0.0068,0.01,-0.16,0.0014,0.0082,-3.7e+02,-0.0015,-0.0057,3e-05,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.0004,0.0004,0.00011,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7590000,0.7,0.0016,-0.014,0.71,-0.0087,0.011,-0.17,0.00064,0.0092,-3.7e+02,-0.0015,-0.0057,3.3e-05,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00041,0.00041,9.8e-05,0.52,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7690000,0.7,0.0017,-0.014,0.71,-0.011,0.012,-0.16,-0.00036,0.01,-3.7e+02,-0.0015,-0.0057,3.2e-05,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00042,0.00042,9.3e-05,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7790000,0.7,0.0017,-0.014,0.71,-0.012,0.013,-0.16,-0.0015,0.011,-3.7e+02,-0.0015,-0.0057,2.4e-05,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00043,0.00043,8.7e-05,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7890000,0.7,0.0017,-0.014,0.71,-0.015,0.015,-0.16,-0.0028,0.013,-3.7e+02,-0.0015,-0.0057,2.6e-05,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00045,0.00045,8.2e-05,0.66,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,1.1e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0
|
||||
7990000,0.7,0.0018,-0.014,0.71,-0.017,0.016,-0.16,-0.0044,0.014,-3.7e+02,-0.0015,-0.0057,2.9e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00046,0.00046,7.8e-05,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,1.1e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0
|
||||
8090000,0.7,0.0018,-0.014,0.71,-0.018,0.018,-0.17,-0.0061,0.016,-3.7e+02,-0.0015,-0.0057,3.4e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00047,0.00047,7.5e-05,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,1e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0
|
||||
8190000,0.7,0.0018,-0.014,0.71,-0.021,0.019,-0.18,-0.0081,0.017,-3.7e+02,-0.0015,-0.0057,2.7e-05,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.0001,0.00049,0.00049,7.1e-05,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,1e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0
|
||||
8290000,0.7,0.0018,-0.014,0.71,-0.022,0.02,-0.17,-0.01,0.019,-3.7e+02,-0.0015,-0.0057,2.2e-05,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.0001,0.0005,0.0005,6.8e-05,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,1e-05,0.04,0.04,0.036,0,0,0,0,0,0,0,0
|
||||
8390000,0.7,0.0019,-0.014,0.71,-0.025,0.021,-0.17,-0.013,0.021,-3.7e+02,-0.0015,-0.0057,2.8e-05,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,9.8e-05,0.00051,0.00051,6.5e-05,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,1e-05,0.04,0.04,0.035,0,0,0,0,0,0,0,0
|
||||
8490000,0.7,0.0019,-0.014,0.71,-0.027,0.022,-0.17,-0.015,0.022,-3.7e+02,-0.0015,-0.0056,2.4e-05,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,9.5e-05,0.00052,0.00052,6.3e-05,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,1e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0
|
||||
8590000,0.7,0.0019,-0.014,0.71,-0.029,0.025,-0.17,-0.018,0.024,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,9.3e-05,0.00054,0.00054,6e-05,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,1e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0
|
||||
8690000,0.7,0.0019,-0.014,0.71,-0.032,0.025,-0.16,-0.021,0.025,-3.7e+02,-0.0015,-0.0056,2.5e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,9.1e-05,0.00055,0.00055,5.9e-05,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,1e-05,0.04,0.04,0.033,0,0,0,0,0,0,0,0
|
||||
8790000,0.7,0.0019,-0.014,0.71,-0.034,0.027,-0.15,-0.024,0.028,-3.7e+02,-0.0015,-0.0056,1.9e-05,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,8.9e-05,0.00056,0.00056,5.7e-05,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,1e-05,0.04,0.04,0.032,0,0,0,0,0,0,0,0
|
||||
8890000,0.7,0.0019,-0.014,0.71,-0.036,0.027,-0.15,-0.027,0.029,-3.7e+02,-0.0015,-0.0056,1.5e-05,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,8.7e-05,0.00057,0.00057,5.5e-05,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,1e-05,0.04,0.04,0.03,0,0,0,0,0,0,0,0
|
||||
8990000,0.7,0.002,-0.014,0.71,-0.038,0.028,-0.14,-0.031,0.032,-3.7e+02,-0.0015,-0.0056,7e-06,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,8.6e-05,0.00059,0.00059,5.3e-05,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,1e-05,0.04,0.04,0.029,0,0,0,0,0,0,0,0
|
||||
9090000,0.7,0.002,-0.014,0.71,-0.04,0.029,-0.14,-0.034,0.033,-3.7e+02,-0.0015,-0.0056,7.8e-07,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,0.0006,0.0006,5.2e-05,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,1e-05,0.04,0.04,0.028,0,0,0,0,0,0,0,0
|
||||
9190000,0.7,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.038,0.035,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,8.3e-05,0.00062,0.00062,5e-05,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.027,0,0,0,0,0,0,0,0
|
||||
9290000,0.7,0.002,-0.014,0.71,-0.043,0.03,-0.14,-0.041,0.036,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,8.2e-05,0.00062,0.00062,4.9e-05,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.025,0,0,0,0,0,0,0,0
|
||||
9390000,0.7,0.002,-0.014,0.71,-0.044,0.032,-0.14,-0.046,0.039,-3.7e+02,-0.0015,-0.0056,1.6e-05,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,8e-05,0.00064,0.00064,4.8e-05,1.7,1.7,0.093,5.9,5.9,0.086,0.00013,0.00013,1e-05,0.04,0.04,0.024,0,0,0,0,0,0,0,0
|
||||
9490000,0.7,0.002,-0.014,0.71,-0.045,0.032,-0.13,-0.048,0.04,-3.7e+02,-0.0015,-0.0056,2.9e-05,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,7.9e-05,0.00064,0.00064,4.7e-05,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.023,0,0,0,0,0,0,0,0
|
||||
9590000,0.7,0.002,-0.014,0.71,-0.048,0.034,-0.13,-0.053,0.043,-3.7e+02,-0.0015,-0.0056,3.2e-05,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,7.8e-05,0.00066,0.00066,4.6e-05,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.021,0,0,0,0,0,0,0,0
|
||||
9690000,0.7,0.0021,-0.014,0.71,-0.048,0.035,-0.12,-0.054,0.043,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,0.00065,0.00065,4.5e-05,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,1e-05,0.04,0.04,0.02,0,0,0,0,0,0,0,0
|
||||
9790000,0.7,0.0021,-0.014,0.71,-0.049,0.037,-0.11,-0.059,0.046,-3.7e+02,-0.0015,-0.0056,2.5e-05,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,0.00067,0.00067,4.4e-05,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.019,0,0,0,0,0,0,0,0
|
||||
9890000,0.7,0.002,-0.014,0.71,-0.049,0.037,-0.11,-0.06,0.046,-3.7e+02,-0.0015,-0.0056,2.2e-05,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,7.6e-05,0.00067,0.00067,4.3e-05,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.018,0,0,0,0,0,0,0,0
|
||||
9990000,0.7,0.0021,-0.014,0.71,-0.051,0.038,-0.1,-0.065,0.049,-3.7e+02,-0.0015,-0.0056,1.5e-05,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,7.5e-05,0.00069,0.00069,4.2e-05,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,1e-05,0.04,0.04,0.017,0,0,0,0,0,0,0,0
|
||||
10090000,0.7,0.0021,-0.014,0.71,-0.049,0.037,-0.096,-0.065,0.049,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,0.00068,0.00068,4.2e-05,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.016,0,0,0,0,0,0,0,0
|
||||
10190000,0.7,0.0021,-0.014,0.71,-0.051,0.04,-0.096,-0.07,0.052,-3.7e+02,-0.0015,-0.0056,-5.2e-06,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,0.0007,0.0007,4.1e-05,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,1e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0
|
||||
10290000,0.7,0.0021,-0.014,0.71,-0.052,0.04,-0.084,-0.075,0.056,-3.7e+02,-0.0015,-0.0056,-1.9e-05,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,0.00072,0.00072,4e-05,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0
|
||||
10390000,0.7,0.0021,-0.014,0.71,0.0095,-0.019,0.0096,0.00087,-0.0017,-3.7e+02,-0.0015,-0.0056,-2e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,0.00075,0.00075,4e-05,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,1e-05,0.04,0.04,0.013,0,0,0,0,0,0,0,0
|
||||
10490000,0.7,0.0021,-0.014,0.71,0.0082,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,-3.5e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,0.00077,0.00077,3.9e-05,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,9.9e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
|
||||
10590000,0.7,0.0022,-0.014,0.71,0.0078,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-0.0015,-0.0056,-3.6e-05,-0.00027,3.1e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.00078,0.00078,3.9e-05,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,9.9e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
|
||||
10690000,0.7,0.0023,-0.014,0.71,0.0057,-0.0058,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,-4.3e-05,-0.00027,3.2e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.0008,0.0008,3.8e-05,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,9.9e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
|
||||
10790000,0.7,0.0023,-0.014,0.71,0.0052,-0.0031,0.024,0.0027,-0.00072,-3.7e+02,-0.0014,-0.0056,-4.3e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.00077,0.00077,3.8e-05,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,9.8e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
|
||||
10890000,0.7,0.0022,-0.014,0.71,0.004,-0.0017,0.02,0.0031,-0.00093,-3.7e+02,-0.0014,-0.0056,-4.6e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.0008,0.0008,3.8e-05,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,9.8e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
|
||||
10990000,0.7,0.0022,-0.014,0.71,0.0068,0.0033,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,-3.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.00073,0.00073,3.7e-05,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,9.7e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
|
||||
11090000,0.7,0.0022,-0.014,0.71,0.0056,0.0058,0.019,0.0053,-0.0018,-3.7e+02,-0.0014,-0.0055,-2.4e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.00075,0.00075,3.7e-05,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,9.7e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
|
||||
11190000,0.7,0.0021,-0.014,0.71,0.01,0.0083,0.0077,0.0067,-0.0028,-3.7e+02,-0.0013,-0.0055,-3.9e-05,-0.00092,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00065,0.00065,3.7e-05,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,9.6e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
||||
11290000,0.7,0.0022,-0.014,0.71,0.01,0.011,0.0074,0.0078,-0.0018,-3.7e+02,-0.0013,-0.0055,-6e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00067,0.00067,3.6e-05,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,9.6e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
||||
11390000,0.7,0.0022,-0.014,0.71,0.0054,0.0091,0.0017,0.0055,-0.0019,-3.7e+02,-0.0013,-0.0056,-7.6e-05,-0.0005,0.00088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00055,0.00055,3.6e-05,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,9.5e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
||||
11490000,0.7,0.0022,-0.014,0.71,0.0029,0.012,0.0025,0.006,-0.00089,-3.7e+02,-0.0013,-0.0056,-0.00011,-0.00051,0.00088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00057,0.00057,3.6e-05,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,9.5e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
||||
11590000,0.7,0.0021,-0.014,0.71,-0.0015,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,-0.00012,-8.9e-05,0.00075,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00047,0.00047,3.6e-05,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,9.4e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
11690000,0.7,0.0021,-0.014,0.71,-0.0043,0.013,-0.0079,0.0042,-0.00027,-3.7e+02,-0.0014,-0.0056,-0.00013,-7.9e-05,0.00074,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00048,0.00048,3.5e-05,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,9.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
11790000,0.7,0.0021,-0.014,0.71,-0.01,0.013,-0.0098,0.0018,0.00056,-3.7e+02,-0.0014,-0.0056,-0.00013,2.7e-05,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.0004,0.0004,3.5e-05,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.4e-05,9.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
11890000,0.7,0.0021,-0.014,0.71,-0.012,0.014,-0.011,0.00078,0.0019,-3.7e+02,-0.0014,-0.0056,-0.00015,2.1e-05,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00041,0.00041,3.5e-05,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.4e-05,9.2e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
11990000,0.7,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.00029,0.0023,-3.7e+02,-0.0014,-0.0057,-0.00015,0.00016,0.00056,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00034,0.00034,3.5e-05,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,9.2e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12090000,0.7,0.0022,-0.014,0.71,-0.014,0.016,-0.022,-0.0017,0.0038,-3.7e+02,-0.0014,-0.0057,-0.00013,0.00018,0.00055,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00035,0.00035,3.5e-05,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,9.1e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12190000,0.7,0.0018,-0.014,0.71,-0.008,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,-0.00013,0.00043,0.001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.0003,0.0003,3.5e-05,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12290000,0.7,0.0017,-0.014,0.71,-0.011,0.015,-0.016,0.00056,0.0033,-3.7e+02,-0.0013,-0.0057,-0.00013,0.0004,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00031,0.00031,3.4e-05,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12390000,0.7,0.0014,-0.014,0.71,-0.0051,0.011,-0.015,0.003,0.0016,-3.7e+02,-0.0012,-0.0058,-0.00014,0.00056,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00027,0.00027,3.4e-05,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,8.9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12490000,0.7,0.0014,-0.014,0.71,-0.0062,0.013,-0.018,0.0025,0.0029,-3.7e+02,-0.0012,-0.0058,-0.00016,0.00056,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00028,0.00028,3.4e-05,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,8.8e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12590000,0.7,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-0.0013,-0.0058,-0.00016,0.00069,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00025,0.00025,3.4e-05,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,8.8e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0
|
||||
12690000,0.7,0.0015,-0.014,0.71,-0.014,0.012,-0.027,-0.0042,0.0026,-3.7e+02,-0.0013,-0.0058,-0.00017,0.00072,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00026,0.00026,3.4e-05,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,8.7e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0
|
||||
12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0091,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0058,-0.00016,0.00076,0.001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00023,0.00023,3.4e-05,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,8.6e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0
|
||||
12890000,0.7,0.0015,-0.014,0.71,-0.021,0.0091,-0.029,-0.0096,0.0022,-3.7e+02,-0.0014,-0.0058,-0.00016,0.00069,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00024,0.00024,3.4e-05,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,8.6e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0
|
||||
12990000,0.7,0.0012,-0.014,0.71,-0.0083,0.0065,-0.03,-0.001,0.0012,-3.7e+02,-0.0012,-0.0059,-0.00014,0.00067,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00022,0.00022,3.4e-05,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,8.5e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
|
||||
13090000,0.7,0.0012,-0.014,0.71,-0.009,0.0067,-0.03,-0.0019,0.0018,-3.7e+02,-0.0013,-0.0059,-0.00016,0.00064,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00023,0.00023,3.4e-05,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,8.4e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
|
||||
13190000,0.7,0.00095,-0.014,0.71,5.6e-05,0.0061,-0.027,0.0044,0.0011,-3.7e+02,-0.0012,-0.0059,-0.00017,0.00049,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,8.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
|
||||
13290000,0.7,0.00096,-0.014,0.71,-0.0002,0.0069,-0.024,0.0044,0.0018,-3.7e+02,-0.0012,-0.0059,-0.00015,0.00036,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00022,0.00022,3.4e-05,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,8.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
|
||||
13390000,0.7,0.00081,-0.014,0.71,0.00062,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,-0.00013,0.0002,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,8.2e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0
|
||||
13490000,0.7,0.00084,-0.014,0.71,0.00012,0.0058,-0.019,0.0034,0.0016,-3.7e+02,-0.0012,-0.0059,-0.00011,0.00011,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,8.1e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0
|
||||
13590000,0.7,0.00078,-0.014,0.71,0.00037,0.006,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.0059,-0.00013,8.4e-05,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,8.1e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0
|
||||
13690000,0.7,0.00076,-0.014,0.71,0.0011,0.0078,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.0059,-0.0001,0.00012,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,8e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0
|
||||
13790000,0.7,0.00064,-0.014,0.71,0.0016,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0001,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,7.9e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0
|
||||
13890000,0.7,0.00061,-0.014,0.71,0.0021,0.0035,-0.031,0.0037,-0.0003,-3.7e+02,-0.0011,-0.006,-8.7e-05,-7e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,7.8e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0
|
||||
13990000,0.7,0.00054,-0.014,0.71,0.0024,0.001,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,-8.3e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,7.8e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0
|
||||
14090000,0.7,0.00052,-0.014,0.71,0.0024,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,-5.6e-05,-0.00032,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,7.7e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0
|
||||
14190000,0.7,0.00042,-0.014,0.71,0.0058,0.00063,-0.033,0.0068,-0.0016,-3.7e+02,-0.0011,-0.006,-4.1e-05,-0.0003,0.00089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,7.6e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0
|
||||
14290000,0.7,0.00043,-0.014,0.71,0.0066,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-0.0011,-0.006,-2.9e-05,-0.00037,0.00096,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,7.5e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0
|
||||
14390000,0.7,0.00035,-0.014,0.71,0.0084,0.0023,-0.034,0.0087,-0.0013,-3.7e+02,-0.0011,-0.006,-1.2e-07,-0.00037,0.00071,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,7.4e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0
|
||||
14490000,0.7,0.00033,-0.013,0.71,0.0084,0.0035,-0.037,0.0096,-0.001,-3.7e+02,-0.0011,-0.006,9.8e-06,-0.00032,0.00067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,7.4e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0
|
||||
14590000,0.7,0.00032,-0.013,0.71,0.0049,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-0.0011,-0.0061,1.3e-05,-0.00069,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,7.3e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0
|
||||
14690000,0.7,0.00028,-0.013,0.71,0.0062,-0.001,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00079,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,7.2e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0
|
||||
14790000,0.7,0.0003,-0.013,0.71,0.003,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-0.0012,-0.0061,4.3e-05,-0.0012,0.0017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,7.1e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0
|
||||
14890000,0.7,0.0003,-0.013,0.71,0.0046,-0.0016,-0.033,0.0041,-0.0036,-3.7e+02,-0.0012,-0.0061,5.9e-05,-0.0012,0.0017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.00019,3.4e-05,0.048,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,7.1e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0
|
||||
14990000,0.7,0.00029,-0.013,0.71,0.0034,-0.0018,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,5.7e-05,-0.0012,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,7e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0
|
||||
15090000,0.7,0.00022,-0.013,0.71,0.0038,-0.002,-0.032,0.0035,-0.0031,-3.7e+02,-0.0012,-0.0061,5.9e-05,-0.0012,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.9e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0
|
||||
15190000,0.7,0.00023,-0.013,0.71,0.0032,-0.00077,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,5.8e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.8e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0
|
||||
15290000,0.7,0.0002,-0.013,0.71,0.0037,-0.00061,-0.027,0.0031,-0.0025,-3.7e+02,-0.0012,-0.0061,7.4e-05,-0.0013,0.0021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.7e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0
|
||||
15390000,0.7,0.0002,-0.013,0.71,0.003,-0.00026,-0.024,0.00055,-0.002,-3.7e+02,-0.0012,-0.0061,0.00011,-0.0013,0.0024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.7e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0
|
||||
15490000,0.7,0.00022,-0.013,0.71,0.0042,-0.00065,-0.024,0.00092,-0.0021,-3.7e+02,-0.0012,-0.0061,9.3e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.6e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0
|
||||
15590000,0.7,0.00024,-0.013,0.71,0.0023,-0.00064,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,8.4e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.5e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0
|
||||
15690000,0.7,0.00024,-0.013,0.71,0.0026,-0.00081,-0.023,-0.0011,-0.0018,-3.7e+02,-0.0012,-0.0061,8.6e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,6.4e-06,0.035,0.035,0.0033,0,0,0,0,0,0,0,0
|
||||
15790000,0.7,0.0002,-0.013,0.71,0.0031,-0.0025,-0.026,-0.00097,-0.0028,-3.7e+02,-0.0012,-0.0061,8.9e-05,-0.0015,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0
|
||||
15890000,0.7,0.00015,-0.013,0.71,0.004,-0.003,-0.024,-0.00058,-0.0031,-3.7e+02,-0.0012,-0.0061,9.5e-05,-0.0016,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0
|
||||
15990000,0.7,9.4e-05,-0.013,0.71,0.0039,-0.0039,-0.019,-0.00065,-0.0039,-3.7e+02,-0.0012,-0.0061,0.00012,-0.0018,0.0028,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.2e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0
|
||||
16090000,0.7,9.5e-05,-0.013,0.71,0.0056,-0.0041,-0.016,-0.0002,-0.0043,-3.7e+02,-0.0012,-0.0061,0.00015,-0.0019,0.0029,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6.1e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0
|
||||
16190000,0.7,0.00012,-0.013,0.71,0.0056,-0.0033,-0.014,-0.0004,-0.0035,-3.7e+02,-0.0012,-0.0061,0.00016,-0.0018,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0
|
||||
16290000,0.7,0.00014,-0.013,0.71,0.0072,-0.0041,-0.016,0.00025,-0.0038,-3.7e+02,-0.0012,-0.0061,0.00019,-0.0018,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,6e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0
|
||||
16390000,0.7,0.00013,-0.013,0.71,0.0061,-0.0043,-0.015,-7.1e-05,-0.0031,-3.7e+02,-0.0012,-0.0061,0.00019,-0.0017,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,5.9e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0
|
||||
16490000,0.7,0.00015,-0.013,0.71,0.0053,-0.0039,-0.018,0.00048,-0.0035,-3.7e+02,-0.0012,-0.0061,0.0002,-0.0016,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,5.8e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0
|
||||
16590000,0.71,0.0004,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0025,-7.5e-05,-3.7e+02,-0.0013,-0.006,0.0002,-0.00094,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.4e-05,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,5.7e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0
|
||||
16690000,0.7,0.00039,-0.013,0.71,0.002,-0.0007,-0.015,-0.0023,-0.00017,-3.7e+02,-0.0013,-0.006,0.00019,-0.001,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00016,3.4e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,5.7e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0
|
||||
16790000,0.71,0.00054,-0.013,0.71,-0.0014,0.0015,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,0.0002,-0.00043,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.4e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,5.6e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0
|
||||
16890000,0.7,0.00055,-0.013,0.71,-0.0017,0.0023,-0.011,-0.0048,0.0027,-3.7e+02,-0.0013,-0.006,0.00019,-0.00047,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.4e-05,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,5.5e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0
|
||||
16990000,0.7,0.00049,-0.013,0.71,-0.0016,0.00035,-0.01,-0.0052,0.00086,-3.7e+02,-0.0013,-0.006,0.00018,-0.00088,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,5.5e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0
|
||||
17090000,0.7,0.00046,-0.013,0.71,-0.00086,0.0013,-0.01,-0.0053,0.00091,-3.7e+02,-0.0013,-0.006,0.00018,-0.00087,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.3e-05,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,5.4e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0
|
||||
17190000,0.71,0.00045,-0.013,0.71,-0.0004,0.0013,-0.011,-0.0056,-0.00053,-3.7e+02,-0.0014,-0.006,0.0002,-0.0012,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,5.3e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0
|
||||
17290000,0.7,0.00042,-0.013,0.71,0.0017,0.0023,-0.0066,-0.0056,-0.00036,-3.7e+02,-0.0014,-0.006,0.00019,-0.0013,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,5.2e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0
|
||||
17390000,0.71,0.00039,-0.013,0.71,0.0023,0.0015,-0.0047,-0.0047,-0.0016,-3.7e+02,-0.0014,-0.006,0.00021,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,5.2e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0
|
||||
17490000,0.71,0.00038,-0.013,0.71,0.0029,0.0011,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,0.00021,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,5.1e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0
|
||||
17590000,0.71,0.00029,-0.013,0.71,0.0041,-8.3e-05,0.0025,-0.0037,-0.0026,-3.7e+02,-0.0014,-0.0061,0.00022,-0.002,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,5e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0
|
||||
17690000,0.71,0.00026,-0.013,0.71,0.005,0.00063,0.0019,-0.0033,-0.0026,-3.7e+02,-0.0014,-0.0061,0.00023,-0.002,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,5e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0
|
||||
17790000,0.71,0.00017,-0.013,0.71,0.0076,0.00035,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,0.00027,-0.0019,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,4.9e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0
|
||||
17890000,0.71,0.00018,-0.013,0.71,0.0091,-0.00041,0.00069,-0.0013,-0.0022,-3.7e+02,-0.0013,-0.0061,0.00028,-0.0019,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,4.8e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0
|
||||
17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0021,0.0019,-0.00055,-0.0019,-3.7e+02,-0.0013,-0.0061,0.00028,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,4.8e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0
|
||||
18090000,0.71,0.00013,-0.013,0.71,0.011,-0.0023,0.0043,0.00057,-0.0021,-3.7e+02,-0.0013,-0.0061,0.00026,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,4.7e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0
|
||||
18190000,0.71,9.9e-05,-0.013,0.71,0.012,-0.0012,0.0056,0.0014,-0.0017,-3.7e+02,-0.0013,-0.0061,0.00028,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,4.7e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0
|
||||
18290000,0.71,4e-05,-0.012,0.71,0.012,-0.0018,0.0068,0.0026,-0.0018,-3.7e+02,-0.0013,-0.0061,0.00027,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,4.6e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0
|
||||
18390000,0.71,5.6e-05,-0.013,0.71,0.013,-0.00016,0.008,0.0032,-0.0014,-3.7e+02,-0.0013,-0.0061,0.00029,-0.0017,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,4.5e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0
|
||||
18490000,0.71,7.1e-05,-0.012,0.71,0.014,0.00025,0.0076,0.0046,-0.0014,-3.7e+02,-0.0013,-0.0061,0.0003,-0.0018,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,4.5e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0
|
||||
18590000,0.71,7.6e-05,-0.012,0.71,0.013,0.00049,0.0058,0.0035,-0.0012,-3.7e+02,-0.0014,-0.0061,0.00033,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00012,0.00012,3.3e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,4.4e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0
|
||||
18690000,0.71,4.5e-05,-0.012,0.71,0.014,-0.0002,0.0039,0.0049,-0.0011,-3.7e+02,-0.0014,-0.0061,0.00032,-0.0017,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,4.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0
|
||||
18790000,0.71,7.4e-05,-0.012,0.71,0.012,0.0001,0.0035,0.0037,-0.0009,-3.7e+02,-0.0014,-0.0061,0.00032,-0.0017,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00012,0.00012,3.3e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,4.3e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0
|
||||
18890000,0.71,9.8e-05,-0.012,0.71,0.013,0.0006,0.0042,0.005,-0.00083,-3.7e+02,-0.0014,-0.0061,0.00035,-0.0017,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,4.2e-06,0.031,0.031,0.0007,0,0,0,0,0,0,0,0
|
||||
18990000,0.71,8.5e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.00069,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0017,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,4.2e-06,0.031,0.031,0.00066,0,0,0,0,0,0,0,0
|
||||
19090000,0.71,7e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0077,-0.00048,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,4.1e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0
|
||||
19190000,0.71,7.2e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0085,-0.00044,-3.7e+02,-0.0014,-0.0061,0.00037,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,4.1e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0
|
||||
19290000,0.71,9.4e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00025,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.2e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,4e-06,0.03,0.03,0.0006,0,0,0,0,0,0,0,0
|
||||
19390000,0.71,0.00011,-0.012,0.71,0.012,0.00042,0.012,0.008,-0.00026,-3.7e+02,-0.0014,-0.0061,0.00038,-0.0018,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,4e-06,0.03,0.03,0.00058,0,0,0,0,0,0,0,0
|
||||
19490000,0.71,0.00013,-0.012,0.71,0.012,-0.00029,0.0088,0.0092,-0.00026,-3.7e+02,-0.0014,-0.0061,0.0004,-0.0018,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,3.9e-06,0.03,0.03,0.00056,0,0,0,0,0,0,0,0
|
||||
19590000,0.71,0.00018,-0.012,0.71,0.0096,-0.0013,0.0081,0.0074,-0.00028,-3.7e+02,-0.0014,-0.0061,0.00043,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,3.9e-06,0.03,0.03,0.00054,0,0,0,0,0,0,0,0
|
||||
19690000,0.71,0.00018,-0.012,0.71,0.01,-0.0035,0.0096,0.0084,-0.00053,-3.7e+02,-0.0014,-0.0061,0.00041,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,3.8e-06,0.03,0.03,0.00052,0,0,0,0,0,0,0,0
|
||||
19790000,0.71,0.00025,-0.012,0.71,0.0077,-0.0043,0.01,0.0068,-0.00043,-3.7e+02,-0.0014,-0.0061,0.00042,-0.0018,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,3.7e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19890000,0.71,0.00019,-0.012,0.71,0.0064,-0.0046,0.011,0.0075,-0.00089,-3.7e+02,-0.0014,-0.0061,0.00045,-0.0018,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,3.7e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19990000,0.71,0.00018,-0.012,0.71,0.004,-0.0053,0.014,0.0061,-0.00074,-3.7e+02,-0.0014,-0.006,0.00049,-0.0017,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20090000,0.71,0.00017,-0.012,0.71,0.0037,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-0.0014,-0.006,0.00052,-0.0017,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20190000,0.71,0.00028,-0.012,0.71,0.0014,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-0.0014,-0.006,0.00054,-0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.0001,0.0001,3.2e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20290000,0.71,0.00024,-0.012,0.71,0.00027,-0.0095,0.015,0.0043,-0.0019,-3.7e+02,-0.0014,-0.006,0.00055,-0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,3.5e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20390000,0.71,0.00026,-0.012,0.71,-0.0022,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0014,-0.006,0.00055,-0.0015,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,3.5e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20490000,0.71,0.00031,-0.012,0.71,-0.0026,-0.011,0.016,0.0021,-0.0026,-3.7e+02,-0.0014,-0.006,0.00054,-0.0015,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,3.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20590000,0.71,0.00034,-0.012,0.71,-0.0023,-0.011,0.013,0.0018,-0.0021,-3.7e+02,-0.0014,-0.006,0.00054,-0.0013,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,3.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20690000,0.71,0.00036,-0.012,0.71,-0.0023,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-0.0014,-0.006,0.00055,-0.0013,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,1.9e-06,3.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20790000,0.71,0.00039,-0.012,0.71,-0.0034,-0.011,0.015,0.0013,-0.0025,-3.7e+02,-0.0014,-0.006,0.00055,-0.0011,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,3.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20890000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.014,0.00098,-0.0038,-3.7e+02,-0.0014,-0.006,0.00057,-0.0011,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,3.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20990000,0.71,0.00038,-0.012,0.71,-0.0041,-0.014,0.015,0.0026,-0.0031,-3.7e+02,-0.0014,-0.006,0.00058,-0.0009,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.9e-05,9.8e-05,3.1e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,3.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
21090000,0.71,0.00038,-0.012,0.71,-0.0042,-0.017,0.015,0.0022,-0.0047,-3.7e+02,-0.0014,-0.006,0.00059,-0.0009,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.9e-05,9.9e-05,3.1e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,3.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
21190000,0.71,0.00042,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,0.00058,-0.00066,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.7e-05,9.7e-05,3.1e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21290000,0.71,0.00046,-0.012,0.71,-0.004,-0.018,0.016,0.0033,-0.0054,-3.7e+02,-0.0014,-0.006,0.00061,-0.00066,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.8e-05,9.8e-05,3.1e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21390000,0.71,0.0005,-0.012,0.71,-0.0048,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,0.0006,-0.00028,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.6e-05,9.6e-05,3.1e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21490000,0.71,0.00051,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-0.0014,-0.006,0.00061,-0.00028,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.7e-05,9.7e-05,3.1e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21590000,0.71,0.00053,-0.012,0.71,-0.0059,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-0.0014,-0.006,0.0006,6.7e-05,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.5e-05,9.5e-05,3.1e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21690000,0.71,0.00054,-0.012,0.71,-0.0058,-0.016,0.017,0.0013,-0.0048,-3.7e+02,-0.0014,-0.006,0.00061,6.4e-05,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.6e-05,9.5e-05,3.1e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21790000,0.71,0.00056,-0.012,0.71,-0.0064,-0.011,0.015,4.8e-05,-0.00076,-3.7e+02,-0.0014,-0.0059,0.0006,0.00059,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.4e-05,9.4e-05,3.1e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.2e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21890000,0.71,0.00056,-0.012,0.71,-0.0063,-0.012,0.016,-0.00059,-0.0019,-3.7e+02,-0.0014,-0.0059,0.0006,0.00059,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.5e-05,9.4e-05,3.1e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21990000,0.71,0.00062,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-0.0014,-0.0059,0.0006,0.001,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.3e-05,9.3e-05,3.1e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22090000,0.71,0.00063,-0.012,0.71,-0.0072,-0.0082,0.015,-0.0022,0.00062,-3.7e+02,-0.0014,-0.0059,0.00059,0.001,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.4e-05,9.3e-05,3e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22190000,0.71,0.0006,-0.012,0.71,-0.007,-0.0073,0.015,-0.0018,0.00058,-3.7e+02,-0.0014,-0.0059,0.0006,0.0011,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.2e-05,9.2e-05,3e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22290000,0.71,0.00064,-0.012,0.71,-0.0083,-0.0081,0.015,-0.0026,-0.0002,-3.7e+02,-0.0014,-0.0059,0.00059,0.0011,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.3e-05,9.3e-05,3e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22390000,0.71,0.00061,-0.012,0.71,-0.0089,-0.0076,0.017,-0.0022,-0.00019,-3.7e+02,-0.0014,-0.0059,0.00059,0.0012,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.1e-05,9.1e-05,3e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22490000,0.71,0.00062,-0.012,0.71,-0.0096,-0.0075,0.018,-0.0031,-0.00096,-3.7e+02,-0.0014,-0.0059,0.00059,0.0012,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.2e-05,9.2e-05,3e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22590000,0.71,0.0006,-0.012,0.71,-0.0093,-0.007,0.017,-0.0034,0.00012,-3.7e+02,-0.0014,-0.0059,0.00059,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.1e-05,9.1e-05,3e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22690000,0.71,0.00063,-0.012,0.71,-0.011,-0.0067,0.018,-0.0044,-0.00056,-3.7e+02,-0.0014,-0.0059,0.0006,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9.1e-05,9.1e-05,3e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22790000,0.71,0.00062,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00045,-3.7e+02,-0.0014,-0.0059,0.00057,0.0014,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22890000,0.71,0.00063,-0.012,0.71,-0.012,-0.0052,0.021,-0.0067,-0.00099,-3.7e+02,-0.0014,-0.0059,0.00057,0.0014,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22990000,0.71,0.00061,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00087,-3.7e+02,-0.0014,-0.0059,0.00057,0.0015,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,3e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23090000,0.71,0.00058,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,0.00055,0.0015,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23190000,0.71,0.00064,-0.012,0.71,-0.015,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,0.00055,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,2.9e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23290000,0.71,0.00058,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-0.0014,-0.0059,0.00055,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,2.9e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23390000,0.71,0.00067,-0.012,0.71,-0.016,-0.0081,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,0.00055,0.0016,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-0.0014,-0.0059,0.00056,0.0016,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.8e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,0.00055,0.0018,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-0.0014,-0.0059,0.00055,0.0018,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23790000,0.71,0.005,0.00065,0.71,-0.089,-0.027,-0.15,-0.021,-0.0018,-3.7e+02,-0.0014,-0.0059,0.00055,0.002,0.0062,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.7e-05,8.7e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.005,-3.7e+02,-0.0014,-0.0059,0.00054,0.002,0.0062,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.7e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23990000,0.71,0.00096,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-0.0014,-0.0059,0.00055,0.0022,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.6e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24090000,0.71,0.0022,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,0.00056,0.0022,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.7e-05,2.9e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.7e-07,6.7e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,0.00056,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.6e-05,2.8e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-07,6.4e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-0.0014,-0.0059,0.00055,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.6e-05,2.8e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.4e-07,6.4e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24390000,0.71,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-0.0013,-0.0059,0.00054,0.0021,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24490000,0.71,0.0047,-0.0018,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-0.0013,-0.0059,0.00054,0.0021,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.5e-05,2.8e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,0.00055,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-0.0013,-0.0059,0.00056,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,0.00054,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.4e-05,8.4e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-0.0013,-0.0059,0.00053,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.4e-05,8.4e-05,2.8e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,0.00052,0.0033,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.3e-05,8.3e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.4e-07,5.4e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,0.00051,0.0034,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.4e-05,8.3e-05,2.8e-05,0.018,0.017,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,0.00051,0.003,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.3e-05,8.2e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-07,5.2e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,0.00051,0.003,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.3e-05,8.3e-05,2.8e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,0.00051,0.0032,-0.00027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.2e-05,8.2e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,0.00052,0.0032,-0.00026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.2e-05,8.2e-05,2.7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,0.00052,0.0029,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8.1e-05,2.7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,0.00052,0.0029,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8.1e-05,2.7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,0.00053,0.0037,-0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-07,4.7e-07,1.7e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,0.00054,0.0036,-0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8e-05,2.7e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-07,4.7e-07,1.7e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,0.00054,0.0032,-0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-07,4.6e-07,1.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,0.00052,0.0033,-0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-07,4.6e-07,1.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,0.00052,0.0044,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.9e-05,2.7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-07,4.4e-07,1.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,0.00052,0.0044,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.9e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-07,4.5e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
6190000,0.71,0.0013,-0.015,0.71,-0.004,0.0045,-0.005,0.0017,-0.00054,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-8.8e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.00034,0.00034,0.0016,0.22,0.22,4.9,0.13,0.13,0.32,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6290000,0.71,0.0013,-0.015,0.71,-0.0041,0.0058,-0.012,0.0013,-8.7e-06,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-9.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00034,0.00034,0.00075,0.22,0.22,3.2,0.16,0.16,0.3,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6390000,0.71,0.0013,-0.014,0.71,-0.0051,0.0063,-0.05,0.00079,0.00061,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-3.7e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00054,0.00034,0.00034,0.00051,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6490000,0.71,0.0014,-0.014,0.71,-0.0053,0.0071,-0.052,0.00026,0.0013,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-8.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00034,0.00034,0.00037,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6590000,0.71,0.0014,-0.014,0.71,-0.0058,0.0072,-0.099,-0.00026,0.002,-3.7e+02,-0.0015,-0.0057,4.4e-05,0,0,9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00034,0.00034,0.00029,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6690000,0.7,0.0014,-0.014,0.71,-0.0054,0.0083,-0.076,-0.00083,0.0028,-3.7e+02,-0.0015,-0.0057,4.2e-05,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00035,0.00035,0.00024,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6790000,0.71,0.0014,-0.014,0.71,-0.0067,0.0082,-0.11,-0.0014,0.0036,-3.7e+02,-0.0015,-0.0057,4.3e-05,0,0,8.1e-06,0.37,0.0037,0.025,0,0,0,0,0,0.00025,0.00035,0.00035,0.00021,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6890000,0.71,0.0014,-0.014,0.71,-0.0088,0.0088,-0.12,-0.0022,0.0045,-3.7e+02,-0.0015,-0.0057,4.3e-05,0,0,-4.3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00022,0.00036,0.00036,0.00018,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
6990000,0.7,0.0015,-0.014,0.71,-0.0088,0.0097,-0.12,-0.0031,0.0054,-3.7e+02,-0.0015,-0.0057,3.8e-05,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.00016,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
7090000,0.7,0.0015,-0.014,0.71,-0.0094,0.0093,-0.13,-0.004,0.0063,-3.7e+02,-0.0015,-0.0057,3.3e-05,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00037,0.00037,0.00015,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
7190000,0.7,0.0015,-0.014,0.71,-0.011,0.0095,-0.15,-0.005,0.0072,-3.7e+02,-0.0015,-0.0057,3.1e-05,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00038,0.00038,0.00013,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
7290000,0.7,0.0015,-0.014,0.71,-0.012,0.0097,-0.15,-0.0062,0.0081,-3.7e+02,-0.0015,-0.0057,3e-05,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00039,0.00039,0.00012,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
||||
7390000,0.7,0.0016,-0.014,0.71,-0.013,0.011,-0.16,-0.0074,0.0092,-3.7e+02,-0.0015,-0.0056,3.1e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00015,0.00039,0.00039,0.00011,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7490000,0.7,0.0016,-0.014,0.71,-0.014,0.012,-0.16,-0.0087,0.01,-3.7e+02,-0.0015,-0.0056,3e-05,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.0004,0.0004,0.00011,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7590000,0.7,0.0016,-0.014,0.71,-0.016,0.013,-0.17,-0.01,0.011,-3.7e+02,-0.0015,-0.0056,3.3e-05,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00041,0.00041,9.8e-05,0.52,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7690000,0.7,0.0017,-0.014,0.71,-0.018,0.014,-0.16,-0.012,0.013,-3.7e+02,-0.0015,-0.0056,3.2e-05,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00042,0.00042,9.3e-05,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7790000,0.7,0.0017,-0.014,0.71,-0.019,0.015,-0.16,-0.014,0.014,-3.7e+02,-0.0015,-0.0056,2.4e-05,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00043,0.00043,8.7e-05,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
||||
7890000,0.7,0.0017,-0.014,0.71,-0.022,0.016,-0.16,-0.016,0.015,-3.7e+02,-0.0015,-0.0056,2.6e-05,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00045,0.00045,8.2e-05,0.66,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,1.1e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0
|
||||
7990000,0.7,0.0018,-0.014,0.71,-0.024,0.018,-0.16,-0.018,0.017,-3.7e+02,-0.0015,-0.0056,2.9e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00046,0.00046,7.8e-05,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,1.1e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0
|
||||
8090000,0.7,0.0018,-0.014,0.71,-0.025,0.019,-0.17,-0.02,0.018,-3.7e+02,-0.0015,-0.0056,3.4e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00047,0.00047,7.5e-05,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,1e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0
|
||||
8190000,0.7,0.0018,-0.014,0.71,-0.028,0.021,-0.18,-0.023,0.02,-3.7e+02,-0.0015,-0.0056,2.7e-05,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.0001,0.00049,0.00049,7.1e-05,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,1e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0
|
||||
8290000,0.7,0.0018,-0.014,0.71,-0.029,0.021,-0.17,-0.025,0.022,-3.7e+02,-0.0015,-0.0056,2.2e-05,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.0001,0.0005,0.0005,6.8e-05,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,1e-05,0.04,0.04,0.036,0,0,0,0,0,0,0,0
|
||||
8390000,0.7,0.0019,-0.014,0.71,-0.031,0.022,-0.17,-0.028,0.024,-3.7e+02,-0.0015,-0.0056,2.8e-05,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,9.8e-05,0.00051,0.00051,6.5e-05,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,1e-05,0.04,0.04,0.035,0,0,0,0,0,0,0,0
|
||||
8490000,0.7,0.0018,-0.014,0.71,-0.033,0.024,-0.17,-0.031,0.025,-3.7e+02,-0.0015,-0.0056,2.4e-05,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,9.5e-05,0.00052,0.00052,6.3e-05,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,1e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0
|
||||
8590000,0.7,0.0019,-0.014,0.71,-0.035,0.026,-0.17,-0.035,0.028,-3.7e+02,-0.0015,-0.0056,1.6e-05,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,9.3e-05,0.00054,0.00054,6e-05,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,1e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0
|
||||
8690000,0.7,0.0019,-0.014,0.71,-0.038,0.027,-0.16,-0.038,0.029,-3.7e+02,-0.0015,-0.0056,2.5e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,9.1e-05,0.00055,0.00055,5.9e-05,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,1e-05,0.04,0.04,0.033,0,0,0,0,0,0,0,0
|
||||
8790000,0.7,0.0019,-0.014,0.71,-0.041,0.029,-0.15,-0.042,0.031,-3.7e+02,-0.0015,-0.0056,1.9e-05,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,8.9e-05,0.00056,0.00056,5.7e-05,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,1e-05,0.04,0.04,0.032,0,0,0,0,0,0,0,0
|
||||
8890000,0.7,0.0019,-0.014,0.71,-0.042,0.029,-0.15,-0.045,0.033,-3.7e+02,-0.0015,-0.0056,1.5e-05,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,8.7e-05,0.00057,0.00057,5.5e-05,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,1e-05,0.04,0.04,0.03,0,0,0,0,0,0,0,0
|
||||
8990000,0.7,0.002,-0.014,0.71,-0.044,0.03,-0.14,-0.049,0.035,-3.7e+02,-0.0015,-0.0056,6.5e-06,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,8.6e-05,0.00059,0.00059,5.3e-05,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,1e-05,0.04,0.04,0.029,0,0,0,0,0,0,0,0
|
||||
9090000,0.7,0.002,-0.014,0.71,-0.046,0.03,-0.14,-0.052,0.037,-3.7e+02,-0.0015,-0.0056,1.7e-07,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,0.0006,0.0006,5.2e-05,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,1e-05,0.04,0.04,0.028,0,0,0,0,0,0,0,0
|
||||
9190000,0.7,0.002,-0.014,0.71,-0.047,0.031,-0.14,-0.057,0.04,-3.7e+02,-0.0015,-0.0056,1.6e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,8.3e-05,0.00062,0.00062,5e-05,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.027,0,0,0,0,0,0,0,0
|
||||
9290000,0.7,0.002,-0.014,0.71,-0.047,0.032,-0.14,-0.059,0.04,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,8.2e-05,0.00062,0.00062,4.9e-05,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.025,0,0,0,0,0,0,0,0
|
||||
9390000,0.7,0.002,-0.014,0.71,-0.049,0.034,-0.14,-0.064,0.043,-3.7e+02,-0.0015,-0.0056,1.5e-05,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,8e-05,0.00064,0.00064,4.8e-05,1.7,1.7,0.093,5.9,5.9,0.086,0.00013,0.00013,1e-05,0.04,0.04,0.024,0,0,0,0,0,0,0,0
|
||||
9490000,0.7,0.002,-0.014,0.71,-0.049,0.034,-0.13,-0.065,0.044,-3.7e+02,-0.0015,-0.0056,2.8e-05,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,7.9e-05,0.00064,0.00064,4.7e-05,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.023,0,0,0,0,0,0,0,0
|
||||
9590000,0.7,0.002,-0.014,0.71,-0.052,0.036,-0.13,-0.07,0.047,-3.7e+02,-0.0015,-0.0056,3e-05,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,7.8e-05,0.00066,0.00066,4.6e-05,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.021,0,0,0,0,0,0,0,0
|
||||
9690000,0.7,0.002,-0.014,0.71,-0.051,0.037,-0.12,-0.071,0.047,-3.7e+02,-0.0015,-0.0056,1.5e-05,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,0.00065,0.00065,4.5e-05,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,1e-05,0.04,0.04,0.02,0,0,0,0,0,0,0,0
|
||||
9790000,0.7,0.002,-0.014,0.71,-0.052,0.039,-0.11,-0.077,0.05,-3.7e+02,-0.0015,-0.0056,2.3e-05,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,0.00067,0.00067,4.4e-05,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.019,0,0,0,0,0,0,0,0
|
||||
9890000,0.7,0.002,-0.014,0.71,-0.051,0.039,-0.11,-0.076,0.05,-3.7e+02,-0.0015,-0.0056,2.1e-05,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,7.6e-05,0.00067,0.00067,4.3e-05,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.018,0,0,0,0,0,0,0,0
|
||||
9990000,0.7,0.0021,-0.014,0.71,-0.053,0.04,-0.1,-0.082,0.054,-3.7e+02,-0.0015,-0.0056,1.3e-05,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,7.5e-05,0.00069,0.00069,4.2e-05,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,1e-05,0.04,0.04,0.017,0,0,0,0,0,0,0,0
|
||||
10090000,0.7,0.0021,-0.014,0.71,-0.05,0.039,-0.096,-0.08,0.053,-3.7e+02,-0.0014,-0.0056,1.4e-05,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,0.00068,0.00068,4.2e-05,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.016,0,0,0,0,0,0,0,0
|
||||
10190000,0.7,0.0021,-0.014,0.71,-0.052,0.042,-0.096,-0.085,0.057,-3.7e+02,-0.0014,-0.0056,-7.6e-06,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,0.0007,0.0007,4.1e-05,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,1e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0
|
||||
10290000,0.7,0.0021,-0.014,0.71,-0.053,0.043,-0.084,-0.091,0.061,-3.7e+02,-0.0014,-0.0056,-2.2e-05,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,0.00072,0.00072,4e-05,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0
|
||||
10390000,0.7,0.002,-0.014,0.71,0.0096,-0.019,0.0096,0.00087,-0.0017,-3.7e+02,-0.0014,-0.0056,-2.3e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,0.00075,0.00075,4e-05,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,1e-05,0.04,0.04,0.013,0,0,0,0,0,0,0,0
|
||||
10490000,0.7,0.0021,-0.014,0.71,0.0086,-0.017,0.023,0.0018,-0.0035,-3.7e+02,-0.0014,-0.0056,-3.8e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,0.00077,0.00077,3.9e-05,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,9.9e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
|
||||
10590000,0.7,0.0022,-0.014,0.71,0.0081,-0.0063,0.026,0.0018,-0.00081,-3.7e+02,-0.0014,-0.0056,-4e-05,-0.00026,2.6e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.00078,0.00078,3.9e-05,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,9.9e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
|
||||
10690000,0.7,0.0023,-0.014,0.71,0.0062,-0.0056,0.03,0.0026,-0.0014,-3.7e+02,-0.0014,-0.0056,-4.6e-05,-0.00026,2.7e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.0008,0.0008,3.8e-05,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,9.9e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
|
||||
10790000,0.7,0.0023,-0.014,0.71,0.0057,-0.0028,0.024,0.0027,-0.00071,-3.7e+02,-0.0014,-0.0055,-4.7e-05,-0.00041,0.00014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.00077,0.00077,3.8e-05,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,9.8e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
|
||||
10890000,0.7,0.0022,-0.014,0.71,0.0046,-0.0014,0.02,0.0032,-0.00089,-3.7e+02,-0.0014,-0.0055,-5e-05,-0.00041,0.00014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.0008,0.0008,3.8e-05,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,9.8e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
|
||||
10990000,0.7,0.0022,-0.014,0.71,0.0073,0.0036,0.014,0.0048,-0.0022,-3.7e+02,-0.0013,-0.0055,-4e-05,-0.00079,0.00072,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.00073,0.00073,3.7e-05,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,9.7e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
|
||||
11090000,0.7,0.0022,-0.014,0.71,0.0062,0.0062,0.019,0.0054,-0.0018,-3.7e+02,-0.0013,-0.0055,-2.8e-05,-0.0008,0.00072,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.00075,0.00075,3.7e-05,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,9.7e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
|
||||
11190000,0.7,0.0021,-0.014,0.71,0.011,0.0086,0.0077,0.0068,-0.0027,-3.7e+02,-0.0013,-0.0055,-4.3e-05,-0.00088,0.0012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00065,0.00065,3.7e-05,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,9.6e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
||||
11290000,0.7,0.0021,-0.014,0.71,0.011,0.011,0.0074,0.0079,-0.0017,-3.7e+02,-0.0013,-0.0055,-6.5e-05,-0.00089,0.0012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00067,0.00067,3.6e-05,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,9.6e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
||||
11390000,0.7,0.0022,-0.014,0.71,0.0058,0.0094,0.0017,0.0056,-0.0019,-3.7e+02,-0.0013,-0.0055,-8.1e-05,-0.00045,0.00078,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00055,0.00055,3.6e-05,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,9.5e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
||||
11490000,0.7,0.0022,-0.014,0.71,0.0035,0.012,0.0025,0.0061,-0.00084,-3.7e+02,-0.0013,-0.0055,-0.00011,-0.00046,0.00078,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00057,0.00057,3.6e-05,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,9.5e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
||||
11590000,0.7,0.0021,-0.014,0.71,-0.0011,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,-0.00012,-2.2e-05,0.00063,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00047,0.00047,3.6e-05,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,9.4e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
11690000,0.7,0.0021,-0.014,0.71,-0.0038,0.014,-0.0079,0.0043,-0.00022,-3.7e+02,-0.0014,-0.0056,-0.00013,-1.3e-05,0.00062,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00048,0.00048,3.5e-05,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,9.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
11790000,0.7,0.0021,-0.014,0.71,-0.0097,0.013,-0.0098,0.0019,0.00058,-3.7e+02,-0.0014,-0.0056,-0.00014,0.0001,0.00041,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.0004,0.0004,3.5e-05,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.4e-05,9.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
11890000,0.7,0.0021,-0.014,0.71,-0.011,0.014,-0.011,0.00086,0.002,-3.7e+02,-0.0014,-0.0056,-0.00015,9.7e-05,0.00041,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00041,0.00041,3.5e-05,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.4e-05,9.2e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
11990000,0.7,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.00025,0.0023,-3.7e+02,-0.0014,-0.0056,-0.00015,0.00024,0.00042,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00034,0.00034,3.5e-05,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,9.2e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12090000,0.7,0.0022,-0.014,0.71,-0.014,0.016,-0.022,-0.0016,0.0038,-3.7e+02,-0.0014,-0.0056,-0.00014,0.00026,0.00041,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00035,0.00035,3.5e-05,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,9.1e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12190000,0.7,0.0018,-0.014,0.71,-0.0077,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,-0.00014,0.00052,0.0009,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.0003,0.0003,3.5e-05,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12290000,0.7,0.0018,-0.014,0.71,-0.01,0.015,-0.016,0.00061,0.0033,-3.7e+02,-0.0013,-0.0057,-0.00013,0.00049,0.00092,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00031,0.00031,3.4e-05,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12390000,0.7,0.0014,-0.014,0.71,-0.0049,0.011,-0.015,0.0031,0.0017,-3.7e+02,-0.0013,-0.0058,-0.00015,0.00065,0.0012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00027,0.00027,3.4e-05,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,8.9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12490000,0.7,0.0014,-0.014,0.71,-0.006,0.013,-0.018,0.0025,0.0029,-3.7e+02,-0.0013,-0.0058,-0.00016,0.00065,0.0012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00028,0.00028,3.4e-05,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,8.8e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
||||
12590000,0.7,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0027,0.0015,-3.7e+02,-0.0013,-0.0058,-0.00016,0.00079,0.00096,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00025,0.00025,3.4e-05,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,8.8e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0
|
||||
12690000,0.7,0.0015,-0.014,0.71,-0.014,0.013,-0.027,-0.0041,0.0026,-3.7e+02,-0.0013,-0.0058,-0.00018,0.00081,0.00094,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00026,0.00026,3.4e-05,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,8.7e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0
|
||||
12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0093,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0058,-0.00017,0.00085,0.00088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00023,0.00023,3.4e-05,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,8.6e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0
|
||||
12890000,0.7,0.0015,-0.014,0.71,-0.021,0.0093,-0.029,-0.0096,0.0022,-3.7e+02,-0.0014,-0.0058,-0.00017,0.00078,0.00094,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00024,0.00024,3.4e-05,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,8.6e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0
|
||||
12990000,0.7,0.0012,-0.014,0.71,-0.0082,0.0067,-0.03,-0.00099,0.0012,-3.7e+02,-0.0013,-0.0059,-0.00015,0.00077,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00022,0.00022,3.4e-05,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,8.5e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
|
||||
13090000,0.7,0.0012,-0.014,0.71,-0.0089,0.0069,-0.03,-0.0018,0.0018,-3.7e+02,-0.0013,-0.0059,-0.00017,0.00073,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00023,0.00023,3.4e-05,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,8.4e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
|
||||
13190000,0.7,0.00096,-0.014,0.71,0.00012,0.0063,-0.027,0.0044,0.0012,-3.7e+02,-0.0012,-0.0059,-0.00017,0.00058,0.0012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,8.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
|
||||
13290000,0.7,0.00097,-0.014,0.71,-0.00014,0.0071,-0.024,0.0045,0.0018,-3.7e+02,-0.0012,-0.0059,-0.00015,0.00046,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00022,0.00022,3.4e-05,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,8.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
|
||||
13390000,0.7,0.00082,-0.014,0.71,0.00065,0.0061,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,-0.00013,0.00029,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,8.2e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0
|
||||
13490000,0.7,0.00085,-0.014,0.71,0.00015,0.006,-0.019,0.0034,0.0017,-3.7e+02,-0.0012,-0.0059,-0.00012,0.0002,0.0014,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,8.1e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0
|
||||
13590000,0.7,0.00079,-0.014,0.71,0.00039,0.0062,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.0059,-0.00013,0.00017,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,8.1e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0
|
||||
13690000,0.7,0.00077,-0.014,0.71,0.0011,0.008,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.0059,-0.00011,0.0002,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,8e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0
|
||||
13790000,0.7,0.00065,-0.014,0.71,0.0016,0.0038,-0.027,0.0035,-0.00062,-3.7e+02,-0.0011,-0.006,-0.00011,-1.6e-05,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,7.9e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0
|
||||
13890000,0.7,0.00062,-0.014,0.71,0.0021,0.0037,-0.031,0.0037,-0.00027,-3.7e+02,-0.0011,-0.006,-9.1e-05,1.6e-05,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,7.8e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0
|
||||
13990000,0.7,0.00055,-0.014,0.71,0.0024,0.0012,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,-8.7e-05,-0.00025,0.001,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,7.8e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0
|
||||
14090000,0.7,0.00053,-0.014,0.71,0.0024,0.0014,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,-5.9e-05,-0.00024,0.001,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,7.7e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0
|
||||
14190000,0.7,0.00043,-0.014,0.71,0.0058,0.00081,-0.033,0.0068,-0.0016,-3.7e+02,-0.0011,-0.006,-4.4e-05,-0.00022,0.00074,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,7.6e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0
|
||||
14290000,0.7,0.00044,-0.014,0.71,0.0065,0.0016,-0.032,0.0074,-0.0015,-3.7e+02,-0.0011,-0.006,-3.2e-05,-0.00029,0.0008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,7.5e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0
|
||||
14390000,0.7,0.00036,-0.014,0.71,0.0083,0.0025,-0.034,0.0087,-0.0013,-3.7e+02,-0.0011,-0.006,-3.1e-06,-0.0003,0.00056,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,7.4e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0
|
||||
14490000,0.7,0.00034,-0.014,0.71,0.0083,0.0037,-0.037,0.0096,-0.001,-3.7e+02,-0.0011,-0.006,7e-06,-0.00024,0.00052,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,7.4e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0
|
||||
14590000,0.7,0.00033,-0.013,0.71,0.0048,0.0021,-0.037,0.006,-0.0024,-3.7e+02,-0.0011,-0.006,1e-05,-0.00062,0.00092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,7.3e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0
|
||||
14690000,0.7,0.00029,-0.013,0.71,0.0062,-0.00082,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.006,3.3e-05,-0.00072,0.001,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,7.2e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0
|
||||
14790000,0.7,0.00031,-0.013,0.71,0.0029,-0.0024,-0.03,0.0037,-0.0034,-3.7e+02,-0.0012,-0.0061,4.1e-05,-0.0011,0.0015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,7.1e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0
|
||||
14890000,0.7,0.00031,-0.013,0.71,0.0044,-0.0014,-0.033,0.0041,-0.0036,-3.7e+02,-0.0012,-0.0061,5.6e-05,-0.0011,0.0015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.00019,3.4e-05,0.048,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,7.1e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0
|
||||
14990000,0.7,0.0003,-0.013,0.71,0.0033,-0.0016,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,5.4e-05,-0.0012,0.0017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,7e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0
|
||||
15090000,0.7,0.00023,-0.013,0.71,0.0036,-0.0018,-0.032,0.0035,-0.003,-3.7e+02,-0.0012,-0.0061,5.7e-05,-0.0011,0.0017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.9e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0
|
||||
15190000,0.7,0.00024,-0.013,0.71,0.003,-0.00058,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,5.6e-05,-0.0011,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.8e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0
|
||||
15290000,0.7,0.00021,-0.013,0.71,0.0036,-0.0004,-0.027,0.0031,-0.0025,-3.7e+02,-0.0012,-0.0061,7.2e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.7e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0
|
||||
15390000,0.7,0.00021,-0.013,0.71,0.0028,-7.6e-05,-0.024,0.00054,-0.002,-3.7e+02,-0.0012,-0.0061,0.00011,-0.0013,0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.7e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0
|
||||
15490000,0.7,0.00023,-0.013,0.71,0.0041,-0.00044,-0.024,0.00089,-0.002,-3.7e+02,-0.0012,-0.0061,9.1e-05,-0.0012,0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.6e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0
|
||||
15590000,0.7,0.00024,-0.013,0.71,0.0022,-0.00045,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,8.2e-05,-0.0013,0.0024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.5e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0
|
||||
15690000,0.7,0.00025,-0.013,0.71,0.0025,-0.00061,-0.023,-0.0011,-0.0017,-3.7e+02,-0.0012,-0.0061,8.4e-05,-0.0013,0.0024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,6.4e-06,0.035,0.035,0.0033,0,0,0,0,0,0,0,0
|
||||
15790000,0.7,0.00021,-0.013,0.71,0.003,-0.0023,-0.026,-0.00099,-0.0028,-3.7e+02,-0.0012,-0.0061,8.7e-05,-0.0015,0.0024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0
|
||||
15890000,0.7,0.00016,-0.013,0.71,0.0039,-0.0028,-0.024,-0.00062,-0.0031,-3.7e+02,-0.0012,-0.0061,9.3e-05,-0.0015,0.0024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0
|
||||
15990000,0.7,0.0001,-0.013,0.71,0.0038,-0.0037,-0.019,-0.00068,-0.0038,-3.7e+02,-0.0012,-0.0061,0.00012,-0.0018,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.2e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0
|
||||
16090000,0.7,0.0001,-0.013,0.71,0.0055,-0.0039,-0.016,-0.00024,-0.0042,-3.7e+02,-0.0012,-0.0061,0.00015,-0.0019,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6.1e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0
|
||||
16190000,0.7,0.00013,-0.013,0.71,0.0055,-0.0031,-0.014,-0.00043,-0.0034,-3.7e+02,-0.0012,-0.0061,0.00016,-0.0018,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0
|
||||
16290000,0.7,0.00015,-0.013,0.71,0.0071,-0.0039,-0.016,0.0002,-0.0038,-3.7e+02,-0.0012,-0.0061,0.00019,-0.0018,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,6e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0
|
||||
16390000,0.7,0.00013,-0.013,0.71,0.006,-0.0042,-0.015,-0.0001,-0.003,-3.7e+02,-0.0013,-0.0061,0.00019,-0.0016,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,5.9e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0
|
||||
16490000,0.7,0.00015,-0.013,0.71,0.0052,-0.0037,-0.018,0.00043,-0.0034,-3.7e+02,-0.0013,-0.0061,0.0002,-0.0016,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,5.8e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0
|
||||
16590000,0.7,0.00041,-0.013,0.71,0.0016,-0.001,-0.018,-0.0025,-2.7e-05,-3.7e+02,-0.0013,-0.006,0.0002,-0.00093,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.4e-05,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,5.7e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0
|
||||
16690000,0.7,0.0004,-0.013,0.71,0.0018,-0.00052,-0.015,-0.0023,-0.0001,-3.7e+02,-0.0013,-0.006,0.00019,-0.00099,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00016,3.4e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,5.7e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0
|
||||
16790000,0.7,0.00054,-0.013,0.71,-0.0016,0.0017,-0.014,-0.0047,0.0026,-3.7e+02,-0.0013,-0.006,0.0002,-0.00042,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.4e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,5.6e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0
|
||||
16890000,0.7,0.00056,-0.013,0.71,-0.0019,0.0025,-0.011,-0.0048,0.0028,-3.7e+02,-0.0013,-0.006,0.00019,-0.00046,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.4e-05,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,5.5e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0
|
||||
16990000,0.7,0.00049,-0.013,0.71,-0.0018,0.00051,-0.01,-0.0053,0.0009,-3.7e+02,-0.0013,-0.006,0.00018,-0.00088,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,5.5e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0
|
||||
17090000,0.7,0.00046,-0.013,0.71,-0.001,0.0015,-0.01,-0.0054,0.00098,-3.7e+02,-0.0013,-0.006,0.00018,-0.00087,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.3e-05,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,5.4e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0
|
||||
17190000,0.71,0.00045,-0.013,0.71,-0.00056,0.0014,-0.011,-0.0057,-0.00048,-3.7e+02,-0.0014,-0.006,0.0002,-0.0012,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,5.3e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0
|
||||
17290000,0.7,0.00042,-0.013,0.71,0.0015,0.0025,-0.0066,-0.0056,-0.0003,-3.7e+02,-0.0014,-0.006,0.00019,-0.0013,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,5.2e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0
|
||||
17390000,0.71,0.00039,-0.013,0.71,0.0022,0.0017,-0.0047,-0.0047,-0.0016,-3.7e+02,-0.0014,-0.006,0.00021,-0.0016,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,5.2e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0
|
||||
17490000,0.71,0.00038,-0.013,0.71,0.0027,0.0012,-0.003,-0.0045,-0.0014,-3.7e+02,-0.0014,-0.006,0.00021,-0.0016,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,5.1e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0
|
||||
17590000,0.71,0.00029,-0.013,0.71,0.004,5.6e-05,0.0025,-0.0038,-0.0026,-3.7e+02,-0.0014,-0.0061,0.00022,-0.002,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,5e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0
|
||||
17690000,0.71,0.00026,-0.013,0.71,0.0048,0.00078,0.0019,-0.0033,-0.0025,-3.7e+02,-0.0014,-0.0061,0.00023,-0.002,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,5e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0
|
||||
17790000,0.71,0.00017,-0.013,0.71,0.0074,0.00048,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,0.00027,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,4.9e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0
|
||||
17890000,0.71,0.00018,-0.013,0.71,0.0089,-0.00027,0.00069,-0.0013,-0.0021,-3.7e+02,-0.0013,-0.0061,0.00029,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,4.8e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0
|
||||
17990000,0.71,0.00012,-0.013,0.71,0.011,-0.002,0.0019,-0.0006,-0.0018,-3.7e+02,-0.0013,-0.0061,0.00028,-0.0019,0.0046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,4.8e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0
|
||||
18090000,0.71,0.00013,-0.013,0.71,0.011,-0.0022,0.0043,0.00051,-0.0021,-3.7e+02,-0.0013,-0.0061,0.00026,-0.0019,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,4.7e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0
|
||||
18190000,0.71,9.6e-05,-0.013,0.71,0.012,-0.0011,0.0056,0.0014,-0.0016,-3.7e+02,-0.0013,-0.0061,0.00028,-0.0018,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,4.7e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0
|
||||
18290000,0.71,3.7e-05,-0.012,0.71,0.012,-0.0017,0.0068,0.0026,-0.0018,-3.7e+02,-0.0013,-0.0061,0.00027,-0.0018,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,4.6e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0
|
||||
18390000,0.71,5.2e-05,-0.013,0.71,0.013,-4.9e-05,0.008,0.0031,-0.0013,-3.7e+02,-0.0013,-0.0061,0.0003,-0.0018,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,4.5e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0
|
||||
18490000,0.71,6.7e-05,-0.012,0.71,0.014,0.00037,0.0076,0.0046,-0.0013,-3.7e+02,-0.0013,-0.0061,0.0003,-0.0018,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,4.5e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0
|
||||
18590000,0.71,7.1e-05,-0.012,0.71,0.013,0.0006,0.0058,0.0035,-0.0011,-3.7e+02,-0.0014,-0.0061,0.00033,-0.0018,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00012,0.00012,3.3e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,4.4e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0
|
||||
18690000,0.71,4e-05,-0.012,0.71,0.014,-8.7e-05,0.0039,0.0048,-0.0011,-3.7e+02,-0.0014,-0.0061,0.00033,-0.0018,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,4.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0
|
||||
18790000,0.71,6.9e-05,-0.012,0.71,0.012,0.0002,0.0035,0.0037,-0.00085,-3.7e+02,-0.0014,-0.006,0.00032,-0.0018,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00012,0.00012,3.3e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,4.3e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0
|
||||
18890000,0.71,9.3e-05,-0.012,0.71,0.013,0.00071,0.0042,0.0049,-0.00077,-3.7e+02,-0.0014,-0.006,0.00035,-0.0018,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,4.2e-06,0.031,0.031,0.0007,0,0,0,0,0,0,0,0
|
||||
18990000,0.71,8e-05,-0.012,0.71,0.014,0.0016,0.0028,0.0063,-0.00065,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,4.2e-06,0.031,0.031,0.00066,0,0,0,0,0,0,0,0
|
||||
19090000,0.71,6.4e-05,-0.012,0.71,0.014,0.0022,0.0059,0.0077,-0.00043,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,4.1e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0
|
||||
19190000,0.71,6.6e-05,-0.012,0.71,0.014,0.0022,0.0059,0.0085,-0.00039,-3.7e+02,-0.0014,-0.0061,0.00037,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,4.1e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0
|
||||
19290000,0.71,8.8e-05,-0.012,0.71,0.015,0.0014,0.0086,0.0099,-0.00019,-3.7e+02,-0.0014,-0.0061,0.00037,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.2e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,4e-06,0.03,0.03,0.0006,0,0,0,0,0,0,0,0
|
||||
19390000,0.71,9.9e-05,-0.012,0.71,0.012,0.00051,0.012,0.008,-0.00022,-3.7e+02,-0.0014,-0.0061,0.00038,-0.0019,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,4e-06,0.03,0.03,0.00058,0,0,0,0,0,0,0,0
|
||||
19490000,0.71,0.00012,-0.012,0.71,0.011,-0.0002,0.0088,0.0091,-0.00021,-3.7e+02,-0.0014,-0.0061,0.0004,-0.0019,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,3.9e-06,0.03,0.03,0.00056,0,0,0,0,0,0,0,0
|
||||
19590000,0.71,0.00017,-0.012,0.71,0.0095,-0.0012,0.0081,0.0074,-0.00024,-3.7e+02,-0.0014,-0.0061,0.00043,-0.0019,0.0061,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,3.9e-06,0.03,0.03,0.00054,0,0,0,0,0,0,0,0
|
||||
19690000,0.71,0.00017,-0.012,0.71,0.0099,-0.0034,0.0096,0.0083,-0.00048,-3.7e+02,-0.0014,-0.0061,0.00042,-0.0019,0.0061,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,3.8e-06,0.03,0.03,0.00052,0,0,0,0,0,0,0,0
|
||||
19790000,0.71,0.00024,-0.012,0.71,0.0075,-0.0043,0.01,0.0068,-0.00039,-3.7e+02,-0.0014,-0.0061,0.00042,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,3.7e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19890000,0.71,0.00019,-0.012,0.71,0.0063,-0.0045,0.011,0.0075,-0.00084,-3.7e+02,-0.0014,-0.0061,0.00045,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,3.7e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19990000,0.71,0.00017,-0.012,0.71,0.0039,-0.0053,0.014,0.0061,-0.00071,-3.7e+02,-0.0014,-0.006,0.00049,-0.0018,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20090000,0.71,0.00017,-0.012,0.71,0.0036,-0.0072,0.014,0.0064,-0.0013,-3.7e+02,-0.0014,-0.006,0.00052,-0.0018,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20190000,0.71,0.00027,-0.012,0.71,0.0013,-0.0079,0.017,0.0042,-0.001,-3.7e+02,-0.0014,-0.006,0.00054,-0.0017,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.0001,0.0001,3.2e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20290000,0.71,0.00023,-0.012,0.71,0.00017,-0.0095,0.015,0.0042,-0.0019,-3.7e+02,-0.0014,-0.006,0.00055,-0.0017,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,3.5e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20390000,0.71,0.00025,-0.012,0.71,-0.0023,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0014,-0.006,0.00055,-0.0015,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,3.5e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20490000,0.71,0.00031,-0.012,0.71,-0.0027,-0.011,0.016,0.0021,-0.0025,-3.7e+02,-0.0014,-0.006,0.00055,-0.0015,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,3.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20590000,0.71,0.00033,-0.012,0.71,-0.0024,-0.011,0.013,0.0018,-0.002,-3.7e+02,-0.0014,-0.006,0.00054,-0.0014,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,3.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20690000,0.71,0.00035,-0.012,0.71,-0.0024,-0.012,0.015,0.0015,-0.0032,-3.7e+02,-0.0014,-0.006,0.00055,-0.0014,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,1.9e-06,3.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20790000,0.71,0.00038,-0.012,0.71,-0.0035,-0.011,0.015,0.0013,-0.0025,-3.7e+02,-0.0014,-0.006,0.00056,-0.0012,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,3.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20890000,0.71,0.00037,-0.012,0.71,-0.0039,-0.014,0.014,0.00092,-0.0037,-3.7e+02,-0.0014,-0.006,0.00058,-0.0012,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,3.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
20990000,0.71,0.00037,-0.012,0.71,-0.0041,-0.014,0.015,0.0026,-0.0031,-3.7e+02,-0.0014,-0.006,0.00058,-0.00095,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.9e-05,9.8e-05,3.1e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,3.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
21090000,0.71,0.00037,-0.012,0.71,-0.0043,-0.017,0.015,0.0022,-0.0046,-3.7e+02,-0.0014,-0.006,0.00059,-0.00096,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.9e-05,9.9e-05,3.1e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,3.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
21190000,0.71,0.00041,-0.012,0.71,-0.0035,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,0.00059,-0.00071,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.7e-05,9.7e-05,3.1e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21290000,0.71,0.00045,-0.012,0.71,-0.0041,-0.018,0.016,0.0033,-0.0054,-3.7e+02,-0.0014,-0.006,0.00061,-0.00071,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.8e-05,9.8e-05,3.1e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21390000,0.71,0.00049,-0.012,0.71,-0.0049,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,0.0006,-0.00033,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.6e-05,9.6e-05,3.1e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21490000,0.71,0.0005,-0.012,0.71,-0.0054,-0.018,0.015,0.0022,-0.0051,-3.7e+02,-0.0014,-0.006,0.00061,-0.00034,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.7e-05,9.7e-05,3.1e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21590000,0.71,0.00052,-0.012,0.71,-0.0059,-0.015,0.015,0.0018,-0.0031,-3.7e+02,-0.0014,-0.006,0.00061,1.1e-05,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.5e-05,9.5e-05,3.1e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21690000,0.71,0.00053,-0.012,0.71,-0.0058,-0.016,0.017,0.0012,-0.0047,-3.7e+02,-0.0014,-0.006,0.00062,8.7e-06,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.6e-05,9.5e-05,3.1e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21790000,0.71,0.00055,-0.012,0.71,-0.0064,-0.011,0.015,7.3e-06,-0.00073,-3.7e+02,-0.0014,-0.0059,0.0006,0.00054,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.4e-05,9.4e-05,3.1e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.2e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21890000,0.71,0.00055,-0.012,0.71,-0.0064,-0.012,0.016,-0.00064,-0.0019,-3.7e+02,-0.0014,-0.0059,0.0006,0.00053,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.5e-05,9.4e-05,3.1e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21990000,0.71,0.0006,-0.012,0.71,-0.0069,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-0.0014,-0.0059,0.0006,0.00097,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.3e-05,9.3e-05,3.1e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22090000,0.71,0.00062,-0.012,0.71,-0.0072,-0.0082,0.015,-0.0022,0.00065,-3.7e+02,-0.0014,-0.0059,0.0006,0.00096,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.4e-05,9.3e-05,3e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22190000,0.71,0.00059,-0.012,0.71,-0.007,-0.0073,0.015,-0.0019,0.0006,-3.7e+02,-0.0014,-0.0059,0.0006,0.001,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.2e-05,9.2e-05,3e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22290000,0.71,0.00063,-0.012,0.71,-0.0084,-0.008,0.015,-0.0026,-0.00017,-3.7e+02,-0.0014,-0.0059,0.00059,0.001,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.3e-05,9.3e-05,3e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22390000,0.71,0.0006,-0.012,0.71,-0.0089,-0.0075,0.017,-0.0023,-0.00016,-3.7e+02,-0.0014,-0.0059,0.0006,0.0011,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.1e-05,9.1e-05,3e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22490000,0.71,0.00061,-0.012,0.71,-0.0096,-0.0074,0.018,-0.0032,-0.00093,-3.7e+02,-0.0014,-0.0059,0.00059,0.0011,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.2e-05,9.2e-05,3e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22590000,0.71,0.00059,-0.012,0.71,-0.0093,-0.007,0.017,-0.0035,0.00015,-3.7e+02,-0.0014,-0.0059,0.0006,0.0013,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.1e-05,9.1e-05,3e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22690000,0.71,0.00062,-0.012,0.71,-0.011,-0.0067,0.018,-0.0044,-0.00053,-3.7e+02,-0.0014,-0.0059,0.0006,0.0013,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9.1e-05,9.1e-05,3e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22790000,0.71,0.00061,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00043,-3.7e+02,-0.0014,-0.0059,0.00057,0.0013,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22890000,0.71,0.00062,-0.012,0.71,-0.013,-0.0051,0.021,-0.0067,-0.00096,-3.7e+02,-0.0014,-0.0059,0.00057,0.0013,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
22990000,0.71,0.0006,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00085,-3.7e+02,-0.0014,-0.0059,0.00058,0.0014,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,3e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23090000,0.71,0.00056,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,0.00056,0.0014,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23190000,0.71,0.00063,-0.012,0.71,-0.015,-0.0065,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,0.00056,0.0015,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,2.9e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23290000,0.71,0.00057,-0.012,0.71,-0.015,-0.0078,0.024,-0.014,-0.002,-3.7e+02,-0.0014,-0.0059,0.00056,0.0015,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,2.9e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23390000,0.71,0.00066,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0017,-3.7e+02,-0.0014,-0.0059,0.00055,0.0015,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-0.0014,-0.0059,0.00056,0.0015,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.8e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,0.00055,0.0017,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-0.0014,-0.0059,0.00055,0.0017,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23790000,0.71,0.005,0.00064,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-0.0014,-0.0059,0.00055,0.002,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.7e-05,8.7e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23890000,0.71,0.0023,-0.0054,0.71,-0.11,-0.036,-0.2,-0.031,-0.005,-3.7e+02,-0.0014,-0.0059,0.00055,0.002,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.7e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
23990000,0.71,0.00095,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-0.0014,-0.0059,0.00055,0.0021,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.6e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24090000,0.71,0.0022,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,0.00056,0.0021,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.7e-05,2.9e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.7e-07,6.7e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,0.00056,0.0023,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.6e-05,2.8e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-07,6.4e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-0.0014,-0.0059,0.00056,0.0024,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.6e-05,2.8e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.4e-07,6.4e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24390000,0.71,0.0038,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-0.0013,-0.0059,0.00054,0.002,0.0046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24490000,0.71,0.0047,-0.0018,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-0.0013,-0.0059,0.00054,0.0021,0.0046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.5e-05,2.8e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24590000,0.71,0.0051,0.0018,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,0.00055,0.0019,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-0.0013,-0.0059,0.00056,0.0019,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,0.00055,0.0023,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.4e-05,8.4e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24890000,0.71,0.0066,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-0.0013,-0.0059,0.00054,0.0024,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.4e-05,8.4e-05,2.8e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
24990000,0.71,0.0084,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,0.00052,0.0033,0.0016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.3e-05,8.3e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.4e-07,5.4e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,0.00051,0.0033,0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.4e-05,8.3e-05,2.8e-05,0.018,0.017,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,0.00052,0.0029,0.00098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.3e-05,8.2e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-07,5.2e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,0.00052,0.0029,0.00098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.3e-05,8.3e-05,2.8e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,0.00052,0.0031,-0.00058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.2e-05,8.2e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,0.00052,0.0031,-0.00057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.2e-05,8.2e-05,2.7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,0.00052,0.0028,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8.1e-05,2.7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,0.00052,0.0028,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8.1e-05,2.7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,0.00053,0.0036,-0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-07,4.7e-07,1.7e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,0.00054,0.0036,-0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8e-05,2.7e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-07,4.7e-07,1.7e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,0.00054,0.0032,-0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-07,4.6e-07,1.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,0.00053,0.0032,-0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-07,4.6e-07,1.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,0.00053,0.0044,-0.0096,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.9e-05,2.7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-07,4.4e-07,1.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,0.00052,0.0044,-0.0096,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.9e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-07,4.5e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,0.00052,0.0031,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.8e-05,7.8e-05,2.7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-07,4.3e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,0.00052,0.0031,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.8e-05,7.8e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-07,4.3e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-0.00095,-0.0059,0.00049,0.0041,-0.014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.8e-05,7.7e-05,2.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-07,4.2e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-0.00095,-0.0059,0.00049,0.0041,-0.014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.8e-05,7.7e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-07,4.2e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-0.0009,-0.006,0.00048,0.0018,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.7e-05,2.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.1e-07,4.1e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-0.0009,-0.006,0.00049,0.0018,-0.016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.7e-05,2.7e-05,0.015,0.015,0.0081,0.043,0.043,0.035,4.1e-07,4.1e-07,1.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-0.00079,-0.006,0.00048,0.0026,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.6e-05,7.6e-05,2.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-0.00079,-0.006,0.00048,0.0026,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.6e-05,2.7e-05,0.015,0.015,0.0081,0.043,0.043,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.0059,0.00048,0.0037,-0.021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.6e-05,7.6e-05,2.7e-05,0.015,0.015,0.0081,0.045,0.045,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00078,-0.0059,0.00049,0.0036,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.7e-05,0.017,0.017,0.0081,0.049,0.049,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27390000,0.71,0.036,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00072,-0.0059,0.0005,0.0057,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.7e-05,0.017,0.017,0.0081,0.052,0.052,0.035,3.9e-07,3.9e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27490000,0.71,0.031,0.062,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-0.00072,-0.0059,0.00049,0.0056,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,0.00052,0.003,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.8e-05,7.8e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-07,4.3e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-0.00095,-0.0059,0.00049,0.004,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.8e-05,7.7e-05,2.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-07,4.2e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-0.00095,-0.0059,0.0005,0.004,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.8e-05,7.7e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-07,4.2e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-0.0009,-0.006,0.00049,0.0017,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.7e-05,2.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.1e-07,4.1e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-0.0009,-0.006,0.00049,0.0017,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.7e-05,2.7e-05,0.015,0.015,0.0081,0.043,0.043,0.035,4.1e-07,4.1e-07,1.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-0.00079,-0.006,0.00049,0.0025,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.6e-05,7.6e-05,2.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-0.00079,-0.006,0.00048,0.0025,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.6e-05,2.7e-05,0.015,0.015,0.0081,0.043,0.043,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.0059,0.00049,0.0036,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.6e-05,7.6e-05,2.7e-05,0.015,0.015,0.0081,0.045,0.045,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00078,-0.0059,0.00049,0.0036,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.7e-05,0.017,0.017,0.0081,0.049,0.049,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27390000,0.71,0.036,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00072,-0.0059,0.0005,0.0056,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.7e-05,0.017,0.017,0.0081,0.052,0.052,0.035,3.9e-07,3.9e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27490000,0.71,0.031,0.062,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-0.00072,-0.0059,0.0005,0.0055,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-0.00075,-0.0059,0.0005,0.0055,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.059,0.059,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-0.00075,-0.0059,0.00049,0.0055,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.7e-05,2.6e-05,0.019,0.019,0.0082,0.065,0.065,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-0.00075,-0.0058,0.00048,0.0057,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.067,0.067,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-0.00075,-0.0058,0.00048,0.0055,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0083,0.074,0.073,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-0.00079,-0.0058,0.00048,0.0051,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.019,0.019,0.0083,0.076,0.076,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-0.00079,-0.0058,0.00046,0.005,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0084,0.083,0.082,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-0.00082,-0.0058,0.00047,0.0047,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.089,-4.4,-2.4,-3.7e+02,-0.00082,-0.0058,0.00045,0.0045,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0086,0.092,0.092,0.036,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-0.00082,-0.0058,0.00044,0.0043,-0.015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.7e-05,2.5e-05,0.021,0.021,0.0087,0.099,0.099,0.036,3.7e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28490000,0.71,0.0026,0.0044,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-0.00082,-0.0058,0.00043,0.004,-0.014,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.022,0.022,0.0088,0.11,0.11,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28590000,0.71,0.00081,0.00092,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-0.00082,-0.0058,0.00043,0.0036,-0.013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.023,0.024,0.0089,0.12,0.12,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28690000,0.71,0.0001,5.7e-06,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-0.00082,-0.0058,0.00042,0.0032,-0.012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.025,0.025,0.009,0.12,0.12,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28790000,0.71,-0.00019,-0.00023,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-0.00089,-0.0058,0.00042,0.00016,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28890000,0.71,-0.0002,-1.4e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-0.00089,-0.0058,0.00042,-0.00027,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.4e-05,0.025,0.025,0.009,0.14,0.14,0.036,3.7e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28990000,0.71,-1e-05,0.00044,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-0.00098,-0.0058,0.00041,-0.0023,-0.026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.8e-05,7.7e-05,2.4e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.6e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29090000,0.71,0.00014,0.00085,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-0.00098,-0.0058,0.0004,-0.0028,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29190000,0.71,0.00036,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-0.001,-0.0058,0.0004,-0.0047,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-07,3.6e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29290000,0.71,0.00072,0.0021,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-0.001,-0.0058,0.00039,-0.0053,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-07,3.6e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29390000,0.71,0.0013,0.0036,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-0.0011,-0.0058,0.00037,-0.0068,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.024,0.009,0.16,0.16,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-0.00075,-0.0059,0.00049,0.0054,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.7e-05,2.6e-05,0.019,0.019,0.0082,0.065,0.065,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-0.00075,-0.0058,0.00048,0.0056,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.067,0.067,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-0.00075,-0.0058,0.00048,0.0054,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0083,0.074,0.073,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-0.00079,-0.0058,0.00049,0.005,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.019,0.019,0.0083,0.076,0.076,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-0.00079,-0.0058,0.00047,0.0049,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0084,0.083,0.082,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-0.00082,-0.0058,0.00047,0.0046,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.089,-4.4,-2.4,-3.7e+02,-0.00082,-0.0058,0.00045,0.0044,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0086,0.092,0.092,0.036,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-0.00082,-0.0058,0.00044,0.0042,-0.015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.7e-05,2.5e-05,0.021,0.021,0.0087,0.099,0.099,0.036,3.7e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28490000,0.71,0.0026,0.0044,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-0.00082,-0.0058,0.00044,0.0039,-0.014,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.022,0.022,0.0088,0.11,0.11,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28590000,0.71,0.00079,0.00091,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-0.00082,-0.0058,0.00044,0.0036,-0.013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.023,0.024,0.0089,0.12,0.12,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28690000,0.71,8.9e-05,-2.1e-06,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-0.00082,-0.0058,0.00043,0.0031,-0.012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.025,0.025,0.009,0.12,0.12,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28790000,0.71,-0.0002,-0.00024,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-0.00089,-0.0058,0.00043,8.2e-05,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28890000,0.71,-0.00022,-2.2e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-0.00089,-0.0058,0.00042,-0.00035,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.4e-05,0.025,0.025,0.009,0.14,0.14,0.036,3.7e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
28990000,0.71,-2.5e-05,0.00044,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-0.00098,-0.0058,0.00041,-0.0024,-0.026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.8e-05,7.7e-05,2.4e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.6e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29090000,0.71,0.00013,0.00084,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-0.00098,-0.0058,0.0004,-0.0029,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29190000,0.71,0.00035,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-0.001,-0.0058,0.00041,-0.0048,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-07,3.6e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29290000,0.71,0.0007,0.0021,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-0.001,-0.0058,0.0004,-0.0054,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.025,0.025,0.0091,0.16,0.16,0.036,3.6e-07,3.6e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29390000,0.71,0.0013,0.0036,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-0.0011,-0.0058,0.00037,-0.0069,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.024,0.009,0.16,0.16,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-0.0011,-0.0058,0.00037,-0.0073,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-0.0011,-0.0057,0.00036,-0.0096,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.025,0.009,0.17,0.17,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-0.0011,-0.0057,0.00035,-0.01,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-0.0011,-0.0057,0.00037,-0.0097,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.025,0.009,0.17,0.17,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-0.0011,-0.0057,0.00036,-0.01,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.94,-8.5,-4.1,-3.7e+02,-0.0012,-0.0057,0.00035,-0.012,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29890000,0.71,0.0029,0.0073,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-0.0012,-0.0057,0.00034,-0.013,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29990000,0.71,0.003,0.0075,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-0.0012,-0.0057,0.00032,-0.015,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.18,0.18,0.036,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-0.0012,-0.0057,0.00031,-0.015,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-0.0013,-0.0057,0.00031,-0.016,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.19,0.19,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-0.0013,-0.0057,0.0003,-0.017,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.21,0.21,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30390000,0.71,0.003,0.007,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-0.0013,-0.0057,0.0003,-0.018,-0.024,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.2,0.2,0.036,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29890000,0.71,0.0028,0.0073,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-0.0012,-0.0057,0.00034,-0.013,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
29990000,0.71,0.003,0.0075,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-0.0012,-0.0057,0.00033,-0.015,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.18,0.18,0.036,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-0.0012,-0.0057,0.00032,-0.015,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30190000,0.71,0.0031,0.0073,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-0.0013,-0.0057,0.00032,-0.017,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.19,0.19,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30290000,0.71,0.003,0.0072,0.71,-2,-1,0.87,-9.6,-4.6,-3.7e+02,-0.0013,-0.0057,0.00031,-0.017,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.21,0.21,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30390000,0.71,0.003,0.007,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-0.0013,-0.0057,0.0003,-0.018,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.2,0.2,0.036,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-0.0013,-0.0057,0.0003,-0.018,-0.024,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.026,0.026,0.0091,0.22,0.22,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30590000,0.71,0.0028,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-0.0013,-0.0057,0.0003,-0.019,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-0.0013,-0.0057,0.0003,-0.02,-0.022,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.23,0.23,0.037,3.2e-07,3.2e-07,1.1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30790000,0.71,0.0026,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-0.0013,-0.0057,0.00028,-0.02,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30890000,0.71,0.0025,0.0054,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0057,0.00028,-0.021,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.24,0.24,0.037,3.2e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30990000,0.71,0.0024,0.005,0.71,-1.9,-0.96,0.76,-11,-5.3,-3.7e+02,-0.0013,-0.0057,0.00027,-0.022,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.1e-07,3.1e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30790000,0.71,0.0026,0.0058,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-0.0013,-0.0057,0.00029,-0.021,-0.022,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30890000,0.71,0.0024,0.0054,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0057,0.00029,-0.021,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.24,0.24,0.037,3.2e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
30990000,0.71,0.0024,0.005,0.71,-1.9,-0.96,0.76,-11,-5.3,-3.7e+02,-0.0013,-0.0057,0.00028,-0.022,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.1e-07,3.1e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-0.0013,-0.0057,0.00027,-0.022,-0.018,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.25,0.25,0.037,3.1e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31190000,0.71,0.0022,0.0042,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-0.0014,-0.0057,0.00026,-0.023,-0.016,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-07,3.1e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31290000,0.71,0.0019,0.0037,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-0.0014,-0.0057,0.00026,-0.024,-0.014,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.0089,0.25,0.25,0.037,3.1e-07,3.1e-07,9.9e-07,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31390000,0.71,0.0018,0.0032,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-0.0014,-0.0057,0.00025,-0.025,-0.012,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-07,3.1e-07,9.9e-07,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31490000,0.71,0.0016,0.0026,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-0.0014,-0.0057,0.00024,-0.025,-0.011,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.026,0.026,0.0088,0.26,0.26,0.037,3.1e-07,3.1e-07,9.8e-07,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31590000,0.71,0.0016,0.0023,0.71,-1.7,-0.91,0.72,-12,-5.8,-3.7e+02,-0.0014,-0.0057,0.00024,-0.026,-0.0095,-0.099,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3e-07,3e-07,9.7e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
31690000,0.71,0.0013,0.0016,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-0.0014,-0.0057,0.00024,-0.027,-0.0083,-0.099,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3e-07,3e-07,9.6e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
31790000,0.71,0.0011,0.001,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-0.0014,-0.0057,0.00024,-0.028,-0.0064,-0.098,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-07,3e-07,9.5e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
31890000,0.71,0.00087,0.00033,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-0.0014,-0.0057,0.00024,-0.028,-0.0051,-0.097,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.2e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-07,3e-07,9.4e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
31990000,0.71,0.00074,-0.00013,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-0.0014,-0.0057,0.00023,-0.029,-0.0032,-0.097,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-07,3e-07,9.3e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
32090000,0.71,0.00045,-0.00085,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0057,0.00023,-0.03,-0.0017,-0.096,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-07,3e-07,9.3e-07,0.027,0.026,0.0005,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,-0.0014,-0.0057,0.00021,-0.031,0.00037,-0.096,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-07,2.9e-07,9.2e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32290000,0.71,9.8e-06,-0.0024,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-0.0014,-0.0057,0.00021,-0.031,0.002,-0.095,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0086,0.3,0.3,0.037,2.9e-07,2.9e-07,9.1e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32390000,0.71,-0.00017,-0.003,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-0.0014,-0.0057,0.00021,-0.032,0.0029,-0.095,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-07,2.9e-07,9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32490000,0.71,-0.00029,-0.0032,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-0.0014,-0.0057,0.00021,-0.032,0.004,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-07,2.9e-07,9e-07,0.027,0.025,0.0005,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,-0.0015,-0.0057,0.0002,-0.033,0.0048,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.024,0.025,0.0084,0.31,0.31,0.036,2.9e-07,2.9e-07,8.9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32690000,0.71,-0.00033,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.0053,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-07,2.9e-07,8.8e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32790000,0.71,-0.0003,-0.0035,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.0063,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.024,0.025,0.0084,0.31,0.31,0.036,2.8e-07,2.8e-07,8.7e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32890000,0.71,-0.0002,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-0.0015,-0.0057,0.00018,-0.034,0.0074,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.8e-07,2.9e-07,8.7e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32990000,0.71,-7.4e-05,-0.0034,0.71,-1.3,-0.76,0.7,-15,-7,-3.7e+02,-0.0015,-0.0057,0.00019,-0.034,0.0087,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.024,0.024,0.0083,0.32,0.32,0.036,2.8e-07,2.8e-07,8.6e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
33090000,0.71,-0.00011,-0.0034,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-0.0015,-0.0057,0.0002,-0.035,0.0092,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-07,2.8e-07,8.5e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-0.0015,-0.0057,0.0002,-0.035,0.0099,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.1e-05,0.024,0.024,0.0083,0.33,0.33,0.036,2.8e-07,2.8e-07,8.5e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
31190000,0.71,0.0022,0.0042,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-0.0014,-0.0057,0.00027,-0.024,-0.016,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-07,3.1e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31290000,0.71,0.0019,0.0037,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-0.0014,-0.0057,0.00027,-0.024,-0.014,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.0089,0.25,0.25,0.037,3.1e-07,3.1e-07,9.9e-07,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31390000,0.71,0.0018,0.0032,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-0.0014,-0.0057,0.00026,-0.025,-0.013,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-07,3.1e-07,9.9e-07,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31490000,0.71,0.0016,0.0026,0.71,-1.7,-0.92,0.73,-12,-5.8,-3.7e+02,-0.0014,-0.0057,0.00025,-0.026,-0.011,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.026,0.026,0.0088,0.26,0.26,0.037,3.1e-07,3.1e-07,9.8e-07,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
31590000,0.71,0.0015,0.0023,0.71,-1.7,-0.91,0.72,-12,-5.8,-3.7e+02,-0.0014,-0.0057,0.00025,-0.026,-0.0098,-0.099,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3e-07,3e-07,9.7e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
31690000,0.71,0.0013,0.0016,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-0.0014,-0.0057,0.00025,-0.027,-0.0086,-0.099,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3e-07,3e-07,9.6e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
31790000,0.71,0.0011,0.001,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-0.0014,-0.0057,0.00025,-0.028,-0.0067,-0.098,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-07,3e-07,9.5e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
31890000,0.71,0.00086,0.00032,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-0.0014,-0.0057,0.00024,-0.028,-0.0054,-0.097,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.2e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-07,3e-07,9.4e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
31990000,0.71,0.00072,-0.00013,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-0.0014,-0.0057,0.00024,-0.029,-0.0035,-0.097,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-07,3e-07,9.3e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
32090000,0.71,0.00044,-0.00085,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0057,0.00023,-0.03,-0.002,-0.096,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-07,3e-07,9.3e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
32190000,0.71,0.00023,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-0.0014,-0.0057,0.00021,-0.031,7.9e-05,-0.096,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-07,2.9e-07,9.2e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32290000,0.71,-5.1e-06,-0.0024,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-0.0014,-0.0057,0.00021,-0.032,0.0017,-0.095,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0086,0.3,0.3,0.037,2.9e-07,2.9e-07,9.1e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32390000,0.71,-0.00019,-0.003,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-0.0014,-0.0057,0.00021,-0.032,0.0026,-0.095,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-07,2.9e-07,9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32490000,0.71,-0.00031,-0.0032,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-0.0014,-0.0057,0.00021,-0.032,0.0037,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-07,2.9e-07,9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32590000,0.71,-0.00031,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-0.0015,-0.0057,0.00021,-0.033,0.0045,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.024,0.025,0.0084,0.31,0.31,0.036,2.9e-07,2.9e-07,8.9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32690000,0.71,-0.00035,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.005,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-07,2.9e-07,8.8e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32790000,0.71,-0.00031,-0.0035,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.006,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.024,0.025,0.0084,0.31,0.31,0.036,2.8e-07,2.8e-07,8.7e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32890000,0.71,-0.00022,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-0.0015,-0.0057,0.00019,-0.034,0.0071,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.8e-07,2.9e-07,8.7e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
32990000,0.71,-8.9e-05,-0.0034,0.71,-1.3,-0.76,0.7,-15,-7,-3.7e+02,-0.0015,-0.0057,0.0002,-0.034,0.0084,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.024,0.024,0.0083,0.32,0.32,0.036,2.8e-07,2.8e-07,8.6e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
33090000,0.71,-0.00012,-0.0034,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-0.0015,-0.0057,0.0002,-0.035,0.0089,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-07,2.8e-07,8.5e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-0.0015,-0.0057,0.00021,-0.035,0.0097,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.1e-05,0.024,0.024,0.0083,0.33,0.33,0.036,2.8e-07,2.8e-07,8.5e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-0.0015,-0.0057,0.00021,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.4e-05,1.8e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-07,2.8e-07,8.4e-07,0.027,0.025,0.0005,0.0025,9.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33390000,0.55,0.013,-0.0018,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.5e-05,1.4e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-07,2.8e-07,8.3e-07,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33490000,0.41,0.0068,0.00068,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,7.8e-05,7.7e-05,1.1e-05,0.026,0.026,0.0081,0.35,0.35,0.036,2.8e-07,2.8e-07,8.3e-07,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33590000,0.25,0.00096,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,7.6e-05,7.8e-05,1.1e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.7e-07,2.8e-07,8.2e-07,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33590000,0.25,0.00094,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,7.6e-05,7.8e-05,1.1e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.7e-07,2.8e-07,8.2e-07,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-0.0015,-0.0057,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.5e-05,8e-05,1.3e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.7e-07,2.8e-07,8.1e-07,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-0.0015,-0.0057,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,7.2e-05,8e-05,1.8e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-07,2.7e-07,8.1e-07,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33890000,-0.25,-0.005,-0.0075,0.97,-1,-0.66,0.77,-16,-7.6,-3.7e+02,-0.0015,-0.0057,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,4.7e-05,7.2e-05,8.1e-05,2.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-07,2.7e-07,8e-07,0.027,0.025,0.0005,0.0025,8.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33890000,-0.25,-0.005,-0.0075,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-0.0015,-0.0057,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,4.7e-05,7.2e-05,8.1e-05,2.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-07,2.7e-07,8e-07,0.027,0.025,0.0005,0.0025,8.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33990000,-0.39,-0.0032,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0056,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,6.9e-05,7.8e-05,3.2e-05,0.031,0.032,0.007,0.37,0.37,0.035,2.7e-07,2.7e-07,8e-07,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34090000,-0.5,-0.0021,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0056,0.00023,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,6.9e-05,7.8e-05,3.7e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-07,2.7e-07,7.9e-07,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34190000,-0.57,-0.0014,-0.011,0.82,-0.91,-0.54,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,0.00023,-0.038,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,6.5e-05,7.3e-05,4e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-07,2.7e-07,7.9e-07,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34290000,-0.61,-0.0024,-0.0085,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-0.0015,-0.0057,0.00023,-0.038,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,6.5e-05,7.3e-05,4.1e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-07,2.7e-07,7.8e-07,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34390000,-0.64,-0.0025,-0.006,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,0.00023,-0.043,0.018,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,6e-05,6.7e-05,4.1e-05,0.041,0.043,0.0065,0.39,0.39,0.035,2.6e-07,2.7e-07,7.8e-07,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-0.0016,-0.0057,0.00023,-0.043,0.018,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,6.1e-05,6.7e-05,4.1e-05,0.048,0.05,0.0064,0.4,0.4,0.035,2.7e-07,2.7e-07,7.7e-07,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00024,-0.053,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,5.5e-05,6.1e-05,4e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-07,2.6e-07,7.7e-07,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.36,0.73,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00024,-0.053,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.5e-05,6.1e-05,4e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.6e-07,2.7e-07,7.7e-07,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34790000,-0.67,-0.0021,-0.0017,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00024,-0.064,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.1e-05,5.5e-05,3.9e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-07,2.6e-07,7.6e-07,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34390000,-0.64,-0.0025,-0.006,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,0.00023,-0.043,0.017,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,6e-05,6.7e-05,4.1e-05,0.041,0.043,0.0065,0.39,0.39,0.035,2.6e-07,2.7e-07,7.8e-07,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34490000,-0.65,-0.0035,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-0.0016,-0.0057,0.00024,-0.043,0.017,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,6.1e-05,6.7e-05,4.1e-05,0.048,0.05,0.0064,0.4,0.4,0.035,2.7e-07,2.7e-07,7.7e-07,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00025,-0.053,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,5.5e-05,6.1e-05,4e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-07,2.6e-07,7.7e-07,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.36,0.73,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00025,-0.053,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.5e-05,6.1e-05,4e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.6e-07,2.7e-07,7.7e-07,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34790000,-0.67,-0.0021,-0.0017,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00024,-0.064,0.036,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.1e-05,5.5e-05,3.9e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-07,2.6e-07,7.6e-07,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34890000,-0.68,-0.0021,-0.0016,0.74,-0.7,-0.32,0.72,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.064,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.1e-05,5.5e-05,3.8e-05,0.058,0.061,0.0062,0.42,0.42,0.034,2.6e-07,2.7e-07,7.6e-07,0.026,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34990000,-0.68,-0.0085,-0.0044,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.8e-05,0.056,0.058,0.0068,0.42,0.42,0.034,2.6e-07,2.6e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.7e-05,0.061,0.063,0.0068,0.43,0.43,0.034,2.6e-07,2.7e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35190000,-0.68,-0.0085,-0.0045,0.73,0.46,0.34,-0.18,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.6e-05,0.066,0.068,0.0067,0.44,0.44,0.034,2.7e-07,2.7e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35290000,-0.68,-0.0086,-0.0046,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00025,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.5e-05,0.071,0.074,0.0066,0.45,0.45,0.033,2.7e-07,2.7e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35390000,-0.68,-0.0086,-0.0045,0.73,0.5,0.41,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.5e-05,0.077,0.08,0.0066,0.47,0.47,0.034,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35490000,-0.68,-0.0087,-0.0045,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.4e-05,0.083,0.087,0.0065,0.49,0.49,0.034,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35590000,-0.68,-0.0056,-0.0045,0.73,0.42,0.36,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00026,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.9e-05,4.2e-05,3.3e-05,0.067,0.069,0.0062,0.48,0.48,0.033,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35690000,-0.68,-0.0056,-0.0045,0.73,0.44,0.38,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00026,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.9e-05,4.2e-05,3.3e-05,0.072,0.075,0.0061,0.49,0.49,0.033,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34990000,-0.68,-0.0085,-0.0044,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.078,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.8e-05,0.056,0.058,0.0068,0.42,0.42,0.034,2.6e-07,2.6e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.078,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.7e-05,0.061,0.063,0.0068,0.43,0.43,0.034,2.6e-07,2.7e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35190000,-0.68,-0.0085,-0.0045,0.73,0.46,0.34,-0.18,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.078,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.6e-05,0.066,0.068,0.0067,0.44,0.44,0.034,2.7e-07,2.7e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35290000,-0.68,-0.0086,-0.0045,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00025,-0.078,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.5e-05,0.071,0.074,0.0066,0.45,0.45,0.033,2.7e-07,2.7e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35390000,-0.68,-0.0086,-0.0045,0.73,0.5,0.41,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00025,-0.078,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.5e-05,0.077,0.08,0.0066,0.47,0.47,0.034,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35490000,-0.68,-0.0087,-0.0045,0.73,0.53,0.44,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0057,0.00024,-0.078,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.4e-05,0.083,0.087,0.0065,0.49,0.49,0.034,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35590000,-0.68,-0.0056,-0.0045,0.73,0.42,0.36,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00026,-0.078,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.9e-05,4.2e-05,3.3e-05,0.067,0.069,0.0062,0.48,0.48,0.033,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35690000,-0.68,-0.0056,-0.0045,0.73,0.44,0.38,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00027,-0.078,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.9e-05,4.2e-05,3.3e-05,0.072,0.075,0.0061,0.49,0.49,0.033,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35790000,-0.68,-0.0034,-0.0044,0.73,0.36,0.32,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00028,-0.079,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.3e-05,3.6e-05,3.2e-05,0.06,0.062,0.0059,0.48,0.48,0.033,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35890000,-0.68,-0.0034,-0.0045,0.73,0.38,0.35,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00029,-0.079,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,3.3e-05,3.6e-05,3.1e-05,0.066,0.068,0.0058,0.5,0.5,0.033,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35990000,-0.68,-0.0015,-0.0044,0.73,0.31,0.29,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0003,-0.087,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.9e-05,3.1e-05,3.1e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36090000,-0.68,-0.0016,-0.0044,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00031,-0.087,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.9e-05,3.1e-05,3e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35990000,-0.68,-0.0015,-0.0044,0.73,0.31,0.29,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00031,-0.087,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.9e-05,3.1e-05,3.1e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36090000,-0.68,-0.0016,-0.0044,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00032,-0.087,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.9e-05,3.1e-05,3e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36190000,-0.68,-0.00018,-0.0043,0.73,0.27,0.27,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00032,-0.098,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.6e-05,2.8e-05,3e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-07,2.7e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36290000,-0.68,-0.0003,-0.0042,0.73,0.28,0.29,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00033,-0.098,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.6e-05,2.8e-05,2.9e-05,0.06,0.062,0.0056,0.51,0.51,0.032,2.7e-07,2.8e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36390000,-0.68,0.00075,-0.0041,0.73,0.23,0.24,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00035,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.4e-05,2.5e-05,2.9e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-07,2.8e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36490000,-0.68,0.00066,-0.0042,0.73,0.24,0.26,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00037,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.4e-05,2.5e-05,2.9e-05,0.059,0.061,0.0055,0.52,0.52,0.032,2.8e-07,2.8e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36590000,-0.68,0.0014,-0.004,0.73,0.2,0.22,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00038,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.2e-05,2.3e-05,2.8e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-07,2.8e-07,7.2e-07,0.023,0.021,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36390000,-0.68,0.00075,-0.0041,0.73,0.23,0.24,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00035,-0.11,0.077,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.4e-05,2.5e-05,2.9e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-07,2.8e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36490000,-0.68,0.00065,-0.0042,0.73,0.24,0.26,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00037,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.4e-05,2.5e-05,2.9e-05,0.059,0.061,0.0055,0.52,0.52,0.032,2.8e-07,2.8e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36590000,-0.68,0.0014,-0.004,0.73,0.2,0.22,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00038,-0.12,0.087,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.2e-05,2.3e-05,2.8e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-07,2.8e-07,7.2e-07,0.023,0.021,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36690000,-0.68,0.0014,-0.004,0.73,0.2,0.24,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00039,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.2e-05,2.3e-05,2.8e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,7.1e-07,0.023,0.021,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36790000,-0.68,0.002,-0.0039,0.74,0.17,0.21,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00039,-0.14,0.097,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2e-05,2.1e-05,2.7e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,7.1e-07,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36890000,-0.68,0.0019,-0.0039,0.74,0.17,0.22,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0004,-0.14,0.097,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2e-05,2.1e-05,2.7e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,7.1e-07,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36990000,-0.68,0.0024,-0.0037,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00041,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.9e-05,2e-05,2.7e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,7.1e-07,0.021,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37090000,-0.68,0.0023,-0.0037,0.74,0.14,0.19,-0.15,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00043,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.9e-05,2e-05,2.6e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,7.1e-07,0.021,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37190000,-0.68,0.0026,-0.0036,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00044,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.6e-05,0.05,0.051,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,7e-07,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36790000,-0.68,0.002,-0.0039,0.74,0.17,0.21,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0004,-0.14,0.097,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2e-05,2.1e-05,2.7e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,7.1e-07,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36890000,-0.68,0.0019,-0.0039,0.74,0.17,0.22,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00041,-0.14,0.097,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2e-05,2.1e-05,2.7e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,7.1e-07,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36990000,-0.68,0.0024,-0.0037,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00042,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.9e-05,2e-05,2.7e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,7.1e-07,0.021,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37090000,-0.68,0.0023,-0.0037,0.74,0.15,0.19,-0.15,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00043,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.9e-05,2e-05,2.6e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,7.1e-07,0.021,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37190000,-0.68,0.0026,-0.0036,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00045,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.6e-05,0.05,0.051,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,7e-07,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37290000,-0.68,0.0026,-0.0036,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00046,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.6e-05,0.055,0.057,0.0058,0.56,0.56,0.031,2.8e-07,2.9e-07,7e-07,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37390000,-0.68,0.0028,-0.0035,0.74,0.097,0.15,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00047,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.5e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.8e-07,2.9e-07,7e-07,0.02,0.018,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37490000,-0.68,0.0028,-0.0034,0.74,0.096,0.15,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00047,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.5e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-07,2.9e-07,7e-07,0.02,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37590000,-0.68,0.0029,-0.0033,0.74,0.077,0.13,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00048,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.8e-05,2.5e-05,0.049,0.049,0.0061,0.57,0.57,0.031,2.9e-07,2.9e-07,7e-07,0.019,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37490000,-0.68,0.0028,-0.0034,0.74,0.097,0.15,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00048,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.5e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-07,2.9e-07,7e-07,0.02,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37590000,-0.68,0.0029,-0.0033,0.74,0.077,0.13,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00049,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.8e-05,2.5e-05,0.049,0.049,0.0061,0.57,0.57,0.031,2.9e-07,2.9e-07,7e-07,0.019,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37690000,-0.68,0.0029,-0.0034,0.74,0.075,0.14,-0.11,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0005,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.8e-05,2.4e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-07,2.9e-07,7e-07,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37790000,-0.68,0.003,-0.0033,0.74,0.059,0.12,-0.1,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00051,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.7e-05,1.8e-05,2.4e-05,0.048,0.048,0.0063,0.58,0.58,0.03,2.9e-07,2.9e-07,7e-07,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37890000,-0.68,0.003,-0.0033,0.74,0.056,0.12,-0.093,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00052,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.4e-05,0.052,0.053,0.0064,0.59,0.59,0.03,2.9e-07,2.9e-07,6.9e-07,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37990000,-0.68,0.003,-0.0033,0.74,0.042,0.1,-0.084,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00053,-0.2,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.4e-05,0.046,0.047,0.0065,0.59,0.59,0.031,2.9e-07,2.9e-07,6.9e-07,0.017,0.016,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38090000,-0.68,0.003,-0.0033,0.74,0.038,0.11,-0.074,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00054,-0.2,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-07,2.9e-07,6.9e-07,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38190000,-0.68,0.003,-0.0032,0.74,0.025,0.089,-0.066,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00055,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-07,2.9e-07,6.9e-07,0.016,0.015,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38290000,-0.68,0.003,-0.0032,0.74,0.022,0.09,-0.059,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00056,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-07,2.9e-07,6.9e-07,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38390000,-0.68,0.003,-0.0032,0.74,0.013,0.078,-0.051,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00058,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-07,3e-07,6.9e-07,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38190000,-0.68,0.003,-0.0032,0.74,0.025,0.089,-0.066,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00056,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-07,2.9e-07,6.9e-07,0.016,0.015,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38290000,-0.68,0.003,-0.0032,0.74,0.022,0.09,-0.059,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00057,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-07,2.9e-07,6.9e-07,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38390000,-0.68,0.003,-0.0032,0.74,0.014,0.078,-0.051,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00058,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-07,3e-07,6.9e-07,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38490000,-0.68,0.003,-0.0032,0.74,0.01,0.079,-0.044,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00059,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.2e-05,0.048,0.048,0.007,0.62,0.62,0.031,3e-07,3e-07,6.8e-07,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38590000,-0.68,0.003,-0.0031,0.74,0.0054,0.068,-0.037,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0006,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.2e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-07,3e-07,6.8e-07,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38690000,-0.68,0.0029,-0.0031,0.74,0.001,0.068,-0.03,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00061,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,1.7e-05,1.8e-05,2.2e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-07,3e-07,6.8e-07,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38590000,-0.68,0.003,-0.0031,0.74,0.0055,0.068,-0.037,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0006,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.2e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-07,3e-07,6.8e-07,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38690000,-0.68,0.0029,-0.0031,0.74,0.0011,0.068,-0.03,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00061,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,1.7e-05,1.8e-05,2.2e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-07,3e-07,6.8e-07,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38790000,-0.68,0.0029,-0.003,0.74,-0.0041,0.056,-0.022,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00062,-0.22,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,1.7e-05,1.8e-05,2.2e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-07,3e-07,6.8e-07,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38890000,-0.68,0.0027,-0.0031,0.74,-0.014,0.045,0.48,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00063,-0.22,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,1.8e-05,1.8e-05,2.2e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-07,3e-07,6.8e-07,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
|
|
|
|
@ -61,291 +61,291 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
|||
5890000,1,-0.0088,-0.011,0.00048,0.011,0.015,-0.048,0.0033,0.0035,-0.056,-0.002,-0.0055,9.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,7.7e-08,0.00039,0.00039,3.3e-05,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,1.2e-05,0.04,0.04,0.0054,0,0,0,0,0,0,0,0
|
||||
5990000,1,-0.0088,-0.012,0.00045,0.013,0.016,-0.041,0.0046,0.005,-0.05,-0.002,-0.0055,9.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,8.3e-08,0.00041,0.00041,3.5e-05,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,1.2e-05,0.04,0.04,0.005,0,0,0,0,0,0,0,0
|
||||
6090000,1,-0.0088,-0.012,0.00025,0.013,0.017,-0.039,0.0059,0.0066,-0.047,-0.002,-0.0055,9.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,8.8e-08,0.00044,0.00044,3.7e-05,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,1.2e-05,0.04,0.04,0.0047,0,0,0,0,0,0,0,0
|
||||
6190000,0.98,-0.0066,-0.013,0.19,0.0098,0.016,-0.037,0.0045,0.0054,-0.047,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00034,0.00034,0.0031,0.22,0.22,0.042,0.13,0.13,0.073,0.00015,0.00015,1.1e-05,0.04,0.04,0.0044,0,0,0,0,0,0,0,0
|
||||
6290000,0.98,-0.0066,-0.013,0.19,0.0083,0.018,-0.041,0.0054,0.0071,-0.053,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,0.00034,0.00034,0.0014,0.22,0.22,0.04,0.16,0.16,0.072,0.00015,0.00015,1.1e-05,0.04,0.04,0.0041,0,0,0,0,0,0,0,0
|
||||
6390000,0.98,-0.0065,-0.013,0.19,0.011,0.02,-0.042,0.0064,0.009,-0.056,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,0.00034,0.00034,0.00099,0.23,0.23,0.039,0.19,0.19,0.072,0.00015,0.00015,1.1e-05,0.04,0.04,0.0038,0,0,0,0,0,0,0,0
|
||||
6490000,0.98,-0.0064,-0.013,0.19,0.0084,0.019,-0.039,0.0073,0.011,-0.053,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,0.00034,0.00034,0.00072,0.24,0.24,0.038,0.23,0.23,0.07,0.00015,0.00015,1.1e-05,0.04,0.04,0.0036,0,0,0,0,0,0,0,0
|
||||
6590000,0.98,-0.0064,-0.013,0.19,0.0077,0.022,-0.042,0.0082,0.013,-0.056,-0.0019,-0.0056,9.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,0.00035,0.00035,0.00057,0.26,0.26,0.036,0.28,0.28,0.069,0.00015,0.00015,1.1e-05,0.04,0.04,0.0033,0,0,0,0,0,0,0,0
|
||||
6690000,0.98,-0.0063,-0.013,0.19,0.0052,0.025,-0.044,0.0088,0.015,-0.057,-0.0019,-0.0056,9.1e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.9e-05,0.00035,0.00035,0.00047,0.28,0.28,0.035,0.33,0.33,0.068,0.00015,0.00015,1.1e-05,0.04,0.04,0.0031,0,0,0,0,0,0,0,0
|
||||
6790000,0.98,-0.0063,-0.013,0.19,0.007,0.027,-0.042,0.0093,0.018,-0.058,-0.0019,-0.0056,9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.7e-05,0.00036,0.00036,0.00041,0.3,0.3,0.034,0.38,0.38,0.068,0.00015,0.00015,1.1e-05,0.04,0.04,0.0029,0,0,0,0,0,0,0,0
|
||||
6890000,0.98,-0.0061,-0.013,0.19,0.0066,0.028,-0.038,0.01,0.02,-0.055,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.5e-05,0.00036,0.00036,0.00036,0.32,0.32,0.032,0.45,0.45,0.067,0.00015,0.00015,1.1e-05,0.04,0.04,0.0027,0,0,0,0,0,0,0,0
|
||||
6990000,0.98,-0.006,-0.013,0.19,0.0066,0.029,-0.037,0.011,0.023,-0.055,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.3e-05,0.00037,0.00037,0.00032,0.35,0.35,0.031,0.52,0.52,0.066,0.00015,0.00015,1.1e-05,0.04,0.04,0.0026,0,0,0,0,0,0,0,0
|
||||
7090000,0.98,-0.0059,-0.013,0.19,0.0057,0.035,-0.037,0.011,0.026,-0.056,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.2e-05,0.00037,0.00037,0.00029,0.39,0.39,0.03,0.6,0.6,0.066,0.00015,0.00015,1.1e-05,0.04,0.04,0.0024,0,0,0,0,0,0,0,0
|
||||
7190000,0.98,-0.0058,-0.013,0.19,0.0053,0.038,-0.036,0.012,0.03,-0.058,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.1e-05,0.00038,0.00038,0.00026,0.42,0.42,0.029,0.69,0.69,0.065,0.00015,0.00015,1.1e-05,0.04,0.04,0.0023,0,0,0,0,0,0,0,0
|
||||
7290000,0.98,-0.0058,-0.013,0.19,0.0061,0.042,-0.034,0.012,0.034,-0.054,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1e-05,0.00039,0.00039,0.00024,0.46,0.46,0.028,0.79,0.79,0.064,0.00015,0.00015,1.1e-05,0.04,0.04,0.0021,0,0,0,0,0,0,0,0
|
||||
7390000,0.98,-0.0057,-0.013,0.19,0.0044,0.046,-0.032,0.013,0.038,-0.052,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,9.6e-06,0.0004,0.0004,0.00022,0.51,0.51,0.027,0.9,0.9,0.064,0.00014,0.00014,1.1e-05,0.04,0.04,0.002,0,0,0,0,0,0,0,0
|
||||
7490000,0.98,-0.0057,-0.013,0.19,0.0068,0.05,-0.026,0.013,0.043,-0.046,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,9e-06,0.00041,0.00041,0.0002,0.56,0.56,0.026,1,1,0.063,0.00014,0.00014,1e-05,0.04,0.04,0.0019,0,0,0,0,0,0,0,0
|
||||
7590000,0.98,-0.0057,-0.013,0.19,0.0077,0.053,-0.023,0.014,0.048,-0.041,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,8.5e-06,0.00042,0.00042,0.00019,0.6,0.61,0.025,1.2,1.2,0.062,0.00014,0.00014,1e-05,0.04,0.04,0.0018,0,0,0,0,0,0,0,0
|
||||
7690000,0.98,-0.0057,-0.013,0.19,0.0074,0.057,-0.022,0.015,0.053,-0.036,-0.0019,-0.0056,8.8e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,8.1e-06,0.00043,0.00043,0.00018,0.66,0.66,0.025,1.3,1.3,0.062,0.00014,0.00014,1e-05,0.04,0.04,0.0017,0,0,0,0,0,0,0,0
|
||||
7790000,0.98,-0.0056,-0.013,0.19,0.009,0.06,-0.024,0.015,0.058,-0.041,-0.0019,-0.0056,8.6e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7.7e-06,0.00043,0.00043,0.00017,0.72,0.72,0.024,1.5,1.5,0.061,0.00014,0.00014,1e-05,0.04,0.04,0.0016,0,0,0,0,0,0,0,0
|
||||
7890000,0.98,-0.0056,-0.013,0.19,0.0077,0.065,-0.025,0.016,0.064,-0.045,-0.0019,-0.0056,8.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7.3e-06,0.00045,0.00045,0.00016,0.78,0.78,0.023,1.7,1.7,0.06,0.00014,0.00014,1e-05,0.04,0.04,0.0015,0,0,0,0,0,0,0,0
|
||||
7990000,0.98,-0.0056,-0.013,0.19,0.0078,0.068,-0.021,0.016,0.07,-0.041,-0.0019,-0.0056,8.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7e-06,0.00045,0.00045,0.00015,0.84,0.84,0.022,1.9,1.9,0.059,0.00014,0.00014,1e-05,0.04,0.04,0.0014,0,0,0,0,0,0,0,0
|
||||
8090000,0.98,-0.0054,-0.013,0.19,0.0093,0.073,-0.022,0.017,0.077,-0.044,-0.0019,-0.0056,7.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.8e-06,0.00047,0.00047,0.00014,0.92,0.92,0.022,2.1,2.1,0.059,0.00014,0.00014,1e-05,0.04,0.04,0.0014,0,0,0,0,0,0,0,0
|
||||
8190000,0.98,-0.0055,-0.013,0.19,0.01,0.08,-0.018,0.018,0.085,-0.038,-0.0019,-0.0056,7.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-06,0.00048,0.00048,0.00014,1,1,0.021,2.4,2.4,0.058,0.00014,0.00014,1e-05,0.04,0.04,0.0013,0,0,0,0,0,0,0,0
|
||||
8290000,0.98,-0.0055,-0.013,0.19,0.012,0.084,-0.016,0.019,0.091,-0.038,-0.0019,-0.0056,6.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-06,0.00049,0.00049,0.00013,1.1,1.1,0.02,2.6,2.6,0.057,0.00014,0.00014,1e-05,0.04,0.04,0.0012,0,0,0,0,0,0,0,0
|
||||
8390000,0.98,-0.0054,-0.013,0.19,0.0099,0.087,-0.015,0.02,0.1,-0.036,-0.0019,-0.0056,6.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,6.1e-06,0.0005,0.0005,0.00013,1.1,1.1,0.02,2.9,2.9,0.057,0.00014,0.00014,1e-05,0.04,0.04,0.0012,0,0,0,0,0,0,0,0
|
||||
8490000,0.98,-0.0053,-0.013,0.19,0.0095,0.091,-0.017,0.02,0.11,-0.041,-0.0018,-0.0056,7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-06,0.00051,0.00051,0.00012,1.2,1.2,0.019,3.2,3.2,0.056,0.00014,0.00014,1e-05,0.04,0.04,0.0011,0,0,0,0,0,0,0,0
|
||||
8590000,0.98,-0.0052,-0.013,0.19,0.011,0.095,-0.012,0.021,0.11,-0.036,-0.0018,-0.0056,6.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.8e-06,0.00052,0.00052,0.00012,1.3,1.3,0.018,3.6,3.6,0.055,0.00014,0.00014,1e-05,0.04,0.04,0.0011,0,0,0,0,0,0,0,0
|
||||
8690000,0.98,-0.0053,-0.013,0.19,0.01,0.096,-0.014,0.021,0.12,-0.037,-0.0018,-0.0056,6.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.6e-06,0.00053,0.00053,0.00011,1.4,1.4,0.018,3.9,3.9,0.055,0.00013,0.00013,1e-05,0.04,0.04,0.001,0,0,0,0,0,0,0,0
|
||||
8790000,0.98,-0.0053,-0.013,0.19,0.012,0.1,-0.013,0.022,0.13,-0.035,-0.0018,-0.0056,6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.5e-06,0.00054,0.00054,0.00011,1.5,1.5,0.018,4.3,4.3,0.055,0.00013,0.00013,1e-05,0.04,0.04,0.00096,0,0,0,0,0,0,0,0
|
||||
8890000,0.98,-0.0053,-0.013,0.19,0.011,0.1,-0.0091,0.023,0.13,-0.029,-0.0018,-0.0056,6.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.3e-06,0.00054,0.00054,0.00011,1.5,1.5,0.017,4.6,4.6,0.054,0.00013,0.00013,1e-05,0.04,0.04,0.00091,0,0,0,0,0,0,0,0
|
||||
8990000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0083,0.024,0.15,-0.032,-0.0018,-0.0056,7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.2e-06,0.00056,0.00056,0.0001,1.6,1.6,0.017,5.2,5.2,0.054,0.00013,0.00013,1e-05,0.04,0.04,0.00088,0,0,0,0,0,0,0,0
|
||||
9090000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0093,0.024,0.15,-0.032,-0.0018,-0.0056,7.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.1e-06,0.00055,0.00055,0.0001,1.7,1.7,0.016,5.4,5.5,0.053,0.00013,0.00013,1e-05,0.04,0.04,0.00084,0,0,0,0,0,0,0,0
|
||||
9190000,0.98,-0.0053,-0.013,0.19,0.014,0.11,-0.0088,0.025,0.16,-0.032,-0.0018,-0.0056,8.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5e-06,0.00057,0.00057,9.8e-05,1.8,1.8,0.016,6.1,6.1,0.052,0.00013,0.00013,1e-05,0.04,0.04,0.0008,0,0,0,0,0,0,0,0
|
||||
9290000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0072,0.025,0.16,-0.03,-0.0017,-0.0056,8.5e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.9e-06,0.00056,0.00055,9.5e-05,1.8,1.8,0.015,6.3,6.3,0.052,0.00012,0.00012,1e-05,0.04,0.04,0.00076,0,0,0,0,0,0,0,0
|
||||
9390000,0.98,-0.0051,-0.013,0.19,0.016,0.12,-0.006,0.027,0.17,-0.03,-0.0017,-0.0056,7.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.9e-06,0.00057,0.00057,9.3e-05,1.9,1.9,0.015,7,7,0.052,0.00012,0.00012,1e-05,0.04,0.04,0.00073,0,0,0,0,0,0,0,0
|
||||
9490000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0044,0.026,0.17,-0.027,-0.0017,-0.0056,7.9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.8e-06,0.00056,0.00056,9.1e-05,1.9,1.9,0.015,7.2,7.2,0.051,0.00012,0.00012,1e-05,0.04,0.04,0.0007,0,0,0,0,0,0,0,0
|
||||
9590000,0.98,-0.0052,-0.013,0.19,0.015,0.12,-0.0043,0.028,0.18,-0.028,-0.0017,-0.0056,6.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.7e-06,0.00057,0.00057,8.9e-05,2,2,0.014,7.9,7.9,0.05,0.00012,0.00012,1e-05,0.04,0.04,0.00067,0,0,0,0,0,0,0,0
|
||||
9690000,0.98,-0.0053,-0.013,0.19,0.015,0.11,-0.0014,0.027,0.18,-0.027,-0.0017,-0.0056,5.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.6e-06,0.00055,0.00055,8.7e-05,2,2,0.014,8.1,8.1,0.05,0.00012,0.00012,1e-05,0.04,0.04,0.00065,0,0,0,0,0,0,0,0
|
||||
9790000,0.98,-0.0053,-0.013,0.19,0.016,0.12,-0.0027,0.028,0.19,-0.028,-0.0017,-0.0056,4.1e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.6e-06,0.00057,0.00057,8.5e-05,2.1,2.2,0.014,8.9,8.9,0.05,0.00012,0.00012,1e-05,0.04,0.04,0.00062,0,0,0,0,0,0,0,0
|
||||
9890000,0.98,-0.0054,-0.013,0.19,0.018,0.11,-0.0014,0.027,0.19,-0.029,-0.0016,-0.0056,4.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.5e-06,0.00054,0.00054,8.4e-05,2.1,2.1,0.013,8.9,8.9,0.049,0.00011,0.00011,1e-05,0.04,0.04,0.0006,0,0,0,0,0,0,0,0
|
||||
9990000,0.98,-0.0054,-0.013,0.19,0.019,0.12,-0.00072,0.029,0.2,-0.031,-0.0016,-0.0056,3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.5e-06,0.00056,0.00056,8.2e-05,2.2,2.2,0.013,9.8,9.8,0.049,0.00011,0.00011,1e-05,0.04,0.04,0.00058,0,0,0,0,0,0,0,0
|
||||
10090000,0.98,-0.0055,-0.013,0.19,0.017,0.11,0.00048,0.028,0.19,-0.029,-0.0016,-0.0057,1.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.4e-06,0.00053,0.00053,8.1e-05,2.1,2.1,0.013,9.7,9.7,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.00056,0,0,0,0,0,0,0,0
|
||||
10190000,0.98,-0.0054,-0.013,0.19,0.015,0.11,0.0014,0.029,0.2,-0.03,-0.0016,-0.0057,-5.6e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00055,0.00055,8e-05,2.3,2.3,0.012,11,11,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.00054,0,0,0,0,0,0,0,0
|
||||
10290000,0.98,-0.0054,-0.013,0.19,0.016,0.11,0.0003,0.031,0.21,-0.029,-0.0016,-0.0057,1.4e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00057,0.00057,7.9e-05,2.4,2.4,0.012,12,12,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.00052,0,0,0,0,0,0,0,0
|
||||
10390000,0.98,-0.0054,-0.013,0.19,0.007,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0057,6e-06,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00059,0.00058,7.8e-05,0.25,0.25,0.56,0.25,0.25,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10490000,0.98,-0.0053,-0.012,0.19,0.0084,0.0077,0.007,0.0015,0.00075,-0.023,-0.0016,-0.0057,-9.5e-06,-1.2e-06,8.3e-07,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.0006,0.0006,7.6e-05,0.26,0.26,0.55,0.26,0.26,0.057,0.00011,0.00011,9.9e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10590000,0.98,-0.0053,-0.012,0.19,-0.0013,0.0055,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,-5.9e-07,0.00032,8.8e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.00061,0.00061,7.5e-05,0.13,0.13,0.27,0.13,0.13,0.055,0.00011,0.00011,9.9e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10690000,0.98,-0.0052,-0.012,0.19,-0.00013,0.0067,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,-6.1e-06,0.00032,9.5e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.00063,0.00063,7.5e-05,0.15,0.15,0.26,0.14,0.14,0.065,0.00011,0.00011,9.8e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10790000,0.98,-0.0054,-0.013,0.19,0.0017,0.0031,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,-8.7e-06,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00062,0.00062,7.4e-05,0.1,0.1,0.17,0.091,0.091,0.062,0.00011,0.00011,9.8e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10890000,0.98,-0.0053,-0.013,0.19,0.0018,0.0066,0.01,-0.0006,-0.0042,-0.018,-0.0016,-0.0057,9.2e-06,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00064,0.00064,7.3e-05,0.12,0.12,0.16,0.098,0.098,0.068,0.00011,0.00011,9.7e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10990000,0.98,-0.0054,-0.013,0.19,0.0013,0.012,0.016,-0.00045,-0.003,-0.011,-0.0015,-0.0057,2.8e-06,0.00067,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.0006,0.0006,7.2e-05,0.096,0.096,0.12,0.073,0.073,0.065,9.9e-05,9.9e-05,9.7e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0
|
||||
11090000,0.98,-0.0055,-0.013,0.19,0.0022,0.017,0.02,-0.00032,-0.0016,-0.0074,-0.0015,-0.0057,-1.7e-05,0.00067,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00062,0.00062,7.2e-05,0.12,0.12,0.11,0.08,0.08,0.069,9.9e-05,9.9e-05,9.7e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0
|
||||
11190000,0.98,-0.0058,-0.013,0.19,0.0039,0.017,0.026,0.0011,-0.0018,-0.00035,-0.0015,-0.0057,-2.9e-05,0.00065,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00055,0.00055,7.1e-05,0.096,0.096,0.083,0.063,0.063,0.066,9.1e-05,9.1e-05,9.6e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
||||
11290000,0.98,-0.0058,-0.013,0.19,0.0041,0.018,0.026,0.0014,-2.5e-05,-0.00012,-0.0015,-0.0057,-3.5e-05,0.00065,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00057,0.00057,7.1e-05,0.12,0.12,0.077,0.07,0.07,0.069,9.1e-05,9.1e-05,9.6e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
||||
11390000,0.98,-0.006,-0.013,0.19,0.0025,0.015,0.016,0.00088,-0.00088,-0.0086,-0.0014,-0.0058,-3.4e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00049,0.00049,7e-05,0.097,0.097,0.062,0.057,0.057,0.066,8.3e-05,8.3e-05,9.5e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
||||
11490000,0.98,-0.0059,-0.013,0.19,0.0015,0.016,0.02,0.001,0.00072,-0.0025,-0.0014,-0.0058,-3.1e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.0005,0.0005,7e-05,0.12,0.12,0.057,0.065,0.065,0.067,8.3e-05,8.3e-05,9.4e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
||||
11590000,0.98,-0.0062,-0.012,0.19,0.0033,0.013,0.018,0.00083,-0.00036,-0.0036,-0.0013,-0.0058,-3.1e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00042,0.00042,6.9e-05,0.096,0.096,0.048,0.054,0.054,0.065,7.5e-05,7.5e-05,9.4e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
||||
11690000,0.98,-0.0062,-0.012,0.19,0.0038,0.017,0.018,0.0012,0.0011,-0.0049,-0.0013,-0.0058,-2.4e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00044,0.00044,6.9e-05,0.12,0.12,0.044,0.062,0.062,0.066,7.5e-05,7.5e-05,9.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
||||
11790000,0.98,-0.0066,-0.012,0.19,0.0024,0.011,0.019,0.0007,-0.0018,-0.002,-0.0012,-0.0059,-3.6e-06,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00037,0.00037,6.8e-05,0.092,0.092,0.037,0.052,0.052,0.063,6.8e-05,6.8e-05,9.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
11890000,0.98,-0.0067,-0.012,0.19,0.0051,0.012,0.017,0.001,-0.0007,-0.0013,-0.0012,-0.0059,-5.8e-06,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00038,0.00038,6.8e-05,0.11,0.11,0.034,0.061,0.061,0.063,6.8e-05,6.8e-05,9.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
11990000,0.98,-0.0069,-0.012,0.19,0.0081,0.012,0.015,0.0021,-0.0018,-0.0049,-0.0012,-0.0059,2.5e-06,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00032,0.00032,6.8e-05,0.088,0.088,0.03,0.051,0.051,0.061,6.2e-05,6.2e-05,9.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12090000,0.98,-0.0068,-0.012,0.19,0.0097,0.012,0.018,0.003,-0.00063,0.0011,-0.0012,-0.0059,4e-06,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00033,0.00033,6.7e-05,0.11,0.11,0.027,0.06,0.06,0.06,6.2e-05,6.2e-05,9.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12190000,0.98,-0.0067,-0.012,0.19,0.0077,0.011,0.017,0.0018,0.00039,0.0029,-0.0012,-0.0059,-2.4e-06,0.0022,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00029,0.00029,6.7e-05,0.083,0.083,0.024,0.05,0.05,0.058,5.7e-05,5.7e-05,9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12290000,0.98,-0.0068,-0.012,0.19,0.0054,0.011,0.016,0.0025,0.0015,0.0039,-0.0012,-0.0059,-7.7e-06,0.0022,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.0003,0.0003,6.7e-05,0.098,0.098,0.022,0.059,0.059,0.058,5.7e-05,5.7e-05,9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12390000,0.98,-0.0069,-0.012,0.19,0.004,0.0072,0.014,0.0017,0.00049,-0.0021,-0.0012,-0.006,-7.3e-06,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00026,0.00026,6.7e-05,0.078,0.078,0.02,0.05,0.05,0.056,5.3e-05,5.3e-05,8.9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12490000,0.98,-0.0069,-0.012,0.19,0.004,0.0082,0.018,0.0021,0.0013,-6.6e-05,-0.0012,-0.006,-7.2e-06,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00027,0.00027,6.7e-05,0.091,0.091,0.018,0.059,0.059,0.055,5.3e-05,5.3e-05,8.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12590000,0.98,-0.0071,-0.012,0.19,0.0078,0.0015,0.02,0.0033,-0.0014,0.0017,-0.0011,-0.006,-7.6e-06,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00024,0.00024,6.7e-05,0.072,0.072,0.017,0.049,0.049,0.054,5e-05,5e-05,8.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12690000,0.98,-0.007,-0.012,0.19,0.0083,-0.00065,0.019,0.004,-0.0013,0.0033,-0.0011,-0.006,-4.2e-06,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00025,0.00025,6.6e-05,0.084,0.084,0.016,0.058,0.058,0.053,5e-05,5e-05,8.7e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12790000,0.98,-0.0073,-0.012,0.19,0.0099,-0.004,0.021,0.0041,-0.0044,0.0054,-0.0011,-0.006,2.7e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00023,0.00023,6.6e-05,0.068,0.068,0.014,0.049,0.049,0.052,4.7e-05,4.7e-05,8.6e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12890000,0.98,-0.0073,-0.012,0.19,0.01,-0.005,0.022,0.0052,-0.0049,0.0085,-0.0011,-0.006,4.9e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00024,0.00024,6.6e-05,0.078,0.078,0.013,0.058,0.058,0.051,4.7e-05,4.7e-05,8.6e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12990000,0.98,-0.0072,-0.012,0.19,0.0079,-0.0029,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.006,7e-05,0.0026,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00022,0.00022,6.6e-05,0.064,0.064,0.012,0.049,0.049,0.05,4.5e-05,4.5e-05,8.5e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13090000,0.98,-0.0073,-0.012,0.19,0.0089,-0.0028,0.02,0.0044,-0.0038,0.0085,-0.0011,-0.006,9.8e-05,0.0027,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00023,0.00023,6.6e-05,0.073,0.073,0.012,0.057,0.057,0.049,4.5e-05,4.5e-05,8.4e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13190000,0.98,-0.0073,-0.012,0.19,0.0038,-0.0045,0.019,0.00096,-0.0046,0.0091,-0.0011,-0.006,0.00012,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.06,0.06,0.011,0.049,0.049,0.047,4.3e-05,4.3e-05,8.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13290000,0.98,-0.0073,-0.012,0.19,0.0035,-0.0054,0.016,0.0013,-0.005,0.0085,-0.0011,-0.006,0.00012,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00022,0.00022,6.6e-05,0.068,0.068,0.01,0.057,0.057,0.047,4.3e-05,4.3e-05,8.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13390000,0.98,-0.0072,-0.012,0.19,0.0026,-0.0035,0.016,0.00085,-0.0037,0.0091,-0.0011,-0.006,0.00012,0.0029,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.056,0.056,0.0097,0.049,0.049,0.046,4e-05,4.1e-05,8.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13490000,0.98,-0.0072,-0.012,0.19,0.003,-0.0018,0.015,0.0011,-0.0039,0.0053,-0.0011,-0.006,0.00013,0.003,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.064,0.064,0.0093,0.057,0.057,0.045,4e-05,4.1e-05,8.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13590000,0.98,-0.0072,-0.012,0.19,0.0076,-0.002,0.017,0.004,-0.0032,0.0038,-0.0011,-0.006,0.00012,0.0032,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.053,0.053,0.0088,0.048,0.048,0.044,3.9e-05,3.9e-05,8.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13690000,0.98,-0.0072,-0.012,0.19,0.0076,-0.0035,0.017,0.0048,-0.0034,0.0064,-0.0011,-0.006,0.00014,0.0032,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.061,0.061,0.0085,0.056,0.056,0.044,3.9e-05,3.9e-05,8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13790000,0.98,-0.0071,-0.012,0.19,0.015,0.00072,0.017,0.0083,-0.00093,0.0059,-0.0011,-0.0059,0.00014,0.0035,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.051,0.051,0.0082,0.048,0.048,0.043,3.7e-05,3.7e-05,7.9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13890000,0.98,-0.007,-0.012,0.19,0.016,0.0014,0.018,0.0098,-0.00082,0.0081,-0.0011,-0.0059,0.00016,0.0035,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.058,0.058,0.008,0.056,0.056,0.042,3.7e-05,3.7e-05,7.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0015,0.017,0.0074,-0.0023,0.007,-0.0011,-0.006,0.00018,0.0034,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.049,0.049,0.0077,0.048,0.048,0.041,3.5e-05,3.5e-05,7.7e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0029,0.018,0.0088,-0.0024,0.0034,-0.0011,-0.006,0.00014,0.0035,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.5e-05,0.055,0.055,0.0076,0.055,0.055,0.041,3.5e-05,3.5e-05,7.7e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
14190000,0.98,-0.0071,-0.011,0.19,0.01,-0.0016,0.018,0.008,-0.0018,0.0036,-0.0011,-0.006,0.00013,0.0036,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-05,3.3e-05,7.6e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0017,0.016,0.009,-0.002,0.0079,-0.0011,-0.006,0.00013,0.0035,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-05,3.3e-05,7.5e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0047,0.017,0.0084,-0.0031,0.012,-0.0011,-0.006,0.00015,0.0034,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-05,3.1e-05,7.4e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0045,0.021,0.0095,-0.0036,0.015,-0.0011,-0.006,0.00013,0.0034,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-05,3.1e-05,7.4e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14590000,0.98,-0.0073,-0.011,0.19,0.0079,-0.0046,0.019,0.0059,-0.0042,0.011,-0.0011,-0.006,0.00013,0.0031,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.6e-05,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-05,2.9e-05,7.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14690000,0.98,-0.0073,-0.011,0.19,0.0071,-0.0046,0.019,0.0066,-0.0046,0.011,-0.0011,-0.006,0.00014,0.0032,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-05,2.9e-05,7.2e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14790000,0.98,-0.0072,-0.011,0.19,0.0088,0.0025,0.019,0.0053,0.00078,0.014,-0.0012,-0.006,0.00017,0.0032,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-05,2.8e-05,7.1e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14890000,0.98,-0.0071,-0.011,0.19,0.0074,5e-05,0.023,0.006,0.00092,0.014,-0.0012,-0.006,0.00019,0.0033,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.049,0.049,0.007,0.054,0.054,0.037,2.7e-05,2.8e-05,7e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14990000,0.98,-0.0073,-0.011,0.19,0.0062,-0.0016,0.026,0.0047,-0.00069,0.017,-0.0012,-0.0061,0.0002,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,7e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
15090000,0.98,-0.0072,-0.011,0.19,0.0062,-0.00052,0.03,0.0054,-0.00084,0.019,-0.0012,-0.0061,0.00021,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.00019,6.5e-05,0.048,0.048,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,6.9e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
15190000,0.98,-0.0073,-0.011,0.19,0.0044,-0.0016,0.03,0.0042,-0.00076,0.021,-0.0012,-0.0061,0.0002,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.6e-05,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,6.8e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
15290000,0.98,-0.0074,-0.011,0.19,0.005,-0.0027,0.03,0.0047,-0.00095,0.018,-0.0012,-0.0061,0.00022,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.047,0.047,0.0071,0.054,0.054,0.035,2.4e-05,2.4e-05,6.7e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
15390000,0.98,-0.0075,-0.011,0.19,0.0052,-0.00028,0.029,0.0038,-0.00065,0.018,-0.0012,-0.0061,0.00022,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-05,2.2e-05,6.7e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15490000,0.98,-0.0076,-0.011,0.19,0.0046,-0.0028,0.029,0.0042,-0.00078,0.019,-0.0012,-0.0061,0.00022,0.0035,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.6e-05,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-05,2.2e-05,6.6e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15590000,0.98,-0.0078,-0.011,0.19,0.0081,-0.0067,0.029,0.0063,-0.0047,0.018,-0.0011,-0.0061,0.00024,0.0039,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,6.5e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15690000,0.98,-0.0077,-0.011,0.19,0.0099,-0.0098,0.029,0.0072,-0.0055,0.019,-0.0011,-0.0061,0.00026,0.0039,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-05,2.1e-05,6.4e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15790000,0.98,-0.0077,-0.011,0.19,0.0064,-0.0091,0.029,0.0055,-0.0043,0.02,-0.0011,-0.0061,0.00029,0.0038,0.0027,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15890000,0.98,-0.0078,-0.011,0.19,0.0053,-0.0075,0.03,0.0061,-0.0051,0.02,-0.0011,-0.0061,0.00027,0.004,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.045,0.045,0.0074,0.053,0.053,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15990000,0.98,-0.0076,-0.011,0.19,0.0033,-0.006,0.027,0.0048,-0.0039,0.019,-0.0012,-0.0061,0.00028,0.0042,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,6.2e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
16090000,0.98,-0.0076,-0.011,0.19,0.0026,-0.0073,0.024,0.005,-0.0046,0.019,-0.0012,-0.0061,0.00027,0.0044,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,6.1e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
16190000,0.98,-0.0075,-0.011,0.19,-0.0013,-0.0049,0.023,0.0027,-0.0034,0.016,-0.0012,-0.0061,0.00025,0.0045,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,6e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16290000,0.98,-0.0075,-0.011,0.19,-0.001,-0.0065,0.023,0.0025,-0.004,0.017,-0.0012,-0.0061,0.00026,0.0045,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,6e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16390000,0.98,-0.0074,-0.011,0.19,0.0015,-0.0057,0.023,0.0036,-0.003,0.017,-0.0012,-0.0061,0.00028,0.0051,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00016,6.5e-05,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,5.9e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16490000,0.98,-0.0076,-0.011,0.19,0.0034,-0.0074,0.026,0.0038,-0.0037,0.021,-0.0012,-0.0061,0.00028,0.005,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,5.8e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16590000,0.98,-0.0075,-0.011,0.19,0.0075,-0.0074,0.029,0.0034,-0.0029,0.021,-0.0012,-0.0061,0.00028,0.0051,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,5.7e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16690000,0.98,-0.0076,-0.011,0.19,0.009,-0.012,0.029,0.0042,-0.0038,0.022,-0.0012,-0.0061,0.00029,0.0053,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.042,0.042,0.008,0.053,0.053,0.034,1.3e-05,1.3e-05,5.7e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16790000,0.98,-0.0074,-0.011,0.19,0.0098,-0.011,0.028,0.0033,-0.0027,0.022,-0.0012,-0.0061,0.0003,0.0053,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,5.6e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
16890000,0.98,-0.0074,-0.011,0.19,0.0088,-0.011,0.029,0.0042,-0.0038,0.02,-0.0012,-0.0061,0.00033,0.0056,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,5.5e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
16990000,0.98,-0.0074,-0.011,0.19,0.0085,-0.011,0.029,0.004,-0.0028,0.019,-0.0013,-0.0061,0.00033,0.0062,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,5.5e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.005,-0.0041,0.018,-0.0013,-0.0061,0.00033,0.0064,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00015,6.5e-05,0.04,0.041,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,5.4e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17190000,0.98,-0.0076,-0.011,0.19,0.0089,-0.018,0.03,0.0033,-0.0075,0.021,-0.0012,-0.0061,0.00031,0.0063,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-06,9.9e-06,5.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17290000,0.98,-0.0076,-0.011,0.19,0.0099,-0.019,0.03,0.0043,-0.0094,0.021,-0.0012,-0.0061,0.00029,0.0065,0.002,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-06,9.9e-06,5.2e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17390000,0.98,-0.0074,-0.011,0.19,0.0066,-0.018,0.029,0.0057,-0.0059,0.021,-0.0013,-0.006,0.00031,0.0073,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00014,0.00014,6.5e-05,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-06,8.9e-06,5.2e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17490000,0.98,-0.0075,-0.011,0.19,0.0047,-0.019,0.029,0.0062,-0.0078,0.023,-0.0013,-0.006,0.0003,0.0074,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-06,8.9e-06,5.1e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17590000,0.98,-0.0074,-0.011,0.19,0.00086,-0.015,0.028,0.0024,-0.0058,0.02,-0.0013,-0.0061,0.0003,0.0073,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-06,8.1e-06,5e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
17690000,0.98,-0.0075,-0.011,0.19,-9.1e-05,-0.016,0.029,0.0025,-0.0074,0.023,-0.0013,-0.0061,0.00031,0.0073,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-06,8.1e-06,5e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
17790000,0.98,-0.0074,-0.011,0.19,0.0026,-0.014,0.029,0.0035,-0.0062,0.028,-0.0014,-0.006,0.00031,0.0076,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00013,6.5e-05,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-06,7.3e-06,4.9e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
17890000,0.98,-0.0073,-0.011,0.19,0.0047,-0.016,0.029,0.0039,-0.0077,0.032,-0.0014,-0.006,0.00032,0.0075,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-06,7.3e-06,4.8e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
17990000,0.98,-0.0071,-0.011,0.19,0.0041,-0.0093,0.029,0.0031,-0.002,0.033,-0.0014,-0.006,0.00032,0.0079,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-06,6.6e-06,4.8e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18090000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0098,0.028,0.0035,-0.003,0.031,-0.0014,-0.006,0.00032,0.0082,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-06,6.6e-06,4.7e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18190000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0088,0.028,0.0041,-0.0022,0.029,-0.0014,-0.006,0.00034,0.0088,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-06,6e-06,4.7e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18290000,0.98,-0.0072,-0.011,0.19,0.0045,-0.0093,0.027,0.0045,-0.0031,0.027,-0.0014,-0.006,0.00034,0.009,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.036,0.036,0.0087,0.051,0.051,0.035,6e-06,6e-06,4.6e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18390000,0.98,-0.0072,-0.011,0.19,0.0054,-0.008,0.027,0.0061,-0.0023,0.026,-0.0014,-0.006,0.00034,0.0096,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00012,6.4e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-06,5.4e-06,4.5e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18490000,0.98,-0.0072,-0.011,0.19,0.0082,-0.008,0.026,0.0069,-0.0031,0.028,-0.0014,-0.006,0.00035,0.0097,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-06,5.4e-06,4.5e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18590000,0.98,-0.007,-0.011,0.19,0.0066,-0.0074,0.026,0.0055,-0.0024,0.031,-0.0015,-0.006,0.00033,0.0095,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-06,4.9e-06,4.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
18690000,0.98,-0.007,-0.011,0.19,0.0066,-0.0063,0.024,0.0062,-0.0031,0.029,-0.0015,-0.006,0.00034,0.0097,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-06,4.9e-06,4.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
18790000,0.98,-0.007,-0.011,0.19,0.0056,-0.006,0.024,0.0062,-0.0025,0.027,-0.0015,-0.006,0.00034,0.01,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,4.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
18890000,0.98,-0.0069,-0.011,0.19,0.0043,-0.0056,0.021,0.0067,-0.0032,0.023,-0.0015,-0.006,0.00033,0.01,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,4.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
18990000,0.98,-0.0069,-0.011,0.19,0.0027,-0.0057,0.022,0.0055,-0.0025,0.026,-0.0015,-0.006,0.00033,0.01,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.3e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,4.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19090000,0.98,-0.007,-0.011,0.19,0.00066,-0.0062,0.023,0.0058,-0.0031,0.022,-0.0015,-0.006,0.00034,0.011,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.3e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,4.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19190000,0.98,-0.0069,-0.011,0.19,-0.00084,-0.0059,0.022,0.0048,-0.0025,0.022,-0.0015,-0.006,0.00031,0.011,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-06,3.7e-06,4.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19290000,0.98,-0.0069,-0.011,0.19,-0.0017,-0.0057,0.023,0.0047,-0.0031,0.021,-0.0015,-0.006,0.00031,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.031,0.031,0.0087,0.05,0.051,0.036,3.7e-06,3.7e-06,4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19390000,0.98,-0.0069,-0.011,0.19,-0.0021,-0.0022,0.024,0.004,-0.0012,0.02,-0.0015,-0.006,0.0003,0.011,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19490000,0.98,-0.007,-0.011,0.19,-0.003,-0.0022,0.023,0.0038,-0.0014,0.019,-0.0015,-0.006,0.00028,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,3.9e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19590000,0.98,-0.0069,-0.011,0.19,-0.0041,-0.0051,0.025,0.0044,-0.0024,0.019,-0.0015,-0.006,0.00028,0.012,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,3.8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19690000,0.98,-0.0069,-0.011,0.19,-0.0057,-0.0037,0.023,0.0039,-0.0028,0.019,-0.0015,-0.006,0.00028,0.012,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,3.8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19790000,0.98,-0.007,-0.011,0.19,-0.0058,-0.0022,0.022,0.0063,-0.0023,0.014,-0.0015,-0.006,0.00027,0.012,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,3.7e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19890000,0.98,-0.0071,-0.011,0.19,-0.0058,-0.002,0.022,0.0057,-0.0025,0.013,-0.0015,-0.006,0.00026,0.013,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,3.7e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19990000,0.98,-0.0071,-0.011,0.19,-0.0055,-0.0019,0.019,0.0061,-0.00091,0.0097,-0.0015,-0.0059,0.00026,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,3.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20090000,0.98,-0.0071,-0.011,0.19,-0.005,-0.0041,0.019,0.0055,-0.0012,0.013,-0.0015,-0.0059,0.00026,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.0001,6.2e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,3.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20190000,0.98,-0.0071,-0.011,0.19,-0.0039,-0.0016,0.02,0.0065,-0.0009,0.013,-0.0015,-0.0059,0.00025,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,3.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20290000,0.98,-0.0071,-0.011,0.19,-0.0071,-0.0026,0.02,0.006,-0.0011,0.013,-0.0015,-0.0059,0.00024,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,3.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20390000,0.98,-0.007,-0.011,0.19,-0.0078,-0.0015,0.021,0.0069,-0.00077,0.014,-0.0015,-0.0059,0.00025,0.014,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,3.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.0059,-0.00094,0.012,-0.0015,-0.0059,0.00025,0.014,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.1e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,3.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0034,0.02,0.0069,-0.00079,0.011,-0.0015,-0.0059,0.00026,0.014,0.0022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,9.9e-05,6.1e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,3.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0021,0.021,0.0057,-0.001,0.011,-0.0015,-0.0059,0.00025,0.014,0.0022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,9.9e-05,6.1e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,3.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.00042,0.0055,0.0048,-0.0008,0.0097,-0.0015,-0.0059,0.00025,0.014,0.0021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.8e-05,9.7e-05,6.1e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,3.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20890000,0.98,0.0028,-0.0073,0.19,-0.022,0.012,-0.11,0.0029,-0.00012,0.0034,-0.0015,-0.0059,0.00025,0.015,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.9e-05,9.8e-05,6.1e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,3.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0022,0.00052,-0.011,-0.0015,-0.0059,0.00025,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.7e-05,9.6e-05,6.1e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,3.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.046,-0.37,-0.0017,0.0044,-0.042,-0.0015,-0.0059,0.00025,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.8e-05,9.6e-05,6.1e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21190000,0.98,0.0017,-0.0059,0.19,-0.049,0.05,-0.5,-0.0013,0.0035,-0.078,-0.0014,-0.0059,0.00025,0.015,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.5e-05,9.4e-05,6e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-06,1.6e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21290000,0.98,-0.00051,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0087,-0.14,-0.0014,-0.0059,0.00023,0.015,0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.6e-05,9.5e-05,6e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-06,1.6e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.2,-0.0014,-0.0059,0.00023,0.015,0.00089,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.4e-05,9.2e-05,6e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0093,0.016,-0.29,-0.0014,-0.0059,0.00024,0.015,0.00079,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.4e-05,9.3e-05,6e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.008,0.016,-0.38,-0.0014,-0.0059,0.00024,0.015,0.00074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.2e-05,9e-05,6e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-0.0014,-0.0059,0.00025,0.015,0.00056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.2e-05,9.1e-05,6e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0038,0.018,-0.61,-0.0014,-0.0058,0.00027,0.016,0.00036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9e-05,8.9e-05,5.9e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,2.9e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.75,-0.0014,-0.0058,0.00026,0.016,0.00024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9e-05,8.9e-05,5.9e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,2.8e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00036,0.017,-0.89,-0.0014,-0.0058,0.00027,0.015,0.00047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.8e-05,8.7e-05,5.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-06,1.1e-06,2.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0017,0.019,-1,-0.0014,-0.0058,0.00028,0.016,0.00034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.8e-05,8.7e-05,5.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-06,1.1e-06,2.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.006,0.013,-1.2,-0.0014,-0.0058,0.00029,0.016,0.00037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.6e-05,8.5e-05,5.9e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,2.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22290000,0.98,-0.0069,-0.01,0.19,0.0016,0.0078,-1.4,0.0059,0.014,-1.3,-0.0014,-0.0058,0.00028,0.016,0.00028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.7e-05,8.5e-05,5.8e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,2.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22390000,0.98,-0.0073,-0.01,0.19,0.0066,-0.0018,-1.4,0.013,0.0041,-1.5,-0.0014,-0.0058,0.00027,0.016,-0.0001,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.5e-05,8.3e-05,5.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1e-06,1e-06,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22490000,0.98,-0.0074,-0.011,0.19,0.01,-0.0078,-1.4,0.014,0.0036,-1.6,-0.0014,-0.0058,0.00026,0.016,-0.00017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.5e-05,8.4e-05,5.8e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,0.00027,0.016,-0.00033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.3e-05,8.2e-05,5.8e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-07,9.4e-07,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0073,-1.9,-0.0014,-0.0058,0.00026,0.016,-0.00041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.4e-05,8.2e-05,5.8e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-07,9.4e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,0.00025,0.016,-0.00052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.2e-05,8.1e-05,5.8e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.035,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,0.00026,0.016,-0.0006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.2e-05,8.1e-05,5.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,0.00028,0.017,-0.00074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8.1e-05,8e-05,5.7e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-0.0014,-0.0058,0.00028,0.017,-0.00077,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8.1e-05,8e-05,5.7e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-0.0014,-0.0058,0.00027,0.017,-0.00092,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.9e-05,5.7e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-07,7.9e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-0.0014,-0.0058,0.00027,0.017,-0.00098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.9e-05,5.7e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8e-07,8e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-0.0014,-0.0058,0.00026,0.017,-0.00071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.8e-05,5.7e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-07,7.5e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23490000,0.98,-0.0079,-0.014,0.19,0.061,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,0.00027,0.017,-0.00076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.8e-05,5.6e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-07,7.6e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0058,0.00027,0.017,-0.00088,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.7e-05,5.6e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0059,0.00028,0.017,-0.00091,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.8e-05,5.6e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,0.00029,0.017,-0.00092,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-07,6.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23890000,0.98,-0.014,-0.021,0.18,0.052,-0.059,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,0.00029,0.017,-0.00093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.12,-0.089,-3.6,-0.0014,-0.0058,0.00029,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24090000,0.98,-0.016,-0.023,0.18,0.06,-0.066,0.09,0.13,-0.095,-3.6,-0.0014,-0.0058,0.00028,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24190000,0.98,-0.013,-0.019,0.18,0.071,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,0.00029,0.019,-0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-07,6.3e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00029,0.019,-0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-07,6.3e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00031,0.019,-0.0031,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0031,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0038,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24690000,0.98,-0.011,-0.015,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0038,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,0.00032,0.019,-0.0044,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0044,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0051,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0051,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.4e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00032,0.019,-0.0056,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,1.9e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25290000,0.98,-0.011,-0.012,0.18,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0056,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.3e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-07,5.3e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.028,0.18,-0.1,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-07,5.1e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.1e-07,5.1e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25590000,0.98,-0.012,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,0.00029,0.018,-0.0067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,0.00029,0.019,-0.0067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-07,5e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25790000,0.98,-0.011,-0.011,0.18,0.0021,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,0.00028,0.019,-0.0072,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-07,4.8e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25890000,0.98,-0.011,-0.011,0.19,-0.0037,-0.028,0.019,0.17,-0.096,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0072,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-07,4.8e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25990000,0.98,-0.011,-0.011,0.19,-0.013,-0.022,0.013,0.16,-0.086,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.021,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26290000,0.98,-0.01,-0.012,0.18,-0.026,-0.014,0.00051,0.15,-0.083,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26390000,0.98,-0.0098,-0.012,0.18,-0.032,-0.0064,0.0045,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00025,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.4e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0033,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00024,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0047,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,0.00023,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.3e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0098,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,0.00021,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-07,4.3e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.11,-0.062,-3.6,-0.0016,-0.0058,0.0002,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.2e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26890000,0.98,-0.008,-0.011,0.18,-0.051,0.017,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,0.0002,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-07,4.2e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,0.0002,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4.1e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27090000,0.98,-0.0073,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-0.0016,-0.0058,0.00019,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4.1e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.036,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-07,4e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27290000,0.98,-0.0076,-0.013,0.18,-0.073,0.042,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8e-05,7.9e-05,5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-07,4e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27390000,0.98,-0.009,-0.015,0.18,-0.078,0.047,0.45,0.055,-0.035,-3.5,-0.0016,-0.0058,0.00018,0.02,-0.0094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27490000,0.98,-0.01,-0.017,0.18,-0.081,0.053,0.76,0.047,-0.029,-3.5,-0.0016,-0.0058,0.00016,0.02,-0.0095,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.014,0.014,0.008,0.042,0.042,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27590000,0.98,-0.01,-0.016,0.18,-0.075,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,0.00016,0.02,-0.0096,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27690000,0.98,-0.009,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.0097,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27790000,0.98,-0.0076,-0.011,0.18,-0.071,0.05,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
27890000,0.98,-0.0073,-0.012,0.18,-0.078,0.057,0.79,0.017,-0.012,-3.2,-0.0016,-0.0058,0.00015,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,0.00015,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0043,-0.0047,-3,-0.0016,-0.0058,0.00015,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.7e-07,3.7e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0023,-0.0043,-3,-0.0016,-0.0058,0.00015,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28290000,0.98,-0.0069,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0015,-2.9,-0.0016,-0.0058,0.00015,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.061,0.79,-0.015,0.0044,-2.8,-0.0015,-0.0058,0.00016,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28490000,0.98,-0.0072,-0.014,0.18,-0.089,0.066,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,0.00015,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28590000,0.98,-0.0073,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0084,-2.7,-0.0015,-0.0058,0.00015,0.02,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28690000,0.98,-0.007,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.6,-0.0015,-0.0058,0.00015,0.02,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,0.00015,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28890000,0.98,-0.0062,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.5,-0.0015,-0.0058,0.00016,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.4,-0.0015,-0.0058,0.00016,0.02,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,0.00015,0.02,-0.0087,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,0.00016,0.02,-0.0089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29290000,0.98,-0.0061,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.2,-0.0015,-0.0058,0.00016,0.02,-0.009,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.065,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,0.00016,0.02,-0.0091,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,0.00017,0.02,-0.0092,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,0.00018,0.02,-0.0094,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29690000,0.98,-0.0065,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,0.00019,0.02,-0.0095,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29790000,0.98,-0.0063,-0.013,0.18,-0.074,0.056,0.78,-0.065,0.044,-1.8,-0.0014,-0.0058,0.00019,0.02,-0.0097,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29890000,0.98,-0.0058,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-0.0014,-0.0058,0.0002,0.02,-0.0099,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29990000,0.98,-0.0059,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,0.0002,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30090000,0.98,-0.0061,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,0.00019,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30190000,0.98,-0.006,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,0.00018,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
6190000,0.98,-0.0066,-0.013,0.19,0.0036,0.019,-0.037,0.004,0.0056,-0.047,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00034,0.00034,0.0031,0.22,0.22,0.042,0.13,0.13,0.073,0.00015,0.00015,1.1e-05,0.04,0.04,0.0044,0,0,0,0,0,0,0,0
|
||||
6290000,0.98,-0.0066,-0.013,0.19,0.0021,0.021,-0.041,0.0043,0.0076,-0.053,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,0.00034,0.00034,0.0014,0.22,0.22,0.04,0.16,0.16,0.072,0.00015,0.00015,1.1e-05,0.04,0.04,0.0041,0,0,0,0,0,0,0,0
|
||||
6390000,0.98,-0.0065,-0.013,0.19,0.0043,0.023,-0.042,0.0046,0.0098,-0.056,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,0.00034,0.00034,0.00099,0.23,0.23,0.039,0.19,0.19,0.072,0.00015,0.00015,1.1e-05,0.04,0.04,0.0038,0,0,0,0,0,0,0,0
|
||||
6490000,0.98,-0.0064,-0.013,0.19,0.0022,0.022,-0.039,0.005,0.012,-0.053,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,0.00034,0.00034,0.00072,0.24,0.24,0.038,0.23,0.23,0.07,0.00015,0.00015,1.1e-05,0.04,0.04,0.0036,0,0,0,0,0,0,0,0
|
||||
6590000,0.98,-0.0064,-0.013,0.19,0.0016,0.025,-0.042,0.0052,0.014,-0.056,-0.0019,-0.0056,9.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,0.00035,0.00035,0.00057,0.26,0.26,0.036,0.28,0.28,0.069,0.00015,0.00015,1.1e-05,0.04,0.04,0.0033,0,0,0,0,0,0,0,0
|
||||
6690000,0.98,-0.0063,-0.013,0.19,-0.001,0.028,-0.044,0.0052,0.017,-0.057,-0.0019,-0.0056,9.1e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.9e-05,0.00035,0.00035,0.00047,0.28,0.28,0.035,0.33,0.33,0.068,0.00015,0.00015,1.1e-05,0.04,0.04,0.0031,0,0,0,0,0,0,0,0
|
||||
6790000,0.98,-0.0063,-0.013,0.19,0.00082,0.03,-0.042,0.0051,0.02,-0.058,-0.0019,-0.0056,9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.7e-05,0.00036,0.00036,0.00041,0.3,0.3,0.034,0.38,0.38,0.068,0.00015,0.00015,1.1e-05,0.04,0.04,0.0029,0,0,0,0,0,0,0,0
|
||||
6890000,0.98,-0.0061,-0.013,0.19,0.00042,0.031,-0.038,0.0052,0.023,-0.055,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.5e-05,0.00036,0.00036,0.00036,0.32,0.32,0.032,0.45,0.45,0.067,0.00015,0.00015,1.1e-05,0.04,0.04,0.0027,0,0,0,0,0,0,0,0
|
||||
6990000,0.98,-0.006,-0.013,0.19,0.00043,0.032,-0.037,0.0052,0.026,-0.055,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.3e-05,0.00037,0.00037,0.00032,0.35,0.35,0.031,0.52,0.52,0.066,0.00015,0.00015,1.1e-05,0.04,0.04,0.0026,0,0,0,0,0,0,0,0
|
||||
7090000,0.98,-0.0059,-0.013,0.19,-0.00042,0.038,-0.037,0.0052,0.029,-0.056,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.2e-05,0.00037,0.00037,0.00029,0.39,0.39,0.03,0.6,0.6,0.066,0.00015,0.00015,1.1e-05,0.04,0.04,0.0024,0,0,0,0,0,0,0,0
|
||||
7190000,0.98,-0.0059,-0.013,0.19,-0.00082,0.041,-0.036,0.005,0.033,-0.058,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.1e-05,0.00038,0.00038,0.00026,0.42,0.42,0.029,0.69,0.69,0.065,0.00015,0.00015,1.1e-05,0.04,0.04,0.0023,0,0,0,0,0,0,0,0
|
||||
7290000,0.98,-0.0058,-0.013,0.19,3.1e-05,0.045,-0.034,0.005,0.037,-0.054,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1e-05,0.00039,0.00039,0.00024,0.46,0.46,0.028,0.79,0.79,0.064,0.00015,0.00015,1.1e-05,0.04,0.04,0.0021,0,0,0,0,0,0,0,0
|
||||
7390000,0.98,-0.0057,-0.013,0.19,-0.0017,0.049,-0.032,0.0049,0.042,-0.052,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,9.6e-06,0.0004,0.0004,0.00022,0.51,0.51,0.027,0.9,0.9,0.064,0.00014,0.00014,1.1e-05,0.04,0.04,0.002,0,0,0,0,0,0,0,0
|
||||
7490000,0.98,-0.0057,-0.013,0.19,0.00071,0.052,-0.026,0.0049,0.047,-0.046,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,9e-06,0.00041,0.00041,0.0002,0.56,0.56,0.026,1,1,0.063,0.00014,0.00014,1e-05,0.04,0.04,0.0019,0,0,0,0,0,0,0,0
|
||||
7590000,0.98,-0.0057,-0.013,0.19,0.0017,0.056,-0.023,0.005,0.052,-0.041,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,8.5e-06,0.00042,0.00042,0.00019,0.6,0.61,0.025,1.2,1.2,0.062,0.00014,0.00014,1e-05,0.04,0.04,0.0018,0,0,0,0,0,0,0,0
|
||||
7690000,0.98,-0.0057,-0.013,0.19,0.0015,0.06,-0.022,0.0051,0.058,-0.036,-0.0019,-0.0056,8.8e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,8.1e-06,0.00043,0.00043,0.00018,0.66,0.66,0.025,1.3,1.3,0.062,0.00014,0.00014,1e-05,0.04,0.04,0.0017,0,0,0,0,0,0,0,0
|
||||
7790000,0.98,-0.0056,-0.013,0.19,0.0031,0.063,-0.024,0.0053,0.063,-0.041,-0.0019,-0.0056,8.6e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7.7e-06,0.00043,0.00043,0.00017,0.72,0.72,0.024,1.5,1.5,0.061,0.00014,0.00014,1e-05,0.04,0.04,0.0016,0,0,0,0,0,0,0,0
|
||||
7890000,0.98,-0.0056,-0.013,0.19,0.0018,0.068,-0.025,0.0054,0.07,-0.045,-0.0019,-0.0056,8.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7.3e-06,0.00045,0.00045,0.00016,0.78,0.78,0.023,1.7,1.7,0.06,0.00014,0.00014,1e-05,0.04,0.04,0.0015,0,0,0,0,0,0,0,0
|
||||
7990000,0.98,-0.0056,-0.013,0.19,0.0021,0.071,-0.021,0.0055,0.075,-0.041,-0.0019,-0.0056,8.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7e-06,0.00045,0.00045,0.00015,0.84,0.84,0.022,1.9,1.9,0.059,0.00014,0.00014,1e-05,0.04,0.04,0.0014,0,0,0,0,0,0,0,0
|
||||
8090000,0.98,-0.0054,-0.013,0.19,0.0036,0.076,-0.022,0.0058,0.082,-0.044,-0.0019,-0.0056,7.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.8e-06,0.00047,0.00047,0.00014,0.92,0.92,0.022,2.1,2.1,0.059,0.00014,0.00014,1e-05,0.04,0.04,0.0014,0,0,0,0,0,0,0,0
|
||||
8190000,0.98,-0.0055,-0.013,0.19,0.0043,0.083,-0.018,0.0062,0.091,-0.038,-0.0019,-0.0056,7.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-06,0.00048,0.00048,0.00014,1,1,0.021,2.4,2.4,0.058,0.00014,0.00014,1e-05,0.04,0.04,0.0013,0,0,0,0,0,0,0,0
|
||||
8290000,0.98,-0.0055,-0.013,0.19,0.0065,0.087,-0.016,0.0066,0.097,-0.038,-0.0019,-0.0056,6.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-06,0.00049,0.00049,0.00013,1.1,1.1,0.02,2.6,2.6,0.057,0.00014,0.00014,1e-05,0.04,0.04,0.0012,0,0,0,0,0,0,0,0
|
||||
8390000,0.98,-0.0054,-0.013,0.19,0.0044,0.09,-0.015,0.0071,0.11,-0.036,-0.0019,-0.0056,6.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,6.1e-06,0.0005,0.0005,0.00013,1.1,1.1,0.02,2.9,2.9,0.057,0.00014,0.00014,1e-05,0.04,0.04,0.0012,0,0,0,0,0,0,0,0
|
||||
8490000,0.98,-0.0053,-0.013,0.19,0.0043,0.093,-0.017,0.0073,0.11,-0.041,-0.0018,-0.0056,7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-06,0.00051,0.00051,0.00012,1.2,1.2,0.019,3.2,3.2,0.056,0.00014,0.00014,1e-05,0.04,0.04,0.0011,0,0,0,0,0,0,0,0
|
||||
8590000,0.98,-0.0053,-0.013,0.19,0.0054,0.098,-0.012,0.0078,0.12,-0.036,-0.0018,-0.0056,6.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.8e-06,0.00052,0.00052,0.00012,1.3,1.3,0.018,3.6,3.6,0.055,0.00014,0.00014,1e-05,0.04,0.04,0.0011,0,0,0,0,0,0,0,0
|
||||
8690000,0.98,-0.0053,-0.013,0.19,0.0054,0.099,-0.014,0.008,0.13,-0.037,-0.0018,-0.0056,6.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.6e-06,0.00053,0.00053,0.00011,1.4,1.4,0.018,3.9,3.9,0.055,0.00013,0.00013,1e-05,0.04,0.04,0.001,0,0,0,0,0,0,0,0
|
||||
8790000,0.98,-0.0053,-0.013,0.19,0.0069,0.1,-0.013,0.0085,0.14,-0.035,-0.0018,-0.0056,6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.5e-06,0.00054,0.00054,0.00011,1.5,1.5,0.018,4.3,4.3,0.055,0.00013,0.00013,1e-05,0.04,0.04,0.00096,0,0,0,0,0,0,0,0
|
||||
8890000,0.98,-0.0054,-0.013,0.19,0.0071,0.1,-0.0091,0.0089,0.14,-0.029,-0.0018,-0.0056,6.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.3e-06,0.00054,0.00054,0.00011,1.5,1.5,0.017,4.6,4.6,0.054,0.00013,0.00013,1e-05,0.04,0.04,0.00091,0,0,0,0,0,0,0,0
|
||||
8990000,0.98,-0.0053,-0.013,0.19,0.0063,0.11,-0.0083,0.0096,0.15,-0.032,-0.0018,-0.0056,7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.2e-06,0.00056,0.00056,0.0001,1.6,1.6,0.017,5.2,5.2,0.054,0.00013,0.00013,1e-05,0.04,0.04,0.00088,0,0,0,0,0,0,0,0
|
||||
9090000,0.98,-0.0053,-0.013,0.19,0.0068,0.11,-0.0093,0.0098,0.15,-0.032,-0.0018,-0.0056,7.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.1e-06,0.00055,0.00055,0.0001,1.7,1.7,0.016,5.4,5.5,0.053,0.00013,0.00013,1e-05,0.04,0.04,0.00084,0,0,0,0,0,0,0,0
|
||||
9190000,0.98,-0.0053,-0.013,0.19,0.011,0.12,-0.0088,0.011,0.17,-0.032,-0.0018,-0.0056,8.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5e-06,0.00057,0.00057,9.8e-05,1.8,1.8,0.016,6.1,6.1,0.052,0.00013,0.00013,1e-05,0.04,0.04,0.0008,0,0,0,0,0,0,0,0
|
||||
9290000,0.98,-0.0052,-0.013,0.19,0.013,0.11,-0.0072,0.011,0.17,-0.03,-0.0017,-0.0056,8.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.9e-06,0.00056,0.00055,9.5e-05,1.8,1.8,0.015,6.3,6.3,0.052,0.00012,0.00012,1e-05,0.04,0.04,0.00076,0,0,0,0,0,0,0,0
|
||||
9390000,0.98,-0.0051,-0.013,0.19,0.013,0.12,-0.006,0.013,0.18,-0.03,-0.0017,-0.0056,7.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.9e-06,0.00057,0.00057,9.3e-05,1.9,1.9,0.015,7,7,0.052,0.00012,0.00012,1e-05,0.04,0.04,0.00073,0,0,0,0,0,0,0,0
|
||||
9490000,0.98,-0.0052,-0.013,0.19,0.013,0.12,-0.0044,0.013,0.18,-0.027,-0.0017,-0.0056,8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.8e-06,0.00056,0.00056,9.1e-05,1.9,1.9,0.015,7.2,7.2,0.051,0.00012,0.00012,1e-05,0.04,0.04,0.0007,0,0,0,0,0,0,0,0
|
||||
9590000,0.98,-0.0053,-0.013,0.19,0.013,0.12,-0.0043,0.014,0.19,-0.028,-0.0017,-0.0056,6.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.7e-06,0.00057,0.00057,8.9e-05,2,2,0.014,7.9,7.9,0.05,0.00012,0.00012,1e-05,0.04,0.04,0.00067,0,0,0,0,0,0,0,0
|
||||
9690000,0.98,-0.0054,-0.013,0.19,0.013,0.11,-0.0014,0.014,0.19,-0.027,-0.0017,-0.0056,5.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.6e-06,0.00055,0.00055,8.7e-05,2,2,0.014,8.1,8.1,0.05,0.00012,0.00012,1e-05,0.04,0.04,0.00065,0,0,0,0,0,0,0,0
|
||||
9790000,0.98,-0.0053,-0.013,0.19,0.015,0.12,-0.0027,0.015,0.2,-0.028,-0.0017,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.6e-06,0.00057,0.00057,8.5e-05,2.1,2.2,0.014,8.9,8.9,0.05,0.00012,0.00012,1e-05,0.04,0.04,0.00062,0,0,0,0,0,0,0,0
|
||||
9890000,0.98,-0.0054,-0.013,0.19,0.017,0.11,-0.0014,0.015,0.19,-0.029,-0.0016,-0.0056,4.5e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.5e-06,0.00054,0.00054,8.4e-05,2.1,2.1,0.013,8.9,8.9,0.049,0.00011,0.00011,1e-05,0.04,0.04,0.0006,0,0,0,0,0,0,0,0
|
||||
9990000,0.98,-0.0054,-0.013,0.19,0.019,0.12,-0.00072,0.017,0.2,-0.031,-0.0016,-0.0056,3.1e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.5e-06,0.00056,0.00056,8.2e-05,2.2,2.2,0.013,9.8,9.8,0.049,0.00011,0.00011,1e-05,0.04,0.04,0.00058,0,0,0,0,0,0,0,0
|
||||
10090000,0.98,-0.0055,-0.013,0.19,0.017,0.11,0.00048,0.017,0.19,-0.029,-0.0016,-0.0056,1.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.4e-06,0.00053,0.00053,8.1e-05,2.1,2.1,0.013,9.7,9.7,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.00056,0,0,0,0,0,0,0,0
|
||||
10190000,0.98,-0.0055,-0.013,0.19,0.015,0.11,0.0014,0.018,0.2,-0.03,-0.0016,-0.0056,-4.4e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00055,0.00055,8e-05,2.3,2.3,0.012,11,11,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.00054,0,0,0,0,0,0,0,0
|
||||
10290000,0.98,-0.0055,-0.013,0.19,0.016,0.11,0.00029,0.02,0.22,-0.029,-0.0016,-0.0056,2.8e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00057,0.00057,7.9e-05,2.4,2.4,0.012,12,12,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.00052,0,0,0,0,0,0,0,0
|
||||
10390000,0.98,-0.0055,-0.013,0.19,0.0072,0.0051,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0056,7.5e-06,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00059,0.00058,7.8e-05,0.25,0.25,0.56,0.25,0.25,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10490000,0.98,-0.0054,-0.013,0.19,0.0088,0.0075,0.007,0.0015,0.00074,-0.023,-0.0016,-0.0056,-7.8e-06,-1.2e-06,8.4e-07,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.0006,0.0006,7.6e-05,0.26,0.26,0.55,0.26,0.26,0.057,0.00011,0.00011,9.9e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10590000,0.98,-0.0053,-0.012,0.19,-0.00088,0.0053,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,1.3e-06,0.00033,4.9e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.00061,0.00061,7.5e-05,0.13,0.13,0.27,0.13,0.13,0.055,0.00011,0.00011,9.9e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10690000,0.98,-0.0053,-0.013,0.19,0.00044,0.0066,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,-4.1e-06,0.00033,5.6e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.00063,0.00063,7.5e-05,0.15,0.15,0.26,0.14,0.14,0.065,0.00011,0.00011,9.8e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10790000,0.98,-0.0054,-0.013,0.19,0.0022,0.003,0.014,-0.00076,-0.0047,-0.015,-0.0016,-0.0057,-6.6e-06,0.00054,0.00046,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00062,0.00062,7.4e-05,0.1,0.1,0.17,0.091,0.091,0.062,0.00011,0.00011,9.8e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10890000,0.98,-0.0054,-0.013,0.19,0.0025,0.0064,0.01,-0.00051,-0.0043,-0.018,-0.0016,-0.0057,1.2e-05,0.00054,0.00046,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00064,0.00064,7.3e-05,0.12,0.12,0.16,0.098,0.098,0.068,0.00011,0.00011,9.7e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
||||
10990000,0.98,-0.0054,-0.013,0.19,0.0019,0.012,0.016,-0.00041,-0.0031,-0.011,-0.0015,-0.0057,5.3e-06,0.00071,0.00069,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.0006,0.0006,7.2e-05,0.096,0.096,0.12,0.073,0.073,0.065,9.9e-05,9.9e-05,9.7e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0
|
||||
11090000,0.98,-0.0056,-0.013,0.19,0.0031,0.017,0.02,-0.00021,-0.0016,-0.0074,-0.0015,-0.0057,-1.5e-05,0.00071,0.00069,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00062,0.00062,7.2e-05,0.12,0.12,0.11,0.08,0.08,0.069,9.9e-05,9.9e-05,9.7e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0
|
||||
11190000,0.98,-0.0059,-0.013,0.19,0.0046,0.017,0.026,0.0011,-0.0018,-0.00035,-0.0014,-0.0057,-2.7e-05,0.00073,0.0015,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00055,0.00055,7.1e-05,0.096,0.096,0.083,0.063,0.063,0.066,9.1e-05,9.1e-05,9.6e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
||||
11290000,0.98,-0.0058,-0.013,0.19,0.005,0.018,0.026,0.0016,-6.2e-05,-0.00012,-0.0015,-0.0057,-3.2e-05,0.00073,0.0015,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00057,0.00057,7.1e-05,0.12,0.12,0.077,0.07,0.07,0.069,9.1e-05,9.1e-05,9.6e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
||||
11390000,0.98,-0.006,-0.013,0.19,0.0031,0.015,0.016,0.00094,-0.0009,-0.0086,-0.0014,-0.0058,-3.1e-05,0.0013,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00049,0.00049,7e-05,0.097,0.097,0.062,0.057,0.057,0.066,8.3e-05,8.3e-05,9.5e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
||||
11490000,0.98,-0.0059,-0.013,0.19,0.0023,0.016,0.02,0.0011,0.00068,-0.0025,-0.0014,-0.0058,-2.8e-05,0.0013,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.0005,0.0005,7e-05,0.12,0.12,0.057,0.065,0.065,0.067,8.3e-05,8.3e-05,9.4e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
||||
11590000,0.98,-0.0063,-0.013,0.19,0.0039,0.013,0.018,0.0009,-0.00038,-0.0036,-0.0013,-0.0058,-2.8e-05,0.0017,0.0027,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00042,0.00042,6.9e-05,0.096,0.096,0.048,0.054,0.054,0.065,7.5e-05,7.5e-05,9.4e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
||||
11690000,0.98,-0.0062,-0.012,0.19,0.0045,0.017,0.018,0.0013,0.0011,-0.0049,-0.0013,-0.0058,-2.1e-05,0.0017,0.0027,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00044,0.00044,6.9e-05,0.12,0.12,0.044,0.062,0.062,0.066,7.5e-05,7.5e-05,9.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
||||
11790000,0.98,-0.0066,-0.012,0.19,0.003,0.011,0.019,0.00076,-0.0018,-0.002,-0.0012,-0.0059,-5.6e-07,0.0022,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00037,0.00037,6.8e-05,0.092,0.092,0.037,0.052,0.052,0.063,6.8e-05,6.8e-05,9.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
11890000,0.98,-0.0067,-0.012,0.19,0.0057,0.012,0.017,0.0011,-0.00073,-0.0013,-0.0012,-0.0059,-2.8e-06,0.0022,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00038,0.00038,6.8e-05,0.11,0.11,0.034,0.061,0.061,0.063,6.8e-05,6.8e-05,9.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
11990000,0.98,-0.0069,-0.012,0.19,0.0085,0.012,0.015,0.0022,-0.0018,-0.0049,-0.0012,-0.0059,5.5e-06,0.0022,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00032,0.00032,6.8e-05,0.088,0.088,0.03,0.051,0.051,0.061,6.2e-05,6.2e-05,9.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12090000,0.98,-0.0068,-0.012,0.19,0.01,0.012,0.018,0.0031,-0.00066,0.0011,-0.0012,-0.0059,7e-06,0.0022,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00033,0.00033,6.7e-05,0.11,0.11,0.027,0.06,0.06,0.06,6.2e-05,6.2e-05,9.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12190000,0.98,-0.0067,-0.012,0.19,0.0081,0.011,0.017,0.0018,0.00038,0.0029,-0.0012,-0.0059,5e-07,0.0024,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00029,0.00029,6.7e-05,0.083,0.083,0.024,0.05,0.05,0.058,5.7e-05,5.7e-05,9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12290000,0.98,-0.0068,-0.012,0.19,0.0059,0.01,0.016,0.0025,0.0015,0.0039,-0.0012,-0.0059,-4.9e-06,0.0024,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.0003,0.0003,6.7e-05,0.098,0.098,0.022,0.059,0.059,0.058,5.7e-05,5.7e-05,9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12390000,0.98,-0.0069,-0.012,0.19,0.0043,0.0071,0.014,0.0017,0.00048,-0.0021,-0.0012,-0.0059,-4.5e-06,0.0027,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00026,0.00026,6.7e-05,0.078,0.078,0.02,0.05,0.05,0.056,5.3e-05,5.3e-05,8.9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12490000,0.98,-0.0069,-0.012,0.19,0.0044,0.0081,0.018,0.0022,0.0012,-6.9e-05,-0.0012,-0.0059,-4.5e-06,0.0026,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00027,0.00027,6.7e-05,0.091,0.091,0.018,0.059,0.059,0.055,5.3e-05,5.3e-05,8.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12590000,0.98,-0.0071,-0.012,0.19,0.0081,0.0015,0.019,0.0033,-0.0014,0.0017,-0.0011,-0.006,-4.9e-06,0.0027,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00024,0.00024,6.7e-05,0.072,0.072,0.017,0.049,0.049,0.054,5e-05,5e-05,8.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12690000,0.98,-0.007,-0.012,0.19,0.0086,-0.00071,0.019,0.0041,-0.0013,0.0033,-0.0011,-0.006,-1.6e-06,0.0027,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00025,0.00025,6.6e-05,0.084,0.084,0.016,0.058,0.058,0.053,5e-05,5e-05,8.7e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12790000,0.98,-0.0073,-0.012,0.19,0.01,-0.0041,0.021,0.0042,-0.0044,0.0054,-0.0011,-0.006,3e-05,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00023,0.00023,6.6e-05,0.068,0.068,0.014,0.049,0.049,0.052,4.7e-05,4.7e-05,8.6e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12890000,0.98,-0.0073,-0.012,0.19,0.01,-0.005,0.022,0.0052,-0.0049,0.0085,-0.0011,-0.006,5.1e-05,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00024,0.00024,6.6e-05,0.078,0.078,0.013,0.058,0.058,0.051,4.7e-05,4.7e-05,8.6e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
12990000,0.98,-0.0072,-0.012,0.19,0.0082,-0.003,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.006,7.3e-05,0.0028,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00022,0.00022,6.6e-05,0.064,0.064,0.012,0.049,0.049,0.05,4.5e-05,4.5e-05,8.5e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13090000,0.98,-0.0073,-0.012,0.19,0.0091,-0.0028,0.02,0.0045,-0.0038,0.0085,-0.0011,-0.006,0.0001,0.0029,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00023,0.00023,6.6e-05,0.073,0.073,0.012,0.057,0.057,0.049,4.5e-05,4.5e-05,8.4e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13190000,0.98,-0.0073,-0.012,0.19,0.004,-0.0045,0.019,0.00099,-0.0046,0.0091,-0.0011,-0.006,0.00012,0.003,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.06,0.06,0.011,0.049,0.049,0.047,4.3e-05,4.3e-05,8.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13290000,0.98,-0.0073,-0.012,0.19,0.0037,-0.0055,0.016,0.0013,-0.005,0.0084,-0.0011,-0.006,0.00012,0.003,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00022,0.00022,6.6e-05,0.068,0.068,0.01,0.057,0.057,0.047,4.3e-05,4.3e-05,8.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13390000,0.98,-0.0072,-0.012,0.19,0.0028,-0.0035,0.016,0.00087,-0.0037,0.0091,-0.0011,-0.006,0.00012,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.056,0.056,0.0097,0.049,0.049,0.046,4e-05,4.1e-05,8.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13490000,0.98,-0.0072,-0.012,0.19,0.0032,-0.0018,0.015,0.0012,-0.0039,0.0053,-0.0011,-0.006,0.00013,0.0031,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.064,0.064,0.0093,0.057,0.057,0.045,4e-05,4.1e-05,8.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13590000,0.98,-0.0072,-0.012,0.19,0.0077,-0.002,0.017,0.004,-0.0032,0.0038,-0.0011,-0.006,0.00013,0.0034,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.053,0.053,0.0088,0.048,0.048,0.044,3.9e-05,3.9e-05,8.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13690000,0.98,-0.0072,-0.012,0.19,0.0077,-0.0035,0.017,0.0048,-0.0034,0.0064,-0.0011,-0.006,0.00014,0.0034,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.061,0.061,0.0085,0.056,0.056,0.044,3.9e-05,3.9e-05,8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13790000,0.98,-0.0071,-0.012,0.19,0.015,0.00073,0.017,0.0083,-0.00094,0.0059,-0.0011,-0.0059,0.00014,0.0037,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.051,0.051,0.0082,0.048,0.048,0.043,3.7e-05,3.7e-05,7.9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13890000,0.98,-0.007,-0.012,0.19,0.016,0.0014,0.018,0.0098,-0.00082,0.0081,-0.0011,-0.0059,0.00016,0.0037,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.058,0.058,0.008,0.056,0.056,0.042,3.7e-05,3.7e-05,7.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0016,0.017,0.0074,-0.0023,0.007,-0.0011,-0.006,0.00018,0.0035,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.049,0.049,0.0077,0.048,0.048,0.041,3.5e-05,3.5e-05,7.7e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0029,0.018,0.0089,-0.0024,0.0034,-0.0011,-0.006,0.00015,0.0037,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.5e-05,0.055,0.055,0.0076,0.055,0.055,0.041,3.5e-05,3.5e-05,7.7e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
14190000,0.98,-0.0071,-0.012,0.19,0.01,-0.0016,0.018,0.0081,-0.0018,0.0036,-0.0011,-0.006,0.00013,0.0038,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-05,3.3e-05,7.6e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0016,0.016,0.009,-0.002,0.0079,-0.0011,-0.006,0.00013,0.0037,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-05,3.3e-05,7.5e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
||||
14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0046,0.017,0.0084,-0.0031,0.012,-0.0011,-0.006,0.00015,0.0036,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-05,3.1e-05,7.4e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0044,0.021,0.0095,-0.0036,0.015,-0.0011,-0.006,0.00013,0.0036,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-05,3.1e-05,7.4e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14590000,0.98,-0.0073,-0.011,0.19,0.0079,-0.0045,0.019,0.0059,-0.0042,0.011,-0.0011,-0.006,0.00013,0.0033,0.0031,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.6e-05,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-05,2.9e-05,7.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14690000,0.98,-0.0073,-0.011,0.19,0.0071,-0.0045,0.019,0.0066,-0.0046,0.011,-0.0011,-0.006,0.00014,0.0034,0.0031,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-05,2.9e-05,7.2e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14790000,0.98,-0.0072,-0.011,0.19,0.0088,0.0025,0.019,0.0053,0.00079,0.014,-0.0012,-0.006,0.00017,0.0034,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-05,2.8e-05,7.1e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14890000,0.98,-0.0071,-0.011,0.19,0.0075,0.0001,0.023,0.0061,0.00093,0.014,-0.0012,-0.006,0.00019,0.0035,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.049,0.049,0.007,0.054,0.054,0.037,2.7e-05,2.8e-05,7e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
14990000,0.98,-0.0073,-0.011,0.19,0.0062,-0.0015,0.026,0.0048,-0.00069,0.017,-0.0012,-0.0061,0.0002,0.0033,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,7e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
15090000,0.98,-0.0072,-0.011,0.19,0.0063,-0.00047,0.03,0.0054,-0.00083,0.019,-0.0012,-0.0061,0.00021,0.0033,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.00019,6.5e-05,0.048,0.048,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,6.9e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
15190000,0.98,-0.0073,-0.011,0.19,0.0044,-0.0015,0.03,0.0042,-0.00076,0.021,-0.0012,-0.0061,0.0002,0.0033,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.6e-05,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,6.8e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
15290000,0.98,-0.0074,-0.011,0.19,0.005,-0.0026,0.03,0.0047,-0.00094,0.018,-0.0012,-0.0061,0.00022,0.0036,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.047,0.047,0.0071,0.054,0.054,0.035,2.4e-05,2.4e-05,6.7e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
||||
15390000,0.98,-0.0075,-0.011,0.19,0.0052,-0.00022,0.029,0.0038,-0.00064,0.018,-0.0012,-0.0061,0.00022,0.0036,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-05,2.2e-05,6.7e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15490000,0.98,-0.0076,-0.011,0.19,0.0046,-0.0028,0.029,0.0043,-0.00076,0.019,-0.0012,-0.0061,0.00022,0.0037,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.6e-05,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-05,2.2e-05,6.6e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15590000,0.98,-0.0078,-0.011,0.19,0.0081,-0.0066,0.029,0.0063,-0.0047,0.018,-0.0011,-0.0061,0.00024,0.0041,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,6.5e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15690000,0.98,-0.0077,-0.011,0.19,0.0099,-0.0097,0.029,0.0072,-0.0055,0.019,-0.0011,-0.0061,0.00026,0.0041,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-05,2.1e-05,6.4e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15790000,0.98,-0.0077,-0.011,0.19,0.0064,-0.009,0.029,0.0055,-0.0043,0.02,-0.0011,-0.0061,0.00029,0.004,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15890000,0.98,-0.0078,-0.011,0.19,0.0053,-0.0074,0.03,0.0061,-0.0051,0.02,-0.0011,-0.0061,0.00027,0.0042,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.045,0.045,0.0074,0.053,0.053,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
15990000,0.98,-0.0076,-0.011,0.19,0.0032,-0.0059,0.027,0.0048,-0.0039,0.019,-0.0012,-0.0061,0.00027,0.0044,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,6.2e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
16090000,0.98,-0.0076,-0.011,0.19,0.0026,-0.0072,0.024,0.005,-0.0046,0.019,-0.0012,-0.0061,0.00027,0.0046,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,6.1e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
||||
16190000,0.98,-0.0075,-0.011,0.19,-0.0013,-0.0049,0.023,0.0027,-0.0034,0.016,-0.0012,-0.0061,0.00025,0.0047,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,6e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16290000,0.98,-0.0075,-0.011,0.19,-0.001,-0.0064,0.023,0.0026,-0.004,0.017,-0.0012,-0.0061,0.00026,0.0047,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,6e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16390000,0.98,-0.0075,-0.011,0.19,0.0014,-0.0057,0.023,0.0036,-0.003,0.017,-0.0012,-0.0061,0.00028,0.0053,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00016,6.5e-05,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,5.9e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16490000,0.98,-0.0076,-0.011,0.19,0.0034,-0.0073,0.026,0.0038,-0.0037,0.021,-0.0012,-0.0061,0.00028,0.0052,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,5.8e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16590000,0.98,-0.0075,-0.011,0.19,0.0075,-0.0073,0.029,0.0034,-0.0029,0.021,-0.0012,-0.0061,0.00028,0.0053,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,5.7e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16690000,0.98,-0.0076,-0.011,0.19,0.0089,-0.012,0.029,0.0042,-0.0038,0.022,-0.0012,-0.0061,0.00029,0.0054,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.042,0.042,0.008,0.053,0.053,0.034,1.3e-05,1.3e-05,5.7e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
||||
16790000,0.98,-0.0074,-0.011,0.19,0.0098,-0.011,0.028,0.0033,-0.0027,0.022,-0.0012,-0.0061,0.0003,0.0055,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,5.6e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
16890000,0.98,-0.0074,-0.011,0.19,0.0088,-0.011,0.029,0.0042,-0.0038,0.02,-0.0012,-0.0061,0.00033,0.0058,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,5.5e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
16990000,0.98,-0.0074,-0.011,0.19,0.0085,-0.011,0.029,0.004,-0.0028,0.019,-0.0013,-0.0061,0.00033,0.0064,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,5.5e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.005,-0.0041,0.018,-0.0013,-0.0061,0.00033,0.0066,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00015,6.5e-05,0.04,0.041,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,5.4e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17190000,0.98,-0.0076,-0.011,0.19,0.0089,-0.018,0.03,0.0033,-0.0075,0.021,-0.0012,-0.0061,0.00031,0.0065,0.002,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-06,9.9e-06,5.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17290000,0.98,-0.0076,-0.011,0.19,0.0098,-0.019,0.03,0.0043,-0.0094,0.021,-0.0012,-0.0061,0.00029,0.0067,0.0018,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-06,9.9e-06,5.2e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17390000,0.98,-0.0075,-0.011,0.19,0.0066,-0.018,0.029,0.0057,-0.0059,0.021,-0.0013,-0.006,0.00031,0.0075,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00014,0.00014,6.5e-05,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-06,8.9e-06,5.2e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17490000,0.98,-0.0075,-0.011,0.19,0.0046,-0.019,0.029,0.0062,-0.0078,0.022,-0.0013,-0.006,0.0003,0.0076,0.0023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-06,8.9e-06,5.1e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
||||
17590000,0.98,-0.0074,-0.011,0.19,0.00081,-0.015,0.028,0.0024,-0.0058,0.02,-0.0013,-0.0061,0.0003,0.0074,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-06,8.1e-06,5e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
17690000,0.98,-0.0075,-0.011,0.19,-0.00015,-0.016,0.029,0.0025,-0.0074,0.023,-0.0013,-0.0061,0.00031,0.0075,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-06,8.1e-06,5e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
17790000,0.98,-0.0074,-0.011,0.19,0.0025,-0.014,0.029,0.0035,-0.0062,0.028,-0.0014,-0.006,0.00031,0.0078,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00013,6.5e-05,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-06,7.3e-06,4.9e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
17890000,0.98,-0.0073,-0.011,0.19,0.0046,-0.016,0.029,0.0039,-0.0077,0.032,-0.0014,-0.006,0.00032,0.0077,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-06,7.3e-06,4.8e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
17990000,0.98,-0.0071,-0.011,0.19,0.004,-0.0092,0.029,0.0031,-0.0019,0.033,-0.0014,-0.006,0.00032,0.0081,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-06,6.6e-06,4.8e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18090000,0.98,-0.0072,-0.011,0.19,0.0035,-0.0098,0.028,0.0035,-0.0029,0.031,-0.0014,-0.006,0.00031,0.0084,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-06,6.6e-06,4.7e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18190000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0087,0.028,0.0041,-0.0022,0.029,-0.0014,-0.006,0.00034,0.0089,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-06,6e-06,4.7e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18290000,0.98,-0.0072,-0.011,0.19,0.0045,-0.0092,0.027,0.0045,-0.003,0.027,-0.0014,-0.006,0.00034,0.0092,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.036,0.036,0.0087,0.051,0.051,0.035,6e-06,6e-06,4.6e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18390000,0.98,-0.0072,-0.011,0.19,0.0054,-0.0079,0.027,0.0061,-0.0023,0.026,-0.0014,-0.006,0.00033,0.0098,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00012,6.4e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-06,5.4e-06,4.5e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18490000,0.98,-0.0072,-0.011,0.19,0.0081,-0.008,0.026,0.0069,-0.0031,0.028,-0.0014,-0.006,0.00034,0.0098,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-06,5.4e-06,4.5e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0
|
||||
18590000,0.98,-0.007,-0.011,0.19,0.0065,-0.0073,0.026,0.0055,-0.0024,0.031,-0.0015,-0.006,0.00033,0.0097,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-06,4.9e-06,4.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
18690000,0.98,-0.007,-0.011,0.19,0.0066,-0.0063,0.024,0.0062,-0.0031,0.029,-0.0015,-0.006,0.00034,0.0099,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-06,4.9e-06,4.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
18790000,0.98,-0.007,-0.011,0.19,0.0056,-0.006,0.024,0.0062,-0.0025,0.027,-0.0015,-0.006,0.00034,0.01,0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,4.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
18890000,0.98,-0.0069,-0.011,0.19,0.0043,-0.0056,0.021,0.0067,-0.0031,0.023,-0.0015,-0.006,0.00033,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,4.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
18990000,0.98,-0.0069,-0.011,0.19,0.0026,-0.0057,0.022,0.0055,-0.0025,0.026,-0.0015,-0.006,0.00033,0.011,0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.3e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,4.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19090000,0.98,-0.007,-0.011,0.19,0.0006,-0.0062,0.023,0.0057,-0.003,0.022,-0.0015,-0.006,0.00034,0.011,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.3e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,4.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19190000,0.98,-0.0069,-0.011,0.19,-0.00089,-0.0058,0.022,0.0048,-0.0025,0.021,-0.0015,-0.006,0.00031,0.011,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-06,3.7e-06,4.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19290000,0.98,-0.0069,-0.011,0.19,-0.0018,-0.0057,0.023,0.0047,-0.0031,0.021,-0.0015,-0.006,0.00031,0.011,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.031,0.031,0.0087,0.05,0.051,0.036,3.7e-06,3.7e-06,4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19390000,0.98,-0.0069,-0.011,0.19,-0.0022,-0.0022,0.024,0.004,-0.0011,0.019,-0.0015,-0.006,0.0003,0.011,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19490000,0.98,-0.007,-0.011,0.19,-0.003,-0.0022,0.023,0.0038,-0.0014,0.019,-0.0015,-0.006,0.00028,0.012,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,3.9e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19590000,0.98,-0.0069,-0.011,0.19,-0.0041,-0.0051,0.025,0.0043,-0.0024,0.019,-0.0015,-0.006,0.00027,0.012,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,3.8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19690000,0.98,-0.007,-0.011,0.19,-0.0058,-0.0036,0.023,0.0039,-0.0028,0.019,-0.0015,-0.006,0.00028,0.012,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,3.8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19790000,0.98,-0.007,-0.011,0.19,-0.0058,-0.0022,0.022,0.0063,-0.0023,0.014,-0.0015,-0.006,0.00027,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,3.7e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19890000,0.98,-0.0071,-0.011,0.19,-0.0058,-0.0019,0.022,0.0057,-0.0025,0.013,-0.0015,-0.006,0.00026,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,3.7e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
||||
19990000,0.98,-0.0071,-0.011,0.19,-0.0055,-0.0019,0.019,0.0061,-0.00089,0.0097,-0.0015,-0.0059,0.00026,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,3.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20090000,0.98,-0.0071,-0.011,0.19,-0.005,-0.0041,0.019,0.0055,-0.0012,0.013,-0.0015,-0.0059,0.00026,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.0001,6.2e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,3.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20190000,0.98,-0.0071,-0.011,0.19,-0.004,-0.0015,0.02,0.0065,-0.00088,0.013,-0.0015,-0.0059,0.00024,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,3.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20290000,0.98,-0.0071,-0.011,0.19,-0.0072,-0.0026,0.02,0.006,-0.001,0.013,-0.0015,-0.0059,0.00024,0.014,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,3.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20390000,0.98,-0.007,-0.011,0.19,-0.0079,-0.0014,0.021,0.0069,-0.00075,0.014,-0.0015,-0.0059,0.00025,0.014,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,3.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.0058,-0.00092,0.012,-0.0015,-0.0059,0.00024,0.014,0.0022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.1e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,3.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20590000,0.98,-0.007,-0.011,0.19,-0.012,-0.0033,0.02,0.0069,-0.00077,0.011,-0.0015,-0.0059,0.00026,0.014,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,9.9e-05,6.1e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,3.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0021,0.021,0.0057,-0.00099,0.011,-0.0015,-0.0059,0.00025,0.014,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,9.9e-05,6.1e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,3.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.00045,0.0055,0.0048,-0.00079,0.0097,-0.0015,-0.0059,0.00025,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.8e-05,9.7e-05,6.1e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,3.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20890000,0.98,0.0028,-0.0073,0.19,-0.022,0.012,-0.11,0.0029,-0.0001,0.0034,-0.0015,-0.0059,0.00025,0.015,0.0018,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.9e-05,9.8e-05,6.1e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,3.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0022,0.00054,-0.011,-0.0015,-0.0059,0.00025,0.015,0.0017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.7e-05,9.6e-05,6.1e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,3.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.046,-0.37,-0.0017,0.0044,-0.042,-0.0015,-0.0059,0.00024,0.015,0.0017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.8e-05,9.6e-05,6.1e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21190000,0.98,0.0016,-0.0059,0.19,-0.049,0.05,-0.5,-0.0013,0.0035,-0.078,-0.0014,-0.0059,0.00025,0.015,0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.5e-05,9.4e-05,6e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-06,1.6e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21290000,0.98,-0.00052,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0088,-0.14,-0.0014,-0.0059,0.00023,0.015,0.001,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.6e-05,9.5e-05,6e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-06,1.6e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21390000,0.98,-0.002,-0.0079,0.19,-0.045,0.05,-0.75,-0.005,0.011,-0.2,-0.0014,-0.0059,0.00023,0.015,0.00069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.4e-05,9.2e-05,6e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0093,0.016,-0.29,-0.0014,-0.0059,0.00023,0.015,0.00058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.4e-05,9.3e-05,6e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.008,0.017,-0.38,-0.0014,-0.0059,0.00024,0.015,0.00054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.2e-05,9e-05,6e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-0.0014,-0.0059,0.00025,0.015,0.00036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.2e-05,9.1e-05,6e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0038,0.018,-0.61,-0.0014,-0.0058,0.00027,0.016,0.00016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9e-05,8.9e-05,5.9e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,2.9e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.75,-0.0014,-0.0058,0.00026,0.016,3.2e-05,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9e-05,8.9e-05,5.9e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,2.8e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
|
||||
21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00037,0.017,-0.89,-0.0014,-0.0058,0.00026,0.016,0.00027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.8e-05,8.7e-05,5.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-06,1.1e-06,2.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0017,0.019,-1,-0.0014,-0.0058,0.00028,0.016,0.00013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.8e-05,8.7e-05,5.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-06,1.1e-06,2.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.006,0.013,-1.2,-0.0014,-0.0058,0.00029,0.016,0.00016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.6e-05,8.5e-05,5.9e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,2.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22290000,0.98,-0.0069,-0.01,0.19,0.0016,0.0078,-1.4,0.0059,0.014,-1.3,-0.0014,-0.0058,0.00028,0.016,6.8e-05,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.7e-05,8.5e-05,5.8e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,2.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22390000,0.98,-0.0073,-0.01,0.19,0.0066,-0.0018,-1.4,0.013,0.0042,-1.5,-0.0014,-0.0058,0.00027,0.016,-0.00031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.5e-05,8.3e-05,5.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1e-06,1e-06,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22490000,0.98,-0.0074,-0.011,0.19,0.01,-0.0077,-1.4,0.014,0.0036,-1.6,-0.0014,-0.0058,0.00025,0.016,-0.00038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.5e-05,8.4e-05,5.8e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,0.00027,0.016,-0.00054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.3e-05,8.2e-05,5.8e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-07,9.4e-07,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22690000,0.98,-0.0073,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.9,-0.0014,-0.0058,0.00026,0.016,-0.00062,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.4e-05,8.2e-05,5.8e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-07,9.4e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22790000,0.98,-0.0073,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,0.00025,0.017,-0.00073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.2e-05,8.1e-05,5.8e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.035,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,0.00026,0.017,-0.00081,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.2e-05,8.1e-05,5.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,0.00027,0.017,-0.00095,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8.1e-05,8e-05,5.7e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-0.0014,-0.0058,0.00027,0.017,-0.00098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8.1e-05,8e-05,5.7e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-0.0014,-0.0058,0.00027,0.017,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.9e-05,5.7e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-07,7.9e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-0.0014,-0.0058,0.00027,0.017,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.9e-05,5.7e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8e-07,8e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-0.0014,-0.0058,0.00025,0.017,-0.00092,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.8e-05,5.7e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-07,7.5e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23490000,0.98,-0.0079,-0.014,0.19,0.061,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,0.00026,0.017,-0.00097,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.8e-05,5.6e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-07,7.6e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0059,0.00027,0.017,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.7e-05,5.6e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0059,0.00028,0.017,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.8e-05,5.6e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,0.00029,0.017,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-07,6.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23890000,0.98,-0.014,-0.021,0.18,0.052,-0.059,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,0.00029,0.018,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.12,-0.089,-3.6,-0.0014,-0.0058,0.00029,0.018,-0.0017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24090000,0.98,-0.016,-0.023,0.18,0.06,-0.066,0.09,0.13,-0.095,-3.6,-0.0014,-0.0058,0.00028,0.018,-0.0017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24190000,0.98,-0.013,-0.019,0.18,0.071,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,0.00029,0.019,-0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-07,6.3e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00029,0.019,-0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-07,6.3e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,0.0003,0.019,-0.0033,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0033,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.004,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24690000,0.98,-0.011,-0.015,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.004,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,0.00032,0.019,-0.0046,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0046,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0053,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0053,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.4e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00032,0.019,-0.0058,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,1.9e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25290000,0.98,-0.011,-0.012,0.18,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0059,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.3e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-07,5.3e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.028,0.18,-0.1,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-07,5.1e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.1e-07,5.1e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25590000,0.98,-0.012,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,0.00029,0.019,-0.0069,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,0.00029,0.019,-0.0069,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-07,5e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25790000,0.98,-0.011,-0.011,0.18,0.002,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,0.00028,0.019,-0.0074,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-07,4.8e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25890000,0.98,-0.011,-0.011,0.19,-0.0037,-0.028,0.019,0.17,-0.096,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0074,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-07,4.8e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
25990000,0.98,-0.011,-0.011,0.19,-0.013,-0.022,0.013,0.16,-0.086,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.021,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0081,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26290000,0.98,-0.01,-0.012,0.18,-0.026,-0.013,0.00051,0.15,-0.083,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0081,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26390000,0.98,-0.0098,-0.012,0.18,-0.032,-0.0064,0.0045,0.13,-0.074,-3.6,-0.0016,-0.0058,0.00024,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.4e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0032,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00024,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0047,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,0.00023,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.3e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0098,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,0.00021,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-07,4.3e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.1,-0.062,-3.6,-0.0016,-0.0058,0.0002,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.2e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26890000,0.98,-0.008,-0.011,0.18,-0.051,0.017,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,0.0002,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-07,4.2e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,0.0002,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4.1e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27090000,0.98,-0.0074,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.051,-3.6,-0.0016,-0.0058,0.00019,0.02,-0.0092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4.1e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.036,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0093,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-07,4e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27290000,0.98,-0.0076,-0.013,0.18,-0.073,0.042,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8e-05,7.9e-05,5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-07,4e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27390000,0.98,-0.009,-0.015,0.18,-0.078,0.047,0.45,0.055,-0.035,-3.5,-0.0016,-0.0058,0.00017,0.02,-0.0096,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27490000,0.98,-0.01,-0.017,0.18,-0.082,0.053,0.76,0.047,-0.029,-3.5,-0.0016,-0.0058,0.00016,0.02,-0.0097,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.014,0.014,0.008,0.042,0.042,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27590000,0.98,-0.01,-0.016,0.18,-0.075,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,0.00016,0.02,-0.0098,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27690000,0.98,-0.009,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.0099,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0
|
||||
27790000,0.98,-0.0076,-0.011,0.18,-0.071,0.05,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.0093,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
27890000,0.98,-0.0073,-0.012,0.18,-0.078,0.057,0.79,0.017,-0.012,-3.2,-0.0016,-0.0058,0.00015,0.02,-0.0094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,0.00014,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0042,-0.0047,-3,-0.0016,-0.0058,0.00015,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.7e-07,3.7e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0023,-0.0043,-3,-0.0016,-0.0058,0.00015,0.02,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28290000,0.98,-0.0069,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0015,-2.9,-0.0016,-0.0058,0.00015,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.062,0.79,-0.015,0.0044,-2.8,-0.0015,-0.0058,0.00016,0.02,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28490000,0.98,-0.0072,-0.014,0.18,-0.09,0.066,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,0.00015,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28590000,0.98,-0.0073,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0085,-2.7,-0.0015,-0.0058,0.00015,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28690000,0.98,-0.007,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.6,-0.0015,-0.0058,0.00015,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,0.00015,0.02,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28890000,0.98,-0.0062,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.5,-0.0015,-0.0058,0.00016,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.4,-0.0015,-0.0058,0.00015,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,0.00015,0.02,-0.0089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,0.00016,0.02,-0.0091,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29290000,0.98,-0.0061,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.2,-0.0015,-0.0058,0.00016,0.02,-0.0092,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.065,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,0.00016,0.02,-0.0093,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,0.00017,0.02,-0.0094,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,0.00018,0.02,-0.0096,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29690000,0.98,-0.0065,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,0.00019,0.02,-0.0097,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29790000,0.98,-0.0063,-0.013,0.18,-0.074,0.056,0.78,-0.065,0.044,-1.8,-0.0014,-0.0058,0.00019,0.021,-0.0099,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29890000,0.98,-0.0058,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-0.0014,-0.0058,0.0002,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
29990000,0.98,-0.006,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,0.0002,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30090000,0.98,-0.0061,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,0.00019,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30190000,0.98,-0.0061,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,0.00018,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30290000,0.98,-0.0061,-0.013,0.19,-0.062,0.05,0.77,-0.074,0.053,-1.4,-0.0014,-0.0057,0.00018,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30390000,0.98,-0.0061,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.4,-0.0014,-0.0057,0.00019,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30490000,0.98,-0.0061,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,0.0002,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.5e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30590000,0.98,-0.0064,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,0.00021,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-0.0014,-0.0057,0.00021,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30790000,0.98,-0.0065,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-0.0014,-0.0057,0.00021,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30390000,0.98,-0.0061,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.4,-0.0014,-0.0057,0.00019,0.022,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30490000,0.98,-0.0061,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.5e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30590000,0.98,-0.0064,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30790000,0.98,-0.0065,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31090000,0.98,-0.0062,-0.013,0.19,-0.035,0.025,0.76,-0.061,0.051,-0.86,-0.0014,-0.0057,0.00019,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31190000,0.98,-0.0064,-0.013,0.18,-0.031,0.021,0.76,-0.052,0.046,-0.79,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-07,2.9e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-0.0014,-0.0057,0.00021,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31390000,0.98,-0.0064,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,9.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31490000,0.98,-0.0061,-0.014,0.19,-0.022,0.009,0.76,-0.049,0.043,-0.58,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8.1e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,9.8e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31390000,0.98,-0.0064,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-0.0014,-0.0057,0.0002,0.023,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,9.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31490000,0.98,-0.0061,-0.014,0.18,-0.022,0.009,0.76,-0.049,0.043,-0.58,-0.0014,-0.0057,0.0002,0.023,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8.1e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,9.8e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31590000,0.98,-0.006,-0.014,0.18,-0.018,0.0067,0.76,-0.038,0.039,-0.51,-0.0014,-0.0057,0.00021,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,9.7e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31690000,0.98,-0.006,-0.015,0.18,-0.02,0.0057,0.76,-0.04,0.039,-0.44,-0.0014,-0.0057,0.00022,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,9.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31790000,0.98,-0.0062,-0.015,0.18,-0.011,0.0031,0.76,-0.028,0.037,-0.36,-0.0014,-0.0057,0.00022,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.4e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,9.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31890000,0.98,-0.0059,-0.015,0.18,-0.008,0.00081,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,0.00023,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31990000,0.98,-0.0062,-0.015,0.18,-0.0001,0.00015,0.75,-0.017,0.034,-0.23,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.4e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,9.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32090000,0.98,-0.0065,-0.014,0.18,-0.00064,-0.0033,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32190000,0.98,-0.0067,-0.015,0.18,0.0047,-0.0065,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32290000,0.98,-0.0066,-0.015,0.18,0.0063,-0.0092,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31890000,0.98,-0.0059,-0.015,0.18,-0.008,0.0008,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,0.00023,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
31990000,0.98,-0.0062,-0.015,0.18,-9.1e-05,0.00014,0.75,-0.017,0.034,-0.23,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.4e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,9.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32090000,0.98,-0.0065,-0.014,0.18,-0.00063,-0.0033,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32190000,0.98,-0.0067,-0.015,0.18,0.0047,-0.0065,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32290000,0.98,-0.0066,-0.015,0.18,0.0063,-0.0092,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32390000,0.98,-0.0067,-0.015,0.18,0.013,-0.01,0.75,0.0057,0.03,0.051,-0.0013,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,7.9e-05,4.3e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-07,2.7e-07,9.1e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.073,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32590000,0.98,-0.0095,-0.013,0.18,0.039,-0.075,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8e-05,7.8e-05,4.3e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-07,2.7e-07,8.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.074,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32590000,0.98,-0.0095,-0.013,0.18,0.04,-0.075,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8e-05,7.8e-05,4.3e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-07,2.7e-07,8.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.08,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8e-05,7.9e-05,4.3e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-07,2.7e-07,8.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32790000,0.98,-0.0092,-0.013,0.18,0.034,-0.078,-0.12,0.034,0.01,0.0044,-0.0014,-0.0057,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.7e-05,7.6e-05,4.3e-05,0.019,0.02,0.0071,0.037,0.037,0.035,2.7e-07,2.7e-07,8.8e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32890000,0.98,-0.0092,-0.013,0.18,0.033,-0.084,-0.13,0.038,0.0021,-0.011,-0.0014,-0.0057,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.7e-05,7.6e-05,4.2e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-07,2.7e-07,8.7e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.0011,-0.024,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.3e-05,7.2e-05,4.2e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,8.7e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33090000,0.98,-0.0088,-0.013,0.18,0.026,-0.083,-0.12,0.048,-0.0092,-0.031,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.3e-05,7.2e-05,4.2e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,8.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33090000,0.98,-0.0089,-0.013,0.18,0.026,-0.083,-0.12,0.048,-0.0092,-0.031,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.3e-05,7.2e-05,4.2e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,8.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33190000,0.98,-0.0085,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-0.0014,-0.0056,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.7e-05,6.6e-05,4.2e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-07,2.6e-07,8.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.08,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.7e-05,6.6e-05,4.2e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-07,2.6e-07,8.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.1e-05,6e-05,4.2e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-07,2.6e-07,8.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33490000,0.98,-0.0081,-0.013,0.18,0.0094,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.1e-05,6e-05,4.2e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-07,2.6e-07,8.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,0.00024,0.025,-0.017,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.1e-05,6e-05,4.2e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-07,2.6e-07,8.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33490000,0.98,-0.0081,-0.013,0.18,0.0094,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,0.00024,0.025,-0.017,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.1e-05,6e-05,4.2e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-07,2.6e-07,8.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33590000,0.98,-0.0077,-0.013,0.18,0.0055,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,0.00025,0.025,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,5.3e-05,5.3e-05,4.2e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,8.3e-07,0.026,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33690000,0.98,-0.0077,-0.013,0.18,0.00078,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,0.00025,0.025,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,5.4e-05,5.3e-05,4.2e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-07,2.6e-07,8.2e-07,0.026,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33790000,0.98,-0.0075,-0.013,0.18,-0.0024,-0.047,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,0.00024,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.7e-05,4.6e-05,4.1e-05,0.045,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,8.1e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
33890000,0.98,-0.0075,-0.013,0.18,-0.0066,-0.045,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,0.00025,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.7e-05,4.6e-05,4.1e-05,0.052,0.053,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,8.1e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.1e-05,4.1e-05,4.1e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,8e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.1e-05,4.1e-05,4.1e-05,0.054,0.055,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,8e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.02,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.7e-05,3.6e-05,4.1e-05,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,7.9e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0
|
||||
34290000,0.98,-0.0069,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.7e-05,3.7e-05,4.1e-05,0.055,0.055,0.0058,0.05,0.05,0.033,2.6e-07,2.6e-07,7.8e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0
|
||||
33690000,0.98,-0.0077,-0.013,0.18,0.00079,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,0.00025,0.025,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,5.4e-05,5.3e-05,4.2e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-07,2.6e-07,8.2e-07,0.026,0.027,0.0005,0,0,0,0,0,0,0,0
|
||||
33790000,0.98,-0.0075,-0.013,0.18,-0.0024,-0.047,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,0.00024,0.024,-0.022,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.7e-05,4.6e-05,4.1e-05,0.045,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,8.1e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
33890000,0.98,-0.0075,-0.013,0.18,-0.0066,-0.045,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,0.00025,0.023,-0.022,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.7e-05,4.6e-05,4.1e-05,0.052,0.053,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,8.1e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0
|
||||
33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,0.00024,0.021,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.1e-05,4.1e-05,4.1e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,8e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,0.00024,0.021,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.1e-05,4.1e-05,4.1e-05,0.054,0.055,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,8e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0
|
||||
34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.02,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,0.00024,0.019,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.7e-05,3.6e-05,4.1e-05,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,7.9e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0
|
||||
34290000,0.98,-0.0069,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,0.00024,0.019,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.7e-05,3.7e-05,4.1e-05,0.055,0.055,0.0058,0.05,0.05,0.033,2.6e-07,2.6e-07,7.8e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0
|
||||
34390000,0.98,-0.0068,-0.013,0.18,-0.013,-0.01,-0.092,0.073,-0.01,-0.11,-0.0014,-0.0056,0.00024,0.018,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.3e-05,3.3e-05,4.1e-05,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-07,2.6e-07,7.8e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0
|
||||
34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0091,-0.089,0.071,-0.011,-0.11,-0.0014,-0.0056,0.00024,0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.4e-05,3.3e-05,4.1e-05,0.053,0.054,0.0059,0.051,0.051,0.032,2.6e-07,2.6e-07,7.7e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0
|
||||
34590000,0.98,-0.0069,-0.013,0.18,-0.014,-0.0049,0.71,0.073,-0.0087,-0.081,-0.0014,-0.0056,0.00024,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.1e-05,3.1e-05,4.1e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-07,2.6e-07,7.7e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0
|
||||
34690000,0.98,-0.0068,-0.012,0.18,-0.017,-0.0027,1.7,0.071,-0.0091,0.038,-0.0014,-0.0056,0.00023,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.1e-05,3.1e-05,4.1e-05,0.047,0.048,0.006,0.052,0.052,0.032,2.6e-07,2.6e-07,7.6e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0
|
||||
34790000,0.98,-0.0068,-0.012,0.18,-0.019,0.0019,2.7,0.072,-0.0068,0.21,-0.0014,-0.0056,0.00023,0.018,-0.029,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3e-05,2.9e-05,4e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-07,2.6e-07,7.6e-07,0.021,0.021,0.0005,0,0,0,0,0,0,0,0
|
||||
34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0043,3.6,0.07,-0.0063,0.5,-0.0014,-0.0056,0.00023,0.018,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3e-05,3e-05,4e-05,0.044,0.044,0.0061,0.052,0.052,0.032,2.6e-07,2.6e-07,7.5e-07,0.021,0.021,0.0005,0,0,0,0,0,0,0,0
|
||||
34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0091,-0.089,0.071,-0.011,-0.11,-0.0014,-0.0056,0.00024,0.018,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.4e-05,3.3e-05,4.1e-05,0.053,0.054,0.0059,0.051,0.051,0.032,2.6e-07,2.6e-07,7.7e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0
|
||||
34590000,0.98,-0.0069,-0.013,0.18,-0.014,-0.0048,0.71,0.073,-0.0087,-0.081,-0.0014,-0.0056,0.00024,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.1e-05,3.1e-05,4.1e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-07,2.6e-07,7.7e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0
|
||||
34690000,0.98,-0.0069,-0.012,0.18,-0.017,-0.0027,1.7,0.071,-0.0091,0.038,-0.0014,-0.0056,0.00023,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.1e-05,3.1e-05,4.1e-05,0.047,0.048,0.006,0.052,0.052,0.032,2.6e-07,2.6e-07,7.6e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0
|
||||
34790000,0.98,-0.0068,-0.012,0.18,-0.019,0.0019,2.7,0.072,-0.0068,0.21,-0.0014,-0.0056,0.00023,0.018,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3e-05,2.9e-05,4e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-07,2.6e-07,7.6e-07,0.021,0.021,0.0005,0,0,0,0,0,0,0,0
|
||||
34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0044,3.6,0.07,-0.0063,0.5,-0.0014,-0.0056,0.00023,0.018,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3e-05,3e-05,4e-05,0.044,0.044,0.0061,0.052,0.052,0.032,2.6e-07,2.6e-07,7.5e-07,0.021,0.021,0.0005,0,0,0,0,0,0,0,0
|
||||
|
|
|
Loading…
Reference in New Issue