mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-14 04:27:36 +08:00
[WIP] ekf2: GPS always on delayed time horizon
This commit is contained in:
@@ -119,24 +119,6 @@ enum SensorFusionMask : uint16_t {
|
||||
USE_EXT_VIS_VEL = (1<<8) ///< set to true to use external vision velocity data
|
||||
};
|
||||
|
||||
struct gpsMessage {
|
||||
uint64_t time_usec{};
|
||||
int32_t lat{}; ///< Latitude in 1E-7 degrees
|
||||
int32_t lon{}; ///< Longitude in 1E-7 degrees
|
||||
int32_t alt{}; ///< Altitude in 1E-3 meters (millimeters) above MSL
|
||||
float yaw{}; ///< yaw angle. NaN if not set (used for dual antenna GPS), (rad, [-PI, PI])
|
||||
float yaw_offset{}; ///< Heading/Yaw offset for dual antenna GPS - refer to description for GPS_YAW_OFFSET
|
||||
uint8_t fix_type{}; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic
|
||||
float eph{}; ///< GPS horizontal position accuracy in m
|
||||
float epv{}; ///< GPS vertical position accuracy in m
|
||||
float sacc{}; ///< GPS speed accuracy in m/s
|
||||
float vel_m_s{}; ///< GPS ground speed (m/sec)
|
||||
Vector3f vel_ned{}; ///< GPS ground speed NED
|
||||
bool vel_ned_valid{}; ///< GPS ground speed is valid
|
||||
uint8_t nsats{}; ///< number of satellites used
|
||||
float pdop{}; ///< position dilution of precision
|
||||
};
|
||||
|
||||
struct outputSample {
|
||||
uint64_t time_us{}; ///< timestamp of the measurement (uSec)
|
||||
Quatf quat_nominal{}; ///< nominal quaternion describing vehicle attitude
|
||||
@@ -162,13 +144,23 @@ struct imuSample {
|
||||
|
||||
struct gpsSample {
|
||||
uint64_t time_us{}; ///< timestamp of the measurement (uSec)
|
||||
Vector2f pos{}; ///< NE earth frame gps horizontal position measurement (m)
|
||||
float hgt{}; ///< gps height measurement (m)
|
||||
Vector3f vel{}; ///< NED earth frame gps velocity measurement (m/sec)
|
||||
float yaw{}; ///< yaw angle. NaN if not set (used for dual antenna GPS), (rad, [-PI, PI])
|
||||
double lat{};
|
||||
double lon{};
|
||||
float alt{}; ///< gps height measurement (m)
|
||||
|
||||
Vector3f vel{}; ///< NED earth frame gps velocity measurement (m/sec)
|
||||
|
||||
float hacc{}; ///< 1-std horizontal position error (m)
|
||||
float vacc{}; ///< 1-std vertical position error (m)
|
||||
float sacc{}; ///< 1-std speed error (m/sec)
|
||||
|
||||
float yaw{}; ///< yaw angle. NaN if not set (used for dual antenna GPS), (rad, [-PI, PI])
|
||||
float yaw_accuracy{};
|
||||
float yaw_offset{}; ///< Heading/Yaw offset for dual antenna GPS - refer to description for GPS_YAW_OFFSET
|
||||
|
||||
float pdop{}; ///< position dilution of precision
|
||||
uint8_t fix_type{}; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic
|
||||
uint8_t nsats{}; ///< number of satellites used
|
||||
};
|
||||
|
||||
struct magSample {
|
||||
|
||||
@@ -89,13 +89,13 @@ void Ekf::controlFusionModes()
|
||||
// check for intermittent data
|
||||
_baro_hgt_intermittent = !isRecent(_time_last_baro, 2 * BARO_MAX_INTERVAL);
|
||||
|
||||
const uint64_t baro_time_prev = _baro_sample_delayed.time_us;
|
||||
const uint64_t time_prev = _baro_sample_delayed.time_us;
|
||||
_baro_data_ready = _baro_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &_baro_sample_delayed);
|
||||
|
||||
// if we have a new baro sample save the delta time between this sample and the last sample which is
|
||||
// used below for baro offset calculations
|
||||
if (_baro_data_ready && baro_time_prev != 0) {
|
||||
_delta_time_baro_us = _baro_sample_delayed.time_us - baro_time_prev;
|
||||
if (_baro_data_ready && time_prev != 0) {
|
||||
_delta_time_baro_us = _baro_sample_delayed.time_us - time_prev;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -104,22 +104,21 @@ void Ekf::controlFusionModes()
|
||||
_gps_intermittent = !isRecent(_time_last_gps, 2 * GPS_MAX_INTERVAL);
|
||||
|
||||
// check for arrival of new sensor data at the fusion time horizon
|
||||
_time_prev_gps_us = _gps_sample_delayed.time_us;
|
||||
const uint64_t time_prev = _gps_sample_delayed.time_us;
|
||||
_gps_data_ready = _gps_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &_gps_sample_delayed);
|
||||
|
||||
if (_gps_data_ready) {
|
||||
// correct velocity for offset relative to IMU
|
||||
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
|
||||
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
|
||||
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
|
||||
_gps_sample_delayed.vel -= vel_offset_earth;
|
||||
if (time_prev) {
|
||||
// if we have a new sample save the delta time between this sample and the last sample which is
|
||||
// used below for height offset calculations
|
||||
_delta_time_gnss_us = _gps_sample_delayed.time_us - time_prev;
|
||||
}
|
||||
|
||||
// correct position and height for offset relative to IMU
|
||||
const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
|
||||
_gps_sample_delayed.pos -= pos_offset_earth.xy();
|
||||
_gps_sample_delayed.hgt += pos_offset_earth(2);
|
||||
_gps_data_ready = collect_gps(_gps_sample_delayed);
|
||||
|
||||
_gps_sample_delayed.sacc = fmaxf(_gps_sample_delayed.sacc, _params.gps_vel_noise);
|
||||
if (_gps_data_ready) {
|
||||
_time_prev_gps_us = _gps_sample_delayed.time_us;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -554,7 +553,7 @@ void Ekf::resetOnGroundMotionForOpticalFlowChecks()
|
||||
_time_good_motion_us = _imu_sample_delayed.time_us;
|
||||
}
|
||||
|
||||
void Ekf::controlGpsYawFusion(bool gps_checks_passing, bool gps_checks_failing)
|
||||
void Ekf::controlGpsYawFusion(const gpsSample &gps_sample, bool gps_checks_passing, bool gps_checks_failing)
|
||||
{
|
||||
if (!(_params.fusion_mode & SensorFusionMask::USE_GPS_YAW)
|
||||
|| _control_status.flags.gps_yaw_fault) {
|
||||
@@ -563,7 +562,7 @@ void Ekf::controlGpsYawFusion(bool gps_checks_passing, bool gps_checks_failing)
|
||||
return;
|
||||
}
|
||||
|
||||
const bool is_new_data_available = PX4_ISFINITE(_gps_sample_delayed.yaw);
|
||||
const bool is_new_data_available = PX4_ISFINITE(gps_sample.yaw);
|
||||
|
||||
if (is_new_data_available) {
|
||||
|
||||
@@ -583,14 +582,14 @@ void Ekf::controlGpsYawFusion(bool gps_checks_passing, bool gps_checks_failing)
|
||||
|
||||
if (continuing_conditions_passing) {
|
||||
|
||||
fuseGpsYaw();
|
||||
fuseGpsYaw(gps_sample);
|
||||
|
||||
const bool is_fusion_failing = isTimedOut(_time_last_gps_yaw_fuse, _params.reset_timeout_max);
|
||||
|
||||
if (is_fusion_failing) {
|
||||
if (_nb_gps_yaw_reset_available > 0) {
|
||||
// Data seems good, attempt a reset
|
||||
resetYawToGps();
|
||||
resetYawToGps(gps_sample);
|
||||
|
||||
if (_control_status.flags.in_air) {
|
||||
_nb_gps_yaw_reset_available--;
|
||||
@@ -619,7 +618,7 @@ void Ekf::controlGpsYawFusion(bool gps_checks_passing, bool gps_checks_failing)
|
||||
} else {
|
||||
if (starting_conditions_passing) {
|
||||
// Try to activate GPS yaw fusion
|
||||
startGpsYawFusion();
|
||||
startGpsYawFusion(gps_sample);
|
||||
|
||||
if (_control_status.flags.gps_yaw) {
|
||||
_nb_gps_yaw_reset_available = 1;
|
||||
@@ -761,7 +760,7 @@ void Ekf::controlHeightSensorTimeouts()
|
||||
|
||||
// Also reset the vertical velocity
|
||||
if (_control_status.flags.gps && !_gps_intermittent && _gps_checks_passed) {
|
||||
resetVerticalVelocityToGps(_gps_sample_delayed);
|
||||
resetVerticalVelocityToGps();
|
||||
|
||||
} else {
|
||||
resetVerticalVelocityToZero();
|
||||
@@ -915,7 +914,7 @@ void Ekf::controlHeightFusion()
|
||||
case VerticalHeightSensor::GPS:
|
||||
|
||||
// NOTE: emergency fallback due to extended loss of currently selected sensor data or failure
|
||||
// to pass innovation cinsistency checks is handled elsewhere in Ekf::controlHeightSensorTimeouts.
|
||||
// to pass innovation consistency checks is handled elsewhere in Ekf::controlHeightSensorTimeouts.
|
||||
// Do switching between GPS and rangefinder if using range finder as a height source when close
|
||||
// to ground and moving slowly. Also handle switch back from emergency Baro sensor when GPS recovers.
|
||||
if (do_range_aid) {
|
||||
@@ -949,10 +948,24 @@ void Ekf::controlHeightFusion()
|
||||
}
|
||||
|
||||
updateBaroHgtBias();
|
||||
updateBaroHgtOffset();
|
||||
|
||||
updateGroundEffect();
|
||||
|
||||
if (_baro_data_ready) {
|
||||
if (!_control_status.flags.baro_hgt) {
|
||||
// calculate a filtered offset between the baro origin and local NED origin if we are not
|
||||
// using the baro as a height reference
|
||||
if (_delta_time_baro_us != 0) {
|
||||
const float local_time_step = math::constrain(1e-6f * _delta_time_baro_us, 0.0f, 1.0f);
|
||||
|
||||
// apply a 10 second first order low pass filter to baro offset
|
||||
const float unbiased_baro = _baro_sample_delayed.hgt - _baro_b_est.getBias();
|
||||
|
||||
const float offset_rate_correction = 0.1f * (unbiased_baro + _state.pos(2) - _baro_hgt_offset);
|
||||
_baro_hgt_offset += local_time_step * math::constrain(offset_rate_correction, -0.1f, 0.1f);
|
||||
}
|
||||
}
|
||||
|
||||
updateBaroHgt(_baro_sample_delayed, _aid_src_baro_hgt);
|
||||
|
||||
if (_control_status.flags.baro_hgt && !_baro_hgt_faulty) {
|
||||
|
||||
@@ -73,7 +73,7 @@ void Ekf::initialiseCovariance()
|
||||
P(9,9) = sq(fmaxf(_params.range_noise, 0.01f));
|
||||
|
||||
} else if (_control_status.flags.gps_hgt) {
|
||||
P(9,9) = getGpsHeightVariance();
|
||||
P(9,9) = sq(fmaxf(1.5f * _params.gps_pos_noise, 0.01f));
|
||||
|
||||
} else {
|
||||
P(9,9) = sq(fmaxf(_params.baro_noise, 0.01f));
|
||||
|
||||
+12
-12
@@ -167,7 +167,7 @@ public:
|
||||
matrix::SquareMatrix<float, 3> position_covariances() const { return P.slice<3, 3>(7, 7); }
|
||||
|
||||
// ask estimator for sensor data collection decision and do any preprocessing if required, returns true if not defined
|
||||
bool collect_gps(const gpsMessage &gps) override;
|
||||
bool collect_gps(const gpsSample &gps);
|
||||
|
||||
// get the ekf WGS-84 origin position and height and the system time it was last set
|
||||
// return true if the origin is valid
|
||||
@@ -425,6 +425,8 @@ private:
|
||||
|
||||
uint64_t _time_acc_bias_check{0}; ///< last time the accel bias check passed (uSec)
|
||||
uint64_t _delta_time_baro_us{0}; ///< delta time between two consecutive delayed baro samples from the buffer (uSec)
|
||||
uint64_t _delta_time_gnss_us{0}; ///< delta time between two consecutive delayed GNSS samples from the buffer (uSec)
|
||||
uint64_t _delta_time_ev_us{0}; ///< delta time between two consecutive delayed EV samples from the buffer (uSec)
|
||||
|
||||
Vector3f _earth_rate_NED{}; ///< earth rotation vector (NED) in rad/s
|
||||
|
||||
@@ -629,11 +631,11 @@ private:
|
||||
const Vector4f &yaw_jacobian);
|
||||
|
||||
// fuse the yaw angle obtained from a dual antenna GPS unit
|
||||
void fuseGpsYaw();
|
||||
void fuseGpsYaw(const gpsSample &gps_sample);
|
||||
|
||||
// reset the quaternions states using the yaw angle obtained from a dual antenna GPS unit
|
||||
// return true if the reset was successful
|
||||
bool resetYawToGps();
|
||||
bool resetYawToGps(const gpsSample& gps_sample);
|
||||
|
||||
// fuse magnetometer declination measurement
|
||||
// argument passed in is the declination uncertainty in radians
|
||||
@@ -683,7 +685,7 @@ private:
|
||||
void resetHeightToRng();
|
||||
void resetHeightToEv();
|
||||
|
||||
void resetVerticalVelocityToGps(const gpsSample &gps_sample_delayed);
|
||||
void resetVerticalVelocityToGps();
|
||||
void resetVerticalVelocityToZero();
|
||||
|
||||
// fuse optical flow line of sight rate measurements
|
||||
@@ -701,10 +703,10 @@ private:
|
||||
bool fuseVerticalPosition(float innov, float innov_gate, float obs_var,
|
||||
float &innov_var, float &test_ratio);
|
||||
|
||||
void updateGpsVel(const gpsSample &gps_sample);
|
||||
void updateGpsVel(const uint64_t& time_us, const Vector3f vel, float sacc);
|
||||
void fuseGpsVel();
|
||||
|
||||
void updateGpsPos(const gpsSample &gps_sample);
|
||||
void updateGpsPos(const uint64_t& time_us, const Vector3f& position, float hacc, float vacc);
|
||||
void fuseGpsPos();
|
||||
|
||||
// calculate optical flow body angular rate compensation
|
||||
@@ -838,7 +840,7 @@ private:
|
||||
Vector3f calcEarthRateNED(float lat_rad) const;
|
||||
|
||||
// return true id the GPS quality is good enough to set an origin and start aiding
|
||||
bool gps_is_good(const gpsMessage &gps);
|
||||
bool gps_is_good(const gpsSample &gps);
|
||||
|
||||
// Control the filter fusion modes
|
||||
void controlFusionModes();
|
||||
@@ -857,7 +859,7 @@ private:
|
||||
bool hasHorizontalAidingTimedOut() const;
|
||||
bool isYawFailure() const;
|
||||
|
||||
void controlGpsYawFusion(bool gps_checks_passing, bool gps_checks_failing);
|
||||
void controlGpsYawFusion(const gpsSample &gps_sample, bool gps_checks_passing, bool gps_checks_failing);
|
||||
|
||||
// control fusion of magnetometer observations
|
||||
void controlMagFusion();
|
||||
@@ -948,13 +950,12 @@ private:
|
||||
void startRngAidHgtFusion();
|
||||
void startEvHgtFusion();
|
||||
|
||||
void updateBaroHgtOffset();
|
||||
void updateBaroHgtBias();
|
||||
|
||||
void updateGroundEffect();
|
||||
|
||||
// return an estimation of the sensor altitude variance
|
||||
float getGpsHeightVariance();
|
||||
float getGpsHeightVariance(float vacc);
|
||||
float getRngHeightVariance() const;
|
||||
|
||||
// calculate the measurement variance for the optical flow sensor
|
||||
@@ -1017,12 +1018,11 @@ private:
|
||||
void startAirspeedFusion();
|
||||
void stopAirspeedFusion();
|
||||
|
||||
void startGpsFusion();
|
||||
void stopGpsFusion();
|
||||
void stopGpsPosFusion();
|
||||
void stopGpsVelFusion();
|
||||
|
||||
void startGpsYawFusion();
|
||||
void startGpsYawFusion(const gpsSample& gps_sample);
|
||||
void stopGpsYawFusion();
|
||||
|
||||
void startEvPosFusion();
|
||||
|
||||
@@ -44,12 +44,19 @@
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <cstdlib>
|
||||
|
||||
void Ekf::resetVelocityToGps(const gpsSample &gps_sample_delayed)
|
||||
void Ekf::resetVelocityToGps(const gpsSample &gps_sample)
|
||||
{
|
||||
_information_events.flags.reset_vel_to_gps = true;
|
||||
ECL_INFO("reset velocity to GPS");
|
||||
resetVelocityTo(gps_sample_delayed.vel);
|
||||
P.uncorrelateCovarianceSetVariance<3>(4, sq(gps_sample_delayed.sacc));
|
||||
|
||||
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
|
||||
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
|
||||
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
|
||||
|
||||
const Vector3f velocity{gps_sample.vel - vel_offset_earth};
|
||||
|
||||
resetVelocityTo(velocity);
|
||||
P.uncorrelateCovarianceSetVariance<3>(4, sq(gps_sample.sacc));
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalVelocityToOpticalFlow()
|
||||
@@ -144,12 +151,19 @@ void Ekf::resetVerticalVelocityTo(float new_vert_vel)
|
||||
_time_last_ver_vel_fuse = _time_last_imu;
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalPositionToGps(const gpsSample &gps_sample_delayed)
|
||||
void Ekf::resetHorizontalPositionToGps(const gpsSample &gps_sample)
|
||||
{
|
||||
_information_events.flags.reset_pos_to_gps = true;
|
||||
ECL_INFO("reset position to GPS");
|
||||
resetHorizontalPositionTo(gps_sample_delayed.pos);
|
||||
P.uncorrelateCovarianceSetVariance<2>(7, sq(gps_sample_delayed.hacc));
|
||||
|
||||
// correct position and height for offset relative to IMU
|
||||
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
|
||||
const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
|
||||
|
||||
const Vector2f gnss_position = _pos_ref.project(gps_sample.lat, gps_sample.lon) - pos_offset_earth.xy();
|
||||
|
||||
resetHorizontalPositionTo(gnss_position);
|
||||
P.uncorrelateCovarianceSetVariance<2>(7, sq(gps_sample.hacc));
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalPositionToVision()
|
||||
@@ -256,13 +270,20 @@ void Ekf::resetHeightToGps()
|
||||
_information_events.flags.reset_hgt_to_gps = true;
|
||||
|
||||
const float z_pos_before_reset = _state.pos(2);
|
||||
resetVerticalPositionTo(-_gps_sample_delayed.hgt + getEkfGlobalOriginAltitude());
|
||||
|
||||
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
|
||||
const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
|
||||
resetVerticalPositionTo(-(_gps_sample_delayed.alt + pos_offset_earth(2)) + getEkfGlobalOriginAltitude());
|
||||
|
||||
// the state variance is the same as the observation
|
||||
P.uncorrelateCovarianceSetVariance<1>(9, getGpsHeightVariance());
|
||||
P.uncorrelateCovarianceSetVariance<1>(9, getGpsHeightVariance(_gps_sample_delayed.vacc));
|
||||
|
||||
// adjust the baro offset
|
||||
_baro_hgt_offset += _state.pos(2) - z_pos_before_reset;
|
||||
// adjust the height offsets
|
||||
const float delta_z = _state.pos(2) - z_pos_before_reset;
|
||||
_baro_hgt_offset += delta_z;
|
||||
_gps_hgt_offset = 0.f;
|
||||
_rng_hgt_offset += delta_z;
|
||||
_ev_hgt_offset += delta_z;
|
||||
}
|
||||
|
||||
void Ekf::resetHeightToRng()
|
||||
@@ -287,8 +308,12 @@ void Ekf::resetHeightToRng()
|
||||
// the state variance is the same as the observation
|
||||
P.uncorrelateCovarianceSetVariance<1>(9, sq(_params.range_noise));
|
||||
|
||||
// adjust the baro offset
|
||||
_baro_hgt_offset += _state.pos(2) - z_pos_before_reset;
|
||||
// adjust the height offsets
|
||||
const float delta_z = _state.pos(2) - z_pos_before_reset;
|
||||
_baro_hgt_offset += delta_z;
|
||||
_gps_hgt_offset += delta_z;
|
||||
_rng_hgt_offset = 0;
|
||||
_ev_hgt_offset += delta_z;
|
||||
}
|
||||
|
||||
void Ekf::resetHeightToEv()
|
||||
@@ -302,16 +327,29 @@ void Ekf::resetHeightToEv()
|
||||
// the state variance is the same as the observation
|
||||
P.uncorrelateCovarianceSetVariance<1>(9, fmaxf(_ev_sample_delayed.posVar(2), sq(0.01f)));
|
||||
|
||||
// adjust the baro offset
|
||||
_baro_hgt_offset += _state.pos(2) - z_pos_before_reset;
|
||||
// adjust the height offsets
|
||||
const float delta_z = _state.pos(2) - z_pos_before_reset;
|
||||
_baro_hgt_offset += delta_z;
|
||||
_gps_hgt_offset += delta_z;
|
||||
_rng_hgt_offset += delta_z;
|
||||
_ev_hgt_offset += 0;
|
||||
}
|
||||
|
||||
void Ekf::resetVerticalVelocityToGps(const gpsSample &gps_sample_delayed)
|
||||
void Ekf::resetVerticalVelocityToGps()
|
||||
{
|
||||
resetVerticalVelocityTo(gps_sample_delayed.vel(2));
|
||||
// correct velocity for offset relative to IMU
|
||||
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
|
||||
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
|
||||
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
|
||||
|
||||
const gpsSample gps_sample{_gps_sample_delayed};
|
||||
|
||||
const Vector3f gnss_velocity = gps_sample.vel - vel_offset_earth;
|
||||
|
||||
resetVerticalVelocityTo(gnss_velocity(2));
|
||||
|
||||
// the state variance is the same as the observation
|
||||
P.uncorrelateCovarianceSetVariance<1>(6, sq(1.5f * gps_sample_delayed.sacc));
|
||||
P.uncorrelateCovarianceSetVariance<1>(6, sq(1.5f * gps_sample.sacc));
|
||||
}
|
||||
|
||||
void Ekf::resetVerticalVelocityToZero()
|
||||
@@ -352,11 +390,20 @@ void Ekf::alignOutputFilter()
|
||||
// It is used to align the yaw angle after launch or takeoff for fixed wing vehicle only.
|
||||
bool Ekf::realignYawGPS(const Vector3f &mag)
|
||||
{
|
||||
const float gpsSpeed = sqrtf(sq(_gps_sample_delayed.vel(0)) + sq(_gps_sample_delayed.vel(1)));
|
||||
const gpsSample& gps_sample = _gps_sample_delayed;
|
||||
|
||||
// correct velocity for offset relative to IMU
|
||||
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
|
||||
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
|
||||
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
|
||||
|
||||
const Vector3f gnss_velocity = gps_sample.vel - vel_offset_earth;
|
||||
|
||||
const float gpsSpeed = sqrtf(sq(gnss_velocity(0)) + sq(gnss_velocity(1)));
|
||||
|
||||
// Need at least 5 m/s of GPS horizontal speed and
|
||||
// ratio of velocity error to velocity < 0.15 for a reliable alignment
|
||||
const bool gps_yaw_alignment_possible = (gpsSpeed > 5.0f) && (_gps_sample_delayed.sacc < (0.15f * gpsSpeed));
|
||||
const bool gps_yaw_alignment_possible = (gpsSpeed > 5.0f) && (gps_sample.sacc < (0.15f * gpsSpeed));
|
||||
|
||||
if (!gps_yaw_alignment_possible) {
|
||||
// attempt a normal alignment using the magnetometer
|
||||
@@ -368,7 +415,7 @@ bool Ekf::realignYawGPS(const Vector3f &mag)
|
||||
const bool badVelInnov = (gps_vel_test_ratio > 1.0f) && _control_status.flags.gps;
|
||||
|
||||
// calculate GPS course over ground angle
|
||||
const float gpsCOG = atan2f(_gps_sample_delayed.vel(1), _gps_sample_delayed.vel(0));
|
||||
const float gpsCOG = atan2f(gnss_velocity(1), gnss_velocity(0));
|
||||
|
||||
// calculate course yaw angle
|
||||
const float ekfCOG = atan2f(_state.vel(1), _state.vel(0));
|
||||
@@ -410,17 +457,17 @@ bool Ekf::realignYawGPS(const Vector3f &mag)
|
||||
} else if (_control_status.flags.wind) {
|
||||
// we have previously aligned yaw in-flight and have wind estimates so set the yaw such that the vehicle nose is
|
||||
// aligned with the wind relative GPS velocity vector
|
||||
yaw_new = atan2f((_gps_sample_delayed.vel(1) - _state.wind_vel(1)),
|
||||
(_gps_sample_delayed.vel(0) - _state.wind_vel(0)));
|
||||
yaw_new = atan2f((gnss_velocity(1) - _state.wind_vel(1)),
|
||||
(gnss_velocity(0) - _state.wind_vel(0)));
|
||||
|
||||
} else {
|
||||
// we don't have wind estimates, so align yaw to the GPS velocity vector
|
||||
yaw_new = atan2f(_gps_sample_delayed.vel(1), _gps_sample_delayed.vel(0));
|
||||
yaw_new = atan2f(gnss_velocity(1), gnss_velocity(0));
|
||||
|
||||
}
|
||||
|
||||
// use the combined EKF and GPS speed variance to calculate a rough estimate of the yaw error after alignment
|
||||
const float SpdErrorVariance = sq(_gps_sample_delayed.sacc) + P(4, 4) + P(5, 5);
|
||||
const float SpdErrorVariance = sq(gps_sample.sacc) + P(4, 4) + P(5, 5);
|
||||
const float sineYawError = math::constrain(sqrtf(SpdErrorVariance) / gpsSpeed, 0.0f, 1.0f);
|
||||
const float yaw_variance_new = sq(asinf(sineYawError));
|
||||
|
||||
@@ -438,8 +485,8 @@ bool Ekf::realignYawGPS(const Vector3f &mag)
|
||||
|
||||
// If heading was bad, then we also need to reset the velocity and position states
|
||||
if (badMagYaw) {
|
||||
resetVelocityToGps(_gps_sample_delayed);
|
||||
resetHorizontalPositionToGps(_gps_sample_delayed);
|
||||
resetVelocityToGps(gps_sample);
|
||||
resetHorizontalPositionToGps(gps_sample);
|
||||
}
|
||||
|
||||
return true;
|
||||
@@ -742,7 +789,7 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons
|
||||
resetVerticalPositionTo(_gps_alt_ref - current_alt);
|
||||
|
||||
_baro_hgt_offset -= _state_reset_status.posD_change;
|
||||
|
||||
_gps_hgt_offset = 0.f; // TODO
|
||||
_rng_hgt_offset -= _state_reset_status.posD_change;
|
||||
_ev_hgt_offset -= _state_reset_status.posD_change;
|
||||
}
|
||||
@@ -1306,14 +1353,7 @@ void Ekf::startBaroHgtFusion()
|
||||
void Ekf::startGpsHgtFusion()
|
||||
{
|
||||
if (!_control_status.flags.gps_hgt) {
|
||||
if (_control_status.flags.rng_hgt) {
|
||||
// switch out of range aid
|
||||
// calculate height sensor offset such that current
|
||||
// measurement matches our current height estimate
|
||||
_gps_hgt_offset = _gps_sample_delayed.hgt - getEkfGlobalOriginAltitude() + _state.pos(2);
|
||||
|
||||
} else {
|
||||
_gps_hgt_offset = 0.f;
|
||||
if (!_control_status.flags.rng_hgt) {
|
||||
resetHeightToGps();
|
||||
}
|
||||
|
||||
@@ -1368,28 +1408,13 @@ void Ekf::startEvHgtFusion()
|
||||
}
|
||||
}
|
||||
|
||||
void Ekf::updateBaroHgtOffset()
|
||||
{
|
||||
// calculate a filtered offset between the baro origin and local NED origin if we are not
|
||||
// using the baro as a height reference
|
||||
if (!_control_status.flags.baro_hgt && _baro_data_ready && (_delta_time_baro_us != 0)) {
|
||||
const float local_time_step = math::constrain(1e-6f * _delta_time_baro_us, 0.0f, 1.0f);
|
||||
|
||||
// apply a 10 second first order low pass filter to baro offset
|
||||
const float unbiased_baro = _baro_sample_delayed.hgt - _baro_b_est.getBias();
|
||||
|
||||
const float offset_rate_correction = 0.1f * (unbiased_baro + _state.pos(2) - _baro_hgt_offset);
|
||||
_baro_hgt_offset += local_time_step * math::constrain(offset_rate_correction, -0.1f, 0.1f);
|
||||
}
|
||||
}
|
||||
|
||||
float Ekf::getGpsHeightVariance()
|
||||
float Ekf::getGpsHeightVariance(float vacc)
|
||||
{
|
||||
// observation variance - receiver defined and parameter limited
|
||||
// use 1.5 as a typical ratio of vacc/hacc
|
||||
const float lower_limit = fmaxf(1.5f * _params.gps_pos_noise, 0.01f);
|
||||
const float upper_limit = fmaxf(1.5f * _params.pos_noaid_noise, lower_limit);
|
||||
const float gps_alt_var = sq(math::constrain(_gps_sample_delayed.vacc, lower_limit, upper_limit));
|
||||
const float gps_alt_var = sq(math::constrain(vacc, lower_limit, upper_limit));
|
||||
return gps_alt_var;
|
||||
}
|
||||
|
||||
@@ -1407,9 +1432,14 @@ void Ekf::updateBaroHgtBias()
|
||||
&& _gps_checks_passed && _NED_origin_initialised
|
||||
&& !_baro_hgt_faulty) {
|
||||
// Use GPS altitude as a reference to compute the baro bias measurement
|
||||
const float baro_bias = (_baro_sample_delayed.hgt - _baro_hgt_offset)
|
||||
- (_gps_sample_delayed.hgt - getEkfGlobalOriginAltitude());
|
||||
const float baro_bias_var = getGpsHeightVariance() + sq(_params.baro_noise);
|
||||
|
||||
// correct position and height for offset relative to IMU
|
||||
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
|
||||
const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
|
||||
const float gps_hgt = _gps_sample_delayed.alt + pos_offset_earth(2) - getEkfGlobalOriginAltitude();
|
||||
|
||||
const float baro_bias = (_baro_sample_delayed.hgt - _baro_hgt_offset) - gps_hgt;
|
||||
const float baro_bias_var = getGpsHeightVariance(_gps_sample_delayed.vacc) + sq(_params.baro_noise);
|
||||
_baro_b_est.fuseBias(baro_bias, baro_bias_var);
|
||||
}
|
||||
}
|
||||
@@ -1589,22 +1619,6 @@ void Ekf::stopAirspeedFusion()
|
||||
_control_status.flags.fuse_aspd = false;
|
||||
}
|
||||
|
||||
void Ekf::startGpsFusion()
|
||||
{
|
||||
if (!_control_status.flags.gps) {
|
||||
resetHorizontalPositionToGps(_gps_sample_delayed);
|
||||
|
||||
// when already using another velocity source velocity reset is not necessary
|
||||
if (!_control_status.flags.opt_flow && !_control_status.flags.ev_vel) {
|
||||
resetVelocityToGps(_gps_sample_delayed);
|
||||
}
|
||||
|
||||
_information_events.flags.starting_gps_fusion = true;
|
||||
ECL_INFO("starting GPS fusion");
|
||||
_control_status.flags.gps = true;
|
||||
}
|
||||
}
|
||||
|
||||
void Ekf::stopGpsFusion()
|
||||
{
|
||||
if (_control_status.flags.gps) {
|
||||
@@ -1642,9 +1656,9 @@ void Ekf::stopGpsVelFusion()
|
||||
resetEstimatorAidStatus(_aid_src_gnss_vel);
|
||||
}
|
||||
|
||||
void Ekf::startGpsYawFusion()
|
||||
void Ekf::startGpsYawFusion(const gpsSample& gps_sample)
|
||||
{
|
||||
if (!_control_status.flags.gps_yaw && resetYawToGps()) {
|
||||
if (!_control_status.flags.gps_yaw && resetYawToGps(gps_sample)) {
|
||||
ECL_INFO("starting GPS yaw fusion");
|
||||
_control_status.flags.yaw_align = true;
|
||||
_control_status.flags.mag_dec = false;
|
||||
@@ -1846,12 +1860,6 @@ void Ekf::runYawEKFGSF()
|
||||
|
||||
const Vector3f imu_gyro_bias = getGyroBias();
|
||||
_yawEstimator.update(_imu_sample_delayed, _control_status.flags.in_air, TAS, imu_gyro_bias);
|
||||
|
||||
// basic sanity check on GPS velocity data
|
||||
if (_gps_data_ready && _gps_sample_delayed.vacc > FLT_EPSILON &&
|
||||
PX4_ISFINITE(_gps_sample_delayed.vel(0)) && PX4_ISFINITE(_gps_sample_delayed.vel(1))) {
|
||||
_yawEstimator.setVelocity(_gps_sample_delayed.vel.xy(), _gps_sample_delayed.vacc);
|
||||
}
|
||||
}
|
||||
|
||||
void Ekf::resetGpsDriftCheckFilters()
|
||||
|
||||
@@ -129,7 +129,7 @@ void EstimatorInterface::setMagData(const magSample &mag_sample)
|
||||
}
|
||||
}
|
||||
|
||||
void EstimatorInterface::setGpsData(const gpsMessage &gps)
|
||||
void EstimatorInterface::setGpsData(const gpsSample &gps)
|
||||
{
|
||||
if (!_initialised) {
|
||||
return;
|
||||
@@ -147,44 +147,18 @@ void EstimatorInterface::setGpsData(const gpsMessage &gps)
|
||||
}
|
||||
}
|
||||
|
||||
if ((gps.time_usec - _time_last_gps) > _min_obs_interval_us) {
|
||||
_time_last_gps = gps.time_usec;
|
||||
if ((gps.time_us - _time_last_gps) > _min_obs_interval_us) {
|
||||
_time_last_gps = gps.time_us;
|
||||
|
||||
gpsSample gps_sample_new;
|
||||
gpsSample gps_sample_new{gps};
|
||||
|
||||
gps_sample_new.time_us = gps.time_usec - static_cast<uint64_t>(_params.gps_delay_ms * 1000);
|
||||
gps_sample_new.time_us = gps.time_us - static_cast<uint64_t>(_params.gps_delay_ms * 1000);
|
||||
gps_sample_new.time_us -= static_cast<uint64_t>(_dt_ekf_avg * 5e5f); // seconds to microseconds divided by 2
|
||||
|
||||
gps_sample_new.vel = gps.vel_ned;
|
||||
|
||||
_gps_speed_valid = gps.vel_ned_valid;
|
||||
gps_sample_new.sacc = gps.sacc;
|
||||
gps_sample_new.hacc = gps.eph;
|
||||
gps_sample_new.vacc = gps.epv;
|
||||
|
||||
gps_sample_new.hgt = (float)gps.alt * 1e-3f;
|
||||
|
||||
gps_sample_new.yaw = gps.yaw;
|
||||
|
||||
if (PX4_ISFINITE(gps.yaw_offset)) {
|
||||
_gps_yaw_offset = gps.yaw_offset;
|
||||
|
||||
} else {
|
||||
_gps_yaw_offset = 0.0f;
|
||||
}
|
||||
|
||||
// Only calculate the relative position if the WGS-84 location of the origin is set
|
||||
if (collect_gps(gps)) {
|
||||
gps_sample_new.pos = _pos_ref.project((gps.lat / 1.0e7), (gps.lon / 1.0e7));
|
||||
|
||||
} else {
|
||||
gps_sample_new.pos(0) = 0.0f;
|
||||
gps_sample_new.pos(1) = 0.0f;
|
||||
}
|
||||
|
||||
_gps_buffer->push(gps_sample_new);
|
||||
|
||||
} else {
|
||||
ECL_ERR("GPS data too fast %" PRIu64, gps.time_usec - _time_last_gps);
|
||||
ECL_ERR("GPS data too fast %" PRIu64, gps.time_us - _time_last_gps);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -77,14 +77,11 @@ using namespace estimator;
|
||||
class EstimatorInterface
|
||||
{
|
||||
public:
|
||||
// ask estimator for sensor data collection decision and do any preprocessing if required, returns true if not defined
|
||||
virtual bool collect_gps(const gpsMessage &gps) = 0;
|
||||
|
||||
void setIMUData(const imuSample &imu_sample);
|
||||
|
||||
void setMagData(const magSample &mag_sample);
|
||||
|
||||
void setGpsData(const gpsMessage &gps);
|
||||
void setGpsData(const gpsSample &gps);
|
||||
|
||||
void setBaroData(const baroSample &baro_sample);
|
||||
|
||||
@@ -319,13 +316,11 @@ protected:
|
||||
bool _initialised{false}; // true if the ekf interface instance (data buffering) is initialized
|
||||
|
||||
bool _NED_origin_initialised{false};
|
||||
bool _gps_speed_valid{false};
|
||||
float _gps_origin_eph{0.0f}; // horizontal position uncertainty of the GPS origin
|
||||
float _gps_origin_epv{0.0f}; // vertical position uncertainty of the GPS origin
|
||||
MapProjection _pos_ref{}; // Contains WGS-84 position latitude and longitude of the EKF origin
|
||||
MapProjection _gps_pos_prev{}; // Contains WGS-84 position latitude and longitude of the previous GPS message
|
||||
float _gps_alt_prev{0.0f}; // height from the previous GPS message (m)
|
||||
float _gps_yaw_offset{0.0f}; // Yaw offset angle for dual GPS antennas used for yaw estimation (radians).
|
||||
|
||||
// innovation consistency check monitoring ratios
|
||||
float _yaw_test_ratio{}; // yaw innovation consistency check ratio
|
||||
|
||||
@@ -55,18 +55,15 @@
|
||||
#define MASK_GPS_HSPD (1<<7)
|
||||
#define MASK_GPS_VSPD (1<<8)
|
||||
|
||||
bool Ekf::collect_gps(const gpsMessage &gps)
|
||||
bool Ekf::collect_gps(const gpsSample &gps)
|
||||
{
|
||||
// Run GPS checks always
|
||||
_gps_checks_passed = gps_is_good(gps);
|
||||
|
||||
if (_filter_initialised && !_NED_origin_initialised && _gps_checks_passed) {
|
||||
// If we have good GPS data set the origin's WGS-84 position to the last gps fix
|
||||
const double lat = gps.lat * 1.0e-7;
|
||||
const double lon = gps.lon * 1.0e-7;
|
||||
|
||||
if (!_pos_ref.isInitialized()) {
|
||||
_pos_ref.initReference(lat, lon, _time_last_imu);
|
||||
_pos_ref.initReference(gps.lat, gps.lon, _time_last_imu);
|
||||
|
||||
// if we are already doing aiding, correct for the change in position since the EKF started navigating
|
||||
if (isHorizontalAidingActive()) {
|
||||
@@ -79,7 +76,7 @@ bool Ekf::collect_gps(const gpsMessage &gps)
|
||||
|
||||
// Take the current GPS height and subtract the filter height above origin to estimate the GPS height of the origin
|
||||
if (!PX4_ISFINITE(_gps_alt_ref)) {
|
||||
_gps_alt_ref = 1e-3f * (float)gps.alt + _state.pos(2);
|
||||
_gps_alt_ref = gps.alt + _state.pos(2);
|
||||
}
|
||||
|
||||
_NED_origin_initialised = true;
|
||||
@@ -90,9 +87,9 @@ bool Ekf::collect_gps(const gpsMessage &gps)
|
||||
const bool declination_was_valid = PX4_ISFINITE(_mag_declination_gps);
|
||||
|
||||
// set the magnetic field data returned by the geo library using the current GPS position
|
||||
_mag_declination_gps = get_mag_declination_radians(lat, lon);
|
||||
_mag_inclination_gps = get_mag_inclination_radians(lat, lon);
|
||||
_mag_strength_gps = get_mag_strength_gauss(lat, lon);
|
||||
_mag_declination_gps = get_mag_declination_radians(gps.lat, gps.lon);
|
||||
_mag_inclination_gps = get_mag_inclination_radians(gps.lat, gps.lon);
|
||||
_mag_strength_gps = get_mag_strength_gauss(gps.lat, gps.lon);
|
||||
|
||||
// request a reset of the yaw using the new declination
|
||||
if ((_params.mag_fusion_type != MagFuseType::NONE)
|
||||
@@ -101,26 +98,23 @@ bool Ekf::collect_gps(const gpsMessage &gps)
|
||||
}
|
||||
|
||||
// save the horizontal and vertical position uncertainty of the origin
|
||||
_gps_origin_eph = gps.eph;
|
||||
_gps_origin_epv = gps.epv;
|
||||
_gps_origin_eph = gps.hacc;
|
||||
_gps_origin_epv = gps.vacc;
|
||||
|
||||
_information_events.flags.gps_checks_passed = true;
|
||||
ECL_INFO("GPS checks passed");
|
||||
|
||||
} else if (!_NED_origin_initialised) {
|
||||
// a rough 2D fix is still sufficient to lookup declination
|
||||
if ((gps.fix_type >= 2) && (gps.eph < 1000)) {
|
||||
if ((gps.fix_type >= 2) && (gps.hacc < 1000)) {
|
||||
|
||||
const bool declination_was_valid = PX4_ISFINITE(_mag_declination_gps);
|
||||
|
||||
// If we have good GPS data set the origin's WGS-84 position to the last gps fix
|
||||
const double lat = gps.lat * 1.0e-7;
|
||||
const double lon = gps.lon * 1.0e-7;
|
||||
|
||||
// set the magnetic field data returned by the geo library using the current GPS position
|
||||
_mag_declination_gps = get_mag_declination_radians(lat, lon);
|
||||
_mag_inclination_gps = get_mag_inclination_radians(lat, lon);
|
||||
_mag_strength_gps = get_mag_strength_gauss(lat, lon);
|
||||
_mag_declination_gps = get_mag_declination_radians(gps.lat, gps.lon);
|
||||
_mag_inclination_gps = get_mag_inclination_radians(gps.lat, gps.lon);
|
||||
_mag_strength_gps = get_mag_strength_gauss(gps.lat, gps.lon);
|
||||
|
||||
// request mag yaw reset if there's a mag declination for the first time
|
||||
if (_params.mag_fusion_type != MagFuseType::NONE) {
|
||||
@@ -129,7 +123,7 @@ bool Ekf::collect_gps(const gpsMessage &gps)
|
||||
}
|
||||
}
|
||||
|
||||
_earth_rate_NED = calcEarthRateNED((float)math::radians(lat));
|
||||
_earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -144,7 +138,7 @@ bool Ekf::collect_gps(const gpsMessage &gps)
|
||||
* Checks are activated using the EKF2_GPS_CHECK bitmask parameter
|
||||
* Checks are adjusted using the EKF2_REQ_* parameters
|
||||
*/
|
||||
bool Ekf::gps_is_good(const gpsMessage &gps)
|
||||
bool Ekf::gps_is_good(const gpsSample &gps)
|
||||
{
|
||||
// Check the fix type
|
||||
_gps_check_fail_status.flags.fix = (gps.fix_type < 3);
|
||||
@@ -156,25 +150,22 @@ bool Ekf::gps_is_good(const gpsMessage &gps)
|
||||
_gps_check_fail_status.flags.pdop = (gps.pdop > _params.req_pdop);
|
||||
|
||||
// Check the reported horizontal and vertical position accuracy
|
||||
_gps_check_fail_status.flags.hacc = (gps.eph > _params.req_hacc);
|
||||
_gps_check_fail_status.flags.vacc = (gps.epv > _params.req_vacc);
|
||||
_gps_check_fail_status.flags.hacc = (gps.hacc > _params.req_hacc);
|
||||
_gps_check_fail_status.flags.vacc = (gps.vacc > _params.req_vacc);
|
||||
|
||||
// Check the reported speed accuracy
|
||||
_gps_check_fail_status.flags.sacc = (gps.sacc > _params.req_sacc);
|
||||
|
||||
// check if GPS quality is degraded
|
||||
_gps_error_norm = fmaxf((gps.eph / _params.req_hacc), (gps.epv / _params.req_vacc));
|
||||
_gps_error_norm = fmaxf((gps.hacc / _params.req_hacc), (gps.vacc / _params.req_vacc));
|
||||
_gps_error_norm = fmaxf(_gps_error_norm, (gps.sacc / _params.req_sacc));
|
||||
|
||||
// Calculate time lapsed since last update, limit to prevent numerical errors and calculate a lowpass filter coefficient
|
||||
constexpr float filt_time_const = 10.0f;
|
||||
constexpr float filt_time_const = 10.f;
|
||||
const float dt = math::constrain(float(int64_t(_time_last_imu) - int64_t(_gps_pos_prev.getProjectionReferenceTimestamp())) * 1e-6f, 0.001f, filt_time_const);
|
||||
const float filter_coef = dt / filt_time_const;
|
||||
|
||||
// The following checks are only valid when the vehicle is at rest
|
||||
const double lat = gps.lat * 1.0e-7;
|
||||
const double lon = gps.lon * 1.0e-7;
|
||||
|
||||
if (!_control_status.flags.in_air && _control_status.flags.vehicle_at_rest) {
|
||||
// Calculate position movement since last measurement
|
||||
float delta_pos_n = 0.0f;
|
||||
@@ -182,21 +173,21 @@ bool Ekf::gps_is_good(const gpsMessage &gps)
|
||||
|
||||
// calculate position movement since last GPS fix
|
||||
if (_gps_pos_prev.getProjectionReferenceTimestamp() > 0) {
|
||||
_gps_pos_prev.project(lat, lon, delta_pos_n, delta_pos_e);
|
||||
_gps_pos_prev.project(gps.lat, gps.lon, delta_pos_n, delta_pos_e);
|
||||
|
||||
} else {
|
||||
// no previous position has been set
|
||||
_gps_pos_prev.initReference(lat, lon, _time_last_imu);
|
||||
_gps_alt_prev = 1e-3f * (float)gps.alt;
|
||||
_gps_pos_prev.initReference(gps.lat, gps.lon, _time_last_imu);
|
||||
_gps_alt_prev = gps.alt;
|
||||
}
|
||||
|
||||
// Calculate the horizontal and vertical drift velocity components and limit to 10x the threshold
|
||||
const Vector3f vel_limit(_params.req_hdrift, _params.req_hdrift, _params.req_vdrift);
|
||||
Vector3f pos_derived(delta_pos_n, delta_pos_e, (_gps_alt_prev - 1e-3f * (float)gps.alt));
|
||||
pos_derived = matrix::constrain(pos_derived / dt, -10.0f * vel_limit, 10.0f * vel_limit);
|
||||
Vector3f pos_derived(delta_pos_n, delta_pos_e, (_gps_alt_prev - gps.alt));
|
||||
pos_derived = matrix::constrain(pos_derived / dt, -10.f * vel_limit, 10.f * vel_limit);
|
||||
|
||||
// Apply a low pass filter
|
||||
_gps_pos_deriv_filt = pos_derived * filter_coef + _gps_pos_deriv_filt * (1.0f - filter_coef);
|
||||
_gps_pos_deriv_filt = pos_derived * filter_coef + _gps_pos_deriv_filt * (1.f - filter_coef);
|
||||
|
||||
// Calculate the horizontal drift speed and fail if too high
|
||||
_gps_horizontal_position_drift_rate_m_s = Vector2f(_gps_pos_deriv_filt.xy()).norm();
|
||||
@@ -207,9 +198,9 @@ bool Ekf::gps_is_good(const gpsMessage &gps)
|
||||
_gps_check_fail_status.flags.vdrift = (_gps_vertical_position_drift_rate_m_s > _params.req_vdrift);
|
||||
|
||||
// Check the magnitude of the filtered horizontal GPS velocity
|
||||
const Vector2f gps_velNE = matrix::constrain(Vector2f(gps.vel_ned.xy()),
|
||||
-10.0f * _params.req_hdrift,
|
||||
10.0f * _params.req_hdrift);
|
||||
const Vector2f gps_velNE = matrix::constrain(Vector2f(gps.vel.xy()),
|
||||
-10.f * _params.req_hdrift,
|
||||
10.f * _params.req_hdrift);
|
||||
_gps_velNE_filt = gps_velNE * filter_coef + _gps_velNE_filt * (1.0f - filter_coef);
|
||||
_gps_filtered_horizontal_velocity_m_s = _gps_velNE_filt.norm();
|
||||
_gps_check_fail_status.flags.hspeed = (_gps_filtered_horizontal_velocity_m_s > _params.req_hdrift);
|
||||
@@ -229,12 +220,12 @@ bool Ekf::gps_is_good(const gpsMessage &gps)
|
||||
}
|
||||
|
||||
// save GPS fix for next time
|
||||
_gps_pos_prev.initReference(lat, lon, _time_last_imu);
|
||||
_gps_alt_prev = 1e-3f * (float)gps.alt;
|
||||
_gps_pos_prev.initReference(gps.lat, gps.lon, _time_last_imu);
|
||||
_gps_alt_prev = gps.alt;
|
||||
|
||||
// Check the filtered difference between GPS and EKF vertical velocity
|
||||
const float vz_diff_limit = 10.0f * _params.req_vdrift;
|
||||
const float vertVel = math::constrain(gps.vel_ned(2) - _state.vel(2), -vz_diff_limit, vz_diff_limit);
|
||||
const float vz_diff_limit = 10.f * _params.req_vdrift;
|
||||
const float vertVel = math::constrain(gps.vel(2) - _state.vel(2), -vz_diff_limit, vz_diff_limit);
|
||||
_gps_velD_diff_filt = vertVel * filter_coef + _gps_velD_diff_filt * (1.0f - filter_coef);
|
||||
_gps_check_fail_status.flags.vspeed = (fabsf(_gps_velD_diff_filt) > _params.req_vdrift);
|
||||
|
||||
|
||||
@@ -48,18 +48,59 @@ void Ekf::controlGpsFusion()
|
||||
|
||||
// Check for new GPS data that has fallen behind the fusion time horizon
|
||||
if (_gps_data_ready) {
|
||||
const gpsSample gps_sample{_gps_sample_delayed};
|
||||
|
||||
// reset flags
|
||||
resetEstimatorAidStatusFlags(_aid_src_gnss_vel);
|
||||
resetEstimatorAidStatusFlags(_aid_src_gnss_pos);
|
||||
|
||||
updateGpsVel(_gps_sample_delayed);
|
||||
updateGpsPos(_gps_sample_delayed);
|
||||
|
||||
// correct velocity for offset relative to IMU
|
||||
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
|
||||
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
|
||||
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
|
||||
|
||||
// correct position and height for offset relative to IMU
|
||||
const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
|
||||
|
||||
const Vector3f gnss_velocity = gps_sample.vel - vel_offset_earth;
|
||||
|
||||
Vector3f gnss_position;
|
||||
gnss_position.xy() = _pos_ref.project(gps_sample.lat, gps_sample.lon) - pos_offset_earth.xy();
|
||||
|
||||
// GPS height: update offset
|
||||
if (!_control_status.flags.gps_hgt) {
|
||||
// calculate a filtered offset between the GNSS origin and local NED origin if we are not
|
||||
// using the GNSS as a height reference
|
||||
if (_delta_time_gnss_us != 0) {
|
||||
const float local_time_step = math::constrain(1e-6f * _delta_time_gnss_us, 0.0f, 1.0f);
|
||||
|
||||
// apply a 10 second first order low pass filter to offset
|
||||
const float hgt_offset = gps_sample.alt + pos_offset_earth(2) - getEkfGlobalOriginAltitude() + _state.pos(2);
|
||||
|
||||
const float offset_rate_correction = 0.1f * (hgt_offset + _state.pos(2) - _gps_hgt_offset);
|
||||
_gps_hgt_offset += local_time_step * math::constrain(offset_rate_correction, -0.1f, 0.1f);
|
||||
}
|
||||
}
|
||||
|
||||
// vertical position - gps measurement has opposite sign to earth z axis
|
||||
gnss_position(2) = -((gps_sample.alt + pos_offset_earth(2)) - getEkfGlobalOriginAltitude() - _gps_hgt_offset);
|
||||
|
||||
updateGpsVel(gps_sample.time_us, gnss_velocity, gps_sample.sacc);
|
||||
updateGpsPos(gps_sample.time_us, gnss_position, gps_sample.hacc, gps_sample.vacc);
|
||||
|
||||
const bool gps_checks_passing = isTimedOut(_last_gps_fail_us, (uint64_t)5e6);
|
||||
const bool gps_checks_failing = isTimedOut(_last_gps_pass_us, (uint64_t)5e6);
|
||||
|
||||
controlGpsYawFusion(gps_checks_passing, gps_checks_failing);
|
||||
|
||||
// Yaw EKFGSF update
|
||||
if (gps_checks_passing && !gps_checks_failing) {
|
||||
_yawEstimator.setVelocity(gnss_velocity.xy(), gps_sample.vacc);
|
||||
}
|
||||
|
||||
// GPS yaw
|
||||
controlGpsYawFusion(gps_sample, gps_checks_passing, gps_checks_failing);
|
||||
|
||||
|
||||
// Determine if we should use GPS aiding for velocity and horizontal position
|
||||
// To start using GPS we need angular alignment completed, the local NED origin set and GPS data that has not failed checks recently
|
||||
@@ -79,7 +120,7 @@ void Ekf::controlGpsFusion()
|
||||
fuseGpsPos();
|
||||
|
||||
if (shouldResetGpsFusion()) {
|
||||
const bool was_gps_signal_lost = isTimedOut(_time_prev_gps_us, 1000000);
|
||||
const bool was_gps_signal_lost = isTimedOut(_time_prev_gps_us, 1'000'000);
|
||||
|
||||
/* A reset is not performed when getting GPS back after a significant period of no data
|
||||
* because the timeout could have been caused by bad GPS.
|
||||
@@ -89,7 +130,7 @@ void Ekf::controlGpsFusion()
|
||||
&& _control_status.flags.in_air
|
||||
&& !was_gps_signal_lost
|
||||
&& _ekfgsf_yaw_reset_count < _params.EKFGSF_reset_count_limit
|
||||
&& isTimedOut(_ekfgsf_yaw_reset_time, 5000000)) {
|
||||
&& isTimedOut(_ekfgsf_yaw_reset_time, 5'000'000)) {
|
||||
// The minimum time interval between resets to the EKF-GSF estimate is limited to allow the EKF-GSF time
|
||||
// to improve its estimate if the previous reset was not successful.
|
||||
if (resetYawToEKFGSF()) {
|
||||
@@ -107,8 +148,15 @@ void Ekf::controlGpsFusion()
|
||||
ECL_WARN("GPS fusion timeout - resetting");
|
||||
}
|
||||
|
||||
resetVelocityToGps(_gps_sample_delayed);
|
||||
resetHorizontalPositionToGps(_gps_sample_delayed);
|
||||
ECL_INFO("reset velocity & position to GNSS");
|
||||
_information_events.flags.reset_vel_to_gps = true;
|
||||
_information_events.flags.reset_pos_to_gps = true;
|
||||
|
||||
resetVelocityTo(gnss_velocity);
|
||||
resetHorizontalPositionTo(gnss_position.xy());
|
||||
|
||||
P.uncorrelateCovarianceSetVariance<3>(4, sq(gps_sample.sacc));
|
||||
P.uncorrelateCovarianceSetVariance<2>(7, sq(gps_sample.hacc));
|
||||
}
|
||||
|
||||
} else {
|
||||
@@ -142,7 +190,26 @@ void Ekf::controlGpsFusion()
|
||||
_inhibit_ev_yaw_use = true;
|
||||
|
||||
} else {
|
||||
startGpsFusion();
|
||||
|
||||
if (!_control_status.flags.gps) {
|
||||
_information_events.flags.starting_gps_fusion = true;
|
||||
ECL_INFO("starting GPS fusion");
|
||||
|
||||
_information_events.flags.reset_pos_to_gps = true;
|
||||
resetHorizontalPositionTo(gnss_position.xy());
|
||||
P.uncorrelateCovarianceSetVariance<2>(7, sq(gps_sample.hacc));
|
||||
|
||||
// when already using another velocity source velocity reset is not necessary
|
||||
if (!_control_status.flags.opt_flow && !_control_status.flags.ev_vel) {
|
||||
// resetVelocityToGps
|
||||
ECL_INFO("reset velocity to GPS");
|
||||
_information_events.flags.reset_vel_to_gps = true;
|
||||
resetVelocityTo(gnss_velocity);
|
||||
P.uncorrelateCovarianceSetVariance<3>(4, sq(gps_sample.sacc));
|
||||
}
|
||||
|
||||
_control_status.flags.gps = true;
|
||||
}
|
||||
}
|
||||
|
||||
} else if (gps_checks_passing && !_control_status.flags.yaw_align && (_params.mag_fusion_type == MagFuseType::NONE)) {
|
||||
@@ -150,18 +217,24 @@ void Ekf::controlGpsFusion()
|
||||
if (resetYawToEKFGSF()) {
|
||||
_information_events.flags.yaw_aligned_to_imu_gps = true;
|
||||
ECL_INFO("Yaw aligned using IMU and GPS");
|
||||
resetVelocityToGps(_gps_sample_delayed);
|
||||
resetHorizontalPositionToGps(_gps_sample_delayed);
|
||||
|
||||
_information_events.flags.reset_vel_to_gps = true;
|
||||
_information_events.flags.reset_pos_to_gps = true;
|
||||
|
||||
resetVelocityTo(gnss_velocity);
|
||||
resetHorizontalPositionTo(gnss_position.xy());
|
||||
P.uncorrelateCovarianceSetVariance<3>(4, sq(gps_sample.sacc));
|
||||
P.uncorrelateCovarianceSetVariance<2>(7, sq(gps_sample.hacc));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
} else if (_control_status.flags.gps && (_imu_sample_delayed.time_us - _gps_sample_delayed.time_us > (uint64_t)10e6)) {
|
||||
} else if (_control_status.flags.gps && (_imu_sample_delayed.time_us - _time_prev_gps_us > (uint64_t)10e6)) {
|
||||
stopGpsFusion();
|
||||
_warning_events.flags.gps_data_stopped = true;
|
||||
ECL_WARN("GPS data stopped");
|
||||
|
||||
} else if (_control_status.flags.gps && (_imu_sample_delayed.time_us - _gps_sample_delayed.time_us > (uint64_t)1e6)
|
||||
} else if (_control_status.flags.gps && (_imu_sample_delayed.time_us - _time_prev_gps_us > (uint64_t)1e6)
|
||||
&& isOtherSourceOfHorizontalAidingThan(_control_status.flags.gps)) {
|
||||
// Handle the case where we are fusing another position source along GPS,
|
||||
// stop waiting for GPS after 1 s of lost signal
|
||||
|
||||
@@ -39,9 +39,9 @@
|
||||
/* #include <mathlib/mathlib.h> */
|
||||
#include "ekf.h"
|
||||
|
||||
void Ekf::updateGpsVel(const gpsSample &gps_sample)
|
||||
void Ekf::updateGpsVel(const uint64_t& time_us, const Vector3f vel, float sacc)
|
||||
{
|
||||
const float vel_var = sq(gps_sample.sacc);
|
||||
const float vel_var = sq(sacc);
|
||||
const Vector3f obs_var{vel_var, vel_var, vel_var * sq(1.5f)};
|
||||
|
||||
// innovation gate size
|
||||
@@ -50,10 +50,10 @@ void Ekf::updateGpsVel(const gpsSample &gps_sample)
|
||||
auto &gps_vel = _aid_src_gnss_vel;
|
||||
|
||||
for (int i = 0; i < 3; i++) {
|
||||
gps_vel.observation[i] = gps_sample.vel(i);
|
||||
gps_vel.observation[i] = vel(i);
|
||||
gps_vel.observation_variance[i] = obs_var(i);
|
||||
|
||||
gps_vel.innovation[i] = _state.vel(i) - gps_sample.vel(i);
|
||||
gps_vel.innovation[i] = _state.vel(i) - vel(i);
|
||||
gps_vel.innovation_variance[i] = P(4 + i, 4 + i) + obs_var(i);
|
||||
}
|
||||
|
||||
@@ -67,18 +67,11 @@ void Ekf::updateGpsVel(const gpsSample &gps_sample)
|
||||
gps_vel.innovation_rejected[2] = false;
|
||||
}
|
||||
|
||||
gps_vel.timestamp_sample = gps_sample.time_us;
|
||||
gps_vel.timestamp_sample = time_us;
|
||||
}
|
||||
|
||||
void Ekf::updateGpsPos(const gpsSample &gps_sample)
|
||||
void Ekf::updateGpsPos(const uint64_t& time_us, const Vector3f& position, float hacc, float vacc)
|
||||
{
|
||||
Vector3f position;
|
||||
position(0) = gps_sample.pos(0);
|
||||
position(1) = gps_sample.pos(1);
|
||||
|
||||
// vertical position - gps measurement has opposite sign to earth z axis
|
||||
position(2) = -(gps_sample.hgt - getEkfGlobalOriginAltitude() - _gps_hgt_offset);
|
||||
|
||||
const float lower_limit = fmaxf(_params.gps_pos_noise, 0.01f);
|
||||
|
||||
Vector3f obs_var;
|
||||
@@ -86,16 +79,16 @@ void Ekf::updateGpsPos(const gpsSample &gps_sample)
|
||||
if (isOtherSourceOfHorizontalAidingThan(_control_status.flags.gps)) {
|
||||
// if we are using other sources of aiding, then relax the upper observation
|
||||
// noise limit which prevents bad GPS perturbing the position estimate
|
||||
obs_var(0) = obs_var(1) = sq(fmaxf(gps_sample.hacc, lower_limit));
|
||||
obs_var(0) = obs_var(1) = sq(fmaxf(hacc, lower_limit));
|
||||
|
||||
} else {
|
||||
// if we are not using another source of aiding, then we are reliant on the GPS
|
||||
// observations to constrain attitude errors and must limit the observation noise value.
|
||||
float upper_limit = fmaxf(_params.pos_noaid_noise, lower_limit);
|
||||
obs_var(0) = obs_var(1) = sq(math::constrain(gps_sample.hacc, lower_limit, upper_limit));
|
||||
obs_var(0) = obs_var(1) = sq(math::constrain(hacc, lower_limit, upper_limit));
|
||||
}
|
||||
|
||||
obs_var(2) = getGpsHeightVariance();
|
||||
obs_var(2) = getGpsHeightVariance(vacc);
|
||||
|
||||
// innovation gate size
|
||||
float innov_gate = fmaxf(_params.gps_pos_innov_gate, 1.f);
|
||||
@@ -120,7 +113,7 @@ void Ekf::updateGpsPos(const gpsSample &gps_sample)
|
||||
gps_pos.innovation_rejected[2] = false;
|
||||
}
|
||||
|
||||
gps_pos.timestamp_sample = gps_sample.time_us;
|
||||
gps_pos.timestamp_sample = time_us;
|
||||
}
|
||||
|
||||
void Ekf::fuseGpsVel()
|
||||
|
||||
@@ -45,7 +45,7 @@
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <cstdlib>
|
||||
|
||||
void Ekf::fuseGpsYaw()
|
||||
void Ekf::fuseGpsYaw(const gpsSample &gps_sample)
|
||||
{
|
||||
// assign intermediate state variables
|
||||
const float q0 = _state.quat_nominal(0);
|
||||
@@ -54,10 +54,10 @@ void Ekf::fuseGpsYaw()
|
||||
const float q3 = _state.quat_nominal(3);
|
||||
|
||||
// calculate the observed yaw angle of antenna array, converting a from body to antenna yaw measurement
|
||||
const float measured_hdg = wrap_pi(_gps_sample_delayed.yaw + _gps_yaw_offset);
|
||||
const float measured_hdg = wrap_pi(gps_sample.yaw + gps_sample.yaw_offset);
|
||||
|
||||
// define the predicted antenna array vector and rotate into earth frame
|
||||
const Vector3f ant_vec_bf = {cosf(_gps_yaw_offset), sinf(_gps_yaw_offset), 0.0f};
|
||||
const Vector3f ant_vec_bf = {cosf(gps_sample.yaw_offset), sinf(gps_sample.yaw_offset), 0.f};
|
||||
const Vector3f ant_vec_ef = _R_to_earth * ant_vec_bf;
|
||||
|
||||
// check if antenna array vector is within 30 degrees of vertical and therefore unable to provide a reliable heading
|
||||
@@ -73,11 +73,11 @@ void Ekf::fuseGpsYaw()
|
||||
const float R_YAW = sq(fmaxf(_params.gps_heading_noise, 1.0e-2f));
|
||||
|
||||
// calculate intermediate variables
|
||||
const float HK0 = sinf(_gps_yaw_offset);
|
||||
const float HK0 = sinf(gps_sample.yaw_offset);
|
||||
const float HK1 = q0*q3;
|
||||
const float HK2 = q1*q2;
|
||||
const float HK3 = 2*HK0*(HK1 - HK2);
|
||||
const float HK4 = cosf(_gps_yaw_offset);
|
||||
const float HK4 = cosf(gps_sample.yaw_offset);
|
||||
const float HK5 = ecl::powf(q1, 2);
|
||||
const float HK6 = ecl::powf(q2, 2);
|
||||
const float HK7 = ecl::powf(q0, 2) - ecl::powf(q3, 2);
|
||||
@@ -195,10 +195,10 @@ void Ekf::fuseGpsYaw()
|
||||
}
|
||||
}
|
||||
|
||||
bool Ekf::resetYawToGps()
|
||||
bool Ekf::resetYawToGps(const gpsSample& gps_sample)
|
||||
{
|
||||
// define the predicted antenna array vector and rotate into earth frame
|
||||
const Vector3f ant_vec_bf = {cosf(_gps_yaw_offset), sinf(_gps_yaw_offset), 0.0f};
|
||||
const Vector3f ant_vec_bf = {cosf(gps_sample.yaw_offset), sinf(gps_sample.yaw_offset), 0.0f};
|
||||
const Vector3f ant_vec_ef = _R_to_earth * ant_vec_bf;
|
||||
|
||||
// check if antenna array vector is within 30 degrees of vertical and therefore unable to provide a reliable heading
|
||||
@@ -207,7 +207,7 @@ bool Ekf::resetYawToGps()
|
||||
}
|
||||
|
||||
// GPS yaw measurement is alreday compensated for antenna offset in the driver
|
||||
const float measured_yaw = _gps_sample_delayed.yaw;
|
||||
const float measured_yaw = gps_sample.yaw;
|
||||
|
||||
const float yaw_variance = sq(fmaxf(_params.gps_heading_noise, 1.0e-2f));
|
||||
resetQuatStateYaw(measured_yaw, yaw_variance, true);
|
||||
|
||||
+26
-22
@@ -1457,13 +1457,13 @@ float EKF2::filter_altitude_ellipsoid(float amsl_hgt)
|
||||
if (_gps_alttitude_ellipsoid_previous_timestamp == 0) {
|
||||
|
||||
_wgs84_hgt_offset = height_diff;
|
||||
_gps_alttitude_ellipsoid_previous_timestamp = _gps_time_usec;
|
||||
_gps_alttitude_ellipsoid_previous_timestamp = _gps_time_us;
|
||||
|
||||
} else if (_gps_time_usec != _gps_alttitude_ellipsoid_previous_timestamp) {
|
||||
} else if (_gps_time_us != _gps_alttitude_ellipsoid_previous_timestamp) {
|
||||
|
||||
// apply a 10 second first order low pass filter to baro offset
|
||||
float dt = 1e-6f * (_gps_time_usec - _gps_alttitude_ellipsoid_previous_timestamp);
|
||||
_gps_alttitude_ellipsoid_previous_timestamp = _gps_time_usec;
|
||||
float dt = 1e-6f * (_gps_time_us - _gps_alttitude_ellipsoid_previous_timestamp);
|
||||
_gps_alttitude_ellipsoid_previous_timestamp = _gps_time_us;
|
||||
float offset_rate_correction = 0.1f * (height_diff - _wgs84_hgt_offset);
|
||||
_wgs84_hgt_offset += dt * constrain(offset_rate_correction, -0.1f, 0.1f);
|
||||
}
|
||||
@@ -1792,31 +1792,35 @@ void EKF2::UpdateGpsSample(ekf2_timestamps_s &ekf2_timestamps)
|
||||
perf_count(_msg_missed_gps_perf);
|
||||
}
|
||||
|
||||
gpsMessage gps_msg{
|
||||
.time_usec = vehicle_gps_position.timestamp,
|
||||
.lat = vehicle_gps_position.lat,
|
||||
.lon = vehicle_gps_position.lon,
|
||||
.alt = vehicle_gps_position.alt,
|
||||
.yaw = vehicle_gps_position.heading,
|
||||
.yaw_offset = vehicle_gps_position.heading_offset,
|
||||
.fix_type = vehicle_gps_position.fix_type,
|
||||
.eph = vehicle_gps_position.eph,
|
||||
.epv = vehicle_gps_position.epv,
|
||||
.sacc = vehicle_gps_position.s_variance_m_s,
|
||||
.vel_m_s = vehicle_gps_position.vel_m_s,
|
||||
.vel_ned = Vector3f{
|
||||
gpsSample gps_sample{
|
||||
.time_us = vehicle_gps_position.timestamp,
|
||||
.lat = vehicle_gps_position.lat * 1.e-7,
|
||||
.lon = vehicle_gps_position.lon * 1.e-7,
|
||||
.alt = vehicle_gps_position.alt * 1e-3f,
|
||||
|
||||
.vel = Vector3f{
|
||||
vehicle_gps_position.vel_n_m_s,
|
||||
vehicle_gps_position.vel_e_m_s,
|
||||
vehicle_gps_position.vel_d_m_s
|
||||
},
|
||||
.vel_ned_valid = vehicle_gps_position.vel_ned_valid,
|
||||
.nsats = vehicle_gps_position.satellites_used,
|
||||
|
||||
.hacc = vehicle_gps_position.eph,
|
||||
.vacc = vehicle_gps_position.epv,
|
||||
.sacc = vehicle_gps_position.s_variance_m_s,
|
||||
|
||||
.yaw = vehicle_gps_position.heading,
|
||||
.yaw_accuracy = vehicle_gps_position.heading_accuracy,
|
||||
.yaw_offset = vehicle_gps_position.heading_offset,
|
||||
|
||||
.pdop = sqrtf(vehicle_gps_position.hdop *vehicle_gps_position.hdop
|
||||
+ vehicle_gps_position.vdop * vehicle_gps_position.vdop),
|
||||
};
|
||||
_ekf.setGpsData(gps_msg);
|
||||
|
||||
_gps_time_usec = gps_msg.time_usec;
|
||||
.fix_type = vehicle_gps_position.fix_type,
|
||||
.nsats = vehicle_gps_position.satellites_used,
|
||||
};
|
||||
_ekf.setGpsData(gps_sample);
|
||||
|
||||
_gps_time_us = vehicle_gps_position.timestamp;
|
||||
_gps_alttitude_ellipsoid = vehicle_gps_position.alt_ellipsoid;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -228,7 +228,7 @@ private:
|
||||
InFlightCalibration _gyro_cal{};
|
||||
InFlightCalibration _mag_cal{};
|
||||
|
||||
uint64_t _gps_time_usec{0};
|
||||
uint64_t _gps_time_us{0};
|
||||
int32_t _gps_alttitude_ellipsoid{0}; ///< altitude in 1E-3 meters (millimeters) above ellipsoid
|
||||
uint64_t _gps_alttitude_ellipsoid_previous_timestamp{0}; ///< storage for previous timestamp to compute dt
|
||||
float _wgs84_hgt_offset = 0; ///< height offset between AMSL and WGS84
|
||||
|
||||
@@ -1,391 +1,391 @@
|
||||
Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
|
||||
10000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
|
||||
90000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
|
||||
190000,1,-0.0105,-0.0107,-0.0167,-0.000387,-0.000237,-0.00902,-2.26e-05,-1e-05,-0.000287,0,0,0,0,0,0,0.192,0.00189,0.404,0,0,0,0,0,1.5e-06,0.00251,0.00251,0.00338,25,25,0.563,100,100,0.8,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
290000,1,-0.0106,-0.011,-0.0167,0.0006,0.000288,-0.0229,-2.94e-05,-3.64e-05,-0.00185,0,0,0,0,0,0,0.192,0.00189,0.404,0,0,0,0,0,1.21e-06,0.00256,0.00256,0.00222,25,25,0.562,101,101,0.337,1e-06,1e-06,9.97e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
390000,1,-0.0106,-0.0113,-0.0167,0.00209,0.000238,-0.0375,6.41e-05,2.46e-05,-0.00489,-1.63e-13,-6.23e-13,-3.16e-15,3.41e-12,-8.91e-13,-9.32e-14,0.192,0.00189,0.404,0,0,0,0,0,1.1e-06,0.00267,0.00267,0.00169,24.8,24.8,0.557,0.29,0.29,0.209,1e-06,1e-06,9.88e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
490000,1,-0.0107,-0.0117,-0.0167,0.00463,-0.000559,-0.0529,0.000405,-6.64e-06,-0.00941,-1.63e-13,-6.23e-13,-3.16e-15,3.41e-12,-8.91e-13,-9.32e-14,0.192,0.00189,0.404,0,0,0,0,0,1.08e-06,0.00282,0.00282,0.00141,24.9,24.9,0.544,0.739,0.739,0.159,1e-06,1e-06,9.73e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
590000,1,-0.0107,-0.012,-0.0167,0.00418,7.22e-05,-0.0661,0.000239,-5.36e-06,-0.0153,-2.19e-11,-5.29e-09,-4.94e-11,1.28e-08,-5.1e-11,-2.89e-10,0.192,0.00189,0.404,0,0,0,0,0,1.11e-06,0.00302,0.00302,0.00125,7.8,7.8,0.527,0.267,0.267,0.141,1e-06,1e-06,9.49e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
690000,1,-0.0108,-0.0123,-0.0167,0.00685,-0.000979,-0.0813,0.000761,-7.95e-05,-0.0227,-2.19e-11,-5.29e-09,-4.94e-11,1.28e-08,-5.1e-11,-2.89e-10,0.192,0.00189,0.404,0,0,0,0,0,1.17e-06,0.00328,0.00328,0.00116,7.87,7.87,0.497,0.556,0.556,0.13,1e-06,1e-06,9.16e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
790000,1,-0.0109,-0.0126,-0.0166,0.00622,-0.000504,-0.0959,0.000417,-4.86e-05,-0.0315,-2.56e-09,-3.32e-08,-2.74e-10,4.83e-08,-3.26e-09,-1.19e-09,0.192,0.00189,0.404,0,0,0,0,0,1.27e-06,0.00356,0.00356,0.00111,2.63,2.63,0.465,0.218,0.218,0.129,9.99e-07,9.99e-07,8.75e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
890000,1,-0.011,-0.0128,-0.0166,0.0107,-0.00161,-0.11,0.00125,-0.00019,-0.0418,-2.56e-09,-3.32e-08,-2.74e-10,4.83e-08,-3.26e-09,-1.19e-09,0.192,0.00189,0.404,0,0,0,0,0,1.39e-06,0.00392,0.00392,0.00109,2.72,2.72,0.471,0.363,0.363,0.164,9.99e-07,9.99e-07,8.27e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
990000,1,-0.0111,-0.0131,-0.0166,0.0117,-0.00274,-0.125,0.00087,-0.000149,-0.0536,-1.95e-08,-1.66e-07,-1.12e-09,1.58e-07,-1.72e-08,-4.19e-09,0.192,0.00189,0.404,0,0,0,0,0,1.53e-06,0.00427,0.00427,0.00108,1.25,1.25,0.477,0.178,0.178,0.209,9.97e-07,9.97e-07,7.73e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1090000,1,-0.0112,-0.0134,-0.0166,0.0161,-0.00421,-0.141,0.00225,-0.000505,-0.0669,-1.95e-08,-1.66e-07,-1.12e-09,1.58e-07,-1.72e-08,-4.19e-09,0.192,0.00189,0.404,0,0,0,0,0,1.7e-06,0.00472,0.00472,0.00108,1.38,1.38,0.484,0.265,0.265,0.263,9.97e-07,9.97e-07,7.15e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1190000,1,-0.0112,-0.0137,-0.0166,0.0163,-0.0049,-0.155,0.00161,-0.000401,-0.0818,-1.25e-07,-6.6e-07,-2.4e-09,4.68e-07,-8.34e-08,-1.35e-08,0.192,0.00189,0.404,0,0,0,0,0,1.85e-06,0.00506,0.00506,0.00108,0.85,0.85,0.491,0.151,0.151,0.328,9.88e-07,9.88e-07,6.56e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1290000,1,-0.0113,-0.0139,-0.0166,0.0212,-0.00611,-0.169,0.00349,-0.000977,-0.098,-1.25e-07,-6.6e-07,-2.4e-09,4.68e-07,-8.34e-08,-1.35e-08,0.192,0.00189,0.404,0,0,0,0,0,2.06e-06,0.0056,0.0056,0.00108,1.03,1.03,0.5,0.214,0.214,0.402,9.88e-07,9.88e-07,5.97e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1390000,1,-0.0114,-0.0142,-0.0166,0.0275,-0.00825,-0.181,0.00597,-0.00168,-0.115,-1.25e-07,-6.6e-07,-2.4e-09,4.68e-07,-8.34e-08,-1.35e-08,0.192,0.00189,0.404,0,0,0,0,0,2.31e-06,0.00618,0.00619,0.00108,1.26,1.26,0.509,0.301,0.301,0.487,9.88e-07,9.88e-07,5.41e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1490000,1,-0.0114,-0.0143,-0.0166,0.0277,-0.00795,-0.196,0.00506,-0.00142,-0.134,-4.58e-07,-2.01e-06,-2.38e-09,1.16e-06,-2.53e-07,-3.54e-08,0.192,0.00189,0.404,0,0,0,0,0,2.42e-06,0.00637,0.00637,0.00108,1.01,1.01,0.519,0.189,0.189,0.582,9.62e-07,9.62e-07,4.87e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1590000,1,-0.0114,-0.0146,-0.0166,0.0346,-0.00911,-0.209,0.00815,-0.00227,-0.155,-4.58e-07,-2.01e-06,-2.38e-09,1.16e-06,-2.53e-07,-3.54e-08,0.192,0.00189,0.404,0,0,0,0,0,2.7e-06,0.00702,0.00702,0.00107,1.3,1.3,0.53,0.268,0.268,0.689,9.62e-07,9.62e-07,4.38e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1690000,1,-0.0115,-0.0145,-0.0166,0.0339,-0.0104,-0.221,0.00659,-0.00188,-0.176,-1.15e-06,-4.89e-06,2.07e-09,2.38e-06,-5.49e-07,-7.51e-08,0.192,0.00189,0.404,0,0,0,0,0,2.66e-06,0.00677,0.00677,0.00105,1.11,1.11,0.542,0.179,0.179,0.807,9.06e-07,9.06e-07,3.92e-07,3.98e-06,3.98e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1790000,1,-0.0115,-0.0148,-0.0167,0.0422,-0.0137,-0.236,0.0104,-0.00306,-0.199,-1.15e-06,-4.89e-06,2.07e-09,2.38e-06,-5.49e-07,-7.51e-08,0.192,0.00189,0.404,0,0,0,0,0,2.96e-06,0.00744,0.00744,0.00104,1.45,1.45,0.554,0.262,0.262,0.936,9.06e-07,9.06e-07,3.51e-07,3.98e-06,3.98e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1890000,1,-0.0113,-0.0144,-0.0167,0.0382,-0.0124,-0.25,0.00784,-0.00241,-0.223,-2.41e-06,-9.67e-06,1.8e-08,4.1e-06,-9.99e-07,-1.33e-07,0.192,0.00189,0.404,0,0,0,0,0,2.68e-06,0.00658,0.00658,0.00102,1.19,1.19,0.567,0.178,0.178,1.08,8.16e-07,8.16e-07,3.14e-07,3.97e-06,3.97e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1990000,1,-0.0114,-0.0146,-0.0167,0.0456,-0.0145,-0.264,0.012,-0.00377,-0.249,-2.41e-06,-9.67e-06,1.8e-08,4.1e-06,-9.99e-07,-1.33e-07,0.192,0.00189,0.404,0,0,0,0,0,2.94e-06,0.00722,0.00722,0.000997,1.54,1.54,0.582,0.266,0.266,1.23,8.16e-07,8.16e-07,2.82e-07,3.97e-06,3.97e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2090000,1,-0.0111,-0.014,-0.0167,0.0361,-0.0127,-0.278,0.00825,-0.00265,-0.276,-4.15e-06,-1.59e-05,4.6e-08,5.94e-06,-1.51e-06,-1.98e-07,0.192,0.00189,0.404,0,0,0,0,0,2.46e-06,0.00588,0.00588,0.000975,1.18,1.18,0.596,0.177,0.177,1.4,7.04e-07,7.05e-07,2.52e-07,3.96e-06,3.96e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2190000,1,-0.0112,-0.0142,-0.0167,0.0433,-0.014,-0.293,0.0122,-0.00399,-0.305,-4.15e-06,-1.59e-05,4.6e-08,5.94e-06,-1.51e-06,-1.98e-07,0.192,0.00189,0.404,0,0,0,0,0,2.7e-06,0.00645,0.00645,0.000953,1.52,1.52,0.612,0.267,0.267,1.58,7.04e-07,7.05e-07,2.27e-07,3.96e-06,3.96e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2290000,1,-0.0111,-0.0135,-0.0168,0.0335,-0.0112,-0.308,0.00784,-0.00256,-0.335,-6.01e-06,-2.24e-05,7.89e-08,7.42e-06,-1.94e-06,-2.51e-07,0.192,0.00189,0.404,0,0,0,0,0,2.15e-06,0.00497,0.00497,0.000929,1.09,1.09,0.628,0.173,0.173,1.77,5.92e-07,5.92e-07,2.04e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2390000,1,-0.0111,-0.0136,-0.0168,0.0391,-0.0129,-0.321,0.0115,-0.0038,-0.366,-6.01e-06,-2.24e-05,7.89e-08,7.42e-06,-1.94e-06,-2.51e-07,0.192,0.00189,0.404,0,0,0,0,0,2.33e-06,0.00545,0.00545,0.000906,1.39,1.39,0.646,0.259,0.259,1.98,5.92e-07,5.92e-07,1.84e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2490000,1,-0.0109,-0.013,-0.0168,0.0285,-0.00963,-0.333,0.00712,-0.00235,-0.399,-7.7e-06,-2.82e-05,1.1e-07,8.34e-06,-2.21e-06,-2.86e-07,0.192,0.00189,0.404,0,0,0,0,0,1.81e-06,0.00411,0.00411,0.000882,0.964,0.964,0.664,0.166,0.166,2.2,4.94e-07,4.95e-07,1.66e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2590000,1,-0.011,-0.0132,-0.0168,0.0331,-0.0104,-0.347,0.0102,-0.00334,-0.433,-7.7e-06,-2.82e-05,1.1e-07,8.34e-06,-2.21e-06,-2.86e-07,0.192,0.00189,0.404,0,0,0,0,0,1.96e-06,0.00452,0.00452,0.00086,1.22,1.22,0.683,0.245,0.245,2.44,4.94e-07,4.95e-07,1.5e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2690000,1,-0.0108,-0.0127,-0.0168,0.0239,-0.00709,-0.36,0.00624,-0.00202,-0.468,-9.09e-06,-3.3e-05,1.35e-07,8.72e-06,-2.32e-06,-3e-07,0.192,0.00189,0.404,0,0,0,0,0,1.53e-06,0.00342,0.00342,0.000837,0.838,0.838,0.702,0.157,0.157,2.7,4.14e-07,4.14e-07,1.36e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2790000,1,-0.0108,-0.0129,-0.0168,0.0276,-0.00845,-0.372,0.00882,-0.00281,-0.505,-9.09e-06,-3.3e-05,1.35e-07,8.72e-06,-2.32e-06,-3e-07,0.192,0.00189,0.404,0,0,0,0,0,1.66e-06,0.00376,0.00377,0.000815,1.05,1.05,0.723,0.228,0.228,2.97,4.14e-07,4.14e-07,1.23e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2890000,1,-0.0107,-0.0125,-0.0169,0.0203,-0.00614,-0.384,0.00542,-0.00169,-0.543,-1.02e-05,-3.68e-05,1.54e-07,8.7e-06,-2.31e-06,-2.99e-07,0.192,0.00189,0.404,0,0,0,0,0,1.31e-06,0.0029,0.0029,0.000794,0.728,0.729,0.744,0.148,0.148,3.25,3.49e-07,3.49e-07,1.12e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2990000,1,-0.0107,-0.0126,-0.0168,0.0243,-0.00696,-0.398,0.00766,-0.00236,-0.582,-1.02e-05,-3.68e-05,1.54e-07,8.7e-06,-2.31e-06,-2.99e-07,0.192,0.00189,0.404,0,0,0,0,0,1.41e-06,0.0032,0.0032,0.000774,0.907,0.908,0.766,0.212,0.212,3.56,3.49e-07,3.49e-07,1.02e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3090000,1,-0.0106,-0.0123,-0.0168,0.0178,-0.00473,-0.41,0.00479,-0.00144,-0.623,-1.1e-05,-4e-05,1.68e-07,8.4e-06,-2.23e-06,-2.88e-07,0.192,0.00189,0.404,0,0,0,0,0,1.13e-06,0.00252,0.00252,0.000754,0.64,0.64,0.789,0.139,0.139,3.88,2.96e-07,2.96e-07,9.36e-08,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3190000,1,-0.0107,-0.0124,-0.0169,0.0208,-0.00484,-0.425,0.00668,-0.00194,-0.664,-1.1e-05,-4e-05,1.68e-07,8.4e-06,-2.23e-06,-2.88e-07,0.192,0.00189,0.404,0,0,0,0,0,1.21e-06,0.00277,0.00277,0.000735,0.795,0.795,0.812,0.196,0.196,4.23,2.96e-07,2.96e-07,8.58e-08,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3290000,1,-0.0106,-0.0121,-0.0169,0.0163,-0.00373,-0.437,0.00424,-0.00117,-0.708,-1.16e-05,-4.26e-05,1.78e-07,7.92e-06,-2.12e-06,-2.69e-07,0.192,0.00189,0.404,0,0,0,0,0,9.91e-07,0.00222,0.00223,0.000716,0.57,0.57,0.837,0.131,0.131,4.59,2.51e-07,2.51e-07,7.87e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3390000,1,-0.0106,-0.0122,-0.0169,0.0184,-0.00451,-0.451,0.006,-0.00157,-0.752,-1.16e-05,-4.26e-05,1.78e-07,7.92e-06,-2.12e-06,-2.69e-07,0.192,0.00189,0.404,0,0,0,0,0,1.06e-06,0.00245,0.00245,0.000698,0.706,0.706,0.862,0.183,0.183,4.97,2.51e-07,2.51e-07,7.24e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3490000,1,-0.0106,-0.0123,-0.0169,0.0217,-0.00613,-0.464,0.008,-0.00209,-0.798,-1.16e-05,-4.26e-05,1.78e-07,7.92e-06,-2.12e-06,-2.69e-07,0.192,0.00189,0.404,0,0,0,0,0,1.13e-06,0.00268,0.00268,0.000681,0.866,0.866,0.888,0.255,0.255,5.38,2.51e-07,2.51e-07,6.68e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3590000,1,-0.0106,-0.0121,-0.0169,0.0161,-0.00587,-0.477,0.0054,-0.00152,-0.845,-1.21e-05,-4.49e-05,1.86e-07,7.3e-06,-1.98e-06,-2.45e-07,0.192,0.00189,0.404,0,0,0,0,0,9.3e-07,0.00218,0.00218,0.000665,0.636,0.637,0.915,0.172,0.172,5.8,2.12e-07,2.12e-07,6.16e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3690000,1,-0.0106,-0.0122,-0.0168,0.0187,-0.00789,-0.491,0.00717,-0.00221,-0.893,-1.21e-05,-4.49e-05,1.86e-07,7.3e-06,-1.98e-06,-2.45e-07,0.192,0.00189,0.404,0,0,0,0,0,9.89e-07,0.00239,0.00239,0.000649,0.779,0.779,0.943,0.237,0.237,6.25,2.12e-07,2.12e-07,5.7e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3790000,1,-0.0106,-0.012,-0.0167,0.0145,-0.00824,-0.504,0.00487,-0.00176,-0.943,-1.27e-05,-4.68e-05,1.95e-07,6.6e-06,-1.78e-06,-2.17e-07,0.192,0.00189,0.404,0,0,0,0,0,8.23e-07,0.00196,0.00196,0.000634,0.58,0.58,0.971,0.162,0.162,6.72,1.79e-07,1.79e-07,5.28e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3890000,1,-0.0105,-0.012,-0.0168,0.0159,-0.00834,-0.518,0.00638,-0.00258,-0.994,-1.27e-05,-4.68e-05,1.95e-07,6.6e-06,-1.78e-06,-2.17e-07,0.192,0.00189,0.404,0,0,0,0,0,8.69e-07,0.00214,0.00214,0.00062,0.709,0.709,1,0.222,0.222,7.22,1.79e-07,1.79e-07,4.91e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3990000,1,-0.0104,-0.0118,-0.0168,0.0134,-0.00684,-0.532,0.00434,-0.00192,-1.05,-1.33e-05,-4.85e-05,2.07e-07,5.87e-06,-1.51e-06,-1.86e-07,0.192,0.00189,0.404,0,0,0,0,0,7.23e-07,0.00176,0.00176,0.000606,0.533,0.533,1.03,0.153,0.153,7.74,1.49e-07,1.49e-07,4.56e-08,3.93e-06,3.93e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4090000,1,-0.0104,-0.0118,-0.0168,0.0155,-0.00822,-0.545,0.0058,-0.00266,-1.1,-1.33e-05,-4.85e-05,2.07e-07,5.87e-06,-1.51e-06,-1.86e-07,0.192,0.00189,0.404,0,0,0,0,0,7.61e-07,0.00191,0.00191,0.000592,0.649,0.649,1.06,0.209,0.209,8.29,1.49e-07,1.49e-07,4.25e-08,3.93e-06,3.93e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4190000,1,-0.0103,-0.0116,-0.0168,0.0132,-0.0074,-0.56,0.00408,-0.00196,-1.16,-1.4e-05,-5e-05,2.2e-07,5.11e-06,-1.19e-06,-1.53e-07,0.192,0.00189,0.404,0,0,0,0,0,6.38e-07,0.00157,0.00157,0.000579,0.491,0.491,1.09,0.146,0.146,8.87,1.24e-07,1.24e-07,3.96e-08,3.93e-06,3.93e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4290000,1,-0.0103,-0.0117,-0.0169,0.0152,-0.00627,-0.573,0.00549,-0.00266,-1.21,-1.4e-05,-5e-05,2.2e-07,5.11e-06,-1.19e-06,-1.53e-07,0.192,0.00189,0.404,0,0,0,0,0,6.73e-07,0.00171,0.00171,0.000567,0.597,0.597,1.13,0.197,0.197,9.47,1.24e-07,1.24e-07,3.7e-08,3.93e-06,3.93e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4390000,1,-0.0101,-0.0115,-0.0169,0.0119,-0.00404,-0.587,0.00385,-0.00176,-1.27,-1.46e-05,-5.14e-05,2.32e-07,4.34e-06,-8.5e-07,-1.19e-07,0.192,0.00189,0.404,0,0,0,0,0,5.67e-07,0.0014,0.0014,0.000555,0.453,0.453,1.16,0.139,0.139,10.1,1.02e-07,1.02e-07,3.46e-08,3.92e-06,3.92e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4490000,1,-0.0101,-0.0116,-0.0168,0.0131,-0.0043,-0.602,0.0051,-0.00216,-1.33,-1.46e-05,-5.14e-05,2.32e-07,4.34e-06,-8.5e-07,-1.19e-07,0.192,0.00189,0.404,0,0,0,0,0,5.92e-07,0.00152,0.00152,0.000544,0.549,0.549,1.19,0.187,0.187,10.8,1.02e-07,1.02e-07,3.24e-08,3.92e-06,3.92e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4590000,1,-0.0101,-0.0114,-0.0168,0.0114,-0.00343,-0.617,0.00359,-0.00141,-1.39,-1.5e-05,-5.26e-05,2.4e-07,3.59e-06,-5.72e-07,-8.71e-08,0.192,0.00189,0.404,0,0,0,0,0,5.02e-07,0.00124,0.00124,0.000533,0.418,0.418,1.23,0.132,0.132,11.5,8.3e-08,8.31e-08,3.04e-08,3.91e-06,3.91e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4690000,1,-0.0101,-0.0114,-0.0168,0.0125,-0.00448,-0.631,0.00481,-0.00179,-1.45,-1.5e-05,-5.26e-05,2.4e-07,3.59e-06,-5.72e-07,-8.71e-08,0.192,0.00189,0.404,0,0,0,0,0,5.23e-07,0.00134,0.00134,0.000522,0.504,0.504,1.26,0.177,0.177,12.2,8.3e-08,8.31e-08,2.85e-08,3.91e-06,3.91e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4790000,1,-0.0101,-0.0112,-0.0168,0.0102,-0.00391,-0.645,0.00335,-0.00124,-1.52,-1.54e-05,-5.37e-05,2.47e-07,2.87e-06,-3.33e-07,-5.74e-08,0.192,0.00189,0.404,0,0,0,0,0,4.47e-07,0.0011,0.0011,0.000512,0.385,0.385,1.3,0.127,0.127,13,6.74e-08,6.74e-08,2.68e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4890000,1,-0.0101,-0.0113,-0.0168,0.0113,-0.00504,-0.66,0.00445,-0.00168,-1.58,-1.54e-05,-5.37e-05,2.47e-07,2.87e-06,-3.33e-07,-5.74e-08,0.192,0.00189,0.404,0,0,0,0,0,4.65e-07,0.00118,0.00118,0.000502,0.461,0.461,1.34,0.168,0.168,13.7,6.74e-08,6.74e-08,2.52e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4990000,1,-0.00999,-0.0112,-0.0168,0.01,-0.00373,-0.675,0.00313,-0.00121,-1.65,-1.57e-05,-5.46e-05,2.53e-07,2.19e-06,-9.75e-08,-2.96e-08,0.192,0.00189,0.404,0,0,0,0,0,4e-07,0.000965,0.000966,0.000492,0.353,0.353,1.37,0.121,0.121,14.6,5.44e-08,5.44e-08,2.38e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5090000,1,-0.01,-0.0112,-0.0168,0.0105,-0.00389,-0.69,0.00416,-0.00158,-1.72,-1.57e-05,-5.46e-05,2.53e-07,2.19e-06,-9.75e-08,-2.96e-08,0.192,0.00189,0.404,0,0,0,0,0,4.14e-07,0.00103,0.00103,0.000483,0.421,0.421,1.41,0.16,0.16,15.4,5.44e-08,5.44e-08,2.24e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5190000,1,-0.00997,-0.0111,-0.0168,0.00852,-0.00353,-0.703,0.00291,-0.00113,-1.79,-1.59e-05,-5.54e-05,2.58e-07,1.57e-06,1.19e-07,-4.12e-09,0.192,0.00189,0.404,0,0,0,0,0,3.58e-07,0.000848,0.000848,0.000474,0.323,0.323,1.45,0.116,0.116,16.3,4.38e-08,4.38e-08,2.12e-08,3.89e-06,3.89e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5290000,1,-0.00992,-0.0111,-0.0168,0.00778,-0.00312,-0.718,0.00373,-0.00148,-1.86,-1.59e-05,-5.54e-05,2.58e-07,1.57e-06,1.19e-07,-4.12e-09,0.192,0.00189,0.404,0,0,0,0,0,3.68e-07,0.000905,0.000905,0.000466,0.384,0.384,1.49,0.152,0.152,17.3,4.38e-08,4.38e-08,2e-08,3.89e-06,3.89e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5390000,1,-0.00981,-0.0111,-0.0167,0.00451,-0.00239,-0.732,0.00247,-0.001,-1.93,-1.62e-05,-5.6e-05,2.63e-07,1.05e-06,3.08e-07,1.7e-08,0.192,0.00189,0.404,0,0,0,0,0,3.23e-07,0.000744,0.000744,0.000457,0.295,0.295,1.53,0.111,0.111,18.3,3.52e-08,3.52e-08,1.9e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5490000,1,-0.00976,-0.0111,-0.0167,0.00459,-0.00238,-0.745,0.00293,-0.00126,-2,-1.62e-05,-5.6e-05,2.63e-07,1.05e-06,3.08e-07,1.7e-08,0.192,0.00189,0.404,0,0,0,0,0,3.3e-07,0.000792,0.000792,0.000449,0.349,0.349,1.58,0.145,0.145,19.3,3.52e-08,3.52e-08,1.8e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5590000,1,-0.00972,-0.0111,-0.0168,0.00519,-0.00237,-0.76,0.00341,-0.00148,-2.08,-1.62e-05,-5.6e-05,2.63e-07,1.05e-06,3.08e-07,1.7e-08,0.192,0.00189,0.404,0,0,0,0,0,3.38e-07,0.000841,0.000842,0.000442,0.41,0.41,1.62,0.188,0.188,20.4,3.52e-08,3.52e-08,1.7e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5690000,1,-0.00961,-0.011,-0.0167,0.00334,-0.000356,-0.775,0.00226,-0.000943,-2.16,-1.63e-05,-5.64e-05,2.66e-07,6.66e-07,4.59e-07,3.27e-08,0.192,0.00189,0.404,0,0,0,0,0,2.96e-07,0.000694,0.000694,0.000434,0.317,0.317,1.66,0.138,0.138,21.5,2.83e-08,2.83e-08,1.62e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5790000,1,-0.00954,-0.011,-0.0167,0.00364,0.00106,0,0.00258,-0.00091,-365,-1.63e-05,-5.64e-05,2.66e-07,6.66e-07,4.59e-07,3.27e-08,0.192,0.00189,0.404,0,0,0,0,0,3.02e-07,0.000735,0.000735,0.000427,0.371,0.371,10,0.178,0.178,4,2.83e-08,2.83e-08,1.53e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5890000,1,-0.00949,-0.011,-0.0167,0.00314,0.0023,0.00413,0.00175,-0.000382,-365,-1.64e-05,-5.67e-05,2.68e-07,3.88e-07,5.42e-07,8.19e-09,0.192,0.00189,0.404,0,0,0,0,0,2.7e-07,0.000609,0.000609,0.00042,0.288,0.288,9.76,0.131,0.131,0.471,2.27e-08,2.27e-08,1.46e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5990000,1,-0.00946,-0.011,-0.0167,0.0034,0.00409,0.0213,0.00206,-1.87e-05,-365,-1.64e-05,-5.67e-05,2.68e-07,3.86e-07,5.45e-07,-1.1e-07,0.192,0.00189,0.404,0,0,0,0,0,2.75e-07,0.000643,0.000643,0.000413,0.335,0.335,8.56,0.168,0.168,0.323,2.27e-08,2.27e-08,1.39e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6090000,1,-0.00942,-0.011,-0.0167,0.00324,0.0055,-0.0035,0.00146,0.00043,-365,-1.64e-05,-5.7e-05,2.67e-07,1.79e-07,5.24e-07,-2.21e-08,0.192,0.00189,0.404,0,0,0,0,0,2.47e-07,0.000536,0.000537,0.000407,0.261,0.261,6.77,0.125,0.125,0.331,1.83e-08,1.83e-08,1.32e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6190000,1,-0.00943,-0.0109,-0.0168,0.00331,0.00755,0.00215,0.0018,0.0011,-365,-1.64e-05,-5.7e-05,2.67e-07,1.73e-07,5.29e-07,-2.76e-07,0.192,0.00189,0.404,0,0,0,0,0,2.52e-07,0.000565,0.000565,0.0004,0.303,0.303,4.66,0.159,0.159,0.319,1.83e-08,1.83e-08,1.26e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6290000,1,-0.00945,-0.0109,-0.0168,0.00352,0.00715,-0.00589,0.00135,0.00124,-365,-1.63e-05,-5.71e-05,2.63e-07,-2.01e-10,3.98e-07,-3.38e-07,0.192,0.00189,0.404,0,0,0,0,0,2.3e-07,0.000475,0.000475,0.000394,0.237,0.237,3.09,0.119,0.119,0.295,1.48e-08,1.48e-08,1.2e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6390000,1,-0.00934,-0.0109,-0.0168,0.00395,0.00844,-0.0441,0.00173,0.00203,-365,-1.63e-05,-5.71e-05,2.63e-07,1.35e-08,3.85e-07,2.89e-07,0.192,0.00189,0.404,0,0,0,0,0,2.32e-07,0.000498,0.000499,0.000388,0.274,0.274,2.16,0.151,0.151,0.288,1.48e-08,1.48e-08,1.15e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6490000,1,-0.00939,-0.0109,-0.0168,0.00359,0.0077,-0.048,0.00134,0.00185,-365,-1.61e-05,-5.73e-05,2.58e-07,-1.54e-07,1.8e-07,-1.73e-07,0.192,0.00189,0.404,0,0,0,0,0,2.15e-07,0.000422,0.000422,0.000382,0.215,0.215,1.47,0.113,0.113,0.256,1.2e-08,1.2e-08,1.09e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6590000,1,-0.00939,-0.0109,-0.0169,0.00353,0.00841,-0.0945,0.0017,0.00262,-365,-1.61e-05,-5.73e-05,2.58e-07,-1.13e-07,1.43e-07,1.71e-06,0.192,0.00189,0.404,0,0,0,0,0,2.18e-07,0.000442,0.000442,0.000377,0.248,0.248,1.03,0.143,0.143,0.229,1.2e-08,1.2e-08,1.05e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6690000,1,-0.0094,-0.0109,-0.017,0.00346,0.00674,-0.0733,0.0013,0.00216,-365,-1.58e-05,-5.74e-05,2.52e-07,-3.26e-07,-4.56e-08,-1.49e-06,0.192,0.00189,0.404,0,0,0,0,0,2.03e-07,0.000378,0.000378,0.000371,0.196,0.196,0.746,0.108,0.108,0.206,9.76e-09,9.77e-09,1e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6790000,1,-0.00938,-0.0109,-0.017,0.00318,0.00814,-0.11,0.00165,0.0029,-365,-1.58e-05,-5.74e-05,2.52e-07,-2.73e-07,-9.31e-08,9.39e-07,0.192,0.00189,0.404,0,0,0,0,0,2.04e-07,0.000394,0.000394,0.000366,0.225,0.225,0.577,0.136,0.136,0.196,9.76e-09,9.77e-09,9.57e-09,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6890000,0.706,0.0013,-0.0143,0.708,0.00244,0.00869,-0.121,0.00124,0.00242,-365,-1.56e-05,-5.75e-05,2.48e-07,-4.13e-07,-3.48e-07,4.83e-07,0.209,0.00206,0.432,0,0,0,0,0,0.00103,0.000339,0.000338,0.00132,0.176,0.176,0.442,0.104,0.104,0.178,7.97e-09,7.98e-09,9.28e-09,3.86e-06,3.86e-06,3.98e-06,0,0,0,0,0,0,0,0
|
||||
6990000,0.704,0.00139,-0.0142,0.71,0.0024,0.00926,-0.123,0.00147,0.00334,-365,-1.56e-05,-5.75e-05,1.96e-07,-4.79e-07,-2.87e-07,-2.51e-06,0.209,0.00206,0.432,0,0,0,0,0,0.000622,0.000339,0.000339,0.000783,0.178,0.178,0.347,0.128,0.128,0.163,7.97e-09,7.98e-09,9.28e-09,3.86e-06,3.86e-06,3.98e-06,0,0,0,0,0,0,0,0
|
||||
7090000,0.703,0.0014,-0.0142,0.711,0.00185,0.00855,-0.124,0.00169,0.00421,-365,-1.56e-05,-5.75e-05,1.16e-07,-5.58e-07,-2.14e-07,-6.11e-06,0.209,0.00206,0.432,0,0,0,0,0,0.000475,0.00034,0.000339,0.000593,0.184,0.184,0.287,0.156,0.156,0.156,7.97e-09,7.97e-09,9.28e-09,3.86e-06,3.86e-06,3.97e-06,0,0,0,0,0,0,0,0
|
||||
7190000,0.703,0.0014,-0.0141,0.711,0.000163,0.00836,-0.145,0.00179,0.00506,-365,-1.56e-05,-5.75e-05,1.08e-07,-5.09e-07,-2.57e-07,-3.87e-06,0.209,0.00206,0.432,0,0,0,0,0,0.000383,0.000341,0.000341,0.000473,0.193,0.193,0.236,0.188,0.188,0.144,7.97e-09,7.97e-09,9.28e-09,3.86e-06,3.86e-06,3.96e-06,0,0,0,0,0,0,0,0
|
||||
7290000,0.703,0.00142,-0.0141,0.711,-0.00132,0.00825,-0.145,0.00174,0.00587,-365,-1.56e-05,-5.75e-05,1.86e-07,-6.58e-07,-1.32e-07,-1.07e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000326,0.000342,0.000342,0.000399,0.205,0.205,0.198,0.223,0.223,0.134,7.96e-09,7.96e-09,9.27e-09,3.86e-06,3.86e-06,3.95e-06,0,0,0,0,0,0,0,0
|
||||
7390000,0.703,0.00143,-0.014,0.711,-0.00145,0.00941,-0.157,0.00158,0.00678,-365,-1.56e-05,-5.75e-05,2.7e-07,-6.93e-07,-1.07e-07,-1.22e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000292,0.000344,0.000344,0.000355,0.221,0.221,0.174,0.263,0.263,0.13,7.96e-09,7.96e-09,9.27e-09,3.86e-06,3.86e-06,3.94e-06,0,0,0,0,0,0,0,0
|
||||
7490000,0.703,0.00149,-0.014,0.711,-0.00306,0.0095,-0.16,0.00133,0.00771,-365,-1.56e-05,-5.75e-05,3.27e-07,-8.61e-07,3.49e-08,-2e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000264,0.000346,0.000346,0.000318,0.24,0.24,0.152,0.307,0.307,0.122,7.94e-09,7.95e-09,9.26e-09,3.86e-06,3.86e-06,3.92e-06,0,0,0,0,0,0,0,0
|
||||
7590000,0.704,0.00149,-0.0139,0.71,-0.00496,0.0104,-0.165,0.000962,0.00872,-365,-1.56e-05,-5.76e-05,5.48e-07,-1.06e-06,1.91e-07,-2.88e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000243,0.000349,0.000349,0.00029,0.263,0.262,0.136,0.358,0.358,0.115,7.94e-09,7.95e-09,9.25e-09,3.86e-06,3.86e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7690000,0.704,0.00157,-0.0138,0.71,-0.00677,0.0109,-0.161,0.000372,0.00977,-365,-1.56e-05,-5.76e-05,5.72e-07,-1.51e-06,5.79e-07,-4.94e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000228,0.000352,0.000352,0.000271,0.289,0.289,0.126,0.414,0.414,0.112,7.94e-09,7.95e-09,9.24e-09,3.86e-06,3.86e-06,3.88e-06,0,0,0,0,0,0,0,0
|
||||
7790000,0.704,0.00159,-0.0138,0.711,-0.00815,0.0114,-0.16,-0.000355,0.0108,-365,-1.56e-05,-5.76e-05,2.37e-07,-1.95e-06,9.7e-07,-6.96e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000215,0.000355,0.000355,0.000253,0.318,0.318,0.116,0.475,0.475,0.107,7.92e-09,7.93e-09,9.22e-09,3.86e-06,3.86e-06,3.84e-06,0,0,0,0,0,0,0,0
|
||||
7890000,0.704,0.0016,-0.0138,0.71,-0.0109,0.013,-0.157,-0.0013,0.0121,-365,-1.56e-05,-5.76e-05,4.56e-07,-2.52e-06,1.44e-06,-9.52e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000204,0.000359,0.000359,0.000239,0.351,0.351,0.109,0.546,0.546,0.102,7.92e-09,7.93e-09,9.2e-09,3.86e-06,3.86e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
7990000,0.704,0.00163,-0.0138,0.71,-0.0127,0.0138,-0.163,-0.00248,0.0133,-365,-1.56e-05,-5.76e-05,6.86e-07,-2.77e-06,1.66e-06,-0.000108,0.209,0.00206,0.432,0,0,0,0,0,0.000196,0.000363,0.000363,0.000227,0.387,0.386,0.104,0.622,0.622,0.0981,7.9e-09,7.9e-09,9.17e-09,3.86e-06,3.86e-06,3.76e-06,0,0,0,0,0,0,0,0
|
||||
8090000,0.704,0.00163,-0.0138,0.71,-0.0146,0.0149,-0.175,-0.00386,0.0148,-366,-1.56e-05,-5.76e-05,1.05e-06,-2.82e-06,1.69e-06,-0.00011,0.209,0.00206,0.432,0,0,0,0,0,0.00019,0.000368,0.000368,0.000219,0.427,0.427,0.102,0.71,0.71,0.097,7.9e-09,7.9e-09,9.15e-09,3.86e-06,3.86e-06,3.71e-06,0,0,0,0,0,0,0,0
|
||||
8190000,0.704,0.00162,-0.0137,0.71,-0.0173,0.016,-0.178,-0.00537,0.0162,-366,-1.56e-05,-5.76e-05,7.57e-07,-3.3e-06,2.14e-06,-0.000134,0.209,0.00206,0.432,0,0,0,0,0,0.000183,0.000372,0.000372,0.00021,0.469,0.469,0.0987,0.804,0.804,0.0939,7.87e-09,7.87e-09,9.11e-09,3.86e-06,3.86e-06,3.65e-06,0,0,0,0,0,0,0,0
|
||||
8290000,0.704,0.00166,-0.0138,0.71,-0.0187,0.0164,-0.174,-0.00719,0.0179,-366,-1.56e-05,-5.76e-05,5.69e-07,-4.2e-06,2.9e-06,-0.000175,0.209,0.00206,0.432,0,0,0,0,0,0.000178,0.000378,0.000378,0.000203,0.517,0.516,0.0967,0.915,0.915,0.0912,7.87e-09,7.87e-09,9.07e-09,3.86e-06,3.86e-06,3.58e-06,0,0,0,0,0,0,0,0
|
||||
8390000,0.704,0.00171,-0.0137,0.71,-0.0206,0.0173,-0.173,-0.00908,0.0194,-366,-1.56e-05,-5.76e-05,9.99e-07,-4.91e-06,3.54e-06,-0.00021,0.209,0.00206,0.432,0,0,0,0,0,0.000175,0.000383,0.000383,0.000198,0.564,0.564,0.0967,1.03,1.03,0.091,7.82e-09,7.83e-09,9.03e-09,3.86e-06,3.86e-06,3.52e-06,0,0,0,0,0,0,0,0
|
||||
8490000,0.704,0.0017,-0.0137,0.71,-0.0226,0.0187,-0.17,-0.0113,0.0212,-366,-1.56e-05,-5.76e-05,8.63e-07,-5.85e-06,4.33e-06,-0.000253,0.209,0.00206,0.432,0,0,0,0,0,0.000171,0.000389,0.000389,0.000193,0.619,0.619,0.0957,1.17,1.17,0.089,7.82e-09,7.83e-09,8.98e-09,3.86e-06,3.86e-06,3.43e-06,0,0,0,0,0,0,0,0
|
||||
8590000,0.704,0.00172,-0.0137,0.71,-0.0247,0.0205,-0.167,-0.0135,0.0229,-366,-1.56e-05,-5.76e-05,4.79e-07,-6.65e-06,5.15e-06,-0.000295,0.209,0.00206,0.432,0,0,0,0,0,0.000168,0.000395,0.000395,0.000188,0.672,0.672,0.0951,1.31,1.31,0.0874,7.78e-09,7.78e-09,8.93e-09,3.85e-06,3.85e-06,3.34e-06,0,0,0,0,0,0,0,0
|
||||
8690000,0.704,0.00177,-0.0136,0.71,-0.028,0.0214,-0.162,-0.0162,0.025,-366,-1.56e-05,-5.76e-05,1.11e-06,-7.81e-06,6.06e-06,-0.000347,0.209,0.00206,0.432,0,0,0,0,0,0.000166,0.000401,0.000401,0.000185,0.735,0.735,0.0958,1.48,1.48,0.0879,7.78e-09,7.78e-09,8.87e-09,3.85e-06,3.85e-06,3.25e-06,0,0,0,0,0,0,0,0
|
||||
8790000,0.704,0.00172,-0.0136,0.71,-0.0301,0.0228,-0.152,-0.0189,0.0269,-366,-1.56e-05,-5.76e-05,8.65e-07,-9e-06,7.29e-06,-0.00041,0.209,0.00206,0.432,0,0,0,0,0,0.000164,0.000407,0.000407,0.000181,0.792,0.791,0.0954,1.64,1.64,0.0867,7.72e-09,7.72e-09,8.8e-09,3.85e-06,3.85e-06,3.14e-06,0,0,0,0,0,0,0,0
|
||||
8890000,0.704,0.00176,-0.0136,0.71,-0.0323,0.0234,-0.151,-0.0221,0.0292,-366,-1.56e-05,-5.76e-05,7.16e-07,-9.86e-06,8e-06,-0.000449,0.209,0.00206,0.432,0,0,0,0,0,0.000162,0.000414,0.000414,0.000178,0.862,0.861,0.0949,1.86,1.86,0.0857,7.72e-09,7.72e-09,8.73e-09,3.85e-06,3.85e-06,3.02e-06,0,0,0,0,0,0,0,0
|
||||
8990000,0.704,0.00181,-0.0135,0.71,-0.0339,0.0235,-0.142,-0.025,0.031,-365,-1.56e-05,-5.76e-05,2.64e-07,-1.09e-05,9.26e-06,-0.000509,0.209,0.00206,0.432,0,0,0,0,0,0.000161,0.00042,0.00042,0.000176,0.922,0.921,0.0956,2.05,2.05,0.0868,7.65e-09,7.66e-09,8.66e-09,3.84e-06,3.84e-06,2.91e-06,0,0,0,0,0,0,0,0
|
||||
9090000,0.704,0.00185,-0.0136,0.71,-0.0366,0.0242,-0.141,-0.0285,0.0334,-366,-1.56e-05,-5.76e-05,-6.81e-09,-1.15e-05,9.77e-06,-0.000537,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000428,0.000428,0.000173,0.999,0.998,0.0949,2.3,2.3,0.086,7.65e-09,7.66e-09,8.58e-09,3.84e-06,3.84e-06,2.78e-06,0,0,0,0,0,0,0,0
|
||||
9190000,0.704,0.00186,-0.0136,0.71,-0.0378,0.0245,-0.141,-0.0315,0.035,-366,-1.55e-05,-5.76e-05,1.15e-06,-1.19e-05,1.05e-05,-0.000569,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.000433,0.000433,0.000171,1.06,1.06,0.094,2.52,2.52,0.0853,7.58e-09,7.59e-09,8.48e-09,3.83e-06,3.83e-06,2.65e-06,0,0,0,0,0,0,0,0
|
||||
9290000,0.704,0.00185,-0.0136,0.71,-0.0393,0.0255,-0.137,-0.0355,0.0376,-366,-1.55e-05,-5.76e-05,1.32e-06,-1.29e-05,1.13e-05,-0.000615,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000442,0.000442,0.000169,1.14,1.14,0.0929,2.83,2.83,0.0847,7.58e-09,7.59e-09,8.39e-09,3.83e-06,3.83e-06,2.52e-06,0,0,0,0,0,0,0,0
|
||||
9390000,0.704,0.00181,-0.0135,0.71,-0.0401,0.0268,-0.135,-0.0383,0.0391,-366,-1.55e-05,-5.75e-05,1.33e-06,-1.32e-05,1.23e-05,-0.000649,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000445,0.000445,0.000168,1.2,1.2,0.0928,3.07,3.07,0.086,7.5e-09,7.51e-09,8.3e-09,3.82e-06,3.82e-06,2.4e-06,0,0,0,0,0,0,0,0
|
||||
9490000,0.704,0.00182,-0.0135,0.71,-0.0425,0.0272,-0.13,-0.0426,0.0418,-366,-1.55e-05,-5.76e-05,2.24e-06,-1.4e-05,1.29e-05,-0.000686,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000455,0.000455,0.000167,1.29,1.29,0.0912,3.44,3.44,0.0854,7.5e-09,7.51e-09,8.19e-09,3.82e-06,3.82e-06,2.27e-06,0,0,0,0,0,0,0,0
|
||||
9590000,0.704,0.00183,-0.0135,0.71,-0.044,0.0276,-0.127,-0.0453,0.043,-366,-1.54e-05,-5.75e-05,2.52e-06,-1.42e-05,1.41e-05,-0.000723,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000458,0.000458,0.000166,1.35,1.35,0.0894,3.7,3.69,0.0848,7.42e-09,7.42e-09,8.08e-09,3.81e-06,3.81e-06,2.13e-06,0,0,0,0,0,0,0,0
|
||||
9690000,0.704,0.00191,-0.0135,0.71,-0.0463,0.0296,-0.119,-0.0499,0.0459,-366,-1.54e-05,-5.75e-05,1.66e-06,-1.52e-05,1.49e-05,-0.00077,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000468,0.000468,0.000165,1.45,1.44,0.0886,4.12,4.12,0.086,7.42e-09,7.42e-09,7.97e-09,3.81e-06,3.81e-06,2.02e-06,0,0,0,0,0,0,0,0
|
||||
9790000,0.705,0.0019,-0.0134,0.71,-0.0467,0.0314,-0.109,-0.0547,0.0491,-365,-1.54e-05,-5.75e-05,2.29e-06,-1.65e-05,1.59e-05,-0.000825,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000479,0.000479,0.000164,1.55,1.55,0.0864,4.59,4.58,0.0853,7.42e-09,7.42e-09,7.85e-09,3.81e-06,3.81e-06,1.89e-06,0,0,0,0,0,0,0,0
|
||||
9890000,0.704,0.00191,-0.0134,0.71,-0.0478,0.0315,-0.106,-0.057,0.05,-365,-1.54e-05,-5.75e-05,2.24e-06,-1.63e-05,1.7e-05,-0.00085,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.00048,0.00048,0.000163,1.59,1.59,0.084,4.87,4.87,0.0846,7.33e-09,7.33e-09,7.72e-09,3.79e-06,3.79e-06,1.76e-06,0,0,0,0,0,0,0,0
|
||||
9990000,0.704,0.00196,-0.0134,0.71,-0.0498,0.0319,-0.1,-0.062,0.0533,-365,-1.54e-05,-5.75e-05,1.83e-06,-1.71e-05,1.76e-05,-0.000888,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000491,0.000491,0.000163,1.7,1.7,0.0827,5.4,5.4,0.0857,7.33e-09,7.33e-09,7.61e-09,3.79e-06,3.79e-06,1.66e-06,0,0,0,0,0,0,0,0
|
||||
10090000,0.705,0.00197,-0.0134,0.71,-0.0494,0.0306,-0.096,-0.0637,0.0536,-365,-1.53e-05,-5.75e-05,2.07e-06,-1.68e-05,1.9e-05,-0.000914,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000491,0.000491,0.000162,1.74,1.74,0.0801,5.67,5.67,0.0848,7.24e-09,7.24e-09,7.47e-09,3.77e-06,3.77e-06,1.54e-06,0,0,0,0,0,0,0,0
|
||||
10190000,0.704,0.00198,-0.0134,0.71,-0.0512,0.0329,-0.0957,-0.0687,0.0568,-366,-1.54e-05,-5.74e-05,8.27e-07,-1.71e-05,1.93e-05,-0.000928,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000502,0.000502,0.000161,1.85,1.85,0.0774,6.28,6.27,0.0839,7.24e-09,7.24e-09,7.33e-09,3.77e-06,3.77e-06,1.44e-06,0,0,0,0,0,0,0,0
|
||||
10290000,0.704,0.00193,-0.0134,0.71,-0.0504,0.0315,-0.0832,-0.0697,0.0565,-365,-1.53e-05,-5.74e-05,6.93e-08,-1.73e-05,2.13e-05,-0.000983,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.0005,0.0005,0.000161,1.87,1.87,0.0758,6.51,6.51,0.0847,7.14e-09,7.15e-09,7.21e-09,3.74e-06,3.74e-06,1.35e-06,0,0,0,0,0,0,0,0
|
||||
10390000,0.704,0.00191,-0.0133,0.71,0.00936,-0.0198,0.00845,0.000863,-0.00177,-365,-1.53e-05,-5.74e-05,1.5e-07,-1.8e-05,2.18e-05,-0.00101,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000512,0.000512,0.00016,0.252,0.252,0.25,0.252,0.252,0.0753,7.14e-09,7.15e-09,7.07e-09,3.74e-06,3.74e-06,1.26e-06,0,0,0,0,0,0,0,0
|
||||
10490000,0.704,0.00195,-0.0133,0.71,0.00799,-0.0184,0.0138,0.00171,-0.00366,-365,-1.53e-05,-5.74e-05,-5.75e-07,-1.87e-05,2.24e-05,-0.00105,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000525,0.000525,0.00016,0.258,0.258,0.248,0.259,0.259,0.0714,7.14e-09,7.15e-09,6.92e-09,3.74e-06,3.74e-06,1.19e-06,0,0,0,0,0,0,0,0
|
||||
10590000,0.704,0.00204,-0.0134,0.71,0.00751,-0.0078,0.0178,0.00181,-0.000838,-365,-1.53e-05,-5.72e-05,-4.85e-07,-2.11e-05,2.26e-05,-0.00106,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.00053,0.00053,0.00016,0.132,0.132,0.169,0.131,0.131,0.0672,7.1e-09,7.11e-09,6.77e-09,3.73e-06,3.73e-06,1.14e-06,0,0,0,0,0,0,0,0
|
||||
10690000,0.704,0.00209,-0.0134,0.71,0.00532,-0.00789,0.0199,0.00248,-0.00164,-365,-1.53e-05,-5.72e-05,-7.09e-07,-2.14e-05,2.28e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000543,0.000543,0.00016,0.143,0.143,0.165,0.137,0.137,0.069,7.1e-09,7.11e-09,6.64e-09,3.73e-06,3.73e-06,1.11e-06,0,0,0,0,0,0,0,0
|
||||
10790000,0.704,0.00208,-0.0135,0.71,0.00471,-0.00515,0.017,0.00267,-0.000809,-365,-1.52e-05,-5.71e-05,-5.38e-07,-2.31e-05,2.37e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000533,0.000533,0.000159,0.0994,0.0994,0.123,0.0914,0.0914,0.0656,6.97e-09,6.98e-09,6.49e-09,3.71e-06,3.71e-06,1.08e-06,0,0,0,0,0,0,0,0
|
||||
10890000,0.704,0.00204,-0.0134,0.71,0.00328,-0.0046,0.013,0.00305,-0.00126,-365,-1.52e-05,-5.71e-05,-5.22e-07,-2.31e-05,2.36e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.000546,0.000546,0.000159,0.114,0.114,0.117,0.0975,0.0975,0.0674,6.97e-09,6.98e-09,6.34e-09,3.71e-06,3.71e-06,1.06e-06,0,0,0,0,0,0,0,0
|
||||
10990000,0.704,0.00202,-0.0136,0.71,0.00547,0.000295,0.00905,0.00459,-0.00245,-365,-1.47e-05,-5.68e-05,3.06e-07,-2.79e-05,2.81e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.000516,0.000515,0.000159,0.0901,0.0901,0.0927,0.0729,0.0729,0.0653,6.73e-09,6.73e-09,6.21e-09,3.68e-06,3.68e-06,1.04e-06,0,0,0,0,0,0,0,0
|
||||
11090000,0.704,0.00202,-0.0135,0.71,0.00393,0.00198,0.0124,0.00507,-0.00238,-365,-1.47e-05,-5.68e-05,1.13e-06,-2.81e-05,2.82e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.000528,0.000528,0.000158,0.108,0.108,0.0871,0.0794,0.0794,0.0671,6.73e-09,6.73e-09,6.05e-09,3.68e-06,3.68e-06,1.03e-06,0,0,0,0,0,0,0,0
|
||||
11190000,0.704,0.00195,-0.0137,0.71,0.00838,0.0048,0.00301,0.00646,-0.0031,-365,-1.41e-05,-5.67e-05,5.45e-07,-3.1e-05,3.31e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.000479,0.000479,0.000158,0.0889,0.0888,0.0709,0.0629,0.0629,0.0641,6.38e-09,6.39e-09,5.9e-09,3.64e-06,3.64e-06,1.01e-06,0,0,0,0,0,0,0,0
|
||||
11290000,0.704,0.00204,-0.0138,0.71,0.00769,0.00648,0.00232,0.00728,-0.00253,-365,-1.42e-05,-5.67e-05,-4.53e-07,-3.1e-05,3.32e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000491,0.000491,0.000158,0.109,0.109,0.0668,0.0699,0.0699,0.0665,6.38e-09,6.39e-09,5.77e-09,3.64e-06,3.64e-06,1.01e-06,0,0,0,0,0,0,0,0
|
||||
11390000,0.704,0.00209,-0.0136,0.71,0.00372,0.00613,-0.00271,0.00534,-0.00222,-365,-1.45e-05,-5.68e-05,-1.25e-06,-2.84e-05,3.06e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000431,0.000431,0.000158,0.0893,0.0893,0.0559,0.0572,0.0572,0.0636,5.99e-09,5.99e-09,5.62e-09,3.59e-06,3.59e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11490000,0.704,0.00211,-0.0136,0.71,0.000894,0.00835,-0.00233,0.00558,-0.0015,-365,-1.45e-05,-5.68e-05,-2.77e-06,-2.84e-05,3.07e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000442,0.000442,0.000157,0.109,0.109,0.052,0.0647,0.0647,0.0645,5.99e-09,5.99e-09,5.47e-09,3.59e-06,3.59e-06,9.94e-07,0,0,0,0,0,0,0,0
|
||||
11590000,0.704,0.00203,-0.0136,0.71,-0.00296,0.00787,-0.00772,0.00433,-0.00159,-365,-1.46e-05,-5.71e-05,-3.09e-06,-2.57e-05,3.07e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.00038,0.00038,0.000158,0.0888,0.0888,0.045,0.0538,0.0538,0.0628,5.58e-09,5.59e-09,5.34e-09,3.56e-06,3.56e-06,9.9e-07,0,0,0,0,0,0,0,0
|
||||
11690000,0.704,0.00201,-0.0136,0.71,-0.00604,0.0105,-0.0121,0.00386,-0.000701,-365,-1.46e-05,-5.71e-05,-3.55e-06,-2.56e-05,3.06e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.00039,0.00039,0.000157,0.108,0.108,0.0421,0.0618,0.0618,0.0632,5.58e-09,5.59e-09,5.2e-09,3.56e-06,3.56e-06,9.86e-07,0,0,0,0,0,0,0,0
|
||||
11790000,0.704,0.00208,-0.0135,0.71,-0.0112,0.0109,-0.0139,0.00173,0.000401,-365,-1.48e-05,-5.7e-05,-3.61e-06,-2.53e-05,2.94e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000334,0.000334,0.000157,0.0866,0.0866,0.0368,0.0518,0.0518,0.0607,5.21e-09,5.22e-09,5.05e-09,3.52e-06,3.53e-06,9.81e-07,0,0,0,0,0,0,0,0
|
||||
11890000,0.704,0.00209,-0.0135,0.71,-0.0129,0.0117,-0.015,0.000541,0.00153,-365,-1.48e-05,-5.7e-05,-4.35e-06,-2.53e-05,2.95e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000343,0.000343,0.000157,0.104,0.104,0.0348,0.0601,0.0601,0.0608,5.21e-09,5.22e-09,4.91e-09,3.52e-06,3.53e-06,9.78e-07,0,0,0,0,0,0,0,0
|
||||
11990000,0.704,0.00211,-0.0135,0.71,-0.0143,0.0122,-0.0201,-0.000414,0.00219,-365,-1.47e-05,-5.71e-05,-4.16e-06,-2.49e-05,3.03e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000296,0.000296,0.000157,0.0831,0.0831,0.0315,0.0507,0.0507,0.0594,4.89e-09,4.89e-09,4.79e-09,3.5e-06,3.5e-06,9.73e-07,0,0,0,0,0,0,0,0
|
||||
12090000,0.704,0.00212,-0.0135,0.71,-0.0158,0.0142,-0.0257,-0.00191,0.00348,-365,-1.47e-05,-5.71e-05,-3.44e-06,-2.48e-05,3.02e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000304,0.000304,0.000156,0.0988,0.0988,0.0301,0.0591,0.0591,0.0593,4.89e-09,4.89e-09,4.65e-09,3.5e-06,3.5e-06,9.71e-07,0,0,0,0,0,0,0,0
|
||||
12190000,0.704,0.0018,-0.0136,0.71,-0.0096,0.0118,-0.0208,0.00116,0.00193,-365,-1.4e-05,-5.76e-05,-3.16e-06,-2.28e-05,3.6e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000265,0.000265,0.000156,0.0788,0.0788,0.0276,0.05,0.05,0.0572,4.61e-09,4.62e-09,4.52e-09,3.49e-06,3.49e-06,9.63e-07,0,0,0,0,0,0,0,0
|
||||
12290000,0.704,0.00177,-0.0136,0.71,-0.0124,0.0133,-0.0203,7.1e-05,0.00319,-365,-1.4e-05,-5.76e-05,-2.95e-06,-2.29e-05,3.61e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000272,0.000272,0.000156,0.0927,0.0927,0.0272,0.0585,0.0585,0.0578,4.61e-09,4.62e-09,4.4e-09,3.49e-06,3.49e-06,9.61e-07,0,0,0,0,0,0,0,0
|
||||
12390000,0.704,0.00148,-0.0136,0.71,-0.00698,0.0104,-0.0189,0.00261,0.00173,-365,-1.35e-05,-5.81e-05,-3.44e-06,-2.15e-05,4.01e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000242,0.000241,0.000155,0.0742,0.0742,0.0255,0.0495,0.0495,0.0558,4.38e-09,4.38e-09,4.28e-09,3.48e-06,3.48e-06,9.51e-07,0,0,0,0,0,0,0,0
|
||||
12490000,0.704,0.00146,-0.0136,0.71,-0.00839,0.0123,-0.0219,0.00186,0.00287,-365,-1.35e-05,-5.81e-05,-4.12e-06,-2.15e-05,4.01e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000248,0.000248,0.000155,0.0866,0.0866,0.0253,0.058,0.058,0.0556,4.38e-09,4.38e-09,4.15e-09,3.48e-06,3.48e-06,9.48e-07,0,0,0,0,0,0,0,0
|
||||
12590000,0.704,0.00154,-0.0134,0.71,-0.0152,0.0104,-0.0274,-0.00299,0.00158,-365,-1.4e-05,-5.83e-05,-4.04e-06,-1.93e-05,3.79e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000224,0.000224,0.000155,0.0697,0.0697,0.0244,0.0492,0.0492,0.0545,4.17e-09,4.17e-09,4.04e-09,3.47e-06,3.47e-06,9.36e-07,0,0,0,0,0,0,0,0
|
||||
12690000,0.704,0.00158,-0.0134,0.71,-0.0159,0.0118,-0.031,-0.00457,0.00271,-365,-1.4e-05,-5.83e-05,-4.47e-06,-1.93e-05,3.79e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.00023,0.00023,0.000155,0.0806,0.0806,0.0246,0.0576,0.0576,0.0543,4.17e-09,4.17e-09,3.92e-09,3.47e-06,3.47e-06,9.32e-07,0,0,0,0,0,0,0,0
|
||||
12790000,0.704,0.00162,-0.0132,0.71,-0.0208,0.00879,-0.0344,-0.00774,0.00147,-365,-1.43e-05,-5.86e-05,-4.16e-06,-1.8e-05,3.74e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000211,0.000211,0.000154,0.0654,0.0654,0.024,0.049,0.049,0.0527,3.99e-09,3.99e-09,3.8e-09,3.47e-06,3.47e-06,9.15e-07,0,0,0,0,0,0,0,0
|
||||
12890000,0.704,0.00158,-0.0132,0.71,-0.022,0.00868,-0.0335,-0.00987,0.00232,-365,-1.43e-05,-5.86e-05,-3.98e-06,-1.81e-05,3.75e-05,-0.00109,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000217,0.000217,0.000154,0.0751,0.0751,0.0247,0.0573,0.0573,0.0532,3.99e-09,3.99e-09,3.7e-09,3.47e-06,3.47e-06,9.12e-07,0,0,0,0,0,0,0,0
|
||||
12990000,0.704,0.00125,-0.0135,0.71,-0.00984,0.0063,-0.0341,-0.00133,0.00132,-365,-1.33e-05,-5.89e-05,-3.14e-06,-1.89e-05,4.04e-05,-0.00109,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.000201,0.000201,0.000154,0.0614,0.0614,0.0244,0.0488,0.0488,0.0518,3.82e-09,3.82e-09,3.59e-09,3.47e-06,3.47e-06,8.91e-07,0,0,0,0,0,0,0,0
|
||||
13090000,0.704,0.00126,-0.0134,0.71,-0.0107,0.00646,-0.0343,-0.00235,0.00196,-365,-1.33e-05,-5.89e-05,-3.91e-06,-1.89e-05,4.05e-05,-0.0011,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.000207,0.000207,0.000153,0.0702,0.0702,0.0252,0.0569,0.0569,0.0517,3.82e-09,3.82e-09,3.49e-09,3.47e-06,3.47e-06,8.85e-07,0,0,0,0,0,0,0,0
|
||||
13190000,0.704,0.00103,-0.0135,0.71,-0.00165,0.00592,-0.0312,0.00402,0.0013,-365,-1.26e-05,-5.91e-05,-3.82e-06,-1.98e-05,4.17e-05,-0.00112,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.000194,0.000194,0.000153,0.0578,0.0578,0.025,0.0486,0.0486,0.0504,3.67e-09,3.67e-09,3.38e-09,3.47e-06,3.47e-06,8.6e-07,0,0,0,0,0,0,0,0
|
||||
13290000,0.704,0.00104,-0.0135,0.71,-0.00209,0.00674,-0.0278,0.00384,0.00194,-365,-1.26e-05,-5.91e-05,-3.06e-06,-2e-05,4.19e-05,-0.00113,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.0002,0.0002,0.000153,0.0658,0.0658,0.0261,0.0566,0.0566,0.0511,3.67e-09,3.67e-09,3.29e-09,3.47e-06,3.47e-06,8.54e-07,0,0,0,0,0,0,0,0
|
||||
13390000,0.704,0.000886,-0.0135,0.71,-0.00101,0.00579,-0.0244,0.00294,0.00119,-365,-1.24e-05,-5.93e-05,-2.42e-06,-2.05e-05,4.15e-05,-0.00114,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000189,0.000189,0.000152,0.0546,0.0546,0.026,0.0484,0.0484,0.05,3.52e-09,3.52e-09,3.19e-09,3.47e-06,3.47e-06,8.26e-07,0,0,0,0,0,0,0,0
|
||||
13490000,0.704,0.000914,-0.0135,0.71,-0.00168,0.00568,-0.023,0.00283,0.00175,-365,-1.24e-05,-5.93e-05,-1.9e-06,-2.06e-05,4.16e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000195,0.000195,0.000152,0.0619,0.0619,0.027,0.0562,0.0562,0.0502,3.52e-09,3.52e-09,3.09e-09,3.47e-06,3.47e-06,8.18e-07,0,0,0,0,0,0,0,0
|
||||
13590000,0.704,0.000857,-0.0134,0.71,-0.0012,0.00597,-0.0253,0.00204,0.00116,-365,-1.23e-05,-5.94e-05,-2.28e-06,-2.09e-05,4.07e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000186,0.000186,0.000152,0.0517,0.0517,0.027,0.0482,0.0482,0.0498,3.38e-09,3.38e-09,3.01e-09,3.47e-06,3.47e-06,7.86e-07,0,0,0,0,0,0,0,0
|
||||
13690000,0.704,0.000831,-0.0134,0.71,-0.00069,0.00772,-0.0299,0.00193,0.00182,-365,-1.23e-05,-5.94e-05,-1.49e-06,-2.09e-05,4.07e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000191,0.000191,0.000151,0.0586,0.0586,0.0281,0.0559,0.0559,0.0501,3.38e-09,3.38e-09,2.92e-09,3.47e-06,3.47e-06,7.77e-07,0,0,0,0,0,0,0,0
|
||||
13790000,0.704,0.000721,-0.0133,0.71,9.19e-05,0.00364,-0.0313,0.00314,-0.00049,-365,-1.21e-05,-5.98e-05,-1.49e-06,-2.24e-05,4.01e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000183,0.000183,0.000151,0.0493,0.0493,0.0279,0.048,0.048,0.0493,3.24e-09,3.24e-09,2.83e-09,3.47e-06,3.47e-06,7.42e-07,0,0,0,0,0,0,0,0
|
||||
13890000,0.704,0.000689,-0.0133,0.71,0.000425,0.00355,-0.0356,0.00316,-0.000152,-365,-1.21e-05,-5.98e-05,-1.03e-06,-2.23e-05,4e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000189,0.000189,0.00015,0.0557,0.0557,0.0292,0.0555,0.0555,0.0503,3.24e-09,3.24e-09,2.76e-09,3.47e-06,3.47e-06,7.32e-07,0,0,0,0,0,0,0,0
|
||||
13990000,0.704,0.000623,-0.0133,0.71,0.000882,0.00111,-0.0348,0.00413,-0.00188,-365,-1.19e-05,-6.01e-05,-9.06e-07,-2.4e-05,3.93e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000181,0.000181,0.00015,0.0472,0.0472,0.0288,0.0478,0.0478,0.0495,3.1e-09,3.1e-09,2.68e-09,3.46e-06,3.46e-06,6.95e-07,0,0,0,0,0,0,0,0
|
||||
14090000,0.704,0.000605,-0.0133,0.71,0.000777,0.00126,-0.0361,0.00419,-0.00178,-365,-1.19e-05,-6.01e-05,-6.97e-08,-2.39e-05,3.92e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000155,0.000187,0.000187,0.000149,0.0533,0.0533,0.0298,0.0551,0.0551,0.05,3.1e-09,3.1e-09,2.6e-09,3.46e-06,3.46e-06,6.83e-07,0,0,0,0,0,0,0,0
|
||||
14190000,0.705,0.0005,-0.0134,0.71,0.0043,0.000704,-0.0377,0.00642,-0.00152,-365,-1.15e-05,-6.02e-05,3.69e-07,-2.43e-05,3.68e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000155,0.00018,0.00018,0.000149,0.0454,0.0454,0.0295,0.0476,0.0476,0.0499,2.95e-09,2.95e-09,2.53e-09,3.46e-06,3.46e-06,6.47e-07,0,0,0,0,0,0,0,0
|
||||
14290000,0.705,0.00051,-0.0133,0.709,0.00491,0.00148,-0.0367,0.00688,-0.00143,-365,-1.15e-05,-6.02e-05,6.87e-07,-2.44e-05,3.69e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000155,0.000185,0.000185,0.000149,0.0512,0.0512,0.0304,0.0548,0.0548,0.0505,2.95e-09,2.95e-09,2.45e-09,3.46e-06,3.46e-06,6.34e-07,0,0,0,0,0,0,0,0
|
||||
14390000,0.705,0.00042,-0.0133,0.709,0.00689,0.00238,-0.0386,0.00836,-0.00123,-365,-1.12e-05,-6.02e-05,1.5e-06,-2.48e-05,3.48e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000154,0.000179,0.000179,0.000148,0.0439,0.0439,0.0297,0.0474,0.0474,0.0498,2.81e-09,2.81e-09,2.38e-09,3.45e-06,3.45e-06,5.96e-07,0,0,0,0,0,0,0,0
|
||||
14490000,0.705,0.000406,-0.0133,0.709,0.00673,0.00361,-0.042,0.00902,-0.000928,-365,-1.12e-05,-6.02e-05,1.73e-06,-2.47e-05,3.46e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000154,0.000184,0.000184,0.000148,0.0495,0.0495,0.0305,0.0545,0.0545,0.0505,2.81e-09,2.81e-09,2.31e-09,3.45e-06,3.45e-06,5.82e-07,0,0,0,0,0,0,0,0
|
||||
14590000,0.705,0.000392,-0.0131,0.709,0.00351,0.00204,-0.0422,0.00568,-0.00234,-365,-1.16e-05,-6.05e-05,1.73e-06,-2.68e-05,3.77e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000154,0.000177,0.000177,0.000148,0.0427,0.0427,0.0299,0.0472,0.0472,0.0503,2.66e-09,2.67e-09,2.25e-09,3.44e-06,3.44e-06,5.47e-07,0,0,0,0,0,0,0,0
|
||||
14690000,0.705,0.000352,-0.0131,0.709,0.00475,-0.000877,-0.0387,0.00613,-0.00227,-365,-1.16e-05,-6.05e-05,2.29e-06,-2.7e-05,3.79e-05,-0.00117,0.209,0.00206,0.432,0,0,0,0,0,0.000153,0.000183,0.000182,0.000147,0.0481,0.0481,0.0305,0.0541,0.0541,0.051,2.66e-09,2.67e-09,2.18e-09,3.44e-06,3.44e-06,5.33e-07,0,0,0,0,0,0,0,0
|
||||
14790000,0.705,0.000371,-0.0129,0.709,0.00178,-0.00242,-0.0348,0.00343,-0.00329,-365,-1.19e-05,-6.07e-05,2.41e-06,-2.88e-05,4.1e-05,-0.00119,0.209,0.00206,0.432,0,0,0,0,0,0.000153,0.000176,0.000176,0.000147,0.0416,0.0416,0.0295,0.047,0.047,0.0502,2.52e-09,2.52e-09,2.12e-09,3.43e-06,3.43e-06,4.98e-07,0,0,0,0,0,0,0,0
|
||||
14890000,0.705,0.000365,-0.0129,0.709,0.00317,-0.00145,-0.0378,0.00366,-0.00348,-365,-1.19e-05,-6.07e-05,2.75e-06,-2.88e-05,4.1e-05,-0.00119,0.209,0.00206,0.432,0,0,0,0,0,0.000152,0.000181,0.000181,0.000146,0.0469,0.0469,0.0303,0.0538,0.0538,0.0516,2.52e-09,2.52e-09,2.06e-09,3.43e-06,3.43e-06,4.85e-07,0,0,0,0,0,0,0,0
|
||||
14990000,0.705,0.000355,-0.0129,0.709,0.00217,-0.00165,-0.0337,0.00287,-0.0028,-365,-1.2e-05,-6.06e-05,2.6e-06,-2.86e-05,4.2e-05,-0.0012,0.209,0.00206,0.432,0,0,0,0,0,0.000152,0.000175,0.000175,0.000146,0.0408,0.0408,0.0292,0.0468,0.0468,0.0508,2.37e-09,2.37e-09,2e-09,3.42e-06,3.42e-06,4.52e-07,0,0,0,0,0,0,0,0
|
||||
15090000,0.705,0.000282,-0.0128,0.709,0.00243,-0.00182,-0.0363,0.00309,-0.00297,-365,-1.2e-05,-6.06e-05,2.58e-06,-2.85e-05,4.18e-05,-0.0012,0.209,0.00206,0.432,0,0,0,0,0,0.000151,0.000179,0.000179,0.000145,0.0459,0.0459,0.0296,0.0536,0.0536,0.0514,2.37e-09,2.37e-09,1.95e-09,3.42e-06,3.42e-06,4.38e-07,0,0,0,0,0,0,0,0
|
||||
15190000,0.705,0.000293,-0.0128,0.709,0.002,-0.000597,-0.0338,0.00249,-0.00235,-365,-1.21e-05,-6.06e-05,2.48e-06,-2.82e-05,4.25e-05,-0.00121,0.209,0.00206,0.432,0,0,0,0,0,0.000151,0.000173,0.000173,0.000145,0.0401,0.04,0.0287,0.0466,0.0466,0.0512,2.22e-09,2.22e-09,1.9e-09,3.41e-06,3.41e-06,4.09e-07,0,0,0,0,0,0,0,0
|
||||
15290000,0.705,0.000255,-0.0129,0.709,0.00245,-0.000402,-0.0314,0.00272,-0.0024,-365,-1.21e-05,-6.06e-05,2.82e-06,-2.83e-05,4.27e-05,-0.00122,0.209,0.00206,0.432,0,0,0,0,0,0.000151,0.000178,0.000177,0.000145,0.0451,0.0451,0.0289,0.0533,0.0533,0.0519,2.22e-09,2.22e-09,1.84e-09,3.41e-06,3.41e-06,3.96e-07,0,0,0,0,0,0,0,0
|
||||
15390000,0.705,0.000254,-0.0128,0.709,0.00188,-7.33e-05,-0.0291,0.00028,-0.00195,-365,-1.22e-05,-6.06e-05,3.57e-06,-2.82e-05,4.39e-05,-0.00123,0.209,0.00206,0.432,0,0,0,0,0,0.00015,0.000171,0.000171,0.000144,0.0394,0.0394,0.0277,0.0465,0.0465,0.051,2.07e-09,2.08e-09,1.79e-09,3.39e-06,3.39e-06,3.68e-07,0,0,0,0,0,0,0,0
|
||||
15490000,0.705,0.000273,-0.0128,0.709,0.00302,-0.000432,-0.0291,0.000535,-0.002,-365,-1.22e-05,-6.05e-05,3.11e-06,-2.82e-05,4.38e-05,-0.00122,0.209,0.00206,0.432,0,0,0,0,0,0.00015,0.000175,0.000175,0.000144,0.0444,0.0444,0.0281,0.0531,0.0531,0.0522,2.07e-09,2.08e-09,1.75e-09,3.39e-06,3.39e-06,3.57e-07,0,0,0,0,0,0,0,0
|
||||
15590000,0.705,0.000283,-0.0128,0.709,0.0013,-0.000441,-0.0275,-0.00158,-0.00165,-365,-1.24e-05,-6.05e-05,2.8e-06,-2.8e-05,4.51e-05,-0.00123,0.209,0.00206,0.432,0,0,0,0,0,0.00015,0.000169,0.000169,0.000144,0.0389,0.0389,0.0269,0.0463,0.0463,0.0513,1.93e-09,1.93e-09,1.7e-09,3.37e-06,3.38e-06,3.31e-07,0,0,0,0,0,0,0,0
|
||||
15690000,0.705,0.000287,-0.0128,0.709,0.00151,-0.000587,-0.0279,-0.00145,-0.00169,-365,-1.24e-05,-6.05e-05,2.77e-06,-2.8e-05,4.51e-05,-0.00123,0.209,0.00206,0.432,0,0,0,0,0,0.000149,0.000173,0.000173,0.000143,0.0438,0.0438,0.027,0.0529,0.0529,0.0518,1.93e-09,1.93e-09,1.65e-09,3.37e-06,3.38e-06,3.19e-07,0,0,0,0,0,0,0,0
|
||||
15790000,0.705,0.000245,-0.0128,0.709,0.00213,-0.00226,-0.0299,-0.00124,-0.00275,-365,-1.24e-05,-6.07e-05,2.76e-06,-3.01e-05,4.54e-05,-0.00122,0.209,0.00206,0.432,0,0,0,0,0,0.000149,0.000166,0.000166,0.000143,0.0384,0.0384,0.0258,0.0462,0.0462,0.0508,1.79e-09,1.79e-09,1.6e-09,3.36e-06,3.36e-06,2.97e-07,0,0,0,0,0,0,0,0
|
||||
15890000,0.705,0.000199,-0.0128,0.709,0.00295,-0.00273,-0.0283,-0.000959,-0.00302,-365,-1.24e-05,-6.07e-05,2.83e-06,-3.01e-05,4.55e-05,-0.00123,0.209,0.00206,0.432,0,0,0,0,0,0.000148,0.00017,0.00017,0.000142,0.0432,0.0432,0.026,0.0527,0.0527,0.052,1.79e-09,1.79e-09,1.56e-09,3.36e-06,3.36e-06,2.87e-07,0,0,0,0,0,0,0,0
|
||||
15990000,0.705,0.000138,-0.0128,0.709,0.00295,-0.00364,-0.0235,-0.000917,-0.00379,-365,-1.24e-05,-6.08e-05,3.34e-06,-3.2e-05,4.64e-05,-0.00124,0.209,0.00206,0.432,0,0,0,0,0,0.000148,0.000163,0.000163,0.000142,0.038,0.038,0.0248,0.0461,0.0461,0.051,1.65e-09,1.65e-09,1.52e-09,3.34e-06,3.34e-06,2.67e-07,0,0,0,0,0,0,0,0
|
||||
16090000,0.705,0.000139,-0.0128,0.709,0.00462,-0.00382,-0.0199,-0.00055,-0.00419,-365,-1.24e-05,-6.09e-05,4.04e-06,-3.21e-05,4.66e-05,-0.00125,0.209,0.00206,0.432,0,0,0,0,0,0.000148,0.000167,0.000167,0.000141,0.0427,0.0427,0.0248,0.0526,0.0526,0.0514,1.65e-09,1.65e-09,1.48e-09,3.34e-06,3.34e-06,2.57e-07,0,0,0,0,0,0,0,0
|
||||
16190000,0.705,0.000157,-0.0128,0.709,0.00474,-0.00307,-0.0185,-0.000653,-0.00339,-365,-1.25e-05,-6.08e-05,4.11e-06,-3.1e-05,4.77e-05,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000147,0.00016,0.00016,0.000141,0.0375,0.0375,0.0238,0.046,0.046,0.051,1.52e-09,1.52e-09,1.44e-09,3.32e-06,3.32e-06,2.4e-07,0,0,0,0,0,0,0,0
|
||||
16290000,0.706,0.000176,-0.0128,0.708,0.00628,-0.00385,-0.0197,-9.63e-05,-0.00373,-365,-1.25e-05,-6.08e-05,4.75e-06,-3.1e-05,4.77e-05,-0.00125,0.209,0.00206,0.432,0,0,0,0,0,0.000147,0.000164,0.000164,0.000141,0.0421,0.0421,0.0237,0.0525,0.0525,0.0513,1.52e-09,1.52e-09,1.4e-09,3.32e-06,3.32e-06,2.31e-07,0,0,0,0,0,0,0,0
|
||||
16390000,0.706,0.000158,-0.0128,0.708,0.00529,-0.00411,-0.0187,-0.000322,-0.00298,-365,-1.26e-05,-6.07e-05,4.52e-06,-2.98e-05,4.93e-05,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000146,0.000157,0.000157,0.00014,0.0371,0.0371,0.0226,0.0459,0.0459,0.0503,1.39e-09,1.39e-09,1.37e-09,3.3e-06,3.3e-06,2.15e-07,0,0,0,0,0,0,0,0
|
||||
16490000,0.706,0.000176,-0.0128,0.708,0.00441,-0.00363,-0.0216,0.000135,-0.00336,-365,-1.26e-05,-6.07e-05,4.62e-06,-2.97e-05,4.92e-05,-0.00125,0.209,0.00206,0.432,0,0,0,0,0,0.000146,0.00016,0.00016,0.00014,0.0416,0.0416,0.0227,0.0523,0.0523,0.0513,1.39e-09,1.39e-09,1.33e-09,3.3e-06,3.3e-06,2.08e-07,0,0,0,0,0,0,0,0
|
||||
16590000,0.706,0.000418,-0.0128,0.708,0.000946,-0.000919,-0.0219,-0.00271,-2.82e-06,-365,-1.31e-05,-6.02e-05,4.68e-06,-2.36e-05,5.51e-05,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000146,0.000154,0.000153,0.00014,0.0366,0.0366,0.0217,0.0458,0.0458,0.0502,1.27e-09,1.27e-09,1.3e-09,3.28e-06,3.28e-06,1.94e-07,0,0,0,0,0,0,0,0
|
||||
16690000,0.706,0.000409,-0.0127,0.708,0.00107,-0.00042,-0.0183,-0.00259,-6.62e-05,-365,-1.31e-05,-6.02e-05,4.37e-06,-2.37e-05,5.53e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000145,0.000157,0.000156,0.000139,0.041,0.041,0.0215,0.0522,0.0522,0.0504,1.27e-09,1.27e-09,1.26e-09,3.28e-06,3.28e-06,1.86e-07,0,0,0,0,0,0,0,0
|
||||
16790000,0.706,0.000543,-0.0127,0.708,-0.00219,0.00177,-0.0173,-0.00488,0.0026,-365,-1.35e-05,-5.98e-05,4.38e-06,-1.86e-05,6.01e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000145,0.00015,0.00015,0.000139,0.0361,0.0361,0.0207,0.0458,0.0458,0.0501,1.16e-09,1.16e-09,1.24e-09,3.26e-06,3.26e-06,1.75e-07,0,0,0,0,0,0,0,0
|
||||
16890000,0.706,0.000562,-0.0127,0.708,-0.00254,0.00266,-0.0146,-0.00511,0.00281,-365,-1.35e-05,-5.98e-05,4.2e-06,-1.87e-05,6.02e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000145,0.000153,0.000153,0.000139,0.0404,0.0404,0.0205,0.0521,0.0521,0.0502,1.16e-09,1.16e-09,1.2e-09,3.26e-06,3.26e-06,1.68e-07,0,0,0,0,0,0,0,0
|
||||
16990000,0.706,0.000499,-0.0126,0.709,-0.00239,0.000624,-0.0138,-0.00546,0.000937,-365,-1.36e-05,-6e-05,3.83e-06,-2.19e-05,6.17e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000144,0.000146,0.000146,0.000138,0.0356,0.0356,0.0196,0.0457,0.0457,0.0492,1.05e-09,1.06e-09,1.17e-09,3.24e-06,3.25e-06,1.58e-07,0,0,0,0,0,0,0,0
|
||||
17090000,0.706,0.000467,-0.0126,0.709,-0.00166,0.00161,-0.0137,-0.00566,0.00102,-365,-1.36e-05,-6e-05,3.87e-06,-2.19e-05,6.17e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000144,0.000149,0.000149,0.000138,0.0398,0.0398,0.0194,0.052,0.052,0.0494,1.06e-09,1.06e-09,1.14e-09,3.24e-06,3.25e-06,1.52e-07,0,0,0,0,0,0,0,0
|
||||
17190000,0.706,0.000452,-0.0126,0.708,-0.00112,0.00155,-0.0143,-0.00589,-0.000449,-365,-1.37e-05,-6.02e-05,4.08e-06,-2.46e-05,6.32e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000143,0.000143,0.000143,0.000137,0.035,0.035,0.0187,0.0456,0.0456,0.049,9.59e-10,9.59e-10,1.12e-09,3.23e-06,3.23e-06,1.43e-07,0,0,0,0,0,0,0,0
|
||||
17290000,0.706,0.000432,-0.0125,0.709,0.000925,0.00262,-0.0098,-0.0059,-0.000256,-365,-1.37e-05,-6.02e-05,3.77e-06,-2.47e-05,6.33e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000143,0.000145,0.000145,0.000137,0.0391,0.0391,0.0185,0.0519,0.0519,0.0491,9.59e-10,9.59e-10,1.09e-09,3.23e-06,3.23e-06,1.38e-07,0,0,0,0,0,0,0,0
|
||||
17390000,0.706,0.000394,-0.0125,0.708,0.00168,0.00176,-0.00775,-0.0049,-0.00155,-365,-1.36e-05,-6.04e-05,4.09e-06,-2.76e-05,6.32e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000143,0.000139,0.000139,0.000137,0.0344,0.0344,0.0177,0.0455,0.0455,0.0481,8.7e-10,8.7e-10,1.06e-09,3.21e-06,3.21e-06,1.29e-07,0,0,0,0,0,0,0,0
|
||||
17490000,0.706,0.000391,-0.0125,0.708,0.00216,0.00135,-0.00595,-0.00473,-0.00141,-365,-1.36e-05,-6.04e-05,4.12e-06,-2.77e-05,6.32e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000142,0.000142,0.000142,0.000136,0.0383,0.0383,0.0177,0.0518,0.0518,0.0488,8.7e-10,8.7e-10,1.04e-09,3.21e-06,3.21e-06,1.25e-07,0,0,0,0,0,0,0,0
|
||||
17590000,0.706,0.000301,-0.0124,0.708,0.00352,0.00015,-0.000412,-0.00395,-0.00252,-365,-1.36e-05,-6.06e-05,4.2e-06,-3.01e-05,6.34e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000142,0.000136,0.000136,0.000136,0.0338,0.0338,0.017,0.0455,0.0455,0.0478,7.89e-10,7.89e-10,1.01e-09,3.19e-06,3.19e-06,1.18e-07,0,0,0,0,0,0,0,0
|
||||
17690000,0.706,0.000272,-0.0124,0.708,0.00436,0.000877,-0.000987,-0.00355,-0.00249,-365,-1.36e-05,-6.06e-05,4.32e-06,-3.01e-05,6.34e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000142,0.000138,0.000138,0.000136,0.0376,0.0376,0.0167,0.0517,0.0517,0.0478,7.89e-10,7.89e-10,9.86e-10,3.19e-06,3.19e-06,1.14e-07,0,0,0,0,0,0,0,0
|
||||
17790000,0.706,0.000178,-0.0124,0.708,0.00703,0.000567,-0.00219,-0.00231,-0.00213,-365,-1.34e-05,-6.06e-05,5e-06,-3.01e-05,6.06e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000141,0.000133,0.000133,0.000135,0.0331,0.0331,0.0162,0.0454,0.0454,0.0475,7.15e-10,7.15e-10,9.65e-10,3.18e-06,3.18e-06,1.08e-07,0,0,0,0,0,0,0,0
|
||||
17890000,0.706,0.000188,-0.0124,0.708,0.00851,-0.000176,-0.00206,-0.00153,-0.00208,-365,-1.34e-05,-6.06e-05,5.25e-06,-3.01e-05,6.06e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000141,0.000135,0.000135,0.000135,0.0368,0.0368,0.016,0.0516,0.0516,0.0475,7.15e-10,7.15e-10,9.41e-10,3.18e-06,3.18e-06,1.04e-07,0,0,0,0,0,0,0,0
|
||||
17990000,0.706,0.000129,-0.0125,0.708,0.0103,-0.00193,-0.000715,-0.000758,-0.0018,-365,-1.33e-05,-6.06e-05,5.15e-06,-2.98e-05,5.9e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00014,0.00013,0.000129,0.000135,0.0325,0.0325,0.0154,0.0453,0.0453,0.0466,6.47e-10,6.48e-10,9.18e-10,3.16e-06,3.17e-06,9.82e-08,0,0,0,0,0,0,0,0
|
||||
18090000,0.706,0.000134,-0.0125,0.708,0.0109,-0.00209,0.00168,0.000307,-0.00204,-365,-1.34e-05,-6.06e-05,4.69e-06,-2.99e-05,5.91e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.00014,0.000131,0.000131,0.000134,0.036,0.036,0.0153,0.0514,0.0514,0.0471,6.47e-10,6.48e-10,8.99e-10,3.16e-06,3.17e-06,9.52e-08,0,0,0,0,0,0,0,0
|
||||
18190000,0.706,9.82e-05,-0.0124,0.708,0.0116,-0.00104,0.00308,0.00123,-0.00158,-365,-1.34e-05,-6.05e-05,4.94e-06,-2.92e-05,5.93e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.00014,0.000126,0.000126,0.000134,0.0318,0.0318,0.0147,0.0452,0.0452,0.0463,5.87e-10,5.87e-10,8.78e-10,3.15e-06,3.15e-06,9.02e-08,0,0,0,0,0,0,0,0
|
||||
18290000,0.706,4e-05,-0.0124,0.708,0.0116,-0.00158,0.00426,0.00239,-0.00171,-365,-1.34e-05,-6.05e-05,4.74e-06,-2.93e-05,5.93e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000139,0.000128,0.000128,0.000134,0.0352,0.0352,0.0145,0.0513,0.0513,0.0462,5.87e-10,5.87e-10,8.57e-10,3.15e-06,3.15e-06,8.71e-08,0,0,0,0,0,0,0,0
|
||||
18390000,0.706,5.21e-05,-0.0124,0.708,0.013,4.76e-05,0.00551,0.00299,-0.0013,-365,-1.34e-05,-6.05e-05,5.08e-06,-2.88e-05,5.98e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000139,0.000124,0.000123,0.000133,0.0311,0.0311,0.014,0.0451,0.0451,0.0454,5.32e-10,5.32e-10,8.36e-10,3.14e-06,3.14e-06,8.27e-08,0,0,0,0,0,0,0,0
|
||||
18490000,0.706,6.76e-05,-0.0124,0.708,0.0138,0.000479,0.00517,0.00438,-0.00127,-365,-1.34e-05,-6.05e-05,5.15e-06,-2.88e-05,5.98e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000139,0.000125,0.000125,0.000133,0.0344,0.0344,0.0139,0.0511,0.0511,0.0458,5.32e-10,5.32e-10,8.19e-10,3.14e-06,3.14e-06,8.03e-08,0,0,0,0,0,0,0,0
|
||||
18590000,0.706,6.82e-05,-0.0123,0.708,0.0129,0.000693,0.00344,0.00332,-0.00109,-365,-1.36e-05,-6.05e-05,5.56e-06,-2.87e-05,6.27e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000139,0.000121,0.000121,0.000133,0.0304,0.0304,0.0134,0.045,0.045,0.045,4.82e-10,4.83e-10,8e-10,3.13e-06,3.13e-06,7.64e-08,0,0,0,0,0,0,0,0
|
||||
18690000,0.706,3.76e-05,-0.0123,0.708,0.0132,1.33e-05,0.0016,0.00462,-0.00103,-365,-1.36e-05,-6.05e-05,5.42e-06,-2.87e-05,6.27e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000138,0.000122,0.000122,0.000132,0.0335,0.0335,0.0133,0.0509,0.0509,0.0449,4.82e-10,4.83e-10,7.82e-10,3.13e-06,3.13e-06,7.39e-08,0,0,0,0,0,0,0,0
|
||||
18790000,0.706,6.4e-05,-0.0123,0.708,0.0117,0.000296,0.00138,0.00353,-0.00082,-365,-1.38e-05,-6.05e-05,5.27e-06,-2.86e-05,6.53e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000138,0.000118,0.000118,0.000132,0.0297,0.0297,0.0129,0.0449,0.0449,0.0447,4.38e-10,4.38e-10,7.66e-10,3.12e-06,3.12e-06,7.08e-08,0,0,0,0,0,0,0,0
|
||||
18890000,0.706,8.76e-05,-0.0123,0.708,0.0123,0.000806,0.00204,0.00473,-0.000731,-365,-1.37e-05,-6.05e-05,5.66e-06,-2.86e-05,6.53e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000138,0.00012,0.00012,0.000132,0.0327,0.0327,0.0128,0.0508,0.0508,0.0446,4.38e-10,4.38e-10,7.48e-10,3.12e-06,3.12e-06,6.85e-08,0,0,0,0,0,0,0,0
|
||||
18990000,0.707,7.3e-05,-0.0123,0.708,0.0136,0.00169,0.000837,0.00613,-0.000613,-365,-1.37e-05,-6.05e-05,5.82e-06,-2.87e-05,6.44e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000137,0.000116,0.000116,0.000132,0.029,0.029,0.0123,0.0448,0.0448,0.0438,3.98e-10,3.98e-10,7.31e-10,3.11e-06,3.11e-06,6.54e-08,0,0,0,0,0,0,0,0
|
||||
19090000,0.707,5.79e-05,-0.0122,0.708,0.0142,0.0023,0.00391,0.00751,-0.000386,-365,-1.37e-05,-6.05e-05,5.79e-06,-2.87e-05,6.44e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000137,0.000117,0.000117,0.000131,0.0319,0.0319,0.0123,0.0506,0.0506,0.0442,3.98e-10,3.98e-10,7.17e-10,3.11e-06,3.11e-06,6.37e-08,0,0,0,0,0,0,0,0
|
||||
19190000,0.707,5.9e-05,-0.0121,0.708,0.0143,0.00228,0.00399,0.00838,-0.000362,-365,-1.37e-05,-6.05e-05,5.94e-06,-2.9e-05,6.41e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000137,0.000114,0.000114,0.000131,0.0283,0.0283,0.0119,0.0446,0.0446,0.0435,3.62e-10,3.62e-10,7.01e-10,3.1e-06,3.1e-06,6.09e-08,0,0,0,0,0,0,0,0
|
||||
19290000,0.707,8.2e-05,-0.0121,0.708,0.0146,0.00154,0.00673,0.00979,-0.000153,-365,-1.37e-05,-6.05e-05,5.73e-06,-2.9e-05,6.41e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000136,0.000115,0.000115,0.000131,0.0311,0.0311,0.0117,0.0504,0.0504,0.0433,3.62e-10,3.62e-10,6.85e-10,3.1e-06,3.1e-06,5.91e-08,0,0,0,0,0,0,0,0
|
||||
19390000,0.707,9.08e-05,-0.012,0.708,0.0122,0.000596,0.0106,0.00784,-0.000191,-365,-1.39e-05,-6.06e-05,5.88e-06,-2.92e-05,6.7e-05,-0.00131,0.209,0.00206,0.432,0,0,0,0,0,0.000136,0.000111,0.000111,0.000131,0.0276,0.0276,0.0115,0.0445,0.0445,0.0431,3.3e-10,3.3e-10,6.72e-10,3.09e-06,3.09e-06,5.69e-08,0,0,0,0,0,0,0,0
|
||||
19490000,0.707,0.000114,-0.012,0.707,0.0112,-0.000104,0.00696,0.00899,-0.00017,-365,-1.39e-05,-6.06e-05,6.17e-06,-2.92e-05,6.7e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000136,0.000113,0.000112,0.00013,0.0303,0.0303,0.0113,0.0502,0.0502,0.043,3.3e-10,3.3e-10,6.57e-10,3.09e-06,3.09e-06,5.53e-08,0,0,0,0,0,0,0,0
|
||||
19590000,0.707,0.00016,-0.0119,0.707,0.00929,-0.00115,0.00631,0.00726,-0.000211,-365,-1.4e-05,-6.06e-05,6.55e-06,-2.92e-05,6.94e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000135,0.00011,0.000109,0.00013,0.0269,0.0269,0.011,0.0444,0.0444,0.0423,3.01e-10,3.01e-10,6.43e-10,3.08e-06,3.08e-06,5.31e-08,0,0,0,0,0,0,0,0
|
||||
19690000,0.707,0.00016,-0.012,0.707,0.00964,-0.00333,0.00785,0.00821,-0.00044,-365,-1.4e-05,-6.06e-05,6.32e-06,-2.92e-05,6.94e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000135,0.000111,0.00011,0.00013,0.0295,0.0295,0.0109,0.05,0.05,0.0422,3.01e-10,3.01e-10,6.29e-10,3.08e-06,3.08e-06,5.16e-08,0,0,0,0,0,0,0,0
|
||||
19790000,0.707,0.000225,-0.0119,0.707,0.00735,-0.00418,0.00835,0.00665,-0.000354,-365,-1.41e-05,-6.05e-05,6.33e-06,-2.87e-05,7.14e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000135,0.000108,0.000108,0.000129,0.0263,0.0263,0.0106,0.0442,0.0442,0.042,2.75e-10,2.75e-10,6.17e-10,3.07e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19890000,0.707,0.000172,-0.0119,0.707,0.0061,-0.00445,0.00953,0.00733,-0.0008,-365,-1.41e-05,-6.05e-05,6.74e-06,-2.87e-05,7.13e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000135,0.000109,0.000109,0.000129,0.0288,0.0288,0.0105,0.0498,0.0498,0.0419,2.75e-10,2.76e-10,6.04e-10,3.07e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19990000,0.707,0.000155,-0.0119,0.707,0.00368,-0.00516,0.0123,0.00596,-0.000671,-365,-1.42e-05,-6.05e-05,7.3e-06,-2.81e-05,7.26e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000134,0.000106,0.000106,0.000129,0.0256,0.0256,0.0102,0.0441,0.0441,0.0412,2.52e-10,2.52e-10,5.91e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20090000,0.707,0.00015,-0.0119,0.707,0.00344,-0.0071,0.0126,0.00632,-0.00127,-365,-1.42e-05,-6.05e-05,7.76e-06,-2.81e-05,7.26e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000134,0.000107,0.000107,0.000129,0.028,0.028,0.0102,0.0495,0.0495,0.0415,2.52e-10,2.52e-10,5.8e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20190000,0.707,0.00025,-0.0118,0.707,0.00114,-0.00779,0.0149,0.00406,-0.000998,-365,-1.43e-05,-6.05e-05,7.95e-06,-2.7e-05,7.47e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000134,0.000104,0.000104,0.000128,0.025,0.025,0.00991,0.0439,0.0439,0.0409,2.31e-10,2.32e-10,5.68e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20290000,0.707,0.000211,-0.0118,0.707,-1.2e-05,-0.00937,0.0129,0.00411,-0.00185,-365,-1.43e-05,-6.05e-05,8.08e-06,-2.71e-05,7.47e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000133,0.000105,0.000105,0.000128,0.0273,0.0273,0.00982,0.0493,0.0493,0.0408,2.32e-10,2.32e-10,5.56e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20390000,0.707,0.000227,-0.0119,0.707,-0.00244,-0.00995,0.015,0.00225,-0.00145,-365,-1.44e-05,-6.04e-05,8.06e-06,-2.57e-05,7.62e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000133,0.000103,0.000103,0.000128,0.0244,0.0244,0.00963,0.0437,0.0437,0.0406,2.13e-10,2.13e-10,5.46e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20490000,0.707,0.000282,-0.0119,0.707,-0.00292,-0.0106,0.0148,0.00197,-0.00248,-365,-1.44e-05,-6.04e-05,7.87e-06,-2.57e-05,7.62e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000133,0.000104,0.000104,0.000128,0.0266,0.0266,0.00955,0.0491,0.0491,0.0405,2.13e-10,2.13e-10,5.35e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20590000,0.707,0.0003,-0.0119,0.707,-0.00253,-0.0106,0.0117,0.00169,-0.00198,-365,-1.44e-05,-6.03e-05,7.7e-06,-2.44e-05,7.6e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000133,0.000102,0.000101,0.000127,0.0238,0.0238,0.00931,0.0436,0.0436,0.0399,1.96e-10,1.96e-10,5.24e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20690000,0.707,0.000326,-0.012,0.707,-0.00254,-0.012,0.0132,0.00143,-0.0031,-365,-1.44e-05,-6.03e-05,7.8e-06,-2.44e-05,7.6e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000132,0.000102,0.000102,0.000127,0.0259,0.0259,0.0093,0.0488,0.0488,0.0402,1.96e-10,1.96e-10,5.15e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20790000,0.708,0.000353,-0.012,0.707,-0.00362,-0.0111,0.0135,0.0012,-0.00245,-365,-1.44e-05,-6.02e-05,7.84e-06,-2.29e-05,7.58e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000132,0.0001,0.0001,0.000127,0.0232,0.0232,0.00908,0.0434,0.0434,0.0397,1.81e-10,1.81e-10,5.04e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20890000,0.708,0.000339,-0.012,0.706,-0.00408,-0.0134,0.0127,0.000819,-0.00368,-365,-1.44e-05,-6.02e-05,8.1e-06,-2.3e-05,7.58e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000132,0.000101,0.000101,0.000126,0.0253,0.0253,0.00902,0.0486,0.0486,0.0395,1.81e-10,1.81e-10,4.94e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20990000,0.708,0.00034,-0.012,0.706,-0.00426,-0.0142,0.0132,0.00249,-0.00301,-365,-1.43e-05,-6.01e-05,8.1e-06,-2.13e-05,7.47e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000132,9.91e-05,9.9e-05,0.000126,0.0227,0.0227,0.00883,0.0432,0.0432,0.039,1.68e-10,1.68e-10,4.85e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21090000,0.708,0.000338,-0.012,0.706,-0.00444,-0.0166,0.0137,0.00206,-0.00455,-365,-1.43e-05,-6.01e-05,8.25e-06,-2.14e-05,7.47e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000131,9.97e-05,9.96e-05,0.000126,0.0246,0.0246,0.00883,0.0483,0.0483,0.0393,1.68e-10,1.68e-10,4.76e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21190000,0.708,0.000373,-0.012,0.706,-0.00362,-0.0154,0.0127,0.00358,-0.0037,-365,-1.42e-05,-6e-05,8.12e-06,-1.95e-05,7.36e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000131,9.8e-05,9.79e-05,0.000126,0.0221,0.0221,0.00865,0.043,0.043,0.0388,1.55e-10,1.55e-10,4.67e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21290000,0.708,0.000413,-0.012,0.706,-0.00423,-0.0176,0.0149,0.00319,-0.00534,-365,-1.42e-05,-6e-05,8.44e-06,-1.95e-05,7.36e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000131,9.86e-05,9.85e-05,0.000126,0.024,0.024,0.00861,0.0481,0.0481,0.0386,1.55e-10,1.55e-10,4.58e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21390000,0.708,0.000455,-0.012,0.706,-0.005,-0.0169,0.0147,0.00269,-0.00333,-365,-1.42e-05,-5.99e-05,8.21e-06,-1.66e-05,7.33e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000131,9.7e-05,9.69e-05,0.000125,0.0216,0.0216,0.00849,0.0429,0.0429,0.0385,1.44e-10,1.44e-10,4.5e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21490000,0.708,0.000462,-0.012,0.706,-0.00554,-0.0179,0.0143,0.00214,-0.00505,-365,-1.42e-05,-5.99e-05,8.31e-06,-1.66e-05,7.33e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.75e-05,9.75e-05,0.000125,0.0235,0.0235,0.00846,0.0478,0.0478,0.0384,1.44e-10,1.44e-10,4.41e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21590000,0.708,0.000484,-0.012,0.706,-0.00603,-0.0153,0.0141,0.00178,-0.00307,-365,-1.42e-05,-5.97e-05,8.2e-06,-1.38e-05,7.29e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.6e-05,9.6e-05,0.000125,0.0211,0.0211,0.00831,0.0427,0.0427,0.0379,1.34e-10,1.34e-10,4.33e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21690000,0.708,0.000493,-0.012,0.706,-0.00593,-0.0163,0.0158,0.00117,-0.00466,-365,-1.42e-05,-5.97e-05,8.28e-06,-1.39e-05,7.29e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.66e-05,9.65e-05,0.000125,0.0229,0.0229,0.00834,0.0476,0.0476,0.0382,1.35e-10,1.35e-10,4.26e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21790000,0.708,0.000504,-0.0121,0.706,-0.00651,-0.0113,0.0143,-5.68e-05,-0.000654,-365,-1.42e-05,-5.95e-05,8.03e-06,-9.65e-06,7.33e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.52e-05,9.51e-05,0.000124,0.0206,0.0206,0.0082,0.0425,0.0425,0.0377,1.25e-10,1.26e-10,4.18e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21890000,0.708,0.000508,-0.012,0.706,-0.0065,-0.0116,0.0147,-0.00071,-0.0018,-365,-1.42e-05,-5.95e-05,7.98e-06,-9.69e-06,7.33e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.57e-05,9.56e-05,0.000124,0.0224,0.0224,0.00818,0.0473,0.0473,0.0376,1.26e-10,1.26e-10,4.1e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21990000,0.708,0.000554,-0.0121,0.706,-0.00697,-0.00894,0.0155,-0.00159,0.00158,-365,-1.42e-05,-5.93e-05,7.93e-06,-6.19e-06,7.35e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000129,9.44e-05,9.43e-05,0.000124,0.0202,0.0202,0.00811,0.0423,0.0423,0.0375,1.17e-10,1.17e-10,4.03e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22090000,0.708,0.000565,-0.0121,0.706,-0.00732,-0.00807,0.0139,-0.0023,0.000743,-365,-1.42e-05,-5.93e-05,7.85e-06,-6.22e-06,7.35e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000129,9.48e-05,9.48e-05,0.000124,0.0219,0.0219,0.0081,0.0471,0.0471,0.0375,1.17e-10,1.18e-10,3.96e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22190000,0.708,0.000536,-0.0121,0.706,-0.0071,-0.00718,0.0143,-0.00192,0.000684,-365,-1.42e-05,-5.92e-05,7.86e-06,-5.68e-06,7.28e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000129,9.36e-05,9.36e-05,0.000124,0.0197,0.0197,0.00799,0.0421,0.0421,0.037,1.1e-10,1.1e-10,3.89e-10,3.02e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22290000,0.708,0.000576,-0.0121,0.706,-0.00846,-0.00791,0.0143,-0.00268,-7.9e-05,-365,-1.42e-05,-5.92e-05,7.7e-06,-5.71e-06,7.29e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000129,9.41e-05,9.4e-05,0.000123,0.0214,0.0214,0.00799,0.0468,0.0468,0.0369,1.1e-10,1.1e-10,3.82e-10,3.02e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22390000,0.708,0.00055,-0.0121,0.706,-0.009,-0.0074,0.0161,-0.0023,-8.38e-05,-365,-1.42e-05,-5.92e-05,7.75e-06,-5.14e-06,7.21e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.29e-05,9.29e-05,0.000123,0.0193,0.0193,0.00793,0.0419,0.0419,0.0369,1.03e-10,1.03e-10,3.76e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22490000,0.708,0.000555,-0.012,0.706,-0.00967,-0.00731,0.0173,-0.00323,-0.000839,-365,-1.42e-05,-5.92e-05,7.68e-06,-5.12e-06,7.21e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.34e-05,9.33e-05,0.000123,0.0209,0.0209,0.00794,0.0466,0.0466,0.0368,1.03e-10,1.04e-10,3.69e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22590000,0.708,0.000535,-0.0121,0.706,-0.00936,-0.00685,0.0164,-0.0035,0.00023,-365,-1.41e-05,-5.91e-05,7.67e-06,-3.93e-06,7.1e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.23e-05,9.22e-05,0.000123,0.0189,0.0189,0.00784,0.0418,0.0418,0.0364,9.73e-11,9.74e-11,3.62e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22690000,0.708,0.000571,-0.0121,0.706,-0.0106,-0.00658,0.0176,-0.00449,-0.000437,-365,-1.41e-05,-5.91e-05,7.75e-06,-3.94e-06,7.1e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.27e-05,9.26e-05,0.000123,0.0205,0.0205,0.0079,0.0464,0.0464,0.0367,9.74e-11,9.75e-11,3.57e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22790000,0.708,0.000553,-0.0121,0.706,-0.0111,-0.00539,0.0187,-0.00559,-0.000347,-365,-1.41e-05,-5.91e-05,7.31e-06,-3.44e-06,7.06e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.17e-05,9.16e-05,0.000122,0.0186,0.0186,0.00781,0.0416,0.0416,0.0363,9.18e-11,9.19e-11,3.5e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22890000,0.708,0.000563,-0.012,0.706,-0.0125,-0.00501,0.0204,-0.00676,-0.000871,-365,-1.41e-05,-5.91e-05,7.22e-06,-3.43e-06,7.06e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.21e-05,9.2e-05,0.000122,0.02,0.02,0.00783,0.0461,0.0461,0.0363,9.19e-11,9.2e-11,3.44e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22990000,0.708,0.000547,-0.0121,0.706,-0.0124,-0.00548,0.0214,-0.00748,-0.000774,-365,-1.41e-05,-5.91e-05,7.32e-06,-3.08e-06,7e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.12e-05,9.11e-05,0.000122,0.0182,0.0182,0.00779,0.0414,0.0414,0.0362,8.68e-11,8.69e-11,3.39e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23090000,0.708,0.000512,-0.012,0.706,-0.0132,-0.00547,0.022,-0.00878,-0.00131,-365,-1.41e-05,-5.91e-05,7.03e-06,-3.03e-06,7e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.15e-05,9.14e-05,0.000122,0.0196,0.0196,0.00782,0.0459,0.0459,0.0362,8.69e-11,8.7e-11,3.33e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23190000,0.708,0.000578,-0.012,0.706,-0.0146,-0.00645,0.0236,-0.0121,-0.00118,-365,-1.41e-05,-5.91e-05,6.97e-06,-2.55e-06,7.11e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.06e-05,9.06e-05,0.000122,0.0179,0.0179,0.00774,0.0412,0.0412,0.0359,8.23e-11,8.23e-11,3.27e-10,3.01e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23290000,0.708,0.000517,-0.012,0.706,-0.0153,-0.00769,0.0239,-0.0135,-0.0019,-365,-1.41e-05,-5.91e-05,6.95e-06,-2.58e-06,7.12e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.1e-05,9.09e-05,0.000121,0.0193,0.0193,0.00781,0.0457,0.0457,0.0361,8.24e-11,8.24e-11,3.22e-10,3.01e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23390000,0.708,0.000607,-0.0119,0.706,-0.0162,-0.00793,0.0215,-0.016,-0.00168,-365,-1.42e-05,-5.9e-05,6.89e-06,-2.06e-06,7.2e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,9.02e-05,9.01e-05,0.000121,0.0175,0.0175,0.00774,0.041,0.041,0.0358,7.81e-11,7.81e-11,3.17e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23490000,0.708,0.003,-0.00951,0.706,-0.0233,-0.00877,-0.012,-0.018,-0.00253,-365,-1.42e-05,-5.9e-05,6.97e-06,-2.1e-06,7.2e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,9.05e-05,9.04e-05,0.000121,0.0189,0.0189,0.00778,0.0454,0.0454,0.0358,7.82e-11,7.82e-11,3.12e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23590000,0.708,0.00823,-0.0017,0.706,-0.0336,-0.00749,-0.0435,-0.0167,-0.00122,-365,-1.41e-05,-5.9e-05,6.82e-06,-3.95e-07,7.03e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,8.97e-05,8.96e-05,0.000121,0.0173,0.0173,0.00771,0.0409,0.0409,0.0355,7.43e-11,7.43e-11,3.06e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23690000,0.707,0.00786,0.00407,0.707,-0.0648,-0.016,-0.094,-0.0215,-0.00232,-365,-1.41e-05,-5.9e-05,6.77e-06,-3.16e-07,7.02e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,9e-05,8.99e-05,0.000121,0.0187,0.0187,0.00779,0.0452,0.0452,0.0358,7.44e-11,7.44e-11,3.02e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23790000,0.707,0.00493,0.00072,0.707,-0.0887,-0.0272,-0.148,-0.0207,-0.00167,-365,-1.39e-05,-5.89e-05,6.78e-06,1.56e-06,6.52e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.92e-05,8.91e-05,0.000121,0.0172,0.0172,0.00773,0.0407,0.0407,0.0355,7.07e-11,7.08e-11,2.97e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23890000,0.707,0.0023,-0.00536,0.708,-0.105,-0.0362,-0.201,-0.0306,-0.00487,-365,-1.39e-05,-5.89e-05,6.69e-06,1.68e-06,6.52e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.95e-05,8.94e-05,0.000121,0.0186,0.0186,0.00777,0.045,0.045,0.0354,7.08e-11,7.09e-11,2.92e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23990000,0.707,0.000895,-0.00996,0.708,-0.106,-0.0395,-0.254,-0.0341,-0.0081,-366,-1.37e-05,-5.89e-05,6.73e-06,2.64e-06,6.18e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.87e-05,8.86e-05,0.00012,0.017,0.017,0.00775,0.0406,0.0406,0.0355,6.75e-11,6.75e-11,2.88e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24090000,0.707,0.00218,-0.00869,0.708,-0.108,-0.0398,-0.302,-0.0448,-0.0121,-366,-1.37e-05,-5.89e-05,6.82e-06,2.61e-06,6.18e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.9e-05,8.89e-05,0.00012,0.0184,0.0184,0.00779,0.0449,0.0449,0.0355,6.76e-11,6.76e-11,2.83e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24190000,0.707,0.00325,-0.00644,0.708,-0.11,-0.0408,-0.35,-0.0463,-0.0141,-366,-1.36e-05,-5.88e-05,6.82e-06,4.44e-06,5.72e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.82e-05,8.81e-05,0.00012,0.0168,0.0168,0.00773,0.0404,0.0404,0.0352,6.45e-11,6.45e-11,2.79e-10,3e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24290000,0.707,0.00374,-0.00562,0.708,-0.121,-0.0447,-0.405,-0.0579,-0.0184,-366,-1.36e-05,-5.88e-05,6.72e-06,4.57e-06,5.73e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.84e-05,8.83e-05,0.00012,0.0182,0.0182,0.00782,0.0447,0.0447,0.0355,6.46e-11,6.46e-11,2.75e-10,3e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24390000,0.706,0.00379,-0.00583,0.708,-0.129,-0.052,-0.457,-0.0638,-0.0299,-366,-1.35e-05,-5.89e-05,6.53e-06,1.87e-06,5.44e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.76e-05,8.75e-05,0.00012,0.0167,0.0167,0.00776,0.0403,0.0403,0.0352,6.17e-11,6.17e-11,2.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24490000,0.706,0.00466,-0.00168,0.708,-0.143,-0.0573,-0.507,-0.0773,-0.0353,-366,-1.35e-05,-5.89e-05,6.47e-06,2.02e-06,5.44e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.79e-05,8.78e-05,0.00012,0.018,0.018,0.00781,0.0445,0.0445,0.0352,6.18e-11,6.18e-11,2.66e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24590000,0.707,0.00511,0.00194,0.708,-0.157,-0.0684,-0.558,-0.0808,-0.0446,-366,-1.33e-05,-5.89e-05,6.6e-06,7.54e-07,4.82e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.7e-05,8.69e-05,0.00012,0.0165,0.0165,0.00779,0.0402,0.0402,0.0353,5.92e-11,5.92e-11,2.62e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24690000,0.707,0.00515,0.00289,0.708,-0.182,-0.0822,-0.641,-0.0977,-0.0521,-366,-1.33e-05,-5.9e-05,6.69e-06,5.56e-07,4.82e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.73e-05,8.71e-05,0.000119,0.0179,0.0179,0.00784,0.0444,0.0444,0.0353,5.93e-11,5.93e-11,2.58e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24790000,0.706,0.00486,0.00152,0.708,-0.198,-0.0945,-0.724,-0.105,-0.0632,-366,-1.3e-05,-5.89e-05,6.51e-06,4.59e-06,4.07e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.64e-05,8.63e-05,0.000119,0.0165,0.0164,0.00778,0.0401,0.0401,0.035,5.68e-11,5.68e-11,2.54e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24890000,0.706,0.00661,0.00321,0.708,-0.221,-0.106,-0.748,-0.126,-0.0732,-366,-1.3e-05,-5.89e-05,6.38e-06,4.8e-06,4.07e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000123,8.66e-05,8.65e-05,0.000119,0.0177,0.0177,0.00783,0.0443,0.0443,0.0351,5.69e-11,5.69e-11,2.5e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24990000,0.706,0.00842,0.00481,0.708,-0.238,-0.114,-0.805,-0.129,-0.0812,-366,-1.27e-05,-5.88e-05,6.19e-06,1.3e-05,2.69e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000123,8.57e-05,8.56e-05,0.000119,0.0163,0.0162,0.00781,0.04,0.04,0.0351,5.46e-11,5.46e-11,2.47e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25090000,0.706,0.00872,0.0042,0.708,-0.269,-0.125,-0.854,-0.154,-0.0931,-366,-1.27e-05,-5.88e-05,6.01e-06,1.34e-05,2.68e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000123,8.6e-05,8.58e-05,0.000119,0.0175,0.0175,0.00786,0.0441,0.0441,0.0352,5.47e-11,5.47e-11,2.43e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25190000,0.706,0.00818,0.00279,0.708,-0.291,-0.137,-0.904,-0.173,-0.119,-366,-1.26e-05,-5.89e-05,6.07e-06,1e-05,2.2e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000123,8.51e-05,8.49e-05,0.000119,0.0161,0.016,0.00781,0.0399,0.0399,0.0349,5.26e-11,5.26e-11,2.4e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25290000,0.706,0.0101,0.00961,0.708,-0.321,-0.146,-0.958,-0.204,-0.133,-366,-1.26e-05,-5.89e-05,6.05e-06,1.01e-05,2.2e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000123,8.53e-05,8.51e-05,0.000119,0.0173,0.0173,0.0079,0.044,0.044,0.0353,5.27e-11,5.27e-11,2.36e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25390000,0.706,0.0114,0.016,0.708,-0.351,-0.166,-1.01,-0.216,-0.153,-366,-1.23e-05,-5.89e-05,6.06e-06,1.21e-05,7.73e-06,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.44e-05,8.42e-05,0.000118,0.0159,0.0159,0.00784,0.0398,0.0398,0.035,5.07e-11,5.07e-11,2.33e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25490000,0.706,0.0116,0.0172,0.707,-0.4,-0.19,-1.06,-0.253,-0.171,-366,-1.23e-05,-5.89e-05,6.11e-06,1.19e-05,7.82e-06,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.46e-05,8.45e-05,0.000118,0.0172,0.0171,0.00789,0.0439,0.0439,0.0351,5.08e-11,5.08e-11,2.29e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25590000,0.707,0.011,0.0153,0.707,-0.439,-0.219,-1.12,-0.28,-0.208,-367,-1.21e-05,-5.91e-05,6.08e-06,9.35e-06,-6.84e-07,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.37e-05,8.36e-05,0.000118,0.0158,0.0157,0.00788,0.0397,0.0397,0.0351,4.9e-11,4.9e-11,2.26e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25690000,0.706,0.0146,0.022,0.707,-0.488,-0.239,-1.17,-0.326,-0.231,-367,-1.21e-05,-5.91e-05,6.08e-06,9.23e-06,-4.7e-07,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.39e-05,8.38e-05,0.000118,0.017,0.0169,0.00793,0.0437,0.0437,0.0352,4.91e-11,4.91e-11,2.23e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25790000,0.706,0.0171,0.0282,0.707,-0.533,-0.266,-1.22,-0.343,-0.26,-367,-1.16e-05,-5.9e-05,6.15e-06,1.7e-05,-2.47e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.3e-05,8.29e-05,0.000118,0.0157,0.0155,0.00787,0.0396,0.0396,0.0349,4.74e-11,4.74e-11,2.2e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25890000,0.706,0.0174,0.0286,0.707,-0.604,-0.296,-1.27,-0.4,-0.288,-367,-1.16e-05,-5.9e-05,6.26e-06,1.67e-05,-2.48e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.32e-05,8.3e-05,0.000118,0.0169,0.0167,0.00796,0.0436,0.0436,0.0353,4.75e-11,4.75e-11,2.17e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25990000,0.706,0.0163,0.0254,0.707,-0.656,-0.332,-1.32,-0.439,-0.344,-367,-1.12e-05,-5.92e-05,6.28e-06,1.33e-05,-4.03e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000121,8.23e-05,8.22e-05,0.000117,0.0156,0.0154,0.0079,0.0395,0.0395,0.0351,4.59e-11,4.59e-11,2.14e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26090000,0.702,0.021,0.0353,0.711,-0.723,-0.359,-1.34,-0.508,-0.378,-367,-1.13e-05,-5.92e-05,6.07e-06,1.36e-05,-3.95e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000121,8.25e-05,8.24e-05,0.000118,0.0167,0.0165,0.00796,0.0435,0.0435,0.0351,4.6e-11,4.6e-11,2.11e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26190000,0.701,0.0232,0.0446,0.712,-0.776,-0.394,-1.31,-0.533,-0.422,-367,-1.06e-05,-5.91e-05,6.07e-06,2.46e-05,-7.55e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.16e-05,8.15e-05,0.000118,0.0153,0.0151,0.0079,0.0394,0.0394,0.0349,4.46e-11,4.46e-11,2.08e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26290000,0.701,0.0241,0.0469,0.711,-0.869,-0.436,-1.3,-0.616,-0.463,-368,-1.06e-05,-5.91e-05,5.97e-06,2.46e-05,-7.48e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.18e-05,8.17e-05,0.000118,0.0164,0.0161,0.00799,0.0434,0.0433,0.0352,4.47e-11,4.47e-11,2.05e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26390000,0.702,0.023,0.0435,0.711,-0.945,-0.492,-1.31,-0.679,-0.548,-368,-1.03e-05,-5.94e-05,5.98e-06,1.26e-05,-8.74e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.11e-05,8.09e-05,0.000117,0.0151,0.0148,0.00793,0.0393,0.0392,0.035,4.34e-11,4.34e-11,2.02e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26490000,0.702,0.0308,0.0593,0.709,-1.04,-0.531,-1.31,-0.778,-0.599,-368,-1.03e-05,-5.94e-05,5.94e-06,1.25e-05,-8.68e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.12e-05,8.11e-05,0.000117,0.0163,0.0158,0.00799,0.0432,0.0431,0.0351,4.35e-11,4.34e-11,1.99e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26590000,0.702,0.0369,0.0752,0.707,-1.14,-0.586,-1.3,-0.822,-0.665,-368,-9.5e-06,-5.93e-05,5.58e-06,2.15e-05,-0.00012,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.05e-05,8.04e-05,0.000117,0.0151,0.0146,0.00797,0.0392,0.0391,0.0351,4.23e-11,4.22e-11,1.97e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26690000,0.703,0.0381,0.078,0.706,-1.28,-0.648,-1.29,-0.943,-0.727,-368,-9.49e-06,-5.93e-05,5.65e-06,2.11e-05,-0.00012,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000119,8.06e-05,8.06e-05,0.000116,0.0163,0.0156,0.00803,0.0431,0.043,0.0352,4.23e-11,4.23e-11,1.94e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26790000,0.704,0.0358,0.0725,0.705,-1.4,-0.73,-1.29,-1.04,-0.854,-368,-9.05e-06,-5.98e-05,5.48e-06,6.01e-08,-0.000139,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000119,8e-05,7.99e-05,0.000116,0.0151,0.0144,0.00797,0.0391,0.039,0.035,4.12e-11,4.12e-11,1.91e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26890000,0.704,0.0447,0.0944,0.703,-1.54,-0.789,-1.3,-1.18,-0.93,-368,-9.05e-06,-5.98e-05,5.52e-06,-3.56e-07,-0.000138,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000119,8.01e-05,8.01e-05,0.000116,0.0164,0.0154,0.00807,0.0429,0.0428,0.0353,4.13e-11,4.13e-11,1.89e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26990000,0.703,0.051,0.116,0.699,-1.68,-0.871,-1.28,-1.24,-1.03,-368,-7.89e-06,-5.97e-05,5.42e-06,7.1e-06,-0.000186,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000119,7.93e-05,7.96e-05,0.000115,0.0153,0.0142,0.00802,0.039,0.0388,0.0351,4.03e-11,4.02e-11,1.86e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27090000,0.704,0.0519,0.12,0.698,-1.88,-0.962,-1.25,-1.42,-1.12,-369,-7.89e-06,-5.97e-05,5.35e-06,7.08e-06,-0.000184,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000119,7.94e-05,7.98e-05,0.000115,0.0167,0.0153,0.00809,0.0428,0.0426,0.0352,4.04e-11,4.03e-11,1.84e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27190000,0.706,0.0485,0.109,0.698,-2.08,-1.03,-1.23,-1.62,-1.2,-369,-7.86e-06,-5.94e-05,5.44e-06,1.61e-05,-0.00018,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000118,7.93e-05,7.94e-05,0.000114,0.0171,0.0154,0.00809,0.0453,0.045,0.0353,4e-11,3.98e-11,1.82e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27290000,0.707,0.0428,0.0941,0.699,-2.24,-1.1,-1.22,-1.84,-1.31,-369,-7.85e-06,-5.94e-05,5.45e-06,1.56e-05,-0.000179,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000118,7.95e-05,7.94e-05,0.000114,0.0185,0.0165,0.00816,0.0498,0.0494,0.0353,4.01e-11,3.99e-11,1.79e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27390000,0.708,0.0365,0.0778,0.701,-2.34,-1.13,-1.22,-2.03,-1.39,-369,-7.31e-06,-5.88e-05,5.55e-06,3.28e-05,-0.000189,-0.00125,0.209,0.00206,0.432,0,0,0,0,0,0.000117,7.94e-05,7.91e-05,0.000113,0.0185,0.0165,0.00812,0.0524,0.0519,0.0351,3.96e-11,3.94e-11,1.77e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27490000,0.709,0.0308,0.0627,0.702,-2.42,-1.17,-1.2,-2.27,-1.5,-369,-7.31e-06,-5.88e-05,5.46e-06,3.22e-05,-0.000186,-0.00125,0.209,0.00206,0.432,0,0,0,0,0,0.000117,7.96e-05,7.93e-05,0.000113,0.0198,0.0176,0.00819,0.0575,0.0568,0.0352,3.97e-11,3.95e-11,1.74e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27590000,0.709,0.0262,0.0504,0.703,-2.49,-1.19,-1.21,-2.53,-1.61,-369,-7.54e-06,-5.86e-05,5.56e-06,2.99e-05,-0.000172,-0.00124,0.209,0.00206,0.432,0,0,0,0,0,0.000116,7.95e-05,7.91e-05,0.000112,0.0196,0.0174,0.00819,0.06,0.0594,0.0352,3.92e-11,3.89e-11,1.72e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27690000,0.709,0.0255,0.0487,0.703,-2.53,-1.2,-1.21,-2.78,-1.73,-369,-7.54e-06,-5.86e-05,5.41e-06,2.95e-05,-0.00017,-0.00124,0.209,0.00206,0.432,0,0,0,0,0,0.000115,7.96e-05,7.92e-05,0.000112,0.0208,0.0185,0.00827,0.0658,0.0649,0.0353,3.93e-11,3.9e-11,1.7e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27790000,0.708,0.0259,0.0504,0.703,-2.57,-1.21,-1.21,-3.04,-1.83,-369,-7.63e-06,-5.83e-05,5.31e-06,2.94e-05,-0.000159,-0.00124,0.209,0.00206,0.432,0,0,0,0,0,0.000114,7.94e-05,7.9e-05,0.000111,0.0203,0.0183,0.00823,0.0682,0.0674,0.0351,3.88e-11,3.85e-11,1.68e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27890000,0.708,0.0253,0.0485,0.704,-2.61,-1.23,-1.21,-3.3,-1.95,-370,-7.63e-06,-5.83e-05,5.29e-06,2.8e-05,-0.000156,-0.00123,0.209,0.00206,0.432,0,0,0,0,0,0.000114,7.96e-05,7.91e-05,0.000111,0.0216,0.0194,0.00836,0.0746,0.0734,0.0355,3.89e-11,3.86e-11,1.66e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27990000,0.709,0.0244,0.0448,0.704,-2.66,-1.24,-1.21,-3.6,-2.07,-370,-8.01e-06,-5.81e-05,5.38e-06,2.25e-05,-0.000142,-0.00122,0.209,0.00206,0.432,0,0,0,0,0,0.000113,7.94e-05,7.89e-05,0.000111,0.021,0.0191,0.00833,0.0769,0.0758,0.0353,3.85e-11,3.8e-11,1.64e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28090000,0.708,0.0302,0.0581,0.703,-2.7,-1.25,-1.22,-3.87,-2.19,-370,-8.01e-06,-5.81e-05,5.12e-06,2.18e-05,-0.000138,-0.00122,0.209,0.00206,0.432,0,0,0,0,0,0.000113,7.95e-05,7.89e-05,0.000111,0.0223,0.0202,0.00842,0.0839,0.0824,0.0353,3.85e-11,3.81e-11,1.62e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28190000,0.708,0.0353,0.0714,0.702,-2.76,-1.27,-0.946,-4.17,-2.3,-370,-8.26e-06,-5.8e-05,5.17e-06,1.74e-05,-0.000126,-0.00121,0.209,0.00206,0.432,0,0,0,0,0,0.000112,7.92e-05,7.86e-05,0.00011,0.0214,0.0196,0.00845,0.0859,0.0846,0.0354,3.8e-11,3.75e-11,1.6e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28290000,0.71,0.0276,0.0544,0.702,-2.76,-1.28,-0.083,-4.44,-2.43,-370,-8.26e-06,-5.79e-05,4.98e-06,1.61e-05,-0.00012,-0.00121,0.209,0.00206,0.432,0,0,0,0,0,0.000112,7.95e-05,7.88e-05,0.00011,0.0219,0.0202,0.00859,0.0933,0.0917,0.0355,3.81e-11,3.75e-11,1.58e-10,2.95e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28390000,0.712,0.0115,0.023,0.702,-2.78,-1.28,0.777,-4.76,-2.55,-370,-8.69e-06,-5.78e-05,4.93e-06,7.46e-07,-0.000148,-0.0012,0.209,0.00206,0.432,0,0,0,0,0,0.000111,7.98e-05,7.93e-05,0.000108,0.021,0.0196,0.00869,0.0952,0.0937,0.0356,3.77e-11,3.7e-11,1.56e-10,2.94e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28490000,0.712,0.00265,0.00476,0.702,-2.74,-1.27,1.07,-5.04,-2.68,-370,-8.68e-06,-5.78e-05,4.88e-06,-1.88e-06,-0.000142,-0.0012,0.209,0.00206,0.432,0,0,0,0,0,0.000111,8.01e-05,7.98e-05,0.000108,0.022,0.0208,0.00882,0.103,0.101,0.036,3.78e-11,3.71e-11,1.54e-10,2.94e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28590000,0.711,0.000808,0.00121,0.703,-2.69,-1.25,0.969,-5.36,-2.79,-370,-9.13e-06,-5.77e-05,4.96e-06,-2.34e-05,-0.000208,-0.00119,0.209,0.00206,0.432,0,0,0,0,0,0.00011,8.03e-05,8e-05,0.000108,0.0212,0.0203,0.0089,0.105,0.103,0.0361,3.74e-11,3.66e-11,1.52e-10,2.93e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28690000,0.71,0.000108,0.000302,0.704,-2.62,-1.23,0.972,-5.63,-2.92,-370,-9.13e-06,-5.77e-05,4.89e-06,-2.77e-05,-0.000197,-0.00119,0.209,0.00206,0.432,0,0,0,0,0,0.00011,8.04e-05,8.01e-05,0.000108,0.0222,0.0215,0.00899,0.113,0.111,0.0362,3.75e-11,3.67e-11,1.5e-10,2.93e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28790000,0.709,-0.000208,1.86e-05,0.705,-2.58,-1.21,0.976,-5.94,-3.03,-370,-9.63e-06,-5.76e-05,4.82e-06,-5.36e-05,-0.000254,-0.00118,0.209,0.00206,0.432,0,0,0,0,0,0.000109,8.06e-05,8.02e-05,0.000107,0.0213,0.0209,0.00893,0.114,0.112,0.036,3.7e-11,3.61e-11,1.49e-10,2.91e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28890000,0.709,-0.000222,0.000243,0.705,-2.51,-1.19,0.965,-6.2,-3.15,-370,-9.63e-06,-5.76e-05,4.78e-06,-5.82e-05,-0.000242,-0.00117,0.209,0.00206,0.432,0,0,0,0,0,0.000109,8.07e-05,8.03e-05,0.000107,0.0224,0.0221,0.00906,0.123,0.121,0.0364,3.71e-11,3.62e-11,1.47e-10,2.91e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28990000,0.708,-6.16e-05,0.000643,0.706,-2.49,-1.17,0.959,-6.53,-3.26,-370,-1.03e-05,-5.75e-05,4.65e-06,-7.51e-05,-0.000311,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.09e-05,8.03e-05,0.000107,0.0216,0.0215,0.00899,0.124,0.122,0.0361,3.67e-11,3.57e-11,1.45e-10,2.9e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29090000,0.708,9.56e-05,0.00105,0.706,-2.42,-1.16,0.95,-6.77,-3.37,-369,-1.03e-05,-5.75e-05,4.56e-06,-8.02e-05,-0.000298,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.1e-05,8.04e-05,0.000107,0.0227,0.0228,0.00907,0.133,0.131,0.0362,3.68e-11,3.58e-11,1.44e-10,2.9e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29190000,0.708,0.000294,0.00145,0.706,-2.38,-1.14,0.943,-7.06,-3.48,-369,-1.07e-05,-5.74e-05,4.61e-06,-9.7e-05,-0.00032,-0.00114,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.11e-05,8.04e-05,0.000107,0.0218,0.0221,0.00905,0.134,0.132,0.0363,3.63e-11,3.52e-11,1.42e-10,2.89e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29290000,0.708,0.000652,0.00231,0.706,-2.33,-1.13,0.968,-7.29,-3.6,-369,-1.07e-05,-5.74e-05,4.5e-06,-0.000103,-0.000304,-0.00114,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.13e-05,8.05e-05,0.000106,0.023,0.0234,0.00912,0.143,0.141,0.0364,3.64e-11,3.53e-11,1.41e-10,2.89e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29390000,0.708,0.00118,0.00379,0.706,-2.31,-1.11,0.977,-7.59,-3.71,-369,-1.12e-05,-5.74e-05,4.23e-06,-0.000117,-0.000333,-0.00112,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.14e-05,8.04e-05,0.000106,0.0221,0.0227,0.00904,0.144,0.142,0.0362,3.58e-11,3.47e-11,1.39e-10,2.88e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29490000,0.708,0.00169,0.00493,0.706,-2.26,-1.1,0.973,-7.82,-3.82,-369,-1.12e-05,-5.74e-05,4.21e-06,-0.000121,-0.00032,-0.00112,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.16e-05,8.05e-05,0.000106,0.0233,0.024,0.00916,0.153,0.151,0.0366,3.59e-11,3.48e-11,1.38e-10,2.88e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29590000,0.708,0.00207,0.00604,0.706,-2.23,-1.09,0.964,-8.08,-3.92,-369,-1.15e-05,-5.73e-05,4.13e-06,-0.000144,-0.00032,-0.00111,0.209,0.00206,0.432,0,0,0,0,0,0.000107,8.17e-05,8.04e-05,0.000106,0.0224,0.0232,0.00908,0.153,0.152,0.0364,3.54e-11,3.43e-11,1.36e-10,2.87e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29690000,0.708,0.00237,0.00672,0.706,-2.19,-1.08,0.956,-8.3,-4.02,-369,-1.15e-05,-5.73e-05,4.03e-06,-0.000149,-0.000307,-0.0011,0.209,0.00206,0.432,0,0,0,0,0,0.000107,8.18e-05,8.05e-05,0.000106,0.0236,0.0245,0.00914,0.164,0.162,0.0365,3.55e-11,3.44e-11,1.34e-10,2.87e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29790000,0.708,0.00265,0.00723,0.706,-2.17,-1.07,0.942,-8.58,-4.12,-369,-1.2e-05,-5.72e-05,4.01e-06,-0.000165,-0.000317,-0.00109,0.209,0.00206,0.432,0,0,0,0,0,0.000107,8.19e-05,8.04e-05,0.000105,0.0227,0.0236,0.0091,0.163,0.162,0.0366,3.5e-11,3.38e-11,1.33e-10,2.87e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29890000,0.708,0.00274,0.00748,0.706,-2.13,-1.06,0.928,-8.79,-4.23,-369,-1.2e-05,-5.72e-05,3.86e-06,-0.000174,-0.000294,-0.00109,0.209,0.00206,0.432,0,0,0,0,0,0.000107,8.21e-05,8.05e-05,0.000105,0.024,0.0249,0.00916,0.174,0.172,0.0367,3.51e-11,3.39e-11,1.32e-10,2.87e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29990000,0.708,0.00287,0.00767,0.706,-2.11,-1.05,0.911,-9.04,-4.32,-369,-1.22e-05,-5.71e-05,3.73e-06,-0.000194,-0.000285,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000107,8.22e-05,8.04e-05,0.000105,0.023,0.024,0.00907,0.173,0.171,0.0364,3.45e-11,3.34e-11,1.3e-10,2.86e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30090000,0.709,0.00287,0.00762,0.706,-2.08,-1.04,0.897,-9.25,-4.43,-369,-1.22e-05,-5.71e-05,3.61e-06,-0.0002,-0.000269,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000107,8.23e-05,8.04e-05,0.000104,0.0243,0.0253,0.00912,0.184,0.182,0.0365,3.46e-11,3.35e-11,1.29e-10,2.86e-06,2.79e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30190000,0.709,0.00293,0.0075,0.705,-2.06,-1.03,0.883,-9.5,-4.52,-369,-1.25e-05,-5.7e-05,3.61e-06,-0.000213,-0.000271,-0.00106,0.209,0.00206,0.432,0,0,0,0,0,0.000106,8.24e-05,8.03e-05,0.000104,0.0233,0.0243,0.00907,0.183,0.181,0.0366,3.41e-11,3.3e-11,1.27e-10,2.86e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30290000,0.709,0.00283,0.00733,0.705,-2.03,-1.02,0.87,-9.7,-4.62,-368,-1.25e-05,-5.7e-05,3.53e-06,-0.000218,-0.000261,-0.00106,0.209,0.00206,0.432,0,0,0,0,0,0.000106,8.25e-05,8.03e-05,0.000104,0.0246,0.0256,0.00912,0.194,0.192,0.0367,3.42e-11,3.31e-11,1.26e-10,2.86e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30390000,0.709,0.00285,0.00718,0.705,-2.01,-1.01,0.853,-9.93,-4.72,-368,-1.27e-05,-5.7e-05,3.47e-06,-0.00023,-0.000248,-0.00105,0.209,0.00206,0.432,0,0,0,0,0,0.000106,8.26e-05,8.01e-05,0.000103,0.0236,0.0245,0.00902,0.193,0.191,0.0364,3.36e-11,3.25e-11,1.25e-10,2.85e-06,2.77e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30490000,0.709,0.00273,0.00694,0.705,-1.97,-1.01,0.838,-10.1,-4.82,-368,-1.27e-05,-5.7e-05,3.48e-06,-0.000234,-0.000239,-0.00105,0.209,0.00206,0.432,0,0,0,0,0,0.000106,8.27e-05,8.02e-05,0.000103,0.0248,0.0258,0.00911,0.205,0.203,0.0368,3.37e-11,3.26e-11,1.23e-10,2.85e-06,2.76e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30590000,0.709,0.00265,0.00665,0.705,-1.96,-0.997,0.797,-10.4,-4.91,-368,-1.3e-05,-5.7e-05,3.49e-06,-0.000243,-0.000231,-0.00104,0.209,0.00206,0.432,0,0,0,0,0,0.000106,8.28e-05,8e-05,0.000103,0.0238,0.0247,0.00901,0.203,0.201,0.0366,3.32e-11,3.21e-11,1.22e-10,2.85e-06,2.75e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30690000,0.709,0.0025,0.00635,0.705,-1.93,-0.989,0.79,-10.6,-5.01,-368,-1.3e-05,-5.7e-05,3.46e-06,-0.000249,-0.000216,-0.00104,0.209,0.00206,0.432,0,0,0,0,0,0.000106,8.29e-05,8e-05,0.000103,0.0251,0.0261,0.00904,0.215,0.213,0.0367,3.33e-11,3.22e-11,1.21e-10,2.85e-06,2.74e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30790000,0.709,0.00245,0.00603,0.705,-1.91,-0.978,0.781,-10.8,-5.1,-368,-1.31e-05,-5.69e-05,3.31e-06,-0.000257,-0.00021,-0.00103,0.209,0.00206,0.432,0,0,0,0,0,0.000106,8.29e-05,7.97e-05,0.000102,0.024,0.0249,0.00899,0.213,0.211,0.0367,3.27e-11,3.18e-11,1.19e-10,2.84e-06,2.73e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30890000,0.709,0.00228,0.00561,0.705,-1.88,-0.971,0.768,-11,-5.2,-368,-1.31e-05,-5.69e-05,3.31e-06,-0.000262,-0.000197,-0.00103,0.209,0.00206,0.432,0,0,0,0,0,0.000105,8.31e-05,7.98e-05,0.000102,0.0253,0.0262,0.00902,0.224,0.223,0.0368,3.28e-11,3.19e-11,1.18e-10,2.84e-06,2.73e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30990000,0.709,0.00225,0.00515,0.705,-1.86,-0.961,0.759,-11.2,-5.29,-368,-1.34e-05,-5.68e-05,3.23e-06,-0.000271,-0.000187,-0.00102,0.209,0.00206,0.432,0,0,0,0,0,0.000105,8.3e-05,7.95e-05,0.000101,0.0242,0.025,0.00891,0.222,0.22,0.0365,3.23e-11,3.14e-11,1.17e-10,2.84e-06,2.72e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31090000,0.709,0.00204,0.00467,0.705,-1.83,-0.954,0.747,-11.4,-5.38,-368,-1.34e-05,-5.68e-05,3.16e-06,-0.000278,-0.000172,-0.00102,0.209,0.00206,0.432,0,0,0,0,0,0.000105,8.32e-05,7.95e-05,0.000101,0.0255,0.0263,0.00899,0.234,0.232,0.037,3.24e-11,3.15e-11,1.16e-10,2.84e-06,2.71e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31190000,0.709,0.00198,0.00446,0.705,-1.81,-0.946,0.735,-11.6,-5.48,-368,-1.35e-05,-5.68e-05,3.12e-06,-0.000292,-0.000143,-0.00101,0.209,0.00206,0.432,0,0,0,0,0,0.000105,8.31e-05,7.92e-05,0.000101,0.0243,0.025,0.00888,0.232,0.23,0.0367,3.19e-11,3.1e-11,1.15e-10,2.84e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31290000,0.709,0.00176,0.00395,0.705,-1.78,-0.937,0.736,-11.7,-5.57,-368,-1.35e-05,-5.68e-05,3.11e-06,-0.000299,-0.000126,-0.00101,0.209,0.00206,0.432,0,0,0,0,0,0.000105,8.33e-05,7.92e-05,0.000101,0.0256,0.0263,0.00891,0.244,0.242,0.0367,3.2e-11,3.11e-11,1.13e-10,2.84e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31390000,0.709,0.00162,0.00348,0.705,-1.76,-0.929,0.732,-12,-5.67,-368,-1.37e-05,-5.68e-05,3.05e-06,-0.000308,-0.000109,-0.000999,0.209,0.00206,0.432,0,0,0,0,0,0.000104,8.32e-05,7.89e-05,0.0001,0.0244,0.025,0.0088,0.241,0.239,0.0365,3.14e-11,3.07e-11,1.12e-10,2.84e-06,2.69e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31490000,0.709,0.00142,0.00288,0.705,-1.73,-0.921,0.726,-12.1,-5.76,-368,-1.37e-05,-5.68e-05,2.94e-06,-0.000315,-9.35e-05,-0.000994,0.209,0.00206,0.432,0,0,0,0,0,0.000104,8.34e-05,7.89e-05,0.0001,0.0257,0.0263,0.00887,0.254,0.252,0.0369,3.15e-11,3.08e-11,1.11e-10,2.83e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31590000,0.709,0.00136,0.00255,0.705,-1.7,-0.908,0.721,-12.3,-5.84,-368,-1.39e-05,-5.68e-05,2.95e-06,-0.000324,-7.52e-05,-0.000988,0.209,0.00206,0.432,0,0,0,0,0,0.000104,8.33e-05,7.86e-05,9.96e-05,0.0245,0.025,0.00876,0.251,0.249,0.0366,3.1e-11,3.04e-11,1.1e-10,2.83e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31690000,0.709,0.00111,0.0019,0.705,-1.68,-0.9,0.725,-12.5,-5.93,-368,-1.39e-05,-5.68e-05,2.94e-06,-0.00033,-6.14e-05,-0.000984,0.209,0.00206,0.432,0,0,0,0,0,0.000104,8.34e-05,7.86e-05,9.95e-05,0.0258,0.0263,0.00878,0.263,0.261,0.0366,3.11e-11,3.05e-11,1.09e-10,2.83e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31790000,0.709,0.000913,0.00129,0.705,-1.66,-0.89,0.723,-12.7,-6.02,-368,-1.41e-05,-5.67e-05,2.94e-06,-0.00034,-4.19e-05,-0.000977,0.209,0.00206,0.432,0,0,0,0,0,0.000104,8.33e-05,7.83e-05,9.91e-05,0.0246,0.025,0.00872,0.26,0.258,0.0367,3.07e-11,3.01e-11,1.08e-10,2.83e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31890000,0.709,0.00067,0.000603,0.705,-1.63,-0.879,0.718,-12.9,-6.1,-367,-1.41e-05,-5.67e-05,2.91e-06,-0.000346,-2.73e-05,-0.000972,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.35e-05,7.83e-05,9.9e-05,0.0259,0.0263,0.00874,0.273,0.271,0.0367,3.08e-11,3.02e-11,1.07e-10,2.83e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31990000,0.709,0.000534,0.000152,0.705,-1.6,-0.867,0.712,-13,-6.18,-367,-1.42e-05,-5.67e-05,2.83e-06,-0.000356,-6.78e-06,-0.000966,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.33e-05,7.79e-05,9.85e-05,0.0247,0.025,0.00863,0.27,0.268,0.0364,3.03e-11,2.98e-11,1.06e-10,2.83e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32090000,0.709,0.000248,-0.00056,0.705,-1.57,-0.857,0.718,-13.2,-6.27,-367,-1.42e-05,-5.67e-05,2.78e-06,-0.000364,9.84e-06,-0.000961,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.35e-05,7.8e-05,9.84e-05,0.0259,0.0262,0.0087,0.282,0.28,0.0368,3.04e-11,2.99e-11,1.05e-10,2.83e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32190000,0.709,3.63e-05,-0.00133,0.705,-1.55,-0.848,0.716,-13.4,-6.35,-367,-1.43e-05,-5.66e-05,2.6e-06,-0.000374,3.17e-05,-0.000953,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.34e-05,7.76e-05,9.8e-05,0.0247,0.0249,0.00859,0.279,0.277,0.0365,2.99e-11,2.96e-11,1.04e-10,2.82e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32290000,0.709,-0.000194,-0.00205,0.705,-1.51,-0.838,0.71,-13.5,-6.43,-367,-1.43e-05,-5.66e-05,2.58e-06,-0.000382,4.93e-05,-0.000948,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.35e-05,7.76e-05,9.79e-05,0.026,0.0261,0.00861,0.292,0.29,0.0366,3e-11,2.97e-11,1.03e-10,2.82e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32390000,0.709,-0.000378,-0.00268,0.705,-1.48,-0.826,0.709,-13.7,-6.51,-367,-1.44e-05,-5.66e-05,2.61e-06,-0.000387,5.92e-05,-0.000944,0.209,0.00206,0.432,0,0,0,0,0,0.000102,8.34e-05,7.73e-05,9.75e-05,0.0247,0.0248,0.00855,0.288,0.286,0.0366,2.96e-11,2.93e-11,1.02e-10,2.82e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32490000,0.709,-0.000498,-0.00291,0.705,-1.45,-0.814,0.714,-13.8,-6.6,-367,-1.44e-05,-5.66e-05,2.61e-06,-0.000392,7.18e-05,-0.00094,0.209,0.00206,0.432,0,0,0,0,0,0.000102,8.35e-05,7.73e-05,9.74e-05,0.026,0.026,0.00857,0.301,0.299,0.0366,2.97e-11,2.94e-11,1.01e-10,2.82e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32590000,0.709,-0.000494,-0.00312,0.705,-1.43,-0.804,0.711,-14,-6.68,-367,-1.45e-05,-5.66e-05,2.54e-06,-0.000396,8.02e-05,-0.000937,0.209,0.00206,0.432,0,0,0,0,0,0.000102,8.33e-05,7.7e-05,9.7e-05,0.0247,0.0247,0.00846,0.298,0.295,0.0363,2.92e-11,2.91e-11,9.97e-11,2.82e-06,2.61e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32690000,0.709,-0.000535,-0.0032,0.705,-1.39,-0.794,0.707,-14.1,-6.76,-367,-1.45e-05,-5.66e-05,2.52e-06,-0.000399,8.69e-05,-0.000935,0.209,0.00206,0.432,0,0,0,0,0,0.000102,8.35e-05,7.7e-05,9.69e-05,0.026,0.026,0.00848,0.311,0.308,0.0364,2.93e-11,2.92e-11,9.88e-11,2.82e-06,2.61e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32790000,0.709,-0.000498,-0.00314,0.705,-1.37,-0.783,0.703,-14.3,-6.83,-367,-1.45e-05,-5.66e-05,2.5e-06,-0.000404,9.69e-05,-0.000932,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.33e-05,7.67e-05,9.65e-05,0.0248,0.0247,0.00843,0.307,0.304,0.0364,2.89e-11,2.88e-11,9.79e-11,2.82e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32890000,0.709,-0.000405,-0.00309,0.706,-1.34,-0.773,0.703,-14.4,-6.91,-367,-1.45e-05,-5.66e-05,2.35e-06,-0.00041,0.000109,-0.000927,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.35e-05,7.67e-05,9.65e-05,0.026,0.0259,0.00845,0.32,0.317,0.0364,2.9e-11,2.89e-11,9.7e-11,2.82e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32990000,0.709,-0.000273,-0.00302,0.706,-1.32,-0.765,0.697,-14.6,-6.99,-367,-1.47e-05,-5.66e-05,2.47e-06,-0.000416,0.000123,-0.000923,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.33e-05,7.64e-05,9.61e-05,0.0248,0.0246,0.00834,0.316,0.314,0.0361,2.86e-11,2.86e-11,9.61e-11,2.82e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33090000,0.709,-0.000306,-0.00304,0.706,-1.29,-0.756,0.691,-14.7,-7.07,-367,-1.47e-05,-5.66e-05,2.54e-06,-0.000419,0.000129,-0.000921,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.34e-05,7.64e-05,9.6e-05,0.026,0.0258,0.00841,0.329,0.327,0.0365,2.87e-11,2.87e-11,9.53e-11,2.81e-06,2.59e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33190000,0.705,0.0031,-0.00207,0.71,-1.26,-0.746,0.632,-14.8,-7.14,-367,-1.47e-05,-5.66e-05,2.56e-06,-0.000422,0.000137,-0.000918,0.209,0.00206,0.432,0,0,0,0,0,9.98e-05,8.32e-05,7.61e-05,9.63e-05,0.0248,0.0245,0.00831,0.325,0.323,0.0362,2.83e-11,2.84e-11,9.44e-11,2.81e-06,2.59e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33290000,0.653,0.0153,-0.00116,0.757,-1.26,-0.727,0.614,-15,-7.21,-367,-1.47e-05,-5.66e-05,2.61e-06,-0.000425,0.000142,-0.000916,0.209,0.00206,0.432,0,0,0,0,0,9.24e-05,8.27e-05,7.67e-05,0.000104,0.0261,0.0258,0.00833,0.338,0.336,0.0362,2.84e-11,2.85e-11,9.36e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33390000,0.55,0.0133,-0.00141,0.835,-1.26,-0.716,0.804,-15.1,-7.29,-367,-1.48e-05,-5.66e-05,2.66e-06,-0.00043,0.000151,-0.000913,0.209,0.00206,0.432,0,0,0,0,0,7.9e-05,8.15e-05,7.76e-05,0.000117,0.0246,0.0243,0.00827,0.335,0.332,0.0363,2.8e-11,2.82e-11,9.28e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33490000,0.412,0.00679,0.00107,0.911,-1.25,-0.71,0.821,-15.2,-7.36,-366,-1.48e-05,-5.66e-05,2.66e-06,-0.00043,0.000152,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,6.47e-05,8.04e-05,7.94e-05,0.000131,0.0261,0.0257,0.0081,0.348,0.345,0.0363,2.81e-11,2.83e-11,9.19e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33590000,0.254,0.000972,-0.00144,0.967,-1.21,-0.709,0.787,-15.3,-7.42,-366,-1.47e-05,-5.66e-05,2.66e-06,-0.00043,0.000152,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,5.3e-05,7.84e-05,8.07e-05,0.000143,0.0256,0.0254,0.00779,0.344,0.341,0.0359,2.77e-11,2.8e-11,9.11e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33690000,0.0878,-0.00224,-0.00452,0.996,-1.16,-0.706,0.793,-15.5,-7.49,-366,-1.47e-05,-5.66e-05,2.74e-06,-0.00043,0.000152,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,4.64e-05,7.71e-05,8.26e-05,0.00015,0.0282,0.028,0.00765,0.357,0.354,0.0362,2.78e-11,2.81e-11,9.04e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33790000,-0.0817,-0.00368,-0.00636,0.997,-1.1,-0.689,0.775,-15.6,-7.55,-366,-1.48e-05,-5.65e-05,2.74e-06,-0.00043,0.000152,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,4.55e-05,7.43e-05,8.22e-05,0.000151,0.0284,0.0282,0.00737,0.353,0.35,0.0359,2.75e-11,2.78e-11,8.96e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33890000,-0.248,-0.00476,-0.00712,0.969,-1.04,-0.667,0.76,-15.7,-7.62,-366,-1.48e-05,-5.65e-05,2.76e-06,-0.00043,0.000152,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,5.07e-05,7.36e-05,8.33e-05,0.000146,0.032,0.0319,0.00722,0.366,0.363,0.0358,2.76e-11,2.79e-11,8.88e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33990000,-0.394,-0.00292,-0.0109,0.919,-0.989,-0.63,0.731,-15.8,-7.68,-366,-1.5e-05,-5.65e-05,2.75e-06,-0.00043,0.000152,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,6e-05,7.05e-05,8.02e-05,0.000136,0.0322,0.0322,0.00698,0.362,0.359,0.0354,2.72e-11,2.75e-11,8.79e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34090000,-0.5,-0.00181,-0.0124,0.866,-0.937,-0.586,0.734,-15.9,-7.74,-366,-1.5e-05,-5.65e-05,2.87e-06,-0.00043,0.000152,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,6.98e-05,7.07e-05,8.01e-05,0.000126,0.0369,0.037,0.00689,0.375,0.372,0.0356,2.73e-11,2.76e-11,8.73e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34190000,-0.569,-0.00114,-0.0112,0.822,-0.922,-0.546,0.733,-16.1,-7.81,-366,-1.53e-05,-5.65e-05,2.84e-06,-0.000456,0.000171,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,7.72e-05,6.68e-05,7.5e-05,0.000118,0.0371,0.0374,0.00669,0.372,0.368,0.0352,2.69e-11,2.73e-11,8.65e-11,2.81e-06,2.57e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34290000,-0.612,-0.00206,-0.00836,0.79,-0.875,-0.5,0.731,-16.2,-7.86,-366,-1.53e-05,-5.65e-05,2.87e-06,-0.000456,0.000171,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.25e-05,6.69e-05,7.48e-05,0.000113,0.0432,0.0437,0.0066,0.384,0.381,0.035,2.7e-11,2.74e-11,8.58e-11,2.81e-06,2.57e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34390000,-0.639,-0.00222,-0.00587,0.77,-0.86,-0.466,0.729,-16.3,-7.92,-366,-1.56e-05,-5.65e-05,2.89e-06,-0.000503,0.000218,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.55e-05,6.21e-05,6.87e-05,0.000109,0.0428,0.0435,0.00646,0.381,0.378,0.0349,2.67e-11,2.71e-11,8.51e-11,2.78e-06,2.55e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34490000,-0.654,-0.00315,-0.00373,0.756,-0.81,-0.426,0.728,-16.4,-7.97,-366,-1.56e-05,-5.65e-05,2.93e-06,-0.000503,0.000217,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.76e-05,6.22e-05,6.86e-05,0.000107,0.0498,0.0508,0.00641,0.394,0.39,0.0347,2.68e-11,2.72e-11,8.44e-11,2.78e-06,2.55e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34590000,-0.664,-0.00258,-0.00267,0.748,-0.809,-0.412,0.724,-16.5,-8.04,-366,-1.59e-05,-5.66e-05,3.02e-06,-0.000598,0.000304,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.86e-05,5.69e-05,6.23e-05,0.000105,0.048,0.0491,0.00627,0.391,0.387,0.0343,2.66e-11,2.71e-11,8.36e-11,2.72e-06,2.51e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34690000,-0.67,-0.00296,-0.00188,0.742,-0.758,-0.374,0.72,-16.6,-8.08,-366,-1.59e-05,-5.66e-05,3e-06,-0.000598,0.000304,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.94e-05,5.7e-05,6.22e-05,0.000104,0.0555,0.0571,0.00628,0.403,0.4,0.0344,2.67e-11,2.72e-11,8.3e-11,2.72e-06,2.51e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
34790000,-0.674,-0.00191,-0.00164,0.739,-0.76,-0.365,0.714,-16.7,-8.15,-366,-1.61e-05,-5.67e-05,2.93e-06,-0.000701,0.000407,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.96e-05,5.19e-05,5.62e-05,0.000103,0.0522,0.0536,0.00617,0.401,0.397,0.034,2.65e-11,2.7e-11,8.23e-11,2.65e-06,2.44e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34890000,-0.676,-0.00193,-0.00153,0.737,-0.713,-0.333,0.712,-16.8,-8.18,-365,-1.61e-05,-5.67e-05,3.02e-06,-0.000701,0.000407,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.99e-05,5.19e-05,5.62e-05,0.000102,0.0598,0.0616,0.00618,0.413,0.409,0.0339,2.66e-11,2.71e-11,8.17e-11,2.65e-06,2.44e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34990000,-0.679,-0.00831,-0.00434,0.734,0.298,0.276,-0.133,-16.9,-8.21,-366,-1.63e-05,-5.68e-05,2.95e-06,-0.000834,0.000545,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,9.02e-05,4.73e-05,5.09e-05,0.000102,0.0602,0.0585,0.00683,0.41,0.407,0.0338,2.66e-11,2.71e-11,8.11e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35090000,-0.679,-0.00834,-0.00437,0.734,0.423,0.297,-0.192,-16.8,-8.18,-366,-1.63e-05,-5.68e-05,3e-06,-0.000834,0.000545,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,9.01e-05,4.73e-05,5.09e-05,0.000102,0.0655,0.0639,0.00682,0.421,0.418,0.0337,2.67e-11,2.72e-11,8.04e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35190000,-0.679,-0.00842,-0.00439,0.734,0.446,0.329,-0.189,-16.8,-8.15,-366,-1.63e-05,-5.68e-05,3.01e-06,-0.000834,0.000545,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,9e-05,4.72e-05,5.1e-05,0.000102,0.0706,0.0693,0.00666,0.434,0.432,0.0334,2.68e-11,2.73e-11,7.98e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35290000,-0.679,-0.00846,-0.00445,0.734,0.469,0.36,-0.187,-16.8,-8.11,-366,-1.63e-05,-5.68e-05,3.01e-06,-0.000834,0.000545,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.99e-05,4.72e-05,5.1e-05,0.000102,0.0761,0.0751,0.00658,0.448,0.446,0.0333,2.69e-11,2.74e-11,7.91e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35390000,-0.679,-0.00859,-0.0044,0.734,0.493,0.393,-0.182,-16.7,-8.07,-366,-1.63e-05,-5.68e-05,2.95e-06,-0.000834,0.000545,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.99e-05,4.71e-05,5.11e-05,0.000102,0.0818,0.0813,0.00646,0.464,0.463,0.0333,2.7e-11,2.75e-11,7.86e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35490000,-0.679,-0.00863,-0.00439,0.734,0.515,0.423,-0.18,-16.7,-8.03,-366,-1.63e-05,-5.68e-05,2.9e-06,-0.000834,0.000545,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.98e-05,4.71e-05,5.11e-05,0.000101,0.088,0.0879,0.00639,0.481,0.481,0.0332,2.71e-11,2.76e-11,7.8e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35590000,-0.679,-0.00565,-0.0044,0.734,0.405,0.345,-0.192,-16.8,-8.12,-366,-1.67e-05,-5.69e-05,3.06e-06,-0.000834,0.000545,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.9e-05,3.98e-05,4.27e-05,0.0001,0.0697,0.07,0.00609,0.47,0.469,0.0327,2.7e-11,2.76e-11,7.73e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35690000,-0.679,-0.00566,-0.00436,0.734,0.424,0.372,-0.19,-16.7,-8.08,-366,-1.67e-05,-5.69e-05,3.06e-06,-0.000834,0.000545,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.89e-05,3.98e-05,4.27e-05,0.0001,0.0749,0.0756,0.00605,0.486,0.485,0.0329,2.71e-11,2.77e-11,7.68e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35790000,-0.679,-0.0035,-0.00429,0.734,0.346,0.312,-0.197,-16.8,-8.15,-366,-1.69e-05,-5.69e-05,3.18e-06,-0.000853,0.000562,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.84e-05,3.44e-05,3.67e-05,9.92e-05,0.0621,0.0628,0.00582,0.478,0.476,0.0325,2.72e-11,2.77e-11,7.61e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35890000,-0.679,-0.00349,-0.00433,0.734,0.36,0.336,-0.196,-16.8,-8.11,-366,-1.69e-05,-5.69e-05,3.31e-06,-0.000853,0.000562,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.83e-05,3.45e-05,3.68e-05,9.91e-05,0.0674,0.0685,0.00578,0.493,0.491,0.0324,2.73e-11,2.78e-11,7.55e-11,2.55e-06,2.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35990000,-0.679,-0.00165,-0.00424,0.735,0.295,0.282,-0.202,-16.8,-8.17,-366,-1.7e-05,-5.7e-05,3.52e-06,-0.000927,0.000625,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.81e-05,3.03e-05,3.22e-05,9.87e-05,0.0578,0.0588,0.00564,0.486,0.484,0.0322,2.73e-11,2.79e-11,7.5e-11,2.54e-06,2.35e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36090000,-0.678,-0.00169,-0.00423,0.735,0.305,0.303,-0.202,-16.8,-8.14,-366,-1.7e-05,-5.7e-05,3.65e-06,-0.000927,0.000625,-0.000912,0.209,0.00206,0.432,0,0,0,0,0,8.8e-05,3.04e-05,3.23e-05,9.86e-05,0.0633,0.0647,0.00562,0.5,0.498,0.0321,2.74e-11,2.8e-11,7.45e-11,2.54e-06,2.35e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36190000,-0.678,-0.000275,-0.00411,0.735,0.251,0.256,-0.205,-16.8,-8.19,-366,-1.71e-05,-5.7e-05,3.68e-06,-0.00103,0.000711,-0.000913,0.209,0.00206,0.432,0,0,0,0,0,8.78e-05,2.71e-05,2.88e-05,9.84e-05,0.0553,0.0566,0.0055,0.495,0.493,0.0317,2.75e-11,2.81e-11,7.39e-11,2.51e-06,2.32e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36290000,-0.678,-0.000336,-0.00407,0.735,0.259,0.274,-0.205,-16.8,-8.17,-366,-1.71e-05,-5.7e-05,3.82e-06,-0.00103,0.000711,-0.000913,0.209,0.00206,0.432,0,0,0,0,0,8.77e-05,2.72e-05,2.88e-05,9.83e-05,0.0609,0.0625,0.00553,0.509,0.507,0.0319,2.76e-11,2.82e-11,7.34e-11,2.51e-06,2.32e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
36390000,-0.678,0.000688,-0.00397,0.735,0.215,0.232,-0.208,-16.8,-8.2,-366,-1.72e-05,-5.7e-05,4.03e-06,-0.00115,0.000803,-0.000914,0.209,0.00206,0.432,0,0,0,0,0,8.76e-05,2.46e-05,2.61e-05,9.82e-05,0.0539,0.0552,0.00545,0.505,0.502,0.0315,2.77e-11,2.82e-11,7.29e-11,2.46e-06,2.28e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36490000,-0.678,0.000636,-0.00401,0.735,0.222,0.247,-0.207,-16.8,-8.18,-366,-1.72e-05,-5.7e-05,4.3e-06,-0.00115,0.000803,-0.000914,0.209,0.00206,0.432,0,0,0,0,0,8.75e-05,2.47e-05,2.62e-05,9.81e-05,0.0595,0.0612,0.00548,0.517,0.515,0.0314,2.78e-11,2.83e-11,7.23e-11,2.46e-06,2.28e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
36590000,-0.678,0.00141,-0.00387,0.735,0.183,0.211,-0.207,-16.9,-8.21,-366,-1.72e-05,-5.7e-05,4.42e-06,-0.00128,0.000894,-0.000916,0.209,0.00206,0.432,0,0,0,0,0,8.74e-05,2.27e-05,2.4e-05,9.8e-05,0.053,0.0543,0.00544,0.514,0.512,0.0311,2.79e-11,2.84e-11,7.18e-11,2.39e-06,2.22e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36690000,-0.678,0.00143,-0.00383,0.735,0.187,0.223,-0.206,-16.8,-8.19,-366,-1.72e-05,-5.7e-05,4.55e-06,-0.00128,0.000894,-0.000916,0.209,0.00206,0.432,0,0,0,0,0,8.74e-05,2.28e-05,2.41e-05,9.8e-05,0.0585,0.0602,0.00551,0.527,0.524,0.0312,2.8e-11,2.85e-11,7.13e-11,2.39e-06,2.22e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36790000,-0.678,0.00201,-0.00375,0.735,0.155,0.192,-0.205,-16.9,-8.22,-366,-1.72e-05,-5.7e-05,4.67e-06,-0.0014,0.000979,-0.000917,0.209,0.00206,0.432,0,0,0,0,0,8.73e-05,2.12e-05,2.24e-05,9.79e-05,0.0523,0.0536,0.0055,0.524,0.522,0.0309,2.81e-11,2.86e-11,7.08e-11,2.31e-06,2.15e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36890000,-0.677,0.00197,-0.00374,0.736,0.156,0.201,-0.204,-16.8,-8.2,-366,-1.72e-05,-5.7e-05,4.8e-06,-0.0014,0.000979,-0.000917,0.209,0.00206,0.432,0,0,0,0,0,8.72e-05,2.13e-05,2.25e-05,9.78e-05,0.0577,0.0592,0.00557,0.536,0.534,0.0308,2.82e-11,2.87e-11,7.03e-11,2.31e-06,2.15e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36990000,-0.677,0.00243,-0.00358,0.736,0.129,0.173,-0.203,-16.9,-8.22,-366,-1.72e-05,-5.69e-05,4.94e-06,-0.00151,0.00105,-0.000919,0.209,0.00206,0.432,0,0,0,0,0,8.72e-05,2.01e-05,2.13e-05,9.78e-05,0.0516,0.0528,0.0056,0.534,0.532,0.0308,2.83e-11,2.88e-11,6.99e-11,2.22e-06,2.07e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37090000,-0.677,0.0024,-0.00355,0.736,0.13,0.18,-0.201,-16.9,-8.2,-366,-1.72e-05,-5.69e-05,5.15e-06,-0.00151,0.00105,-0.000919,0.209,0.00206,0.432,0,0,0,0,0,8.71e-05,2.02e-05,2.14e-05,9.77e-05,0.0568,0.0582,0.00569,0.545,0.543,0.0307,2.84e-11,2.89e-11,6.94e-11,2.22e-06,2.07e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37190000,-0.677,0.00273,-0.00345,0.736,0.107,0.152,-0.197,-16.9,-8.22,-366,-1.72e-05,-5.69e-05,5.37e-06,-0.00162,0.00112,-0.000922,0.209,0.00206,0.432,0,0,0,0,0,8.7e-05,1.93e-05,2.04e-05,9.77e-05,0.0509,0.0519,0.00572,0.544,0.542,0.0305,2.85e-11,2.9e-11,6.89e-11,2.12e-06,1.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37290000,-0.677,0.00273,-0.00348,0.736,0.107,0.158,-0.195,-16.9,-8.2,-366,-1.72e-05,-5.69e-05,5.52e-06,-0.00162,0.00112,-0.000922,0.209,0.00206,0.432,0,0,0,0,0,8.7e-05,1.94e-05,2.05e-05,9.76e-05,0.0559,0.0571,0.00584,0.555,0.553,0.0307,2.86e-11,2.91e-11,6.85e-11,2.12e-06,1.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37390000,-0.677,0.00295,-0.00334,0.736,0.086,0.133,-0.192,-16.9,-8.22,-366,-1.72e-05,-5.69e-05,5.67e-06,-0.00171,0.00117,-0.000924,0.209,0.00206,0.432,0,0,0,0,0,8.69e-05,1.88e-05,1.99e-05,9.75e-05,0.05,0.051,0.00588,0.554,0.552,0.0305,2.87e-11,2.92e-11,6.8e-11,2.03e-06,1.89e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37490000,-0.677,0.00293,-0.00332,0.736,0.0848,0.139,-0.189,-16.9,-8.2,-366,-1.72e-05,-5.69e-05,5.79e-06,-0.00171,0.00117,-0.000924,0.209,0.00206,0.432,0,0,0,0,0,8.68e-05,1.89e-05,2e-05,9.75e-05,0.0548,0.0559,0.006,0.565,0.562,0.0304,2.88e-11,2.93e-11,6.75e-11,2.03e-06,1.89e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37590000,-0.677,0.0031,-0.00323,0.736,0.0673,0.118,-0.185,-16.9,-8.22,-366,-1.72e-05,-5.69e-05,5.93e-06,-0.00179,0.00121,-0.000928,0.209,0.00206,0.432,0,0,0,0,0,8.68e-05,1.84e-05,1.95e-05,9.74e-05,0.0491,0.0499,0.00607,0.564,0.562,0.0305,2.89e-11,2.94e-11,6.71e-11,1.93e-06,1.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37690000,-0.676,0.00307,-0.00326,0.736,0.0649,0.123,-0.183,-16.9,-8.21,-366,-1.72e-05,-5.69e-05,6.09e-06,-0.00179,0.00121,-0.000928,0.209,0.00206,0.432,0,0,0,0,0,8.67e-05,1.85e-05,1.96e-05,9.73e-05,0.0536,0.0545,0.0062,0.574,0.572,0.0305,2.9e-11,2.95e-11,6.67e-11,1.93e-06,1.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37790000,-0.676,0.00319,-0.00323,0.737,0.0511,0.104,-0.174,-16.9,-8.22,-366,-1.72e-05,-5.68e-05,6.26e-06,-0.00187,0.00125,-0.000934,0.209,0.00206,0.432,0,0,0,0,0,8.66e-05,1.82e-05,1.93e-05,9.72e-05,0.0481,0.0487,0.00626,0.574,0.572,0.0304,2.91e-11,2.96e-11,6.62e-11,1.84e-06,1.73e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37890000,-0.676,0.00314,-0.00322,0.737,0.049,0.108,-0.164,-16.9,-8.21,-366,-1.72e-05,-5.68e-05,6.44e-06,-0.00188,0.00126,-0.000938,0.209,0.00206,0.432,0,0,0,0,0,8.65e-05,1.83e-05,1.94e-05,9.71e-05,0.0523,0.0531,0.00639,0.584,0.582,0.0304,2.92e-11,2.97e-11,6.58e-11,1.84e-06,1.73e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37990000,-0.676,0.00319,-0.0032,0.737,0.0365,0.0919,-0.155,-16.9,-8.22,-366,-1.72e-05,-5.68e-05,6.6e-06,-0.00194,0.00129,-0.000944,0.209,0.00206,0.432,0,0,0,0,0,8.64e-05,1.81e-05,1.91e-05,9.7e-05,0.047,0.0475,0.00647,0.584,0.582,0.0305,2.92e-11,2.98e-11,6.54e-11,1.76e-06,1.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38090000,-0.676,0.00314,-0.0032,0.737,0.0331,0.095,-0.146,-16.9,-8.21,-366,-1.72e-05,-5.68e-05,6.74e-06,-0.00194,0.0013,-0.000947,0.209,0.00206,0.432,0,0,0,0,0,8.63e-05,1.82e-05,1.93e-05,9.7e-05,0.051,0.0516,0.00661,0.594,0.592,0.0306,2.93e-11,2.99e-11,6.5e-11,1.76e-06,1.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38190000,-0.676,0.00318,-0.00312,0.737,0.0214,0.0801,-0.137,-16.9,-8.21,-366,-1.72e-05,-5.68e-05,6.9e-06,-0.002,0.00132,-0.000953,0.209,0.00206,0.432,0,0,0,0,0,8.62e-05,1.8e-05,1.91e-05,9.68e-05,0.0458,0.0463,0.00667,0.594,0.592,0.0305,2.94e-11,3e-11,6.45e-11,1.68e-06,1.57e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38290000,-0.676,0.00314,-0.00311,0.737,0.0188,0.0811,-0.129,-16.9,-8.21,-366,-1.72e-05,-5.68e-05,7.05e-06,-0.002,0.00132,-0.000957,0.209,0.00206,0.432,0,0,0,0,0,8.62e-05,1.81e-05,1.92e-05,9.68e-05,0.0496,0.0501,0.00683,0.604,0.602,0.0308,2.95e-11,3.01e-11,6.42e-11,1.68e-06,1.57e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38390000,-0.675,0.00317,-0.00303,0.737,0.0116,0.0697,-0.121,-16.9,-8.21,-366,-1.72e-05,-5.67e-05,7.23e-06,-0.00205,0.00134,-0.000963,0.209,0.00206,0.432,0,0,0,0,0,8.6e-05,1.81e-05,1.92e-05,9.66e-05,0.0447,0.045,0.00689,0.604,0.602,0.0307,2.96e-11,3.02e-11,6.37e-11,1.6e-06,1.51e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38490000,-0.675,0.00314,-0.00302,0.738,0.00884,0.0714,-0.114,-16.9,-8.21,-366,-1.72e-05,-5.67e-05,7.38e-06,-0.00205,0.00134,-0.000966,0.209,0.00206,0.432,0,0,0,0,0,8.6e-05,1.82e-05,1.93e-05,9.66e-05,0.0482,0.0486,0.00703,0.614,0.611,0.0309,2.97e-11,3.03e-11,6.33e-11,1.6e-06,1.51e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38590000,-0.675,0.00314,-0.00292,0.738,0.00498,0.061,-0.107,-16.9,-8.21,-366,-1.72e-05,-5.67e-05,7.54e-06,-0.00209,0.00135,-0.000971,0.209,0.00206,0.432,0,0,0,0,0,8.59e-05,1.82e-05,1.93e-05,9.65e-05,0.0435,0.0438,0.00711,0.614,0.612,0.031,2.98e-11,3.03e-11,6.3e-11,1.54e-06,1.44e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38690000,-0.675,0.00304,-0.00292,0.738,0.00124,0.0605,-0.0985,-16.9,-8.21,-366,-1.72e-05,-5.67e-05,7.66e-06,-0.00209,0.00135,-0.000974,0.209,0.00206,0.432,0,0,0,0,0,8.58e-05,1.83e-05,1.94e-05,9.64e-05,0.0468,0.0471,0.00725,0.624,0.621,0.0312,2.99e-11,3.04e-11,6.26e-11,1.54e-06,1.44e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38790000,-0.675,0.00304,-0.00288,0.738,-0.00334,0.0495,-0.0908,-16.9,-8.21,-366,-1.72e-05,-5.67e-05,7.79e-06,-0.00213,0.00136,-0.000979,0.209,0.00206,0.432,0,0,0,0,0,8.56e-05,1.83e-05,1.94e-05,9.62e-05,0.0424,0.0426,0.00729,0.624,0.622,0.0311,2.99e-11,3.05e-11,6.22e-11,1.47e-06,1.39e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38890000,-0.675,0.00286,-0.00293,0.738,-0.0129,0.039,0.408,-16.9,-8.21,-366,-1.72e-05,-5.67e-05,7.93e-06,-0.00213,0.00136,-0.000981,0.209,0.00206,0.432,0,0,0,0,0,8.56e-05,1.84e-05,1.95e-05,9.62e-05,0.0452,0.0454,0.00745,0.634,0.631,0.0316,3e-11,3.06e-11,6.18e-11,1.47e-06,1.39e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
190000,1,-0.0106,-0.0106,-0.0216,-0.000389,-0.000233,-0.00902,-2.27e-05,-9.79e-06,-0.000287,0,0,0,0,0,0,0.192,-9.31e-10,0.404,0,0,0,0,0,2.14e-06,0.00251,0.00251,0.00338,25,25,0.563,100,100,0.8,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
290000,1,-0.0106,-0.011,-0.0216,0.000602,0.000283,-0.0229,-2.98e-05,-3.6e-05,-0.00185,0,0,0,0,0,0,0.192,-9.31e-10,0.404,0,0,0,0,0,1.62e-06,0.00256,0.00256,0.00222,25,25,0.562,101,101,0.337,1e-06,1e-06,9.97e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
390000,1,-0.0107,-0.0113,-0.0216,0.00209,0.000219,-0.0375,6.44e-05,2.4e-05,-0.00489,-1.6e-13,-6.23e-13,-3.2e-15,3.42e-12,-8.79e-13,-9.3e-14,0.192,-9.31e-10,0.404,0,0,0,0,0,1.41e-06,0.00267,0.00267,0.00169,24.8,24.8,0.557,0.29,0.29,0.209,1e-06,1e-06,9.88e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
490000,1,-0.0107,-0.0116,-0.0217,0.00462,-0.000602,-0.0529,0.000405,-1.04e-05,-0.00941,-1.6e-13,-6.23e-13,-3.2e-15,3.42e-12,-8.79e-13,-9.3e-14,0.192,-9.31e-10,0.404,0,0,0,0,0,1.35e-06,0.00282,0.00282,0.00141,24.9,24.9,0.544,0.739,0.739,0.159,1e-06,1e-06,9.73e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
590000,1,-0.0107,-0.0119,-0.0216,0.00418,3.23e-05,-0.0661,0.000239,-7.62e-06,-0.0153,-1.91e-11,-5.29e-09,-4.94e-11,1.28e-08,-4.43e-11,-2.89e-10,0.192,-9.31e-10,0.404,0,0,0,0,0,1.34e-06,0.00302,0.00302,0.00125,7.8,7.8,0.527,0.267,0.267,0.141,1e-06,1e-06,9.49e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
690000,1,-0.0109,-0.0122,-0.0216,0.00684,-0.00104,-0.0813,0.000761,-8.68e-05,-0.0227,-1.91e-11,-5.29e-09,-4.94e-11,1.28e-08,-4.43e-11,-2.89e-10,0.192,-9.31e-10,0.404,0,0,0,0,0,1.39e-06,0.00328,0.00328,0.00116,7.87,7.87,0.497,0.556,0.556,0.13,1e-06,1e-06,9.16e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
790000,1,-0.011,-0.0125,-0.0216,0.00621,-0.000564,-0.0959,0.000416,-5.26e-05,-0.0315,-2.55e-09,-3.32e-08,-2.74e-10,4.83e-08,-3.24e-09,-1.19e-09,0.192,-9.31e-10,0.404,0,0,0,0,0,1.47e-06,0.00356,0.00356,0.00111,2.63,2.63,0.465,0.218,0.218,0.129,9.99e-07,9.99e-07,8.75e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
890000,1,-0.0111,-0.0128,-0.0216,0.0107,-0.00171,-0.11,0.00125,-0.000202,-0.0418,-2.55e-09,-3.32e-08,-2.74e-10,4.83e-08,-3.24e-09,-1.19e-09,0.192,-9.31e-10,0.404,0,0,0,0,0,1.59e-06,0.00392,0.00392,0.00109,2.72,2.72,0.471,0.363,0.363,0.164,9.99e-07,9.99e-07,8.27e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
990000,1,-0.0111,-0.0131,-0.0215,0.0117,-0.00285,-0.125,0.000869,-0.000157,-0.0536,-1.94e-08,-1.66e-07,-1.12e-09,1.58e-07,-1.72e-08,-4.19e-09,0.192,-9.31e-10,0.404,0,0,0,0,0,1.72e-06,0.00427,0.00427,0.00108,1.25,1.25,0.477,0.178,0.178,0.209,9.97e-07,9.97e-07,7.73e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1090000,1,-0.0112,-0.0134,-0.0216,0.0161,-0.00437,-0.141,0.00224,-0.000527,-0.0669,-1.94e-08,-1.66e-07,-1.12e-09,1.58e-07,-1.72e-08,-4.19e-09,0.192,-9.31e-10,0.404,0,0,0,0,0,1.9e-06,0.00472,0.00472,0.00108,1.38,1.38,0.484,0.265,0.265,0.263,9.97e-07,9.97e-07,7.15e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1190000,1,-0.0113,-0.0136,-0.0216,0.0163,-0.00506,-0.155,0.0016,-0.000417,-0.0818,-1.25e-07,-6.6e-07,-2.4e-09,4.68e-07,-8.33e-08,-1.35e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,2.04e-06,0.00506,0.00506,0.00108,0.85,0.85,0.491,0.151,0.151,0.328,9.88e-07,9.88e-07,6.56e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1290000,1,-0.0113,-0.0139,-0.0215,0.0212,-0.00632,-0.169,0.00348,-0.00101,-0.098,-1.25e-07,-6.6e-07,-2.4e-09,4.68e-07,-8.33e-08,-1.35e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,2.25e-06,0.0056,0.0056,0.00108,1.03,1.03,0.5,0.214,0.214,0.402,9.88e-07,9.88e-07,5.97e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1390000,1,-0.0114,-0.0142,-0.0215,0.0274,-0.00852,-0.181,0.00595,-0.00174,-0.115,-1.25e-07,-6.6e-07,-2.4e-09,4.68e-07,-8.33e-08,-1.35e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,2.49e-06,0.00618,0.00619,0.00108,1.26,1.26,0.509,0.301,0.301,0.487,9.88e-07,9.88e-07,5.41e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1490000,1,-0.0115,-0.0143,-0.0215,0.0276,-0.00822,-0.196,0.00505,-0.00147,-0.134,-4.58e-07,-2.02e-06,-2.37e-09,1.16e-06,-2.53e-07,-3.54e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,2.61e-06,0.00637,0.00637,0.00108,1.01,1.01,0.519,0.189,0.189,0.582,9.62e-07,9.62e-07,4.87e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1590000,1,-0.0115,-0.0145,-0.0215,0.0345,-0.00945,-0.209,0.00813,-0.00235,-0.155,-4.58e-07,-2.02e-06,-2.37e-09,1.16e-06,-2.53e-07,-3.54e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,2.88e-06,0.00702,0.00702,0.00107,1.3,1.3,0.53,0.268,0.268,0.689,9.62e-07,9.62e-07,4.38e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1690000,1,-0.0115,-0.0144,-0.0216,0.0338,-0.0108,-0.221,0.00657,-0.00194,-0.176,-1.15e-06,-4.89e-06,2.08e-09,2.38e-06,-5.49e-07,-7.51e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,2.84e-06,0.00677,0.00677,0.00105,1.11,1.11,0.542,0.179,0.179,0.807,9.06e-07,9.06e-07,3.92e-07,3.98e-06,3.98e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1790000,1,-0.0116,-0.0147,-0.0216,0.0421,-0.0141,-0.236,0.0103,-0.00317,-0.199,-1.15e-06,-4.89e-06,2.08e-09,2.38e-06,-5.49e-07,-7.51e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,3.13e-06,0.00744,0.00744,0.00104,1.45,1.45,0.554,0.262,0.262,0.936,9.06e-07,9.06e-07,3.51e-07,3.98e-06,3.98e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1890000,1,-0.0114,-0.0143,-0.0216,0.038,-0.0127,-0.25,0.00781,-0.00249,-0.223,-2.41e-06,-9.68e-06,1.8e-08,4.1e-06,-9.99e-07,-1.33e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,2.85e-06,0.00658,0.00658,0.00102,1.19,1.19,0.567,0.178,0.178,1.08,8.16e-07,8.16e-07,3.14e-07,3.97e-06,3.97e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
1990000,1,-0.0114,-0.0145,-0.0216,0.0455,-0.015,-0.264,0.012,-0.00389,-0.249,-2.41e-06,-9.68e-06,1.8e-08,4.1e-06,-9.99e-07,-1.33e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,3.11e-06,0.00722,0.00722,0.000997,1.54,1.54,0.582,0.266,0.266,1.23,8.16e-07,8.16e-07,2.82e-07,3.97e-06,3.97e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2090000,1,-0.0112,-0.0139,-0.0217,0.036,-0.013,-0.278,0.00822,-0.00273,-0.276,-4.15e-06,-1.59e-05,4.61e-08,5.94e-06,-1.51e-06,-1.98e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,2.63e-06,0.00588,0.00588,0.000975,1.18,1.18,0.596,0.177,0.177,1.4,7.04e-07,7.05e-07,2.52e-07,3.96e-06,3.96e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2190000,1,-0.0113,-0.0141,-0.0217,0.0432,-0.0144,-0.293,0.0122,-0.00411,-0.305,-4.15e-06,-1.59e-05,4.61e-08,5.94e-06,-1.51e-06,-1.98e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,2.86e-06,0.00645,0.00645,0.000953,1.52,1.52,0.612,0.267,0.267,1.58,7.04e-07,7.05e-07,2.27e-07,3.96e-06,3.96e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2290000,1,-0.0111,-0.0134,-0.0217,0.0334,-0.0116,-0.308,0.00782,-0.00264,-0.335,-6.01e-06,-2.24e-05,7.9e-08,7.42e-06,-1.94e-06,-2.51e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,2.31e-06,0.00497,0.00497,0.000929,1.09,1.09,0.628,0.173,0.173,1.77,5.92e-07,5.92e-07,2.04e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2390000,1,-0.0112,-0.0136,-0.0217,0.0389,-0.0132,-0.321,0.0114,-0.00391,-0.366,-6.01e-06,-2.24e-05,7.9e-08,7.42e-06,-1.94e-06,-2.51e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,2.49e-06,0.00545,0.00545,0.000906,1.39,1.39,0.646,0.259,0.259,1.98,5.92e-07,5.92e-07,1.84e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2490000,1,-0.011,-0.0129,-0.0217,0.0284,-0.00992,-0.333,0.0071,-0.00242,-0.399,-7.7e-06,-2.82e-05,1.1e-07,8.34e-06,-2.21e-06,-2.86e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.96e-06,0.00411,0.00411,0.000882,0.964,0.964,0.664,0.166,0.166,2.2,4.94e-07,4.95e-07,1.66e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2590000,1,-0.011,-0.0131,-0.0217,0.033,-0.0108,-0.347,0.0102,-0.00345,-0.433,-7.7e-06,-2.82e-05,1.1e-07,8.34e-06,-2.21e-06,-2.86e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,2.11e-06,0.00452,0.00452,0.00086,1.22,1.22,0.683,0.245,0.245,2.44,4.94e-07,4.95e-07,1.5e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2690000,1,-0.0109,-0.0127,-0.0217,0.0238,-0.00733,-0.36,0.00622,-0.00208,-0.468,-9.09e-06,-3.3e-05,1.35e-07,8.72e-06,-2.32e-06,-3e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.68e-06,0.00342,0.00342,0.000837,0.838,0.838,0.702,0.157,0.157,2.7,4.14e-07,4.14e-07,1.36e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2790000,1,-0.0109,-0.0129,-0.0218,0.0276,-0.00873,-0.372,0.00879,-0.0029,-0.505,-9.09e-06,-3.3e-05,1.35e-07,8.72e-06,-2.32e-06,-3e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.8e-06,0.00376,0.00377,0.000815,1.05,1.05,0.723,0.228,0.228,2.97,4.14e-07,4.14e-07,1.23e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2890000,1,-0.0108,-0.0125,-0.0218,0.0202,-0.00634,-0.384,0.0054,-0.00175,-0.543,-1.02e-05,-3.68e-05,1.54e-07,8.7e-06,-2.31e-06,-2.99e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.46e-06,0.0029,0.0029,0.000794,0.728,0.728,0.744,0.148,0.148,3.25,3.49e-07,3.49e-07,1.12e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
2990000,1,-0.0108,-0.0126,-0.0218,0.0243,-0.0072,-0.398,0.00764,-0.00243,-0.582,-1.02e-05,-3.68e-05,1.54e-07,8.7e-06,-2.31e-06,-2.99e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.54e-06,0.0032,0.0032,0.000773,0.907,0.908,0.766,0.212,0.212,3.56,3.49e-07,3.49e-07,1.02e-07,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3090000,1,-0.0107,-0.0123,-0.0218,0.0177,-0.00491,-0.41,0.00477,-0.00149,-0.623,-1.1e-05,-4e-05,1.68e-07,8.41e-06,-2.23e-06,-2.88e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.27e-06,0.00252,0.00252,0.000753,0.64,0.64,0.789,0.139,0.139,3.88,2.96e-07,2.96e-07,9.36e-08,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3190000,1,-0.0108,-0.0123,-0.0218,0.0207,-0.00505,-0.425,0.00666,-0.00201,-0.664,-1.1e-05,-4e-05,1.68e-07,8.41e-06,-2.23e-06,-2.88e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.35e-06,0.00277,0.00277,0.000734,0.795,0.795,0.812,0.196,0.196,4.23,2.96e-07,2.96e-07,8.58e-08,3.95e-06,3.95e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3290000,1,-0.0107,-0.0121,-0.0218,0.0163,-0.00389,-0.437,0.00423,-0.00121,-0.708,-1.16e-05,-4.26e-05,1.78e-07,7.92e-06,-2.12e-06,-2.69e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.12e-06,0.00222,0.00223,0.000716,0.57,0.57,0.837,0.131,0.131,4.59,2.51e-07,2.51e-07,7.87e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3390000,1,-0.0107,-0.0122,-0.0218,0.0184,-0.00469,-0.451,0.00598,-0.00163,-0.752,-1.16e-05,-4.26e-05,1.78e-07,7.92e-06,-2.12e-06,-2.69e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.18e-06,0.00245,0.00245,0.000698,0.706,0.706,0.862,0.183,0.183,4.97,2.51e-07,2.51e-07,7.24e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3490000,1,-0.0107,-0.0123,-0.0219,0.0216,-0.00635,-0.464,0.00798,-0.00218,-0.798,-1.16e-05,-4.26e-05,1.78e-07,7.92e-06,-2.12e-06,-2.69e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.25e-06,0.00268,0.00268,0.000681,0.866,0.866,0.888,0.255,0.255,5.38,2.51e-07,2.51e-07,6.68e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3590000,1,-0.0106,-0.012,-0.0218,0.0161,-0.00603,-0.477,0.00539,-0.00157,-0.845,-1.21e-05,-4.49e-05,1.86e-07,7.3e-06,-1.98e-06,-2.45e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.05e-06,0.00218,0.00218,0.000665,0.636,0.636,0.915,0.172,0.172,5.8,2.12e-07,2.12e-07,6.16e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3690000,1,-0.0107,-0.0121,-0.0217,0.0186,-0.00808,-0.491,0.00715,-0.00228,-0.893,-1.21e-05,-4.49e-05,1.86e-07,7.3e-06,-1.98e-06,-2.45e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,1.11e-06,0.00239,0.00239,0.000649,0.779,0.779,0.943,0.237,0.237,6.25,2.12e-07,2.12e-07,5.7e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3790000,1,-0.0107,-0.0119,-0.0217,0.0144,-0.00838,-0.504,0.00485,-0.00181,-0.943,-1.27e-05,-4.69e-05,1.95e-07,6.6e-06,-1.78e-06,-2.17e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,9.38e-07,0.00196,0.00196,0.000634,0.58,0.58,0.971,0.162,0.162,6.72,1.79e-07,1.79e-07,5.28e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3890000,1,-0.0106,-0.012,-0.0217,0.0158,-0.0085,-0.518,0.00635,-0.00265,-0.994,-1.27e-05,-4.69e-05,1.95e-07,6.6e-06,-1.78e-06,-2.17e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,9.8e-07,0.00214,0.00214,0.00062,0.709,0.709,1,0.222,0.222,7.22,1.79e-07,1.79e-07,4.91e-08,3.94e-06,3.94e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
3990000,1,-0.0104,-0.0118,-0.0217,0.0134,-0.00697,-0.532,0.00432,-0.00196,-1.05,-1.33e-05,-4.86e-05,2.07e-07,5.87e-06,-1.51e-06,-1.86e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,8.34e-07,0.00176,0.00176,0.000606,0.533,0.533,1.03,0.153,0.153,7.74,1.49e-07,1.49e-07,4.56e-08,3.93e-06,3.93e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4090000,1,-0.0104,-0.0118,-0.0217,0.0155,-0.00838,-0.545,0.00577,-0.00271,-1.1,-1.33e-05,-4.86e-05,2.07e-07,5.87e-06,-1.51e-06,-1.86e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,8.68e-07,0.00191,0.00191,0.000592,0.649,0.649,1.06,0.209,0.209,8.29,1.49e-07,1.49e-07,4.25e-08,3.93e-06,3.93e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4190000,1,-0.0103,-0.0116,-0.0218,0.0132,-0.00753,-0.56,0.00406,-0.002,-1.16,-1.4e-05,-5.01e-05,2.2e-07,5.11e-06,-1.19e-06,-1.53e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,7.44e-07,0.00157,0.00157,0.000579,0.491,0.491,1.09,0.146,0.146,8.87,1.24e-07,1.24e-07,3.96e-08,3.93e-06,3.93e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4290000,1,-0.0103,-0.0116,-0.0218,0.0151,-0.00642,-0.573,0.00546,-0.00272,-1.21,-1.4e-05,-5.01e-05,2.2e-07,5.11e-06,-1.19e-06,-1.53e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,7.77e-07,0.00171,0.00171,0.000567,0.597,0.597,1.13,0.197,0.197,9.47,1.24e-07,1.24e-07,3.7e-08,3.93e-06,3.93e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4390000,1,-0.0102,-0.0115,-0.0218,0.0118,-0.00416,-0.587,0.00384,-0.0018,-1.27,-1.46e-05,-5.14e-05,2.32e-07,4.34e-06,-8.49e-07,-1.19e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,6.69e-07,0.0014,0.0014,0.000555,0.453,0.453,1.16,0.139,0.139,10.1,1.02e-07,1.02e-07,3.46e-08,3.92e-06,3.92e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4490000,1,-0.0102,-0.0115,-0.0218,0.013,-0.00443,-0.602,0.00508,-0.00221,-1.33,-1.46e-05,-5.14e-05,2.32e-07,4.34e-06,-8.49e-07,-1.19e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,6.91e-07,0.00152,0.00152,0.000544,0.549,0.549,1.19,0.187,0.187,10.8,1.02e-07,1.02e-07,3.24e-08,3.92e-06,3.92e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4590000,1,-0.0101,-0.0114,-0.0217,0.0114,-0.00355,-0.617,0.00357,-0.00145,-1.39,-1.5e-05,-5.26e-05,2.4e-07,3.59e-06,-5.71e-07,-8.71e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,6e-07,0.00124,0.00124,0.000532,0.418,0.418,1.23,0.132,0.132,11.5,8.3e-08,8.31e-08,3.04e-08,3.91e-06,3.91e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4690000,1,-0.0101,-0.0114,-0.0217,0.0125,-0.00461,-0.631,0.00479,-0.00184,-1.45,-1.5e-05,-5.26e-05,2.4e-07,3.59e-06,-5.71e-07,-8.71e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,6.19e-07,0.00134,0.00134,0.000522,0.504,0.504,1.26,0.177,0.177,12.2,8.3e-08,8.31e-08,2.85e-08,3.91e-06,3.91e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4790000,1,-0.0101,-0.0112,-0.0218,0.0101,-0.00401,-0.645,0.00334,-0.00128,-1.52,-1.54e-05,-5.37e-05,2.47e-07,2.87e-06,-3.31e-07,-5.74e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,5.42e-07,0.0011,0.0011,0.000512,0.385,0.385,1.3,0.127,0.127,13,6.74e-08,6.74e-08,2.68e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4890000,1,-0.0102,-0.0112,-0.0218,0.0112,-0.00515,-0.66,0.00443,-0.00172,-1.58,-1.54e-05,-5.37e-05,2.47e-07,2.87e-06,-3.31e-07,-5.74e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,5.58e-07,0.00118,0.00118,0.000502,0.461,0.461,1.34,0.168,0.168,13.7,6.74e-08,6.74e-08,2.52e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
4990000,1,-0.01,-0.0111,-0.0218,0.01,-0.00384,-0.675,0.00312,-0.00124,-1.65,-1.57e-05,-5.46e-05,2.53e-07,2.19e-06,-9.59e-08,-2.95e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,4.91e-07,0.000965,0.000966,0.000492,0.353,0.353,1.37,0.121,0.121,14.6,5.44e-08,5.44e-08,2.38e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5090000,1,-0.0101,-0.0111,-0.0218,0.0105,-0.004,-0.69,0.00414,-0.00162,-1.72,-1.57e-05,-5.46e-05,2.53e-07,2.19e-06,-9.59e-08,-2.95e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,5.03e-07,0.00103,0.00103,0.000483,0.421,0.421,1.41,0.16,0.16,15.4,5.44e-08,5.44e-08,2.24e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5190000,1,-0.01,-0.011,-0.0217,0.00848,-0.00361,-0.703,0.00289,-0.00116,-1.79,-1.6e-05,-5.54e-05,2.58e-07,1.57e-06,1.21e-07,-4.08e-09,0.192,-9.31e-10,0.404,0,0,0,0,0,4.47e-07,0.000848,0.000848,0.000474,0.323,0.323,1.45,0.116,0.116,16.3,4.38e-08,4.38e-08,2.12e-08,3.89e-06,3.89e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5290000,1,-0.00997,-0.011,-0.0218,0.00775,-0.00319,-0.718,0.00371,-0.00152,-1.86,-1.6e-05,-5.54e-05,2.58e-07,1.57e-06,1.21e-07,-4.08e-09,0.192,-9.31e-10,0.404,0,0,0,0,0,4.55e-07,0.000905,0.000905,0.000466,0.384,0.384,1.49,0.152,0.152,17.3,4.38e-08,4.38e-08,2e-08,3.89e-06,3.89e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5390000,1,-0.00987,-0.011,-0.0217,0.00449,-0.00244,-0.732,0.00246,-0.00103,-1.93,-1.62e-05,-5.6e-05,2.63e-07,1.05e-06,3.1e-07,1.71e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,4.08e-07,0.000744,0.000744,0.000457,0.295,0.295,1.53,0.111,0.111,18.3,3.52e-08,3.52e-08,1.9e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5490000,1,-0.00981,-0.011,-0.0217,0.00457,-0.00243,-0.745,0.00291,-0.00129,-2,-1.62e-05,-5.6e-05,2.63e-07,1.05e-06,3.1e-07,1.71e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,4.14e-07,0.000792,0.000792,0.000449,0.349,0.349,1.58,0.145,0.145,19.3,3.52e-08,3.52e-08,1.8e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5590000,1,-0.00978,-0.011,-0.0217,0.00517,-0.00242,-0.76,0.0034,-0.00152,-2.08,-1.62e-05,-5.6e-05,2.63e-07,1.05e-06,3.1e-07,1.71e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,4.2e-07,0.000841,0.000842,0.000442,0.41,0.41,1.62,0.188,0.188,20.4,3.52e-08,3.52e-08,1.7e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5690000,1,-0.00966,-0.011,-0.0217,0.00334,-0.00039,-0.775,0.00225,-0.000966,-2.16,-1.64e-05,-5.65e-05,2.66e-07,6.67e-07,4.61e-07,3.28e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,3.77e-07,0.000694,0.000694,0.000434,0.317,0.317,1.66,0.138,0.138,21.5,2.83e-08,2.83e-08,1.62e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5790000,1,-0.0096,-0.011,-0.0217,0.00365,0.00102,0,0.00257,-0.000936,-365,-1.64e-05,-5.65e-05,2.66e-07,6.67e-07,4.61e-07,3.28e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,3.82e-07,0.000735,0.000735,0.000427,0.371,0.371,10,0.178,0.178,4,2.83e-08,2.83e-08,1.53e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5890000,1,-0.00954,-0.0109,-0.0217,0.00316,0.00227,0.00413,0.00174,-0.0004,-365,-1.64e-05,-5.68e-05,2.68e-07,3.89e-07,5.45e-07,8.24e-09,0.192,-9.31e-10,0.404,0,0,0,0,0,3.48e-07,0.000609,0.000609,0.00042,0.288,0.288,9.76,0.131,0.131,0.471,2.27e-08,2.27e-08,1.46e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
5990000,1,-0.00951,-0.011,-0.0217,0.00344,0.00406,0.0213,0.00206,-3.97e-05,-365,-1.64e-05,-5.68e-05,2.68e-07,3.86e-07,5.47e-07,-1.1e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,3.52e-07,0.000643,0.000643,0.000413,0.335,0.335,8.56,0.168,0.168,0.323,2.27e-08,2.27e-08,1.39e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6090000,1,-0.00948,-0.0109,-0.0217,0.00329,0.00546,-0.0035,0.00146,0.000415,-365,-1.64e-05,-5.7e-05,2.67e-07,1.79e-07,5.26e-07,-2.21e-08,0.192,-9.31e-10,0.404,0,0,0,0,0,3.24e-07,0.000536,0.000537,0.000407,0.261,0.261,6.77,0.125,0.125,0.331,1.83e-08,1.83e-08,1.32e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6190000,1,-0.00948,-0.0109,-0.0218,0.00338,0.00751,0.00215,0.00181,0.00108,-365,-1.64e-05,-5.7e-05,2.67e-07,1.73e-07,5.32e-07,-2.76e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,3.27e-07,0.000565,0.000565,0.0004,0.303,0.303,4.66,0.159,0.159,0.319,1.83e-08,1.83e-08,1.26e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6290000,1,-0.00951,-0.0109,-0.0218,0.00359,0.00711,-0.00589,0.00136,0.00123,-365,-1.63e-05,-5.71e-05,2.63e-07,-1.07e-10,4e-07,-3.38e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,3.05e-07,0.000475,0.000475,0.000394,0.237,0.237,3.09,0.119,0.119,0.295,1.48e-08,1.48e-08,1.2e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6390000,1,-0.00939,-0.0108,-0.0218,0.00403,0.0084,-0.0441,0.00175,0.00201,-365,-1.63e-05,-5.71e-05,2.63e-07,1.36e-08,3.87e-07,2.89e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,3.05e-07,0.000498,0.000499,0.000388,0.274,0.274,2.16,0.151,0.151,0.288,1.48e-08,1.48e-08,1.15e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6490000,1,-0.00944,-0.0109,-0.0218,0.00367,0.00766,-0.048,0.00135,0.00184,-365,-1.61e-05,-5.73e-05,2.58e-07,-1.54e-07,1.83e-07,-1.73e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,2.87e-07,0.000422,0.000422,0.000382,0.215,0.215,1.47,0.113,0.113,0.256,1.2e-08,1.2e-08,1.09e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6590000,1,-0.00944,-0.0109,-0.0219,0.00361,0.00838,-0.0945,0.00173,0.0026,-365,-1.61e-05,-5.73e-05,2.58e-07,-1.13e-07,1.45e-07,1.71e-06,0.192,-9.31e-10,0.404,0,0,0,0,0,2.89e-07,0.000442,0.000442,0.000377,0.248,0.248,1.03,0.143,0.143,0.229,1.2e-08,1.2e-08,1.05e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6690000,1,-0.00946,-0.0109,-0.022,0.00353,0.0067,-0.0733,0.00132,0.00215,-365,-1.59e-05,-5.74e-05,2.52e-07,-3.26e-07,-4.32e-08,-1.49e-06,0.192,-9.31e-10,0.404,0,0,0,0,0,2.74e-07,0.000378,0.000378,0.000371,0.196,0.196,0.746,0.108,0.108,0.206,9.76e-09,9.77e-09,1e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6790000,1,-0.00944,-0.0108,-0.0219,0.00326,0.00811,-0.11,0.00168,0.00288,-365,-1.59e-05,-5.74e-05,2.52e-07,-2.73e-07,-9.08e-08,9.39e-07,0.192,-9.31e-10,0.404,0,0,0,0,0,2.74e-07,0.000394,0.000394,0.000366,0.225,0.225,0.577,0.136,0.136,0.196,9.76e-09,9.77e-09,9.57e-09,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
6890000,0.757,-0.0141,-0.00231,-0.654,0.00283,0.00845,-0.121,0.00126,0.0024,-365,-1.56e-05,-5.75e-05,2.48e-07,-4.13e-07,-3.46e-07,4.83e-07,-0.206,-0.0318,0.432,0,0,0,0,0,0.000873,0.000338,0.000339,0.00146,0.176,0.176,0.442,0.104,0.104,0.178,7.97e-09,7.98e-09,9.28e-09,3.86e-06,3.86e-06,3.98e-06,0,0,0,0,0,0,0,0
|
||||
6990000,0.759,-0.0141,-0.00241,-0.651,0.00297,0.00788,-0.123,0.00156,0.00319,-365,-1.56e-05,-5.75e-05,1.97e-07,-4.79e-07,-2.85e-07,-2.51e-06,-0.206,-0.0318,0.432,0,0,0,0,0,0.000525,0.000339,0.000339,0.000847,0.178,0.178,0.347,0.128,0.128,0.163,7.97e-09,7.98e-09,9.28e-09,3.86e-06,3.86e-06,3.98e-06,0,0,0,0,0,0,0,0
|
||||
7090000,0.76,-0.0141,-0.00243,-0.65,0.00343,0.00863,-0.124,0.00187,0.00403,-365,-1.56e-05,-5.75e-05,1.17e-07,-5.59e-07,-2.12e-07,-6.11e-06,-0.206,-0.0318,0.432,0,0,0,0,0,0.000402,0.000339,0.00034,0.000628,0.184,0.184,0.287,0.156,0.156,0.156,7.97e-09,7.97e-09,9.28e-09,3.86e-06,3.86e-06,3.97e-06,0,0,0,0,0,0,0,0
|
||||
7190000,0.76,-0.014,-0.00243,-0.65,0.0051,0.00903,-0.145,0.0023,0.0049,-365,-1.56e-05,-5.75e-05,1.08e-07,-5.09e-07,-2.55e-07,-3.87e-06,-0.206,-0.0318,0.432,0,0,0,0,0,0.000324,0.00034,0.000341,0.000491,0.193,0.193,0.236,0.188,0.188,0.144,7.97e-09,7.97e-09,9.28e-09,3.86e-06,3.86e-06,3.96e-06,0,0,0,0,0,0,0,0
|
||||
7290000,0.759,-0.014,-0.00245,-0.65,0.00656,0.00928,-0.145,0.00287,0.00582,-365,-1.56e-05,-5.76e-05,1.85e-07,-6.63e-07,-1.28e-07,-1.07e-05,-0.206,-0.0318,0.432,0,0,0,0,0,0.000277,0.000342,0.000342,0.000408,0.205,0.205,0.198,0.223,0.223,0.134,7.96e-09,7.96e-09,9.27e-09,3.86e-06,3.86e-06,3.95e-06,0,0,0,0,0,0,0,0
|
||||
7390000,0.759,-0.0139,-0.00246,-0.651,0.00687,0.00808,-0.157,0.00356,0.00667,-365,-1.56e-05,-5.76e-05,2.68e-07,-6.97e-07,-1.03e-07,-1.22e-05,-0.206,-0.0318,0.432,0,0,0,0,0,0.000249,0.000344,0.000344,0.000358,0.222,0.222,0.174,0.263,0.264,0.13,7.96e-09,7.96e-09,9.27e-09,3.86e-06,3.86e-06,3.94e-06,0,0,0,0,0,0,0,0
|
||||
7490000,0.759,-0.0139,-0.00252,-0.651,0.00848,0.00811,-0.16,0.00433,0.00745,-365,-1.56e-05,-5.76e-05,3.22e-07,-8.77e-07,4.42e-08,-2e-05,-0.206,-0.0318,0.432,0,0,0,0,0,0.000225,0.000346,0.000346,0.000315,0.241,0.241,0.152,0.308,0.308,0.122,7.94e-09,7.95e-09,9.26e-09,3.86e-06,3.86e-06,3.92e-06,0,0,0,0,0,0,0,0
|
||||
7590000,0.759,-0.0138,-0.00252,-0.651,0.0105,0.00736,-0.165,0.00525,0.00822,-365,-1.56e-05,-5.76e-05,5.39e-07,-1.07e-06,2.01e-07,-2.88e-05,-0.206,-0.0318,0.432,0,0,0,0,0,0.000207,0.000349,0.000349,0.000284,0.265,0.265,0.136,0.358,0.358,0.115,7.94e-09,7.95e-09,9.25e-09,3.86e-06,3.86e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7690000,0.759,-0.0137,-0.0026,-0.651,0.0124,0.00708,-0.161,0.0064,0.00896,-365,-1.56e-05,-5.76e-05,5.59e-07,-1.53e-06,5.89e-07,-4.94e-05,-0.206,-0.0318,0.432,0,0,0,0,0,0.000195,0.000352,0.000352,0.000263,0.292,0.292,0.126,0.415,0.415,0.112,7.94e-09,7.95e-09,9.24e-09,3.86e-06,3.86e-06,3.88e-06,0,0,0,0,0,0,0,0
|
||||
7790000,0.759,-0.0137,-0.00262,-0.651,0.0138,0.00654,-0.16,0.00766,0.00961,-365,-1.56e-05,-5.76e-05,2.19e-07,-1.99e-06,9.91e-07,-6.96e-05,-0.206,-0.0318,0.432,0,0,0,0,0,0.000184,0.000355,0.000355,0.000243,0.322,0.322,0.116,0.477,0.477,0.107,7.92e-09,7.93e-09,9.22e-09,3.86e-06,3.86e-06,3.84e-06,0,0,0,0,0,0,0,0
|
||||
7890000,0.759,-0.0137,-0.00264,-0.651,0.0168,0.00522,-0.157,0.00918,0.0102,-365,-1.56e-05,-5.76e-05,4.31e-07,-2.56e-06,1.46e-06,-9.52e-05,-0.206,-0.0318,0.432,0,0,0,0,0,0.000176,0.000359,0.000359,0.000227,0.357,0.357,0.109,0.548,0.548,0.102,7.92e-09,7.93e-09,9.2e-09,3.86e-06,3.86e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
7990000,0.759,-0.0137,-0.00268,-0.651,0.0187,0.00452,-0.163,0.0109,0.0106,-365,-1.56e-05,-5.76e-05,6.52e-07,-2.86e-06,1.7e-06,-0.000108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000168,0.000363,0.000363,0.000214,0.394,0.394,0.104,0.625,0.625,0.0981,7.9e-09,7.9e-09,9.17e-09,3.86e-06,3.86e-06,3.76e-06,0,0,0,0,0,0,0,0
|
||||
8090000,0.759,-0.0137,-0.00267,-0.651,0.0207,0.00352,-0.175,0.0129,0.011,-366,-1.56e-05,-5.76e-05,1.01e-06,-2.92e-06,1.73e-06,-0.00011,-0.206,-0.0318,0.432,0,0,0,0,0,0.000163,0.000368,0.000368,0.000204,0.436,0.436,0.102,0.716,0.716,0.097,7.9e-09,7.9e-09,9.15e-09,3.86e-06,3.86e-06,3.71e-06,0,0,0,0,0,0,0,0
|
||||
8190000,0.759,-0.0136,-0.00267,-0.651,0.0236,0.00254,-0.178,0.015,0.0112,-366,-1.56e-05,-5.76e-05,7.02e-07,-3.47e-06,2.21e-06,-0.000134,-0.206,-0.0318,0.432,0,0,0,0,0,0.000158,0.000372,0.000372,0.000195,0.479,0.479,0.0987,0.811,0.811,0.0939,7.86e-09,7.87e-09,9.11e-09,3.86e-06,3.86e-06,3.65e-06,0,0,0,0,0,0,0,0
|
||||
8290000,0.759,-0.0137,-0.00272,-0.651,0.025,0.00208,-0.174,0.0174,0.0114,-366,-1.56e-05,-5.76e-05,5.01e-07,-4.38e-06,2.98e-06,-0.000175,-0.206,-0.0318,0.432,0,0,0,0,0,0.000154,0.000377,0.000378,0.000187,0.529,0.529,0.0967,0.925,0.925,0.0912,7.86e-09,7.87e-09,9.07e-09,3.86e-06,3.86e-06,3.58e-06,0,0,0,0,0,0,0,0
|
||||
8390000,0.759,-0.0137,-0.00277,-0.651,0.027,0.00117,-0.173,0.0198,0.0115,-366,-1.56e-05,-5.76e-05,9.17e-07,-5.22e-06,3.67e-06,-0.00021,-0.206,-0.0318,0.432,0,0,0,0,0,0.000151,0.000382,0.000383,0.000181,0.578,0.578,0.0967,1.04,1.04,0.091,7.82e-09,7.83e-09,9.03e-09,3.86e-06,3.86e-06,3.52e-06,0,0,0,0,0,0,0,0
|
||||
8490000,0.759,-0.0137,-0.00276,-0.651,0.0292,-0.000193,-0.17,0.0227,0.0115,-366,-1.56e-05,-5.76e-05,7.64e-07,-6.16e-06,4.46e-06,-0.000253,-0.206,-0.0318,0.432,0,0,0,0,0,0.000148,0.000389,0.000389,0.000175,0.636,0.636,0.0957,1.19,1.19,0.089,7.82e-09,7.83e-09,8.98e-09,3.86e-06,3.86e-06,3.43e-06,0,0,0,0,0,0,0,0
|
||||
8590000,0.759,-0.0136,-0.00279,-0.651,0.0315,-0.00218,-0.167,0.0255,0.0113,-366,-1.56e-05,-5.76e-05,3.61e-07,-7.15e-06,5.35e-06,-0.000295,-0.206,-0.0318,0.432,0,0,0,0,0,0.000145,0.000394,0.000394,0.00017,0.69,0.69,0.0951,1.33,1.33,0.0874,7.77e-09,7.78e-09,8.93e-09,3.85e-06,3.85e-06,3.34e-06,0,0,0,0,0,0,0,0
|
||||
8690000,0.759,-0.0136,-0.00284,-0.651,0.0349,-0.00281,-0.162,0.0288,0.011,-366,-1.56e-05,-5.77e-05,9.76e-07,-8.31e-06,6.27e-06,-0.000347,-0.206,-0.0318,0.432,0,0,0,0,0,0.000143,0.0004,0.000401,0.000166,0.755,0.755,0.0958,1.51,1.51,0.0879,7.77e-09,7.78e-09,8.87e-09,3.85e-06,3.85e-06,3.25e-06,0,0,0,0,0,0,0,0
|
||||
8790000,0.759,-0.0135,-0.00279,-0.651,0.0371,-0.00448,-0.152,0.032,0.0105,-366,-1.56e-05,-5.77e-05,7.06e-07,-9.76e-06,7.61e-06,-0.00041,-0.206,-0.0318,0.432,0,0,0,0,0,0.000142,0.000405,0.000406,0.000162,0.814,0.814,0.0954,1.68,1.68,0.0867,7.71e-09,7.72e-09,8.8e-09,3.85e-06,3.85e-06,3.14e-06,0,0,0,0,0,0,0,0
|
||||
8890000,0.759,-0.0135,-0.00283,-0.651,0.0394,-0.00503,-0.151,0.0359,0.00998,-366,-1.56e-05,-5.77e-05,5.33e-07,-1.06e-05,8.32e-06,-0.000449,-0.206,-0.0318,0.432,0,0,0,0,0,0.00014,0.000413,0.000413,0.000158,0.887,0.887,0.0949,1.9,1.9,0.0857,7.71e-09,7.72e-09,8.73e-09,3.85e-06,3.85e-06,3.02e-06,0,0,0,0,0,0,0,0
|
||||
8990000,0.759,-0.0135,-0.00289,-0.651,0.041,-0.0056,-0.142,0.0392,0.00926,-365,-1.56e-05,-5.77e-05,5.78e-08,-1.2e-05,9.71e-06,-0.000509,-0.206,-0.0318,0.432,0,0,0,0,0,0.000139,0.000418,0.000418,0.000156,0.948,0.948,0.0956,2.1,2.1,0.0868,7.64e-09,7.65e-09,8.66e-09,3.84e-06,3.84e-06,2.91e-06,0,0,0,0,0,0,0,0
|
||||
9090000,0.759,-0.0135,-0.00293,-0.651,0.0438,-0.00618,-0.141,0.0435,0.00868,-366,-1.56e-05,-5.77e-05,-2.42e-07,-1.26e-05,1.02e-05,-0.000537,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000426,0.000426,0.000153,1.03,1.03,0.0949,2.36,2.36,0.086,7.64e-09,7.65e-09,8.58e-09,3.84e-06,3.84e-06,2.78e-06,0,0,0,0,0,0,0,0
|
||||
9190000,0.759,-0.0135,-0.00294,-0.651,0.0449,-0.00708,-0.141,0.0469,0.0078,-366,-1.56e-05,-5.78e-05,8.85e-07,-1.34e-05,1.12e-05,-0.000569,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.00043,0.00043,0.000151,1.09,1.09,0.094,2.59,2.59,0.0853,7.57e-09,7.57e-09,8.49e-09,3.84e-06,3.84e-06,2.65e-06,0,0,0,0,0,0,0,0
|
||||
9290000,0.759,-0.0135,-0.00294,-0.651,0.0465,-0.00816,-0.137,0.0515,0.00702,-366,-1.56e-05,-5.78e-05,1.02e-06,-1.44e-05,1.2e-05,-0.000615,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.000438,0.000439,0.000149,1.18,1.18,0.0929,2.91,2.91,0.0847,7.57e-09,7.57e-09,8.39e-09,3.84e-06,3.84e-06,2.52e-06,0,0,0,0,0,0,0,0
|
||||
9390000,0.758,-0.0135,-0.0029,-0.652,0.0473,-0.0102,-0.135,0.0546,0.0059,-366,-1.56e-05,-5.78e-05,1.01e-06,-1.52e-05,1.32e-05,-0.000649,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.000441,0.000441,0.000148,1.24,1.24,0.0928,3.16,3.16,0.086,7.48e-09,7.49e-09,8.3e-09,3.82e-06,3.82e-06,2.4e-06,0,0,0,0,0,0,0,0
|
||||
9490000,0.758,-0.0135,-0.00291,-0.652,0.0497,-0.0106,-0.13,0.0596,0.00486,-366,-1.56e-05,-5.78e-05,1.89e-06,-1.6e-05,1.38e-05,-0.000686,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.00045,0.000451,0.000146,1.33,1.33,0.0912,3.54,3.54,0.0854,7.48e-09,7.49e-09,8.19e-09,3.82e-06,3.82e-06,2.27e-06,0,0,0,0,0,0,0,0
|
||||
9590000,0.758,-0.0135,-0.00293,-0.652,0.0511,-0.0118,-0.127,0.0623,0.0036,-366,-1.55e-05,-5.79e-05,2.12e-06,-1.68e-05,1.52e-05,-0.000723,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000452,0.000452,0.000145,1.38,1.38,0.0894,3.8,3.8,0.0848,7.39e-09,7.39e-09,8.08e-09,3.81e-06,3.81e-06,2.13e-06,0,0,0,0,0,0,0,0
|
||||
9690000,0.758,-0.0135,-0.00301,-0.652,0.0537,-0.0138,-0.119,0.0677,0.00229,-366,-1.56e-05,-5.79e-05,1.23e-06,-1.79e-05,1.6e-05,-0.00077,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000461,0.000462,0.000144,1.48,1.48,0.0886,4.24,4.24,0.086,7.39e-09,7.39e-09,7.97e-09,3.81e-06,3.81e-06,2.02e-06,0,0,0,0,0,0,0,0
|
||||
9790000,0.758,-0.0134,-0.003,-0.652,0.0544,-0.0159,-0.109,0.0733,0.000803,-365,-1.56e-05,-5.79e-05,1.83e-06,-1.91e-05,1.7e-05,-0.000825,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000472,0.000472,0.000143,1.59,1.59,0.0864,4.73,4.73,0.0853,7.39e-09,7.39e-09,7.85e-09,3.81e-06,3.81e-06,1.89e-06,0,0,0,0,0,0,0,0
|
||||
9890000,0.758,-0.0133,-0.003,-0.652,0.0552,-0.017,-0.106,0.0754,-0.000886,-365,-1.55e-05,-5.8e-05,1.74e-06,-1.96e-05,1.84e-05,-0.00085,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000471,0.000471,0.000142,1.63,1.63,0.084,5.02,5.02,0.0846,7.29e-09,7.3e-09,7.72e-09,3.79e-06,3.79e-06,1.76e-06,0,0,0,0,0,0,0,0
|
||||
9990000,0.758,-0.0133,-0.00306,-0.652,0.0573,-0.0175,-0.1,0.0812,-0.00265,-365,-1.56e-05,-5.8e-05,1.3e-06,-2.04e-05,1.91e-05,-0.000888,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000482,0.000482,0.000142,1.74,1.74,0.0827,5.57,5.57,0.0857,7.29e-09,7.3e-09,7.61e-09,3.79e-06,3.79e-06,1.66e-06,0,0,0,0,0,0,0,0
|
||||
10090000,0.758,-0.0133,-0.00306,-0.652,0.0566,-0.0173,-0.096,0.0825,-0.00422,-365,-1.55e-05,-5.81e-05,1.52e-06,-2.09e-05,2.07e-05,-0.000914,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000479,0.00048,0.000141,1.77,1.77,0.0801,5.85,5.85,0.0848,7.19e-09,7.19e-09,7.47e-09,3.77e-06,3.77e-06,1.54e-06,0,0,0,0,0,0,0,0
|
||||
10190000,0.758,-0.0134,-0.00308,-0.652,0.0587,-0.0197,-0.0957,0.0883,-0.0061,-366,-1.56e-05,-5.8e-05,2.43e-07,-2.12e-05,2.1e-05,-0.000928,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000491,0.000491,0.00014,1.89,1.89,0.0774,6.47,6.47,0.0839,7.19e-09,7.19e-09,7.34e-09,3.77e-06,3.77e-06,1.44e-06,0,0,0,0,0,0,0,0
|
||||
10290000,0.759,-0.0134,-0.00303,-0.651,0.0575,-0.0195,-0.0832,0.0887,-0.00766,-365,-1.56e-05,-5.81e-05,-5.38e-07,-2.22e-05,2.33e-05,-0.000983,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.000486,0.000486,0.00014,1.9,1.9,0.0758,6.7,6.7,0.0847,7.08e-09,7.09e-09,7.21e-09,3.74e-06,3.74e-06,1.35e-06,0,0,0,0,0,0,0,0
|
||||
10390000,0.759,-0.0133,-0.003,-0.651,0.0107,-0.0205,0.00771,0.000943,-0.00184,-365,-1.56e-05,-5.81e-05,-4.83e-07,-2.28e-05,2.39e-05,-0.00101,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.000497,0.000498,0.00014,0.0418,0.0418,0.0402,0.25,0.25,0.0739,7.08e-09,7.09e-09,7.07e-09,3.74e-06,3.74e-06,1.26e-06,0,0,0,0,0,0,0,0
|
||||
10490000,0.759,-0.0133,-0.00305,-0.651,0.0123,-0.0221,0.00785,0.00211,-0.00399,-365,-1.56e-05,-5.81e-05,-1.23e-06,-2.36e-05,2.45e-05,-0.00105,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.000509,0.00051,0.000139,0.0479,0.0479,0.0405,0.252,0.252,0.0657,7.08e-09,7.09e-09,6.92e-09,3.74e-06,3.74e-06,1.19e-06,0,0,0,0,0,0,0,0
|
||||
10590000,0.759,-0.013,-0.00274,-0.651,0.0125,-0.0101,0.0109,0.00197,-0.000793,-365,-1.54e-05,-5.92e-05,-9.47e-07,-9.47e-06,2.23e-05,-0.00106,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.00048,0.000481,0.000139,0.0271,0.0271,0.0282,0.126,0.126,0.0589,6.86e-09,6.87e-09,6.77e-09,3.71e-06,3.71e-06,1.14e-06,0,0,0,0,0,0,0,0
|
||||
10690000,0.759,-0.013,-0.00278,-0.651,0.0146,-0.00882,0.00995,0.00329,-0.00172,-365,-1.54e-05,-5.92e-05,-9.77e-07,-9.75e-06,2.25e-05,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000492,0.000492,0.000139,0.0368,0.0368,0.0286,0.127,0.127,0.0555,6.86e-09,6.87e-09,6.64e-09,3.71e-06,3.71e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
10790000,0.759,-0.0128,-0.00243,-0.651,0.014,-0.00238,0.0101,0.00297,-0.000554,-365,-1.5e-05,-6e-05,-4.41e-07,1.37e-07,2.47e-05,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000411,0.000411,0.000138,0.0264,0.0264,0.0221,0.0848,0.0848,0.0508,6.36e-09,6.36e-09,6.49e-09,3.63e-06,3.63e-06,1.06e-06,0,0,0,0,0,0,0,0
|
||||
10890000,0.758,-0.0128,-0.00237,-0.652,0.0151,-0.00104,0.00714,0.00444,-0.000757,-365,-1.5e-05,-6e-05,-4.51e-08,1.67e-07,2.47e-05,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000421,0.000421,0.000138,0.0373,0.0373,0.0226,0.0861,0.0861,0.0485,6.36e-09,6.36e-09,6.34e-09,3.63e-06,3.63e-06,1.03e-06,0,0,0,0,0,0,0,0
|
||||
10990000,0.758,-0.0123,-0.00223,-0.652,0.0208,0.00662,0.00286,0.00692,0.00106,-365,-1.54e-05,-6.09e-05,1.33e-06,9.44e-06,1.71e-05,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000325,0.000325,0.000138,0.0266,0.0266,0.0185,0.0862,0.0862,0.0454,5.77e-09,5.78e-09,6.21e-09,3.55e-06,3.55e-06,9.94e-07,0,0,0,0,0,0,0,0
|
||||
11090000,0.758,-0.0123,-0.00222,-0.652,0.0229,0.00819,0.0026,0.00908,0.00184,-365,-1.53e-05,-6.1e-05,2.74e-06,9.15e-06,1.73e-05,-0.00109,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000334,0.000334,0.000138,0.0366,0.0366,0.0191,0.088,0.088,0.0442,5.77e-09,5.78e-09,6.06e-09,3.55e-06,3.55e-06,9.73e-07,0,0,0,0,0,0,0,0
|
||||
11190000,0.758,-0.0123,-0.00211,-0.652,0.0222,0.0113,-0.0018,0.0108,0.0031,-365,-1.51e-05,-6.11e-05,2.79e-06,1.14e-05,1.92e-05,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000257,0.000257,0.000137,0.0254,0.0254,0.0163,0.0878,0.0878,0.0412,5.29e-09,5.29e-09,5.9e-09,3.49e-06,3.49e-06,9.37e-07,0,0,0,0,0,0,0,0
|
||||
11290000,0.758,-0.0122,-0.00219,-0.652,0.0236,0.0132,-0.00329,0.0131,0.0043,-365,-1.51e-05,-6.11e-05,2.32e-06,1.13e-05,1.92e-05,-0.00109,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000264,0.000264,0.000138,0.0337,0.0337,0.017,0.0898,0.0898,0.0412,5.29e-09,5.29e-09,5.77e-09,3.49e-06,3.49e-06,9.23e-07,0,0,0,0,0,0,0,0
|
||||
11390000,0.758,-0.013,-0.00196,-0.652,0.0125,0.00808,-0.00814,0.00699,0.00171,-365,-1.34e-05,-6.02e-05,1.91e-06,7.91e-06,3.66e-05,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000211,0.000211,0.000137,0.0234,0.0234,0.015,0.0663,0.0663,0.0386,4.93e-09,4.93e-09,5.62e-09,3.46e-06,3.46e-06,8.85e-07,0,0,0,0,0,0,0,0
|
||||
11490000,0.758,-0.013,-0.00197,-0.652,0.0144,0.00872,-0.0112,0.00832,0.00255,-365,-1.35e-05,-6.01e-05,7.71e-07,8.07e-06,3.65e-05,-0.00107,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000217,0.000217,0.000137,0.03,0.03,0.0157,0.068,0.068,0.0386,4.93e-09,4.93e-09,5.47e-09,3.46e-06,3.46e-06,8.73e-07,0,0,0,0,0,0,0,0
|
||||
11590000,0.758,-0.0134,-0.00182,-0.652,0.00936,0.00509,-0.0168,0.00523,0.00119,-365,-1.25e-05,-5.96e-05,6.59e-07,6.7e-06,4.42e-05,-0.00105,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000183,0.000183,0.000137,0.0214,0.0214,0.0141,0.0537,0.0537,0.0367,4.66e-09,4.66e-09,5.34e-09,3.45e-06,3.45e-06,8.34e-07,0,0,0,0,0,0,0,0
|
||||
11690000,0.758,-0.0134,-0.00179,-0.652,0.0108,0.00468,-0.0235,0.00625,0.00171,-365,-1.25e-05,-5.96e-05,4.2e-07,7.21e-06,4.38e-05,-0.00103,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000189,0.000189,0.000137,0.0267,0.0267,0.015,0.0553,0.0553,0.0369,4.66e-09,4.66e-09,5.2e-09,3.45e-06,3.45e-06,8.24e-07,0,0,0,0,0,0,0,0
|
||||
11790000,0.758,-0.0137,-0.00142,-0.652,0.00295,0.00869,-0.0335,0.00239,0.00294,-365,-1.14e-05,-6e-05,6.03e-07,1.16e-05,4.89e-05,-0.000999,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000167,0.000167,0.000136,0.0195,0.0195,0.0137,0.0455,0.0455,0.035,4.45e-09,4.45e-09,5.06e-09,3.44e-06,3.44e-06,7.81e-07,0,0,0,0,0,0,0,0
|
||||
11890000,0.758,-0.0136,-0.00141,-0.652,0.00167,0.01,-0.0424,0.0026,0.00386,-366,-1.14e-05,-5.99e-05,1.13e-07,1.22e-05,4.84e-05,-0.000973,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000172,0.000172,0.000136,0.0239,0.0239,0.0146,0.0471,0.0471,0.0354,4.45e-09,4.45e-09,4.91e-09,3.44e-06,3.44e-06,7.73e-07,0,0,0,0,0,0,0,0
|
||||
11990000,0.758,-0.0138,-0.00131,-0.652,-0.00379,0.011,-0.0525,0.000145,0.00425,-366,-1.07e-05,-6e-05,5.21e-07,1.36e-05,4.99e-05,-0.000948,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000157,0.000157,0.000136,0.0179,0.0179,0.0135,0.0398,0.0398,0.0339,4.26e-09,4.27e-09,4.79e-09,3.44e-06,3.44e-06,7.28e-07,0,0,0,0,0,0,0,0
|
||||
12090000,0.758,-0.0138,-0.0013,-0.652,-0.00546,0.011,-0.0663,-0.000323,0.00537,-366,-1.07e-05,-6e-05,1.48e-06,1.45e-05,4.92e-05,-0.000909,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000162,0.000162,0.000136,0.0217,0.0217,0.0144,0.0414,0.0414,0.0345,4.26e-09,4.27e-09,4.66e-09,3.44e-06,3.44e-06,7.21e-07,0,0,0,0,0,0,0,0
|
||||
12190000,0.758,-0.0137,-0.00159,-0.652,-0.000612,0.00644,-0.0641,0.00203,0.00365,-366,-1.15e-05,-5.94e-05,1.85e-06,1.26e-05,4.95e-05,-0.000936,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000151,0.000151,0.000135,0.0166,0.0166,0.0134,0.0357,0.0357,0.0328,4.1e-09,4.1e-09,4.52e-09,3.44e-06,3.44e-06,6.73e-07,0,0,0,0,0,0,0,0
|
||||
12290000,0.758,-0.0137,-0.00156,-0.652,-1.89e-06,0.00665,-0.0732,0.00199,0.00429,-366,-1.15e-05,-5.94e-05,2.09e-06,1.3e-05,4.92e-05,-0.000918,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000156,0.000156,0.000135,0.0198,0.0198,0.0144,0.0373,0.0373,0.0337,4.1e-09,4.1e-09,4.41e-09,3.44e-06,3.44e-06,6.68e-07,0,0,0,0,0,0,0,0
|
||||
12390000,0.758,-0.0137,-0.00171,-0.652,0.00256,0.00416,-0.0704,0.00357,0.00314,-366,-1.2e-05,-5.9e-05,1.54e-06,1.24e-05,5.07e-05,-0.000952,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000148,0.000148,0.000135,0.0155,0.0155,0.0134,0.0326,0.0326,0.0322,3.93e-09,3.94e-09,4.28e-09,3.44e-06,3.44e-06,6.19e-07,0,0,0,0,0,0,0,0
|
||||
12490000,0.758,-0.0137,-0.00168,-0.652,0.00262,0.00331,-0.0811,0.00382,0.00351,-366,-1.2e-05,-5.89e-05,7.73e-07,1.29e-05,5.03e-05,-0.00093,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000153,0.000153,0.000134,0.0184,0.0184,0.0144,0.0343,0.0343,0.0329,3.93e-09,3.94e-09,4.15e-09,3.44e-06,3.44e-06,6.14e-07,0,0,0,0,0,0,0,0
|
||||
12590000,0.758,-0.0141,-0.00139,-0.652,-0.00931,0.00109,-0.0829,-0.00257,0.00273,-366,-1.02e-05,-5.89e-05,6.88e-07,1.33e-05,4.56e-05,-0.000949,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000146,0.000146,0.000134,0.0147,0.0147,0.0134,0.0303,0.0303,0.0317,3.77e-09,3.77e-09,4.04e-09,3.44e-06,3.44e-06,5.66e-07,0,0,0,0,0,0,0,0
|
||||
12690000,0.758,-0.0141,-0.00142,-0.652,-0.0113,0.000194,-0.0926,-0.00358,0.00279,-366,-1.03e-05,-5.89e-05,1.24e-07,1.37e-05,4.53e-05,-0.000928,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000151,0.000151,0.000134,0.0173,0.0173,0.0144,0.0319,0.0319,0.0325,3.77e-09,3.77e-09,3.92e-09,3.44e-06,3.44e-06,5.62e-07,0,0,0,0,0,0,0,0
|
||||
12790000,0.758,-0.0143,-0.00127,-0.652,-0.0184,0.000262,-0.0921,-0.0079,0.00242,-366,-9.24e-06,-5.9e-05,2.44e-07,1.31e-05,4.12e-05,-0.000959,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000146,0.000146,0.000133,0.014,0.014,0.0134,0.0284,0.0284,0.0311,3.59e-09,3.59e-09,3.81e-09,3.43e-06,3.43e-06,5.15e-07,0,0,0,0,0,0,0,0
|
||||
12890000,0.758,-0.0143,-0.00122,-0.652,-0.0208,0.000646,-0.0984,-0.00987,0.00249,-366,-9.24e-06,-5.9e-05,2.82e-07,1.33e-05,4.1e-05,-0.000951,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.00015,0.000151,0.000133,0.0164,0.0164,0.0144,0.03,0.03,0.0322,3.59e-09,3.59e-09,3.71e-09,3.43e-06,3.43e-06,5.11e-07,0,0,0,0,0,0,0,0
|
||||
12990000,0.758,-0.014,-0.00162,-0.652,-0.0107,0.000593,-0.0882,-0.00426,0.00243,-366,-1.16e-05,-5.87e-05,9.81e-07,1.34e-05,5.56e-05,-0.00102,-0.206,-0.0318,0.432,0,0,0,0,0,0.000138,0.000145,0.000146,0.000133,0.0136,0.0136,0.0134,0.03,0.03,0.0309,3.41e-09,3.41e-09,3.59e-09,3.43e-06,3.43e-06,4.66e-07,0,0,0,0,0,0,0,0
|
||||
13090000,0.758,-0.014,-0.00162,-0.652,-0.0117,0.00057,-0.0941,-0.00538,0.00249,-366,-1.16e-05,-5.87e-05,-2.3e-08,1.36e-05,5.54e-05,-0.00101,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.00015,0.00015,0.000132,0.0159,0.0159,0.0143,0.0317,0.0317,0.0317,3.41e-09,3.41e-09,3.49e-09,3.43e-06,3.43e-06,4.63e-07,0,0,0,0,0,0,0,0
|
||||
13190000,0.758,-0.0137,-0.00193,-0.652,-0.00392,-0.00085,-0.0821,-9.26e-05,0.00231,-366,-1.34e-05,-5.84e-05,-1.38e-07,1.4e-05,6.94e-05,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000145,0.000145,0.000132,0.0133,0.0133,0.0132,0.0316,0.0316,0.0304,3.21e-09,3.21e-09,3.38e-09,3.42e-06,3.42e-06,4.21e-07,0,0,0,0,0,0,0,0
|
||||
13290000,0.758,-0.0137,-0.00195,-0.652,-0.00412,-0.00166,-0.085,-0.000506,0.00218,-366,-1.34e-05,-5.84e-05,3.94e-07,1.4e-05,6.93e-05,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.00015,0.00015,0.000132,0.0155,0.0155,0.0142,0.0334,0.0334,0.0315,3.21e-09,3.21e-09,3.29e-09,3.42e-06,3.42e-06,4.18e-07,0,0,0,0,0,0,0,0
|
||||
13390000,0.758,-0.0135,-0.00201,-0.652,-0.000643,-0.00204,-0.0779,0.00209,0.00236,-366,-1.43e-05,-5.84e-05,7.86e-07,1.31e-05,7.66e-05,-0.00112,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000145,0.000145,0.000131,0.013,0.013,0.0131,0.0331,0.0331,0.0303,3.01e-09,3.01e-09,3.19e-09,3.41e-06,3.41e-06,3.79e-07,0,0,0,0,0,0,0,0
|
||||
13490000,0.758,-0.0135,-0.00205,-0.652,-0.000307,-0.00198,-0.0812,0.00202,0.00217,-366,-1.43e-05,-5.84e-05,1.04e-06,1.32e-05,7.66e-05,-0.00111,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000149,0.00015,0.000131,0.0152,0.0152,0.014,0.0351,0.0351,0.0311,3.01e-09,3.01e-09,3.1e-09,3.41e-06,3.41e-06,3.76e-07,0,0,0,0,0,0,0,0
|
||||
13590000,0.758,-0.0134,-0.00215,-0.652,0.00306,-0.00317,-0.076,0.00429,0.00237,-366,-1.5e-05,-5.85e-05,4.42e-07,1.22e-05,8.26e-05,-0.00115,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,0.000144,0.000144,0.000131,0.0128,0.0128,0.013,0.0347,0.0347,0.0302,2.8e-09,2.8e-09,3.01e-09,3.39e-06,3.39e-06,3.41e-07,0,0,0,0,0,0,0,0
|
||||
13690000,0.758,-0.0133,-0.00214,-0.652,0.00285,-0.00521,-0.0824,0.0046,0.00198,-366,-1.5e-05,-5.85e-05,9.71e-07,1.23e-05,8.24e-05,-0.00114,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.000149,0.000149,0.00013,0.0149,0.0149,0.0138,0.0367,0.0367,0.031,2.8e-09,2.8e-09,2.92e-09,3.39e-06,3.39e-06,3.38e-07,0,0,0,0,0,0,0,0
|
||||
13790000,0.758,-0.0133,-0.00229,-0.652,0.00599,-0.00648,-0.0755,0.00598,0.000111,-366,-1.54e-05,-5.81e-05,6.68e-07,1.51e-05,8.67e-05,-0.00117,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.000143,0.000143,0.000129,0.0124,0.0124,0.0127,0.0319,0.0319,0.0299,2.58e-09,2.58e-09,2.83e-09,3.37e-06,3.37e-06,3.06e-07,0,0,0,0,0,0,0,0
|
||||
13890000,0.758,-0.0133,-0.00228,-0.652,0.00604,-0.007,-0.0809,0.00658,-0.000543,-366,-1.54e-05,-5.81e-05,8.66e-07,1.53e-05,8.65e-05,-0.00117,-0.206,-0.0318,0.432,0,0,0,0,0,0.000136,0.000147,0.000148,0.000129,0.0145,0.0145,0.0136,0.0337,0.0337,0.0309,2.58e-09,2.58e-09,2.76e-09,3.37e-06,3.37e-06,3.04e-07,0,0,0,0,0,0,0,0
|
||||
13990000,0.758,-0.0133,-0.00239,-0.652,0.00843,-0.00843,-0.073,0.00722,-0.00177,-366,-1.56e-05,-5.79e-05,6.51e-07,1.67e-05,8.91e-05,-0.0012,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000142,0.000142,0.000129,0.0122,0.0122,0.0125,0.0297,0.0297,0.0298,2.36e-09,2.37e-09,2.68e-09,3.35e-06,3.35e-06,2.75e-07,0,0,0,0,0,0,0,0
|
||||
14090000,0.758,-0.0133,-0.0024,-0.652,0.0092,-0.00936,-0.0754,0.00812,-0.00264,-366,-1.56e-05,-5.79e-05,1.15e-06,1.68e-05,8.9e-05,-0.0012,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000146,0.000146,0.000128,0.0143,0.0143,0.0132,0.0314,0.0314,0.0306,2.36e-09,2.37e-09,2.6e-09,3.35e-06,3.35e-06,2.73e-07,0,0,0,0,0,0,0,0
|
||||
14190000,0.758,-0.0131,-0.00243,-0.652,0.0123,-0.00702,-0.0713,0.0103,-0.00146,-366,-1.63e-05,-5.84e-05,1.36e-06,1.17e-05,9.71e-05,-0.00122,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.00014,0.00014,0.000128,0.0121,0.0121,0.0122,0.028,0.028,0.0298,2.15e-09,2.15e-09,2.53e-09,3.33e-06,3.33e-06,2.48e-07,0,0,0,0,0,0,0,0
|
||||
14290000,0.758,-0.013,-0.00247,-0.652,0.0129,-0.00853,-0.0727,0.0116,-0.00222,-366,-1.63e-05,-5.84e-05,1.39e-06,1.17e-05,9.71e-05,-0.00122,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000144,0.000144,0.000127,0.0141,0.0141,0.0129,0.0296,0.0296,0.0306,2.15e-09,2.15e-09,2.45e-09,3.33e-06,3.33e-06,2.46e-07,0,0,0,0,0,0,0,0
|
||||
14390000,0.758,-0.0128,-0.00245,-0.653,0.0159,-0.00771,-0.0692,0.0131,-0.00123,-366,-1.68e-05,-5.89e-05,1.98e-06,6.4e-06,0.000103,-0.00124,-0.206,-0.0318,0.432,0,0,0,0,0,0.000134,0.000138,0.000138,0.000127,0.012,0.012,0.0119,0.0266,0.0266,0.0295,1.94e-09,1.94e-09,2.38e-09,3.31e-06,3.31e-06,2.23e-07,0,0,0,0,0,0,0,0
|
||||
14490000,0.758,-0.0128,-0.00246,-0.653,0.0177,-0.00943,-0.072,0.0148,-0.00208,-366,-1.68e-05,-5.89e-05,1.98e-06,6.52e-06,0.000103,-0.00123,-0.206,-0.0318,0.432,0,0,0,0,0,0.000134,0.000141,0.000141,0.000126,0.014,0.014,0.0125,0.0281,0.0281,0.0303,1.94e-09,1.94e-09,2.31e-09,3.31e-06,3.31e-06,2.21e-07,0,0,0,0,0,0,0,0
|
||||
14590000,0.758,-0.0129,-0.00216,-0.652,0.0105,-0.0109,-0.065,0.00995,-0.00298,-366,-1.52e-05,-5.91e-05,1.74e-06,4e-06,8.52e-05,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000134,0.000135,0.000135,0.000126,0.0119,0.0119,0.0116,0.0254,0.0254,0.0295,1.74e-09,1.74e-09,2.25e-09,3.28e-06,3.28e-06,2.01e-07,0,0,0,0,0,0,0,0
|
||||
14690000,0.758,-0.0129,-0.00215,-0.653,0.00975,-0.00889,-0.0644,0.0109,-0.00398,-366,-1.52e-05,-5.91e-05,2.08e-06,3.96e-06,8.52e-05,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000133,0.000138,0.000138,0.000125,0.0139,0.0139,0.0122,0.027,0.027,0.0303,1.74e-09,1.74e-09,2.18e-09,3.28e-06,3.28e-06,1.99e-07,0,0,0,0,0,0,0,0
|
||||
14790000,0.758,-0.0131,-0.00196,-0.653,0.00462,-0.00963,-0.0571,0.00722,-0.0047,-366,-1.4e-05,-5.92e-05,1.95e-06,2.44e-06,7.26e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000133,0.000132,0.000132,0.000125,0.0118,0.0118,0.0113,0.0245,0.0245,0.0293,1.55e-09,1.55e-09,2.12e-09,3.26e-06,3.26e-06,1.82e-07,0,0,0,0,0,0,0,0
|
||||
14890000,0.758,-0.013,-0.00197,-0.653,0.00378,-0.0117,-0.0598,0.00765,-0.00576,-366,-1.4e-05,-5.92e-05,2.11e-06,2.49e-06,7.25e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000133,0.000135,0.000135,0.000125,0.0138,0.0138,0.0119,0.0261,0.0261,0.0302,1.55e-09,1.55e-09,2.06e-09,3.26e-06,3.26e-06,1.8e-07,0,0,0,0,0,0,0,0
|
||||
14990000,0.758,-0.013,-0.00181,-0.652,0.00293,-0.00841,-0.0519,0.00667,-0.00429,-366,-1.39e-05,-5.99e-05,1.8e-06,-5.45e-06,7.16e-05,-0.00131,-0.206,-0.0318,0.432,0,0,0,0,0,0.000132,0.000129,0.000129,0.000124,0.0117,0.0117,0.011,0.0237,0.0237,0.0293,1.38e-09,1.38e-09,2e-09,3.24e-06,3.24e-06,1.65e-07,0,0,0,0,0,0,0,0
|
||||
15090000,0.758,-0.0129,-0.00175,-0.652,0.00297,-0.00898,-0.0539,0.00697,-0.00516,-366,-1.39e-05,-5.99e-05,1.63e-06,-5.34e-06,7.15e-05,-0.0013,-0.206,-0.0318,0.432,0,0,0,0,0,0.000132,0.000131,0.000132,0.000124,0.0136,0.0136,0.0115,0.0253,0.0253,0.03,1.38e-09,1.38e-09,1.95e-09,3.24e-06,3.24e-06,1.63e-07,0,0,0,0,0,0,0,0
|
||||
15190000,0.758,-0.0129,-0.00164,-0.652,0.00207,-0.00773,-0.0479,0.00606,-0.00399,-366,-1.38e-05,-6.04e-05,1.43e-06,-1.14e-05,7.04e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.000132,0.000126,0.000126,0.000123,0.0116,0.0116,0.0107,0.0231,0.0231,0.0293,1.22e-09,1.22e-09,1.9e-09,3.21e-06,3.21e-06,1.5e-07,0,0,0,0,0,0,0,0
|
||||
15290000,0.758,-0.0129,-0.00162,-0.653,0.00191,-0.00853,-0.0491,0.00626,-0.0048,-366,-1.38e-05,-6.04e-05,1.67e-06,-1.14e-05,7.04e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.000131,0.000128,0.000128,0.000123,0.0134,0.0134,0.0111,0.0247,0.0247,0.03,1.22e-09,1.22e-09,1.84e-09,3.21e-06,3.21e-06,1.48e-07,0,0,0,0,0,0,0,0
|
||||
15390000,0.757,-0.0128,-0.0015,-0.653,0.000397,-0.00694,-0.0454,0.00608,-0.00411,-366,-1.38e-05,-6.08e-05,2.36e-06,-1.69e-05,7.02e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000131,0.000123,0.000123,0.000122,0.0116,0.0116,0.0103,0.0247,0.0247,0.029,1.08e-09,1.08e-09,1.79e-09,3.19e-06,3.19e-06,1.36e-07,0,0,0,0,0,0,0,0
|
||||
15490000,0.758,-0.0128,-0.00153,-0.653,-0.000603,-0.00715,-0.0456,0.00606,-0.0048,-366,-1.38e-05,-6.08e-05,1.84e-06,-1.68e-05,7.01e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.000131,0.000125,0.000125,0.000122,0.0134,0.0134,0.0108,0.0264,0.0264,0.03,1.08e-09,1.08e-09,1.75e-09,3.19e-06,3.19e-06,1.35e-07,0,0,0,0,0,0,0,0
|
||||
15590000,0.758,-0.0128,-0.00147,-0.653,-0.00029,-0.00534,-0.042,0.00612,-0.00411,-366,-1.39e-05,-6.12e-05,1.5e-06,-2.1e-05,7.11e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.00013,0.00012,0.00012,0.000121,0.0115,0.0115,0.01,0.0263,0.0263,0.029,9.51e-10,9.52e-10,1.7e-09,3.18e-06,3.18e-06,1.25e-07,0,0,0,0,0,0,0,0
|
||||
15690000,0.758,-0.0128,-0.00148,-0.653,-0.000372,-0.00552,-0.0431,0.0061,-0.00467,-366,-1.39e-05,-6.12e-05,1.44e-06,-2.09e-05,7.1e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.00013,0.000122,0.000122,0.000121,0.0133,0.0133,0.0104,0.028,0.028,0.0297,9.52e-10,9.52e-10,1.65e-09,3.18e-06,3.18e-06,1.23e-07,0,0,0,0,0,0,0,0
|
||||
15790000,0.758,-0.0129,-0.00151,-0.653,-0.000993,-0.00664,-0.0419,0.00555,-0.0057,-366,-1.39e-05,-6.1e-05,1.37e-06,-1.82e-05,7.1e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000129,0.000117,0.000117,0.00012,0.0112,0.0112,0.00972,0.0252,0.0252,0.0288,8.41e-10,8.42e-10,1.6e-09,3.16e-06,3.16e-06,1.14e-07,0,0,0,0,0,0,0,0
|
||||
15890000,0.758,-0.0129,-0.00148,-0.653,-0.00169,-0.00675,-0.0416,0.00539,-0.00636,-366,-1.39e-05,-6.1e-05,1.4e-06,-1.82e-05,7.1e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000129,0.000119,0.000119,0.00012,0.0129,0.0129,0.0101,0.0269,0.0269,0.0297,8.41e-10,8.42e-10,1.56e-09,3.16e-06,3.16e-06,1.13e-07,0,0,0,0,0,0,0,0
|
||||
15990000,0.758,-0.0129,-0.00148,-0.653,-0.00156,-0.0078,-0.0378,0.00507,-0.00703,-366,-1.39e-05,-6.08e-05,1.83e-06,-1.65e-05,7.18e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000129,0.000114,0.000114,0.00012,0.011,0.011,0.00944,0.0244,0.0244,0.0288,7.45e-10,7.45e-10,1.52e-09,3.14e-06,3.14e-06,1.05e-07,0,0,0,0,0,0,0,0
|
||||
16090000,0.757,-0.0129,-0.00149,-0.653,-0.00302,-0.00844,-0.0374,0.00485,-0.00782,-366,-1.39e-05,-6.08e-05,2.47e-06,-1.65e-05,7.18e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000128,0.000116,0.000116,0.000119,0.0126,0.0126,0.00978,0.026,0.026,0.0295,7.45e-10,7.45e-10,1.48e-09,3.14e-06,3.14e-06,1.03e-07,0,0,0,0,0,0,0,0
|
||||
16190000,0.757,-0.0128,-0.00144,-0.653,-0.00294,-0.00647,-0.0347,0.00472,-0.00625,-366,-1.41e-05,-6.12e-05,2.51e-06,-2.06e-05,7.4e-05,-0.00134,-0.206,-0.0318,0.432,0,0,0,0,0,0.000128,0.000112,0.000112,0.000119,0.0108,0.0108,0.00917,0.0236,0.0236,0.0288,6.6e-10,6.61e-10,1.44e-09,3.13e-06,3.13e-06,9.63e-08,0,0,0,0,0,0,0,0
|
||||
16290000,0.757,-0.0128,-0.00147,-0.653,-0.00432,-0.00633,-0.0374,0.00435,-0.0069,-366,-1.41e-05,-6.12e-05,3.12e-06,-2.05e-05,7.39e-05,-0.00134,-0.206,-0.0318,0.432,0,0,0,0,0,0.000128,0.000113,0.000113,0.000118,0.0123,0.0123,0.00949,0.0252,0.0252,0.0294,6.61e-10,6.61e-10,1.4e-09,3.13e-06,3.13e-06,9.52e-08,0,0,0,0,0,0,0,0
|
||||
16390000,0.757,-0.0127,-0.0014,-0.653,-0.00321,-0.00376,-0.0363,0.00437,-0.00571,-366,-1.43e-05,-6.14e-05,2.87e-06,-2.31e-05,7.64e-05,-0.00134,-0.206,-0.0318,0.432,0,0,0,0,0,0.000127,0.000109,0.000109,0.000118,0.0105,0.0105,0.00888,0.023,0.023,0.0286,5.86e-10,5.87e-10,1.37e-09,3.12e-06,3.12e-06,8.88e-08,0,0,0,0,0,0,0,0
|
||||
16490000,0.757,-0.0127,-0.00142,-0.653,-0.00199,-0.0044,-0.0406,0.00414,-0.00612,-366,-1.43e-05,-6.14e-05,2.97e-06,-2.3e-05,7.64e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000127,0.000111,0.000111,0.000117,0.012,0.012,0.00921,0.0246,0.0246,0.0294,5.87e-10,5.87e-10,1.33e-09,3.12e-06,3.12e-06,8.79e-08,0,0,0,0,0,0,0,0
|
||||
16590000,0.757,-0.0126,-0.00119,-0.653,-0.00668,0.00263,-0.0435,0.000167,-0.00143,-366,-1.37e-05,-6.23e-05,3.07e-06,-3.55e-05,6.95e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000127,0.000107,0.000107,0.000117,0.0104,0.0104,0.00864,0.0225,0.0225,0.0286,5.22e-10,5.22e-10,1.3e-09,3.1e-06,3.1e-06,8.22e-08,0,0,0,0,0,0,0,0
|
||||
16690000,0.757,-0.0126,-0.00118,-0.653,-0.00691,0.00235,-0.045,-0.00053,-0.00119,-366,-1.37e-05,-6.23e-05,2.84e-06,-3.55e-05,6.95e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000126,0.000108,0.000109,0.000116,0.0118,0.0118,0.00891,0.0241,0.0241,0.0292,5.22e-10,5.22e-10,1.26e-09,3.1e-06,3.1e-06,8.13e-08,0,0,0,0,0,0,0,0
|
||||
16790000,0.757,-0.0125,-0.000959,-0.653,-0.00999,0.00779,-0.0453,-0.00361,0.00246,-366,-1.34e-05,-6.3e-05,2.95e-06,-4.41e-05,6.47e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000126,0.000105,0.000105,0.000116,0.0102,0.0102,0.0084,0.0221,0.0221,0.0286,4.65e-10,4.65e-10,1.24e-09,3.09e-06,3.09e-06,7.63e-08,0,0,0,0,0,0,0,0
|
||||
16890000,0.757,-0.0124,-0.000966,-0.653,-0.0101,0.0076,-0.0467,-0.00463,0.00325,-366,-1.34e-05,-6.3e-05,2.91e-06,-4.41e-05,6.47e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.000126,0.000106,0.000106,0.000116,0.0115,0.0115,0.00866,0.0236,0.0236,0.0291,4.65e-10,4.65e-10,1.2e-09,3.09e-06,3.09e-06,7.54e-08,0,0,0,0,0,0,0,0
|
||||
16990000,0.757,-0.0125,-0.00103,-0.653,-0.0111,0.00372,-0.0501,-0.00525,0.000434,-366,-1.33e-05,-6.24e-05,2.62e-06,-3.64e-05,6.36e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.000126,0.000103,0.000103,0.000115,0.00998,0.00998,0.00815,0.0218,0.0218,0.0283,4.16e-10,4.16e-10,1.17e-09,3.08e-06,3.08e-06,7.09e-08,0,0,0,0,0,0,0,0
|
||||
17090000,0.757,-0.0126,-0.001,-0.653,-0.0123,0.00296,-0.0537,-0.00643,0.000793,-366,-1.33e-05,-6.24e-05,2.74e-06,-3.63e-05,6.35e-05,-0.00131,-0.206,-0.0318,0.432,0,0,0,0,0,0.000125,0.000104,0.000104,0.000115,0.0113,0.0113,0.00839,0.0233,0.0233,0.0289,4.16e-10,4.16e-10,1.14e-09,3.08e-06,3.08e-06,7.01e-08,0,0,0,0,0,0,0,0
|
||||
17190000,0.757,-0.0127,-0.00109,-0.653,-0.0131,-0.00165,-0.0578,-0.00679,-0.00145,-366,-1.33e-05,-6.21e-05,2.99e-06,-3.09e-05,6.36e-05,-0.0013,-0.206,-0.0318,0.432,0,0,0,0,0,0.000125,0.000102,0.000102,0.000115,0.00979,0.00979,0.00794,0.0215,0.0215,0.0283,3.72e-10,3.72e-10,1.12e-09,3.08e-06,3.08e-06,6.61e-08,0,0,0,0,0,0,0,0
|
||||
17290000,0.757,-0.0126,-0.00106,-0.653,-0.0155,-0.00293,-0.0615,-0.00822,-0.00167,-366,-1.33e-05,-6.2e-05,2.72e-06,-3.09e-05,6.35e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000125,0.000103,0.000103,0.000114,0.0111,0.0111,0.00817,0.023,0.023,0.0288,3.72e-10,3.73e-10,1.09e-09,3.08e-06,3.08e-06,6.54e-08,0,0,0,0,0,0,0,0
|
||||
17390000,0.757,-0.0125,-0.00121,-0.653,-0.0124,-0.00541,-0.0609,-0.00625,-0.0032,-366,-1.37e-05,-6.18e-05,3.06e-06,-2.68e-05,6.89e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000124,0.0001,0.0001,0.000114,0.00961,0.00961,0.00771,0.0212,0.0212,0.0281,3.34e-10,3.35e-10,1.06e-09,3.07e-06,3.07e-06,6.17e-08,0,0,0,0,0,0,0,0
|
||||
17490000,0.757,-0.0125,-0.00121,-0.653,-0.0133,-0.00517,-0.0654,-0.00751,-0.00372,-366,-1.37e-05,-6.18e-05,3.1e-06,-2.68e-05,6.89e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000124,0.000101,0.000101,0.000113,0.0108,0.0108,0.00795,0.0227,0.0227,0.0288,3.35e-10,3.35e-10,1.04e-09,3.07e-06,3.07e-06,6.11e-08,0,0,0,0,0,0,0,0
|
||||
17590000,0.757,-0.0125,-0.00126,-0.653,-0.0116,-0.0067,-0.063,-0.00585,-0.00484,-366,-1.4e-05,-6.16e-05,3.18e-06,-2.39e-05,7.32e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000124,9.87e-05,9.88e-05,0.000113,0.00943,0.00943,0.00752,0.021,0.021,0.0281,3.01e-10,3.02e-10,1.01e-09,3.06e-06,3.06e-06,5.78e-08,0,0,0,0,0,0,0,0
|
||||
17690000,0.757,-0.0125,-0.00123,-0.653,-0.0125,-0.00777,-0.0704,-0.00706,-0.00554,-366,-1.4e-05,-6.16e-05,3.29e-06,-2.39e-05,7.31e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000123,9.95e-05,9.96e-05,0.000112,0.0106,0.0106,0.00772,0.0225,0.0225,0.0286,3.02e-10,3.02e-10,9.86e-10,3.06e-06,3.06e-06,5.72e-08,0,0,0,0,0,0,0,0
|
||||
17790000,0.757,-0.0123,-0.00133,-0.653,-0.00677,-0.00602,-0.0692,-0.00236,-0.00486,-366,-1.48e-05,-6.17e-05,3.98e-06,-2.44e-05,8.46e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000123,9.74e-05,9.75e-05,0.000112,0.00942,0.00942,0.00734,0.0226,0.0226,0.028,2.73e-10,2.73e-10,9.65e-10,3.06e-06,3.06e-06,5.43e-08,0,0,0,0,0,0,0,0
|
||||
17890000,0.757,-0.0123,-0.00134,-0.653,-0.00806,-0.00563,-0.0747,-0.0031,-0.00548,-366,-1.48e-05,-6.17e-05,4.22e-06,-2.44e-05,8.45e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000123,9.81e-05,9.83e-05,0.000112,0.0106,0.0106,0.00753,0.0242,0.0242,0.0285,2.73e-10,2.73e-10,9.41e-10,3.06e-06,3.06e-06,5.38e-08,0,0,0,0,0,0,0,0
|
||||
17990000,0.757,-0.0121,-0.00143,-0.653,-0.00303,-0.00275,-0.0718,0.00153,-0.00489,-366,-1.55e-05,-6.17e-05,4.14e-06,-2.42e-05,9.37e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000122,9.62e-05,9.63e-05,0.000111,0.00937,0.00937,0.00714,0.0242,0.0242,0.0278,2.47e-10,2.47e-10,9.19e-10,3.05e-06,3.05e-06,5.11e-08,0,0,0,0,0,0,0,0
|
||||
18090000,0.757,-0.0121,-0.00145,-0.653,-0.00301,-0.00275,-0.0752,0.00122,-0.00513,-366,-1.55e-05,-6.17e-05,3.68e-06,-2.42e-05,9.37e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000122,9.69e-05,9.7e-05,0.000111,0.0105,0.0105,0.00735,0.0259,0.0259,0.0285,2.47e-10,2.47e-10,8.99e-10,3.05e-06,3.05e-06,5.06e-08,0,0,0,0,0,0,0,0
|
||||
18190000,0.757,-0.012,-0.00146,-0.653,-0.000276,-0.00277,-0.0729,0.00347,-0.00445,-366,-1.58e-05,-6.17e-05,3.93e-06,-2.4e-05,9.75e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000122,9.51e-05,9.52e-05,0.000111,0.00907,0.00907,0.00698,0.0235,0.0235,0.0278,2.25e-10,2.25e-10,8.78e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18290000,0.757,-0.012,-0.00141,-0.653,0.000429,-0.00225,-0.077,0.00349,-0.0047,-366,-1.58e-05,-6.17e-05,3.73e-06,-2.41e-05,9.75e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000121,9.57e-05,9.58e-05,0.00011,0.0101,0.0101,0.00715,0.0251,0.0251,0.0282,2.25e-10,2.25e-10,8.57e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18390000,0.757,-0.0119,-0.00145,-0.654,0.00161,-0.00315,-0.0752,0.0051,-0.00415,-366,-1.59e-05,-6.18e-05,4.08e-06,-2.39e-05,0.0001,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000121,9.41e-05,9.42e-05,0.00011,0.00883,0.00883,0.0068,0.0229,0.0229,0.0276,2.05e-10,2.05e-10,8.36e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18490000,0.757,-0.0119,-0.00147,-0.654,0.00179,-0.00366,-0.08,0.00522,-0.0045,-366,-1.59e-05,-6.18e-05,4.15e-06,-2.39e-05,0.0001,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000121,9.47e-05,9.48e-05,0.00011,0.00987,0.00987,0.00699,0.0245,0.0245,0.0282,2.05e-10,2.05e-10,8.19e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18590000,0.757,-0.0118,-0.00141,-0.654,0.000976,-0.00308,-0.0796,0.00455,-0.00375,-366,-1.59e-05,-6.19e-05,4.56e-06,-2.45e-05,9.93e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000121,9.32e-05,9.33e-05,0.000109,0.00864,0.00864,0.00666,0.0224,0.0224,0.0275,1.88e-10,1.88e-10,8e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18690000,0.757,-0.0119,-0.00138,-0.654,0.00147,-0.00239,-0.0857,0.00468,-0.00405,-366,-1.59e-05,-6.19e-05,4.43e-06,-2.46e-05,9.94e-05,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.00012,9.38e-05,9.39e-05,0.000109,0.00963,0.00963,0.00682,0.024,0.024,0.0279,1.88e-10,1.88e-10,7.82e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18790000,0.757,-0.0119,-0.00136,-0.654,0.00134,-0.00203,-0.084,0.00414,-0.00355,-366,-1.59e-05,-6.19e-05,4.29e-06,-2.46e-05,9.85e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.00012,9.24e-05,9.25e-05,0.000109,0.00846,0.00846,0.00653,0.022,0.022,0.0275,1.73e-10,1.73e-10,7.66e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18890000,0.756,-0.0118,-0.00138,-0.654,0.00167,-0.00254,-0.09,0.0043,-0.00381,-366,-1.59e-05,-6.19e-05,4.69e-06,-2.48e-05,9.86e-05,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.00012,9.29e-05,9.3e-05,0.000108,0.00943,0.00943,0.00669,0.0236,0.0236,0.0279,1.73e-10,1.73e-10,7.48e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18990000,0.756,-0.0117,-0.00146,-0.654,0.00538,-0.00287,-0.092,0.00753,-0.00329,-366,-1.62e-05,-6.19e-05,4.86e-06,-2.44e-05,0.000103,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000119,9.16e-05,9.17e-05,0.000108,0.00831,0.00831,0.00639,0.0217,0.0217,0.0273,1.6e-10,1.6e-10,7.31e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19090000,0.756,-0.0117,-0.00145,-0.654,0.00585,-0.00345,-0.095,0.0081,-0.00363,-366,-1.62e-05,-6.19e-05,4.84e-06,-2.45e-05,0.000103,-0.00125,-0.206,-0.0318,0.432,0,0,0,0,0,0.000119,9.21e-05,9.22e-05,0.000108,0.00925,0.00925,0.00657,0.0232,0.0232,0.0279,1.6e-10,1.6e-10,7.17e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19190000,0.756,-0.0115,-0.00151,-0.654,0.00943,-0.0028,-0.0951,0.0106,-0.00305,-366,-1.64e-05,-6.19e-05,5e-06,-2.43e-05,0.000107,-0.00125,-0.206,-0.0318,0.432,0,0,0,0,0,0.000119,9.09e-05,9.1e-05,0.000107,0.00818,0.00818,0.00629,0.0214,0.0214,0.0272,1.48e-10,1.48e-10,7.01e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19290000,0.756,-0.0114,-0.00153,-0.654,0.0102,-0.00198,-0.0984,0.0117,-0.0033,-366,-1.64e-05,-6.19e-05,4.81e-06,-2.44e-05,0.000107,-0.00125,-0.206,-0.0318,0.432,0,0,0,0,0,0.000119,9.14e-05,9.15e-05,0.000107,0.00909,0.00909,0.00645,0.0229,0.0229,0.0276,1.48e-10,1.48e-10,6.85e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19390000,0.756,-0.0114,-0.00145,-0.654,0.00882,-0.000631,-0.0927,0.00986,-0.00284,-366,-1.62e-05,-6.2e-05,4.95e-06,-2.45e-05,0.000104,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000119,9.03e-05,9.04e-05,0.000107,0.00805,0.00805,0.0062,0.0212,0.0212,0.0272,1.37e-10,1.37e-10,6.72e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19490000,0.756,-0.0114,-0.00148,-0.654,0.0107,0.000336,-0.099,0.0109,-0.00285,-366,-1.62e-05,-6.2e-05,5.26e-06,-2.47e-05,0.000104,-0.00125,-0.206,-0.0318,0.432,0,0,0,0,0,0.000118,9.07e-05,9.08e-05,0.000106,0.00893,0.00893,0.00635,0.0226,0.0226,0.0276,1.37e-10,1.37e-10,6.57e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19590000,0.756,-0.0114,-0.00145,-0.654,0.00913,0.00154,-0.0961,0.00912,-0.00256,-366,-1.61e-05,-6.2e-05,5.65e-06,-2.44e-05,0.000101,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000118,8.97e-05,8.98e-05,0.000106,0.00793,0.00793,0.00609,0.0209,0.0209,0.027,1.27e-10,1.27e-10,6.43e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19690000,0.756,-0.0115,-0.00146,-0.654,0.0094,0.00378,-0.0978,0.01,-0.00229,-366,-1.61e-05,-6.2e-05,5.43e-06,-2.45e-05,0.000101,-0.00125,-0.206,-0.0318,0.432,0,0,0,0,0,0.000118,9.01e-05,9.02e-05,0.000106,0.00879,0.00879,0.00625,0.0224,0.0224,0.0273,1.27e-10,1.27e-10,6.29e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19790000,0.756,-0.0115,-0.00146,-0.654,0.00857,0.00458,-0.095,0.00851,-0.00235,-366,-1.59e-05,-6.2e-05,5.44e-06,-2.35e-05,9.83e-05,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000117,8.91e-05,8.92e-05,0.000105,0.00781,0.00781,0.00602,0.0208,0.0208,0.027,1.19e-10,1.19e-10,6.17e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19890000,0.756,-0.0114,-0.00141,-0.654,0.0106,0.00514,-0.0968,0.00946,-0.00185,-366,-1.59e-05,-6.2e-05,5.87e-06,-2.37e-05,9.84e-05,-0.00125,-0.206,-0.0318,0.432,0,0,0,0,0,0.000117,8.95e-05,8.96e-05,0.000105,0.00865,0.00865,0.00618,0.0222,0.0222,0.0273,1.19e-10,1.19e-10,6.04e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19990000,0.756,-0.0115,-0.00134,-0.655,0.0101,0.00577,-0.0924,0.00789,-0.00202,-366,-1.58e-05,-6.2e-05,6.43e-06,-2.25e-05,9.56e-05,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000117,8.86e-05,8.87e-05,0.000105,0.0077,0.0077,0.00594,0.0206,0.0206,0.0267,1.11e-10,1.11e-10,5.91e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20090000,0.756,-0.0115,-0.00133,-0.655,0.0107,0.00782,-0.0947,0.00894,-0.00136,-366,-1.57e-05,-6.2e-05,6.9e-06,-2.26e-05,9.56e-05,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000117,8.9e-05,8.91e-05,0.000105,0.00852,0.00852,0.00612,0.0221,0.0221,0.0273,1.11e-10,1.11e-10,5.8e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20190000,0.756,-0.0116,-0.00133,-0.655,0.00748,0.00811,-0.0881,0.00561,-0.00182,-366,-1.55e-05,-6.19e-05,7.09e-06,-2.1e-05,9.07e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000116,8.82e-05,8.83e-05,0.000104,0.00759,0.00759,0.00589,0.0205,0.0205,0.0267,1.04e-10,1.04e-10,5.68e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20290000,0.756,-0.0115,-0.0013,-0.655,0.00887,0.0099,-0.0917,0.00643,-0.00093,-366,-1.55e-05,-6.19e-05,7.23e-06,-2.11e-05,9.08e-05,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000116,8.85e-05,8.86e-05,0.000104,0.0084,0.00839,0.00605,0.0219,0.0219,0.0271,1.04e-10,1.04e-10,5.56e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20390000,0.756,-0.0117,-0.00124,-0.655,0.00654,0.01,-0.0849,0.00347,-0.00161,-366,-1.52e-05,-6.18e-05,7.21e-06,-1.9e-05,8.64e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000116,8.77e-05,8.78e-05,0.000104,0.00749,0.00749,0.00585,0.0204,0.0204,0.0267,9.77e-11,9.77e-11,5.46e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20490000,0.756,-0.0117,-0.0013,-0.655,0.00721,0.0108,-0.0864,0.00417,-0.000568,-366,-1.52e-05,-6.18e-05,7.03e-06,-1.92e-05,8.64e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000116,8.81e-05,8.82e-05,0.000103,0.00827,0.00827,0.00601,0.0218,0.0218,0.027,9.78e-11,9.78e-11,5.35e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20590000,0.756,-0.0118,-0.00131,-0.655,0.00567,0.0101,-0.0859,0.00328,-0.00133,-367,-1.51e-05,-6.17e-05,6.87e-06,-1.71e-05,8.46e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000115,8.73e-05,8.74e-05,0.000103,0.0074,0.0074,0.0058,0.0203,0.0203,0.0265,9.2e-11,9.21e-11,5.24e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20690000,0.756,-0.0118,-0.00133,-0.655,0.00573,0.0115,-0.0864,0.00386,-0.00026,-367,-1.51e-05,-6.17e-05,6.97e-06,-1.72e-05,8.46e-05,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000115,8.76e-05,8.77e-05,0.000103,0.00816,0.00816,0.00598,0.0217,0.0217,0.027,9.21e-11,9.22e-11,5.15e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20790000,0.755,-0.0118,-0.00135,-0.655,0.00597,0.0102,-0.0829,0.00312,-0.00113,-367,-1.51e-05,-6.16e-05,7.02e-06,-1.51e-05,8.3e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000115,8.7e-05,8.71e-05,0.000103,0.0073,0.0073,0.00577,0.0202,0.0202,0.0265,8.69e-11,8.69e-11,5.04e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20890000,0.755,-0.0118,-0.00134,-0.655,0.00631,0.0126,-0.0843,0.00373,1.17e-05,-367,-1.51e-05,-6.16e-05,7.28e-06,-1.52e-05,8.3e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000115,8.73e-05,8.74e-05,0.000102,0.00805,0.00805,0.00594,0.0216,0.0216,0.0268,8.7e-11,8.7e-11,4.94e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20990000,0.755,-0.0119,-0.00135,-0.655,0.00654,0.0129,-0.08,0.00326,-0.000892,-367,-1.5e-05,-6.15e-05,7.28e-06,-1.29e-05,8.13e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000114,8.66e-05,8.67e-05,0.000102,0.00738,0.00738,0.00573,0.0218,0.0218,0.0263,8.24e-11,8.24e-11,4.85e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21090000,0.755,-0.0119,-0.00135,-0.655,0.00659,0.0153,-0.0804,0.00392,0.000515,-367,-1.5e-05,-6.15e-05,7.43e-06,-1.29e-05,8.13e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000114,8.69e-05,8.7e-05,0.000102,0.00811,0.00811,0.00592,0.0233,0.0233,0.0268,8.25e-11,8.25e-11,4.76e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21190000,0.755,-0.0119,-0.00139,-0.655,0.0059,0.0134,-0.0772,0.0033,-0.000782,-367,-1.49e-05,-6.14e-05,7.31e-06,-1.05e-05,7.96e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000114,8.63e-05,8.64e-05,0.000101,0.00741,0.00741,0.00572,0.0233,0.0233,0.0263,7.82e-11,7.82e-11,4.67e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21290000,0.755,-0.0119,-0.00143,-0.656,0.0064,0.0156,-0.0767,0.00392,0.000656,-367,-1.49e-05,-6.14e-05,7.63e-06,-1.05e-05,7.96e-05,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000114,8.66e-05,8.67e-05,0.000101,0.00814,0.00814,0.00589,0.025,0.025,0.0266,7.83e-11,7.83e-11,4.58e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21390000,0.755,-0.0119,-0.00142,-0.655,0.00593,0.0168,-0.0731,0.00294,0.00107,-367,-1.48e-05,-6.13e-05,7.41e-06,-9.65e-06,7.83e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000114,8.6e-05,8.61e-05,0.000101,0.00722,0.00722,0.00571,0.0228,0.0228,0.0263,7.42e-11,7.42e-11,4.5e-10,3e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21490000,0.755,-0.0119,-0.00143,-0.656,0.00648,0.018,-0.0738,0.00358,0.0028,-367,-1.48e-05,-6.13e-05,7.52e-06,-9.72e-06,7.83e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000113,8.63e-05,8.64e-05,0.000101,0.00792,0.00792,0.00588,0.0244,0.0244,0.0266,7.43e-11,7.43e-11,4.41e-10,3e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21590000,0.755,-0.0119,-0.0014,-0.656,0.00619,0.017,-0.0698,0.00271,0.00287,-367,-1.47e-05,-6.13e-05,7.41e-06,-8.65e-06,7.7e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000113,8.57e-05,8.58e-05,0.0001,0.00706,0.00706,0.00569,0.0223,0.0223,0.0261,7.07e-11,7.07e-11,4.33e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21690000,0.755,-0.0119,-0.00142,-0.656,0.00608,0.0181,-0.0681,0.00333,0.00463,-367,-1.47e-05,-6.13e-05,7.51e-06,-8.67e-06,7.7e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000113,8.6e-05,8.61e-05,0.0001,0.00775,0.00775,0.00588,0.0239,0.0239,0.0266,7.08e-11,7.08e-11,4.26e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21790000,0.755,-0.0119,-0.00127,-0.656,0.00364,0.0195,-0.0652,0.000707,0.00825,-367,-1.46e-05,-6.14e-05,7.28e-06,-1.07e-05,7.51e-05,-0.0013,-0.206,-0.0318,0.432,0,0,0,0,0,0.000113,8.55e-05,8.56e-05,0.0001,0.00694,0.00694,0.00569,0.022,0.022,0.0261,6.75e-11,6.75e-11,4.18e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21890000,0.755,-0.0118,-0.00127,-0.656,0.00359,0.0201,-0.0634,0.00107,0.0102,-367,-1.46e-05,-6.14e-05,7.25e-06,-1.07e-05,7.51e-05,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000113,8.57e-05,8.58e-05,9.97e-05,0.00762,0.00762,0.00586,0.0234,0.0234,0.0264,6.75e-11,6.76e-11,4.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21990000,0.755,-0.0118,-0.00119,-0.656,0.00138,0.0229,-0.0585,-0.00117,0.0132,-367,-1.45e-05,-6.15e-05,7.24e-06,-1.22e-05,7.34e-05,-0.0013,-0.206,-0.0318,0.432,0,0,0,0,0,0.000112,8.53e-05,8.54e-05,9.96e-05,0.00684,0.00684,0.00569,0.0216,0.0216,0.0261,6.45e-11,6.45e-11,4.03e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22090000,0.755,-0.0118,-0.0012,-0.656,0.00173,0.0226,-0.058,-0.00103,0.0155,-367,-1.45e-05,-6.15e-05,7.2e-06,-1.22e-05,7.34e-05,-0.0013,-0.206,-0.0318,0.432,0,0,0,0,0,0.000112,8.55e-05,8.56e-05,9.93e-05,0.00751,0.00751,0.00586,0.0231,0.0231,0.0264,6.46e-11,6.46e-11,3.96e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22190000,0.755,-0.0119,-0.00122,-0.656,0.002,0.0188,-0.0512,-0.00106,0.0124,-367,-1.45e-05,-6.13e-05,7.23e-06,-8.91e-06,7.23e-05,-0.00131,-0.206,-0.0318,0.432,0,0,0,0,0,0.000112,8.5e-05,8.51e-05,9.91e-05,0.00676,0.00676,0.00567,0.0213,0.0213,0.026,6.19e-11,6.19e-11,3.89e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22290000,0.755,-0.0119,-0.00126,-0.656,0.00315,0.0201,-0.049,-0.000815,0.0143,-367,-1.45e-05,-6.13e-05,7.11e-06,-8.87e-06,7.23e-05,-0.00131,-0.206,-0.0318,0.432,0,0,0,0,0,0.000112,8.53e-05,8.54e-05,9.88e-05,0.00741,0.00741,0.00585,0.0228,0.0228,0.0263,6.2e-11,6.2e-11,3.82e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22390000,0.755,-0.0119,-0.00127,-0.656,0.00399,0.0172,-0.0423,-0.000947,0.0116,-367,-1.44e-05,-6.11e-05,7.18e-06,-6.11e-06,7.12e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.000112,8.49e-05,8.5e-05,9.87e-05,0.00669,0.00669,0.00568,0.0211,0.0211,0.026,5.94e-11,5.94e-11,3.75e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22490000,0.755,-0.0119,-0.00127,-0.656,0.00459,0.0176,-0.0395,-0.000529,0.0134,-367,-1.45e-05,-6.11e-05,7.13e-06,-6.02e-06,7.11e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.000111,8.51e-05,8.52e-05,9.84e-05,0.00733,0.00733,0.00585,0.0225,0.0225,0.0263,5.95e-11,5.95e-11,3.69e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22590000,0.755,-0.0119,-0.00128,-0.656,0.00586,0.0177,-0.0368,0.000881,0.0139,-367,-1.45e-05,-6.11e-05,7.15e-06,-4.86e-06,7.15e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.000111,8.47e-05,8.48e-05,9.81e-05,0.00678,0.00678,0.00567,0.0227,0.0227,0.0258,5.72e-11,5.72e-11,3.62e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22690000,0.755,-0.0119,-0.00131,-0.656,0.00712,0.018,-0.0349,0.00152,0.0157,-367,-1.45e-05,-6.11e-05,7.24e-06,-4.86e-06,7.15e-05,-0.00132,-0.206,-0.0318,0.432,0,0,0,0,0,0.000111,8.49e-05,8.5e-05,9.8e-05,0.00742,0.00742,0.00586,0.0242,0.0242,0.0263,5.73e-11,5.73e-11,3.57e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22790000,0.755,-0.0119,-0.00131,-0.656,0.00684,0.0149,-0.0306,0.000972,0.0141,-367,-1.44e-05,-6.1e-05,6.82e-06,-2.78e-06,7.01e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000111,8.45e-05,8.46e-05,9.78e-05,0.00685,0.00685,0.00568,0.0242,0.0242,0.0259,5.51e-11,5.51e-11,3.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22890000,0.755,-0.0119,-0.00132,-0.656,0.00828,0.015,-0.0282,0.00172,0.0156,-367,-1.44e-05,-6.1e-05,6.75e-06,-2.76e-06,7.01e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000111,8.48e-05,8.49e-05,9.75e-05,0.00748,0.00748,0.00585,0.0258,0.0258,0.0262,5.52e-11,5.52e-11,3.44e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22990000,0.755,-0.0119,-0.00132,-0.656,0.00726,0.0138,-0.024,0.000923,0.0142,-367,-1.43e-05,-6.09e-05,6.86e-06,-1.13e-06,6.88e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.00011,8.44e-05,8.45e-05,9.74e-05,0.00688,0.00688,0.00569,0.0258,0.0258,0.0259,5.32e-11,5.32e-11,3.39e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23090000,0.755,-0.0119,-0.00128,-0.656,0.00793,0.0141,-0.023,0.0017,0.0156,-367,-1.44e-05,-6.09e-05,6.58e-06,-1.06e-06,6.88e-05,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.00011,8.46e-05,8.47e-05,9.71e-05,0.00751,0.00751,0.00586,0.0275,0.0275,0.0262,5.33e-11,5.33e-11,3.33e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23190000,0.755,-0.012,-0.00125,-0.656,0.00141,0.0134,-0.0185,-0.00519,0.0142,-367,-1.41e-05,-6.08e-05,6.52e-06,-3.37e-07,6.43e-05,-0.00134,-0.206,-0.0318,0.432,0,0,0,0,0,0.00011,8.43e-05,8.44e-05,9.69e-05,0.0069,0.0069,0.00568,0.0274,0.0274,0.0258,5.14e-11,5.14e-11,3.27e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23290000,0.755,-0.012,-0.00119,-0.656,0.00163,0.0149,-0.0169,-0.00504,0.0156,-367,-1.41e-05,-6.08e-05,6.52e-06,-3.57e-07,6.43e-05,-0.00134,-0.206,-0.0318,0.432,0,0,0,0,0,0.00011,8.45e-05,8.46e-05,9.68e-05,0.00752,0.00752,0.00587,0.0292,0.0292,0.0263,5.15e-11,5.15e-11,3.22e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23390000,0.755,-0.0121,-0.0012,-0.656,-0.00404,0.0135,-0.0157,-0.0115,0.0141,-367,-1.39e-05,-6.07e-05,6.46e-06,4.4e-07,6.07e-05,-0.00134,-0.206,-0.0318,0.432,0,0,0,0,0,0.00011,8.41e-05,8.42e-05,9.65e-05,0.0069,0.0069,0.00569,0.029,0.029,0.0258,4.97e-11,4.97e-11,3.17e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23490000,0.755,-0.00948,-0.00341,-0.656,0.00229,0.0155,-0.048,-0.0117,0.0155,-367,-1.39e-05,-6.07e-05,6.55e-06,4.2e-07,6.06e-05,-0.00134,-0.206,-0.0318,0.432,0,0,0,0,0,0.00011,8.43e-05,8.44e-05,9.63e-05,0.00754,0.00754,0.00587,0.0308,0.0308,0.0261,4.98e-11,4.98e-11,3.12e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23590000,0.755,-0.00131,-0.00805,-0.655,0.0125,0.0163,-0.0765,-0.0126,0.0143,-367,-1.38e-05,-6.07e-05,6.41e-06,1.43e-06,5.89e-05,-0.00134,-0.206,-0.0318,0.432,0,0,0,0,0,0.000109,8.39e-05,8.4e-05,9.61e-05,0.00669,0.00669,0.00568,0.0274,0.0274,0.0257,4.81e-11,4.81e-11,3.06e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23690000,0.756,0.00442,-0.00727,-0.655,0.0415,0.0293,-0.126,-0.00994,0.0165,-367,-1.38e-05,-6.07e-05,6.36e-06,1.49e-06,5.89e-05,-0.00134,-0.206,-0.0318,0.432,0,0,0,0,0,0.000109,8.41e-05,8.41e-05,9.6e-05,0.00733,0.00733,0.00588,0.0291,0.0291,0.0262,4.82e-11,4.82e-11,3.02e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23790000,0.756,0.000797,-0.00453,-0.654,0.0599,0.043,-0.173,-0.0144,0.0144,-367,-1.35e-05,-6.06e-05,6.38e-06,3.82e-06,4.88e-05,-0.00136,-0.206,-0.0318,0.432,0,0,0,0,0,0.000109,8.36e-05,8.37e-05,9.57e-05,0.00658,0.00657,0.0057,0.0261,0.0261,0.0257,4.66e-11,4.66e-11,2.97e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23890000,0.756,-0.00546,-0.00234,-0.654,0.0743,0.0544,-0.226,-0.00753,0.0193,-367,-1.35e-05,-6.06e-05,6.3e-06,3.86e-06,4.88e-05,-0.00135,-0.206,-0.0318,0.432,0,0,0,0,0,0.000109,8.38e-05,8.39e-05,9.54e-05,0.00721,0.00721,0.00587,0.0277,0.0277,0.0261,4.67e-11,4.67e-11,2.92e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23990000,0.756,-0.0107,-0.00104,-0.654,0.0531,0.0472,-0.274,-0.0295,0.0107,-367,-1.25e-05,-6.03e-05,6.32e-06,1.59e-05,1.11e-05,-0.00136,-0.206,-0.0318,0.432,0,0,0,0,0,0.000109,8.33e-05,8.34e-05,9.52e-05,0.00669,0.00669,0.00571,0.0277,0.0277,0.0258,4.52e-11,4.52e-11,2.88e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24090000,0.756,-0.00934,-0.00223,-0.654,0.0537,0.0476,-0.321,-0.0242,0.0155,-367,-1.25e-05,-6.03e-05,6.41e-06,1.58e-05,1.11e-05,-0.00136,-0.206,-0.0318,0.432,0,0,0,0,0,0.000109,8.35e-05,8.36e-05,9.5e-05,0.00732,0.00732,0.00588,0.0294,0.0294,0.0261,4.53e-11,4.53e-11,2.83e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24190000,0.756,-0.00749,-0.00294,-0.654,0.0379,0.0399,-0.36,-0.0452,0.00686,-367,-1.17e-05,-6.01e-05,6.39e-06,3.01e-05,-2.75e-05,-0.00138,-0.206,-0.0318,0.432,0,0,0,0,0,0.000108,8.29e-05,8.3e-05,9.48e-05,0.00677,0.00677,0.0057,0.0293,0.0293,0.0257,4.39e-11,4.39e-11,2.79e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24290000,0.756,-0.00665,-0.00337,-0.654,0.0459,0.0448,-0.415,-0.041,0.0111,-367,-1.17e-05,-6.01e-05,6.26e-06,3.02e-05,-2.74e-05,-0.00138,-0.206,-0.0318,0.432,0,0,0,0,0,0.000108,8.31e-05,8.32e-05,9.47e-05,0.00741,0.0074,0.0059,0.031,0.031,0.0262,4.4e-11,4.4e-11,2.75e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24390000,0.757,-0.00763,-0.00333,-0.654,0.0288,0.0321,-0.462,-0.0682,-0.00584,-367,-1.08e-05,-5.96e-05,6.03e-06,5.73e-05,-7.84e-05,-0.00139,-0.206,-0.0318,0.432,0,0,0,0,0,0.000108,8.24e-05,8.25e-05,9.45e-05,0.00683,0.00683,0.00571,0.0309,0.0309,0.0257,4.27e-11,4.27e-11,2.7e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24490000,0.757,-0.00344,-0.00388,-0.654,0.0388,0.0381,-0.512,-0.0648,-0.00237,-367,-1.08e-05,-5.96e-05,5.92e-06,5.75e-05,-7.84e-05,-0.00139,-0.206,-0.0318,0.432,0,0,0,0,0,0.000108,8.26e-05,8.26e-05,9.43e-05,0.00746,0.00746,0.00589,0.0327,0.0327,0.0261,4.28e-11,4.28e-11,2.66e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24590000,0.756,-0.000494,-0.00397,-0.654,0.0302,0.033,-0.554,-0.0919,-0.0189,-367,-9.95e-06,-5.92e-05,5.99e-06,8.53e-05,-0.000131,-0.00141,-0.206,-0.0318,0.432,0,0,0,0,0,0.000108,8.18e-05,8.19e-05,9.42e-05,0.00687,0.00686,0.00572,0.0325,0.0325,0.0258,4.16e-11,4.16e-11,2.62e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24690000,0.756,0.000437,-0.00394,-0.654,0.0496,0.0482,-0.637,-0.0879,-0.0149,-367,-9.95e-06,-5.92e-05,5.99e-06,8.52e-05,-0.000131,-0.0014,-0.206,-0.0318,0.432,0,0,0,0,0,0.000108,8.2e-05,8.21e-05,9.4e-05,0.00752,0.00752,0.0059,0.0343,0.0343,0.0261,4.17e-11,4.17e-11,2.58e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24790000,0.757,-0.00168,-0.00341,-0.654,0.0355,0.0489,-0.717,-0.123,-0.0265,-367,-8.91e-06,-5.89e-05,5.7e-06,0.000109,-0.000204,-0.00141,-0.206,-0.0318,0.432,0,0,0,0,0,0.000108,8.12e-05,8.13e-05,9.37e-05,0.00693,0.00693,0.00571,0.0341,0.0341,0.0257,4.05e-11,4.05e-11,2.54e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24890000,0.757,0.000107,-0.00503,-0.654,0.0517,0.0611,-0.739,-0.119,-0.021,-367,-8.91e-06,-5.89e-05,5.48e-06,0.000109,-0.000204,-0.00141,-0.206,-0.0318,0.432,0,0,0,0,0,0.000107,8.13e-05,8.14e-05,9.35e-05,0.00753,0.00753,0.00589,0.0359,0.0359,0.026,4.06e-11,4.06e-11,2.5e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24990000,0.757,0.00115,-0.00643,-0.654,0.0425,0.059,-0.788,-0.155,-0.0346,-367,-7.89e-06,-5.86e-05,5.18e-06,0.000139,-0.00028,-0.00142,-0.206,-0.0318,0.432,0,0,0,0,0,0.000107,8.05e-05,8.06e-05,9.34e-05,0.00691,0.00691,0.00572,0.0357,0.0357,0.0257,3.95e-11,3.95e-11,2.47e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25090000,0.757,0.000546,-0.00677,-0.653,0.066,0.0714,-0.837,-0.15,-0.0281,-367,-7.89e-06,-5.86e-05,4.89e-06,0.00014,-0.00028,-0.00142,-0.206,-0.0318,0.432,0,0,0,0,0,0.000107,8.07e-05,8.07e-05,9.32e-05,0.00753,0.00753,0.0059,0.0375,0.0375,0.0261,3.96e-11,3.96e-11,2.43e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25190000,0.757,-0.000914,-0.00644,-0.653,0.0865,0.0789,-0.884,-0.142,-0.0205,-367,-7.9e-06,-5.86e-05,4.85e-06,0.00014,-0.00028,-0.00143,-0.206,-0.0318,0.432,0,0,0,0,0,0.000107,8.08e-05,8.09e-05,9.3e-05,0.00819,0.00819,0.00572,0.0396,0.0396,0.0256,3.97e-11,3.97e-11,2.39e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25290000,0.757,0.006,-0.00784,-0.653,0.109,0.0899,-0.938,-0.132,-0.0122,-367,-7.9e-06,-5.86e-05,4.74e-06,0.00014,-0.00028,-0.00143,-0.206,-0.0318,0.432,0,0,0,0,0,0.000107,8.1e-05,8.1e-05,9.3e-05,0.0089,0.00889,0.00591,0.0418,0.0418,0.0261,3.98e-11,3.98e-11,2.36e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25390000,0.757,0.0126,-0.00879,-0.654,0.142,0.112,-0.978,-0.12,-0.00211,-368,-7.9e-06,-5.86e-05,4.66e-06,0.000141,-0.000281,-0.00144,-0.206,-0.0318,0.432,0,0,0,0,0,0.000107,8.11e-05,8.12e-05,9.28e-05,0.00964,0.00963,0.00573,0.0443,0.0443,0.0257,3.99e-11,3.99e-11,2.33e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25490000,0.757,0.0138,-0.00894,-0.653,0.182,0.139,-1.03,-0.104,0.0104,-368,-7.91e-06,-5.86e-05,4.6e-06,0.000141,-0.000281,-0.00144,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.13e-05,8.13e-05,9.26e-05,0.0104,0.0104,0.0059,0.0471,0.0471,0.026,3.99e-11,4e-11,2.29e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25590000,0.757,0.0119,-0.00867,-0.654,0.22,0.165,-1.08,-0.0835,0.0257,-368,-7.91e-06,-5.86e-05,4.5e-06,0.000142,-0.000281,-0.00144,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.14e-05,8.15e-05,9.25e-05,0.0113,0.0113,0.00574,0.0501,0.0501,0.0257,4e-11,4.01e-11,2.26e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25690000,0.757,0.0188,-0.0117,-0.653,0.26,0.189,-1.14,-0.0596,0.0433,-368,-7.91e-06,-5.86e-05,4.4e-06,0.000142,-0.000281,-0.00144,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.16e-05,8.16e-05,9.24e-05,0.0122,0.0122,0.00591,0.0534,0.0533,0.0261,4.01e-11,4.02e-11,2.23e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25790000,0.757,0.0255,-0.014,-0.653,0.316,0.222,-1.18,-0.0308,0.0638,-368,-7.92e-06,-5.86e-05,4.38e-06,0.000143,-0.000283,-0.00145,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.18e-05,8.17e-05,9.22e-05,0.0131,0.0131,0.00573,0.057,0.057,0.0256,4.02e-11,4.03e-11,2.2e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25890000,0.756,0.0259,-0.0143,-0.653,0.377,0.258,-1.23,0.00381,0.0879,-368,-7.92e-06,-5.86e-05,4.41e-06,0.000143,-0.000283,-0.00144,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.19e-05,8.19e-05,9.21e-05,0.0141,0.0141,0.00593,0.0609,0.0609,0.0262,4.03e-11,4.04e-11,2.17e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25990000,0.757,0.0227,-0.0136,-0.653,0.433,0.291,-1.29,0.0442,0.115,-368,-7.91e-06,-5.86e-05,4.34e-06,0.000142,-0.000281,-0.00143,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.21e-05,8.21e-05,9.19e-05,0.0152,0.0152,0.00574,0.0653,0.0653,0.0257,4.04e-11,4.05e-11,2.14e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26090000,0.76,0.0329,-0.0176,-0.649,0.49,0.324,-1.31,0.0902,0.146,-368,-7.92e-06,-5.86e-05,4.03e-06,0.000143,-0.00028,-0.00143,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.23e-05,8.22e-05,9.14e-05,0.0163,0.0162,0.00592,0.07,0.07,0.026,4.05e-11,4.06e-11,2.11e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26190000,0.761,0.0428,-0.0194,-0.647,0.561,0.369,-1.28,0.143,0.181,-369,-7.92e-06,-5.86e-05,3.96e-06,0.000143,-0.00028,-0.00143,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.25e-05,8.23e-05,9.11e-05,0.0173,0.0173,0.00573,0.0752,0.0752,0.0256,4.06e-11,4.07e-11,2.08e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26290000,0.761,0.0451,-0.0201,-0.647,0.644,0.421,-1.27,0.203,0.22,-369,-7.92e-06,-5.86e-05,3.78e-06,0.000143,-0.000279,-0.00143,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.26e-05,8.24e-05,9.1e-05,0.0185,0.0184,0.00593,0.0808,0.0808,0.0261,4.07e-11,4.08e-11,2.05e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26390000,0.76,0.0417,-0.0195,-0.648,0.723,0.471,-1.28,0.271,0.265,-369,-7.91e-06,-5.86e-05,3.71e-06,0.000141,-0.000274,-0.00141,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,8.28e-05,8.26e-05,9.09e-05,0.0197,0.0197,0.00574,0.087,0.0869,0.0257,4.08e-11,4.09e-11,2.02e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26490000,0.758,0.058,-0.0262,-0.649,0.808,0.521,-1.28,0.347,0.314,-369,-7.91e-06,-5.86e-05,3.57e-06,0.000141,-0.000273,-0.00141,-0.206,-0.0318,0.432,0,0,0,0,0,0.000105,8.3e-05,8.27e-05,9.09e-05,0.021,0.0209,0.00593,0.0937,0.0936,0.026,4.09e-11,4.1e-11,2e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26590000,0.756,0.0749,-0.0315,-0.649,0.925,0.591,-1.27,0.433,0.37,-369,-7.91e-06,-5.86e-05,3.14e-06,0.00014,-0.000264,-0.0014,-0.206,-0.0318,0.432,0,0,0,0,0,0.000105,8.33e-05,8.28e-05,9.1e-05,0.0223,0.0223,0.00576,0.101,0.101,0.0257,4.1e-11,4.11e-11,1.97e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26690000,0.755,0.0777,-0.0325,-0.65,1.06,0.671,-1.26,0.532,0.433,-369,-7.91e-06,-5.86e-05,3.13e-06,0.00014,-0.000264,-0.00139,-0.206,-0.0318,0.432,0,0,0,0,0,0.000105,8.35e-05,8.29e-05,9.1e-05,0.0238,0.0238,0.00594,0.109,0.109,0.0261,4.11e-11,4.12e-11,1.94e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26790000,0.755,0.0721,-0.0311,-0.651,1.18,0.744,-1.27,0.644,0.503,-369,-7.89e-06,-5.85e-05,2.9e-06,0.000138,-0.000254,-0.00138,-0.206,-0.0318,0.432,0,0,0,0,0,0.000105,8.36e-05,8.31e-05,9.09e-05,0.0254,0.0253,0.00576,0.117,0.117,0.0256,4.12e-11,4.13e-11,1.92e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26890000,0.752,0.0946,-0.0384,-0.651,1.32,0.82,-1.28,0.768,0.581,-369,-7.89e-06,-5.85e-05,2.84e-06,0.000138,-0.000253,-0.00138,-0.206,-0.0318,0.432,0,0,0,0,0,0.000104,8.39e-05,8.31e-05,9.1e-05,0.027,0.027,0.00597,0.127,0.126,0.0261,4.13e-11,4.14e-11,1.89e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26990000,0.749,0.117,-0.0437,-0.65,1.49,0.924,-1.26,0.907,0.668,-370,-7.87e-06,-5.85e-05,2.69e-06,0.000135,-0.000242,-0.00136,-0.206,-0.0318,0.432,0,0,0,0,0,0.000104,8.43e-05,8.31e-05,9.1e-05,0.0287,0.0287,0.00579,0.137,0.136,0.0257,4.14e-11,4.15e-11,1.87e-10,2.97e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27090000,0.748,0.121,-0.0443,-0.651,1.68,1.04,-1.24,1.07,0.766,-370,-7.88e-06,-5.85e-05,2.53e-06,0.000135,-0.000239,-0.00136,-0.206,-0.0318,0.432,0,0,0,0,0,0.000104,8.45e-05,8.33e-05,9.09e-05,0.0306,0.0306,0.00599,0.147,0.147,0.026,4.15e-11,4.16e-11,1.84e-10,2.97e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27190000,0.749,0.111,-0.0415,-0.652,1.86,1.15,-1.22,1.24,0.875,-370,-7.85e-06,-5.85e-05,2.38e-06,0.000131,-0.000226,-0.00135,-0.206,-0.0318,0.432,0,0,0,0,0,0.000104,8.46e-05,8.35e-05,9.09e-05,0.0326,0.0325,0.00583,0.159,0.159,0.0258,4.16e-11,4.16e-11,1.82e-10,2.97e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27290000,0.75,0.095,-0.037,-0.654,2.01,1.24,-1.21,1.43,0.995,-370,-7.85e-06,-5.85e-05,2.31e-06,0.000131,-0.000225,-0.00135,-0.206,-0.0318,0.432,0,0,0,0,0,0.000104,8.46e-05,8.38e-05,9.06e-05,0.0345,0.0346,0.00603,0.172,0.171,0.0261,4.17e-11,4.17e-11,1.8e-10,2.97e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27390000,0.751,0.0789,-0.0319,-0.655,2.12,1.31,-1.21,1.64,1.12,-370,-7.8e-06,-5.85e-05,2.24e-06,0.000125,-0.000207,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000104,8.47e-05,8.42e-05,9.04e-05,0.0365,0.0366,0.00585,0.185,0.185,0.0257,4.18e-11,4.18e-11,1.77e-10,2.97e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27490000,0.753,0.0635,-0.0273,-0.655,2.2,1.36,-1.2,1.85,1.25,-370,-7.8e-06,-5.85e-05,2.1e-06,0.000124,-0.000204,-0.00133,-0.206,-0.0318,0.432,0,0,0,0,0,0.000104,8.48e-05,8.45e-05,9.01e-05,0.0384,0.0387,0.00606,0.2,0.2,0.026,4.19e-11,4.19e-11,1.75e-10,2.97e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27590000,0.754,0.0508,-0.0234,-0.655,2.25,1.38,-1.21,2.07,1.39,-370,-7.74e-06,-5.84e-05,1.97e-06,0.000115,-0.000178,-0.00131,-0.206,-0.0318,0.432,0,0,0,0,0,0.000104,8.49e-05,8.47e-05,8.99e-05,0.0404,0.0408,0.0059,0.215,0.215,0.0257,4.2e-11,4.2e-11,1.73e-10,2.97e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27690000,0.754,0.0491,-0.0229,-0.655,2.29,1.41,-1.21,2.3,1.53,-371,-7.74e-06,-5.84e-05,1.79e-06,0.000115,-0.000176,-0.0013,-0.206,-0.0318,0.432,0,0,0,0,0,0.000103,8.51e-05,8.49e-05,8.97e-05,0.0424,0.043,0.0061,0.232,0.232,0.0261,4.21e-11,4.21e-11,1.71e-10,2.97e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27790000,0.754,0.051,-0.023,-0.654,2.32,1.43,-1.21,2.53,1.67,-371,-7.69e-06,-5.84e-05,1.52e-06,0.000104,-0.000146,-0.00129,-0.206,-0.0318,0.432,0,0,0,0,0,0.000103,8.53e-05,8.51e-05,8.95e-05,0.0445,0.0453,0.00593,0.25,0.25,0.0256,4.22e-11,4.22e-11,1.69e-10,2.97e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27890000,0.754,0.049,-0.0225,-0.654,2.35,1.45,-1.21,2.76,1.81,-371,-7.69e-06,-5.84e-05,1.49e-06,0.000103,-0.000144,-0.00128,-0.206,-0.0318,0.432,0,0,0,0,0,0.000103,8.55e-05,8.53e-05,8.94e-05,0.0466,0.0477,0.00616,0.27,0.269,0.0262,4.22e-11,4.23e-11,1.67e-10,2.97e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27990000,0.755,0.0451,-0.0217,-0.654,2.38,1.46,-1.22,2.99,1.96,-371,-7.66e-06,-5.84e-05,1.42e-06,9.54e-05,-0.000123,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000103,8.56e-05,8.56e-05,8.92e-05,0.0488,0.0502,0.00598,0.29,0.29,0.0257,4.23e-11,4.24e-11,1.65e-10,2.96e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28090000,0.754,0.0589,-0.0264,-0.654,2.41,1.48,-1.23,3.23,2.11,-371,-7.66e-06,-5.84e-05,1.16e-06,9.49e-05,-0.00012,-0.00127,-0.206,-0.0318,0.432,0,0,0,0,0,0.000103,8.58e-05,8.57e-05,8.92e-05,0.0511,0.0528,0.0062,0.312,0.312,0.0261,4.24e-11,4.25e-11,1.63e-10,2.96e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28190000,0.753,0.0724,-0.0304,-0.654,2.45,1.51,-0.955,3.47,2.26,-371,-7.64e-06,-5.84e-05,1.1e-06,8.79e-05,-0.000102,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000103,8.6e-05,8.58e-05,8.92e-05,0.0527,0.0546,0.00605,0.336,0.336,0.0258,4.25e-11,4.26e-11,1.61e-10,2.96e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28290000,0.753,0.0549,-0.024,-0.655,2.45,1.52,-0.0913,3.72,2.41,-371,-7.64e-06,-5.84e-05,9.19e-07,8.71e-05,-9.81e-05,-0.00126,-0.206,-0.0318,0.432,0,0,0,0,0,0.000103,8.61e-05,8.61e-05,8.91e-05,0.0529,0.055,0.00631,0.36,0.361,0.0262,4.26e-11,4.27e-11,1.59e-10,2.96e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28390000,0.753,0.0223,-0.0102,-0.657,2.44,1.53,0.769,3.96,2.56,-371,-7.63e-06,-5.84e-05,7.54e-07,8.53e-05,-9.27e-05,-0.00125,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.63e-05,8.65e-05,8.89e-05,0.0536,0.0558,0.00655,0.386,0.387,0.0265,4.27e-11,4.28e-11,1.57e-10,2.96e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28490000,0.753,0.00344,-0.00273,-0.657,2.4,1.52,1.06,4.2,2.71,-371,-7.62e-06,-5.84e-05,7.07e-07,8.34e-05,-8.77e-05,-0.00125,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.66e-05,8.69e-05,8.87e-05,0.0553,0.0579,0.00678,0.412,0.414,0.0271,4.28e-11,4.29e-11,1.55e-10,2.96e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28590000,0.754,-0.000203,-0.00122,-0.657,2.33,1.48,0.963,4.44,2.86,-371,-7.62e-06,-5.84e-05,7.05e-07,8.05e-05,-8.02e-05,-0.00124,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.68e-05,8.71e-05,8.84e-05,0.0578,0.0607,0.00701,0.44,0.442,0.0275,4.29e-11,4.3e-11,1.53e-10,2.96e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28690000,0.755,-0.00118,-0.000584,-0.655,2.26,1.45,0.967,4.67,3.01,-371,-7.61e-06,-5.84e-05,6.45e-07,7.71e-05,-7.12e-05,-0.00124,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.7e-05,8.73e-05,8.82e-05,0.0602,0.0635,0.00723,0.47,0.473,0.0279,4.3e-11,4.31e-11,1.51e-10,2.96e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28790000,0.756,-0.00139,-0.000345,-0.655,2.18,1.42,0.968,4.89,3.15,-371,-7.58e-06,-5.83e-05,5.26e-07,6.29e-05,-3.39e-05,-0.00122,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.69e-05,8.75e-05,8.79e-05,0.0627,0.0663,0.00691,0.502,0.505,0.0273,4.31e-11,4.32e-11,1.5e-10,2.96e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28890000,0.756,-0.00119,-0.000305,-0.654,2.12,1.4,0.958,5.1,3.29,-371,-7.58e-06,-5.83e-05,4.94e-07,5.96e-05,-2.5e-05,-0.00122,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.71e-05,8.77e-05,8.78e-05,0.0654,0.0693,0.00715,0.535,0.54,0.0279,4.32e-11,4.33e-11,1.48e-10,2.96e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28990000,0.757,-0.000732,-0.000443,-0.654,2.05,1.37,0.949,5.31,3.43,-371,-7.56e-06,-5.83e-05,3.4e-07,4.68e-05,8.38e-06,-0.00121,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.69e-05,8.79e-05,8.76e-05,0.0682,0.0724,0.00684,0.571,0.576,0.0273,4.33e-11,4.34e-11,1.46e-10,2.96e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29090000,0.757,-0.000343,-0.000554,-0.653,1.99,1.34,0.942,5.51,3.57,-371,-7.56e-06,-5.83e-05,2.67e-07,4.33e-05,1.77e-05,-0.0012,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.71e-05,8.81e-05,8.75e-05,0.0711,0.0756,0.00705,0.608,0.615,0.0277,4.34e-11,4.35e-11,1.45e-10,2.96e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29190000,0.757,0.000213,-0.00076,-0.653,1.92,1.32,0.929,5.71,3.7,-371,-7.55e-06,-5.83e-05,3.36e-07,2.04e-05,7.79e-05,-0.00118,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.69e-05,8.83e-05,8.74e-05,0.0741,0.0789,0.00678,0.647,0.655,0.0273,4.35e-11,4.36e-11,1.43e-10,2.95e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29290000,0.757,0.00105,-0.00103,-0.653,1.86,1.29,0.956,5.89,3.83,-371,-7.54e-06,-5.83e-05,2.38e-07,1.63e-05,8.85e-05,-0.00118,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.71e-05,8.85e-05,8.73e-05,0.0772,0.0822,0.00699,0.689,0.699,0.0277,4.36e-11,4.37e-11,1.41e-10,2.95e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29390000,0.757,0.0027,-0.00146,-0.653,1.81,1.27,0.959,6.08,3.96,-370,-7.54e-06,-5.83e-05,6.25e-09,-1.02e-05,0.000157,-0.00116,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.68e-05,8.87e-05,8.71e-05,0.0804,0.0857,0.0067,0.733,0.744,0.0271,4.37e-11,4.38e-11,1.4e-10,2.95e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29490000,0.757,0.00383,-0.00187,-0.653,1.75,1.25,0.957,6.26,4.08,-370,-7.54e-06,-5.83e-05,8.05e-10,-1.31e-05,0.000165,-0.00115,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.7e-05,8.89e-05,8.71e-05,0.0837,0.0894,0.00693,0.779,0.792,0.0277,4.38e-11,4.39e-11,1.38e-10,2.95e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29590000,0.757,0.00508,-0.00217,-0.653,1.7,1.23,0.943,6.43,4.21,-370,-7.55e-06,-5.83e-05,-8.85e-09,-3.65e-05,0.000226,-0.00114,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.68e-05,8.91e-05,8.69e-05,0.0873,0.0932,0.00665,0.828,0.843,0.0271,4.39e-11,4.4e-11,1.37e-10,2.95e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29690000,0.757,0.00573,-0.00239,-0.653,1.66,1.21,0.938,6.6,4.33,-370,-7.54e-06,-5.83e-05,-9.03e-08,-3.96e-05,0.000234,-0.00113,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.7e-05,8.93e-05,8.68e-05,0.0909,0.0971,0.00686,0.879,0.897,0.0274,4.4e-11,4.41e-11,1.35e-10,2.95e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29790000,0.757,0.0063,-0.00259,-0.654,1.61,1.2,0.92,6.76,4.45,-370,-7.56e-06,-5.83e-05,-4.02e-08,-5.87e-05,0.000283,-0.00112,-0.206,-0.0318,0.432,0,0,0,0,0,0.000102,8.67e-05,8.95e-05,8.68e-05,0.0947,0.101,0.0066,0.933,0.954,0.0271,4.41e-11,4.42e-11,1.34e-10,2.95e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29890000,0.757,0.00648,-0.00263,-0.654,1.57,1.18,0.909,6.92,4.57,-370,-7.55e-06,-5.83e-05,-1.67e-07,-6.38e-05,0.000296,-0.00111,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.69e-05,8.97e-05,8.67e-05,0.0986,0.105,0.00681,0.991,1.01,0.0274,4.42e-11,4.43e-11,1.32e-10,2.95e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29990000,0.757,0.00676,-0.00271,-0.654,1.53,1.17,0.888,7.08,4.69,-370,-7.57e-06,-5.83e-05,-2.13e-07,-8.34e-05,0.000346,-0.0011,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.66e-05,8.99e-05,8.65e-05,0.103,0.11,0.00654,1.05,1.08,0.0269,4.43e-11,4.44e-11,1.31e-10,2.94e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30090000,0.757,0.00664,-0.00268,-0.654,1.49,1.15,0.877,7.23,4.8,-370,-7.57e-06,-5.83e-05,-3.11e-07,-8.7e-05,0.000355,-0.0011,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.69e-05,9.01e-05,8.64e-05,0.107,0.114,0.00674,1.11,1.14,0.0272,4.44e-11,4.45e-11,1.29e-10,2.94e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30190000,0.756,0.00652,-0.00267,-0.654,1.45,1.14,0.861,7.38,4.92,-370,-7.58e-06,-5.83e-05,-2.34e-07,-9.99e-05,0.000388,-0.00109,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.66e-05,9.03e-05,8.64e-05,0.111,0.119,0.00649,1.18,1.21,0.0269,4.45e-11,4.46e-11,1.28e-10,2.94e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30290000,0.756,0.00629,-0.00256,-0.654,1.41,1.13,0.85,7.52,5.03,-370,-7.58e-06,-5.83e-05,-2.79e-07,-0.000102,0.000392,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.68e-05,9.06e-05,8.63e-05,0.116,0.123,0.0067,1.25,1.29,0.0272,4.46e-11,4.47e-11,1.27e-10,2.94e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30390000,0.756,0.00612,-0.00253,-0.654,1.37,1.11,0.833,7.66,5.14,-370,-7.6e-06,-5.83e-05,-2.84e-07,-0.000113,0.000421,-0.00108,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.66e-05,9.08e-05,8.61e-05,0.12,0.128,0.00643,1.32,1.36,0.0267,4.47e-11,4.48e-11,1.25e-10,2.94e-06,2.76e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30490000,0.756,0.00582,-0.0024,-0.654,1.33,1.1,0.82,7.8,5.25,-370,-7.59e-06,-5.83e-05,-2.45e-07,-0.000115,0.000425,-0.00107,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.68e-05,9.1e-05,8.61e-05,0.125,0.133,0.00665,1.4,1.44,0.0272,4.48e-11,4.49e-11,1.24e-10,2.94e-06,2.76e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30590000,0.756,0.00539,-0.00224,-0.654,1.29,1.09,0.78,7.93,5.36,-370,-7.6e-06,-5.83e-05,-1.66e-07,-0.00012,0.00044,-0.00107,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.65e-05,9.12e-05,8.6e-05,0.13,0.139,0.0064,1.48,1.53,0.0267,4.49e-11,4.5e-11,1.23e-10,2.93e-06,2.75e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30690000,0.756,0.00502,-0.00208,-0.655,1.26,1.07,0.775,8.06,5.47,-369,-7.6e-06,-5.83e-05,-1.78e-07,-0.000123,0.000447,-0.00107,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.67e-05,9.15e-05,8.59e-05,0.135,0.144,0.00659,1.56,1.62,0.0271,4.5e-11,4.51e-11,1.21e-10,2.93e-06,2.74e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30790000,0.756,0.00469,-0.00197,-0.655,1.22,1.06,0.765,8.19,5.58,-369,-7.61e-06,-5.83e-05,-2.5e-07,-0.000131,0.000467,-0.00106,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.65e-05,9.17e-05,8.58e-05,0.14,0.149,0.00636,1.65,1.71,0.0267,4.51e-11,4.52e-11,1.2e-10,2.93e-06,2.73e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30890000,0.756,0.0042,-0.0018,-0.655,1.18,1.05,0.754,8.31,5.68,-369,-7.62e-06,-5.83e-05,-2.28e-07,-0.000134,0.000473,-0.00106,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,8.67e-05,9.2e-05,8.57e-05,0.146,0.155,0.00655,1.75,1.81,0.0271,4.52e-11,4.53e-11,1.19e-10,2.93e-06,2.73e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30990000,0.756,0.00363,-0.00167,-0.655,1.14,1.03,0.746,8.42,5.79,-369,-7.62e-06,-5.83e-05,-2.35e-07,-0.00014,0.000488,-0.00105,-0.206,-0.0318,0.432,0,0,0,0,0,0.0001,8.65e-05,9.22e-05,8.56e-05,0.151,0.161,0.0063,1.84,1.91,0.0265,4.52e-11,4.54e-11,1.18e-10,2.93e-06,2.71e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31090000,0.756,0.00307,-0.00148,-0.655,1.1,1.02,0.736,8.54,5.89,-369,-7.63e-06,-5.83e-05,-2.83e-07,-0.000143,0.000496,-0.00105,-0.206,-0.0318,0.432,0,0,0,0,0,0.0001,8.68e-05,9.24e-05,8.55e-05,0.157,0.166,0.00651,1.95,2.02,0.0271,4.53e-11,4.55e-11,1.17e-10,2.93e-06,2.71e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31190000,0.756,0.00289,-0.00139,-0.655,1.07,1.01,0.722,8.66,5.99,-369,-7.67e-06,-5.83e-05,-2.74e-07,-0.000163,0.000544,-0.00104,-0.206,-0.0318,0.432,0,0,0,0,0,0.0001,8.66e-05,9.27e-05,8.54e-05,0.162,0.172,0.00627,2.05,2.14,0.0266,4.54e-11,4.56e-11,1.16e-10,2.93e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31290000,0.756,0.0023,-0.00117,-0.655,1.03,0.991,0.725,8.76,6.09,-369,-7.67e-06,-5.83e-05,-2.52e-07,-0.000167,0.000553,-0.00103,-0.206,-0.0318,0.432,0,0,0,0,0,0.0001,8.68e-05,9.29e-05,8.53e-05,0.168,0.179,0.00646,2.16,2.26,0.0269,4.55e-11,4.57e-11,1.14e-10,2.93e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31390000,0.756,0.00181,-0.00102,-0.655,0.994,0.978,0.718,8.87,6.2,-369,-7.71e-06,-5.83e-05,-2.62e-07,-0.000183,0.00059,-0.00102,-0.206,-0.0318,0.432,0,0,0,0,0,0.0001,8.67e-05,9.32e-05,8.52e-05,0.174,0.185,0.00622,2.28,2.38,0.0264,4.56e-11,4.58e-11,1.13e-10,2.92e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31490000,0.756,0.00113,-0.000828,-0.655,0.954,0.963,0.715,8.97,6.29,-369,-7.71e-06,-5.83e-05,-3.48e-07,-0.000186,0.000598,-0.00102,-0.206,-0.0318,0.432,0,0,0,0,0,0.0001,8.69e-05,9.35e-05,8.51e-05,0.181,0.191,0.00642,2.4,2.51,0.0269,4.57e-11,4.59e-11,1.12e-10,2.92e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31590000,0.756,0.00082,-0.000717,-0.655,0.918,0.949,0.708,9.07,6.39,-369,-7.75e-06,-5.83e-05,-2.63e-07,-0.0002,0.000631,-0.00101,-0.206,-0.0318,0.432,0,0,0,0,0,9.99e-05,8.68e-05,9.37e-05,8.5e-05,0.187,0.198,0.00618,2.53,2.64,0.0264,4.58e-11,4.6e-11,1.11e-10,2.92e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31690000,0.756,8.99e-05,-0.000488,-0.655,0.88,0.934,0.714,9.16,6.49,-369,-7.75e-06,-5.83e-05,-2.45e-07,-0.000202,0.000637,-0.00101,-0.206,-0.0318,0.432,0,0,0,0,0,9.99e-05,8.7e-05,9.4e-05,8.49e-05,0.194,0.205,0.00637,2.66,2.79,0.0268,4.59e-11,4.61e-11,1.1e-10,2.92e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31790000,0.756,-0.000562,-0.000237,-0.655,0.843,0.92,0.71,9.26,6.58,-369,-7.79e-06,-5.83e-05,-1.85e-07,-0.000216,0.000669,-0.000996,-0.206,-0.0318,0.432,0,0,0,0,0,9.98e-05,8.69e-05,9.42e-05,8.48e-05,0.2,0.212,0.00615,2.8,2.93,0.0264,4.6e-11,4.62e-11,1.09e-10,2.92e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31890000,0.756,-0.00133,-1.32e-05,-0.655,0.802,0.903,0.707,9.35,6.68,-369,-7.79e-06,-5.83e-05,-1.82e-07,-0.000219,0.000676,-0.000993,-0.206,-0.0318,0.432,0,0,0,0,0,9.97e-05,8.71e-05,9.45e-05,8.47e-05,0.207,0.219,0.00634,2.95,3.09,0.0268,4.61e-11,4.63e-11,1.08e-10,2.92e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31990000,0.756,-0.00178,0.000154,-0.655,0.764,0.889,0.7,9.43,6.77,-369,-7.82e-06,-5.83e-05,-2.1e-07,-0.000231,0.000702,-0.000984,-0.206,-0.0318,0.432,0,0,0,0,0,9.96e-05,8.71e-05,9.48e-05,8.46e-05,0.214,0.226,0.00611,3.1,3.25,0.0263,4.62e-11,4.64e-11,1.07e-10,2.92e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32090000,0.756,-0.00258,0.000419,-0.655,0.724,0.873,0.708,9.51,6.86,-369,-7.83e-06,-5.83e-05,-2.34e-07,-0.000234,0.000711,-0.000981,-0.206,-0.0318,0.432,0,0,0,0,0,9.96e-05,8.73e-05,9.51e-05,8.45e-05,0.222,0.234,0.00631,3.26,3.42,0.0268,4.63e-11,4.65e-11,1.06e-10,2.92e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32190000,0.756,-0.00342,0.000668,-0.655,-1.71,-0.853,0.643,-1e+06,-1e+06,-369,-7.87e-06,-5.83e-05,-3.58e-07,-0.000246,0.000737,-0.000971,-0.206,-0.0318,0.432,0,0,0,0,0,9.95e-05,8.73e-05,9.53e-05,8.44e-05,0.0402,0.0402,0.0401,0.25,0.25,0.0252,4.63e-11,4.66e-11,1.05e-10,2.91e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32290000,0.756,-0.00424,0.00088,-0.655,-1.75,-0.87,0.64,-1e+06,-1e+06,-368,-7.87e-06,-5.83e-05,-3.46e-07,-0.000249,0.000744,-0.000969,-0.206,-0.0318,0.432,0,0,0,0,0,9.94e-05,8.75e-05,9.56e-05,8.43e-05,0.0405,0.0405,0.0402,0.251,0.251,0.025,4.64e-11,4.67e-11,1.04e-10,2.91e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32390000,0.756,-0.00478,0.000956,-0.655,-1.68,-0.861,0.641,-1e+06,-1e+06,-368,-8.13e-06,-5.83e-05,-2.9e-07,-0.00025,0.000746,-0.000968,-0.206,-0.0318,0.432,0,0,0,0,0,9.94e-05,8.77e-05,9.59e-05,8.42e-05,0.0204,0.0204,0.0278,0.252,0.252,0.0248,4.64e-11,4.67e-11,1.03e-10,2.91e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32490000,0.756,-0.00509,0.00109,-0.655,-1.72,-0.879,0.649,-1e+06,-1e+06,-368,-8.13e-06,-5.83e-05,-2.58e-07,-0.000252,0.000751,-0.000966,-0.206,-0.0318,0.432,0,0,0,0,0,9.93e-05,8.8e-05,9.62e-05,8.41e-05,0.0209,0.0209,0.0278,0.253,0.253,0.0253,4.65e-11,4.68e-11,1.02e-10,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32590000,0.756,-0.00512,0.000967,-0.654,-1.69,-0.875,0.647,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,-2.96e-07,-0.000253,0.00075,-0.000966,-0.206,-0.0318,0.432,0,0,0,0,0,9.92e-05,8.81e-05,9.62e-05,8.39e-05,0.0142,0.0142,0.0212,0.253,0.253,0.025,4.63e-11,4.66e-11,1.01e-10,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32690000,0.756,-0.00525,0.00103,-0.654,-1.73,-0.891,0.645,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,-2.91e-07,-0.000253,0.000751,-0.000966,-0.206,-0.0318,0.432,0,0,0,0,0,9.91e-05,8.83e-05,9.65e-05,8.38e-05,0.0148,0.0148,0.0212,0.255,0.255,0.0258,4.64e-11,4.67e-11,9.99e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32790000,0.756,-0.00527,0.00107,-0.654,-1.77,-0.907,0.646,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,-2.79e-07,-0.000254,0.000753,-0.000965,-0.206,-0.0318,0.432,0,0,0,0,0,9.91e-05,8.86e-05,9.69e-05,8.38e-05,0.0156,0.0156,0.0171,0.256,0.256,0.0255,4.65e-11,4.68e-11,9.91e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32890000,0.756,-0.00529,0.00101,-0.654,-1.81,-0.923,0.648,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,-4.12e-07,-0.000256,0.000756,-0.000964,-0.206,-0.0318,0.432,0,0,0,0,0,9.9e-05,8.89e-05,9.72e-05,8.36e-05,0.0166,0.0166,0.017,0.259,0.259,0.0263,4.66e-11,4.69e-11,9.81e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32990000,0.756,-0.00536,0.000979,-0.654,-1.85,-0.937,0.647,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,-2.46e-07,-0.000256,0.00076,-0.000963,-0.206,-0.0318,0.432,0,0,0,0,0,9.9e-05,8.92e-05,9.75e-05,8.35e-05,0.0177,0.0177,0.0143,0.261,0.261,0.0258,4.67e-11,4.7e-11,9.72e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33090000,0.756,-0.00543,0.00104,-0.654,-1.89,-0.952,0.643,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,-1.48e-07,-0.000257,0.000761,-0.000963,-0.206,-0.0318,0.432,0,0,0,0,0,9.89e-05,8.95e-05,9.78e-05,8.35e-05,0.019,0.019,0.0142,0.264,0.264,0.0268,4.68e-11,4.71e-11,9.64e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33190000,0.76,-0.00428,-0.00221,-0.65,-1.92,-0.967,0.584,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,-9.29e-08,-0.000257,0.000761,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,9.94e-05,8.98e-05,9.8e-05,8.29e-05,0.0206,0.0205,0.0122,0.267,0.267,0.0263,4.69e-11,4.72e-11,9.55e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33290000,0.804,-0.00242,-0.0141,-0.595,-1.93,-0.988,0.567,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,-2.06e-08,-0.000257,0.000762,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,0.000106,9.07e-05,9.78e-05,7.68e-05,0.0222,0.0222,0.0121,0.271,0.271,0.0271,4.7e-11,4.73e-11,9.47e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33390000,0.874,-0.00275,-0.0118,-0.486,-1.95,-1,0.764,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,5.01e-08,-0.000258,0.000764,-0.000963,-0.206,-0.0318,0.432,0,0,0,0,0,0.000116,9.23e-05,9.71e-05,6.63e-05,0.0237,0.0237,0.0107,0.275,0.275,0.0267,4.71e-11,4.74e-11,9.39e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33490000,0.939,-0.000535,-0.00469,-0.343,-1.97,-1.02,0.783,-1e+06,-1e+06,-368,-8.58e-06,-5.84e-05,6.62e-08,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,0.000127,9.45e-05,9.6e-05,5.59e-05,0.0258,0.0258,0.0106,0.28,0.28,0.0274,4.72e-11,4.75e-11,9.3e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33590000,0.983,-0.0031,0.00128,-0.182,-2.02,-1.03,0.744,-1e+06,-1e+06,-368,-8.59e-06,-5.84e-05,9.97e-08,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,0.000134,9.68e-05,9.47e-05,4.85e-05,0.0287,0.0288,0.00935,0.285,0.285,0.0268,4.73e-11,4.76e-11,9.22e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33690000,1,-0.00604,0.00455,-0.0135,-2.07,-1.05,0.752,-1e+06,-1e+06,-368,-8.59e-06,-5.84e-05,1.94e-07,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,0.000137,9.9e-05,9.34e-05,4.6e-05,0.0323,0.0325,0.00928,0.291,0.291,0.0276,4.74e-11,4.77e-11,9.15e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33790000,0.988,-0.00748,0.00623,0.156,-2.14,-1.08,0.732,-1e+06,-1e+06,-367,-8.6e-06,-5.84e-05,2.37e-07,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,0.000135,0.000101,9.23e-05,4.86e-05,0.0366,0.0371,0.00833,0.298,0.298,0.027,4.75e-11,4.78e-11,9.06e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33890000,0.947,-0.00784,0.00738,0.32,-2.21,-1.12,0.72,-1e+06,-1e+06,-367,-8.6e-06,-5.84e-05,2.7e-07,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,0.000128,0.000102,9.15e-05,5.62e-05,0.0417,0.0424,0.00825,0.306,0.306,0.0276,4.76e-11,4.79e-11,8.98e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33990000,0.887,-0.0108,0.00574,0.461,-2.27,-1.17,0.694,-1e+06,-1e+06,-367,-8.6e-06,-5.84e-05,3.19e-07,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,0.000118,0.000102,9.12e-05,6.67e-05,0.0476,0.0486,0.0075,0.315,0.315,0.027,4.77e-11,4.8e-11,8.9e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34090000,0.826,-0.0119,0.00448,0.563,-2.31,-1.23,0.699,-1e+06,-1e+06,-367,-8.6e-06,-5.84e-05,4.49e-07,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,0.000108,0.000102,9.13e-05,7.65e-05,0.0544,0.0558,0.00748,0.326,0.326,0.0277,4.78e-11,4.81e-11,8.83e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34190000,0.777,-0.0101,0.00474,0.629,-2.36,-1.29,0.703,-1e+06,-1e+06,-367,-8.6e-06,-5.84e-05,4.57e-07,-0.000258,0.000765,-0.000963,-0.206,-0.0318,0.432,0,0,0,0,0,0.000101,0.000102,9.14e-05,8.38e-05,0.0625,0.0643,0.00688,0.337,0.337,0.0271,4.79e-11,4.82e-11,8.76e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34290000,0.743,-0.00707,0.00582,0.669,-2.4,-1.35,0.704,-1e+06,-1e+06,-367,-8.6e-06,-5.84e-05,4.85e-07,-0.000258,0.000765,-0.000963,-0.206,-0.0318,0.432,0,0,0,0,0,9.57e-05,0.000102,9.14e-05,8.87e-05,0.0718,0.0741,0.00686,0.351,0.351,0.0275,4.8e-11,4.83e-11,8.68e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34390000,0.72,-0.00418,0.00699,0.694,-2.44,-1.4,0.705,-1e+06,-1e+06,-367,-8.6e-06,-5.84e-05,5.28e-07,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,9.25e-05,0.000101,9.14e-05,9.17e-05,0.0822,0.0852,0.00641,0.366,0.367,0.0271,4.81e-11,4.84e-11,8.61e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34490000,0.706,-0.00204,0.00806,0.709,-2.49,-1.46,0.706,-1e+06,-1e+06,-367,-8.61e-06,-5.84e-05,5.66e-07,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,9.05e-05,0.000101,9.13e-05,9.36e-05,0.0938,0.0977,0.00643,0.384,0.385,0.0274,4.82e-11,4.85e-11,8.54e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34590000,0.696,-0.00067,0.00881,0.718,-2.54,-1.51,0.707,-1e+06,-1e+06,-367,-8.61e-06,-5.84e-05,6.5e-07,-0.000259,0.000764,-0.000961,-0.206,-0.0318,0.432,0,0,0,0,0,8.92e-05,0.000101,9.1e-05,9.47e-05,0.107,0.111,0.00605,0.404,0.405,0.0269,4.83e-11,4.86e-11,8.46e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34690000,0.691,0.0001,0.00922,0.723,-2.59,-1.56,0.705,-1e+06,-1e+06,-367,-8.61e-06,-5.84e-05,6.05e-07,-0.000259,0.000764,-0.000961,-0.206,-0.0318,0.432,0,0,0,0,0,8.84e-05,0.0001,9.09e-05,9.54e-05,0.121,0.127,0.00612,0.427,0.429,0.0274,4.84e-11,4.87e-11,8.4e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34790000,0.687,0.000612,0.00938,0.727,-2.64,-1.62,0.704,-1e+06,-1e+06,-367,-8.61e-06,-5.84e-05,4.91e-07,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.78e-05,0.0001,9.06e-05,9.58e-05,0.136,0.143,0.00581,0.454,0.457,0.0268,4.85e-11,4.88e-11,8.33e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34890000,0.684,0.000704,0.0094,0.729,-2.7,-1.67,0.704,-1e+06,-1e+06,-367,-8.61e-06,-5.84e-05,5.41e-07,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.74e-05,0.0001,9.04e-05,9.6e-05,0.152,0.161,0.00589,0.485,0.488,0.0271,4.86e-11,4.89e-11,8.26e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34990000,0.681,-0.00242,0.0169,0.732,-3.69,-2.49,-0.113,-1e+06,-1e+06,-367,-8.61e-06,-5.84e-05,4.14e-07,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.7e-05,9.98e-05,9.01e-05,9.64e-05,0.178,0.19,0.00677,0.52,0.525,0.0267,4.87e-11,4.9e-11,8.2e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35090000,0.681,-0.00248,0.0169,0.732,-3.82,-2.54,-0.168,-1e+06,-1e+06,-367,-8.61e-06,-5.84e-05,3.98e-07,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.69e-05,9.96e-05,8.99e-05,9.63e-05,0.193,0.207,0.00693,0.561,0.567,0.0271,4.88e-11,4.91e-11,8.13e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35190000,0.681,-0.00249,0.0175,0.732,-3.87,-2.61,-0.155,-1e+06,-1e+06,-367,-8.44e-06,-5.83e-05,3.29e-07,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.68e-05,9.94e-05,8.82e-05,9.62e-05,0.206,0.221,0.00649,0.605,0.614,0.0265,4.87e-11,4.92e-11,8.06e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35290000,0.681,-0.00259,0.0175,0.732,-3.9,-2.66,-0.151,-1e+06,-1e+06,-367,-8.43e-06,-5.83e-05,2.41e-07,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.67e-05,9.92e-05,8.8e-05,9.61e-05,0.221,0.237,0.00655,0.657,0.668,0.0268,4.88e-11,4.93e-11,8e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35390000,0.681,-0.00256,0.0181,0.732,-3.95,-2.73,-0.138,-1e+06,-1e+06,-367,-8.29e-06,-5.83e-05,1e-07,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.67e-05,9.9e-05,8.64e-05,9.61e-05,0.235,0.253,0.00618,0.712,0.726,0.0265,4.88e-11,4.93e-11,7.94e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35490000,0.681,-0.0026,0.0181,0.732,-3.98,-2.78,-0.135,-1e+06,-1e+06,-367,-8.28e-06,-5.83e-05,-4.4e-08,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.66e-05,9.88e-05,8.62e-05,9.6e-05,0.252,0.271,0.00624,0.775,0.793,0.0267,4.89e-11,4.94e-11,7.88e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35590000,0.681,-0.00261,0.0186,0.732,-4.03,-2.85,-0.125,-1e+06,-1e+06,-367,-8.16e-06,-5.82e-05,-3.8e-08,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.65e-05,9.87e-05,8.47e-05,9.59e-05,0.267,0.287,0.0059,0.842,0.865,0.0262,4.9e-11,4.95e-11,7.81e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35690000,0.681,-0.00261,0.0185,0.732,-4.06,-2.9,-0.123,-1e+06,-1e+06,-367,-8.16e-06,-5.82e-05,-1.75e-07,-0.000259,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.65e-05,9.85e-05,8.45e-05,9.59e-05,0.284,0.306,0.00599,0.92,0.947,0.0266,4.9e-11,4.96e-11,7.76e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35790000,0.681,-0.00264,0.0189,0.732,-4.11,-2.96,-0.114,-1e+06,-1e+06,-367,-8.05e-06,-5.81e-05,-2.58e-07,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.64e-05,9.83e-05,8.31e-05,9.58e-05,0.301,0.324,0.00569,1,1.03,0.0261,4.91e-11,4.97e-11,7.7e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35890000,0.681,-0.00272,0.0189,0.732,-4.14,-3.02,-0.112,-1e+06,-1e+06,-367,-8.06e-06,-5.81e-05,-3.26e-07,-0.000258,0.000764,-0.000962,-0.206,-0.0318,0.432,0,0,0,0,0,8.63e-05,9.81e-05,8.29e-05,9.57e-05,0.321,0.346,0.00578,1.09,1.13,0.0264,4.92e-11,4.98e-11,7.64e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35990000,0.681,-0.00274,0.0191,0.732,-4.18,-3.08,-0.105,-1e+06,-1e+06,-367,-7.98e-06,-5.81e-05,-3.26e-07,-0.000256,0.000762,-0.000963,-0.206,-0.0318,0.432,0,0,0,0,0,8.63e-05,9.8e-05,8.15e-05,9.57e-05,0.339,0.366,0.00555,1.19,1.24,0.0261,4.92e-11,4.98e-11,7.58e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36090000,0.681,-0.00276,0.0191,0.732,-4.21,-3.13,-0.103,-1e+06,-1e+06,-367,-7.98e-06,-5.81e-05,-4.36e-07,-0.000256,0.000762,-0.000963,-0.206,-0.0318,0.432,0,0,0,0,0,8.62e-05,9.78e-05,8.13e-05,9.56e-05,0.361,0.389,0.00566,1.3,1.35,0.0263,4.93e-11,4.99e-11,7.52e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36190000,0.68,-0.0028,0.0194,0.733,-4.26,-3.2,-0.0949,-1e+06,-1e+06,-367,-7.92e-06,-5.8e-05,-6.76e-07,-0.000253,0.00076,-0.000965,-0.206,-0.0318,0.432,0,0,0,0,0,8.61e-05,9.76e-05,7.99e-05,9.55e-05,0.382,0.412,0.00545,1.42,1.48,0.0258,4.93e-11,5e-11,7.47e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36290000,0.68,-0.0028,0.0194,0.733,-4.29,-3.25,-0.0929,-1e+06,-1e+06,-367,-7.92e-06,-5.8e-05,-7.62e-07,-0.000253,0.00076,-0.000965,-0.206,-0.0318,0.432,0,0,0,0,0,8.61e-05,9.75e-05,7.97e-05,9.55e-05,0.406,0.438,0.0056,1.55,1.62,0.0262,4.94e-11,5.01e-11,7.42e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36390000,0.68,-0.00285,0.0197,0.733,-4.33,-3.31,-0.0868,-1e+06,-1e+06,-367,-7.85e-06,-5.8e-05,-8.23e-07,-0.000248,0.000756,-0.000968,-0.206,-0.0318,0.432,0,0,0,0,0,8.6e-05,9.73e-05,7.84e-05,9.54e-05,0.428,0.462,0.00542,1.68,1.76,0.0257,4.94e-11,5.02e-11,7.36e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36490000,0.68,-0.00292,0.0197,0.733,-4.37,-3.36,-0.0845,-1e+06,-1e+06,-367,-7.86e-06,-5.8e-05,-8.23e-07,-0.000248,0.000756,-0.000968,-0.206,-0.0318,0.432,0,0,0,0,0,8.59e-05,9.72e-05,7.82e-05,9.53e-05,0.454,0.49,0.00557,1.84,1.93,0.026,4.95e-11,5.03e-11,7.3e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36590000,0.68,-0.00293,0.0199,0.733,-4.41,-3.43,-0.0765,-1e+06,-1e+06,-367,-7.81e-06,-5.8e-05,-9.89e-07,-0.000243,0.000753,-0.000971,-0.206,-0.0318,0.432,0,0,0,0,0,8.58e-05,9.7e-05,7.7e-05,9.52e-05,0.479,0.516,0.00541,2,2.1,0.0255,4.95e-11,5.04e-11,7.25e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36690000,0.68,-0.00292,0.0198,0.733,-4.44,-3.48,-0.074,-1e+06,-1e+06,-367,-7.81e-06,-5.8e-05,-1.12e-06,-0.000243,0.000753,-0.000971,-0.206,-0.0318,0.432,0,0,0,0,0,8.58e-05,9.69e-05,7.67e-05,9.52e-05,0.507,0.546,0.00559,2.18,2.29,0.0259,4.96e-11,5.05e-11,7.2e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36790000,0.68,-0.00297,0.02,0.733,-4.48,-3.54,-0.0673,-1e+06,-1e+06,-367,-7.78e-06,-5.8e-05,-1.29e-06,-0.000239,0.00075,-0.000973,-0.206,-0.0318,0.432,0,0,0,0,0,8.57e-05,9.67e-05,7.56e-05,9.51e-05,0.533,0.574,0.00544,2.36,2.48,0.0255,4.97e-11,5.05e-11,7.15e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36890000,0.68,-0.003,0.02,0.733,-4.51,-3.6,-0.0642,-1e+06,-1e+06,-367,-7.79e-06,-5.8e-05,-1.45e-06,-0.00024,0.00075,-0.000973,-0.206,-0.0318,0.432,0,0,0,0,0,8.56e-05,9.66e-05,7.53e-05,9.51e-05,0.563,0.606,0.00562,2.57,2.7,0.0257,4.98e-11,5.06e-11,7.1e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36990000,0.68,-0.00296,0.0201,0.733,-4.55,-3.66,-0.0588,-1e+06,-1e+06,-367,-7.76e-06,-5.79e-05,-1.57e-06,-0.000236,0.000748,-0.000975,-0.206,-0.0318,0.432,0,0,0,0,0,8.56e-05,9.64e-05,7.42e-05,9.5e-05,0.592,0.636,0.0055,2.78,2.93,0.0254,4.98e-11,5.07e-11,7.05e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37090000,0.68,-0.00295,0.0201,0.733,-4.58,-3.71,-0.0542,-1e+06,-1e+06,-367,-7.76e-06,-5.79e-05,-1.66e-06,-0.000236,0.000748,-0.000975,-0.206,-0.0318,0.432,0,0,0,0,0,8.55e-05,9.63e-05,7.4e-05,9.5e-05,0.624,0.67,0.00569,3.02,3.18,0.0256,4.99e-11,5.08e-11,7e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37190000,0.68,-0.00299,0.0202,0.733,-4.62,-3.77,-0.0459,-1e+06,-1e+06,-367,-7.73e-06,-5.79e-05,-1.73e-06,-0.00023,0.000743,-0.000978,-0.206,-0.0318,0.432,0,0,0,0,0,8.54e-05,9.61e-05,7.29e-05,9.49e-05,0.654,0.701,0.00555,3.27,3.44,0.0252,4.99e-11,5.09e-11,6.95e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37290000,0.679,-0.00305,0.0202,0.733,-4.65,-3.83,-0.0418,-1e+06,-1e+06,-367,-7.73e-06,-5.79e-05,-1.83e-06,-0.00023,0.000743,-0.000978,-0.206,-0.0318,0.432,0,0,0,0,0,8.54e-05,9.6e-05,7.27e-05,9.49e-05,0.688,0.738,0.00577,3.54,3.73,0.0256,5e-11,5.1e-11,6.91e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37390000,0.679,-0.00303,0.0203,0.734,-4.69,-3.89,-0.0354,-1e+06,-1e+06,-367,-7.71e-06,-5.79e-05,-1.96e-06,-0.000226,0.00074,-0.000981,-0.206,-0.0318,0.432,0,0,0,0,0,8.53e-05,9.59e-05,7.17e-05,9.48e-05,0.72,0.771,0.00563,3.82,4.03,0.0252,5.01e-11,5.11e-11,6.86e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37490000,0.679,-0.00304,0.0203,0.734,-4.72,-3.94,-0.0306,-1e+06,-1e+06,-367,-7.71e-06,-5.79e-05,-2.13e-06,-0.000226,0.00074,-0.00098,-0.206,-0.0318,0.432,0,0,0,0,0,8.52e-05,9.57e-05,7.14e-05,9.48e-05,0.756,0.809,0.00585,4.13,4.36,0.0255,5.02e-11,5.12e-11,6.81e-11,2.91e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37590000,0.679,-0.00306,0.0204,0.734,-4.76,-4.01,-0.0225,-1e+06,-1e+06,-367,-7.68e-06,-5.79e-05,-2.24e-06,-0.000219,0.000735,-0.000984,-0.206,-0.0318,0.432,0,0,0,0,0,8.52e-05,9.56e-05,7.05e-05,9.47e-05,0.79,0.843,0.00572,4.45,4.69,0.0252,5.02e-11,5.12e-11,6.77e-11,2.91e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37690000,0.679,-0.00312,0.0204,0.734,-4.79,-4.06,-0.0176,-1e+06,-1e+06,-367,-7.68e-06,-5.79e-05,-2.37e-06,-0.000219,0.000735,-0.000984,-0.206,-0.0318,0.432,0,0,0,0,0,8.51e-05,9.55e-05,7.03e-05,9.47e-05,0.828,0.883,0.00594,4.81,5.07,0.0255,5.03e-11,5.13e-11,6.72e-11,2.91e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37790000,0.679,-0.0032,0.0205,0.734,-4.83,-4.12,-0.0102,-1e+06,-1e+06,-367,-7.66e-06,-5.79e-05,-2.47e-06,-0.000214,0.000732,-0.000987,-0.206,-0.0318,0.432,0,0,0,0,0,8.5e-05,9.53e-05,6.94e-05,9.46e-05,0.864,0.919,0.0058,5.17,5.45,0.0251,5.04e-11,5.14e-11,6.67e-11,2.9e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37890000,0.679,-0.00323,0.0204,0.734,-4.86,-4.18,-0.00477,-1e+06,-1e+06,-367,-7.67e-06,-5.79e-05,-2.57e-06,-0.000215,0.000732,-0.000987,-0.206,-0.0318,0.432,0,0,0,0,0,8.5e-05,9.52e-05,6.92e-05,9.45e-05,0.904,0.961,0.00602,5.58,5.87,0.0254,5.05e-11,5.15e-11,6.63e-11,2.9e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37990000,0.679,-0.0033,0.0204,0.734,-4.89,-4.23,0.00205,-1e+06,-1e+06,-367,-7.67e-06,-5.79e-05,-2.64e-06,-0.000214,0.000732,-0.000987,-0.206,-0.0318,0.432,0,0,0,0,0,8.49e-05,9.51e-05,6.84e-05,9.45e-05,0.942,0.999,0.00588,5.99,6.29,0.0251,5.05e-11,5.16e-11,6.59e-11,2.9e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38090000,0.679,-0.00333,0.0204,0.734,-4.92,-4.29,0.00858,-1e+06,-1e+06,-367,-7.67e-06,-5.79e-05,-2.78e-06,-0.000214,0.000732,-0.000987,-0.206,-0.0318,0.432,0,0,0,0,0,8.48e-05,9.5e-05,6.81e-05,9.44e-05,0.984,1.04,0.00611,6.44,6.77,0.0254,5.06e-11,5.17e-11,6.55e-11,2.9e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38190000,0.679,-0.00332,0.0204,0.734,-4.95,-4.34,0.0135,-1e+06,-1e+06,-367,-7.67e-06,-5.79e-05,-2.87e-06,-0.000215,0.000733,-0.000986,-0.206,-0.0318,0.432,0,0,0,0,0,8.48e-05,9.48e-05,6.74e-05,9.44e-05,1.02,1.08,0.00595,6.91,7.25,0.0251,5.07e-11,5.18e-11,6.5e-11,2.9e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38290000,0.679,-0.00335,0.0203,0.734,-4.98,-4.39,0.0191,-1e+06,-1e+06,-367,-7.67e-06,-5.79e-05,-2.94e-06,-0.000215,0.000733,-0.000986,-0.206,-0.0318,0.432,0,0,0,0,0,8.47e-05,9.47e-05,6.72e-05,9.44e-05,1.07,1.13,0.00619,7.42,7.78,0.0255,5.08e-11,5.19e-11,6.46e-11,2.9e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38390000,0.678,-0.00332,0.0202,0.734,-5.01,-4.44,0.0204,-1e+06,-1e+06,-367,-7.7e-06,-5.79e-05,-3e-06,-0.000223,0.000738,-0.000982,-0.206,-0.0318,0.432,0,0,0,0,0,8.47e-05,9.46e-05,6.65e-05,9.43e-05,1.11,1.17,0.00602,7.94,8.31,0.0251,5.09e-11,5.19e-11,6.42e-11,2.9e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38490000,0.678,-0.00335,0.0202,0.734,-5.04,-4.49,0.0259,-1e+06,-1e+06,-367,-7.7e-06,-5.79e-05,-3.09e-06,-0.000223,0.000738,-0.000982,-0.206,-0.0318,0.432,0,0,0,0,0,8.46e-05,9.45e-05,6.63e-05,9.42e-05,1.16,1.22,0.00625,8.51,8.9,0.0255,5.1e-11,5.2e-11,6.38e-11,2.9e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38590000,0.678,-0.00329,0.02,0.734,-5.06,-4.53,0.0276,-1e+06,-1e+06,-367,-7.72e-06,-5.79e-05,-3.13e-06,-0.000232,0.000744,-0.000977,-0.206,-0.0318,0.432,0,0,0,0,0,8.46e-05,9.44e-05,6.57e-05,9.42e-05,1.2,1.26,0.00608,9.1,9.49,0.0252,5.1e-11,5.21e-11,6.34e-11,2.89e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38690000,0.678,-0.00333,0.0201,0.735,-5.09,-4.58,0.0332,-1e+06,-1e+06,-367,-7.73e-06,-5.79e-05,-3.25e-06,-0.000233,0.000745,-0.000976,-0.206,-0.0318,0.432,0,0,0,0,0,8.45e-05,9.43e-05,6.55e-05,9.42e-05,1.25,1.31,0.00631,9.73,10.2,0.0256,5.11e-11,5.22e-11,6.3e-11,2.89e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38790000,0.678,-0.00334,0.02,0.735,-5.11,-4.63,0.0362,-1e+06,-1e+06,-367,-7.74e-06,-5.79e-05,-3.33e-06,-0.000238,0.000749,-0.000973,-0.206,-0.0318,0.432,0,0,0,0,0,8.44e-05,9.41e-05,6.49e-05,9.41e-05,1.29,1.35,0.00612,10.4,10.8,0.0252,5.12e-11,5.23e-11,6.26e-11,2.89e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38890000,0.678,-0.00344,0.0201,0.735,-5.13,-4.65,0.535,-1e+06,-1e+06,-367,-7.74e-06,-5.79e-05,-3.39e-06,-0.000238,0.000749,-0.000973,-0.206,-0.0318,0.432,0,0,0,0,0,8.44e-05,9.41e-05,6.48e-05,9.41e-05,1.33,1.38,0.00633,11.1,11.5,0.0257,5.13e-11,5.24e-11,6.23e-11,2.89e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
|
||||
|
@@ -1,351 +1,351 @@
|
||||
Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
|
||||
10000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
|
||||
90000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
|
||||
190000,0.979,-0.00865,-0.0138,0.205,-0.000572,-0.00011,-0.00742,-2.83e-05,-2.2e-05,-0.0351,-2.69e-14,7.98e-14,2.03e-15,2.99e-11,-2.9e-11,1.29e-09,0.203,0.0109,0.434,0,0,0,0,0,0.000143,0.00247,0.00247,0.00324,25,25,0.563,100,100,0.8,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
290000,0.979,-0.00873,-0.0141,0.205,0.000802,-0.000466,-0.0239,-6.92e-05,-2.29e-05,-0.0538,5.71e-12,-9.05e-13,-1.79e-13,1.07e-09,-1.03e-09,4.57e-08,0.203,0.0109,0.434,0,0,0,0,0,9.45e-05,0.00253,0.00253,0.00213,25,25,0.562,101,101,0.337,1e-06,1e-06,9.97e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
390000,0.979,-0.00874,-0.0144,0.205,0.00384,-0.000206,-0.0425,0.000107,7.77e-06,-0.0658,-2.92e-11,-1.07e-10,-1.39e-12,8.73e-09,-8.37e-09,3.69e-07,0.203,0.0109,0.434,0,0,0,0,0,7.23e-05,0.00263,0.00263,0.00162,24.8,24.8,0.557,0.29,0.29,0.209,1e-06,1e-06,9.88e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
490000,0.979,-0.00876,-0.0148,0.205,0.00668,-0.00219,-0.0639,0.000628,-0.00011,-0.0812,-2.87e-10,-5.71e-10,-3.06e-12,2.75e-08,-2.63e-08,1.15e-06,0.203,0.0109,0.434,0,0,0,0,0,6.04e-05,0.00279,0.00279,0.00135,24.9,24.9,0.544,0.739,0.739,0.159,1e-06,1e-06,9.73e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
590000,0.979,-0.00877,-0.015,0.205,0.00456,-0.00282,-0.0851,0.000297,-0.000135,-0.0938,-6.02e-09,-7.53e-09,5.54e-11,6.35e-08,-5.84e-08,2.02e-06,0.203,0.0109,0.434,0,0,0,0,0,5.37e-05,0.00299,0.00299,0.0012,7.8,7.8,0.527,0.267,0.267,0.141,1e-06,1e-06,9.49e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
690000,0.979,-0.0088,-0.0153,0.205,0.00888,-0.00425,-0.0976,0.000996,-0.000484,-0.103,-6.06e-09,-7.57e-09,5.59e-11,6.46e-08,-5.94e-08,2.07e-06,0.203,0.0109,0.434,0,0,0,0,0,5.01e-05,0.00324,0.00324,0.00111,7.87,7.87,0.497,0.556,0.556,0.13,1e-06,1e-06,9.16e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
790000,0.979,-0.0088,-0.0156,0.205,0.00942,-0.00187,-0.11,0.000559,-0.000205,-0.114,-3.56e-08,-3.46e-08,4.58e-10,1.03e-07,-1.01e-07,2.23e-06,0.203,0.0109,0.434,0,0,0,0,0,4.82e-05,0.00353,0.00353,0.00106,2.63,2.63,0.46,0.218,0.218,0.125,9.99e-07,9.99e-07,8.75e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
890000,0.979,-0.00883,-0.0159,0.205,0.0126,-0.00133,-0.128,0.00162,-0.000368,-0.13,-3.77e-08,-3.7e-08,4.82e-10,1.4e-07,-1.35e-07,3.74e-06,0.203,0.0109,0.434,0,0,0,0,0,4.75e-05,0.00388,0.00388,0.00104,2.72,2.72,0.423,0.363,0.363,0.128,9.99e-07,9.99e-07,8.27e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
990000,0.979,-0.00877,-0.0162,0.205,0.0132,0.000543,-0.143,0.00107,-0.000148,-0.144,-1.29e-07,-1.78e-07,1.19e-09,2.67e-07,-2.2e-07,4.15e-06,0.203,0.0109,0.434,0,0,0,0,0,4.74e-05,0.00424,0.00424,0.00103,1.25,1.25,0.379,0.178,0.178,0.127,9.97e-07,9.97e-07,7.73e-07,4e-06,4e-06,3.98e-06,0,0,0,0,0,0,0,0
|
||||
1090000,0.979,-0.00889,-0.0164,0.205,0.0231,-0.00141,-0.157,0.00285,-0.000128,-0.16,-1.3e-07,-1.8e-07,1.2e-09,2.81e-07,-2.33e-07,4.72e-06,0.203,0.0109,0.434,0,0,0,0,0,4.76e-05,0.00469,0.00469,0.00103,1.38,1.38,0.335,0.265,0.265,0.125,9.97e-07,9.97e-07,7.15e-07,4e-06,4e-06,3.97e-06,0,0,0,0,0,0,0,0
|
||||
1190000,0.979,-0.00881,-0.0166,0.205,0.0251,-0.00245,-0.171,0.00218,-0.000138,-0.176,-4.35e-07,-7.71e-07,3.59e-09,6.52e-07,-4.25e-07,4.71e-06,0.203,0.0109,0.434,0,0,0,0,0,4.79e-05,0.00503,0.00503,0.00104,0.846,0.847,0.299,0.151,0.151,0.128,9.88e-07,9.88e-07,6.56e-07,3.99e-06,3.99e-06,3.95e-06,0,0,0,0,0,0,0,0
|
||||
1290000,0.979,-0.00869,-0.0168,0.205,0.0347,-0.00229,-0.186,0.00524,-0.000423,-0.194,-4.35e-07,-7.71e-07,3.59e-09,6.52e-07,-4.25e-07,4.71e-06,0.203,0.0109,0.434,0,0,0,0,0,4.82e-05,0.00557,0.00557,0.00104,1.02,1.02,0.262,0.214,0.214,0.125,9.88e-07,9.88e-07,5.97e-07,3.99e-06,3.99e-06,3.94e-06,0,0,0,0,0,0,0,0
|
||||
1390000,0.979,-0.00868,-0.017,0.205,0.0454,-0.00312,-0.2,0.0093,-0.000696,-0.214,-4.35e-07,-7.71e-07,3.59e-09,6.52e-07,-4.25e-07,4.71e-06,0.203,0.0109,0.434,0,0,0,0,0,4.84e-05,0.00616,0.00615,0.00104,1.25,1.25,0.23,0.3,0.3,0.122,9.88e-07,9.88e-07,5.41e-07,3.99e-06,3.99e-06,3.92e-06,0,0,0,0,0,0,0,0
|
||||
1490000,0.979,-0.00855,-0.017,0.205,0.0434,-0.00331,-0.214,0.00801,-0.000537,-0.234,-1.42e-06,-2.63e-06,1.57e-08,1.6e-06,-9.28e-07,4.67e-06,0.203,0.0109,0.434,0,0,0,0,0,4.83e-05,0.00635,0.00635,0.00103,1.01,1.01,0.202,0.188,0.188,0.118,9.62e-07,9.62e-07,4.87e-07,3.99e-06,3.99e-06,3.89e-06,0,0,0,0,0,0,0,0
|
||||
1590000,0.979,-0.00863,-0.0173,0.205,0.0533,-0.00359,-0.228,0.0128,-0.000939,-0.256,-1.42e-06,-2.63e-06,1.57e-08,1.6e-06,-9.28e-07,4.67e-06,0.203,0.0109,0.434,0,0,0,0,0,4.83e-05,0.007,0.007,0.00102,1.3,1.3,0.182,0.268,0.268,0.118,9.62e-07,9.62e-07,4.38e-07,3.99e-06,3.99e-06,3.87e-06,0,0,0,0,0,0,0,0
|
||||
1690000,0.979,-0.00854,-0.017,0.205,0.0494,-0.00234,-0.244,0.0101,-0.000621,-0.28,-3.52e-06,-6.61e-06,4.8e-08,3.3e-06,-1.82e-06,4.59e-06,0.203,0.0109,0.434,0,0,0,0,0,4.78e-05,0.00675,0.00675,0.00101,1.1,1.1,0.163,0.179,0.179,0.114,9.06e-07,9.06e-07,3.92e-07,3.98e-06,3.98e-06,3.83e-06,0,0,0,0,0,0,0,0
|
||||
1790000,0.979,-0.00865,-0.0173,0.205,0.0604,-0.00312,-0.257,0.0157,-0.000917,-0.305,-3.52e-06,-6.61e-06,4.8e-08,3.3e-06,-1.82e-06,4.59e-06,0.203,0.0109,0.434,0,0,0,0,0,4.75e-05,0.00743,0.00743,0.000993,1.44,1.44,0.147,0.262,0.262,0.11,9.06e-07,9.06e-07,3.51e-07,3.98e-06,3.98e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
1890000,0.979,-0.00832,-0.0166,0.205,0.0501,7.74e-05,-0.269,0.0114,-0.000468,-0.331,-6.76e-06,-1.3e-05,1.05e-07,5.58e-06,-2.98e-06,4.46e-06,0.203,0.0109,0.434,0,0,0,0,0,4.63e-05,0.00657,0.00657,0.000975,1.18,1.18,0.137,0.178,0.178,0.109,8.15e-07,8.16e-07,3.15e-07,3.97e-06,3.97e-06,3.76e-06,0,0,0,0,0,0,0,0
|
||||
1990000,0.979,-0.00839,-0.0169,0.205,0.0585,0.000592,-0.282,0.0168,-0.000492,-0.359,-6.76e-06,-1.3e-05,1.05e-07,5.58e-06,-2.98e-06,4.46e-06,0.203,0.0109,0.434,0,0,0,0,0,4.58e-05,0.00722,0.00722,0.000955,1.54,1.54,0.126,0.266,0.266,0.105,8.15e-07,8.16e-07,2.82e-07,3.97e-06,3.97e-06,3.72e-06,0,0,0,0,0,0,0,0
|
||||
2090000,0.979,-0.00819,-0.0161,0.205,0.0446,0.00161,-0.296,0.0111,-0.000117,-0.388,-1.04e-05,-2.08e-05,1.73e-07,7.87e-06,-4.05e-06,4.31e-06,0.203,0.0109,0.434,0,0,0,0,0,4.42e-05,0.00588,0.00588,0.000934,1.18,1.18,0.118,0.177,0.177,0.102,7.03e-07,7.03e-07,2.52e-07,3.96e-06,3.96e-06,3.67e-06,0,0,0,0,0,0,0,0
|
||||
2190000,0.979,-0.00811,-0.0164,0.205,0.0523,0.00169,-0.293,0.0162,0.000104,-0.4,-1.03e-05,-2.05e-05,1.71e-07,7.17e-06,-3.42e-06,-2.46e-05,0.203,0.0109,0.434,0,0,0,0,0,4.36e-05,0.00645,0.00645,0.000912,1.51,1.51,0.113,0.267,0.267,0.101,7.03e-07,7.03e-07,2.27e-07,3.96e-06,3.96e-06,3.62e-06,0,0,0,0,0,0,0,0
|
||||
2290000,0.979,-0.00794,-0.0156,0.205,0.037,0.00274,-0.275,0.0102,0.00024,-0.394,-1.33e-05,-2.77e-05,2.28e-07,7.55e-06,-2.91e-06,-8.4e-05,0.203,0.0109,0.434,0,0,0,0,0,4.18e-05,0.00497,0.00497,0.00089,1.09,1.09,0.107,0.173,0.173,0.0977,5.9e-07,5.91e-07,2.04e-07,3.95e-06,3.95e-06,3.56e-06,0,0,0,0,0,0,0,0
|
||||
2390000,0.979,-0.00796,-0.0158,0.205,0.0446,0.00236,-0.263,0.0146,0.000478,-0.391,-1.32e-05,-2.73e-05,2.24e-07,6.19e-06,-1.67e-06,-0.000142,0.203,0.0109,0.434,0,0,0,0,0,4.11e-05,0.00545,0.00545,0.000867,1.38,1.39,0.103,0.259,0.259,0.0949,5.9e-07,5.91e-07,1.84e-07,3.95e-06,3.95e-06,3.49e-06,0,0,0,0,0,0,0,0
|
||||
2490000,0.979,-0.00769,-0.015,0.205,0.0284,0.00337,-0.259,0.00872,0.000394,-0.4,-1.57e-05,-3.37e-05,2.7e-07,6.44e-06,-1.33e-06,-0.000178,0.203,0.0109,0.434,0,0,0,0,0,3.94e-05,0.00411,0.00411,0.000845,0.963,0.963,0.101,0.166,0.166,0.0946,4.92e-07,4.93e-07,1.66e-07,3.95e-06,3.95e-06,3.43e-06,0,0,0,0,0,0,0,0
|
||||
2590000,0.979,-0.00779,-0.0152,0.205,0.0323,0.00208,-0.247,0.012,0.000676,-0.397,-1.56e-05,-3.34e-05,2.68e-07,5.1e-06,-9.65e-08,-0.000238,0.203,0.0109,0.434,0,0,0,0,0,3.86e-05,0.00452,0.00452,0.000823,1.21,1.21,0.0981,0.245,0.245,0.0923,4.92e-07,4.93e-07,1.5e-07,3.95e-06,3.95e-06,3.35e-06,0,0,0,0,0,0,0,0
|
||||
2690000,0.979,-0.00772,-0.0146,0.205,0.0208,0.00295,-0.235,0.00706,0.000468,-0.394,-1.73e-05,-3.82e-05,2.99e-07,4.12e-06,1.04e-06,-0.000299,0.203,0.0109,0.434,0,0,0,0,0,3.7e-05,0.00342,0.00342,0.000802,0.836,0.836,0.096,0.157,0.157,0.0903,4.12e-07,4.12e-07,1.36e-07,3.95e-06,3.95e-06,3.26e-06,0,0,0,0,0,0,0,0
|
||||
2790000,0.979,-0.00762,-0.0147,0.205,0.0256,0.00351,-0.226,0.00965,0.000814,-0.393,-1.72e-05,-3.79e-05,2.97e-07,2.86e-06,2.2e-06,-0.000356,0.203,0.0109,0.434,0,0,0,0,0,3.62e-05,0.00376,0.00376,0.000781,1.05,1.05,0.0943,0.228,0.228,0.0885,4.12e-07,4.12e-07,1.23e-07,3.95e-06,3.95e-06,3.17e-06,0,0,0,0,0,0,0,0
|
||||
2890000,0.979,-0.00759,-0.0143,0.205,0.0181,0.00184,-0.222,0.00574,0.000507,-0.399,-1.85e-05,-4.16e-05,3.18e-07,1.91e-06,3.08e-06,-0.000398,0.203,0.0109,0.434,0,0,0,0,0,3.48e-05,0.0029,0.0029,0.000761,0.727,0.727,0.0942,0.148,0.148,0.0889,3.47e-07,3.47e-07,1.12e-07,3.95e-06,3.95e-06,3.08e-06,0,0,0,0,0,0,0,0
|
||||
2990000,0.979,-0.00756,-0.0144,0.205,0.0208,0.00137,-0.207,0.00795,0.000696,-0.392,-1.84e-05,-4.14e-05,3.17e-07,3.11e-07,4.56e-06,-0.000471,0.203,0.0109,0.434,0,0,0,0,0,3.41e-05,0.00319,0.00319,0.000741,0.904,0.904,0.0929,0.211,0.211,0.0875,3.47e-07,3.47e-07,1.02e-07,3.95e-06,3.95e-06,2.98e-06,0,0,0,0,0,0,0,0
|
||||
3090000,0.979,-0.0075,-0.0141,0.205,0.017,-0.000481,-0.203,0.00489,0.000335,-0.395,-1.94e-05,-4.43e-05,3.34e-07,-9.68e-07,5.59e-06,-0.000516,0.203,0.0109,0.434,0,0,0,0,0,3.3e-05,0.00252,0.00252,0.000722,0.638,0.638,0.0919,0.139,0.139,0.0862,2.94e-07,2.94e-07,9.36e-08,3.95e-06,3.95e-06,2.87e-06,0,0,0,0,0,0,0,0
|
||||
3190000,0.979,-0.00749,-0.0143,0.205,0.0201,-0.00147,-0.195,0.00684,0.00019,-0.398,-1.94e-05,-4.42e-05,3.34e-07,-2.01e-06,6.55e-06,-0.000563,0.203,0.0109,0.434,0,0,0,0,0,3.23e-05,0.00277,0.00277,0.000704,0.791,0.791,0.092,0.196,0.196,0.087,2.94e-07,2.94e-07,8.58e-08,3.95e-06,3.95e-06,2.78e-06,0,0,0,0,0,0,0,0
|
||||
3290000,0.979,-0.00737,-0.0139,0.205,0.0145,-0.00116,-0.183,0.00435,1.95e-06,-0.394,-2.04e-05,-4.65e-05,3.52e-07,-3.87e-06,8.03e-06,-0.000628,0.203,0.0109,0.434,0,0,0,0,0,3.12e-05,0.00222,0.00222,0.000686,0.567,0.567,0.0909,0.131,0.131,0.086,2.49e-07,2.49e-07,7.87e-08,3.94e-06,3.94e-06,2.66e-06,0,0,0,0,0,0,0,0
|
||||
3390000,0.979,-0.00721,-0.014,0.205,0.0157,0.00022,-0.174,0.00588,-6.27e-05,-0.391,-2.04e-05,-4.64e-05,3.52e-07,-5.16e-06,9.2e-06,-0.000686,0.203,0.0109,0.434,0,0,0,0,0,3.05e-05,0.00244,0.00244,0.000669,0.702,0.702,0.0898,0.183,0.183,0.0851,2.49e-07,2.49e-07,7.24e-08,3.94e-06,3.94e-06,2.54e-06,0,0,0,0,0,0,0,0
|
||||
3490000,0.979,-0.00714,-0.014,0.205,0.0195,0.00302,-0.172,0.00774,9.55e-05,-0.398,-2.04e-05,-4.64e-05,3.51e-07,-5.81e-06,9.79e-06,-0.000716,0.203,0.0109,0.434,0,0,0,0,0,2.99e-05,0.00268,0.00268,0.000653,0.86,0.86,0.0898,0.254,0.254,0.0861,2.49e-07,2.49e-07,6.68e-08,3.94e-06,3.94e-06,2.44e-06,0,0,0,0,0,0,0,0
|
||||
3590000,0.979,-0.00699,-0.0136,0.205,0.0157,0.00279,-0.167,0.00528,0.00032,-0.399,-2.12e-05,-4.83e-05,3.66e-07,-7.38e-06,1.09e-05,-0.000762,0.203,0.0109,0.434,0,0,0,0,0,2.89e-05,0.00218,0.00218,0.000637,0.632,0.632,0.0884,0.171,0.171,0.0853,2.11e-07,2.11e-07,6.16e-08,3.94e-06,3.94e-06,2.31e-06,0,0,0,0,0,0,0,0
|
||||
3690000,0.979,-0.00698,-0.0137,0.205,0.0169,0.00374,-0.156,0.00703,0.000611,-0.396,-2.12e-05,-4.83e-05,3.66e-07,-8.6e-06,1.21e-05,-0.000818,0.203,0.0109,0.434,0,0,0,0,0,2.83e-05,0.00239,0.00239,0.000622,0.773,0.773,0.0868,0.236,0.236,0.0845,2.11e-07,2.11e-07,5.7e-08,3.94e-06,3.94e-06,2.19e-06,0,0,0,0,0,0,0,0
|
||||
3790000,0.979,-0.00687,-0.0135,0.205,0.0111,0.00704,-0.152,0.00459,0.000841,-0.398,-2.17e-05,-5e-05,3.75e-07,-1.01e-05,1.3e-05,-0.000855,0.203,0.0109,0.434,0,0,0,0,0,2.75e-05,0.00196,0.00196,0.000607,0.575,0.575,0.0864,0.161,0.161,0.0856,1.78e-07,1.78e-07,5.28e-08,3.94e-06,3.94e-06,2.09e-06,0,0,0,0,0,0,0,0
|
||||
3890000,0.979,-0.00681,-0.0136,0.205,0.0112,0.00817,-0.145,0.0058,0.00164,-0.399,-2.17e-05,-5e-05,3.75e-07,-1.09e-05,1.38e-05,-0.000894,0.203,0.0109,0.434,0,0,0,0,0,2.7e-05,0.00214,0.00214,0.000594,0.702,0.702,0.0846,0.221,0.221,0.0848,1.78e-07,1.78e-07,4.91e-08,3.94e-06,3.94e-06,1.97e-06,0,0,0,0,0,0,0,0
|
||||
3990000,0.979,-0.00682,-0.0134,0.205,0.00939,0.00749,-0.14,0.00376,0.00142,-0.397,-2.19e-05,-5.15e-05,3.75e-07,-1.26e-05,1.47e-05,-0.000939,0.203,0.0109,0.434,0,0,0,0,0,2.62e-05,0.00176,0.00176,0.00058,0.528,0.528,0.0826,0.153,0.153,0.0841,1.49e-07,1.49e-07,4.56e-08,3.93e-06,3.93e-06,1.85e-06,0,0,0,0,0,0,0,0
|
||||
4090000,0.979,-0.00675,-0.0133,0.205,0.0113,0.00776,-0.129,0.00492,0.00221,-0.393,-2.19e-05,-5.14e-05,3.75e-07,-1.37e-05,1.57e-05,-0.00099,0.203,0.0109,0.434,0,0,0,0,0,2.57e-05,0.00191,0.00191,0.000567,0.642,0.643,0.0806,0.208,0.208,0.0833,1.49e-07,1.49e-07,4.25e-08,3.93e-06,3.93e-06,1.74e-06,0,0,0,0,0,0,0,0
|
||||
4190000,0.979,-0.0069,-0.0131,0.205,0.00845,0.00589,-0.128,0.00325,0.00165,-0.4,-2.19e-05,-5.28e-05,3.71e-07,-1.47e-05,1.6e-05,-0.00101,0.203,0.0109,0.434,0,0,0,0,0,2.5e-05,0.00158,0.00158,0.000555,0.486,0.486,0.0795,0.145,0.145,0.0842,1.23e-07,1.23e-07,3.96e-08,3.92e-06,3.92e-06,1.64e-06,0,0,0,0,0,0,0,0
|
||||
4290000,0.979,-0.00694,-0.0132,0.205,0.011,0.00743,-0.121,0.00431,0.00232,-0.397,-2.19e-05,-5.28e-05,3.71e-07,-1.56e-05,1.69e-05,-0.00105,0.203,0.0109,0.434,0,0,0,0,0,2.45e-05,0.00171,0.00171,0.000543,0.59,0.59,0.0773,0.196,0.196,0.0834,1.23e-07,1.23e-07,3.7e-08,3.92e-06,3.92e-06,1.54e-06,0,0,0,0,0,0,0,0
|
||||
4390000,0.979,-0.00689,-0.013,0.205,0.0102,0.00495,-0.112,0.00307,0.00162,-0.392,-2.18e-05,-5.39e-05,3.65e-07,-1.73e-05,1.77e-05,-0.00109,0.203,0.0109,0.434,0,0,0,0,0,2.39e-05,0.00141,0.00141,0.000532,0.449,0.449,0.0749,0.138,0.138,0.0825,1.02e-07,1.02e-07,3.46e-08,3.92e-06,3.92e-06,1.43e-06,0,0,0,0,0,0,0,0
|
||||
4490000,0.979,-0.00693,-0.013,0.205,0.0106,0.00759,-0.111,0.00415,0.0023,-0.397,-2.18e-05,-5.39e-05,3.65e-07,-1.76e-05,1.8e-05,-0.00111,0.203,0.0109,0.434,0,0,0,0,0,2.35e-05,0.00152,0.00152,0.000521,0.542,0.542,0.0736,0.186,0.186,0.0833,1.02e-07,1.02e-07,3.24e-08,3.92e-06,3.92e-06,1.35e-06,0,0,0,0,0,0,0,0
|
||||
4590000,0.979,-0.00695,-0.0129,0.205,0.00919,0.00514,-0.102,0.00293,0.00167,-0.392,-2.16e-05,-5.49e-05,3.6e-07,-1.92e-05,1.88e-05,-0.00115,0.203,0.0109,0.434,0,0,0,0,0,2.29e-05,0.00125,0.00125,0.00051,0.414,0.414,0.0711,0.132,0.132,0.0824,8.3e-08,8.31e-08,3.04e-08,3.91e-06,3.91e-06,1.26e-06,0,0,0,0,0,0,0,0
|
||||
4690000,0.979,-0.0069,-0.0129,0.205,0.00855,0.00579,-0.0979,0.0039,0.00225,-0.394,-2.16e-05,-5.49e-05,3.6e-07,-1.96e-05,1.91e-05,-0.00117,0.203,0.0109,0.434,0,0,0,0,0,2.25e-05,0.00135,0.00135,0.0005,0.498,0.498,0.0687,0.177,0.177,0.0814,8.3e-08,8.31e-08,2.85e-08,3.91e-06,3.91e-06,1.17e-06,0,0,0,0,0,0,0,0
|
||||
4790000,0.979,-0.00681,-0.0128,0.205,0.00171,0.00455,-0.0963,0.00239,0.00159,-0.398,-2.15e-05,-5.58e-05,3.55e-07,-2.06e-05,1.93e-05,-0.00119,0.203,0.0109,0.434,0,0,0,0,0,2.2e-05,0.0011,0.0011,0.00049,0.38,0.38,0.0672,0.126,0.126,0.082,6.74e-08,6.75e-08,2.68e-08,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
4890000,0.979,-0.00674,-0.0128,0.205,0.00197,0.00281,-0.087,0.00259,0.00195,-0.392,-2.15e-05,-5.58e-05,3.55e-07,-2.13e-05,2e-05,-0.00122,0.203,0.0109,0.434,0,0,0,0,0,2.16e-05,0.00119,0.00119,0.000481,0.456,0.456,0.0647,0.168,0.168,0.0809,6.74e-08,6.75e-08,2.53e-08,3.9e-06,3.9e-06,1.02e-06,0,0,0,0,0,0,0,0
|
||||
4990000,0.979,-0.00673,-0.0127,0.205,0.00228,0.00292,-0.0813,0.00157,0.00129,-0.392,-2.13e-05,-5.64e-05,3.49e-07,-2.22e-05,2.03e-05,-0.00124,0.203,0.0109,0.434,0,0,0,0,0,2.11e-05,0.000973,0.000973,0.000472,0.349,0.349,0.0622,0.121,0.121,0.0798,5.45e-08,5.46e-08,2.38e-08,3.9e-06,3.9e-06,9.49e-07,0,0,0,0,0,0,0,0
|
||||
5090000,0.979,-0.0066,-0.0127,0.205,0.00206,0.00403,-0.0839,0.00181,0.0016,-0.4,-2.13e-05,-5.64e-05,3.49e-07,-2.22e-05,2.03e-05,-0.00124,0.203,0.0109,0.434,0,0,0,0,0,2.07e-05,0.00104,0.00104,0.000463,0.416,0.416,0.0607,0.159,0.159,0.0803,5.45e-08,5.46e-08,2.24e-08,3.9e-06,3.9e-06,8.89e-07,0,0,0,0,0,0,0,0
|
||||
5190000,0.979,-0.00647,-0.0126,0.205,-0.00151,0.00553,-0.0801,0.00104,0.00119,-0.399,-2.12e-05,-5.68e-05,3.44e-07,-2.3e-05,2.06e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,2.03e-05,0.000856,0.000856,0.000454,0.32,0.32,0.0583,0.115,0.115,0.0791,4.39e-08,4.4e-08,2.12e-08,3.89e-06,3.89e-06,8.26e-07,0,0,0,0,0,0,0,0
|
||||
5290000,0.979,-0.00636,-0.0126,0.206,-0.000922,0.00698,-0.0777,0.000963,0.00181,-0.407,-2.12e-05,-5.68e-05,3.44e-07,-2.3e-05,2.06e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,2e-05,0.000914,0.000914,0.000446,0.379,0.379,0.056,0.152,0.152,0.078,4.39e-08,4.4e-08,2e-08,3.89e-06,3.89e-06,7.67e-07,0,0,0,0,0,0,0,0
|
||||
5390000,0.979,-0.00633,-0.0126,0.206,-0.00393,0.00825,-0.0811,0.000425,0.00145,-0.415,-2.09e-05,-5.7e-05,3.37e-07,-2.32e-05,2.03e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.96e-05,0.000753,0.000753,0.000438,0.292,0.292,0.0538,0.111,0.111,0.0768,3.54e-08,3.54e-08,1.9e-08,3.88e-06,3.88e-06,7.13e-07,0,0,0,0,0,0,0,0
|
||||
5490000,0.979,-0.00631,-0.0126,0.206,-0.00347,0.0114,-0.0811,2.31e-05,0.00242,-0.423,-2.09e-05,-5.7e-05,3.37e-07,-2.32e-05,2.03e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.92e-05,0.000801,0.000801,0.000431,0.345,0.345,0.0523,0.144,0.144,0.0771,3.54e-08,3.54e-08,1.8e-08,3.88e-06,3.88e-06,6.68e-07,0,0,0,0,0,0,0,0
|
||||
5590000,0.979,-0.00631,-0.0126,0.205,-0.00445,0.015,-0.0822,-0.000327,0.00377,-0.431,-2.09e-05,-5.7e-05,3.37e-07,-2.32e-05,2.03e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.89e-05,0.000851,0.000851,0.000423,0.405,0.405,0.0502,0.187,0.187,0.0759,3.54e-08,3.54e-08,1.7e-08,3.88e-06,3.88e-06,6.21e-07,0,0,0,0,0,0,0,0
|
||||
5690000,0.979,-0.00636,-0.0126,0.205,-0.00414,0.0155,-0.086,-0.000649,0.00344,-0.439,-2.04e-05,-5.72e-05,3.25e-07,-2.33e-05,1.99e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.85e-05,0.000703,0.000703,0.000416,0.314,0.314,0.0482,0.137,0.137,0.0747,2.85e-08,2.85e-08,1.62e-08,3.88e-06,3.88e-06,5.77e-07,0,0,0,0,0,0,0,0
|
||||
5790000,0.979,-0.00621,-0.0125,0.205,-0.00438,0.0179,-0.0875,-0.00107,0.00511,-0.448,-2.04e-05,-5.72e-05,3.25e-07,-2.33e-05,1.99e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.82e-05,0.000745,0.000745,0.000409,0.367,0.367,0.0468,0.177,0.177,0.0749,2.85e-08,2.85e-08,1.53e-08,3.88e-06,3.88e-06,5.42e-07,0,0,0,0,0,0,0,0
|
||||
5890000,0.979,-0.00624,-0.0126,0.205,-0.0019,0.0166,-0.0869,-0.000854,0.00444,-0.457,-1.98e-05,-5.73e-05,3.09e-07,-2.34e-05,1.93e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.79e-05,0.000618,0.000619,0.000402,0.285,0.285,0.0449,0.131,0.131,0.0737,2.29e-08,2.29e-08,1.46e-08,3.87e-06,3.87e-06,5.04e-07,0,0,0,0,0,0,0,0
|
||||
5990000,0.979,-0.00621,-0.0127,0.205,-0.00154,0.0181,-0.0868,-0.000999,0.00615,-0.465,-1.98e-05,-5.73e-05,3.09e-07,-2.34e-05,1.93e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.76e-05,0.000653,0.000653,0.000396,0.332,0.332,0.0431,0.167,0.167,0.0725,2.29e-08,2.29e-08,1.39e-08,3.87e-06,3.87e-06,4.7e-07,0,0,0,0,0,0,0,0
|
||||
6090000,0.979,-0.00631,-0.0126,0.205,-0.00194,0.0157,-0.0885,-0.000744,0.00497,-0.474,-1.91e-05,-5.75e-05,2.93e-07,-2.36e-05,1.87e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.73e-05,0.000546,0.000546,0.00039,0.259,0.259,0.0419,0.124,0.124,0.0726,1.85e-08,1.85e-08,1.32e-08,3.87e-06,3.87e-06,4.41e-07,0,0,0,0,0,0,0,0
|
||||
6190000,0.979,-0.00633,-0.0126,0.205,-0.00319,0.0177,-0.0899,-0.000947,0.00666,-0.483,-1.91e-05,-5.75e-05,2.93e-07,-2.36e-05,1.87e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.7e-05,0.000575,0.000575,0.000383,0.3,0.3,0.0402,0.159,0.159,0.0714,1.85e-08,1.85e-08,1.26e-08,3.87e-06,3.87e-06,4.12e-07,0,0,0,0,0,0,0,0
|
||||
6290000,0.979,-0.00641,-0.0126,0.205,-0.00475,0.0159,-0.0915,-0.000858,0.00526,-0.492,-1.85e-05,-5.76e-05,2.76e-07,-2.38e-05,1.8e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.67e-05,0.000484,0.000484,0.000378,0.235,0.235,0.0385,0.119,0.119,0.0703,1.49e-08,1.5e-08,1.2e-08,3.87e-06,3.87e-06,3.84e-07,0,0,0,0,0,0,0,0
|
||||
6390000,0.979,-0.00635,-0.0125,0.205,-0.00313,0.0175,-0.0933,-0.00127,0.00693,-0.501,-1.85e-05,-5.76e-05,2.76e-07,-2.38e-05,1.8e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.65e-05,0.000508,0.000508,0.000372,0.272,0.272,0.0375,0.15,0.15,0.0704,1.49e-08,1.5e-08,1.15e-08,3.87e-06,3.87e-06,3.62e-07,0,0,0,0,0,0,0,0
|
||||
6490000,0.979,-0.00642,-0.0125,0.205,-0.00506,0.0124,-0.0944,-0.00109,0.00526,-0.511,-1.78e-05,-5.78e-05,2.61e-07,-2.39e-05,1.74e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.62e-05,0.000431,0.000431,0.000366,0.214,0.214,0.036,0.113,0.113,0.0692,1.21e-08,1.21e-08,1.09e-08,3.86e-06,3.86e-06,3.38e-07,0,0,0,0,0,0,0,0
|
||||
6590000,0.979,-0.00637,-0.0125,0.205,-0.0063,0.0146,-0.0978,-0.00162,0.00655,-0.52,-1.78e-05,-5.78e-05,2.61e-07,-2.39e-05,1.74e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.6e-05,0.000451,0.000451,0.000361,0.246,0.246,0.0345,0.143,0.143,0.0681,1.21e-08,1.21e-08,1.05e-08,3.86e-06,3.86e-06,3.16e-07,0,0,0,0,0,0,0,0
|
||||
6690000,0.979,-0.00639,-0.0124,0.205,-0.00853,0.0133,-0.102,-0.00159,0.00502,-0.53,-1.73e-05,-5.79e-05,2.47e-07,-2.4e-05,1.68e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.57e-05,0.000386,0.000386,0.000356,0.195,0.195,0.0332,0.108,0.108,0.067,9.87e-09,9.88e-09,1e-08,3.86e-06,3.86e-06,2.96e-07,0,0,0,0,0,0,0,0
|
||||
6790000,0.979,-0.00641,-0.0124,0.205,-0.00723,0.0146,-0.103,-0.00243,0.00639,-0.541,-1.73e-05,-5.79e-05,2.47e-07,-2.4e-05,1.68e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.55e-05,0.000403,0.000403,0.00035,0.223,0.223,0.0323,0.135,0.135,0.067,9.87e-09,9.88e-09,9.57e-09,3.86e-06,3.86e-06,2.8e-07,0,0,0,0,0,0,0,0
|
||||
6890000,0.979,-0.00633,-0.0123,0.205,-0.00685,0.011,-0.103,-0.002,0.00482,-0.551,-1.68e-05,-5.79e-05,2.34e-07,-2.4e-05,1.62e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.52e-05,0.000347,0.000347,0.000346,0.177,0.177,0.0311,0.103,0.103,0.0659,8.07e-09,8.07e-09,9.16e-09,3.86e-06,3.86e-06,2.62e-07,0,0,0,0,0,0,0,0
|
||||
6990000,0.979,-0.00628,-0.0123,0.205,-0.00731,0.0117,-0.104,-0.00275,0.00595,-0.561,-1.68e-05,-5.79e-05,2.34e-07,-2.4e-05,1.62e-05,-0.00126,0.203,0.0109,0.434,0,0,0,0,0,1.5e-05,0.000362,0.000362,0.000341,0.203,0.203,0.0299,0.129,0.129,0.0648,8.07e-09,8.07e-09,8.78e-09,3.86e-06,3.86e-06,2.46e-07,0,0,0,0,0,0,0,0
|
||||
7090000,0.982,-0.00648,-0.0121,0.188,-0.00737,0.0134,-0.106,-0.00225,0.00469,-0.572,-1.63e-05,-5.79e-05,2.22e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,9.14e-05,0.000314,0.000314,0.00244,0.16,0.16,0.0291,0.0991,0.0991,0.0649,6.62e-09,6.63e-09,8.49e-09,3.86e-06,3.86e-06,2.33e-07,0,0,0,0,0,0,0,0
|
||||
7190000,0.982,-0.00644,-0.0122,0.188,-0.00815,0.0147,-0.106,-0.00306,0.00616,-0.582,-1.63e-05,-5.79e-05,2.15e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,4.82e-05,0.000314,0.000314,0.00128,0.161,0.161,0.028,0.122,0.122,0.0638,6.62e-09,6.63e-09,8.49e-09,3.86e-06,3.86e-06,2.19e-07,0,0,0,0,0,0,0,0
|
||||
7290000,0.982,-0.00642,-0.0121,0.188,-0.00769,0.0181,-0.108,-0.00391,0.00776,-0.593,-1.63e-05,-5.79e-05,2.39e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,3.28e-05,0.000315,0.000315,0.000872,0.167,0.167,0.027,0.148,0.148,0.0628,6.62e-09,6.62e-09,8.49e-09,3.86e-06,3.86e-06,2.06e-07,0,0,0,0,0,0,0,0
|
||||
7390000,0.982,-0.0063,-0.0121,0.188,-0.00979,0.0203,-0.109,-0.00478,0.00973,-0.604,-1.63e-05,-5.79e-05,2.53e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.56e-05,0.000316,0.000315,0.000681,0.176,0.176,0.0263,0.177,0.177,0.0628,6.62e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.96e-07,0,0,0,0,0,0,0,0
|
||||
7490000,0.982,-0.00631,-0.0122,0.187,-0.00782,0.0224,-0.109,-0.00563,0.0119,-0.615,-1.63e-05,-5.79e-05,3.44e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.05e-05,0.000317,0.000317,0.000545,0.188,0.188,0.0253,0.21,0.21,0.0618,6.61e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.85e-07,0,0,0,0,0,0,0,0
|
||||
7590000,0.982,-0.00639,-0.0121,0.187,-0.00719,0.0246,-0.11,-0.00638,0.0142,-0.626,-1.63e-05,-5.79e-05,3.53e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,1.72e-05,0.000318,0.000318,0.000455,0.205,0.205,0.0244,0.247,0.247,0.0609,6.61e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.74e-07,0,0,0,0,0,0,0,0
|
||||
7690000,0.982,-0.00641,-0.0122,0.187,-0.0079,0.0277,-0.114,-0.00714,0.0168,-0.637,-1.63e-05,-5.79e-05,3.31e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,1.5e-05,0.00032,0.00032,0.000398,0.225,0.225,0.0239,0.289,0.289,0.0608,6.61e-09,6.62e-09,8.47e-09,3.86e-06,3.86e-06,1.66e-07,0,0,0,0,0,0,0,0
|
||||
7790000,0.982,-0.00629,-0.0122,0.187,-0.00667,0.0293,-0.116,-0.00784,0.0196,-0.648,-1.63e-05,-5.79e-05,2.72e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,1.32e-05,0.000322,0.000322,0.000348,0.249,0.249,0.023,0.335,0.335,0.0599,6.6e-09,6.61e-09,8.46e-09,3.86e-06,3.86e-06,1.57e-07,0,0,0,0,0,0,0,0
|
||||
7890000,0.982,-0.00631,-0.0123,0.187,-0.0084,0.033,-0.117,-0.00867,0.0227,-0.66,-1.63e-05,-5.79e-05,2.4e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,1.18e-05,0.000325,0.000325,0.00031,0.277,0.277,0.0222,0.388,0.389,0.059,6.6e-09,6.61e-09,8.45e-09,3.86e-06,3.86e-06,1.49e-07,0,0,0,0,0,0,0,0
|
||||
7990000,0.982,-0.00625,-0.0122,0.187,-0.00851,0.0351,-0.116,-0.00949,0.0259,-0.672,-1.63e-05,-5.79e-05,2.62e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,1.06e-05,0.000328,0.000328,0.00028,0.308,0.308,0.0215,0.447,0.447,0.0581,6.59e-09,6.59e-09,8.44e-09,3.86e-06,3.86e-06,1.41e-07,0,0,0,0,0,0,0,0
|
||||
8090000,0.982,-0.00611,-0.0122,0.187,-0.00744,0.0385,-0.118,-0.0102,0.0295,-0.683,-1.63e-05,-5.79e-05,5.32e-09,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,9.84e-06,0.000331,0.000331,0.000259,0.344,0.344,0.021,0.515,0.515,0.0581,6.59e-09,6.59e-09,8.42e-09,3.86e-06,3.86e-06,1.34e-07,0,0,0,0,0,0,0,0
|
||||
8190000,0.982,-0.00618,-0.0121,0.188,-0.0072,0.0432,-0.118,-0.0109,0.0335,-0.695,-1.62e-05,-5.79e-05,-1.92e-07,-2.4e-05,1.57e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,9.08e-06,0.000334,0.000334,0.000239,0.382,0.382,0.0203,0.59,0.59,0.0573,6.56e-09,6.57e-09,8.4e-09,3.86e-06,3.86e-06,1.28e-07,0,0,0,0,0,0,0,0
|
||||
8290000,0.982,-0.00616,-0.0121,0.188,-0.00542,0.0471,-0.119,-0.0116,0.038,-0.707,-1.63e-05,-5.79e-05,-2.37e-07,-2.4e-05,1.57e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,8.44e-06,0.000338,0.000338,0.000222,0.425,0.425,0.0197,0.677,0.677,0.0564,6.57e-09,6.57e-09,8.37e-09,3.86e-06,3.86e-06,1.21e-07,0,0,0,0,0,0,0,0
|
||||
8390000,0.982,-0.00611,-0.0121,0.188,-0.00798,0.0484,-0.12,-0.0121,0.0424,-0.719,-1.62e-05,-5.79e-05,-2.89e-07,-2.4e-05,1.58e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,7.98e-06,0.000341,0.000341,0.000209,0.47,0.47,0.0193,0.771,0.771,0.0564,6.54e-09,6.54e-09,8.35e-09,3.85e-06,3.86e-06,1.16e-07,0,0,0,0,0,0,0,0
|
||||
8490000,0.982,-0.00601,-0.0121,0.188,-0.00863,0.0521,-0.121,-0.013,0.0474,-0.731,-1.62e-05,-5.79e-05,-5.22e-08,-2.4e-05,1.58e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,7.53e-06,0.000346,0.000346,0.000197,0.521,0.521,0.0187,0.883,0.883,0.0556,6.54e-09,6.54e-09,8.32e-09,3.85e-06,3.86e-06,1.1e-07,0,0,0,0,0,0,0,0
|
||||
8590000,0.982,-0.00598,-0.0122,0.188,-0.00795,0.0543,-0.12,-0.0137,0.0522,-0.743,-1.62e-05,-5.79e-05,-1.68e-07,-2.4e-05,1.6e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,7.13e-06,0.000349,0.000349,0.000187,0.572,0.572,0.0181,1,1,0.0548,6.5e-09,6.51e-09,8.28e-09,3.85e-06,3.85e-06,1.05e-07,0,0,0,0,0,0,0,0
|
||||
8690000,0.982,-0.006,-0.0123,0.187,-0.00841,0.0562,-0.123,-0.0146,0.0578,-0.755,-1.62e-05,-5.79e-05,-8.68e-08,-2.4e-05,1.6e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,6.85e-06,0.000354,0.000354,0.000179,0.631,0.631,0.0177,1.14,1.14,0.0548,6.5e-09,6.51e-09,8.24e-09,3.85e-06,3.85e-06,1.01e-07,0,0,0,0,0,0,0,0
|
||||
8790000,0.982,-0.00598,-0.0122,0.188,-0.00733,0.0584,-0.125,-0.0153,0.0627,-0.767,-1.62e-05,-5.79e-05,-3.43e-07,-2.4e-05,1.62e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,6.56e-06,0.000358,0.000358,0.000172,0.687,0.687,0.0172,1.29,1.29,0.0541,6.46e-09,6.47e-09,8.2e-09,3.85e-06,3.85e-06,9.63e-08,0,0,0,0,0,0,0,0
|
||||
8890000,0.982,-0.00603,-0.0122,0.187,-0.00777,0.0615,-0.125,-0.016,0.0688,-0.78,-1.62e-05,-5.79e-05,-5.23e-08,-2.4e-05,1.62e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,6.3e-06,0.000363,0.000364,0.000165,0.754,0.754,0.0167,1.47,1.47,0.0533,6.46e-09,6.47e-09,8.14e-09,3.85e-06,3.85e-06,9.2e-08,0,0,0,0,0,0,0,0
|
||||
8990000,0.982,-0.00596,-0.0122,0.187,-0.00898,0.065,-0.124,-0.0166,0.0739,-0.792,-1.61e-05,-5.79e-05,3.46e-07,-2.39e-05,1.66e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,6.13e-06,0.000366,0.000366,0.00016,0.814,0.814,0.0164,1.64,1.64,0.0533,6.41e-09,6.42e-09,8.1e-09,3.85e-06,3.85e-06,8.84e-08,0,0,0,0,0,0,0,0
|
||||
9090000,0.982,-0.00595,-0.0122,0.187,-0.00912,0.0695,-0.127,-0.0175,0.0806,-0.805,-1.61e-05,-5.79e-05,8.08e-07,-2.39e-05,1.66e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,5.93e-06,0.000373,0.000373,0.000155,0.888,0.888,0.0159,1.86,1.86,0.0526,6.41e-09,6.42e-09,8.03e-09,3.85e-06,3.85e-06,8.46e-08,0,0,0,0,0,0,0,0
|
||||
9190000,0.982,-0.00596,-0.0123,0.187,-0.0058,0.0708,-0.127,-0.0179,0.086,-0.818,-1.6e-05,-5.79e-05,1.21e-06,-2.38e-05,1.72e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,5.77e-06,0.000375,0.000375,0.000151,0.95,0.95,0.0155,2.07,2.07,0.0519,6.35e-09,6.36e-09,7.97e-09,3.84e-06,3.84e-06,8.1e-08,0,0,0,0,0,0,0,0
|
||||
9290000,0.982,-0.00581,-0.0121,0.187,-0.00399,0.0736,-0.128,-0.0183,0.0932,-0.831,-1.6e-05,-5.79e-05,1.34e-06,-2.38e-05,1.72e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,5.62e-06,0.000381,0.000381,0.000147,1.03,1.03,0.0151,2.34,2.34,0.0512,6.35e-09,6.36e-09,7.9e-09,3.84e-06,3.84e-06,7.77e-08,0,0,0,0,0,0,0,0
|
||||
9390000,0.982,-0.00573,-0.0121,0.187,-0.00411,0.0746,-0.128,-0.0182,0.0981,-0.843,-1.59e-05,-5.79e-05,8.93e-07,-2.36e-05,1.8e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,5.53e-06,0.000382,0.000382,0.000145,1.09,1.09,0.0148,2.58,2.58,0.0512,6.28e-09,6.28e-09,7.83e-09,3.84e-06,3.84e-06,7.49e-08,0,0,0,0,0,0,0,0
|
||||
9490000,0.982,-0.00575,-0.0122,0.187,-0.00469,0.0765,-0.129,-0.0187,0.106,-0.856,-1.59e-05,-5.8e-05,1.08e-06,-2.36e-05,1.8e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,5.42e-06,0.000389,0.000389,0.000142,1.18,1.18,0.0144,2.91,2.91,0.0506,6.28e-09,6.29e-09,7.75e-09,3.84e-06,3.84e-06,7.19e-08,0,0,0,0,0,0,0,0
|
||||
9590000,0.982,-0.00582,-0.0122,0.187,-0.00493,0.076,-0.13,-0.0186,0.11,-0.869,-1.59e-05,-5.8e-05,1.59e-07,-2.34e-05,1.91e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,5.32e-06,0.000388,0.000388,0.000139,1.24,1.24,0.014,3.17,3.17,0.05,6.2e-09,6.2e-09,7.66e-09,3.83e-06,3.83e-06,6.91e-08,0,0,0,0,0,0,0,0
|
||||
9690000,0.982,-0.00582,-0.0121,0.187,-0.00548,0.0785,-0.128,-0.0191,0.117,-0.882,-1.59e-05,-5.8e-05,-8.91e-08,-2.34e-05,1.91e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,5.27e-06,0.000395,0.000395,0.000138,1.33,1.33,0.0138,3.56,3.56,0.05,6.2e-09,6.2e-09,7.58e-09,3.83e-06,3.83e-06,6.68e-08,0,0,0,0,0,0,0,0
|
||||
9790000,0.982,-0.00579,-0.0121,0.187,-0.00462,0.0816,-0.131,-0.0196,0.125,-0.895,-1.59e-05,-5.79e-05,-1.02e-06,-2.35e-05,1.92e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,5.2e-06,0.000403,0.000403,0.000136,1.43,1.43,0.0135,3.99,3.99,0.0493,6.2e-09,6.2e-09,7.48e-09,3.83e-06,3.83e-06,6.42e-08,0,0,0,0,0,0,0,0
|
||||
9890000,0.982,-0.00579,-0.012,0.187,-0.00241,0.0807,-0.13,-0.0192,0.128,-0.908,-1.58e-05,-5.8e-05,-8.34e-07,-2.31e-05,2.05e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,5.13e-06,0.0004,0.0004,0.000134,1.48,1.48,0.0131,4.29,4.29,0.0487,6.11e-09,6.11e-09,7.38e-09,3.82e-06,3.82e-06,6.19e-08,0,0,0,0,0,0,0,0
|
||||
9990000,0.982,-0.00574,-0.0121,0.188,-0.00111,0.0851,-0.0989,-0.0191,0.141,-0.849,-1.58e-05,-5.79e-05,-1.61e-06,-2.38e-05,1.92e-05,-0.00131,0.204,0.00201,0.435,0,0,0,0,0,5.11e-06,0.000408,0.000408,0.000134,1.59,1.59,0.0129,4.79,4.79,0.0488,6.11e-09,6.11e-09,7.29e-09,3.82e-06,3.82e-06,5.99e-08,0,0,0,0,0,0,0,0
|
||||
10090000,0.982,-0.0057,-0.0123,0.188,-0.00271,0.0846,-0.0654,-0.018,0.147,-0.779,-1.57e-05,-5.79e-05,-2.53e-06,-2.4e-05,1.92e-05,-0.00137,0.204,0.00201,0.435,0,0,0,0,0,5.06e-06,0.000402,0.000402,0.000133,1.62,1.62,0.0126,5.1,5.1,0.0482,6.01e-09,6.01e-09,7.18e-09,3.8e-06,3.8e-06,5.78e-08,0,0,0,0,0,0,0,0
|
||||
10190000,0.982,-0.00563,-0.0122,0.188,-0.00469,0.0904,-0.035,-0.018,0.16,-0.716,-1.57e-05,-5.78e-05,-3.64e-06,-2.46e-05,1.77e-05,-0.00141,0.204,0.00201,0.435,0,0,0,0,0,5.03e-06,0.00041,0.00041,0.000132,1.73,1.73,0.0123,5.67,5.67,0.0476,6.01e-09,6.02e-09,7.07e-09,3.8e-06,3.8e-06,5.58e-08,0,0,0,0,0,0,0,0
|
||||
10290000,0.982,-0.00569,-0.0121,0.188,-0.0041,0.0905,-0.0122,-0.0172,0.164,-0.662,-1.56e-05,-5.78e-05,-3.29e-06,-2.44e-05,1.84e-05,-0.00145,0.204,0.00201,0.435,0,0,0,0,0,5.02e-06,0.000402,0.000402,0.000132,1.75,1.75,0.0122,5.95,5.95,0.0476,5.9e-09,5.91e-09,6.97e-09,3.78e-06,3.78e-06,5.41e-08,0,0,0,0,0,0,0,0
|
||||
10390000,0.982,-0.00566,-0.0121,0.188,0.00655,0.0046,0.0101,0.000733,0.000123,-0.606,-1.56e-05,-5.77e-05,-3.07e-06,-2.47e-05,1.7e-05,-0.00148,0.204,0.00201,0.435,0,0,0,0,0,4.99e-06,0.00041,0.00041,0.000131,0.252,0.252,0.25,0.252,0.252,0.0457,5.9e-09,5.91e-09,6.85e-09,3.78e-06,3.78e-06,5.24e-08,0,0,0,0,0,0,0,0
|
||||
10490000,0.982,-0.00554,-0.012,0.188,0.00741,0.00657,0.053,0.00141,0.000651,-0.548,-1.56e-05,-5.77e-05,-3.96e-06,-2.51e-05,1.58e-05,-0.00151,0.204,0.00201,0.435,0,0,0,0,0,4.96e-06,0.000419,0.000419,0.00013,0.257,0.257,0.247,0.259,0.259,0.0479,5.9e-09,5.91e-09,6.73e-09,3.78e-06,3.78e-06,5.09e-08,0,0,0,0,0,0,0,0
|
||||
10590000,0.982,-0.00546,-0.0119,0.188,-0.00216,0.00452,0.0811,-0.00118,-0.00544,-0.499,-1.56e-05,-5.78e-05,-3.51e-06,-2.31e-05,1.48e-05,-0.00154,0.204,0.00201,0.435,0,0,0,0,0,4.95e-06,0.000423,0.000423,0.00013,0.13,0.13,0.169,0.131,0.131,0.0486,5.89e-09,5.89e-09,6.6e-09,3.77e-06,3.77e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10690000,0.982,-0.00539,-0.012,0.188,-0.00152,0.00539,0.124,-0.00136,-0.00494,-0.448,-1.56e-05,-5.77e-05,-3.85e-06,-2.32e-05,1.41e-05,-0.00155,0.204,0.00201,0.435,0,0,0,0,0,4.96e-06,0.000432,0.000433,0.00013,0.139,0.139,0.164,0.137,0.137,0.054,5.89e-09,5.89e-09,6.49e-09,3.77e-06,3.77e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10790000,0.982,-0.00546,-0.0121,0.188,0.000355,0.00222,0.135,-0.000823,-0.00466,-0.405,-1.54e-05,-5.78e-05,-4.01e-06,-2.23e-05,1.69e-05,-0.00157,0.204,0.00201,0.435,0,0,0,0,0,4.94e-06,0.000427,0.000428,0.00013,0.0961,0.0961,0.123,0.0913,0.0913,0.0538,5.83e-09,5.84e-09,6.36e-09,3.75e-06,3.75e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10890000,0.982,-0.00542,-0.0122,0.188,-2.71e-05,0.00548,0.17,-0.000799,-0.00432,-0.357,-1.54e-05,-5.78e-05,-3.14e-06,-2.24e-05,1.65e-05,-0.00158,0.204,0.00201,0.435,0,0,0,0,0,4.93e-06,0.000437,0.000437,0.00013,0.108,0.108,0.116,0.0974,0.0974,0.0583,5.83e-09,5.84e-09,6.23e-09,3.75e-06,3.75e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10990000,0.982,-0.00545,-0.0123,0.188,-0.00035,0.0117,0.174,-0.000548,-0.00303,-0.323,-1.53e-05,-5.78e-05,-3.53e-06,-2.2e-05,1.79e-05,-0.00159,0.204,0.00201,0.435,0,0,0,0,0,4.94e-06,0.000419,0.000419,0.00013,0.0849,0.0849,0.0921,0.0728,0.0728,0.0579,5.72e-09,5.73e-09,6.11e-09,3.72e-06,3.72e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11090000,0.982,-0.00557,-0.0123,0.188,0.000205,0.0165,0.205,-0.000592,-0.00167,-0.274,-1.53e-05,-5.78e-05,-4.65e-06,-2.21e-05,1.77e-05,-0.0016,0.204,0.00201,0.435,0,0,0,0,0,4.93e-06,0.000429,0.000429,0.00013,0.0999,0.0999,0.0863,0.0791,0.0791,0.0614,5.72e-09,5.73e-09,5.98e-09,3.72e-06,3.72e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11190000,0.982,-0.00578,-0.0123,0.188,0.00185,0.0168,0.207,0.000862,-0.0017,-0.243,-1.49e-05,-5.77e-05,-5.28e-06,-2.3e-05,2.44e-05,-0.0016,0.204,0.00201,0.435,0,0,0,0,0,4.91e-06,0.000398,0.000398,0.00013,0.0823,0.0823,0.0701,0.0627,0.0627,0.0596,5.56e-09,5.56e-09,5.85e-09,3.68e-06,3.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11290000,0.982,-0.00575,-0.0123,0.188,0.00158,0.0181,0.223,0.001,0.000108,-0.206,-1.49e-05,-5.77e-05,-5.63e-06,-2.3e-05,2.43e-05,-0.00161,0.204,0.00201,0.435,0,0,0,0,0,4.94e-06,0.000407,0.000407,0.00013,0.0989,0.099,0.0657,0.0694,0.0694,0.063,5.56e-09,5.56e-09,5.73e-09,3.68e-06,3.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11390000,0.982,-0.00586,-0.0123,0.188,0.000542,0.0163,0.209,0.000676,-0.000587,-0.195,-1.45e-05,-5.79e-05,-5.61e-06,-1.98e-05,3.06e-05,-0.00161,0.204,0.00201,0.435,0,0,0,0,0,4.91e-06,0.000367,0.000368,0.00013,0.0823,0.0823,0.0546,0.0569,0.0569,0.0608,5.36e-09,5.36e-09,5.59e-09,3.63e-06,3.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11490000,0.982,-0.00578,-0.0122,0.188,-0.000726,0.0177,0.224,0.000599,0.00113,-0.158,-1.45e-05,-5.79e-05,-5.54e-06,-1.98e-05,3.05e-05,-0.00161,0.204,0.00201,0.435,0,0,0,0,0,4.9e-06,0.000376,0.000376,0.00013,0.0996,0.0996,0.0504,0.064,0.064,0.0622,5.36e-09,5.36e-09,5.46e-09,3.63e-06,3.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11590000,0.982,-0.00607,-0.0122,0.188,0.00157,0.0146,0.213,0.000628,9.52e-05,-0.147,-1.41e-05,-5.8e-05,-5.58e-06,-1.76e-05,3.67e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.91e-06,0.000333,0.000333,0.00013,0.0822,0.0822,0.0432,0.0535,0.0535,0.0609,5.13e-09,5.14e-09,5.34e-09,3.58e-06,3.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11690000,0.982,-0.00604,-0.0122,0.188,0.00175,0.0188,0.219,0.000809,0.00174,-0.123,-1.4e-05,-5.8e-05,-5.35e-06,-1.76e-05,3.67e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.9e-06,0.000342,0.000342,0.00013,0.099,0.099,0.0398,0.0611,0.0611,0.0616,5.13e-09,5.14e-09,5.21e-09,3.58e-06,3.58e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11790000,0.982,-0.0064,-0.0121,0.188,0.00099,0.0134,0.211,0.000517,-0.00108,-0.113,-1.33e-05,-5.84e-05,-4.42e-06,-1.35e-05,4.55e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.88e-06,0.000301,0.000301,0.00013,0.0809,0.0809,0.0343,0.0515,0.0515,0.0593,4.91e-09,4.92e-09,5.08e-09,3.54e-06,3.54e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11890000,0.982,-0.00648,-0.012,0.188,0.00347,0.0152,0.211,0.000687,0.000315,-0.0927,-1.33e-05,-5.84e-05,-4.67e-06,-1.35e-05,4.55e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.87e-06,0.000308,0.000308,0.000129,0.0967,0.0967,0.0316,0.0594,0.0594,0.0595,4.91e-09,4.92e-09,4.95e-09,3.54e-06,3.54e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11990000,0.982,-0.00666,-0.0121,0.188,0.00663,0.0146,0.2,0.00192,-0.00113,-0.0914,-1.31e-05,-5.83e-05,-4.38e-06,-1.42e-05,4.86e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.88e-06,0.000272,0.000272,0.00013,0.0784,0.0784,0.0279,0.0503,0.0503,0.0582,4.7e-09,4.71e-09,4.83e-09,3.51e-06,3.51e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12090000,0.982,-0.00657,-0.0121,0.188,0.00805,0.015,0.203,0.00264,0.000328,-0.071,-1.31e-05,-5.83e-05,-4.43e-06,-1.42e-05,4.86e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.87e-06,0.000279,0.000279,0.000129,0.0928,0.0928,0.0258,0.0584,0.0584,0.058,4.7e-09,4.71e-09,4.7e-09,3.51e-06,3.51e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12190000,0.982,-0.00651,-0.0121,0.188,0.00678,0.0136,0.194,0.00167,0.000997,-0.0669,-1.31e-05,-5.86e-05,-4.81e-06,-1.2e-05,4.88e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.84e-06,0.000249,0.000249,0.000129,0.0751,0.0751,0.0228,0.0496,0.0496,0.056,4.51e-09,4.52e-09,4.58e-09,3.49e-06,3.49e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12290000,0.982,-0.00658,-0.0121,0.188,0.0044,0.0132,0.192,0.00225,0.00235,-0.0541,-1.31e-05,-5.85e-05,-5.11e-06,-1.2e-05,4.89e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.86e-06,0.000255,0.000256,0.000129,0.088,0.088,0.0213,0.0578,0.0578,0.0564,4.51e-09,4.52e-09,4.47e-09,3.49e-06,3.49e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12390000,0.982,-0.00671,-0.012,0.188,0.00335,0.00959,0.182,0.0016,0.0011,-0.0593,-1.28e-05,-5.88e-05,-5.13e-06,-1.03e-05,5.1e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.83e-06,0.00023,0.00023,0.000129,0.0712,0.0712,0.019,0.0492,0.0492,0.0544,4.34e-09,4.34e-09,4.34e-09,3.48e-06,3.48e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12490000,0.982,-0.0067,-0.0119,0.188,0.00331,0.0109,0.185,0.00197,0.00212,-0.0489,-1.28e-05,-5.88e-05,-5.19e-06,-1.03e-05,5.1e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.82e-06,0.000237,0.000237,0.000128,0.0828,0.0828,0.0177,0.0574,0.0574,0.0539,4.34e-09,4.34e-09,4.22e-09,3.48e-06,3.48e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12590000,0.982,-0.00689,-0.0119,0.188,0.00714,0.00407,0.18,0.00318,-0.000691,-0.0466,-1.23e-05,-5.88e-05,-5.21e-06,-1.01e-05,5.43e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.83e-06,0.000216,0.000216,0.000129,0.0672,0.0672,0.0161,0.0489,0.0489,0.0528,4.18e-09,4.19e-09,4.12e-09,3.47e-06,3.47e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12690000,0.982,-0.00684,-0.0119,0.188,0.0076,0.00221,0.178,0.00387,-0.000372,-0.039,-1.23e-05,-5.88e-05,-5.12e-06,-1.02e-05,5.44e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.81e-06,0.000223,0.000223,0.000128,0.0776,0.0777,0.015,0.0571,0.0571,0.0521,4.18e-09,4.19e-09,4e-09,3.47e-06,3.47e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12790000,0.982,-0.00709,-0.0118,0.188,0.0092,-0.00139,0.173,0.00396,-0.00371,-0.0386,-1.18e-05,-5.88e-05,-3.9e-06,-9.74e-06,5.67e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.78e-06,0.000206,0.000206,0.000128,0.0634,0.0634,0.0137,0.0487,0.0487,0.0505,4.03e-09,4.04e-09,3.89e-09,3.47e-06,3.47e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12890000,0.982,-0.00709,-0.0118,0.188,0.0093,-0.00198,0.172,0.00492,-0.0039,-0.03,-1.18e-05,-5.88e-05,-3.11e-06,-9.75e-06,5.67e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.78e-06,0.000212,0.000212,0.000128,0.0728,0.0728,0.013,0.0568,0.0568,0.0504,4.03e-09,4.04e-09,3.79e-09,3.47e-06,3.47e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12990000,0.982,-0.00707,-0.0117,0.187,0.00752,-0.000567,0.167,0.00348,-0.00299,-0.0311,-1.19e-05,-5.9e-05,-2.38e-06,-9.31e-06,5.62e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.76e-06,0.000199,0.000199,0.000127,0.0598,0.0598,0.012,0.0485,0.0485,0.0488,3.9e-09,3.9e-09,3.68e-09,3.47e-06,3.47e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13090000,0.982,-0.00709,-0.0116,0.187,0.00841,-0.000178,0.162,0.00426,-0.00297,-0.0293,-1.19e-05,-5.91e-05,-1.45e-06,-9.36e-06,5.63e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.74e-06,0.000205,0.000205,0.000127,0.0683,0.0683,0.0113,0.0565,0.0565,0.0481,3.9e-09,3.9e-09,3.58e-09,3.47e-06,3.47e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
13190000,0.982,-0.00712,-0.0115,0.187,0.00364,-0.00222,0.156,0.000927,-0.00401,-0.0314,-1.18e-05,-5.94e-05,-8.43e-07,-8.66e-06,5.61e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.71e-06,0.000193,0.000193,0.000126,0.0565,0.0565,0.0105,0.0484,0.0484,0.0467,3.76e-09,3.76e-09,3.47e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
13290000,0.982,-0.00714,-0.0116,0.187,0.00329,-0.00289,0.152,0.00122,-0.00424,-0.0287,-1.18e-05,-5.94e-05,-7.39e-07,-8.76e-06,5.62e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.71e-06,0.000199,0.000199,0.000126,0.0643,0.0643,0.0101,0.0562,0.0562,0.0465,3.76e-09,3.76e-09,3.39e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
13390000,0.982,-0.00708,-0.0117,0.187,0.00251,-0.00135,0.148,0.000831,-0.00327,-0.0311,-1.19e-05,-5.94e-05,-1.02e-06,-9.1e-06,5.63e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.68e-06,0.00019,0.00019,0.000125,0.0536,0.0536,0.00943,0.0482,0.0482,0.0452,3.63e-09,3.63e-09,3.29e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
13490000,0.982,-0.00706,-0.0116,0.187,0.00298,0.000544,0.145,0.00112,-0.00324,-0.0338,-1.19e-05,-5.94e-05,-7.29e-07,-9.25e-06,5.64e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.66e-06,0.000196,0.000196,0.000125,0.0607,0.0607,0.00904,0.0559,0.0559,0.0445,3.63e-09,3.63e-09,3.19e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
13590000,0.982,-0.00707,-0.0117,0.187,0.00735,-1.5e-05,0.143,0.00393,-0.00275,-0.0368,-1.18e-05,-5.91e-05,-9.05e-07,-8.96e-06,5.62e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.66e-06,0.000187,0.000187,0.000125,0.0509,0.0509,0.00862,0.0481,0.0481,0.0439,3.49e-09,3.5e-09,3.11e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
13690000,0.982,-0.00702,-0.0116,0.187,0.00735,-0.00124,0.142,0.00465,-0.00281,-0.0336,-1.18e-05,-5.91e-05,-3.87e-07,-9.06e-06,5.62e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.63e-06,0.000193,0.000193,0.000124,0.0576,0.0576,0.00832,0.0556,0.0556,0.0432,3.49e-09,3.5e-09,3.02e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
13790000,0.982,-0.00697,-0.0118,0.187,0.0142,0.00254,0.138,0.00814,-0.000595,-0.0374,-1.19e-05,-5.87e-05,-5.78e-07,-7.59e-06,5.66e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.6e-06,0.000186,0.000186,0.000123,0.0487,0.0487,0.00794,0.0479,0.0479,0.0421,3.36e-09,3.36e-09,2.93e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
13890000,0.982,-0.00688,-0.0117,0.187,0.0153,0.00344,0.138,0.00959,-0.00029,-0.0338,-1.18e-05,-5.87e-05,5.07e-08,-7.71e-06,5.66e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.59e-06,0.000191,0.000191,0.000123,0.055,0.055,0.00777,0.0553,0.0553,0.0419,3.36e-09,3.36e-09,2.85e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
13990000,0.982,-0.00694,-0.0114,0.187,0.0148,0.00342,0.133,0.00728,-0.00193,-0.0384,-1.17e-05,-5.91e-05,7.03e-07,-9.92e-06,5.6e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.56e-06,0.000185,0.000185,0.000122,0.0467,0.0467,0.00748,0.0477,0.0477,0.0409,3.22e-09,3.22e-09,2.77e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
14090000,0.982,-0.00695,-0.0114,0.187,0.0124,-0.000798,0.133,0.00873,-0.00182,-0.0425,-1.17e-05,-5.91e-05,-6.09e-07,-1.02e-05,5.62e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.54e-06,0.00019,0.00019,0.000121,0.0527,0.0527,0.00733,0.0549,0.0549,0.0403,3.22e-09,3.22e-09,2.69e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
14190000,0.982,-0.00692,-0.0113,0.187,0.00986,0.000255,0.13,0.00797,-0.00139,-0.0444,-1.18e-05,-5.92e-05,-1.19e-06,-1.09e-05,5.68e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.53e-06,0.000184,0.000184,0.000121,0.0451,0.0451,0.00715,0.0475,0.0475,0.0398,3.08e-09,3.08e-09,2.62e-09,3.45e-06,3.45e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14290000,0.982,-0.00686,-0.0113,0.187,0.0115,0.000382,0.127,0.00892,-0.00141,-0.0412,-1.18e-05,-5.92e-05,-1.07e-06,-1.11e-05,5.69e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.5e-06,0.000189,0.000189,0.00012,0.0508,0.0508,0.00705,0.0546,0.0546,0.0393,3.08e-09,3.08e-09,2.54e-09,3.45e-06,3.45e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14390000,0.982,-0.00696,-0.0112,0.187,0.0116,-0.00279,0.125,0.00836,-0.00271,-0.0408,-1.16e-05,-5.94e-05,-6.25e-07,-1.23e-05,5.58e-05,-0.00161,0.204,0.00201,0.435,0,0,0,0,0,4.47e-06,0.000183,0.000183,0.00012,0.0437,0.0437,0.00689,0.0473,0.0473,0.0385,2.93e-09,2.94e-09,2.47e-09,3.45e-06,3.45e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14490000,0.982,-0.00707,-0.0112,0.187,0.0101,-0.00237,0.128,0.00939,-0.00298,-0.0397,-1.16e-05,-5.94e-05,-1.26e-06,-1.25e-05,5.6e-05,-0.00161,0.204,0.00201,0.435,0,0,0,0,0,4.44e-06,0.000188,0.000188,0.000119,0.0492,0.0492,0.00683,0.0543,0.0543,0.038,2.94e-09,2.94e-09,2.4e-09,3.45e-06,3.45e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14590000,0.982,-0.00714,-0.011,0.187,0.00796,-0.00265,0.123,0.00589,-0.00379,-0.0461,-1.17e-05,-5.99e-05,-1.33e-06,-1.7e-05,5.65e-05,-0.00161,0.204,0.00201,0.435,0,0,0,0,0,4.43e-06,0.000182,0.000182,0.000118,0.0425,0.0425,0.00675,0.0471,0.0471,0.0376,2.79e-09,2.79e-09,2.34e-09,3.44e-06,3.44e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14690000,0.982,-0.00713,-0.011,0.187,0.00716,-0.00247,0.122,0.00662,-0.00403,-0.0474,-1.17e-05,-5.99e-05,-1.04e-06,-1.74e-05,5.67e-05,-0.00161,0.204,0.00201,0.435,0,0,0,0,0,4.4e-06,0.000187,0.000187,0.000118,0.048,0.048,0.00673,0.054,0.054,0.0372,2.79e-09,2.79e-09,2.27e-09,3.44e-06,3.44e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14790000,0.982,-0.00706,-0.011,0.187,0.00889,0.00413,0.12,0.00529,0.0011,-0.0485,-1.24e-05,-5.98e-05,-2.58e-07,-1.68e-05,6.35e-05,-0.00161,0.204,0.00201,0.435,0,0,0,0,0,4.36e-06,0.000181,0.000181,0.000117,0.0416,0.0416,0.00665,0.0469,0.0469,0.0365,2.63e-09,2.64e-09,2.2e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14890000,0.982,-0.00697,-0.0109,0.187,0.00755,0.00188,0.123,0.00606,0.00141,-0.0479,-1.24e-05,-5.99e-05,3.09e-07,-1.72e-05,6.37e-05,-0.00161,0.204,0.00201,0.435,0,0,0,0,0,4.35e-06,0.000186,0.000186,0.000116,0.0469,0.0469,0.0067,0.0537,0.0537,0.0365,2.63e-09,2.64e-09,2.15e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14990000,0.982,-0.00712,-0.0108,0.187,0.00629,0.000129,0.123,0.00475,-0.000331,-0.0499,-1.22e-05,-6.02e-05,6.56e-07,-2.05e-05,6.25e-05,-0.0016,0.204,0.00201,0.435,0,0,0,0,0,4.32e-06,0.00018,0.00018,0.000116,0.0408,0.0408,0.00664,0.0467,0.0467,0.0359,2.48e-09,2.48e-09,2.09e-09,3.41e-06,3.41e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15090000,0.982,-0.00707,-0.0109,0.187,0.00632,0.00136,0.125,0.00539,-0.000298,-0.0492,-1.22e-05,-6.02e-05,6.77e-07,-2.09e-05,6.27e-05,-0.0016,0.204,0.00201,0.435,0,0,0,0,0,4.28e-06,0.000185,0.000185,0.000115,0.046,0.046,0.00668,0.0535,0.0535,0.0355,2.48e-09,2.48e-09,2.03e-09,3.41e-06,3.41e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15190000,0.982,-0.0072,-0.0109,0.187,0.00444,0.000112,0.124,0.00422,-0.000382,-0.0502,-1.23e-05,-6.04e-05,4.79e-07,-2.32e-05,6.35e-05,-0.0016,0.204,0.00201,0.435,0,0,0,0,0,4.27e-06,0.000178,0.000178,0.000114,0.0402,0.0402,0.00668,0.0466,0.0466,0.0353,2.32e-09,2.33e-09,1.98e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15290000,0.982,-0.00729,-0.0109,0.187,0.00493,-0.000793,0.122,0.0047,-0.00039,-0.0554,-1.22e-05,-6.04e-05,1.05e-06,-2.39e-05,6.39e-05,-0.00159,0.204,0.00201,0.435,0,0,0,0,0,4.24e-06,0.000183,0.000183,0.000114,0.0453,0.0453,0.00674,0.0533,0.0533,0.035,2.32e-09,2.33e-09,1.92e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15390000,0.982,-0.00737,-0.0109,0.187,0.00508,0.00143,0.119,0.00373,-0.000254,-0.0592,-1.23e-05,-6.05e-05,9.9e-07,-2.61e-05,6.52e-05,-0.00159,0.204,0.00201,0.435,0,0,0,0,0,4.21e-06,0.000176,0.000176,0.000113,0.0396,0.0396,0.00673,0.0464,0.0464,0.0346,2.17e-09,2.17e-09,1.86e-09,3.38e-06,3.38e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15490000,0.982,-0.00739,-0.0109,0.187,0.00443,-0.000957,0.118,0.0042,-0.000203,-0.0592,-1.23e-05,-6.05e-05,1.01e-06,-2.64e-05,6.53e-05,-0.00159,0.204,0.00201,0.435,0,0,0,0,0,4.2e-06,0.000181,0.000181,0.000112,0.0447,0.0447,0.00684,0.0531,0.0531,0.0346,2.17e-09,2.17e-09,1.82e-09,3.38e-06,3.38e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15590000,0.982,-0.00759,-0.0109,0.187,0.00785,-0.00487,0.116,0.00615,-0.00423,-0.0648,-1.16e-05,-6.05e-05,1.37e-06,-2.72e-05,5.81e-05,-0.00158,0.204,0.00201,0.435,0,0,0,0,0,4.17e-06,0.000174,0.000174,0.000111,0.0392,0.0392,0.00684,0.0463,0.0463,0.0342,2.02e-09,2.02e-09,1.77e-09,3.36e-06,3.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15690000,0.982,-0.00754,-0.0108,0.187,0.00955,-0.0078,0.115,0.007,-0.00485,-0.0664,-1.16e-05,-6.05e-05,1.85e-06,-2.83e-05,5.9e-05,-0.00158,0.204,0.00201,0.435,0,0,0,0,0,4.13e-06,0.000178,0.000178,0.00011,0.0441,0.0441,0.00693,0.0529,0.0529,0.034,2.02e-09,2.02e-09,1.72e-09,3.36e-06,3.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15790000,0.982,-0.00753,-0.0107,0.186,0.00602,-0.00733,0.112,0.00536,-0.00381,-0.0692,-1.19e-05,-6.07e-05,2.51e-06,-3.16e-05,6.33e-05,-0.00157,0.204,0.00201,0.435,0,0,0,0,0,4.09e-06,0.000171,0.000171,0.00011,0.0387,0.0387,0.00694,0.0462,0.0462,0.0337,1.87e-09,1.87e-09,1.67e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15890000,0.982,-0.00758,-0.0108,0.187,0.00477,-0.00558,0.112,0.00587,-0.00447,-0.0709,-1.19e-05,-6.07e-05,2.04e-06,-3.19e-05,6.33e-05,-0.00157,0.204,0.00201,0.435,0,0,0,0,0,4.08e-06,0.000175,0.000175,0.000109,0.0436,0.0436,0.00706,0.0527,0.0527,0.0338,1.87e-09,1.87e-09,1.63e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15990000,0.982,-0.00738,-0.0107,0.186,0.0027,-0.00429,0.106,0.00462,-0.00347,-0.076,-1.21e-05,-6.08e-05,2.01e-06,-3.41e-05,6.62e-05,-0.00157,0.204,0.00201,0.435,0,0,0,0,0,4.05e-06,0.000168,0.000168,0.000108,0.0383,0.0383,0.00708,0.0461,0.0461,0.0335,1.72e-09,1.72e-09,1.59e-09,3.32e-06,3.32e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16090000,0.982,-0.00735,-0.0107,0.186,0.00194,-0.00542,0.103,0.00479,-0.00395,-0.0788,-1.21e-05,-6.08e-05,1.75e-06,-3.46e-05,6.64e-05,-0.00156,0.204,0.00201,0.435,0,0,0,0,0,4.01e-06,0.000172,0.000172,0.000107,0.0431,0.0431,0.00718,0.0526,0.0526,0.0334,1.72e-09,1.72e-09,1.54e-09,3.32e-06,3.32e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16190000,0.982,-0.00725,-0.0106,0.187,-0.00201,-0.00325,0.0995,0.00249,-0.00292,-0.0851,-1.23e-05,-6.1e-05,1.39e-06,-3.8e-05,6.99e-05,-0.00156,0.204,0.00201,0.435,0,0,0,0,0,3.99e-06,0.000164,0.000164,0.000107,0.0379,0.0379,0.00723,0.046,0.046,0.0334,1.58e-09,1.58e-09,1.51e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16290000,0.982,-0.00727,-0.0105,0.187,-0.00182,-0.00463,0.0979,0.00225,-0.00335,-0.0867,-1.23e-05,-6.1e-05,1.56e-06,-3.88e-05,7.04e-05,-0.00155,0.204,0.00201,0.435,0,0,0,0,0,3.96e-06,0.000168,0.000168,0.000106,0.0426,0.0426,0.00734,0.0525,0.0525,0.0334,1.58e-09,1.58e-09,1.46e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16390000,0.982,-0.00723,-0.0105,0.186,0.000586,-0.0041,0.0957,0.0033,-0.00256,-0.0913,-1.24e-05,-6.08e-05,1.95e-06,-3.7e-05,7.17e-05,-0.00155,0.204,0.00201,0.435,0,0,0,0,0,3.93e-06,0.000161,0.000161,0.000105,0.0375,0.0375,0.00736,0.0459,0.0459,0.0331,1.44e-09,1.45e-09,1.43e-09,3.27e-06,3.28e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16490000,0.982,-0.00735,-0.0105,0.186,0.00249,-0.0056,0.0969,0.00347,-0.0031,-0.089,-1.24e-05,-6.08e-05,1.81e-06,-3.73e-05,7.18e-05,-0.00154,0.204,0.00201,0.435,0,0,0,0,0,3.91e-06,0.000164,0.000164,0.000105,0.0421,0.0421,0.0075,0.0524,0.0524,0.0334,1.45e-09,1.45e-09,1.39e-09,3.27e-06,3.28e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16590000,0.982,-0.00731,-0.0105,0.186,0.00657,-0.00581,0.0981,0.00305,-0.0024,-0.0936,-1.25e-05,-6.08e-05,1.83e-06,-3.86e-05,7.45e-05,-0.00154,0.204,0.00201,0.435,0,0,0,0,0,3.88e-06,0.000157,0.000157,0.000104,0.037,0.037,0.00751,0.0459,0.0459,0.0332,1.32e-09,1.32e-09,1.35e-09,3.25e-06,3.25e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16690000,0.982,-0.00736,-0.0104,0.186,0.00787,-0.0103,0.0965,0.00376,-0.00318,-0.0963,-1.25e-05,-6.09e-05,2.07e-06,-3.96e-05,7.52e-05,-0.00153,0.204,0.00201,0.435,0,0,0,0,0,3.85e-06,0.00016,0.00016,0.000103,0.0415,0.0415,0.00763,0.0523,0.0523,0.0332,1.32e-09,1.32e-09,1.32e-09,3.25e-06,3.25e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16790000,0.982,-0.00718,-0.0103,0.186,0.00874,-0.00925,0.0931,0.00289,-0.00227,-0.1,-1.28e-05,-6.1e-05,2.24e-06,-4.21e-05,7.98e-05,-0.00153,0.204,0.00201,0.435,0,0,0,0,0,3.83e-06,0.000153,0.000153,0.000103,0.0365,0.0365,0.00767,0.0458,0.0458,0.0333,1.2e-09,1.2e-09,1.29e-09,3.23e-06,3.23e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16890000,0.982,-0.00715,-0.0103,0.186,0.00751,-0.00956,0.0924,0.00366,-0.00317,-0.105,-1.28e-05,-6.1e-05,2.73e-06,-4.34e-05,8.07e-05,-0.00152,0.204,0.00201,0.435,0,0,0,0,0,3.8e-06,0.000156,0.000156,0.000102,0.0409,0.0409,0.00778,0.0522,0.0522,0.0333,1.2e-09,1.2e-09,1.25e-09,3.23e-06,3.23e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16990000,0.982,-0.00716,-0.0104,0.186,0.00722,-0.00906,0.0896,0.00354,-0.00234,-0.112,-1.3e-05,-6.08e-05,2.84e-06,-4.18e-05,8.33e-05,-0.00152,0.204,0.00201,0.435,0,0,0,0,0,3.76e-06,0.000149,0.000149,0.000101,0.036,0.036,0.00778,0.0457,0.0457,0.0332,1.09e-09,1.09e-09,1.22e-09,3.21e-06,3.21e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17090000,0.982,-0.00725,-0.0103,0.186,0.00859,-0.0116,0.0874,0.00433,-0.00342,-0.116,-1.3e-05,-6.08e-05,2.72e-06,-4.27e-05,8.38e-05,-0.00151,0.204,0.00201,0.435,0,0,0,0,0,3.73e-06,0.000152,0.000152,0.0001,0.0402,0.0402,0.00789,0.0521,0.0521,0.0332,1.09e-09,1.09e-09,1.19e-09,3.21e-06,3.21e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17190000,0.982,-0.00737,-0.0102,0.186,0.00754,-0.0169,0.0868,0.00281,-0.00703,-0.117,-1.28e-05,-6.1e-05,2.2e-06,-4.52e-05,8.2e-05,-0.00151,0.204,0.00201,0.435,0,0,0,0,0,3.72e-06,0.000145,0.000145,0.0001,0.0354,0.0354,0.00791,0.0457,0.0457,0.0334,9.89e-10,9.89e-10,1.16e-09,3.19e-06,3.19e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17290000,0.982,-0.00732,-0.0102,0.186,0.00826,-0.0173,0.0846,0.00357,-0.00869,-0.121,-1.28e-05,-6.1e-05,1.84e-06,-4.6e-05,8.24e-05,-0.0015,0.204,0.00201,0.435,0,0,0,0,0,3.69e-06,0.000148,0.000148,9.93e-05,0.0395,0.0395,0.00802,0.052,0.052,0.0335,9.89e-10,9.89e-10,1.13e-09,3.19e-06,3.19e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17390000,0.982,-0.00718,-0.0102,0.186,0.00503,-0.017,0.0814,0.00507,-0.0054,-0.126,-1.33e-05,-6.06e-05,2.18e-06,-4.24e-05,8.95e-05,-0.00149,0.204,0.00201,0.435,0,0,0,0,0,3.66e-06,0.000141,0.000141,9.85e-05,0.0348,0.0348,0.008,0.0456,0.0456,0.0333,8.96e-10,8.96e-10,1.11e-09,3.17e-06,3.17e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17490000,0.982,-0.0072,-0.0102,0.186,0.00293,-0.0177,0.0797,0.00541,-0.00712,-0.128,-1.33e-05,-6.06e-05,1.99e-06,-4.31e-05,8.99e-05,-0.00149,0.204,0.00201,0.435,0,0,0,0,0,3.64e-06,0.000144,0.000144,9.81e-05,0.0388,0.0388,0.00813,0.0519,0.0519,0.0337,8.96e-10,8.96e-10,1.08e-09,3.17e-06,3.17e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17590000,0.982,-0.00709,-0.0101,0.186,-0.000834,-0.0138,0.0763,0.00175,-0.00528,-0.135,-1.37e-05,-6.09e-05,1.98e-06,-4.81e-05,9.74e-05,-0.00148,0.204,0.00201,0.435,0,0,0,0,0,3.61e-06,0.000138,0.000138,9.73e-05,0.0342,0.0342,0.00811,0.0455,0.0455,0.0336,8.11e-10,8.11e-10,1.05e-09,3.15e-06,3.15e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17690000,0.982,-0.00718,-0.01,0.186,-0.00195,-0.0143,0.0755,0.00162,-0.00671,-0.137,-1.37e-05,-6.09e-05,2.04e-06,-4.89e-05,9.79e-05,-0.00148,0.204,0.00201,0.435,0,0,0,0,0,3.58e-06,0.00014,0.00014,9.65e-05,0.038,0.038,0.0082,0.0518,0.0518,0.0337,8.11e-10,8.11e-10,1.03e-09,3.15e-06,3.15e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17790000,0.982,-0.00713,-0.01,0.186,0.00092,-0.0127,0.0737,0.0028,-0.00569,-0.136,-1.4e-05,-6.06e-05,2.08e-06,-4.51e-05,0.000102,-0.00147,0.204,0.00201,0.435,0,0,0,0,0,3.56e-06,0.000134,0.000134,9.62e-05,0.0335,0.0335,0.00821,0.0455,0.0455,0.0339,7.34e-10,7.34e-10,1.01e-09,3.13e-06,3.13e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17890000,0.983,-0.00706,-0.0101,0.186,0.00291,-0.0145,0.0716,0.00303,-0.00706,-0.136,-1.4e-05,-6.06e-05,2.2e-06,-4.58e-05,0.000103,-0.00147,0.204,0.00201,0.435,0,0,0,0,0,3.53e-06,0.000136,0.000136,9.54e-05,0.0372,0.0372,0.00829,0.0517,0.0517,0.034,7.34e-10,7.34e-10,9.81e-10,3.13e-06,3.13e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17990000,0.983,-0.00684,-0.0101,0.186,0.00245,-0.00801,0.0687,0.00239,-0.00147,-0.141,-1.46e-05,-6.04e-05,2.15e-06,-4.39e-05,0.000113,-0.00147,0.204,0.00201,0.435,0,0,0,0,0,3.5e-06,0.000131,0.000131,9.46e-05,0.0328,0.0328,0.00825,0.0454,0.0454,0.0339,6.64e-10,6.64e-10,9.57e-10,3.12e-06,3.12e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18090000,0.983,-0.00692,-0.0101,0.186,0.00174,-0.00844,0.0665,0.00263,-0.00232,-0.147,-1.46e-05,-6.04e-05,2.09e-06,-4.49e-05,0.000114,-0.00146,0.204,0.00201,0.435,0,0,0,0,0,3.48e-06,0.000133,0.000133,9.43e-05,0.0364,0.0364,0.00837,0.0515,0.0515,0.0343,6.64e-10,6.64e-10,9.37e-10,3.12e-06,3.12e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18190000,0.983,-0.00692,-0.0101,0.186,0.00185,-0.00749,0.0644,0.00334,-0.00165,-0.154,-1.47e-05,-6.03e-05,2.57e-06,-4.41e-05,0.000116,-0.00145,0.204,0.00201,0.435,0,0,0,0,0,3.45e-06,0.000127,0.000127,9.35e-05,0.0321,0.0321,0.00832,0.0453,0.0453,0.0342,6e-10,6e-10,9.14e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18290000,0.983,-0.00695,-0.0101,0.186,0.00252,-0.00787,0.0614,0.00349,-0.00239,-0.16,-1.47e-05,-6.03e-05,2.58e-06,-4.51e-05,0.000117,-0.00145,0.204,0.00201,0.435,0,0,0,0,0,3.43e-06,0.000129,0.000129,9.28e-05,0.0356,0.0356,0.00839,0.0514,0.0514,0.0343,6e-10,6e-10,8.92e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18390000,0.983,-0.00686,-0.0101,0.186,0.00356,-0.00671,0.0588,0.00529,-0.00178,-0.166,-1.48e-05,-6.01e-05,2.39e-06,-4.27e-05,0.000118,-0.00144,0.204,0.00201,0.435,0,0,0,0,0,3.4e-06,0.000124,0.000124,9.21e-05,0.0314,0.0314,0.00834,0.0452,0.0452,0.0342,5.43e-10,5.43e-10,8.71e-10,3.09e-06,3.09e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18490000,0.983,-0.0069,-0.0101,0.186,0.00615,-0.00666,0.0566,0.00586,-0.00247,-0.169,-1.48e-05,-6.01e-05,2.56e-06,-4.32e-05,0.000119,-0.00144,0.204,0.00201,0.435,0,0,0,0,0,3.39e-06,0.000126,0.000126,9.17e-05,0.0347,0.0347,0.00844,0.0512,0.0512,0.0347,5.43e-10,5.43e-10,8.53e-10,3.09e-06,3.09e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18590000,0.982,-0.00672,-0.00997,0.186,0.00473,-0.00613,0.0542,0.00471,-0.00186,-0.171,-1.49e-05,-6.01e-05,2.27e-06,-4.53e-05,0.000121,-0.00143,0.204,0.00201,0.435,0,0,0,0,0,3.37e-06,0.000121,0.000121,9.1e-05,0.0307,0.0307,0.00838,0.0451,0.0451,0.0345,4.92e-10,4.92e-10,8.33e-10,3.08e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18690000,0.983,-0.00668,-0.00991,0.186,0.00458,-0.00499,0.0508,0.00516,-0.00241,-0.177,-1.49e-05,-6.02e-05,2.47e-06,-4.61e-05,0.000122,-0.00143,0.204,0.00201,0.435,0,0,0,0,0,3.34e-06,0.000123,0.000123,9.03e-05,0.0339,0.0339,0.00844,0.0511,0.0511,0.0347,4.92e-10,4.92e-10,8.14e-10,3.08e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18790000,0.983,-0.00665,-0.00981,0.186,0.00371,-0.00478,0.0487,0.00531,-0.00194,-0.184,-1.5e-05,-6.01e-05,2.4e-06,-4.64e-05,0.000124,-0.00142,0.204,0.00201,0.435,0,0,0,0,0,3.33e-06,0.000119,0.000118,8.99e-05,0.0299,0.0299,0.00841,0.045,0.045,0.0348,4.46e-10,4.46e-10,7.97e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18890000,0.983,-0.0066,-0.00983,0.186,0.00216,-0.00429,0.0449,0.00554,-0.00246,-0.192,-1.5e-05,-6.01e-05,2.22e-06,-4.77e-05,0.000124,-0.00142,0.204,0.00201,0.435,0,0,0,0,0,3.3e-06,0.00012,0.00012,8.92e-05,0.033,0.033,0.00846,0.0509,0.0509,0.0349,4.46e-10,4.46e-10,7.79e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18990000,0.982,-0.00658,-0.00985,0.186,0.000722,-0.00454,0.0437,0.00457,-0.00195,-0.194,-1.5e-05,-6.01e-05,2.17e-06,-4.88e-05,0.000126,-0.00141,0.204,0.00201,0.435,0,0,0,0,0,3.28e-06,0.000116,0.000116,8.85e-05,0.0292,0.0292,0.00839,0.0448,0.0448,0.0348,4.05e-10,4.05e-10,7.61e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19090000,0.982,-0.00664,-0.00987,0.186,-0.00149,-0.00494,0.0428,0.00457,-0.00237,-0.202,-1.5e-05,-6.01e-05,2.33e-06,-4.97e-05,0.000127,-0.00141,0.204,0.00201,0.435,0,0,0,0,0,3.27e-06,0.000117,0.000117,8.82e-05,0.0322,0.0322,0.00848,0.0507,0.0507,0.0352,4.05e-10,4.05e-10,7.46e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19190000,0.982,-0.00653,-0.00999,0.186,-0.00281,-0.00468,0.0405,0.0038,-0.00193,-0.208,-1.51e-05,-6.01e-05,1.87e-06,-5.07e-05,0.000129,-0.0014,0.204,0.00201,0.435,0,0,0,0,0,3.24e-06,0.000113,0.000113,8.75e-05,0.0285,0.0285,0.0084,0.0447,0.0447,0.035,3.68e-10,3.68e-10,7.29e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19290000,0.982,-0.00649,-0.00992,0.186,-0.00385,-0.00446,0.0393,0.0035,-0.00237,-0.213,-1.51e-05,-6.01e-05,1.78e-06,-5.16e-05,0.000129,-0.0014,0.204,0.00201,0.435,0,0,0,0,0,3.22e-06,0.000115,0.000115,8.68e-05,0.0313,0.0313,0.00844,0.0505,0.0505,0.0352,3.68e-10,3.68e-10,7.13e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19390000,0.982,-0.00656,-0.00982,0.186,-0.00411,-0.00108,0.039,0.00304,-0.000585,-0.219,-1.52e-05,-6e-05,1.64e-06,-5.14e-05,0.000132,-0.00139,0.204,0.00201,0.435,0,0,0,0,0,3.2e-06,0.000111,0.000111,8.65e-05,0.0278,0.0278,0.0084,0.0446,0.0446,0.0353,3.35e-10,3.35e-10,6.99e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19490000,0.982,-0.00659,-0.00973,0.186,-0.00513,-0.000982,0.0369,0.00256,-0.000672,-0.224,-1.53e-05,-6e-05,1.32e-06,-5.24e-05,0.000133,-0.00139,0.204,0.00201,0.435,0,0,0,0,0,3.18e-06,0.000112,0.000112,8.58e-05,0.0305,0.0305,0.00844,0.0503,0.0503,0.0354,3.35e-10,3.35e-10,6.83e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19590000,0.982,-0.00655,-0.00983,0.186,-0.006,-0.00403,0.0372,0.00334,-0.00181,-0.228,-1.51e-05,-6e-05,1.21e-06,-5.17e-05,0.000131,-0.00138,0.204,0.00201,0.435,0,0,0,0,0,3.16e-06,0.000109,0.000109,8.52e-05,0.0271,0.0271,0.00836,0.0444,0.0444,0.0352,3.05e-10,3.06e-10,6.68e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19690000,0.982,-0.00656,-0.00985,0.186,-0.00783,-0.00248,0.0342,0.00267,-0.00212,-0.233,-1.51e-05,-6e-05,1.35e-06,-5.23e-05,0.000132,-0.00138,0.204,0.00201,0.435,0,0,0,0,0,3.14e-06,0.00011,0.00011,8.45e-05,0.0297,0.0297,0.0084,0.0501,0.0501,0.0353,3.06e-10,3.06e-10,6.54e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19790000,0.982,-0.00664,-0.00989,0.187,-0.0077,-0.00113,0.0314,0.00528,-0.00173,-0.241,-1.51e-05,-5.98e-05,1.1e-06,-5.03e-05,0.000132,-0.00137,0.204,0.00201,0.435,0,0,0,0,0,3.13e-06,0.000107,0.000107,8.42e-05,0.0264,0.0264,0.00835,0.0443,0.0443,0.0354,2.79e-10,2.79e-10,6.41e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19890000,0.982,-0.00666,-0.00997,0.187,-0.00789,-0.000805,0.0304,0.00445,-0.00178,-0.247,-1.51e-05,-5.98e-05,9.76e-07,-5.11e-05,0.000132,-0.00137,0.204,0.00201,0.435,0,0,0,0,0,3.1e-06,0.000108,0.000108,8.36e-05,0.0289,0.0289,0.00839,0.0498,0.0498,0.0355,2.79e-10,2.79e-10,6.28e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19990000,0.982,-0.00666,-0.0101,0.187,-0.00742,-0.000841,0.0263,0.00502,-0.000326,-0.254,-1.51e-05,-5.96e-05,1e-06,-4.94e-05,0.000134,-0.00136,0.204,0.00201,0.435,0,0,0,0,0,3.08e-06,0.000105,0.000105,8.3e-05,0.0258,0.0258,0.0083,0.0441,0.0441,0.0353,2.55e-10,2.55e-10,6.14e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20090000,0.982,-0.00667,-0.0101,0.186,-0.00702,-0.00301,0.0257,0.00427,-0.000528,-0.254,-1.52e-05,-5.96e-05,9.65e-07,-4.96e-05,0.000134,-0.00136,0.204,0.00201,0.435,0,0,0,0,0,3.07e-06,0.000106,0.000106,8.27e-05,0.0282,0.0282,0.00837,0.0496,0.0496,0.0357,2.55e-10,2.56e-10,6.03e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20190000,0.982,-0.00667,-0.0102,0.187,-0.0058,-0.000548,0.0254,0.00549,-0.000333,-0.259,-1.51e-05,-5.95e-05,7.09e-07,-4.89e-05,0.000134,-0.00136,0.204,0.00201,0.435,0,0,0,0,0,3.04e-06,0.000104,0.000104,8.21e-05,0.0251,0.0251,0.00829,0.044,0.044,0.0355,2.34e-10,2.34e-10,5.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20290000,0.982,-0.00665,-0.0103,0.187,-0.00913,-0.00156,0.0245,0.00477,-0.000375,-0.262,-1.52e-05,-5.95e-05,6.16e-07,-4.94e-05,0.000135,-0.00136,0.204,0.00201,0.435,0,0,0,0,0,3.02e-06,0.000104,0.000104,8.15e-05,0.0275,0.0275,0.00832,0.0494,0.0494,0.0356,2.34e-10,2.34e-10,5.78e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20390000,0.982,-0.00662,-0.0103,0.187,-0.00962,-0.000489,0.0238,0.00585,-0.000214,-0.264,-1.51e-05,-5.94e-05,7.51e-07,-4.82e-05,0.000135,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,3.01e-06,0.000102,0.000102,8.12e-05,0.0245,0.0245,0.00827,0.0438,0.0438,0.0357,2.15e-10,2.15e-10,5.67e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20490000,0.982,-0.00661,-0.0102,0.186,-0.0144,-0.00139,0.0226,0.00464,-0.00028,-0.27,-1.51e-05,-5.94e-05,7.19e-07,-4.88e-05,0.000135,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.99e-06,0.000103,0.000103,8.06e-05,0.0267,0.0267,0.0083,0.0491,0.0491,0.0357,2.15e-10,2.15e-10,5.55e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20590000,0.982,-0.0066,-0.0102,0.186,-0.0132,-0.00243,0.0212,0.00589,-0.000237,-0.275,-1.51e-05,-5.93e-05,9.66e-07,-4.71e-05,0.000135,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.96e-06,0.000101,0.0001,8e-05,0.0239,0.0239,0.00821,0.0436,0.0436,0.0355,1.98e-10,1.98e-10,5.44e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20690000,0.982,-0.00651,-0.0102,0.186,-0.0151,-0.00114,0.0214,0.00449,-0.000362,-0.278,-1.51e-05,-5.93e-05,7.37e-07,-4.76e-05,0.000135,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.95e-06,0.000101,0.000101,7.97e-05,0.0261,0.0261,0.00829,0.0489,0.0489,0.0359,1.98e-10,1.98e-10,5.34e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20790000,0.982,-0.00591,-0.0102,0.186,-0.0174,0.00133,0.00537,0.00381,-0.000264,-0.283,-1.51e-05,-5.92e-05,8.08e-07,-4.67e-05,0.000135,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.93e-06,9.92e-05,9.91e-05,7.91e-05,0.0234,0.0234,0.0082,0.0434,0.0434,0.0356,1.83e-10,1.83e-10,5.23e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20890000,0.982,0.00321,-0.00615,0.186,-0.0238,0.0134,-0.114,0.00169,0.000517,-0.293,-1.51e-05,-5.92e-05,8.04e-07,-4.69e-05,0.000135,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.9e-06,9.98e-05,9.98e-05,7.86e-05,0.0258,0.0258,0.00823,0.0487,0.0487,0.0357,1.83e-10,1.83e-10,5.13e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20990000,0.982,0.00653,-0.00273,0.186,-0.0345,0.0313,-0.254,0.00122,0.00104,-0.311,-1.49e-05,-5.92e-05,7.54e-07,-4.47e-05,0.000132,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.89e-06,9.78e-05,9.77e-05,7.8e-05,0.0234,0.0234,0.00814,0.0433,0.0433,0.0354,1.69e-10,1.69e-10,5.03e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21090000,0.982,0.00494,-0.00311,0.187,-0.0482,0.0474,-0.373,-0.00291,0.00502,-0.345,-1.49e-05,-5.92e-05,7.37e-07,-4.48e-05,0.000132,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.88e-06,9.84e-05,9.83e-05,7.77e-05,0.0258,0.0258,0.00822,0.0485,0.0485,0.0358,1.69e-10,1.69e-10,4.94e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21190000,0.982,0.00206,-0.00479,0.187,-0.0517,0.0513,-0.5,-0.00221,0.00397,-0.384,-1.46e-05,-5.9e-05,7.96e-07,-3.99e-05,0.000122,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.87e-06,9.62e-05,9.62e-05,7.72e-05,0.0234,0.0234,0.00813,0.0432,0.0432,0.0356,1.56e-10,1.56e-10,4.84e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21290000,0.982,-0.000107,-0.00612,0.187,-0.0521,0.055,-0.631,-0.0074,0.00931,-0.446,-1.46e-05,-5.9e-05,4.98e-07,-4e-05,0.000122,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.85e-06,9.68e-05,9.68e-05,7.66e-05,0.0257,0.0257,0.00816,0.0483,0.0483,0.0356,1.56e-10,1.56e-10,4.75e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21390000,0.982,-0.0016,-0.00685,0.187,-0.0473,0.0508,-0.756,-0.00599,0.0115,-0.513,-1.44e-05,-5.88e-05,5.02e-07,-3.43e-05,0.000116,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.85e-06,9.46e-05,9.45e-05,7.64e-05,0.0233,0.0233,0.00812,0.0431,0.0431,0.0357,1.44e-10,1.44e-10,4.66e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21490000,0.982,-0.0024,-0.00726,0.187,-0.0431,0.0483,-0.893,-0.0106,0.0165,-0.602,-1.44e-05,-5.88e-05,6.24e-07,-3.47e-05,0.000116,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.84e-06,9.51e-05,9.5e-05,7.58e-05,0.0256,0.0256,0.00815,0.0482,0.0482,0.0357,1.44e-10,1.44e-10,4.57e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21590000,0.982,-0.0029,-0.00729,0.187,-0.0345,0.0437,-1.02,-0.00898,0.0169,-0.694,-1.42e-05,-5.87e-05,7.35e-07,-3.16e-05,0.000112,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.82e-06,9.28e-05,9.27e-05,7.53e-05,0.0232,0.0232,0.00807,0.043,0.043,0.0355,1.34e-10,1.34e-10,4.49e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21690000,0.982,-0.00324,-0.00714,0.187,-0.0328,0.0397,-1.15,-0.0123,0.0211,-0.811,-1.42e-05,-5.87e-05,9.04e-07,-3.22e-05,0.000113,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.81e-06,9.33e-05,9.32e-05,7.5e-05,0.0254,0.0254,0.00815,0.0481,0.0481,0.0358,1.34e-10,1.34e-10,4.41e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21790000,0.982,-0.00361,-0.00736,0.187,-0.0243,0.0335,-1.28,-0.00487,0.0184,-0.933,-1.41e-05,-5.85e-05,1.12e-06,-2.5e-05,0.000109,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.79e-06,9.09e-05,9.09e-05,7.45e-05,0.023,0.023,0.00807,0.0429,0.0429,0.0356,1.24e-10,1.24e-10,4.33e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21890000,0.982,-0.00391,-0.0075,0.187,-0.0212,0.0294,-1.4,-0.00714,0.0216,-1.08,-1.41e-05,-5.85e-05,9.95e-07,-2.55e-05,0.000109,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.77e-06,9.14e-05,9.13e-05,7.4e-05,0.0251,0.0251,0.0081,0.048,0.048,0.0356,1.24e-10,1.24e-10,4.25e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21990000,0.982,-0.00461,-0.0078,0.187,-0.0173,0.0234,-1.38,-0.00151,0.0171,-1.21,-1.4e-05,-5.85e-05,1.1e-06,-2.64e-05,0.00011,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.76e-06,8.9e-05,8.89e-05,7.37e-05,0.0223,0.0223,0.00807,0.0428,0.0428,0.0357,1.15e-10,1.15e-10,4.18e-10,2.93e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22090000,0.982,-0.00534,-0.0086,0.187,-0.015,0.0197,-1.37,-0.00316,0.0192,-1.36,-1.4e-05,-5.85e-05,1.29e-06,-2.68e-05,0.00011,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.75e-06,8.94e-05,8.94e-05,7.32e-05,0.024,0.024,0.0081,0.0478,0.0478,0.0357,1.15e-10,1.15e-10,4.1e-10,2.93e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22190000,0.982,-0.00579,-0.00887,0.187,-0.00629,0.0139,-1.38,0.00479,0.0134,-1.5,-1.39e-05,-5.84e-05,1.44e-06,-2.65e-05,0.000111,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.73e-06,8.73e-05,8.73e-05,7.28e-05,0.0214,0.0214,0.00802,0.0427,0.0427,0.0355,1.08e-10,1.08e-10,4.02e-10,2.91e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22290000,0.982,-0.0065,-0.00912,0.187,-0.00118,0.00872,-1.38,0.0044,0.0145,-1.65,-1.39e-05,-5.84e-05,1.34e-06,-2.71e-05,0.000112,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.71e-06,8.77e-05,8.76e-05,7.23e-05,0.0231,0.0231,0.00806,0.0476,0.0476,0.0355,1.08e-10,1.08e-10,3.95e-10,2.91e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22390000,0.982,-0.00686,-0.00928,0.187,0.00414,-0.000935,-1.38,0.0118,0.00462,-1.79,-1.38e-05,-5.85e-05,1.14e-06,-3.13e-05,0.000111,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.71e-06,8.58e-05,8.58e-05,7.2e-05,0.0206,0.0206,0.00802,0.0425,0.0425,0.0356,1.01e-10,1.01e-10,3.88e-10,2.9e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22490000,0.982,-0.007,-0.00974,0.187,0.008,-0.00689,-1.39,0.0124,0.00419,-1.93,-1.38e-05,-5.85e-05,9.92e-07,-3.15e-05,0.000111,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.69e-06,8.62e-05,8.61e-05,7.15e-05,0.0222,0.0222,0.00806,0.0474,0.0474,0.0356,1.01e-10,1.01e-10,3.81e-10,2.9e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22590000,0.982,-0.00693,-0.0104,0.187,0.0176,-0.0159,-1.38,0.0245,-0.00484,-2.08,-1.37e-05,-5.84e-05,1.16e-06,-2.88e-05,0.00011,-0.00133,0.204,0.00201,0.435,0,0,0,0,0,2.68e-06,8.45e-05,8.44e-05,7.11e-05,0.0199,0.0199,0.00799,0.0423,0.0423,0.0353,9.46e-11,9.47e-11,3.75e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22690000,0.982,-0.00684,-0.0106,0.188,0.0197,-0.0203,-1.39,0.0264,-0.00669,-2.22,-1.37e-05,-5.84e-05,1.07e-06,-2.94e-05,0.000111,-0.00133,0.204,0.00201,0.435,0,0,0,0,0,2.67e-06,8.48e-05,8.48e-05,7.08e-05,0.0215,0.0215,0.00807,0.0471,0.0471,0.0357,9.47e-11,9.48e-11,3.69e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22790000,0.982,-0.00684,-0.011,0.187,0.026,-0.0282,-1.39,0.0367,-0.0168,-2.37,-1.36e-05,-5.84e-05,9.31e-07,-3.16e-05,0.000112,-0.00133,0.204,0.00201,0.435,0,0,0,0,0,2.65e-06,8.33e-05,8.33e-05,7.04e-05,0.0193,0.0193,0.00799,0.0421,0.0421,0.0354,8.92e-11,8.92e-11,3.62e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22890000,0.982,-0.00699,-0.0113,0.187,0.0295,-0.0338,-1.39,0.0394,-0.0198,-2.52,-1.36e-05,-5.84e-05,1.12e-06,-3.2e-05,0.000112,-0.00132,0.204,0.00201,0.435,0,0,0,0,0,2.62e-06,8.36e-05,8.36e-05,6.99e-05,0.0208,0.0208,0.00803,0.0468,0.0468,0.0355,8.93e-11,8.93e-11,3.56e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22990000,0.982,-0.00695,-0.0117,0.187,0.034,-0.039,-1.4,0.0495,-0.0303,-2.67,-1.36e-05,-5.84e-05,1.29e-06,-3.44e-05,0.000114,-0.00132,0.204,0.00201,0.435,0,0,0,0,0,2.61e-06,8.23e-05,8.22e-05,6.97e-05,0.0187,0.0187,0.008,0.0419,0.0419,0.0355,8.43e-11,8.43e-11,3.5e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23090000,0.982,-0.00697,-0.012,0.186,0.039,-0.0437,-1.4,0.0531,-0.0345,-2.81,-1.36e-05,-5.84e-05,1.29e-06,-3.47e-05,0.000114,-0.00131,0.204,0.00201,0.435,0,0,0,0,0,2.58e-06,8.26e-05,8.25e-05,6.93e-05,0.0201,0.0201,0.00804,0.0465,0.0465,0.0356,8.44e-11,8.44e-11,3.44e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23190000,0.982,-0.00699,-0.0122,0.186,0.0456,-0.0454,-1.4,0.0648,-0.0447,-2.96,-1.36e-05,-5.84e-05,1.18e-06,-3.53e-05,0.000114,-0.00131,0.204,0.00201,0.435,0,0,0,0,0,2.56e-06,8.14e-05,8.13e-05,6.88e-05,0.0182,0.0182,0.00796,0.0417,0.0417,0.0353,7.98e-11,7.99e-11,3.38e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23290000,0.982,-0.00746,-0.0123,0.186,0.0505,-0.0503,-1.39,0.0695,-0.0495,-3.1,-1.36e-05,-5.84e-05,1.24e-06,-3.58e-05,0.000115,-0.00131,0.204,0.00201,0.435,0,0,0,0,0,2.55e-06,8.16e-05,8.16e-05,6.86e-05,0.0195,0.0195,0.00805,0.0462,0.0462,0.0357,7.99e-11,8e-11,3.33e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23390000,0.983,-0.00737,-0.0125,0.186,0.0561,-0.0525,-1.39,0.0807,-0.0547,-3.24,-1.37e-05,-5.84e-05,1.03e-06,-3.45e-05,0.000117,-0.00131,0.204,0.00201,0.435,0,0,0,0,0,2.53e-06,8.06e-05,8.05e-05,6.82e-05,0.0177,0.0177,0.00797,0.0414,0.0414,0.0354,7.59e-11,7.59e-11,3.27e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23490000,0.983,-0.00745,-0.0127,0.186,0.0602,-0.0548,-1.4,0.0865,-0.0601,-3.39,-1.37e-05,-5.84e-05,1.18e-06,-3.48e-05,0.000118,-0.00131,0.204,0.00201,0.435,0,0,0,0,0,2.51e-06,8.08e-05,8.08e-05,6.78e-05,0.019,0.019,0.00801,0.0459,0.0459,0.0354,7.6e-11,7.6e-11,3.22e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23590000,0.983,-0.00773,-0.0127,0.185,0.0633,-0.0578,-1.39,0.0941,-0.07,-3.53,-1.37e-05,-5.85e-05,1.24e-06,-3.67e-05,0.000117,-0.0013,0.204,0.00201,0.435,0,0,0,0,0,2.5e-06,7.99e-05,7.98e-05,6.73e-05,0.0173,0.0173,0.00794,0.0412,0.0412,0.0352,7.22e-11,7.23e-11,3.16e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23690000,0.983,-0.00837,-0.0132,0.185,0.0617,-0.0602,-1.29,0.1,-0.076,-3.67,-1.37e-05,-5.85e-05,1.39e-06,-3.68e-05,0.000118,-0.0013,0.204,0.00201,0.435,0,0,0,0,0,2.49e-06,8.01e-05,8.01e-05,6.71e-05,0.0184,0.0184,0.00802,0.0455,0.0455,0.0355,7.23e-11,7.24e-11,3.12e-10,2.87e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23790000,0.982,-0.0102,-0.0161,0.185,0.0573,-0.0577,-0.96,0.11,-0.0806,-3.79,-1.39e-05,-5.84e-05,1.54e-06,-3.56e-05,0.000118,-0.0013,0.204,0.00201,0.435,0,0,0,0,0,2.49e-06,7.93e-05,7.93e-05,6.67e-05,0.0164,0.0164,0.00795,0.0409,0.0409,0.0353,6.9e-11,6.9e-11,3.06e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23890000,0.982,-0.0136,-0.0202,0.185,0.0539,-0.0585,-0.529,0.116,-0.0864,-3.87,-1.39e-05,-5.84e-05,1.55e-06,-3.58e-05,0.000119,-0.0013,0.204,0.00201,0.435,0,0,0,0,0,2.49e-06,7.96e-05,7.95e-05,6.63e-05,0.0172,0.0172,0.00799,0.0451,0.0451,0.0353,6.91e-11,6.91e-11,3.01e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23990000,0.982,-0.0157,-0.0225,0.185,0.0565,-0.0579,-0.145,0.124,-0.0889,-3.93,-1.4e-05,-5.84e-05,1.54e-06,-3.54e-05,0.000119,-0.00127,0.204,0.00201,0.435,0,0,0,0,0,2.49e-06,7.91e-05,7.91e-05,6.61e-05,0.0155,0.0155,0.00796,0.0406,0.0406,0.0354,6.61e-11,6.61e-11,2.97e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24090000,0.982,-0.0152,-0.0214,0.185,0.0636,-0.0663,0.0875,0.13,-0.0951,-3.93,-1.4e-05,-5.84e-05,1.44e-06,-3.54e-05,0.000119,-0.00127,0.204,0.00201,0.435,0,0,0,0,0,2.46e-06,7.94e-05,7.93e-05,6.57e-05,0.0166,0.0166,0.008,0.0446,0.0446,0.0354,6.62e-11,6.62e-11,2.92e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24190000,0.983,-0.0123,-0.0177,0.185,0.0745,-0.0716,0.0746,0.138,-0.0993,-3.94,-1.41e-05,-5.84e-05,1.52e-06,-3.23e-05,0.000115,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.43e-06,7.91e-05,7.91e-05,6.53e-05,0.0153,0.0153,0.00794,0.0402,0.0402,0.0352,6.35e-11,6.35e-11,2.87e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24290000,0.983,-0.00994,-0.0143,0.185,0.0783,-0.075,0.0531,0.146,-0.107,-3.94,-1.41e-05,-5.84e-05,1.53e-06,-3.25e-05,0.000116,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.41e-06,7.93e-05,7.93e-05,6.51e-05,0.0164,0.0164,0.00802,0.0442,0.0442,0.0355,6.36e-11,6.36e-11,2.83e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24390000,0.983,-0.00909,-0.0133,0.185,0.0718,-0.0694,0.0696,0.152,-0.107,-3.93,-1.42e-05,-5.84e-05,1.72e-06,-3.2e-05,0.000107,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.39e-06,7.92e-05,7.91e-05,6.47e-05,0.0151,0.0151,0.00795,0.0399,0.0399,0.0353,6.11e-11,6.12e-11,2.79e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24490000,0.983,-0.00933,-0.0134,0.185,0.0672,-0.0664,0.0675,0.159,-0.114,-3.93,-1.42e-05,-5.84e-05,1.97e-06,-3.18e-05,0.000107,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.38e-06,7.94e-05,7.93e-05,6.43e-05,0.0163,0.0163,0.00799,0.0439,0.0439,0.0353,6.12e-11,6.13e-11,2.74e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24590000,0.983,-0.01,-0.0135,0.185,0.0638,-0.0622,0.0634,0.163,-0.111,-3.92,-1.44e-05,-5.84e-05,1.95e-06,-3.4e-05,9.94e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.38e-06,7.93e-05,7.92e-05,6.41e-05,0.015,0.015,0.00797,0.0396,0.0396,0.0354,5.89e-11,5.89e-11,2.7e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24690000,0.983,-0.0105,-0.0133,0.185,0.0616,-0.0616,0.0629,0.169,-0.117,-3.91,-1.44e-05,-5.84e-05,1.95e-06,-3.4e-05,9.94e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.37e-06,7.95e-05,7.94e-05,6.38e-05,0.0161,0.0161,0.00801,0.0436,0.0436,0.0354,5.9e-11,5.9e-11,2.66e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24790000,0.983,-0.0105,-0.0126,0.185,0.0583,-0.0592,0.0546,0.171,-0.113,-3.91,-1.46e-05,-5.84e-05,1.98e-06,-3.42e-05,9.31e-05,-0.00125,0.204,0.00201,0.435,0,0,0,0,0,2.35e-06,7.94e-05,7.94e-05,6.34e-05,0.0149,0.0149,0.00794,0.0394,0.0394,0.0352,5.69e-11,5.69e-11,2.62e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24890000,0.983,-0.0104,-0.0121,0.185,0.0567,-0.0625,0.0441,0.177,-0.119,-3.91,-1.46e-05,-5.84e-05,2.06e-06,-3.44e-05,9.34e-05,-0.00125,0.204,0.00201,0.435,0,0,0,0,0,2.34e-06,7.96e-05,7.96e-05,6.3e-05,0.016,0.016,0.00799,0.0434,0.0434,0.0352,5.7e-11,5.7e-11,2.58e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24990000,0.983,-0.0101,-0.0119,0.185,0.0477,-0.058,0.037,0.177,-0.111,-3.91,-1.49e-05,-5.83e-05,2.05e-06,-3.63e-05,8.56e-05,-0.00125,0.204,0.00201,0.435,0,0,0,0,0,2.33e-06,7.96e-05,7.96e-05,6.28e-05,0.0148,0.0148,0.00796,0.0393,0.0393,0.0353,5.5e-11,5.5e-11,2.54e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25090000,0.983,-0.0105,-0.012,0.185,0.0442,-0.0572,0.0344,0.182,-0.116,-3.91,-1.49e-05,-5.83e-05,2.01e-06,-3.63e-05,8.6e-05,-0.00125,0.204,0.00201,0.435,0,0,0,0,0,2.32e-06,7.98e-05,7.98e-05,6.25e-05,0.0159,0.0159,0.00801,0.0432,0.0432,0.0353,5.51e-11,5.51e-11,2.5e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25190000,0.983,-0.0107,-0.0118,0.185,0.0393,-0.0505,0.0344,0.182,-0.108,-3.91,-1.51e-05,-5.83e-05,1.9e-06,-3.88e-05,8.06e-05,-0.00125,0.204,0.00201,0.435,0,0,0,0,0,2.31e-06,7.98e-05,7.98e-05,6.21e-05,0.0147,0.0147,0.00794,0.0391,0.0391,0.0351,5.32e-11,5.32e-11,2.47e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25290000,0.983,-0.0108,-0.0111,0.185,0.0344,-0.0517,0.0292,0.185,-0.113,-3.91,-1.51e-05,-5.83e-05,1.73e-06,-3.86e-05,8.05e-05,-0.00125,0.204,0.00201,0.435,0,0,0,0,0,2.3e-06,8e-05,8e-05,6.19e-05,0.0158,0.0158,0.00803,0.043,0.043,0.0355,5.33e-11,5.33e-11,2.43e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25390000,0.983,-0.0108,-0.0109,0.185,0.0261,-0.0445,0.0278,0.181,-0.102,-3.91,-1.53e-05,-5.83e-05,1.73e-06,-3.99e-05,7.28e-05,-0.00124,0.204,0.00201,0.435,0,0,0,0,0,2.29e-06,8e-05,8e-05,6.16e-05,0.0146,0.0146,0.00796,0.039,0.039,0.0352,5.15e-11,5.15e-11,2.4e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25490000,0.983,-0.0109,-0.0106,0.185,0.0209,-0.0442,0.0271,0.184,-0.107,-3.91,-1.53e-05,-5.83e-05,1.64e-06,-3.98e-05,7.29e-05,-0.00124,0.204,0.00201,0.435,0,0,0,0,0,2.28e-06,8.02e-05,8.02e-05,6.12e-05,0.0156,0.0156,0.008,0.0428,0.0428,0.0353,5.16e-11,5.16e-11,2.36e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25590000,0.983,-0.011,-0.0104,0.186,0.0157,-0.0401,0.0282,0.18,-0.0982,-3.91,-1.55e-05,-5.82e-05,1.54e-06,-4.08e-05,6.93e-05,-0.00124,0.204,0.00201,0.435,0,0,0,0,0,2.27e-06,8.02e-05,8.02e-05,6.1e-05,0.0145,0.0145,0.00798,0.0389,0.0389,0.0353,4.99e-11,4.99e-11,2.33e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25690000,0.983,-0.0105,-0.0101,0.186,0.0147,-0.0391,0.0174,0.181,-0.102,-3.91,-1.55e-05,-5.82e-05,1.54e-06,-4.07e-05,6.94e-05,-0.00124,0.204,0.00201,0.435,0,0,0,0,0,2.26e-06,8.04e-05,8.04e-05,6.07e-05,0.0155,0.0155,0.00802,0.0427,0.0427,0.0354,5e-11,5e-11,2.3e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25790000,0.983,-0.0102,-0.00938,0.186,0.00362,-0.0308,0.0169,0.174,-0.0925,-3.91,-1.57e-05,-5.82e-05,1.48e-06,-4.12e-05,6.44e-05,-0.00124,0.204,0.00201,0.435,0,0,0,0,0,2.24e-06,8.04e-05,8.04e-05,6.04e-05,0.0144,0.0144,0.00796,0.0388,0.0388,0.0351,4.84e-11,4.84e-11,2.26e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25890000,0.983,-0.0103,-0.00947,0.186,-0.00211,-0.0285,0.0193,0.174,-0.0954,-3.91,-1.57e-05,-5.82e-05,1.27e-06,-4.1e-05,6.43e-05,-0.00124,0.204,0.00201,0.435,0,0,0,0,0,2.24e-06,8.06e-05,8.06e-05,6.02e-05,0.0154,0.0154,0.00804,0.0426,0.0426,0.0355,4.85e-11,4.85e-11,2.23e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25990000,0.983,-0.0103,-0.00958,0.186,-0.0112,-0.0218,0.0127,0.163,-0.0859,-3.91,-1.58e-05,-5.83e-05,1.19e-06,-3.91e-05,5.96e-05,-0.00124,0.204,0.00201,0.435,0,0,0,0,0,2.23e-06,8.06e-05,8.06e-05,5.99e-05,0.0143,0.0143,0.00798,0.0387,0.0387,0.0353,4.7e-11,4.7e-11,2.2e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26090000,0.983,-0.01,-0.00957,0.186,-0.0164,-0.0215,0.0113,0.162,-0.0881,-3.91,-1.58e-05,-5.83e-05,1.27e-06,-3.91e-05,5.96e-05,-0.00124,0.204,0.00201,0.435,0,0,0,0,0,2.21e-06,8.08e-05,8.08e-05,5.95e-05,0.0153,0.0153,0.00802,0.0425,0.0425,0.0353,4.71e-11,4.71e-11,2.17e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26190000,0.983,-0.00992,-0.0101,0.186,-0.023,-0.0149,0.00648,0.151,-0.081,-3.92,-1.59e-05,-5.83e-05,1.32e-06,-3.86e-05,5.74e-05,-0.00123,0.204,0.00201,0.435,0,0,0,0,0,2.2e-06,8.08e-05,8.08e-05,5.92e-05,0.0142,0.0142,0.00796,0.0386,0.0386,0.0351,4.57e-11,4.57e-11,2.14e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26290000,0.983,-0.00993,-0.0104,0.186,-0.0245,-0.0135,0.000745,0.149,-0.0825,-3.92,-1.59e-05,-5.83e-05,1.18e-06,-3.84e-05,5.73e-05,-0.00123,0.204,0.00201,0.435,0,0,0,0,0,2.2e-06,8.1e-05,8.1e-05,5.9e-05,0.0152,0.0152,0.00804,0.0424,0.0424,0.0354,4.58e-11,4.58e-11,2.11e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26390000,0.983,-0.00935,-0.0103,0.186,-0.0306,-0.0064,0.00471,0.136,-0.0744,-3.92,-1.6e-05,-5.84e-05,1.05e-06,-3.62e-05,5.44e-05,-0.00123,0.204,0.00201,0.435,0,0,0,0,0,2.18e-06,8.1e-05,8.1e-05,5.87e-05,0.0141,0.0141,0.00797,0.0385,0.0385,0.0352,4.45e-11,4.45e-11,2.08e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26490000,0.983,-0.0091,-0.0102,0.185,-0.0338,-0.00325,0.0142,0.132,-0.0749,-3.92,-1.6e-05,-5.84e-05,9.8e-07,-3.62e-05,5.44e-05,-0.00123,0.204,0.00201,0.435,0,0,0,0,0,2.17e-06,8.12e-05,8.12e-05,5.84e-05,0.0151,0.0151,0.00802,0.0423,0.0423,0.0352,4.46e-11,4.46e-11,2.05e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26590000,0.983,-0.00854,-0.0104,0.186,-0.0354,0.00469,0.0142,0.122,-0.0678,-3.92,-1.61e-05,-5.84e-05,8.56e-07,-3.53e-05,5.22e-05,-0.00123,0.204,0.00201,0.435,0,0,0,0,0,2.16e-06,8.12e-05,8.11e-05,5.83e-05,0.014,0.014,0.00799,0.0384,0.0384,0.0353,4.33e-11,4.33e-11,2.03e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26690000,0.983,-0.0084,-0.0101,0.186,-0.0374,0.00978,0.0127,0.118,-0.0671,-3.92,-1.61e-05,-5.84e-05,6.53e-07,-3.52e-05,5.2e-05,-0.00123,0.204,0.00201,0.435,0,0,0,0,0,2.15e-06,8.14e-05,8.13e-05,5.79e-05,0.015,0.015,0.00804,0.0422,0.0422,0.0354,4.34e-11,4.34e-11,2e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26790000,0.983,-0.00819,-0.00958,0.186,-0.0447,0.0133,0.0118,0.106,-0.0618,-3.92,-1.61e-05,-5.84e-05,5.51e-07,-3.32e-05,5.04e-05,-0.00123,0.204,0.00201,0.435,0,0,0,0,0,2.13e-06,8.14e-05,8.13e-05,5.76e-05,0.0139,0.0139,0.00797,0.0383,0.0383,0.0351,4.22e-11,4.22e-11,1.97e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26890000,0.983,-0.00754,-0.00973,0.186,-0.0505,0.0166,0.00704,0.101,-0.0603,-3.92,-1.61e-05,-5.84e-05,5.91e-07,-3.32e-05,5.03e-05,-0.00123,0.204,0.00201,0.435,0,0,0,0,0,2.13e-06,8.16e-05,8.15e-05,5.75e-05,0.0149,0.0149,0.00806,0.0421,0.0421,0.0355,4.23e-11,4.23e-11,1.95e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26990000,0.983,-0.00701,-0.0102,0.186,-0.0575,0.0231,0.00608,0.0884,-0.0542,-3.93,-1.61e-05,-5.85e-05,5.03e-07,-3.15e-05,4.81e-05,-0.00122,0.204,0.00201,0.435,0,0,0,0,0,2.12e-06,8.15e-05,8.15e-05,5.72e-05,0.0138,0.0138,0.00799,0.0383,0.0383,0.0352,4.12e-11,4.12e-11,1.92e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27090000,0.983,-0.00686,-0.0105,0.186,-0.0596,0.0302,0.00875,0.0825,-0.0515,-3.93,-1.61e-05,-5.85e-05,4.4e-07,-3.12e-05,4.75e-05,-0.00122,0.204,0.00201,0.435,0,0,0,0,0,2.11e-06,8.17e-05,8.16e-05,5.69e-05,0.0148,0.0148,0.00803,0.042,0.042,0.0353,4.13e-11,4.13e-11,1.89e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27190000,0.983,-0.00689,-0.0104,0.186,-0.0659,0.0356,0.0106,0.0716,-0.0455,-3.94,-1.6e-05,-5.85e-05,3.69e-07,-3.03e-05,4.61e-05,-0.00122,0.204,0.00201,0.435,0,0,0,0,0,2.1e-06,8.16e-05,8.16e-05,5.67e-05,0.0137,0.0137,0.00801,0.0382,0.0382,0.0354,4.03e-11,4.02e-11,1.87e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27290000,0.983,-0.00707,-0.0114,0.186,-0.0723,0.0415,0.124,0.0648,-0.0416,-3.94,-1.6e-05,-5.85e-05,3.24e-07,-3.02e-05,4.58e-05,-0.00122,0.204,0.00201,0.435,0,0,0,0,0,2.09e-06,8.18e-05,8.18e-05,5.64e-05,0.0146,0.0146,0.00805,0.0419,0.0419,0.0354,4.04e-11,4.03e-11,1.85e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27390000,0.982,-0.00845,-0.0139,0.186,-0.0769,0.0472,0.447,0.0553,-0.0345,-3.92,-1.6e-05,-5.84e-05,2.75e-07,-3.01e-05,4.35e-05,-0.00121,0.204,0.00201,0.435,0,0,0,0,0,2.09e-06,8.18e-05,8.17e-05,5.61e-05,0.0133,0.0133,0.00798,0.0381,0.0381,0.0352,3.94e-11,3.93e-11,1.82e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27490000,0.982,-0.0098,-0.0157,0.186,-0.0795,0.0526,0.759,0.0475,-0.0295,-3.86,-1.6e-05,-5.84e-05,9.68e-08,-3.05e-05,4.34e-05,-0.00121,0.204,0.00201,0.435,0,0,0,0,0,2.08e-06,8.2e-05,8.19e-05,5.59e-05,0.0141,0.0141,0.00803,0.0417,0.0417,0.0352,3.95e-11,3.94e-11,1.8e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27590000,0.982,-0.00968,-0.0145,0.186,-0.0733,0.055,0.853,0.0392,-0.0254,-3.79,-1.59e-05,-5.84e-05,6.22e-08,-3.15e-05,4.37e-05,-0.0012,0.204,0.00201,0.435,0,0,0,0,0,2.07e-06,8.2e-05,8.2e-05,5.57e-05,0.0131,0.0131,0.008,0.038,0.038,0.0353,3.86e-11,3.86e-11,1.78e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27690000,0.983,-0.00845,-0.0116,0.186,-0.0703,0.0517,0.755,0.032,-0.02,-3.72,-1.59e-05,-5.84e-05,4.82e-08,-3.1e-05,4.28e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.05e-06,8.22e-05,8.22e-05,5.54e-05,0.0141,0.0141,0.00804,0.0416,0.0416,0.0354,3.87e-11,3.87e-11,1.75e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27790000,0.983,-0.00712,-0.0102,0.186,-0.0696,0.0494,0.749,0.0258,-0.0176,-3.65,-1.59e-05,-5.84e-05,4.45e-08,-3.34e-05,4.91e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.04e-06,8.23e-05,8.22e-05,5.52e-05,0.0131,0.0131,0.00797,0.0379,0.0379,0.0351,3.78e-11,3.78e-11,1.73e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27890000,0.983,-0.00676,-0.0102,0.186,-0.0766,0.0564,0.788,0.0185,-0.0124,-3.57,-1.59e-05,-5.84e-05,6.54e-09,-3.33e-05,4.86e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.04e-06,8.25e-05,8.24e-05,5.5e-05,0.014,0.014,0.00806,0.0415,0.0415,0.0355,3.79e-11,3.79e-11,1.71e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27990000,0.983,-0.0072,-0.0106,0.186,-0.0769,0.0578,0.775,0.0132,-0.0106,-3.5,-1.57e-05,-5.83e-05,-3.61e-08,-3.55e-05,5.26e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.03e-06,8.25e-05,8.25e-05,5.47e-05,0.013,0.013,0.00799,0.0378,0.0378,0.0352,3.71e-11,3.71e-11,1.69e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28090000,0.983,-0.00747,-0.0106,0.186,-0.0805,0.0585,0.782,0.00533,-0.0048,-3.43,-1.57e-05,-5.83e-05,5.74e-08,-3.54e-05,5.25e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.02e-06,8.27e-05,8.27e-05,5.45e-05,0.0139,0.0139,0.00803,0.0413,0.0413,0.0353,3.72e-11,3.72e-11,1.67e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28190000,0.983,-0.00691,-0.0109,0.186,-0.0811,0.0551,0.788,-0.00133,-0.00437,-3.35,-1.56e-05,-5.83e-05,1.31e-08,-3.65e-05,5.66e-05,-0.00118,0.204,0.00201,0.435,0,0,0,0,0,2.01e-06,8.28e-05,8.27e-05,5.43e-05,0.0129,0.0129,0.008,0.0377,0.0377,0.0354,3.64e-11,3.64e-11,1.65e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28290000,0.983,-0.0064,-0.0111,0.186,-0.0864,0.0586,0.787,-0.00968,0.00136,-3.28,-1.56e-05,-5.83e-05,8.91e-08,-3.6e-05,5.56e-05,-0.00118,0.204,0.00201,0.435,0,0,0,0,0,2e-06,8.3e-05,8.29e-05,5.41e-05,0.0138,0.0138,0.00805,0.0412,0.0412,0.0354,3.65e-11,3.65e-11,1.63e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28390000,0.983,-0.00641,-0.0118,0.186,-0.087,0.0613,0.787,-0.0144,0.00433,-3.21,-1.55e-05,-5.82e-05,1.33e-07,-3.78e-05,5.72e-05,-0.00118,0.204,0.00201,0.435,0,0,0,0,0,2e-06,8.3e-05,8.29e-05,5.38e-05,0.0129,0.0129,0.00798,0.0376,0.0376,0.0352,3.58e-11,3.58e-11,1.61e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28490000,0.983,-0.00671,-0.0122,0.186,-0.0887,0.0655,0.788,-0.0231,0.0106,-3.13,-1.55e-05,-5.82e-05,9.27e-08,-3.75e-05,5.63e-05,-0.00117,0.204,0.00201,0.435,0,0,0,0,0,1.99e-06,8.32e-05,8.31e-05,5.37e-05,0.0138,0.0138,0.00806,0.0412,0.0411,0.0355,3.59e-11,3.59e-11,1.59e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28590000,0.983,-0.00675,-0.0122,0.185,-0.0821,0.0605,0.786,-0.0265,0.00834,-3.06,-1.54e-05,-5.82e-05,1.31e-07,-3.85e-05,5.98e-05,-0.00117,0.204,0.00201,0.435,0,0,0,0,0,1.98e-06,8.32e-05,8.31e-05,5.34e-05,0.0128,0.0128,0.00799,0.0375,0.0375,0.0353,3.52e-11,3.52e-11,1.57e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28690000,0.983,-0.00652,-0.0116,0.186,-0.0824,0.0615,0.786,-0.0347,0.0145,-2.99,-1.54e-05,-5.82e-05,6.74e-08,-3.82e-05,5.89e-05,-0.00117,0.204,0.00201,0.435,0,0,0,0,0,1.98e-06,8.34e-05,8.33e-05,5.31e-05,0.0138,0.0138,0.00803,0.0411,0.0411,0.0353,3.53e-11,3.53e-11,1.55e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28790000,0.983,-0.00585,-0.0114,0.186,-0.079,0.0615,0.784,-0.0372,0.0162,-2.91,-1.53e-05,-5.81e-05,1.37e-07,-3.88e-05,5.88e-05,-0.00117,0.204,0.00201,0.435,0,0,0,0,0,1.97e-06,8.34e-05,8.33e-05,5.29e-05,0.0128,0.0128,0.00797,0.0375,0.0375,0.0351,3.46e-11,3.46e-11,1.53e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28890000,0.983,-0.00569,-0.0111,0.185,-0.0833,0.0636,0.783,-0.0453,0.0225,-2.84,-1.53e-05,-5.81e-05,2.01e-07,-3.84e-05,5.78e-05,-0.00116,0.204,0.00201,0.435,0,0,0,0,0,1.96e-06,8.36e-05,8.35e-05,5.28e-05,0.0137,0.0137,0.00805,0.041,0.041,0.0355,3.47e-11,3.47e-11,1.51e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28990000,0.983,-0.00546,-0.0113,0.186,-0.0792,0.0603,0.781,-0.0448,0.0216,-2.77,-1.51e-05,-5.8e-05,1.69e-07,-3.89e-05,5.76e-05,-0.00116,0.204,0.00201,0.435,0,0,0,0,0,1.95e-06,8.35e-05,8.35e-05,5.25e-05,0.0128,0.0128,0.00798,0.0374,0.0374,0.0352,3.4e-11,3.4e-11,1.5e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29090000,0.983,-0.00531,-0.0114,0.186,-0.082,0.0626,0.78,-0.0529,0.0277,-2.7,-1.51e-05,-5.8e-05,1.61e-07,-3.87e-05,5.7e-05,-0.00116,0.204,0.00201,0.435,0,0,0,0,0,1.95e-06,8.37e-05,8.37e-05,5.23e-05,0.0137,0.0137,0.00802,0.0409,0.0409,0.0353,3.41e-11,3.41e-11,1.48e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29190000,0.983,-0.00526,-0.0116,0.186,-0.0783,0.0611,0.775,-0.0507,0.027,-2.63,-1.5e-05,-5.79e-05,2.24e-07,-3.86e-05,5.57e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.94e-06,8.37e-05,8.36e-05,5.21e-05,0.0128,0.0128,0.00799,0.0374,0.0374,0.0354,3.35e-11,3.35e-11,1.46e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29290000,0.983,-0.00553,-0.0116,0.186,-0.0804,0.0672,0.778,-0.0586,0.0334,-2.55,-1.5e-05,-5.79e-05,2.4e-07,-3.84e-05,5.53e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.93e-06,8.39e-05,8.38e-05,5.19e-05,0.0137,0.0137,0.00803,0.0409,0.0409,0.0354,3.36e-11,3.36e-11,1.44e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29390000,0.983,-0.00598,-0.0111,0.186,-0.0758,0.0655,0.78,-0.0569,0.0342,-2.48,-1.49e-05,-5.79e-05,2.8e-07,-3.83e-05,5.42e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.93e-06,8.38e-05,8.38e-05,5.16e-05,0.0127,0.0127,0.00796,0.0373,0.0373,0.0352,3.3e-11,3.3e-11,1.43e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29490000,0.983,-0.00597,-0.0109,0.186,-0.0787,0.0663,0.78,-0.0646,0.0409,-2.4,-1.49e-05,-5.79e-05,3.89e-07,-3.8e-05,5.36e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.92e-06,8.4e-05,8.4e-05,5.15e-05,0.0136,0.0136,0.00805,0.0408,0.0408,0.0355,3.31e-11,3.31e-11,1.41e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29590000,0.983,-0.00588,-0.0109,0.186,-0.0742,0.0641,0.782,-0.062,0.0399,-2.33,-1.47e-05,-5.78e-05,4.92e-07,-3.75e-05,5.19e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.91e-06,8.39e-05,8.38e-05,5.13e-05,0.0127,0.0127,0.00798,0.0373,0.0373,0.0353,3.25e-11,3.25e-11,1.4e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29690000,0.983,-0.00593,-0.0107,0.185,-0.0785,0.063,0.777,-0.0696,0.0463,-2.25,-1.47e-05,-5.78e-05,5.85e-07,-3.69e-05,5.07e-05,-0.00114,0.204,0.00201,0.435,0,0,0,0,0,1.91e-06,8.41e-05,8.4e-05,5.1e-05,0.0136,0.0136,0.00802,0.0407,0.0407,0.0353,3.26e-11,3.26e-11,1.38e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29790000,0.983,-0.00576,-0.0113,0.185,-0.0743,0.0562,0.774,-0.0649,0.0435,-2.18,-1.46e-05,-5.77e-05,6.79e-07,-3.57e-05,4.84e-05,-0.00114,0.204,0.00201,0.435,0,0,0,0,0,1.9e-06,8.39e-05,8.39e-05,5.09e-05,0.0127,0.0127,0.00799,0.0372,0.0372,0.0354,3.2e-11,3.2e-11,1.37e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29890000,0.983,-0.00524,-0.0116,0.185,-0.075,0.0575,0.769,-0.0723,0.0491,-2.11,-1.46e-05,-5.77e-05,7.65e-07,-3.5e-05,4.69e-05,-0.00114,0.204,0.00201,0.435,0,0,0,0,0,1.9e-06,8.41e-05,8.41e-05,5.07e-05,0.0136,0.0136,0.00803,0.0407,0.0407,0.0354,3.21e-11,3.21e-11,1.35e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29990000,0.983,-0.00541,-0.0117,0.185,-0.0696,0.0524,0.766,-0.0678,0.0444,-2.04,-1.44e-05,-5.76e-05,7.75e-07,-3.36e-05,4.3e-05,-0.00113,0.204,0.00201,0.435,0,0,0,0,0,1.89e-06,8.4e-05,8.39e-05,5.05e-05,0.0127,0.0127,0.00796,0.0372,0.0372,0.0352,3.16e-11,3.16e-11,1.33e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30090000,0.983,-0.00552,-0.0118,0.186,-0.0701,0.0533,0.763,-0.0748,0.0497,-1.97,-1.44e-05,-5.76e-05,6.25e-07,-3.35e-05,4.25e-05,-0.00113,0.204,0.00201,0.435,0,0,0,0,0,1.88e-06,8.41e-05,8.41e-05,5.02e-05,0.0136,0.0136,0.008,0.0406,0.0406,0.0353,3.17e-11,3.17e-11,1.32e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30190000,0.983,-0.00551,-0.0118,0.186,-0.0641,0.05,0.763,-0.0682,0.0477,-1.9,-1.43e-05,-5.75e-05,5.05e-07,-3.17e-05,4.04e-05,-0.00113,0.204,0.00201,0.435,0,0,0,0,0,1.88e-06,8.39e-05,8.39e-05,5.01e-05,0.0127,0.0127,0.00797,0.0371,0.0371,0.0353,3.12e-11,3.12e-11,1.31e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30290000,0.983,-0.00552,-0.0118,0.186,-0.0632,0.0503,0.762,-0.0745,0.0528,-1.83,-1.43e-05,-5.75e-05,5.25e-07,-3.11e-05,3.89e-05,-0.00113,0.204,0.00201,0.435,0,0,0,0,0,1.87e-06,8.41e-05,8.41e-05,4.99e-05,0.0135,0.0135,0.00802,0.0406,0.0406,0.0354,3.13e-11,3.13e-11,1.29e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30390000,0.982,-0.00553,-0.0117,0.186,-0.056,0.0446,0.759,-0.0664,0.0495,-1.77,-1.42e-05,-5.74e-05,6.61e-07,-2.75e-05,3.44e-05,-0.00112,0.204,0.00201,0.435,0,0,0,0,0,1.87e-06,8.39e-05,8.39e-05,4.97e-05,0.0126,0.0126,0.00795,0.0371,0.0371,0.0351,3.07e-11,3.07e-11,1.28e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30490000,0.983,-0.00553,-0.0118,0.186,-0.0588,0.0447,0.76,-0.0721,0.054,-1.69,-1.42e-05,-5.74e-05,7.44e-07,-2.71e-05,3.37e-05,-0.00112,0.204,0.00201,0.435,0,0,0,0,0,1.86e-06,8.41e-05,8.41e-05,4.96e-05,0.0135,0.0135,0.00803,0.0406,0.0406,0.0355,3.08e-11,3.08e-11,1.27e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30590000,0.983,-0.00586,-0.0121,0.186,-0.0544,0.0416,0.76,-0.065,0.0498,-1.62,-1.41e-05,-5.73e-05,8.52e-07,-2.42e-05,2.96e-05,-0.00112,0.204,0.00201,0.435,0,0,0,0,0,1.86e-06,8.38e-05,8.38e-05,4.93e-05,0.0126,0.0126,0.00796,0.0371,0.0371,0.0352,3.03e-11,3.04e-11,1.25e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30690000,0.983,-0.00624,-0.0124,0.186,-0.0524,0.0405,0.758,-0.0704,0.0539,-1.55,-1.41e-05,-5.73e-05,8.6e-07,-2.37e-05,2.86e-05,-0.00111,0.204,0.00201,0.435,0,0,0,0,0,1.85e-06,8.4e-05,8.4e-05,4.91e-05,0.0135,0.0135,0.008,0.0405,0.0405,0.0353,3.04e-11,3.05e-11,1.24e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30790000,0.983,-0.00593,-0.012,0.185,-0.0454,0.035,0.757,-0.0631,0.0524,-1.48,-1.4e-05,-5.72e-05,8.66e-07,-2.07e-05,2.7e-05,-0.00111,0.204,0.00201,0.435,0,0,0,0,0,1.84e-06,8.37e-05,8.37e-05,4.9e-05,0.0126,0.0126,0.00797,0.0371,0.0371,0.0354,3e-11,3e-11,1.23e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30890000,0.983,-0.00529,-0.0119,0.186,-0.0458,0.0321,0.753,-0.0676,0.0558,-1.42,-1.4e-05,-5.72e-05,7.85e-07,-2.04e-05,2.63e-05,-0.00111,0.204,0.00201,0.435,0,0,0,0,0,1.83e-06,8.39e-05,8.39e-05,4.88e-05,0.0135,0.0135,0.00802,0.0405,0.0405,0.0354,3.01e-11,3.01e-11,1.21e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30990000,0.983,-0.00548,-0.0119,0.186,-0.0381,0.0265,0.754,-0.0576,0.0486,-1.35,-1.39e-05,-5.72e-05,7.77e-07,-1.71e-05,2.13e-05,-0.0011,0.204,0.00201,0.435,0,0,0,0,0,1.83e-06,8.36e-05,8.36e-05,4.86e-05,0.0126,0.0126,0.00795,0.037,0.037,0.0352,2.96e-11,2.96e-11,1.2e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31090000,0.982,-0.00562,-0.012,0.186,-0.0371,0.0256,0.753,-0.0613,0.0512,-1.28,-1.39e-05,-5.72e-05,7.25e-07,-1.7e-05,2.11e-05,-0.0011,0.204,0.00201,0.435,0,0,0,0,0,1.83e-06,8.38e-05,8.38e-05,4.85e-05,0.0134,0.0134,0.00803,0.0405,0.0405,0.0355,2.97e-11,2.97e-11,1.19e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31190000,0.983,-0.00581,-0.0121,0.186,-0.0324,0.0209,0.755,-0.0528,0.046,-1.21,-1.38e-05,-5.71e-05,8.7e-07,-1.38e-05,1.75e-05,-0.0011,0.204,0.00201,0.435,0,0,0,0,0,1.82e-06,8.35e-05,8.35e-05,4.83e-05,0.0125,0.0125,0.00796,0.037,0.037,0.0353,2.93e-11,2.93e-11,1.18e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31290000,0.983,-0.00604,-0.0122,0.186,-0.0301,0.0183,0.759,-0.0558,0.048,-1.14,-1.38e-05,-5.71e-05,9.47e-07,-1.33e-05,1.67e-05,-0.0011,0.204,0.00201,0.435,0,0,0,0,0,1.81e-06,8.37e-05,8.37e-05,4.81e-05,0.0134,0.0134,0.008,0.0404,0.0404,0.0353,2.94e-11,2.94e-11,1.16e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31390000,0.983,-0.00582,-0.012,0.186,-0.0241,0.0121,0.757,-0.047,0.0423,-1.06,-1.37e-05,-5.7e-05,8.64e-07,-1.13e-05,1.41e-05,-0.00109,0.204,0.00201,0.435,0,0,0,0,0,1.8e-06,8.33e-05,8.33e-05,4.79e-05,0.0125,0.0125,0.00793,0.037,0.037,0.0351,2.89e-11,2.89e-11,1.15e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31490000,0.982,-0.00555,-0.0123,0.186,-0.0241,0.00935,0.754,-0.0494,0.0433,-0.993,-1.37e-05,-5.7e-05,8.45e-07,-1.1e-05,1.39e-05,-0.00109,0.204,0.00201,0.435,0,0,0,0,0,1.8e-06,8.35e-05,8.35e-05,4.78e-05,0.0134,0.0134,0.00802,0.0404,0.0404,0.0354,2.9e-11,2.9e-11,1.14e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31590000,0.983,-0.00542,-0.0128,0.186,-0.02,0.00712,0.758,-0.0384,0.0389,-0.922,-1.36e-05,-5.7e-05,9.33e-07,-6.86e-06,1.15e-05,-0.00109,0.204,0.00201,0.435,0,0,0,0,0,1.79e-06,8.32e-05,8.31e-05,4.76e-05,0.0125,0.0125,0.00795,0.0369,0.037,0.0352,2.86e-11,2.86e-11,1.13e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31690000,0.983,-0.00541,-0.0133,0.185,-0.0222,0.00606,0.754,-0.0406,0.0395,-0.854,-1.36e-05,-5.7e-05,1.05e-06,-6.22e-06,1.08e-05,-0.00109,0.204,0.00201,0.435,0,0,0,0,0,1.79e-06,8.33e-05,8.33e-05,4.74e-05,0.0133,0.0133,0.00799,0.0404,0.0404,0.0353,2.87e-11,2.87e-11,1.12e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31790000,0.983,-0.00563,-0.0139,0.185,-0.013,0.00349,0.754,-0.029,0.0376,-0.783,-1.36e-05,-5.69e-05,1.12e-06,-9.72e-07,1.07e-05,-0.00108,0.204,0.00201,0.435,0,0,0,0,0,1.79e-06,8.3e-05,8.29e-05,4.73e-05,0.0125,0.0125,0.00796,0.0369,0.0369,0.0353,2.83e-11,2.83e-11,1.11e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31890000,0.983,-0.00536,-0.0136,0.185,-0.00985,0.00122,0.752,-0.0301,0.0378,-0.716,-1.36e-05,-5.69e-05,1.17e-06,-3.52e-07,1.01e-05,-0.00108,0.204,0.00201,0.435,0,0,0,0,0,1.78e-06,8.31e-05,8.31e-05,4.71e-05,0.0133,0.0133,0.00801,0.0403,0.0403,0.0354,2.84e-11,2.84e-11,1.1e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31990000,0.983,-0.00563,-0.0132,0.185,-0.00189,0.000554,0.748,-0.0181,0.0347,-0.651,-1.36e-05,-5.68e-05,1.13e-06,4.26e-06,9.25e-06,-0.00107,0.204,0.00201,0.435,0,0,0,0,0,1.77e-06,8.27e-05,8.27e-05,4.69e-05,0.0124,0.0124,0.00794,0.0369,0.0369,0.0351,2.8e-11,2.8e-11,1.08e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32090000,0.983,-0.00599,-0.0129,0.185,-0.00251,-0.00283,0.75,-0.0183,0.0346,-0.581,-1.36e-05,-5.68e-05,1.14e-06,4.61e-06,9.04e-06,-0.00107,0.204,0.00201,0.435,0,0,0,0,0,1.77e-06,8.29e-05,8.29e-05,4.68e-05,0.0133,0.0133,0.00802,0.0403,0.0403,0.0355,2.81e-11,2.81e-11,1.08e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32190000,0.983,-0.00617,-0.0132,0.185,0.00289,-0.00605,0.75,-0.00708,0.0332,-0.515,-1.36e-05,-5.67e-05,1.1e-06,8.82e-06,1.06e-05,-0.00107,0.204,0.00201,0.435,0,0,0,0,0,1.76e-06,8.25e-05,8.25e-05,4.66e-05,0.0124,0.0124,0.00795,0.0369,0.0369,0.0352,2.77e-11,2.77e-11,1.06e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32290000,0.983,-0.00608,-0.0134,0.185,0.00441,-0.00873,0.748,-0.00675,0.0324,-0.448,-1.36e-05,-5.67e-05,1.17e-06,9.41e-06,1.03e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.75e-06,8.27e-05,8.27e-05,4.64e-05,0.0132,0.0132,0.00799,0.0403,0.0403,0.0353,2.78e-11,2.78e-11,1.05e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32390000,0.983,-0.0062,-0.0135,0.186,0.0107,-0.01,0.747,0.0046,0.0299,-0.374,-1.35e-05,-5.67e-05,1.13e-06,1.25e-05,1.13e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.75e-06,8.23e-05,8.23e-05,4.63e-05,0.0124,0.0124,0.00797,0.0369,0.0369,0.0354,2.74e-11,2.74e-11,1.04e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32490000,0.983,-0.00905,-0.0114,0.185,0.035,-0.0726,-0.126,0.00745,0.0237,-0.372,-1.36e-05,-5.67e-05,1.09e-06,1.25e-05,1.13e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.74e-06,8.24e-05,8.24e-05,4.61e-05,0.0153,0.0153,0.00784,0.0403,0.0403,0.0354,2.75e-11,2.75e-11,1.03e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32590000,0.983,-0.00899,-0.0114,0.185,0.0354,-0.0737,-0.129,0.0196,0.0201,-0.392,-1.36e-05,-5.66e-05,1.18e-06,1.25e-05,1.13e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.73e-06,8.12e-05,8.12e-05,4.59e-05,0.0157,0.0157,0.00755,0.0369,0.0369,0.0351,2.71e-11,2.71e-11,1.02e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32690000,0.983,-0.00897,-0.0113,0.185,0.0311,-0.0793,-0.13,0.0229,0.0124,-0.408,-1.36e-05,-5.66e-05,1.16e-06,1.25e-05,1.13e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.73e-06,8.14e-05,8.14e-05,4.57e-05,0.0187,0.0187,0.00736,0.0406,0.0406,0.0351,2.72e-11,2.72e-11,1.01e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32790000,0.983,-0.00866,-0.0113,0.185,0.0297,-0.0768,-0.131,0.0327,0.0105,-0.425,-1.37e-05,-5.65e-05,1.24e-06,1.25e-05,1.13e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.72e-06,7.87e-05,7.87e-05,4.57e-05,0.0196,0.0196,0.00713,0.0372,0.0372,0.0351,2.68e-11,2.68e-11,1.01e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32890000,0.983,-0.00862,-0.0114,0.185,0.0293,-0.0827,-0.133,0.0357,0.00253,-0.441,-1.37e-05,-5.65e-05,1.28e-06,1.25e-05,1.13e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.72e-06,7.88e-05,7.88e-05,4.55e-05,0.0236,0.0236,0.00697,0.041,0.041,0.035,2.69e-11,2.69e-11,9.97e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32990000,0.983,-0.00835,-0.0113,0.185,0.0268,-0.0787,-0.132,0.0436,-0.00068,-0.455,-1.38e-05,-5.65e-05,1.36e-06,1.25e-05,1.13e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.71e-06,7.44e-05,7.44e-05,4.53e-05,0.0243,0.0243,0.00673,0.0376,0.0376,0.0347,2.65e-11,2.65e-11,9.87e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33090000,0.983,-0.00831,-0.0113,0.185,0.0227,-0.0825,-0.129,0.0461,-0.00872,-0.463,-1.38e-05,-5.65e-05,1.34e-06,1.25e-05,1.13e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.71e-06,7.45e-05,7.45e-05,4.52e-05,0.029,0.029,0.00661,0.0418,0.0418,0.0349,2.66e-11,2.66e-11,9.79e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33190000,0.983,-0.008,-0.0113,0.185,0.019,-0.0781,-0.127,0.0523,-0.0106,-0.47,-1.38e-05,-5.65e-05,1.29e-06,1.23e-05,7.5e-06,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.7e-06,6.85e-05,6.85e-05,4.5e-05,0.0295,0.0296,0.00641,0.0382,0.0382,0.0346,2.62e-11,2.62e-11,9.7e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33290000,0.983,-0.00805,-0.0113,0.185,0.0157,-0.0794,-0.126,0.054,-0.0185,-0.479,-1.38e-05,-5.65e-05,1.39e-06,1.23e-05,7.51e-06,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.69e-06,6.86e-05,6.86e-05,4.49e-05,0.0357,0.0357,0.00629,0.0428,0.0428,0.0344,2.63e-11,2.63e-11,9.61e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33390000,0.983,-0.00759,-0.0114,0.185,0.0113,-0.0653,-0.124,0.0573,-0.0135,-0.49,-1.39e-05,-5.64e-05,1.41e-06,6.51e-06,-1.58e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.69e-06,6.16e-05,6.16e-05,4.48e-05,0.0356,0.0356,0.00616,0.0391,0.0391,0.0343,2.6e-11,2.6e-11,9.53e-11,2.79e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33490000,0.983,-0.00757,-0.0113,0.185,0.00683,-0.0661,-0.125,0.0582,-0.0201,-0.505,-1.39e-05,-5.64e-05,1.41e-06,6.53e-06,-1.58e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.68e-06,6.17e-05,6.17e-05,4.46e-05,0.0428,0.0428,0.00608,0.0442,0.0442,0.0342,2.61e-11,2.61e-11,9.44e-11,2.79e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33590000,0.983,-0.0072,-0.0114,0.185,0.00353,-0.0568,-0.122,0.0609,-0.0163,-0.517,-1.4e-05,-5.64e-05,1.47e-06,-1.54e-06,-4.04e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.67e-06,5.43e-05,5.43e-05,4.44e-05,0.0412,0.0412,0.00596,0.0401,0.0402,0.0338,2.59e-11,2.59e-11,9.36e-11,2.74e-06,2.74e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33690000,0.983,-0.0072,-0.0113,0.185,-0.00109,-0.0572,-0.124,0.0611,-0.022,-0.529,-1.4e-05,-5.64e-05,1.48e-06,-1.53e-06,-4.04e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.67e-06,5.44e-05,5.44e-05,4.43e-05,0.049,0.049,0.00595,0.0458,0.0458,0.0339,2.6e-11,2.6e-11,9.28e-11,2.74e-06,2.74e-06,5.01e-08,0,0,0,0,0,0,0,0
|
||||
33790000,0.983,-0.00696,-0.0114,0.185,-0.00367,-0.0465,-0.119,0.0651,-0.0174,-0.54,-1.4e-05,-5.63e-05,1.42e-06,-1.48e-05,-6.62e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.66e-06,4.76e-05,4.76e-05,4.42e-05,0.0454,0.0454,0.00586,0.0413,0.0413,0.0335,2.58e-11,2.58e-11,9.2e-11,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33890000,0.983,-0.00697,-0.0114,0.185,-0.00777,-0.0442,-0.12,0.0645,-0.022,-0.552,-1.4e-05,-5.63e-05,1.48e-06,-1.47e-05,-6.62e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.66e-06,4.77e-05,4.77e-05,4.4e-05,0.0532,0.0532,0.00584,0.0475,0.0475,0.0334,2.59e-11,2.59e-11,9.12e-11,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33990000,0.983,-0.00668,-0.0116,0.185,-0.00686,-0.0299,-0.118,0.068,-0.0145,-0.562,-1.4e-05,-5.63e-05,1.41e-06,-3.94e-05,-9.61e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.65e-06,4.19e-05,4.19e-05,4.38e-05,0.0478,0.0478,0.00578,0.0425,0.0425,0.033,2.58e-11,2.58e-11,9.03e-11,2.57e-06,2.57e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34090000,0.983,-0.00663,-0.0116,0.185,-0.0111,-0.0299,-0.118,0.0672,-0.0175,-0.574,-1.4e-05,-5.63e-05,1.38e-06,-3.94e-05,-9.61e-05,-0.00106,0.204,0.00201,0.435,0,0,0,0,0,1.65e-06,4.2e-05,4.2e-05,4.38e-05,0.0552,0.0552,0.00582,0.049,0.049,0.0331,2.59e-11,2.59e-11,8.96e-11,2.57e-06,2.57e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34190000,0.983,-0.00655,-0.0117,0.185,-0.0113,-0.0194,-0.117,0.0709,-0.0121,-0.585,-1.41e-05,-5.63e-05,1.4e-06,-5.72e-05,-0.000116,-0.00107,0.204,0.00201,0.435,0,0,0,0,0,1.64e-06,3.74e-05,3.73e-05,4.36e-05,0.0484,0.0485,0.00579,0.0435,0.0435,0.0328,2.59e-11,2.59e-11,8.89e-11,2.47e-06,2.46e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34290000,0.983,-0.00641,-0.0117,0.185,-0.0117,-0.0186,-0.117,0.0698,-0.0141,-0.597,-1.41e-05,-5.63e-05,1.41e-06,-5.71e-05,-0.000116,-0.00107,0.204,0.00201,0.435,0,0,0,0,0,1.64e-06,3.74e-05,3.74e-05,4.34e-05,0.0554,0.0554,0.00583,0.0504,0.0504,0.0326,2.6e-11,2.6e-11,8.81e-11,2.47e-06,2.46e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34390000,0.983,-0.00632,-0.0117,0.185,-0.0126,-0.00919,-0.112,0.0715,-0.00943,-0.606,-1.41e-05,-5.63e-05,1.4e-06,-7.25e-05,-0.000129,-0.00107,0.204,0.00201,0.435,0,0,0,0,0,1.63e-06,3.39e-05,3.39e-05,4.34e-05,0.0478,0.0478,0.00585,0.0444,0.0444,0.0325,2.6e-11,2.6e-11,8.74e-11,2.36e-06,2.35e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34490000,0.983,-0.00639,-0.0116,0.185,-0.0153,-0.00816,-0.112,0.0702,-0.0103,-0.617,-1.41e-05,-5.63e-05,1.43e-06,-7.25e-05,-0.000129,-0.00107,0.204,0.00201,0.435,0,0,0,0,0,1.63e-06,3.4e-05,3.4e-05,4.32e-05,0.0541,0.0541,0.00591,0.0514,0.0514,0.0324,2.61e-11,2.61e-11,8.67e-11,2.36e-06,2.35e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34590000,0.983,-0.00634,-0.0115,0.185,-0.0115,-0.00451,0.682,0.0722,-0.0082,-0.595,-1.41e-05,-5.63e-05,1.4e-06,-8.54e-05,-0.00013,-0.00107,0.204,0.00201,0.435,0,0,0,0,0,1.62e-06,3.15e-05,3.15e-05,4.3e-05,0.0445,0.0445,0.00592,0.0451,0.0451,0.0321,2.62e-11,2.62e-11,8.59e-11,2.25e-06,2.25e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34690000,0.983,-0.00633,-0.0112,0.185,-0.0115,-0.0029,1.67,0.071,-0.00857,-0.477,-1.41e-05,-5.63e-05,1.38e-06,-8.54e-05,-0.00013,-0.00107,0.204,0.00201,0.435,0,0,0,0,0,1.62e-06,3.16e-05,3.16e-05,4.3e-05,0.048,0.048,0.00602,0.0518,0.0518,0.0322,2.63e-11,2.63e-11,8.53e-11,2.25e-06,2.25e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34790000,0.983,-0.00631,-0.011,0.185,-0.0108,0.00113,2.64,0.0721,-0.00635,-0.299,-1.41e-05,-5.63e-05,1.36e-06,-7.1e-05,-0.000146,-0.00104,0.204,0.00201,0.435,0,0,0,0,0,1.61e-06,3.02e-05,3.02e-05,4.28e-05,0.0404,0.0404,0.00604,0.0454,0.0454,0.0319,2.63e-11,2.63e-11,8.45e-11,2.13e-06,2.12e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34890000,0.983,-0.00629,-0.0107,0.185,-0.0112,0.00303,3.63,0.071,-0.006,-0.00811,-1.41e-05,-5.63e-05,1.34e-06,-6.73e-05,-0.000148,-0.00104,0.204,0.00201,0.435,0,0,0,0,0,1.61e-06,3.02e-05,3.02e-05,4.27e-05,0.0441,0.0441,0.00614,0.0519,0.0519,0.0318,2.64e-11,2.64e-11,8.38e-11,2.13e-06,2.12e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
190000,0.984,-0.00902,-0.0136,0.179,-0.000577,-7.92e-05,-0.00742,-2.95e-05,-2.04e-05,-0.0351,-2.69e-14,7.98e-14,2.03e-15,2.99e-11,-2.9e-11,1.29e-09,0.203,-7.92e-09,0.434,0,0,0,0,0,0.000109,0.00248,0.00248,0.00328,25,25,0.563,100,100,0.8,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
290000,0.984,-0.0091,-0.0139,0.179,0.000776,-0.000508,-0.0239,-7.04e-05,-1.91e-05,-0.0538,5.72e-12,-9.06e-13,-1.79e-13,1.07e-09,-1.03e-09,4.57e-08,0.203,-7.92e-09,0.434,0,0,0,0,0,7.2e-05,0.00254,0.00254,0.00215,25,25,0.562,101,101,0.337,1e-06,1e-06,9.97e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
390000,0.984,-0.00912,-0.0142,0.179,0.00382,-0.00041,-0.0425,0.000108,2.06e-06,-0.0658,-2.92e-11,-1.07e-10,-1.38e-12,8.73e-09,-8.37e-09,3.69e-07,0.203,-7.92e-09,0.434,0,0,0,0,0,5.51e-05,0.00264,0.00264,0.00164,24.8,24.8,0.557,0.29,0.29,0.209,1e-06,1e-06,9.88e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
490000,0.984,-0.00915,-0.0145,0.179,0.00656,-0.00254,-0.0639,0.000621,-0.000144,-0.0812,-2.87e-10,-5.71e-10,-3.03e-12,2.75e-08,-2.63e-08,1.15e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,4.62e-05,0.0028,0.0028,0.00136,24.9,24.9,0.544,0.739,0.739,0.159,1e-06,1e-06,9.73e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
590000,0.984,-0.00916,-0.0147,0.179,0.0044,-0.00306,-0.0851,0.00029,-0.000151,-0.0938,-6.02e-09,-7.54e-09,5.62e-11,6.35e-08,-5.84e-08,2.02e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,4.11e-05,0.00299,0.00299,0.00121,7.8,7.8,0.527,0.267,0.267,0.141,1e-06,1e-06,9.49e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
690000,0.984,-0.00921,-0.0151,0.179,0.00864,-0.00471,-0.0976,0.000969,-0.000536,-0.103,-6.06e-09,-7.58e-09,5.67e-11,6.46e-08,-5.94e-08,2.07e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.84e-05,0.00325,0.00325,0.00112,7.87,7.87,0.497,0.556,0.556,0.13,1e-06,1e-06,9.16e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
790000,0.984,-0.00921,-0.0153,0.179,0.00931,-0.00237,-0.11,0.000547,-0.000235,-0.114,-3.56e-08,-3.47e-08,4.61e-10,1.03e-07,-1.01e-07,2.23e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.7e-05,0.00354,0.00354,0.00107,2.63,2.63,0.46,0.218,0.218,0.125,9.99e-07,9.99e-07,8.75e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
890000,0.984,-0.00925,-0.0156,0.179,0.0125,-0.002,-0.128,0.00159,-0.000454,-0.13,-3.77e-08,-3.7e-08,4.85e-10,1.4e-07,-1.35e-07,3.74e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.65e-05,0.00389,0.00389,0.00105,2.72,2.72,0.423,0.363,0.363,0.128,9.99e-07,9.99e-07,8.27e-07,4e-06,4e-06,3.99e-06,0,0,0,0,0,0,0,0
|
||||
990000,0.984,-0.0092,-0.016,0.179,0.0132,-0.000163,-0.143,0.00106,-0.000205,-0.144,-1.29e-07,-1.78e-07,1.21e-09,2.67e-07,-2.2e-07,4.15e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.64e-05,0.00424,0.00424,0.00105,1.25,1.25,0.379,0.178,0.178,0.127,9.97e-07,9.97e-07,7.73e-07,4e-06,4e-06,3.98e-06,0,0,0,0,0,0,0,0
|
||||
1090000,0.984,-0.00933,-0.0161,0.179,0.023,-0.00265,-0.157,0.00284,-0.00028,-0.16,-1.3e-07,-1.8e-07,1.22e-09,2.81e-07,-2.33e-07,4.72e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.66e-05,0.00469,0.00469,0.00105,1.38,1.38,0.335,0.265,0.265,0.125,9.97e-07,9.97e-07,7.15e-07,4e-06,4e-06,3.97e-06,0,0,0,0,0,0,0,0
|
||||
1190000,0.984,-0.00925,-0.0163,0.179,0.0249,-0.00379,-0.171,0.00217,-0.000254,-0.176,-4.35e-07,-7.71e-07,3.63e-09,6.53e-07,-4.25e-07,4.71e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.69e-05,0.00504,0.00504,0.00105,0.847,0.847,0.299,0.151,0.151,0.128,9.88e-07,9.88e-07,6.56e-07,3.99e-06,3.99e-06,3.95e-06,0,0,0,0,0,0,0,0
|
||||
1290000,0.984,-0.00914,-0.0166,0.179,0.0346,-0.00414,-0.186,0.00521,-0.000703,-0.194,-4.35e-07,-7.71e-07,3.63e-09,6.53e-07,-4.25e-07,4.71e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.72e-05,0.00558,0.00558,0.00105,1.02,1.02,0.262,0.214,0.214,0.125,9.88e-07,9.88e-07,5.97e-07,3.99e-06,3.99e-06,3.94e-06,0,0,0,0,0,0,0,0
|
||||
1390000,0.984,-0.00913,-0.0168,0.179,0.0452,-0.00555,-0.2,0.00926,-0.00119,-0.214,-4.35e-07,-7.71e-07,3.63e-09,6.53e-07,-4.25e-07,4.71e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.74e-05,0.00616,0.00616,0.00105,1.25,1.25,0.23,0.3,0.3,0.122,9.88e-07,9.88e-07,5.41e-07,3.99e-06,3.99e-06,3.92e-06,0,0,0,0,0,0,0,0
|
||||
1490000,0.984,-0.009,-0.0167,0.179,0.0432,-0.00563,-0.214,0.00797,-0.000965,-0.234,-1.42e-06,-2.63e-06,1.58e-08,1.6e-06,-9.28e-07,4.67e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.74e-05,0.00636,0.00635,0.00104,1.01,1.01,0.202,0.188,0.188,0.118,9.62e-07,9.62e-07,4.87e-07,3.99e-06,3.99e-06,3.89e-06,0,0,0,0,0,0,0,0
|
||||
1590000,0.984,-0.0091,-0.0171,0.179,0.053,-0.00644,-0.228,0.0128,-0.00163,-0.256,-1.42e-06,-2.63e-06,1.58e-08,1.6e-06,-9.28e-07,4.67e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.75e-05,0.00701,0.00701,0.00103,1.3,1.3,0.182,0.268,0.268,0.118,9.62e-07,9.62e-07,4.38e-07,3.99e-06,3.99e-06,3.87e-06,0,0,0,0,0,0,0,0
|
||||
1690000,0.984,-0.00899,-0.0168,0.179,0.0492,-0.00498,-0.244,0.0101,-0.00116,-0.28,-3.52e-06,-6.61e-06,4.83e-08,3.3e-06,-1.82e-06,4.59e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.7e-05,0.00676,0.00676,0.00102,1.1,1.1,0.163,0.179,0.179,0.114,9.06e-07,9.06e-07,3.92e-07,3.98e-06,3.98e-06,3.83e-06,0,0,0,0,0,0,0,0
|
||||
1790000,0.984,-0.00911,-0.0171,0.179,0.0602,-0.00635,-0.257,0.0156,-0.00175,-0.305,-3.52e-06,-6.61e-06,4.83e-08,3.3e-06,-1.82e-06,4.59e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.69e-05,0.00743,0.00743,0.001,1.44,1.45,0.147,0.262,0.262,0.11,9.06e-07,9.06e-07,3.51e-07,3.98e-06,3.98e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
1890000,0.984,-0.00877,-0.0164,0.179,0.05,-0.00261,-0.269,0.0113,-0.00108,-0.331,-6.75e-06,-1.3e-05,1.06e-07,5.58e-06,-2.98e-06,4.46e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.59e-05,0.00658,0.00658,0.000985,1.18,1.18,0.137,0.178,0.178,0.109,8.16e-07,8.16e-07,3.15e-07,3.97e-06,3.97e-06,3.76e-06,0,0,0,0,0,0,0,0
|
||||
1990000,0.984,-0.00885,-0.0167,0.179,0.0584,-0.00254,-0.282,0.0168,-0.00139,-0.359,-6.75e-06,-1.3e-05,1.06e-07,5.58e-06,-2.98e-06,4.46e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.57e-05,0.00722,0.00722,0.000965,1.54,1.54,0.126,0.266,0.266,0.105,8.16e-07,8.16e-07,2.82e-07,3.97e-06,3.97e-06,3.72e-06,0,0,0,0,0,0,0,0
|
||||
2090000,0.984,-0.00862,-0.0158,0.179,0.0447,-0.000786,-0.296,0.0111,-0.000714,-0.388,-1.04e-05,-2.08e-05,1.74e-07,7.87e-06,-4.05e-06,4.31e-06,0.203,-7.92e-09,0.434,0,0,0,0,0,3.43e-05,0.00588,0.00588,0.000944,1.18,1.18,0.118,0.177,0.177,0.102,7.03e-07,7.04e-07,2.52e-07,3.96e-06,3.96e-06,3.67e-06,0,0,0,0,0,0,0,0
|
||||
2190000,0.984,-0.00855,-0.0162,0.179,0.0524,-0.00112,-0.293,0.0161,-0.000763,-0.4,-1.03e-05,-2.05e-05,1.71e-07,7.17e-06,-3.42e-06,-2.46e-05,0.203,-7.92e-09,0.434,0,0,0,0,0,3.39e-05,0.00645,0.00645,0.000922,1.51,1.51,0.113,0.267,0.267,0.101,7.03e-07,7.04e-07,2.27e-07,3.96e-06,3.96e-06,3.62e-06,0,0,0,0,0,0,0,0
|
||||
2290000,0.984,-0.00836,-0.0154,0.179,0.0371,0.000754,-0.275,0.0102,-0.000306,-0.394,-1.33e-05,-2.77e-05,2.28e-07,7.54e-06,-2.9e-06,-8.4e-05,0.203,-7.92e-09,0.434,0,0,0,0,0,3.24e-05,0.00497,0.00497,0.000899,1.09,1.09,0.107,0.173,0.173,0.0977,5.91e-07,5.91e-07,2.04e-07,3.95e-06,3.95e-06,3.56e-06,0,0,0,0,0,0,0,0
|
||||
2390000,0.984,-0.00838,-0.0156,0.179,0.0447,-3.55e-05,-0.263,0.0146,-0.000303,-0.391,-1.31e-05,-2.73e-05,2.25e-07,6.19e-06,-1.67e-06,-0.000142,0.203,-7.92e-09,0.434,0,0,0,0,0,3.19e-05,0.00545,0.00545,0.000877,1.38,1.39,0.103,0.259,0.259,0.0949,5.91e-07,5.91e-07,1.84e-07,3.95e-06,3.95e-06,3.49e-06,0,0,0,0,0,0,0,0
|
||||
2490000,0.984,-0.00809,-0.0148,0.179,0.0286,0.00184,-0.259,0.00873,-7.4e-05,-0.4,-1.57e-05,-3.37e-05,2.71e-07,6.43e-06,-1.33e-06,-0.000178,0.203,-7.92e-09,0.434,0,0,0,0,0,3.04e-05,0.00411,0.00411,0.000854,0.963,0.963,0.101,0.166,0.166,0.0946,4.93e-07,4.93e-07,1.66e-07,3.95e-06,3.95e-06,3.43e-06,0,0,0,0,0,0,0,0
|
||||
2590000,0.984,-0.0082,-0.0149,0.179,0.0324,0.000339,-0.247,0.012,3.27e-05,-0.397,-1.55e-05,-3.33e-05,2.69e-07,5.09e-06,-9.29e-08,-0.000238,0.203,-7.92e-09,0.434,0,0,0,0,0,2.98e-05,0.00452,0.00452,0.000832,1.21,1.21,0.0981,0.245,0.245,0.0923,4.93e-07,4.93e-07,1.5e-07,3.95e-06,3.95e-06,3.35e-06,0,0,0,0,0,0,0,0
|
||||
2690000,0.984,-0.00811,-0.0144,0.179,0.0209,0.00183,-0.235,0.00708,8.79e-05,-0.394,-1.73e-05,-3.82e-05,2.99e-07,4.12e-06,1.04e-06,-0.000299,0.203,-7.92e-09,0.434,0,0,0,0,0,2.85e-05,0.00342,0.00342,0.00081,0.836,0.836,0.096,0.157,0.157,0.0903,4.13e-07,4.13e-07,1.36e-07,3.95e-06,3.95e-06,3.26e-06,0,0,0,0,0,0,0,0
|
||||
2790000,0.984,-0.00802,-0.0145,0.179,0.0258,0.00212,-0.226,0.00968,0.000295,-0.393,-1.72e-05,-3.79e-05,2.98e-07,2.86e-06,2.21e-06,-0.000356,0.203,-7.92e-09,0.434,0,0,0,0,0,2.8e-05,0.00376,0.00376,0.000789,1.05,1.05,0.0943,0.228,0.228,0.0885,4.13e-07,4.13e-07,1.23e-07,3.95e-06,3.95e-06,3.17e-06,0,0,0,0,0,0,0,0
|
||||
2890000,0.984,-0.00797,-0.0141,0.179,0.0182,0.000862,-0.222,0.00577,0.000197,-0.399,-1.85e-05,-4.16e-05,3.19e-07,1.91e-06,3.08e-06,-0.000398,0.203,-7.92e-09,0.434,0,0,0,0,0,2.68e-05,0.0029,0.0029,0.000769,0.727,0.727,0.0942,0.148,0.148,0.0889,3.48e-07,3.48e-07,1.12e-07,3.95e-06,3.95e-06,3.08e-06,0,0,0,0,0,0,0,0
|
||||
2990000,0.984,-0.00794,-0.0142,0.179,0.0209,0.000245,-0.207,0.00798,0.000268,-0.392,-1.84e-05,-4.14e-05,3.18e-07,3.05e-07,4.57e-06,-0.000471,0.203,-7.92e-09,0.434,0,0,0,0,0,2.63e-05,0.0032,0.0032,0.000749,0.904,0.905,0.0929,0.211,0.211,0.0875,3.48e-07,3.48e-07,1.02e-07,3.95e-06,3.95e-06,2.98e-06,0,0,0,0,0,0,0,0
|
||||
3090000,0.984,-0.00787,-0.0139,0.179,0.017,-0.0014,-0.203,0.0049,7.14e-05,-0.395,-1.94e-05,-4.43e-05,3.35e-07,-9.74e-07,5.59e-06,-0.000516,0.203,-7.92e-09,0.434,0,0,0,0,0,2.53e-05,0.00252,0.00252,0.000729,0.638,0.638,0.0919,0.139,0.139,0.0862,2.94e-07,2.95e-07,9.36e-08,3.95e-06,3.95e-06,2.87e-06,0,0,0,0,0,0,0,0
|
||||
3190000,0.984,-0.00787,-0.0141,0.179,0.02,-0.00256,-0.195,0.00684,-0.000178,-0.398,-1.94e-05,-4.42e-05,3.34e-07,-2.02e-06,6.55e-06,-0.000563,0.203,-7.92e-09,0.434,0,0,0,0,0,2.48e-05,0.00277,0.00277,0.000711,0.791,0.791,0.092,0.196,0.196,0.087,2.94e-07,2.95e-07,8.58e-08,3.95e-06,3.95e-06,2.78e-06,0,0,0,0,0,0,0,0
|
||||
3290000,0.984,-0.00774,-0.0137,0.179,0.0144,-0.00194,-0.183,0.00435,-0.000233,-0.394,-2.04e-05,-4.65e-05,3.53e-07,-3.87e-06,8.04e-06,-0.000628,0.203,-7.92e-09,0.434,0,0,0,0,0,2.39e-05,0.00222,0.00222,0.000693,0.567,0.567,0.0909,0.131,0.131,0.086,2.5e-07,2.5e-07,7.87e-08,3.94e-06,3.94e-06,2.66e-06,0,0,0,0,0,0,0,0
|
||||
3390000,0.984,-0.00758,-0.0138,0.179,0.0157,-0.000629,-0.174,0.00588,-0.00038,-0.391,-2.04e-05,-4.64e-05,3.53e-07,-5.16e-06,9.2e-06,-0.000686,0.203,-7.92e-09,0.434,0,0,0,0,0,2.35e-05,0.00245,0.00245,0.000676,0.702,0.702,0.0898,0.183,0.183,0.0851,2.5e-07,2.5e-07,7.24e-08,3.94e-06,3.94e-06,2.54e-06,0,0,0,0,0,0,0,0
|
||||
3490000,0.984,-0.00752,-0.0138,0.179,0.0197,0.00195,-0.172,0.00775,-0.000322,-0.398,-2.04e-05,-4.64e-05,3.52e-07,-5.82e-06,9.8e-06,-0.000716,0.203,-7.92e-09,0.434,0,0,0,0,0,2.3e-05,0.00268,0.00268,0.00066,0.86,0.86,0.0898,0.254,0.254,0.0861,2.5e-07,2.5e-07,6.68e-08,3.94e-06,3.94e-06,2.44e-06,0,0,0,0,0,0,0,0
|
||||
3590000,0.984,-0.00735,-0.0134,0.179,0.0158,0.00194,-0.167,0.0053,3.47e-05,-0.399,-2.12e-05,-4.83e-05,3.67e-07,-7.39e-06,1.1e-05,-0.000762,0.203,-7.92e-09,0.434,0,0,0,0,0,2.22e-05,0.00218,0.00218,0.000644,0.632,0.632,0.0884,0.171,0.171,0.0853,2.11e-07,2.12e-07,6.17e-08,3.94e-06,3.94e-06,2.31e-06,0,0,0,0,0,0,0,0
|
||||
3690000,0.984,-0.00735,-0.0135,0.179,0.0171,0.00282,-0.156,0.00707,0.00023,-0.396,-2.12e-05,-4.83e-05,3.67e-07,-8.61e-06,1.21e-05,-0.000818,0.203,-7.92e-09,0.434,0,0,0,0,0,2.17e-05,0.00239,0.00239,0.000629,0.773,0.773,0.0868,0.236,0.236,0.0845,2.11e-07,2.12e-07,5.7e-08,3.94e-06,3.94e-06,2.19e-06,0,0,0,0,0,0,0,0
|
||||
3790000,0.984,-0.00724,-0.0133,0.179,0.0115,0.00642,-0.152,0.00463,0.000591,-0.398,-2.17e-05,-5e-05,3.76e-07,-1.01e-05,1.3e-05,-0.000855,0.203,-7.92e-09,0.434,0,0,0,0,0,2.11e-05,0.00196,0.00196,0.000614,0.576,0.576,0.0864,0.161,0.161,0.0856,1.78e-07,1.78e-07,5.28e-08,3.94e-06,3.94e-06,2.09e-06,0,0,0,0,0,0,0,0
|
||||
3890000,0.984,-0.00717,-0.0134,0.179,0.0116,0.00755,-0.145,0.00589,0.00132,-0.399,-2.17e-05,-5e-05,3.76e-07,-1.09e-05,1.38e-05,-0.000894,0.203,-7.92e-09,0.434,0,0,0,0,0,2.07e-05,0.00214,0.00214,0.0006,0.702,0.703,0.0846,0.221,0.221,0.0848,1.78e-07,1.78e-07,4.91e-08,3.94e-06,3.94e-06,1.97e-06,0,0,0,0,0,0,0,0
|
||||
3990000,0.984,-0.00718,-0.0132,0.179,0.00981,0.00697,-0.14,0.00384,0.00122,-0.397,-2.19e-05,-5.15e-05,3.76e-07,-1.26e-05,1.48e-05,-0.000939,0.203,-7.92e-09,0.434,0,0,0,0,0,2.01e-05,0.00176,0.00176,0.000586,0.528,0.528,0.0826,0.153,0.153,0.0841,1.49e-07,1.49e-07,4.56e-08,3.93e-06,3.93e-06,1.85e-06,0,0,0,0,0,0,0,0
|
||||
4090000,0.984,-0.00711,-0.0131,0.179,0.0118,0.00713,-0.129,0.00504,0.00194,-0.393,-2.19e-05,-5.15e-05,3.76e-07,-1.37e-05,1.58e-05,-0.00099,0.203,-7.92e-09,0.434,0,0,0,0,0,1.97e-05,0.00192,0.00192,0.000573,0.643,0.643,0.0806,0.208,0.208,0.0833,1.49e-07,1.49e-07,4.25e-08,3.93e-06,3.93e-06,1.74e-06,0,0,0,0,0,0,0,0
|
||||
4190000,0.984,-0.00725,-0.0129,0.179,0.00879,0.00542,-0.128,0.00335,0.00147,-0.4,-2.19e-05,-5.28e-05,3.72e-07,-1.47e-05,1.61e-05,-0.00101,0.203,-7.92e-09,0.434,0,0,0,0,0,1.91e-05,0.00158,0.00158,0.000561,0.487,0.487,0.0795,0.145,0.145,0.0842,1.24e-07,1.24e-07,3.96e-08,3.92e-06,3.92e-06,1.64e-06,0,0,0,0,0,0,0,0
|
||||
4290000,0.984,-0.00729,-0.013,0.179,0.0115,0.00682,-0.121,0.00444,0.00209,-0.397,-2.19e-05,-5.28e-05,3.72e-07,-1.56e-05,1.69e-05,-0.00105,0.203,-7.92e-09,0.434,0,0,0,0,0,1.88e-05,0.00171,0.00171,0.000549,0.591,0.591,0.0773,0.197,0.197,0.0834,1.24e-07,1.24e-07,3.7e-08,3.92e-06,3.92e-06,1.54e-06,0,0,0,0,0,0,0,0
|
||||
4390000,0.984,-0.00724,-0.0128,0.179,0.0105,0.00439,-0.112,0.00316,0.00145,-0.392,-2.18e-05,-5.39e-05,3.66e-07,-1.73e-05,1.77e-05,-0.00109,0.203,-7.92e-09,0.434,0,0,0,0,0,1.83e-05,0.00141,0.00141,0.000537,0.449,0.449,0.0749,0.138,0.138,0.0825,1.02e-07,1.02e-07,3.46e-08,3.92e-06,3.92e-06,1.43e-06,0,0,0,0,0,0,0,0
|
||||
4490000,0.984,-0.00727,-0.0128,0.179,0.011,0.007,-0.111,0.00428,0.00208,-0.397,-2.18e-05,-5.39e-05,3.66e-07,-1.76e-05,1.8e-05,-0.00111,0.203,-7.92e-09,0.434,0,0,0,0,0,1.79e-05,0.00152,0.00152,0.000526,0.543,0.543,0.0736,0.186,0.186,0.0833,1.02e-07,1.02e-07,3.24e-08,3.92e-06,3.92e-06,1.35e-06,0,0,0,0,0,0,0,0
|
||||
4590000,0.984,-0.00729,-0.0127,0.179,0.00948,0.00463,-0.102,0.00302,0.0015,-0.392,-2.16e-05,-5.5e-05,3.61e-07,-1.92e-05,1.88e-05,-0.00115,0.203,-7.92e-09,0.434,0,0,0,0,0,1.75e-05,0.00125,0.00125,0.000516,0.414,0.414,0.0711,0.132,0.132,0.0824,8.31e-08,8.32e-08,3.04e-08,3.91e-06,3.91e-06,1.26e-06,0,0,0,0,0,0,0,0
|
||||
4690000,0.984,-0.00725,-0.0127,0.179,0.00887,0.00531,-0.0979,0.00402,0.00204,-0.394,-2.16e-05,-5.5e-05,3.61e-07,-1.96e-05,1.92e-05,-0.00117,0.203,-7.92e-09,0.434,0,0,0,0,0,1.72e-05,0.00135,0.00135,0.000505,0.498,0.498,0.0687,0.177,0.177,0.0814,8.31e-08,8.32e-08,2.85e-08,3.91e-06,3.91e-06,1.17e-06,0,0,0,0,0,0,0,0
|
||||
4790000,0.984,-0.00715,-0.0126,0.179,0.00197,0.00444,-0.0963,0.00248,0.00145,-0.398,-2.15e-05,-5.59e-05,3.56e-07,-2.06e-05,1.93e-05,-0.00119,0.203,-7.92e-09,0.434,0,0,0,0,0,1.68e-05,0.0011,0.00111,0.000495,0.381,0.381,0.0672,0.126,0.126,0.082,6.75e-08,6.76e-08,2.68e-08,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
4890000,0.984,-0.00708,-0.0126,0.179,0.00215,0.00269,-0.087,0.0027,0.0018,-0.392,-2.15e-05,-5.58e-05,3.56e-07,-2.14e-05,2e-05,-0.00122,0.203,-7.92e-09,0.434,0,0,0,0,0,1.65e-05,0.00119,0.00119,0.000486,0.456,0.456,0.0647,0.168,0.168,0.0809,6.75e-08,6.76e-08,2.53e-08,3.9e-06,3.9e-06,1.02e-06,0,0,0,0,0,0,0,0
|
||||
4990000,0.984,-0.00707,-0.0125,0.179,0.00245,0.00279,-0.0813,0.00165,0.0012,-0.392,-2.14e-05,-5.64e-05,3.5e-07,-2.22e-05,2.03e-05,-0.00124,0.203,-7.92e-09,0.434,0,0,0,0,0,1.61e-05,0.000974,0.000974,0.000477,0.349,0.349,0.0622,0.121,0.121,0.0798,5.46e-08,5.46e-08,2.38e-08,3.9e-06,3.9e-06,9.49e-07,0,0,0,0,0,0,0,0
|
||||
5090000,0.984,-0.00694,-0.0125,0.179,0.00229,0.0039,-0.0839,0.0019,0.00149,-0.4,-2.14e-05,-5.64e-05,3.5e-07,-2.22e-05,2.03e-05,-0.00124,0.203,-7.92e-09,0.434,0,0,0,0,0,1.58e-05,0.00104,0.00104,0.000468,0.417,0.417,0.0607,0.159,0.159,0.0803,5.46e-08,5.46e-08,2.24e-08,3.9e-06,3.9e-06,8.89e-07,0,0,0,0,0,0,0,0
|
||||
5190000,0.984,-0.00681,-0.0125,0.179,-0.0012,0.0056,-0.0801,0.00111,0.00113,-0.399,-2.12e-05,-5.68e-05,3.45e-07,-2.3e-05,2.06e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.55e-05,0.000857,0.000857,0.000459,0.32,0.32,0.0583,0.115,0.115,0.0791,4.4e-08,4.4e-08,2.12e-08,3.89e-06,3.89e-06,8.26e-07,0,0,0,0,0,0,0,0
|
||||
5290000,0.984,-0.00669,-0.0124,0.179,-0.000527,0.00701,-0.0777,0.00107,0.00175,-0.407,-2.12e-05,-5.68e-05,3.45e-07,-2.3e-05,2.06e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.52e-05,0.000915,0.000915,0.000451,0.38,0.38,0.056,0.152,0.152,0.078,4.4e-08,4.4e-08,2e-08,3.89e-06,3.89e-06,7.67e-07,0,0,0,0,0,0,0,0
|
||||
5390000,0.984,-0.00666,-0.0124,0.179,-0.00346,0.00844,-0.0811,0.000508,0.00142,-0.415,-2.09e-05,-5.7e-05,3.38e-07,-2.32e-05,2.03e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.49e-05,0.000754,0.000754,0.000443,0.292,0.292,0.0538,0.111,0.111,0.0768,3.54e-08,3.54e-08,1.9e-08,3.88e-06,3.88e-06,7.13e-07,0,0,0,0,0,0,0,0
|
||||
5490000,0.984,-0.00665,-0.0125,0.179,-0.00284,0.0116,-0.0811,0.00016,0.00241,-0.423,-2.09e-05,-5.7e-05,3.38e-07,-2.32e-05,2.03e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.47e-05,0.000802,0.000802,0.000435,0.345,0.345,0.0523,0.144,0.144,0.0771,3.54e-08,3.54e-08,1.8e-08,3.88e-06,3.88e-06,6.68e-07,0,0,0,0,0,0,0,0
|
||||
5590000,0.984,-0.00664,-0.0125,0.179,-0.00362,0.0152,-0.0822,-0.000116,0.00378,-0.431,-2.09e-05,-5.7e-05,3.38e-07,-2.32e-05,2.03e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.44e-05,0.000852,0.000852,0.000428,0.405,0.405,0.0502,0.187,0.187,0.0759,3.54e-08,3.54e-08,1.7e-08,3.88e-06,3.88e-06,6.21e-07,0,0,0,0,0,0,0,0
|
||||
5690000,0.984,-0.00669,-0.0124,0.179,-0.00329,0.0157,-0.086,-0.000457,0.00347,-0.439,-2.04e-05,-5.72e-05,3.26e-07,-2.33e-05,1.99e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.41e-05,0.000703,0.000704,0.00042,0.314,0.314,0.0482,0.137,0.137,0.0747,2.85e-08,2.85e-08,1.62e-08,3.88e-06,3.88e-06,5.77e-07,0,0,0,0,0,0,0,0
|
||||
5790000,0.984,-0.00655,-0.0123,0.179,-0.0034,0.0181,-0.0875,-0.000786,0.00515,-0.448,-2.04e-05,-5.72e-05,3.26e-07,-2.33e-05,1.99e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.39e-05,0.000745,0.000745,0.000413,0.367,0.367,0.0468,0.177,0.177,0.0749,2.85e-08,2.85e-08,1.53e-08,3.88e-06,3.88e-06,5.42e-07,0,0,0,0,0,0,0,0
|
||||
5890000,0.984,-0.00658,-0.0124,0.179,-0.000995,0.0166,-0.0869,-0.000608,0.00448,-0.457,-1.98e-05,-5.73e-05,3.11e-07,-2.34e-05,1.94e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.36e-05,0.000619,0.000619,0.000407,0.285,0.285,0.0449,0.131,0.131,0.0737,2.29e-08,2.29e-08,1.46e-08,3.87e-06,3.87e-06,5.04e-07,0,0,0,0,0,0,0,0
|
||||
5990000,0.984,-0.00655,-0.0125,0.179,-0.000548,0.0182,-0.0868,-0.000661,0.00619,-0.465,-1.98e-05,-5.73e-05,3.11e-07,-2.34e-05,1.94e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.34e-05,0.000653,0.000653,0.0004,0.332,0.332,0.0431,0.167,0.167,0.0725,2.29e-08,2.29e-08,1.39e-08,3.87e-06,3.87e-06,4.7e-07,0,0,0,0,0,0,0,0
|
||||
6090000,0.984,-0.00664,-0.0124,0.179,-0.00108,0.0158,-0.0884,-0.000471,0.005,-0.474,-1.91e-05,-5.75e-05,2.94e-07,-2.36e-05,1.87e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.32e-05,0.000546,0.000546,0.000394,0.259,0.259,0.0419,0.124,0.124,0.0726,1.85e-08,1.85e-08,1.32e-08,3.87e-06,3.87e-06,4.41e-07,0,0,0,0,0,0,0,0
|
||||
6190000,0.984,-0.00667,-0.0124,0.179,-0.00222,0.0179,-0.0899,-0.000582,0.0067,-0.483,-1.91e-05,-5.75e-05,2.94e-07,-2.36e-05,1.87e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.3e-05,0.000575,0.000575,0.000388,0.3,0.3,0.0402,0.159,0.159,0.0714,1.85e-08,1.85e-08,1.26e-08,3.87e-06,3.87e-06,4.12e-07,0,0,0,0,0,0,0,0
|
||||
6290000,0.984,-0.00675,-0.0124,0.179,-0.00387,0.0161,-0.0915,-0.00057,0.00529,-0.492,-1.85e-05,-5.77e-05,2.77e-07,-2.38e-05,1.81e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.27e-05,0.000484,0.000484,0.000382,0.235,0.235,0.0385,0.119,0.119,0.0703,1.49e-08,1.5e-08,1.2e-08,3.87e-06,3.87e-06,3.84e-07,0,0,0,0,0,0,0,0
|
||||
6390000,0.984,-0.00668,-0.0123,0.179,-0.00217,0.0176,-0.0933,-0.000896,0.00698,-0.501,-1.85e-05,-5.77e-05,2.77e-07,-2.38e-05,1.81e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.26e-05,0.000508,0.000508,0.000376,0.272,0.272,0.0375,0.15,0.15,0.0704,1.49e-08,1.5e-08,1.15e-08,3.87e-06,3.87e-06,3.62e-07,0,0,0,0,0,0,0,0
|
||||
6490000,0.984,-0.00675,-0.0123,0.179,-0.00438,0.0126,-0.0944,-0.000806,0.0053,-0.511,-1.79e-05,-5.78e-05,2.62e-07,-2.39e-05,1.74e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.23e-05,0.000431,0.000431,0.00037,0.214,0.214,0.036,0.113,0.113,0.0692,1.21e-08,1.21e-08,1.09e-08,3.86e-06,3.86e-06,3.38e-07,0,0,0,0,0,0,0,0
|
||||
6590000,0.984,-0.00671,-0.0123,0.179,-0.00549,0.0149,-0.0978,-0.00126,0.00662,-0.52,-1.79e-05,-5.78e-05,2.62e-07,-2.39e-05,1.74e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.22e-05,0.000451,0.000451,0.000365,0.246,0.246,0.0345,0.143,0.143,0.0681,1.21e-08,1.21e-08,1.05e-08,3.86e-06,3.86e-06,3.16e-07,0,0,0,0,0,0,0,0
|
||||
6690000,0.984,-0.00672,-0.0122,0.179,-0.00779,0.0137,-0.102,-0.00132,0.0051,-0.53,-1.73e-05,-5.79e-05,2.48e-07,-2.4e-05,1.68e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.2e-05,0.000386,0.000386,0.000359,0.195,0.195,0.0332,0.108,0.108,0.067,9.87e-09,9.88e-09,1e-08,3.86e-06,3.86e-06,2.96e-07,0,0,0,0,0,0,0,0
|
||||
6790000,0.984,-0.00674,-0.0122,0.178,-0.00643,0.015,-0.103,-0.00208,0.0065,-0.541,-1.73e-05,-5.79e-05,2.48e-07,-2.4e-05,1.68e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.18e-05,0.000403,0.000403,0.000354,0.223,0.223,0.0323,0.135,0.135,0.067,9.87e-09,9.88e-09,9.57e-09,3.86e-06,3.86e-06,2.8e-07,0,0,0,0,0,0,0,0
|
||||
6890000,0.984,-0.00666,-0.0121,0.178,-0.00624,0.0113,-0.103,-0.00174,0.00492,-0.551,-1.68e-05,-5.79e-05,2.35e-07,-2.41e-05,1.62e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.16e-05,0.000347,0.000347,0.000349,0.178,0.178,0.0311,0.103,0.103,0.0659,8.07e-09,8.08e-09,9.16e-09,3.86e-06,3.86e-06,2.62e-07,0,0,0,0,0,0,0,0
|
||||
6990000,0.984,-0.00661,-0.0121,0.178,-0.00666,0.012,-0.104,-0.00242,0.00608,-0.561,-1.68e-05,-5.79e-05,2.35e-07,-2.41e-05,1.62e-05,-0.00126,0.203,-7.92e-09,0.434,0,0,0,0,0,1.14e-05,0.000362,0.000362,0.000344,0.203,0.203,0.0299,0.129,0.129,0.0648,8.07e-09,8.08e-09,8.78e-09,3.86e-06,3.86e-06,2.46e-07,0,0,0,0,0,0,0,0
|
||||
7090000,-0.257,0.0125,-0.0056,0.966,-0.00598,0.0131,-0.106,-0.00199,0.0048,-0.572,-1.63e-05,-5.79e-05,2.23e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.00211,0.000314,0.000314,0.00049,0.16,0.16,0.0291,0.0991,0.0991,0.0649,6.62e-09,6.63e-09,8.49e-09,3.86e-06,3.86e-06,2.33e-07,0,0,0,0,0,0,0,0
|
||||
7190000,-0.258,0.0126,-0.00554,0.966,-0.00503,0.0119,-0.106,-0.0025,0.00599,-0.582,-1.63e-05,-5.79e-05,2.16e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.00118,0.000314,0.000314,0.000417,0.163,0.163,0.028,0.122,0.122,0.0638,6.62e-09,6.63e-09,8.49e-09,3.86e-06,3.86e-06,2.19e-07,0,0,0,0,0,0,0,0
|
||||
7290000,-0.258,0.0126,-0.00552,0.966,-0.00498,0.00847,-0.108,-0.00294,0.00703,-0.593,-1.63e-05,-5.79e-05,2.39e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000827,0.000315,0.000315,0.00039,0.167,0.167,0.027,0.148,0.148,0.0628,6.62e-09,6.63e-09,8.49e-09,3.86e-06,3.86e-06,2.06e-07,0,0,0,0,0,0,0,0
|
||||
7390000,-0.257,0.0126,-0.0054,0.966,-0.00259,0.00657,-0.109,-0.00332,0.00773,-0.604,-1.63e-05,-5.79e-05,2.53e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000657,0.000316,0.000316,0.000376,0.175,0.175,0.0263,0.177,0.177,0.0628,6.62e-09,6.63e-09,8.48e-09,3.86e-06,3.86e-06,1.96e-07,0,0,0,0,0,0,0,0
|
||||
7490000,-0.257,0.0126,-0.00539,0.966,-0.00422,0.00408,-0.109,-0.00367,0.00823,-0.615,-1.63e-05,-5.79e-05,3.44e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000534,0.000317,0.000317,0.000367,0.185,0.185,0.0253,0.21,0.21,0.0618,6.61e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.85e-07,0,0,0,0,0,0,0,0
|
||||
7590000,-0.257,0.0126,-0.00547,0.966,-0.00453,0.00172,-0.11,-0.00411,0.00856,-0.626,-1.63e-05,-5.79e-05,3.53e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000451,0.000318,0.000318,0.000361,0.198,0.198,0.0244,0.246,0.246,0.0609,6.61e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.74e-07,0,0,0,0,0,0,0,0
|
||||
7690000,-0.257,0.0126,-0.00547,0.966,-0.00339,-0.00125,-0.114,-0.0045,0.00853,-0.637,-1.63e-05,-5.79e-05,3.28e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000399,0.00032,0.00032,0.000356,0.214,0.214,0.0239,0.287,0.287,0.0608,6.61e-09,6.62e-09,8.47e-09,3.86e-06,3.86e-06,1.66e-07,0,0,0,0,0,0,0,0
|
||||
7790000,-0.257,0.0126,-0.00535,0.966,-0.00432,-0.00321,-0.116,-0.00488,0.00834,-0.648,-1.63e-05,-5.79e-05,2.65e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000353,0.000322,0.000323,0.000353,0.232,0.232,0.023,0.332,0.332,0.0599,6.6e-09,6.61e-09,8.46e-09,3.86e-06,3.86e-06,1.57e-07,0,0,0,0,0,0,0,0
|
||||
7890000,-0.257,0.0127,-0.00536,0.966,-0.00208,-0.00667,-0.117,-0.00512,0.00787,-0.66,-1.63e-05,-5.79e-05,2.29e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000317,0.000325,0.000325,0.00035,0.253,0.253,0.0222,0.382,0.382,0.059,6.6e-09,6.61e-09,8.45e-09,3.86e-06,3.86e-06,1.49e-07,0,0,0,0,0,0,0,0
|
||||
7990000,-0.257,0.0126,-0.0053,0.966,-0.00161,-0.00895,-0.116,-0.00529,0.00713,-0.672,-1.63e-05,-5.79e-05,2.46e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000289,0.000328,0.000328,0.000348,0.276,0.276,0.0215,0.436,0.436,0.0581,6.59e-09,6.59e-09,8.43e-09,3.86e-06,3.86e-06,1.41e-07,0,0,0,0,0,0,0,0
|
||||
8090000,-0.257,0.0126,-0.00515,0.966,-0.00215,-0.0127,-0.118,-0.00553,0.0061,-0.683,-1.63e-05,-5.79e-05,-1.98e-08,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.00027,0.000331,0.000331,0.000346,0.302,0.302,0.021,0.498,0.498,0.0581,6.59e-09,6.59e-09,8.42e-09,3.86e-06,3.86e-06,1.34e-07,0,0,0,0,0,0,0,0
|
||||
8190000,-0.257,0.0125,-0.00521,0.966,-0.00161,-0.0177,-0.118,-0.00568,0.00452,-0.695,-1.63e-05,-5.79e-05,-2.28e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.00025,0.000335,0.000335,0.000345,0.33,0.33,0.0203,0.564,0.564,0.0573,6.57e-09,6.57e-09,8.4e-09,3.85e-06,3.86e-06,1.28e-07,0,0,0,0,0,0,0,0
|
||||
8290000,-0.257,0.0125,-0.00519,0.966,-0.0028,-0.0219,-0.119,-0.0059,0.00258,-0.707,-1.63e-05,-5.79e-05,-2.83e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000235,0.000339,0.000339,0.000344,0.362,0.362,0.0197,0.64,0.64,0.0564,6.57e-09,6.57e-09,8.37e-09,3.85e-06,3.86e-06,1.21e-07,0,0,0,0,0,0,0,0
|
||||
8390000,-0.258,0.0125,-0.00513,0.966,4.21e-05,-0.0232,-0.12,-0.00601,0.000363,-0.719,-1.63e-05,-5.79e-05,-3.46e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000223,0.000343,0.000343,0.000343,0.395,0.395,0.0193,0.719,0.719,0.0564,6.54e-09,6.55e-09,8.35e-09,3.85e-06,3.85e-06,1.16e-07,0,0,0,0,0,0,0,0
|
||||
8490000,-0.257,0.0125,-0.00502,0.966,0.00124,-0.027,-0.121,-0.00596,-0.0021,-0.731,-1.63e-05,-5.79e-05,-1.22e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000212,0.000347,0.000347,0.000342,0.433,0.433,0.0187,0.813,0.813,0.0556,6.54e-09,6.55e-09,8.31e-09,3.85e-06,3.85e-06,1.1e-07,0,0,0,0,0,0,0,0
|
||||
8590000,-0.257,0.0126,-0.00497,0.966,0.00107,-0.0297,-0.12,-0.00576,-0.00492,-0.743,-1.63e-05,-5.79e-05,-2.54e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000202,0.000352,0.000352,0.000341,0.47,0.47,0.0181,0.909,0.909,0.0548,6.51e-09,6.52e-09,8.27e-09,3.85e-06,3.85e-06,1.05e-07,0,0,0,0,0,0,0,0
|
||||
8690000,-0.257,0.0127,-0.00498,0.966,0.00184,-0.0319,-0.123,-0.00557,-0.00798,-0.755,-1.63e-05,-5.79e-05,-1.89e-07,-2.4e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000195,0.000357,0.000357,0.000341,0.514,0.514,0.0177,1.02,1.02,0.0548,6.51e-09,6.52e-09,8.24e-09,3.85e-06,3.85e-06,1.01e-07,0,0,0,0,0,0,0,0
|
||||
8790000,-0.257,0.0126,-0.00495,0.966,0.00135,-0.0348,-0.125,-0.00526,-0.0112,-0.767,-1.63e-05,-5.79e-05,-4.67e-07,-2.39e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000188,0.000363,0.000363,0.00034,0.556,0.556,0.0172,1.14,1.14,0.0541,6.48e-09,6.49e-09,8.19e-09,3.85e-06,3.85e-06,9.63e-08,0,0,0,0,0,0,0,0
|
||||
8890000,-0.257,0.0127,-0.00498,0.966,0.00228,-0.0381,-0.125,-0.00509,-0.0148,-0.78,-1.63e-05,-5.79e-05,-2e-07,-2.39e-05,1.56e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000181,0.000369,0.000369,0.000339,0.606,0.606,0.0167,1.28,1.28,0.0533,6.48e-09,6.49e-09,8.14e-09,3.85e-06,3.85e-06,9.2e-08,0,0,0,0,0,0,0,0
|
||||
8990000,-0.257,0.0126,-0.0049,0.966,0.00432,-0.0423,-0.124,-0.00464,-0.0186,-0.792,-1.63e-05,-5.79e-05,1.78e-07,-2.38e-05,1.57e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000177,0.000375,0.000375,0.000339,0.652,0.652,0.0164,1.41,1.41,0.0533,6.44e-09,6.45e-09,8.09e-09,3.84e-06,3.84e-06,8.84e-08,0,0,0,0,0,0,0,0
|
||||
9090000,-0.257,0.0127,-0.00488,0.966,0.00517,-0.0471,-0.127,-0.00421,-0.023,-0.805,-1.63e-05,-5.79e-05,6.09e-07,-2.38e-05,1.57e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000172,0.000381,0.000381,0.000339,0.708,0.707,0.0159,1.58,1.58,0.0526,6.44e-09,6.45e-09,8.03e-09,3.84e-06,3.84e-06,8.46e-08,0,0,0,0,0,0,0,0
|
||||
9190000,-0.257,0.0127,-0.00486,0.966,0.00254,-0.05,-0.127,-0.00376,-0.0275,-0.818,-1.63e-05,-5.79e-05,9.77e-07,-2.37e-05,1.59e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000168,0.000388,0.000388,0.000338,0.757,0.757,0.0155,1.74,1.74,0.0519,6.4e-09,6.41e-09,7.96e-09,3.83e-06,3.84e-06,8.1e-08,0,0,0,0,0,0,0,0
|
||||
9290000,-0.257,0.0125,-0.00471,0.966,0.00122,-0.0535,-0.128,-0.00365,-0.0326,-0.831,-1.63e-05,-5.79e-05,1.07e-06,-2.37e-05,1.59e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000164,0.000395,0.000395,0.000338,0.819,0.819,0.0151,1.94,1.94,0.0512,6.4e-09,6.41e-09,7.89e-09,3.83e-06,3.84e-06,7.77e-08,0,0,0,0,0,0,0,0
|
||||
9390000,-0.257,0.0125,-0.0046,0.966,0.00213,-0.056,-0.128,-0.00344,-0.0373,-0.843,-1.63e-05,-5.79e-05,5.83e-07,-2.35e-05,1.62e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000162,0.000402,0.000402,0.000338,0.871,0.871,0.0148,2.12,2.12,0.0512,6.36e-09,6.36e-09,7.82e-09,3.82e-06,3.82e-06,7.49e-08,0,0,0,0,0,0,0,0
|
||||
9490000,-0.257,0.0126,-0.00461,0.966,0.00307,-0.0583,-0.129,-0.00317,-0.043,-0.856,-1.63e-05,-5.79e-05,7.19e-07,-2.35e-05,1.62e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000159,0.00041,0.00041,0.000338,0.939,0.939,0.0144,2.36,2.36,0.0506,6.36e-09,6.36e-09,7.74e-09,3.82e-06,3.82e-06,7.19e-08,0,0,0,0,0,0,0,0
|
||||
9590000,-0.257,0.0126,-0.00464,0.966,0.00406,-0.0596,-0.13,-0.00265,-0.0476,-0.869,-1.64e-05,-5.79e-05,-2.62e-07,-2.32e-05,1.67e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000157,0.000417,0.000417,0.000337,0.992,0.992,0.014,2.56,2.56,0.05,6.31e-09,6.32e-09,7.65e-09,3.81e-06,3.81e-06,6.91e-08,0,0,0,0,0,0,0,0
|
||||
9690000,-0.257,0.0125,-0.00463,0.966,0.00509,-0.0626,-0.128,-0.00224,-0.0538,-0.882,-1.64e-05,-5.78e-05,-5.7e-07,-2.32e-05,1.67e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000156,0.000426,0.000426,0.000337,1.07,1.07,0.0138,2.85,2.85,0.05,6.31e-09,6.32e-09,7.57e-09,3.81e-06,3.81e-06,6.67e-08,0,0,0,0,0,0,0,0
|
||||
9790000,-0.257,0.0125,-0.00459,0.966,0.00484,-0.0664,-0.13,-0.00174,-0.0603,-0.895,-1.64e-05,-5.78e-05,-1.58e-06,-2.32e-05,1.68e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000154,0.000435,0.000435,0.000337,1.15,1.14,0.0135,3.16,3.16,0.0493,6.31e-09,6.32e-09,7.47e-09,3.81e-06,3.81e-06,6.42e-08,0,0,0,0,0,0,0,0
|
||||
9890000,-0.257,0.0124,-0.00455,0.966,0.00355,-0.0682,-0.13,-0.00124,-0.065,-0.908,-1.64e-05,-5.78e-05,-1.47e-06,-2.28e-05,1.75e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000153,0.000443,0.000443,0.000337,1.2,1.2,0.0131,3.39,3.39,0.0487,6.27e-09,6.28e-09,7.37e-09,3.79e-06,3.79e-06,6.18e-08,0,0,0,0,0,0,0,0
|
||||
9990000,-0.258,0.0125,-0.00448,0.966,0.00339,-0.0735,-0.0989,0.000449,-0.0752,-0.848,-1.65e-05,-5.77e-05,-2.32e-06,-2.36e-05,1.6e-05,-0.00131,-0.202,-0.0311,0.435,0,0,0,0,0,0.000152,0.000452,0.000452,0.000337,1.28,1.28,0.0129,3.76,3.76,0.0488,6.27e-09,6.28e-09,7.28e-09,3.79e-06,3.79e-06,5.99e-08,0,0,0,0,0,0,0,0
|
||||
10090000,-0.258,0.0127,-0.00436,0.966,0.00647,-0.0757,-0.0653,0.0024,-0.0835,-0.779,-1.66e-05,-5.76e-05,-3.35e-06,-2.38e-05,1.52e-05,-0.00137,-0.202,-0.0311,0.435,0,0,0,0,0,0.000151,0.00046,0.00046,0.000337,1.34,1.34,0.0126,4.01,4,0.0482,6.23e-09,6.24e-09,7.17e-09,3.77e-06,3.77e-06,5.77e-08,0,0,0,0,0,0,0,0
|
||||
10190000,-0.258,0.0126,-0.00427,0.966,0.0098,-0.0821,-0.0349,0.00461,-0.0952,-0.716,-1.67e-05,-5.75e-05,-4.58e-06,-2.45e-05,1.34e-05,-0.00141,-0.202,-0.0311,0.435,0,0,0,0,0,0.00015,0.000471,0.000471,0.000337,1.43,1.43,0.0123,4.43,4.42,0.0476,6.23e-09,6.24e-09,7.06e-09,3.77e-06,3.77e-06,5.57e-08,0,0,0,0,0,0,0,0
|
||||
10290000,-0.258,0.0125,-0.00427,0.966,0.0109,-0.0861,-0.0121,0.00669,-0.103,-0.662,-1.68e-05,-5.75e-05,-4.33e-06,-2.43e-05,1.33e-05,-0.00145,-0.202,-0.0311,0.435,0,0,0,0,0,0.00015,0.000479,0.000479,0.000337,1.47,1.47,0.0122,4.67,4.67,0.0476,6.19e-09,6.2e-09,6.95e-09,3.74e-06,3.74e-06,5.4e-08,0,0,0,0,0,0,0,0
|
||||
10390000,-0.258,0.0125,-0.00422,0.966,0.0143,-0.00505,0.000175,0.00109,-0.000142,-0.606,-1.68e-05,-5.74e-05,-4.27e-06,-2.49e-05,1.17e-05,-0.00148,-0.202,-0.0311,0.435,0,0,0,0,0,0.00015,0.00049,0.00049,0.000337,0.0419,0.0419,0.0401,0.25,0.25,0.0441,6.19e-09,6.2e-09,6.84e-09,3.74e-06,3.74e-06,5.23e-08,0,0,0,0,0,0,0,0
|
||||
10490000,-0.258,0.0124,-0.00408,0.966,0.014,-0.00828,0.00935,0.00253,-0.000776,-0.555,-1.69e-05,-5.73e-05,-5.31e-06,-2.54e-05,1.04e-05,-0.00151,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000501,0.000501,0.000337,0.048,0.048,0.0402,0.252,0.252,0.0416,6.19e-09,6.2e-09,6.71e-09,3.74e-06,3.74e-06,5.09e-08,0,0,0,0,0,0,0,0
|
||||
10590000,-0.258,0.0128,-0.00428,0.966,0.00086,-0.00626,0.0216,0.000379,-0.000501,-0.509,-1.6e-05,-5.65e-05,-4.94e-06,-3.72e-05,2.37e-05,-0.00154,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000471,0.000471,0.000336,0.0273,0.0273,0.0278,0.252,0.252,0.0392,5.99e-09,5.99e-09,6.59e-09,3.69e-06,3.69e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10690000,-0.258,0.0129,-0.00419,0.966,-0.00065,-0.00811,0.0322,0.000386,-0.00123,-0.471,-1.6e-05,-5.65e-05,-5.32e-06,-3.75e-05,2.28e-05,-0.00156,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000483,0.000483,0.000336,0.0371,0.0371,0.0278,0.253,0.253,0.0384,5.99e-09,5.99e-09,6.47e-09,3.69e-06,3.69e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10790000,-0.258,0.013,-0.00409,0.966,-0.00209,-0.0123,0.0334,0.000232,-0.0018,-0.441,-1.61e-05,-5.65e-05,-5.58e-06,-3.73e-05,2.06e-05,-0.00158,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000401,0.000401,0.000336,0.0266,0.0266,0.0212,0.127,0.127,0.0365,5.52e-09,5.52e-09,6.35e-09,3.59e-06,3.59e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10890000,-0.258,0.013,-0.00404,0.966,-0.00214,-0.0167,0.0426,5.96e-06,-0.0032,-0.414,-1.61e-05,-5.65e-05,-4.83e-06,-3.74e-05,2.01e-05,-0.00159,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000411,0.000411,0.000336,0.0375,0.0375,0.0211,0.128,0.128,0.0359,5.52e-09,5.52e-09,6.21e-09,3.59e-06,3.59e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10990000,-0.258,0.0129,-0.0046,0.966,-0.00043,-0.0157,0.0465,0.000108,-0.00134,-0.39,-1.49e-05,-5.73e-05,-5.13e-06,-2.57e-05,3.61e-05,-0.0016,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000316,0.000316,0.000336,0.0266,0.0266,0.0171,0.0851,0.0851,0.0346,4.98e-09,4.99e-09,6.1e-09,3.49e-06,3.49e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11090000,-0.258,0.0129,-0.00471,0.966,-0.00102,-0.0205,0.0573,6.59e-05,-0.0031,-0.363,-1.49e-05,-5.72e-05,-6.13e-06,-2.58e-05,3.58e-05,-0.00162,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000324,0.000324,0.000336,0.0366,0.0366,0.017,0.0865,0.0865,0.0344,4.98e-09,4.99e-09,5.96e-09,3.49e-06,3.49e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11190000,-0.258,0.0124,-0.0053,0.966,0.00665,-0.014,0.0633,0.00187,-0.000973,-0.339,-1.4e-05,-5.87e-05,-6.46e-06,-5.95e-06,4.74e-05,-0.00163,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000249,0.000249,0.000336,0.0253,0.0253,0.0142,0.0646,0.0646,0.033,4.55e-09,4.55e-09,5.83e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11290000,-0.259,0.0124,-0.00526,0.966,0.00749,-0.0141,0.0721,0.00262,-0.00243,-0.318,-1.4e-05,-5.87e-05,-6.55e-06,-5.96e-06,4.73e-05,-0.00163,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000255,0.000255,0.000336,0.0336,0.0336,0.0141,0.0662,0.0662,0.0332,4.55e-09,4.55e-09,5.71e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11390000,-0.258,0.0125,-0.00561,0.966,0.00493,-0.00913,0.0695,0.00154,-0.000813,-0.307,-1.29e-05,-5.88e-05,-6.16e-06,-5.22e-06,5.98e-05,-0.00164,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000204,0.000204,0.000336,0.0234,0.0234,0.0122,0.0526,0.0526,0.032,4.23e-09,4.23e-09,5.58e-09,3.38e-06,3.38e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11490000,-0.258,0.0125,-0.00554,0.966,0.00633,-0.00871,0.0789,0.00217,-0.00171,-0.283,-1.28e-05,-5.88e-05,-5.71e-06,-5.19e-06,5.97e-05,-0.00164,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.00021,0.00021,0.000336,0.03,0.03,0.0121,0.0542,0.0542,0.0321,4.23e-09,4.23e-09,5.44e-09,3.38e-06,3.38e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11590000,-0.258,0.0126,-0.00585,0.966,0.00146,-0.00571,0.0758,0.00113,-0.000673,-0.271,-1.22e-05,-5.87e-05,-5.45e-06,-5.72e-06,6.59e-05,-0.00165,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000177,0.000177,0.000336,0.0213,0.0213,0.0106,0.0448,0.0448,0.0312,4e-09,4e-09,5.33e-09,3.35e-06,3.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11690000,-0.258,0.0125,-0.00583,0.966,0.0016,-0.00832,0.0862,0.00127,-0.00136,-0.247,-1.22e-05,-5.87e-05,-4.86e-06,-5.67e-06,6.58e-05,-0.00166,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000182,0.000182,0.000336,0.0266,0.0266,0.0105,0.0464,0.0464,0.0314,4e-09,4e-09,5.19e-09,3.35e-06,3.36e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11790000,-0.258,0.0126,-0.00583,0.966,0.00122,-0.0111,0.0872,0.000966,-0.00235,-0.23,-1.21e-05,-5.86e-05,-3.73e-06,-6.62e-06,6.58e-05,-0.00166,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.00016,0.00016,0.000336,0.0194,0.0194,0.00935,0.0393,0.0393,0.0304,3.82e-09,3.82e-09,5.06e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11890000,-0.258,0.0125,-0.00593,0.966,-0.00128,-0.0125,0.0936,0.00101,-0.00349,-0.207,-1.21e-05,-5.86e-05,-3.82e-06,-6.59e-06,6.57e-05,-0.00167,-0.202,-0.0311,0.435,0,0,0,0,0,0.000148,0.000165,0.000165,0.000336,0.0238,0.0238,0.00929,0.041,0.041,0.0306,3.82e-09,3.82e-09,4.93e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11990000,-0.258,0.0122,-0.00633,0.966,0.00213,-0.0048,0.0911,0.00308,-0.0003,-0.199,-1.14e-05,-5.97e-05,-3.31e-06,-1.35e-06,6.94e-05,-0.00167,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.00015,0.00015,0.000336,0.018,0.018,0.0084,0.0409,0.0409,0.0299,3.66e-09,3.67e-09,4.81e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12090000,-0.258,0.0123,-0.00625,0.966,0.00108,-0.00401,0.1,0.00326,-0.000725,-0.175,-1.14e-05,-5.97e-05,-3.11e-06,-1.3e-06,6.93e-05,-0.00167,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000155,0.000155,0.000336,0.0216,0.0216,0.00835,0.0428,0.0428,0.0301,3.66e-09,3.67e-09,4.69e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12190000,-0.258,0.0123,-0.00635,0.966,-0.00047,0.0024,0.101,0.00269,0.00187,-0.156,-1.08e-05,-6e-05,-3.19e-06,-8.2e-07,7.1e-05,-0.00168,-0.202,-0.0311,0.435,0,0,0,0,0,0.000148,0.000145,0.000145,0.000336,0.0165,0.0165,0.00761,0.0365,0.0365,0.0292,3.53e-09,3.53e-09,4.56e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12290000,-0.258,0.0123,-0.00644,0.966,0.00192,0.00481,0.108,0.00274,0.00221,-0.131,-1.08e-05,-6e-05,-3.23e-06,-7.6e-07,7.09e-05,-0.00168,-0.202,-0.0311,0.435,0,0,0,0,0,0.000149,0.000149,0.000149,0.000336,0.0197,0.0197,0.00761,0.0383,0.0383,0.0297,3.53e-09,3.53e-09,4.45e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12390000,-0.258,0.0123,-0.00639,0.966,0.00084,0.00423,0.109,0.00214,0.00139,-0.119,-1.09e-05,-5.98e-05,-3.04e-06,-1.27e-06,7.11e-05,-0.00168,-0.202,-0.0311,0.435,0,0,0,0,0,0.000148,0.000142,0.000142,0.000336,0.0154,0.0154,0.007,0.0333,0.0333,0.0289,3.39e-09,3.4e-09,4.33e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12490000,-0.258,0.0123,-0.00638,0.966,0.00103,0.00426,0.121,0.0022,0.0018,-0.0928,-1.09e-05,-5.98e-05,-2.92e-06,-1.19e-06,7.11e-05,-0.00169,-0.202,-0.0311,0.435,0,0,0,0,0,0.000148,0.000146,0.000146,0.000336,0.0181,0.0181,0.00699,0.035,0.035,0.0291,3.39e-09,3.4e-09,4.21e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12590000,-0.258,0.0121,-0.00617,0.966,0.00155,0.00126,0.124,0.00368,-0.00078,-0.0747,-1.17e-05,-5.98e-05,-2.91e-06,-1.58e-06,7.25e-05,-0.00169,-0.202,-0.0311,0.435,0,0,0,0,0,0.000148,0.00014,0.00014,0.000336,0.0144,0.0144,0.00652,0.0308,0.0308,0.0286,3.26e-09,3.26e-09,4.1e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12690000,-0.258,0.0122,-0.00611,0.966,0.00119,0.00361,0.132,0.00386,-0.000541,-0.0445,-1.17e-05,-5.98e-05,-2.82e-06,-1.47e-06,7.24e-05,-0.00169,-0.202,-0.0311,0.435,0,0,0,0,0,0.000148,0.000144,0.000144,0.000336,0.017,0.017,0.00653,0.0324,0.0324,0.0288,3.26e-09,3.26e-09,3.99e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12790000,-0.257,0.0119,-0.00584,0.966,0.00765,-0.00542,0.134,0.00775,-0.00482,-0.0264,-1.31e-05,-6.01e-05,-1.75e-06,-2.77e-06,7.77e-05,-0.00169,-0.202,-0.0311,0.435,0,0,0,0,0,0.000147,0.00014,0.00014,0.000336,0.0139,0.0139,0.00611,0.0323,0.0323,0.0281,3.12e-09,3.13e-09,3.88e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12890000,-0.257,0.0118,-0.00582,0.966,0.00847,-0.00518,0.143,0.00852,-0.00535,0.0011,-1.31e-05,-6.01e-05,-1.14e-06,-2.67e-06,7.76e-05,-0.0017,-0.202,-0.0311,0.435,0,0,0,0,0,0.000147,0.000144,0.000144,0.000336,0.0162,0.0162,0.00616,0.0342,0.0342,0.0285,3.12e-09,3.13e-09,3.78e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12990000,-0.257,0.0119,-0.00592,0.966,0.00558,-0.00442,0.144,0.00658,-0.00428,0.02,-1.27e-05,-5.99e-05,-6.01e-07,-1.98e-06,7.63e-05,-0.0017,-0.202,-0.0311,0.435,0,0,0,0,0,0.000147,0.000139,0.00014,0.000336,0.0132,0.0132,0.0058,0.0301,0.0301,0.0278,2.98e-09,2.98e-09,3.67e-09,3.33e-06,3.33e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13090000,-0.257,0.0118,-0.00594,0.966,0.00541,-0.00517,0.151,0.00715,-0.00482,0.0495,-1.27e-05,-5.99e-05,1.72e-07,-1.85e-06,7.62e-05,-0.0017,-0.202,-0.0311,0.435,0,0,0,0,0,0.000146,0.000144,0.000144,0.000336,0.0154,0.0154,0.00585,0.0318,0.0318,0.0281,2.98e-09,2.98e-09,3.56e-09,3.33e-06,3.33e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13190000,-0.257,0.0119,-0.00586,0.966,0.0055,-0.00662,0.15,0.00676,-0.00637,0.0656,-1.28e-05,-5.96e-05,5.79e-07,-6.19e-07,7.77e-05,-0.0017,-0.202,-0.0311,0.435,0,0,0,0,0,0.000145,0.00014,0.00014,0.000336,0.0129,0.0129,0.00555,0.0316,0.0316,0.0274,2.82e-09,2.82e-09,3.46e-09,3.33e-06,3.33e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13290000,-0.257,0.0119,-0.00588,0.966,0.00615,-0.00643,0.155,0.0074,-0.00704,0.0916,-1.28e-05,-5.96e-05,5.12e-07,-5.24e-07,7.76e-05,-0.0017,-0.202,-0.0311,0.435,0,0,0,0,0,0.000145,0.000144,0.000144,0.000336,0.0151,0.0151,0.00563,0.0335,0.0335,0.0278,2.82e-09,2.83e-09,3.37e-09,3.33e-06,3.33e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13390000,-0.257,0.0121,-0.00592,0.966,0.00449,-0.00527,0.153,0.00583,-0.00558,0.105,-1.23e-05,-5.95e-05,6.75e-08,-5.21e-07,7.52e-05,-0.00169,-0.202,-0.0311,0.435,0,0,0,0,0,0.000145,0.000139,0.00014,0.000336,0.0125,0.0125,0.00537,0.0295,0.0295,0.0272,2.66e-09,2.66e-09,3.27e-09,3.32e-06,3.32e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13490000,-0.257,0.012,-0.00589,0.966,0.00451,-0.00759,0.16,0.00628,-0.00629,0.129,-1.23e-05,-5.95e-05,2.18e-07,-4.32e-07,7.51e-05,-0.0017,-0.202,-0.0311,0.435,0,0,0,0,0,0.000144,0.000144,0.000144,0.000335,0.0145,0.0145,0.00545,0.0312,0.0312,0.0274,2.66e-09,2.66e-09,3.18e-09,3.32e-06,3.32e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13590000,-0.257,0.0118,-0.00592,0.966,0.00796,-0.00494,0.159,0.00915,-0.00479,0.138,-1.24e-05,-6.04e-05,-5.35e-08,-9.43e-06,7.66e-05,-0.00169,-0.202,-0.0311,0.435,0,0,0,0,0,0.000144,0.000139,0.000139,0.000335,0.0122,0.0122,0.00524,0.0278,0.0278,0.027,2.49e-09,2.49e-09,3.1e-09,3.31e-06,3.31e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13690000,-0.257,0.0117,-0.00587,0.966,0.00851,-0.00394,0.166,0.00998,-0.00524,0.164,-1.24e-05,-6.05e-05,3.52e-07,-9.31e-06,7.64e-05,-0.00169,-0.202,-0.0311,0.435,0,0,0,0,0,0.000143,0.000143,0.000143,0.000335,0.0142,0.0142,0.00534,0.0295,0.0295,0.0272,2.49e-09,2.49e-09,3.01e-09,3.31e-06,3.31e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13790000,-0.257,0.0114,-0.00596,0.966,0.0125,-0.00173,0.164,0.014,-0.00251,0.178,-1.23e-05,-6.2e-05,1.16e-07,-2.38e-05,7.75e-05,-0.00168,-0.202,-0.0311,0.435,0,0,0,0,0,0.000143,0.000139,0.000139,0.000335,0.012,0.012,0.00514,0.0265,0.0265,0.0267,2.31e-09,2.31e-09,2.92e-09,3.29e-06,3.29e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13890000,-0.257,0.0113,-0.00587,0.966,0.0129,-0.00257,0.171,0.0153,-0.00273,0.207,-1.23e-05,-6.2e-05,7.1e-07,-2.36e-05,7.73e-05,-0.00169,-0.202,-0.0311,0.435,0,0,0,0,0,0.000142,0.000142,0.000142,0.000335,0.014,0.014,0.00526,0.0281,0.0281,0.027,2.31e-09,2.31e-09,2.84e-09,3.29e-06,3.29e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13990000,-0.257,0.0114,-0.00584,0.966,0.00715,-0.00729,0.169,0.0124,-0.00414,0.223,-1.22e-05,-6.11e-05,1.28e-06,-1.69e-05,7.77e-05,-0.00168,-0.202,-0.0311,0.435,0,0,0,0,0,0.000142,0.000137,0.000138,0.000335,0.0118,0.0118,0.00509,0.0254,0.0254,0.0265,2.13e-09,2.13e-09,2.76e-09,3.28e-06,3.28e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14090000,-0.257,0.0113,-0.00584,0.966,0.00991,-0.00288,0.178,0.0132,-0.00464,0.249,-1.23e-05,-6.11e-05,-1.06e-07,-1.67e-05,7.76e-05,-0.00168,-0.202,-0.0311,0.435,0,0,0,0,0,0.000141,0.000141,0.000141,0.000335,0.0138,0.0138,0.0052,0.027,0.027,0.0267,2.13e-09,2.13e-09,2.68e-09,3.28e-06,3.28e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14190000,-0.257,0.0112,-0.00585,0.966,0.0118,-0.00264,0.173,0.0131,-0.00402,0.257,-1.22e-05,-6.12e-05,-7.47e-07,-1.94e-05,7.8e-05,-0.00167,-0.202,-0.0311,0.435,0,0,0,0,0,0.000141,0.000136,0.000136,0.000335,0.0117,0.0117,0.00506,0.0245,0.0245,0.0263,1.95e-09,1.95e-09,2.61e-09,3.26e-06,3.26e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14290000,-0.257,0.0112,-0.00579,0.966,0.0112,-0.00306,0.177,0.0143,-0.00424,0.285,-1.22e-05,-6.12e-05,-6.94e-07,-1.92e-05,7.78e-05,-0.00167,-0.202,-0.0311,0.435,0,0,0,0,0,0.00014,0.000139,0.000139,0.000335,0.0137,0.0137,0.00519,0.026,0.026,0.0265,1.95e-09,1.95e-09,2.53e-09,3.26e-06,3.26e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14390000,-0.257,0.0112,-0.00574,0.966,0.00991,-0.0037,0.173,0.0138,-0.00544,0.297,-1.25e-05,-6.1e-05,-3.47e-07,-1.79e-05,8.27e-05,-0.00166,-0.202,-0.0311,0.435,0,0,0,0,0,0.000139,0.000134,0.000134,0.000335,0.0117,0.0117,0.00505,0.0237,0.0237,0.026,1.77e-09,1.77e-09,2.46e-09,3.24e-06,3.24e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14490000,-0.257,0.0112,-0.00584,0.966,0.0124,-0.00421,0.182,0.015,-0.00582,0.322,-1.25e-05,-6.09e-05,-1.09e-06,-1.78e-05,8.26e-05,-0.00166,-0.202,-0.0311,0.435,0,0,0,0,0,0.000138,0.000137,0.000137,0.000335,0.0136,0.0136,0.00519,0.0253,0.0253,0.0262,1.77e-09,1.77e-09,2.39e-09,3.24e-06,3.24e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14590000,-0.257,0.0114,-0.0059,0.966,0.0046,-0.007,0.176,0.0107,-0.00681,0.327,-1.21e-05,-5.97e-05,-1.28e-06,-5.86e-06,8.01e-05,-0.00165,-0.202,-0.0311,0.435,0,0,0,0,0,0.000138,0.000132,0.000132,0.000335,0.0116,0.0116,0.00506,0.0231,0.0231,0.0259,1.6e-09,1.6e-09,2.33e-09,3.22e-06,3.22e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14690000,-0.257,0.0115,-0.00588,0.966,0.00572,-0.00761,0.181,0.0112,-0.00756,0.349,-1.21e-05,-5.97e-05,-1.11e-06,-5.77e-06,8.01e-05,-0.00165,-0.202,-0.0311,0.435,0,0,0,0,0,0.000137,0.000135,0.000135,0.000335,0.0135,0.0135,0.00521,0.0247,0.0247,0.0261,1.6e-09,1.6e-09,2.26e-09,3.22e-06,3.22e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14790000,-0.257,0.0114,-0.00648,0.966,0.000644,0.00113,0.177,0.00956,-0.000659,0.36,-1.01e-05,-6.05e-05,-3.15e-07,-1.59e-05,5.87e-05,-0.00164,-0.202,-0.0311,0.435,0,0,0,0,0,0.000136,0.000129,0.000129,0.000335,0.0115,0.0115,0.00508,0.0226,0.0226,0.0257,1.44e-09,1.44e-09,2.19e-09,3.19e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14890000,-0.257,0.0113,-0.00641,0.966,0.0017,0.00398,0.185,0.00972,-0.000409,0.38,-1.01e-05,-6.05e-05,3.3e-07,-1.59e-05,5.87e-05,-0.00164,-0.202,-0.0311,0.435,0,0,0,0,0,0.000136,0.000132,0.000132,0.000335,0.0134,0.0134,0.00525,0.0241,0.0241,0.026,1.44e-09,1.44e-09,2.14e-09,3.19e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14990000,-0.257,0.0113,-0.00634,0.966,0.000474,0.000186,0.18,0.00867,-0.0026,0.385,-1.07e-05,-6.01e-05,7.15e-07,-1.31e-05,6.78e-05,-0.00163,-0.202,-0.0311,0.435,0,0,0,0,0,0.000135,0.000126,0.000127,0.000335,0.0114,0.0114,0.00513,0.0221,0.0221,0.0256,1.29e-09,1.29e-09,2.08e-09,3.17e-06,3.17e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15090000,-0.257,0.0114,-0.00628,0.966,0.000549,-0.000967,0.187,0.00871,-0.0026,0.405,-1.07e-05,-6.01e-05,7.5e-07,-1.3e-05,6.77e-05,-0.00163,-0.202,-0.0311,0.435,0,0,0,0,0,0.000134,0.000129,0.000129,0.000335,0.0132,0.0132,0.00529,0.0237,0.0237,0.0258,1.29e-09,1.29e-09,2.02e-09,3.17e-06,3.17e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15190000,-0.257,0.0115,-0.00642,0.966,0.000218,0.000499,0.181,0.00787,-0.00223,0.41,-1.07e-05,-6.01e-05,5.61e-07,-1.53e-05,6.87e-05,-0.00161,-0.202,-0.0311,0.435,0,0,0,0,0,0.000134,0.000124,0.000124,0.000335,0.0113,0.0113,0.00518,0.0218,0.0218,0.0255,1.15e-09,1.15e-09,1.97e-09,3.15e-06,3.15e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15290000,-0.256,0.0115,-0.00651,0.966,-0.000588,0.00138,0.184,0.00783,-0.00216,0.426,-1.07e-05,-6.01e-05,1.15e-06,-1.54e-05,6.87e-05,-0.00161,-0.202,-0.0311,0.435,0,0,0,0,0,0.000133,0.000126,0.000126,0.000335,0.0131,0.0131,0.00535,0.0234,0.0234,0.0257,1.15e-09,1.15e-09,1.91e-09,3.15e-06,3.15e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15390000,-0.257,0.0115,-0.00659,0.966,-0.00193,-0.00107,0.178,0.00719,-0.00214,0.432,-1.07e-05,-6.01e-05,1.09e-06,-1.79e-05,7.12e-05,-0.0016,-0.202,-0.0311,0.435,0,0,0,0,0,0.000132,0.000121,0.000121,0.000335,0.0112,0.0112,0.00522,0.0215,0.0215,0.0253,1.02e-09,1.02e-09,1.86e-09,3.13e-06,3.13e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15490000,-0.257,0.0115,-0.0066,0.966,-0.00188,0.00141,0.181,0.00701,-0.00215,0.452,-1.07e-05,-6.01e-05,1.12e-06,-1.78e-05,7.12e-05,-0.0016,-0.202,-0.0311,0.435,0,0,0,0,0,0.000132,0.000123,0.000123,0.000335,0.0129,0.0129,0.00541,0.0231,0.0231,0.0257,1.02e-09,1.02e-09,1.81e-09,3.13e-06,3.13e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15590000,-0.257,0.0113,-0.00621,0.966,0.00216,-0.00758,0.175,0.0103,-0.00778,0.458,-1.25e-05,-6.03e-05,1.4e-06,-2.25e-05,9.5e-05,-0.00158,-0.202,-0.0311,0.435,0,0,0,0,0,0.000131,0.000118,0.000118,0.000335,0.011,0.011,0.00528,0.0212,0.0212,0.0253,9.1e-10,9.1e-10,1.76e-09,3.12e-06,3.12e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15690000,-0.256,0.0113,-0.00616,0.966,0.000243,-0.00565,0.18,0.0104,-0.00845,0.478,-1.25e-05,-6.03e-05,1.73e-06,-2.24e-05,9.49e-05,-0.00158,-0.202,-0.0311,0.435,0,0,0,0,0,0.00013,0.00012,0.00012,0.000334,0.0127,0.0127,0.00546,0.0228,0.0228,0.0255,9.1e-10,9.1e-10,1.71e-09,3.12e-06,3.12e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15790000,-0.256,0.0112,-0.00628,0.967,0.00117,-0.00325,0.174,0.00953,-0.00718,0.488,-1.22e-05,-6.05e-05,2.26e-06,-2.63e-05,9.37e-05,-0.00157,-0.202,-0.0311,0.435,0,0,0,0,0,0.000129,0.000115,0.000116,0.000334,0.0109,0.0109,0.00533,0.021,0.021,0.0251,8.08e-10,8.09e-10,1.66e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15890000,-0.256,0.0113,-0.00631,0.966,0.00279,-0.00544,0.179,0.00977,-0.00761,0.51,-1.23e-05,-6.05e-05,1.7e-06,-2.62e-05,9.36e-05,-0.00157,-0.202,-0.0311,0.435,0,0,0,0,0,0.000129,0.000117,0.000117,0.000334,0.0125,0.0125,0.00553,0.0226,0.0226,0.0256,8.08e-10,8.09e-10,1.62e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15990000,-0.256,0.0112,-0.00622,0.966,0.00267,-0.00428,0.17,0.00881,-0.00653,0.517,-1.2e-05,-6.05e-05,1.59e-06,-2.95e-05,9.18e-05,-0.00155,-0.202,-0.0311,0.435,0,0,0,0,0,0.000128,0.000113,0.000113,0.000334,0.0107,0.0107,0.00539,0.0208,0.0208,0.0252,7.18e-10,7.19e-10,1.58e-09,3.08e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16090000,-0.256,0.0112,-0.00619,0.966,0.00325,-0.00356,0.172,0.00916,-0.00692,0.54,-1.2e-05,-6.05e-05,1.27e-06,-2.93e-05,9.16e-05,-0.00155,-0.202,-0.0311,0.435,0,0,0,0,0,0.000127,0.000115,0.000115,0.000334,0.0123,0.0123,0.00557,0.0224,0.0224,0.0254,7.18e-10,7.19e-10,1.54e-09,3.08e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16190000,-0.257,0.0113,-0.0062,0.966,0.00139,-0.00377,0.165,0.00631,-0.00627,0.545,-1.17e-05,-6.01e-05,8.62e-07,-2.63e-05,8.83e-05,-0.00154,-0.202,-0.0311,0.435,0,0,0,0,0,0.000127,0.00011,0.000111,0.000334,0.0106,0.0106,0.00545,0.0207,0.0207,0.0252,6.38e-10,6.39e-10,1.5e-09,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16290000,-0.257,0.0112,-0.00623,0.966,0.000618,-0.00286,0.169,0.00643,-0.00656,0.568,-1.17e-05,-6.01e-05,9.82e-07,-2.6e-05,8.82e-05,-0.00154,-0.202,-0.0311,0.435,0,0,0,0,0,0.000126,0.000112,0.000112,0.000334,0.0121,0.0121,0.00563,0.0223,0.0223,0.0255,6.39e-10,6.39e-10,1.46e-09,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16390000,-0.256,0.0111,-0.00621,0.966,0.00153,-0.002,0.163,0.00773,-0.00585,0.575,-1.17e-05,-6.05e-05,1.35e-06,-3.33e-05,9.07e-05,-0.00152,-0.202,-0.0311,0.435,0,0,0,0,0,0.000125,0.000108,0.000108,0.000334,0.0104,0.0104,0.00549,0.0206,0.0206,0.0251,5.68e-10,5.69e-10,1.42e-09,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16490000,-0.257,0.0111,-0.00632,0.966,-0.000732,-0.00114,0.169,0.00775,-0.00596,0.598,-1.17e-05,-6.05e-05,1.19e-06,-3.31e-05,9.05e-05,-0.00152,-0.202,-0.0311,0.435,0,0,0,0,0,0.000125,0.000109,0.00011,0.000334,0.0119,0.0119,0.00569,0.0221,0.0221,0.0255,5.68e-10,5.69e-10,1.39e-09,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16590000,-0.256,0.0111,-0.00633,0.966,-0.0059,-0.000412,0.166,0.00692,-0.00543,0.604,-1.17e-05,-6.05e-05,1.18e-06,-3.59e-05,9.17e-05,-0.00151,-0.202,-0.0311,0.435,0,0,0,0,0,0.000124,0.000106,0.000106,0.000334,0.0102,0.0102,0.00554,0.0205,0.0205,0.0251,5.07e-10,5.07e-10,1.35e-09,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16690000,-0.256,0.011,-0.00639,0.966,-0.00807,0.00352,0.169,0.00621,-0.0053,0.623,-1.17e-05,-6.05e-05,1.4e-06,-3.59e-05,9.17e-05,-0.00151,-0.202,-0.0311,0.435,0,0,0,0,0,0.000123,0.000107,0.000107,0.000334,0.0116,0.0116,0.00573,0.022,0.022,0.0254,5.07e-10,5.07e-10,1.31e-09,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16790000,-0.256,0.0109,-0.00623,0.967,-0.00902,0.00296,0.161,0.0064,-0.00527,0.626,-1.2e-05,-6.07e-05,1.57e-06,-4.12e-05,9.73e-05,-0.00149,-0.202,-0.0311,0.435,0,0,0,0,0,0.000123,0.000104,0.000104,0.000334,0.01,0.01,0.00559,0.0204,0.0204,0.0252,4.53e-10,4.53e-10,1.28e-09,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16890000,-0.256,0.0109,-0.00619,0.967,-0.00813,0.00316,0.165,0.00555,-0.00499,0.642,-1.2e-05,-6.07e-05,2.05e-06,-4.12e-05,9.73e-05,-0.00149,-0.202,-0.0311,0.435,0,0,0,0,0,0.000122,0.000105,0.000105,0.000334,0.0114,0.0114,0.00578,0.0219,0.0219,0.0255,4.53e-10,4.53e-10,1.25e-09,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16990000,-0.256,0.0107,-0.00616,0.967,-0.00135,0.00345,0.159,0.01,-0.00525,0.645,-1.25e-05,-6.14e-05,2.15e-06,-5.37e-05,0.000106,-0.00148,-0.202,-0.0311,0.435,0,0,0,0,0,0.000121,0.000102,0.000102,0.000334,0.01,0.01,0.00562,0.0219,0.0219,0.0251,4.06e-10,4.06e-10,1.22e-09,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17090000,-0.256,0.0106,-0.00625,0.967,-0.00292,0.00553,0.16,0.00979,-0.00476,0.661,-1.25e-05,-6.14e-05,2.02e-06,-5.36e-05,0.000106,-0.00148,-0.202,-0.0311,0.435,0,0,0,0,0,0.00012,0.000103,0.000103,0.000334,0.0113,0.0113,0.00581,0.0236,0.0236,0.0254,4.06e-10,4.06e-10,1.19e-09,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17190000,-0.256,0.0105,-0.00606,0.966,-0.000506,0.00245,0.154,0.012,-0.0093,0.665,-1.33e-05,-6.13e-05,1.45e-06,-5.57e-05,0.00012,-0.00146,-0.202,-0.0311,0.435,0,0,0,0,0,0.00012,0.0001,0.000101,0.000334,0.00997,0.00996,0.00566,0.0235,0.0235,0.0252,3.65e-10,3.65e-10,1.16e-09,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17290000,-0.257,0.0105,-0.00602,0.966,-0.00097,0.00202,0.156,0.012,-0.00913,0.679,-1.33e-05,-6.13e-05,1.01e-06,-5.58e-05,0.00012,-0.00146,-0.202,-0.0311,0.435,0,0,0,0,0,0.000119,0.000101,0.000101,0.000334,0.0112,0.0112,0.00585,0.0253,0.0253,0.0255,3.65e-10,3.65e-10,1.13e-09,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17390000,-0.256,0.0103,-0.00603,0.967,0.00774,0.00854,0.148,0.0154,-0.0064,0.679,-1.34e-05,-6.19e-05,1.3e-06,-6.77e-05,0.000124,-0.00144,-0.202,-0.0311,0.435,0,0,0,0,0,0.000119,9.88e-05,9.89e-05,0.000334,0.00965,0.00965,0.00568,0.023,0.023,0.0251,3.28e-10,3.28e-10,1.1e-09,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17490000,-0.256,0.0103,-0.00604,0.966,0.0103,0.00915,0.149,0.0164,-0.00552,0.693,-1.34e-05,-6.19e-05,1.09e-06,-6.75e-05,0.000124,-0.00144,-0.202,-0.0311,0.435,0,0,0,0,0,0.000118,9.97e-05,9.98e-05,0.000334,0.0109,0.0109,0.00588,0.0247,0.0247,0.0256,3.28e-10,3.28e-10,1.08e-09,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17590000,-0.256,0.0105,-0.00604,0.966,0.00364,0.00624,0.141,0.0099,-0.00603,0.692,-1.33e-05,-6.12e-05,1.05e-06,-5.82e-05,0.000123,-0.00143,-0.202,-0.0311,0.435,0,0,0,0,0,0.000117,9.74e-05,9.75e-05,0.000334,0.0094,0.0094,0.00571,0.0225,0.0225,0.0252,2.97e-10,2.97e-10,1.05e-09,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17690000,-0.256,0.0104,-0.00614,0.967,0.0047,0.00658,0.143,0.0103,-0.00537,0.706,-1.33e-05,-6.12e-05,1.09e-06,-5.83e-05,0.000123,-0.00143,-0.202,-0.0311,0.435,0,0,0,0,0,0.000117,9.82e-05,9.83e-05,0.000334,0.0106,0.0106,0.00589,0.0241,0.0241,0.0255,2.97e-10,2.97e-10,1.02e-09,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17790000,-0.256,0.0103,-0.0062,0.967,0.00432,0.00805,0.136,0.0116,-0.00404,0.71,-1.32e-05,-6.13e-05,1.14e-06,-6.23e-05,0.000125,-0.00142,-0.202,-0.0311,0.435,0,0,0,0,0,0.000116,9.61e-05,9.62e-05,0.000334,0.00938,0.00938,0.00573,0.0241,0.0241,0.0253,2.69e-10,2.69e-10,1e-09,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17890000,-0.256,0.0104,-0.00611,0.967,0.00223,0.00942,0.136,0.0119,-0.00315,0.724,-1.32e-05,-6.13e-05,1.27e-06,-6.24e-05,0.000125,-0.00142,-0.202,-0.0311,0.435,0,0,0,0,0,0.000115,9.69e-05,9.7e-05,0.000334,0.0105,0.0105,0.00592,0.0258,0.0258,0.0256,2.69e-10,2.69e-10,9.78e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17990000,-0.256,0.0104,-0.00626,0.967,0.00129,0.0141,0.131,0.0106,0.00225,0.729,-1.28e-05,-6.15e-05,1.27e-06,-6.7e-05,0.000119,-0.0014,-0.202,-0.0311,0.435,0,0,0,0,0,0.000115,9.49e-05,9.5e-05,0.000334,0.00911,0.00911,0.00574,0.0234,0.0234,0.0252,2.45e-10,2.45e-10,9.54e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18090000,-0.256,0.0103,-0.00635,0.967,0.00198,0.015,0.132,0.0108,0.00373,0.74,-1.28e-05,-6.15e-05,1.28e-06,-6.72e-05,0.00012,-0.0014,-0.202,-0.0311,0.435,0,0,0,0,0,0.000114,9.56e-05,9.57e-05,0.000334,0.0102,0.0102,0.00594,0.0251,0.0251,0.0258,2.45e-10,2.45e-10,9.34e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18190000,-0.256,0.0103,-0.00627,0.967,0.00407,0.0126,0.127,0.0116,0.00191,0.742,-1.32e-05,-6.15e-05,1.82e-06,-6.94e-05,0.000127,-0.00139,-0.202,-0.0311,0.435,0,0,0,0,0,0.000114,9.38e-05,9.39e-05,0.000334,0.00889,0.00889,0.00576,0.0229,0.0229,0.0253,2.23e-10,2.23e-10,9.11e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18290000,-0.256,0.0103,-0.0063,0.967,0.0035,0.0131,0.128,0.0121,0.00318,0.754,-1.32e-05,-6.15e-05,1.88e-06,-6.95e-05,0.000127,-0.00139,-0.202,-0.0311,0.435,0,0,0,0,0,0.000113,9.44e-05,9.45e-05,0.000333,0.00995,0.00995,0.00594,0.0245,0.0245,0.0257,2.23e-10,2.23e-10,8.89e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18390000,-0.256,0.0102,-0.00613,0.967,0.00768,0.0109,0.122,0.0146,0.00174,0.756,-1.36e-05,-6.16e-05,1.73e-06,-7.37e-05,0.000134,-0.00138,-0.202,-0.0311,0.435,0,0,0,0,0,0.000112,9.28e-05,9.29e-05,0.000333,0.00871,0.00871,0.00576,0.0224,0.0224,0.0253,2.04e-10,2.04e-10,8.68e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18490000,-0.256,0.0102,-0.00617,0.967,0.00555,0.0107,0.123,0.0152,0.00282,0.769,-1.35e-05,-6.16e-05,1.94e-06,-7.39e-05,0.000135,-0.00138,-0.202,-0.0311,0.435,0,0,0,0,0,0.000112,9.34e-05,9.35e-05,0.000333,0.00974,0.00974,0.00596,0.024,0.024,0.0258,2.04e-10,2.04e-10,8.5e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18590000,-0.256,0.0101,-0.00598,0.967,0.00437,0.00917,0.117,0.0134,0.00161,0.776,-1.37e-05,-6.14e-05,1.68e-06,-7.25e-05,0.000138,-0.00137,-0.202,-0.0311,0.435,0,0,0,0,0,0.000111,9.18e-05,9.2e-05,0.000333,0.00856,0.00856,0.00577,0.022,0.022,0.0254,1.87e-10,1.87e-10,8.3e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18690000,-0.256,0.01,-0.00595,0.967,0.00499,0.00824,0.118,0.0138,0.00246,0.789,-1.37e-05,-6.14e-05,1.92e-06,-7.25e-05,0.000138,-0.00137,-0.202,-0.0311,0.435,0,0,0,0,0,0.00011,9.24e-05,9.25e-05,0.000333,0.00955,0.00955,0.00595,0.0235,0.0235,0.0257,1.87e-10,1.87e-10,8.11e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18790000,-0.256,0.00989,-0.00589,0.967,0.00688,0.00748,0.111,0.0142,0.00163,0.789,-1.38e-05,-6.14e-05,1.87e-06,-7.52e-05,0.000142,-0.00135,-0.202,-0.0311,0.435,0,0,0,0,0,0.00011,9.1e-05,9.11e-05,0.000333,0.00841,0.00841,0.00578,0.0217,0.0217,0.0255,1.72e-10,1.72e-10,7.95e-10,2.96e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18890000,-0.256,0.00991,-0.00584,0.967,0.00882,0.00736,0.111,0.015,0.00245,0.799,-1.38e-05,-6.14e-05,1.72e-06,-7.51e-05,0.000142,-0.00135,-0.202,-0.0311,0.435,0,0,0,0,0,0.000109,9.15e-05,9.16e-05,0.000333,0.00938,0.00938,0.00596,0.0232,0.0232,0.0258,1.72e-10,1.72e-10,7.76e-10,2.96e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18990000,-0.256,0.01,-0.00581,0.967,0.0075,0.00703,0.106,0.013,0.00162,0.803,-1.39e-05,-6.12e-05,1.69e-06,-7.39e-05,0.000144,-0.00134,-0.202,-0.0311,0.435,0,0,0,0,0,0.000109,9.02e-05,9.03e-05,0.000333,0.00828,0.00828,0.00578,0.0214,0.0214,0.0254,1.59e-10,1.59e-10,7.59e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19090000,-0.256,0.01,-0.00587,0.967,0.00988,0.00785,0.108,0.0138,0.0023,0.811,-1.39e-05,-6.12e-05,1.87e-06,-7.41e-05,0.000144,-0.00134,-0.202,-0.0311,0.435,0,0,0,0,0,0.000108,9.07e-05,9.08e-05,0.000333,0.00922,0.00922,0.00597,0.0229,0.0229,0.0259,1.59e-10,1.59e-10,7.44e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19190000,-0.256,0.0102,-0.00575,0.967,0.00877,0.00705,0.103,0.0119,0.00155,0.813,-1.39e-05,-6.1e-05,1.43e-06,-7.25e-05,0.000146,-0.00133,-0.202,-0.0311,0.435,0,0,0,0,0,0.000108,8.94e-05,8.96e-05,0.000333,0.00815,0.00815,0.00578,0.0211,0.0211,0.0255,1.47e-10,1.47e-10,7.27e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19290000,-0.256,0.0101,-0.00572,0.967,0.00996,0.00705,0.104,0.0128,0.00224,0.823,-1.39e-05,-6.1e-05,1.36e-06,-7.26e-05,0.000146,-0.00133,-0.202,-0.0311,0.435,0,0,0,0,0,0.000107,8.99e-05,9e-05,0.000333,0.00906,0.00906,0.00596,0.0226,0.0226,0.0259,1.47e-10,1.47e-10,7.11e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19390000,-0.256,0.0101,-0.00588,0.967,0.00843,0.00629,0.1,0.0109,0.00326,0.822,-1.38e-05,-6.09e-05,1.24e-06,-7.27e-05,0.000145,-0.00132,-0.202,-0.0311,0.435,0,0,0,0,0,0.000107,8.88e-05,8.89e-05,0.000333,0.00803,0.00803,0.00579,0.0209,0.0209,0.0256,1.36e-10,1.36e-10,6.97e-10,2.95e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19490000,-0.256,0.01,-0.00592,0.967,0.00948,0.00652,0.1,0.0118,0.00389,0.831,-1.38e-05,-6.09e-05,9.45e-07,-7.26e-05,0.000145,-0.00132,-0.202,-0.0311,0.435,0,0,0,0,0,0.000106,8.92e-05,8.93e-05,0.000333,0.00892,0.00892,0.00597,0.0224,0.0224,0.0259,1.36e-10,1.36e-10,6.81e-10,2.95e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19590000,-0.256,0.0101,-0.00574,0.966,0.0113,0.00581,0.0976,0.0119,0.00132,0.834,-1.4e-05,-6.08e-05,8.5e-07,-7.22e-05,0.000149,-0.00131,-0.202,-0.0311,0.435,0,0,0,0,0,0.000106,8.81e-05,8.82e-05,0.000333,0.00792,0.00792,0.00578,0.0207,0.0207,0.0255,1.27e-10,1.27e-10,6.66e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19690000,-0.256,0.0101,-0.00576,0.966,0.0135,0.00455,0.0973,0.0131,0.00182,0.844,-1.4e-05,-6.08e-05,1e-06,-7.2e-05,0.000149,-0.00131,-0.202,-0.0311,0.435,0,0,0,0,0,0.000105,8.85e-05,8.86e-05,0.000333,0.00878,0.00878,0.00596,0.0222,0.0222,0.0259,1.27e-10,1.27e-10,6.52e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19790000,-0.257,0.0101,-0.00582,0.966,0.0157,0.00325,0.092,0.014,0.00152,0.845,-1.4e-05,-6.07e-05,7.61e-07,-7.26e-05,0.000151,-0.0013,-0.202,-0.0311,0.435,0,0,0,0,0,0.000105,8.76e-05,8.77e-05,0.000333,0.00797,0.00797,0.00578,0.0223,0.0223,0.0256,1.18e-10,1.18e-10,6.39e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19890000,-0.257,0.0102,-0.00584,0.966,0.0161,0.00296,0.0939,0.0156,0.0018,0.855,-1.4e-05,-6.07e-05,6.42e-07,-7.26e-05,0.000151,-0.0013,-0.202,-0.0311,0.435,0,0,0,0,0,0.000104,8.8e-05,8.81e-05,0.000333,0.00882,0.00882,0.00596,0.0239,0.0239,0.026,1.18e-10,1.18e-10,6.26e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19990000,-0.257,0.0103,-0.0059,0.966,0.0156,0.00574,0.0853,0.0147,0.00329,0.852,-1.39e-05,-6.07e-05,6.8e-07,-7.39e-05,0.00015,-0.00129,-0.202,-0.0311,0.435,0,0,0,0,0,0.000103,8.7e-05,8.71e-05,0.000333,0.0078,0.0078,0.00577,0.0219,0.0219,0.0255,1.1e-10,1.1e-10,6.12e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20090000,-0.256,0.0103,-0.00591,0.966,0.0151,0.00794,0.0857,0.0163,0.00399,0.863,-1.39e-05,-6.07e-05,6.59e-07,-7.37e-05,0.00015,-0.00129,-0.202,-0.0311,0.435,0,0,0,0,0,0.000103,8.74e-05,8.75e-05,0.000333,0.00862,0.00862,0.00596,0.0235,0.0235,0.026,1.11e-10,1.11e-10,6.01e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20190000,-0.257,0.0104,-0.00588,0.966,0.0129,0.00453,0.081,0.015,0.00324,0.861,-1.39e-05,-6.04e-05,4.18e-07,-7.17e-05,0.000151,-0.00128,-0.202,-0.0311,0.435,0,0,0,0,0,0.000103,8.65e-05,8.67e-05,0.000333,0.00783,0.00783,0.00577,0.0235,0.0235,0.0256,1.04e-10,1.04e-10,5.88e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20290000,-0.256,0.0105,-0.00586,0.966,0.0162,0.00609,0.0805,0.0164,0.0037,0.866,-1.39e-05,-6.04e-05,3.39e-07,-7.19e-05,0.000151,-0.00128,-0.202,-0.0311,0.435,0,0,0,0,0,0.000102,8.69e-05,8.7e-05,0.000333,0.00864,0.00864,0.00595,0.0251,0.0251,0.026,1.04e-10,1.04e-10,5.76e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20390000,-0.257,0.0105,-0.00582,0.966,0.0155,0.00443,0.0737,0.015,0.00303,0.862,-1.39e-05,-6.02e-05,4.82e-07,-7e-05,0.000152,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000102,8.61e-05,8.62e-05,0.000333,0.00783,0.00783,0.00578,0.0251,0.0251,0.0257,9.74e-11,9.74e-11,5.65e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20490000,-0.256,0.0105,-0.00581,0.966,0.0202,0.00606,0.0731,0.0168,0.00353,0.865,-1.39e-05,-6.02e-05,4.6e-07,-7.03e-05,0.000152,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,0.000101,8.64e-05,8.65e-05,0.000333,0.00862,0.00862,0.00595,0.0268,0.0268,0.026,9.75e-11,9.75e-11,5.54e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20590000,-0.256,0.0105,-0.00579,0.967,0.0172,0.00629,0.0673,0.0146,0.0029,0.861,-1.38e-05,-6e-05,7.16e-07,-6.73e-05,0.000152,-0.00125,-0.202,-0.0311,0.435,0,0,0,0,0,0.000101,8.57e-05,8.58e-05,0.000333,0.0078,0.0078,0.00576,0.0267,0.0267,0.0256,9.18e-11,9.18e-11,5.42e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20690000,-0.256,0.0105,-0.0057,0.967,0.0192,0.0053,0.0674,0.0164,0.00342,0.865,-1.38e-05,-6e-05,4.95e-07,-6.76e-05,0.000152,-0.00125,-0.202,-0.0311,0.435,0,0,0,0,0,0.0001,8.6e-05,8.61e-05,0.000333,0.00858,0.00858,0.00596,0.0285,0.0285,0.0261,9.19e-11,9.19e-11,5.33e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20790000,-0.256,0.0105,-0.00512,0.967,0.0189,0.00244,0.0477,0.0128,0.00248,0.861,-1.38e-05,-5.98e-05,5.72e-07,-6.48e-05,0.000152,-0.00124,-0.202,-0.0311,0.435,0,0,0,0,0,9.97e-05,8.53e-05,8.53e-05,0.000333,0.00754,0.00754,0.00576,0.0256,0.0256,0.0257,8.66e-11,8.66e-11,5.22e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20890000,-0.256,0.00583,0.0037,0.967,0.0269,-0.00862,-0.0718,0.0151,0.00214,0.857,-1.38e-05,-5.98e-05,5.74e-07,-6.49e-05,0.000152,-0.00124,-0.202,-0.0311,0.435,0,0,0,0,0,9.91e-05,8.55e-05,8.55e-05,0.000333,0.0084,0.0084,0.00594,0.0272,0.0272,0.026,8.67e-11,8.67e-11,5.11e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20990000,-0.256,0.00225,0.00673,0.967,0.037,-0.0243,-0.209,0.0115,0.0022,0.849,-1.36e-05,-5.96e-05,5.34e-07,-5.89e-05,0.000145,-0.00125,-0.202,-0.0311,0.435,0,0,0,0,0,9.86e-05,8.46e-05,8.46e-05,0.000333,0.00754,0.00754,0.00575,0.0246,0.0246,0.0256,8.19e-11,8.18e-11,5.01e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21090000,-0.257,0.00274,0.00517,0.967,0.0527,-0.0383,-0.328,0.0159,-0.000972,0.821,-1.36e-05,-5.96e-05,5.25e-07,-5.9e-05,0.000146,-0.00125,-0.202,-0.0311,0.435,0,0,0,0,0,9.84e-05,8.48e-05,8.49e-05,0.000333,0.00841,0.0084,0.00595,0.0262,0.0262,0.0261,8.19e-11,8.19e-11,4.92e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21190000,-0.257,0.00476,0.00227,0.966,0.0521,-0.0389,-0.441,0.00979,0.00253,0.808,-1.3e-05,-5.93e-05,6.1e-07,-4.45e-05,0.000119,-0.00128,-0.202,-0.0311,0.435,0,0,0,0,0,9.79e-05,8.36e-05,8.37e-05,0.000332,0.00756,0.00755,0.00575,0.0239,0.0239,0.0257,7.74e-11,7.74e-11,4.83e-10,2.93e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21290000,-0.257,0.00625,0.000206,0.966,0.0526,-0.0424,-0.572,0.015,-0.00156,0.752,-1.3e-05,-5.93e-05,3.36e-07,-4.46e-05,0.000119,-0.00128,-0.202,-0.0311,0.435,0,0,0,0,0,9.74e-05,8.39e-05,8.4e-05,0.000332,0.00843,0.00843,0.00593,0.0254,0.0254,0.026,7.75e-11,7.75e-11,4.73e-10,2.93e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21390000,-0.257,0.00729,-0.00177,0.966,0.0386,-0.0253,-0.688,0.00664,0.00971,0.706,-1.2e-05,-5.91e-05,4.02e-07,-2.94e-05,6.06e-05,-0.0013,-0.202,-0.0311,0.435,0,0,0,0,0,9.71e-05,8.24e-05,8.25e-05,0.000332,0.00776,0.00775,0.00576,0.0255,0.0255,0.0257,7.34e-11,7.34e-11,4.65e-10,2.92e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21490000,-0.257,0.00776,-0.00254,0.966,0.0334,-0.0226,-0.825,0.0103,0.0073,0.623,-1.2e-05,-5.91e-05,6.05e-07,-2.99e-05,6.08e-05,-0.0013,-0.202,-0.0311,0.435,0,0,0,0,0,9.66e-05,8.27e-05,8.27e-05,0.000332,0.00864,0.00864,0.00594,0.0271,0.0271,0.0261,7.35e-11,7.35e-11,4.56e-10,2.92e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21590000,-0.257,0.00813,-0.00358,0.966,0.0132,-0.00677,-0.936,-0.00101,0.0194,0.555,-1.11e-05,-5.89e-05,8.42e-07,-8.04e-06,-4.5e-06,-0.00133,-0.202,-0.0311,0.435,0,0,0,0,0,9.61e-05,8.09e-05,8.1e-05,0.000332,0.0079,0.0079,0.00575,0.027,0.027,0.0256,6.96e-11,6.96e-11,4.47e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21690000,-0.257,0.00801,-0.00394,0.966,0.0096,-0.00175,-1.07,0.00012,0.019,0.445,-1.11e-05,-5.89e-05,1.13e-06,-8.6e-06,-4.22e-06,-0.00133,-0.202,-0.0311,0.435,0,0,0,0,0,9.59e-05,8.11e-05,8.12e-05,0.000332,0.00877,0.00878,0.00594,0.0288,0.0288,0.0261,6.97e-11,6.97e-11,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21790000,-0.257,0.00825,-0.00472,0.966,-0.000129,0.0143,-1.19,-0.00516,0.0315,0.345,-1.05e-05,-5.89e-05,1.51e-06,-6.12e-06,-5.53e-05,-0.00135,-0.202,-0.0311,0.435,0,0,0,0,0,9.54e-05,7.92e-05,7.93e-05,0.000332,0.00798,0.00798,0.00575,0.0286,0.0286,0.0257,6.62e-11,6.62e-11,4.32e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21890000,-0.257,0.00841,-0.00502,0.966,-0.00509,0.0197,-1.31,-0.00542,0.0332,0.208,-1.05e-05,-5.89e-05,1.56e-06,-6.96e-06,-5.45e-05,-0.00135,-0.202,-0.0311,0.435,0,0,0,0,0,9.49e-05,7.94e-05,7.95e-05,0.000332,0.00883,0.00883,0.00593,0.0304,0.0304,0.026,6.63e-11,6.63e-11,4.23e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21990000,-0.257,0.00905,-0.00605,0.966,-0.018,0.0317,-1.28,-0.0175,0.0438,0.0853,-9.96e-06,-5.87e-05,1.83e-06,1.51e-05,-0.0001,-0.00136,-0.202,-0.0311,0.435,0,0,0,0,0,9.46e-05,7.75e-05,7.75e-05,0.000332,0.00784,0.00784,0.00576,0.0302,0.0302,0.0258,6.31e-11,6.31e-11,4.16e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22090000,-0.257,0.0099,-0.00672,0.966,-0.0221,0.0368,-1.27,-0.0195,0.0473,-0.0542,-9.95e-06,-5.87e-05,2.22e-06,1.39e-05,-9.94e-05,-0.00136,-0.202,-0.0311,0.435,0,0,0,0,0,9.41e-05,7.77e-05,7.77e-05,0.000332,0.0085,0.00851,0.00594,0.032,0.032,0.0261,6.32e-11,6.32e-11,4.09e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22190000,-0.256,0.0103,-0.0073,0.967,-0.034,0.0451,-1.29,-0.0279,0.0562,-0.202,-9.68e-06,-5.86e-05,2.57e-06,1.72e-05,-0.000112,-0.00135,-0.202,-0.0311,0.435,0,0,0,0,0,9.36e-05,7.62e-05,7.63e-05,0.000332,0.00763,0.00764,0.00575,0.0318,0.0318,0.0257,6.04e-11,6.04e-11,4.01e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22290000,-0.256,0.0106,-0.00801,0.967,-0.0413,0.0513,-1.29,-0.0317,0.061,-0.343,-9.68e-06,-5.86e-05,2.66e-06,1.64e-05,-0.000112,-0.00134,-0.202,-0.0311,0.435,0,0,0,0,0,9.32e-05,7.64e-05,7.65e-05,0.000332,0.00829,0.0083,0.00592,0.0336,0.0336,0.026,6.05e-11,6.05e-11,3.94e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22390000,-0.256,0.0109,-0.00817,0.966,-0.0501,0.0535,-1.3,-0.04,0.0615,-0.498,-9.76e-06,-5.84e-05,2.6e-06,2.3e-05,-0.000101,-0.00132,-0.202,-0.0311,0.435,0,0,0,0,0,9.29e-05,7.53e-05,7.54e-05,0.000332,0.00746,0.00747,0.00575,0.0334,0.0334,0.0257,5.8e-11,5.8e-11,3.87e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22490000,-0.256,0.0113,-0.00829,0.966,-0.0564,0.0605,-1.31,-0.0453,0.0672,-0.638,-9.76e-06,-5.84e-05,2.61e-06,2.23e-05,-0.0001,-0.00132,-0.202,-0.0311,0.435,0,0,0,0,0,9.25e-05,7.55e-05,7.55e-05,0.000332,0.00811,0.00812,0.00593,0.0352,0.0352,0.0261,5.81e-11,5.81e-11,3.8e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22590000,-0.256,0.0117,-0.008,0.966,-0.0571,0.0641,-1.32,-0.0431,0.0688,-0.789,-1e-05,-5.86e-05,2.92e-06,1.15e-05,-8.42e-05,-0.0013,-0.202,-0.0311,0.435,0,0,0,0,0,9.2e-05,7.46e-05,7.47e-05,0.000332,0.00733,0.00733,0.00574,0.0349,0.0349,0.0256,5.59e-11,5.58e-11,3.74e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22690000,-0.256,0.0119,-0.00791,0.966,-0.0612,0.0697,-1.32,-0.0491,0.0756,-0.931,-1e-05,-5.86e-05,2.95e-06,1.08e-05,-8.34e-05,-0.0013,-0.202,-0.0311,0.435,0,0,0,0,0,9.18e-05,7.48e-05,7.48e-05,0.000332,0.00796,0.00797,0.00593,0.0368,0.0368,0.0261,5.6e-11,5.59e-11,3.68e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22790000,-0.256,0.0123,-0.00768,0.967,-0.0655,0.0692,-1.33,-0.0528,0.0738,-1.09,-1.03e-05,-5.85e-05,2.92e-06,9.07e-06,-6.9e-05,-0.00128,-0.202,-0.0311,0.435,0,0,0,0,0,9.13e-05,7.41e-05,7.41e-05,0.000332,0.00721,0.00722,0.00574,0.0365,0.0365,0.0257,5.39e-11,5.39e-11,3.61e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22890000,-0.256,0.0127,-0.00782,0.967,-0.071,0.0755,-1.34,-0.0596,0.081,-1.23,-1.03e-05,-5.85e-05,3.21e-06,8.05e-06,-6.77e-05,-0.00127,-0.202,-0.0311,0.435,0,0,0,0,0,9.08e-05,7.42e-05,7.43e-05,0.000332,0.00784,0.00784,0.00592,0.0384,0.0384,0.026,5.4e-11,5.4e-11,3.55e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22990000,-0.255,0.013,-0.00751,0.967,-0.0724,0.07,-1.35,-0.0621,0.0759,-1.39,-1.07e-05,-5.85e-05,3.44e-06,5.53e-06,-5.29e-05,-0.00126,-0.202,-0.0311,0.435,0,0,0,0,0,9.05e-05,7.37e-05,7.38e-05,0.000332,0.00712,0.00712,0.00575,0.0381,0.0381,0.0258,5.22e-11,5.21e-11,3.49e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23090000,-0.255,0.0133,-0.00752,0.967,-0.0791,0.075,-1.35,-0.0697,0.0832,-1.53,-1.07e-05,-5.85e-05,3.52e-06,5.05e-06,-5.23e-05,-0.00125,-0.202,-0.0311,0.435,0,0,0,0,0,9e-05,7.39e-05,7.39e-05,0.000332,0.00773,0.00773,0.00593,0.04,0.04,0.0261,5.22e-11,5.22e-11,3.43e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23190000,-0.255,0.0134,-0.00721,0.967,-0.0767,0.0627,-1.36,-0.0665,0.0737,-1.69,-1.12e-05,-5.85e-05,3.45e-06,7.19e-07,-3.87e-05,-0.00124,-0.202,-0.0311,0.435,0,0,0,0,0,8.96e-05,7.35e-05,7.35e-05,0.000331,0.00704,0.00704,0.00574,0.0396,0.0396,0.0257,5.05e-11,5.04e-11,3.37e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23290000,-0.254,0.0136,-0.00767,0.967,-0.0832,0.0675,-1.36,-0.0745,0.0802,-1.83,-1.12e-05,-5.85e-05,3.54e-06,2.1e-07,-3.8e-05,-0.00123,-0.202,-0.0311,0.435,0,0,0,0,0,8.93e-05,7.36e-05,7.36e-05,0.000332,0.00764,0.00764,0.00593,0.0415,0.0415,0.0262,5.06e-11,5.05e-11,3.32e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23390000,-0.254,0.0135,-0.00747,0.967,-0.0769,0.0656,-1.36,-0.0662,0.0785,-1.98,-1.16e-05,-5.88e-05,3.38e-06,-3.92e-06,-3.25e-05,-0.00122,-0.202,-0.0311,0.435,0,0,0,0,0,8.89e-05,7.33e-05,7.33e-05,0.000331,0.00697,0.00697,0.00574,0.0412,0.0412,0.0257,4.9e-11,4.89e-11,3.26e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23490000,-0.254,0.0138,-0.00754,0.967,-0.0818,0.0677,-1.37,-0.0742,0.0852,-2.12,-1.16e-05,-5.88e-05,3.55e-06,-4.29e-06,-3.18e-05,-0.00122,-0.202,-0.0311,0.435,0,0,0,0,0,8.84e-05,7.34e-05,7.34e-05,0.000331,0.00757,0.00757,0.00592,0.0431,0.0431,0.0261,4.91e-11,4.9e-11,3.21e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23590000,-0.254,0.0136,-0.00753,0.967,-0.0769,0.0548,-1.37,-0.0684,0.0717,-2.27,-1.23e-05,-5.89e-05,3.62e-06,-5.35e-06,-2.98e-05,-0.00121,-0.202,-0.0311,0.435,0,0,0,0,0,8.8e-05,7.32e-05,7.32e-05,0.000331,0.00691,0.00691,0.00573,0.0427,0.0427,0.0256,4.76e-11,4.75e-11,3.16e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23690000,-0.254,0.0143,-0.00814,0.967,-0.0758,0.0573,-1.26,-0.0761,0.0774,-2.41,-1.23e-05,-5.89e-05,3.76e-06,-5.55e-06,-2.93e-05,-0.00121,-0.202,-0.0311,0.435,0,0,0,0,0,8.78e-05,7.33e-05,7.33e-05,0.000331,0.00745,0.00745,0.00593,0.0447,0.0447,0.0261,4.77e-11,4.76e-11,3.11e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23790000,-0.254,0.0171,-0.00968,0.967,-0.0571,0.0498,-0.945,-0.0639,0.0722,-2.55,-1.27e-05,-5.92e-05,3.92e-06,-1.24e-06,-3.51e-05,-0.00119,-0.202,-0.0311,0.435,0,0,0,0,0,8.74e-05,7.33e-05,7.33e-05,0.000331,0.00674,0.00674,0.00574,0.0443,0.0443,0.0257,4.63e-11,4.62e-11,3.06e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23890000,-0.254,0.0214,-0.0127,0.967,-0.0534,0.0505,-0.516,-0.0694,0.0772,-2.62,-1.27e-05,-5.92e-05,3.92e-06,-1.65e-06,-3.45e-05,-0.00119,-0.202,-0.0311,0.435,0,0,0,0,0,8.7e-05,7.34e-05,7.34e-05,0.000331,0.00729,0.00729,0.00592,0.0462,0.0462,0.026,4.64e-11,4.63e-11,3.01e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23990000,-0.253,0.0239,-0.0147,0.967,-0.0437,0.044,-0.176,-0.0581,0.0707,-2.74,-1.32e-05,-5.94e-05,3.91e-06,2.1e-05,-7.2e-05,-0.0011,-0.202,-0.0311,0.435,0,0,0,0,0,8.67e-05,7.36e-05,7.36e-05,0.000331,0.00676,0.00676,0.00574,0.0458,0.0458,0.0258,4.52e-11,4.51e-11,2.96e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24090000,-0.253,0.0227,-0.0143,0.967,-0.0512,0.0508,0.0549,-0.0628,0.0754,-2.75,-1.32e-05,-5.94e-05,3.81e-06,2.09e-05,-7.22e-05,-0.0011,-0.202,-0.0311,0.435,0,0,0,0,0,8.63e-05,7.37e-05,7.37e-05,0.000331,0.0074,0.0074,0.00592,0.0477,0.0477,0.0261,4.53e-11,4.52e-11,2.91e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24190000,-0.253,0.0189,-0.0119,0.967,-0.0498,0.0432,0.00881,-0.0499,0.0623,-2.81,-1.37e-05,-5.95e-05,3.92e-06,5.68e-05,-0.00017,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,8.59e-05,7.36e-05,7.36e-05,0.000331,0.00676,0.00676,0.00573,0.0474,0.0474,0.0257,4.42e-11,4.41e-11,2.87e-10,2.77e-06,2.77e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24290000,-0.253,0.0154,-0.00974,0.967,-0.0532,0.0454,-0.0143,-0.0551,0.0668,-2.81,-1.37e-05,-5.95e-05,3.93e-06,5.68e-05,-0.00017,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,8.57e-05,7.36e-05,7.37e-05,0.000331,0.00731,0.00732,0.00593,0.0493,0.0493,0.0262,4.43e-11,4.42e-11,2.83e-10,2.77e-06,2.77e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24390000,-0.253,0.0145,-0.0091,0.967,-0.0305,0.0358,0.00462,-0.0369,0.0589,-2.8,-1.42e-05,-5.98e-05,4.16e-06,0.000103,-0.000241,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,8.53e-05,7.37e-05,7.37e-05,0.000331,0.00671,0.00671,0.00574,0.0489,0.0489,0.0257,4.32e-11,4.31e-11,2.78e-10,2.75e-06,2.75e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24490000,-0.253,0.0146,-0.00932,0.967,-0.0242,0.0326,0.000897,-0.0396,0.0623,-2.8,-1.42e-05,-5.98e-05,4.42e-06,0.000103,-0.000241,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,8.5e-05,7.38e-05,7.38e-05,0.000331,0.00727,0.00727,0.00592,0.0509,0.0509,0.0261,4.33e-11,4.32e-11,2.74e-10,2.75e-06,2.75e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24590000,-0.253,0.0148,-0.0101,0.967,-0.00794,0.0287,-0.00285,-0.0228,0.0582,-2.8,-1.46e-05,-6.01e-05,4.44e-06,0.00014,-0.000285,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,8.48e-05,7.39e-05,7.4e-05,0.000331,0.00667,0.00667,0.00575,0.0505,0.0505,0.0258,4.23e-11,4.22e-11,2.7e-10,2.73e-06,2.73e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24690000,-0.253,0.0146,-0.0106,0.967,-0.00399,0.0276,-0.00475,-0.0235,0.0609,-2.79,-1.46e-05,-6.01e-05,4.45e-06,0.00014,-0.000285,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,8.44e-05,7.41e-05,7.41e-05,0.000331,0.00724,0.00724,0.00593,0.0524,0.0524,0.0261,4.24e-11,4.23e-11,2.66e-10,2.73e-06,2.73e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24790000,-0.253,0.014,-0.0107,0.967,0.00516,0.0245,-0.00773,-0.0138,0.0552,-2.79,-1.48e-05,-6.02e-05,4.52e-06,0.000149,-0.000312,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,8.4e-05,7.42e-05,7.42e-05,0.000331,0.00665,0.00665,0.00574,0.0521,0.0521,0.0257,4.13e-11,4.13e-11,2.61e-10,2.71e-06,2.71e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24890000,-0.253,0.0134,-0.0106,0.967,0.00812,0.0272,-0.0192,-0.0132,0.0577,-2.79,-1.48e-05,-6.02e-05,4.61e-06,0.000149,-0.000312,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,8.37e-05,7.43e-05,7.44e-05,0.000331,0.00721,0.00722,0.00592,0.054,0.054,0.026,4.14e-11,4.14e-11,2.57e-10,2.71e-06,2.71e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24990000,-0.253,0.0132,-0.0104,0.967,0.0222,0.0267,-0.0225,-0.00265,0.0545,-2.78,-1.5e-05,-6.03e-05,4.64e-06,0.000158,-0.00033,-0.00107,-0.202,-0.0311,0.435,0,0,0,0,0,8.35e-05,7.45e-05,7.45e-05,0.000331,0.00663,0.00663,0.00575,0.0536,0.0536,0.0257,4.05e-11,4.04e-11,2.54e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25090000,-0.253,0.0132,-0.0107,0.967,0.0277,0.0256,-0.0257,-0.000153,0.0571,-2.79,-1.5e-05,-6.03e-05,4.62e-06,0.000158,-0.00033,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,8.31e-05,7.46e-05,7.47e-05,0.000331,0.0072,0.0072,0.00593,0.0555,0.0555,0.0261,4.06e-11,4.05e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25190000,-0.253,0.0131,-0.011,0.967,0.038,0.0186,-0.025,0.00998,0.0493,-2.79,-1.53e-05,-6.03e-05,4.55e-06,0.00016,-0.00035,-0.00107,-0.202,-0.0311,0.435,0,0,0,0,0,8.28e-05,7.48e-05,7.48e-05,0.00033,0.00662,0.00663,0.00574,0.0552,0.0552,0.0256,3.96e-11,3.96e-11,2.46e-10,2.69e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25290000,-0.254,0.0124,-0.0111,0.967,0.0448,0.0197,-0.0312,0.0141,0.0512,-2.79,-1.53e-05,-6.03e-05,4.4e-06,0.00016,-0.00035,-0.00107,-0.202,-0.0311,0.435,0,0,0,0,0,8.26e-05,7.49e-05,7.5e-05,0.00033,0.00719,0.0072,0.00594,0.0571,0.0571,0.0261,3.97e-11,3.96e-11,2.43e-10,2.69e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25390000,-0.254,0.0122,-0.0113,0.967,0.0509,0.0179,-0.0318,0.0177,0.0488,-2.79,-1.54e-05,-6.03e-05,4.42e-06,0.000155,-0.000355,-0.00107,-0.202,-0.0311,0.435,0,0,0,0,0,8.22e-05,7.5e-05,7.51e-05,0.00033,0.00662,0.00662,0.00575,0.0568,0.0568,0.0257,3.88e-11,3.87e-11,2.39e-10,2.69e-06,2.69e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25490000,-0.254,0.0119,-0.0113,0.967,0.0581,0.0176,-0.0332,0.0232,0.0506,-2.79,-1.54e-05,-6.03e-05,4.36e-06,0.000155,-0.000355,-0.00107,-0.202,-0.0311,0.435,0,0,0,0,0,8.19e-05,7.52e-05,7.53e-05,0.00033,0.00718,0.00719,0.00593,0.0586,0.0586,0.026,3.89e-11,3.88e-11,2.36e-10,2.69e-06,2.69e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25590000,-0.254,0.0118,-0.0115,0.967,0.06,0.0101,-0.0293,0.0251,0.0395,-2.79,-1.55e-05,-6.01e-05,4.29e-06,0.000143,-0.000364,-0.00108,-0.202,-0.0311,0.435,0,0,0,0,0,8.17e-05,7.53e-05,7.54e-05,0.000329,0.00661,0.00662,0.00576,0.0583,0.0583,0.0258,3.8e-11,3.8e-11,2.32e-10,2.69e-06,2.69e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25690000,-0.254,0.0114,-0.011,0.967,0.0629,0.00849,-0.0404,0.0312,0.0404,-2.79,-1.55e-05,-6.01e-05,4.31e-06,0.000143,-0.000364,-0.00108,-0.202,-0.0311,0.435,0,0,0,0,0,8.14e-05,7.54e-05,7.55e-05,0.000329,0.00717,0.00719,0.00594,0.0602,0.0602,0.0261,3.81e-11,3.81e-11,2.29e-10,2.69e-06,2.69e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25790000,-0.254,0.0107,-0.0108,0.967,0.0692,0.0026,-0.0388,0.0326,0.0349,-2.79,-1.56e-05,-5.99e-05,4.28e-06,0.000135,-0.000365,-0.00108,-0.202,-0.0311,0.435,0,0,0,0,0,8.1e-05,7.55e-05,7.56e-05,0.000329,0.0066,0.00661,0.00575,0.0599,0.0599,0.0257,3.72e-11,3.72e-11,2.26e-10,2.69e-06,2.69e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25890000,-0.254,0.0108,-0.0108,0.967,0.0769,0.000345,-0.0371,0.04,0.0351,-2.79,-1.56e-05,-5.99e-05,4.08e-06,0.000135,-0.000365,-0.00108,-0.202,-0.0311,0.435,0,0,0,0,0,8.08e-05,7.56e-05,7.57e-05,0.000329,0.00716,0.00718,0.00595,0.0618,0.0618,0.0262,3.73e-11,3.73e-11,2.23e-10,2.69e-06,2.69e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25990000,-0.254,0.0111,-0.0109,0.967,0.071,-0.00572,-0.0426,0.0307,0.0284,-2.79,-1.55e-05,-5.95e-05,4.04e-06,0.000122,-0.000364,-0.00108,-0.202,-0.0311,0.435,0,0,0,0,0,8.05e-05,7.57e-05,7.58e-05,0.000328,0.00659,0.00661,0.00576,0.0615,0.0615,0.0257,3.65e-11,3.65e-11,2.2e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26090000,-0.253,0.0111,-0.0106,0.967,0.0773,-0.00615,-0.0442,0.0381,0.0278,-2.79,-1.55e-05,-5.95e-05,4.14e-06,0.000122,-0.000364,-0.00108,-0.202,-0.0311,0.435,0,0,0,0,0,8.01e-05,7.58e-05,7.59e-05,0.000328,0.00715,0.00718,0.00594,0.0633,0.0633,0.0261,3.66e-11,3.66e-11,2.16e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26190000,-0.253,0.0117,-0.0104,0.967,0.0753,-0.0165,-0.0461,0.0356,0.0174,-2.8,-1.56e-05,-5.93e-05,4.22e-06,0.000113,-0.000364,-0.00109,-0.202,-0.0311,0.435,0,0,0,0,0,7.98e-05,7.58e-05,7.59e-05,0.000328,0.00658,0.00661,0.00575,0.063,0.063,0.0256,3.58e-11,3.58e-11,2.13e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26290000,-0.253,0.012,-0.0104,0.967,0.0779,-0.0186,-0.0523,0.0433,0.0157,-2.8,-1.56e-05,-5.93e-05,4.1e-06,0.000113,-0.000363,-0.00109,-0.202,-0.0311,0.435,0,0,0,0,0,7.96e-05,7.6e-05,7.61e-05,0.000328,0.00714,0.00717,0.00595,0.0649,0.0649,0.0261,3.59e-11,3.59e-11,2.11e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26390000,-0.253,0.0121,-0.00984,0.967,0.0672,-0.0281,-0.0453,0.0319,0.00666,-2.8,-1.55e-05,-5.89e-05,4e-06,0.000105,-0.000361,-0.00109,-0.202,-0.0311,0.435,0,0,0,0,0,7.92e-05,7.59e-05,7.6e-05,0.000327,0.00657,0.0066,0.00576,0.0646,0.0646,0.0257,3.51e-11,3.51e-11,2.08e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26490000,-0.253,0.0119,-0.0096,0.967,0.0713,-0.032,-0.0363,0.0388,0.00366,-2.8,-1.55e-05,-5.89e-05,3.93e-06,0.000105,-0.00036,-0.0011,-0.202,-0.0311,0.435,0,0,0,0,0,7.89e-05,7.61e-05,7.62e-05,0.000327,0.00712,0.00716,0.00594,0.0665,0.0665,0.026,3.52e-11,3.52e-11,2.05e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26590000,-0.253,0.0123,-0.00902,0.967,0.0643,-0.0416,-0.0367,0.0348,-0.00368,-2.8,-1.55e-05,-5.87e-05,3.83e-06,0.000103,-0.000361,-0.0011,-0.202,-0.0311,0.435,0,0,0,0,0,7.87e-05,7.6e-05,7.61e-05,0.000327,0.00655,0.00659,0.00577,0.0662,0.0662,0.0258,3.45e-11,3.45e-11,2.02e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26690000,-0.253,0.012,-0.0089,0.967,0.067,-0.0476,-0.0384,0.0414,-0.00815,-2.8,-1.55e-05,-5.86e-05,3.63e-06,0.000102,-0.000361,-0.0011,-0.202,-0.0311,0.435,0,0,0,0,0,7.84e-05,7.62e-05,7.63e-05,0.000327,0.0071,0.00715,0.00595,0.068,0.068,0.0261,3.46e-11,3.46e-11,1.99e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26790000,-0.253,0.0116,-0.00872,0.967,0.0633,-0.0533,-0.0374,0.0359,-0.0157,-2.8,-1.54e-05,-5.84e-05,3.55e-06,0.000101,-0.000361,-0.0011,-0.202,-0.0311,0.435,0,0,0,0,0,7.81e-05,7.61e-05,7.62e-05,0.000326,0.00654,0.00658,0.00576,0.0678,0.0678,0.0257,3.39e-11,3.39e-11,1.97e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26890000,-0.253,0.0117,-0.00805,0.967,0.0692,-0.0571,-0.0423,0.0425,-0.0213,-2.8,-1.54e-05,-5.84e-05,3.59e-06,0.0001,-0.00036,-0.0011,-0.202,-0.0311,0.435,0,0,0,0,0,7.79e-05,7.62e-05,7.63e-05,0.000326,0.00709,0.00714,0.00595,0.0696,0.0696,0.0262,3.4e-11,3.4e-11,1.94e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26990000,-0.253,0.0122,-0.00757,0.967,0.0637,-0.0608,-0.0416,0.0345,-0.0234,-2.81,-1.52e-05,-5.82e-05,3.52e-06,9.99e-05,-0.000361,-0.0011,-0.202,-0.0311,0.435,0,0,0,0,0,7.76e-05,7.61e-05,7.62e-05,0.000326,0.00653,0.00657,0.00576,0.0694,0.0694,0.0257,3.33e-11,3.33e-11,1.92e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27090000,-0.253,0.0125,-0.00738,0.967,0.0663,-0.0688,-0.0382,0.0411,-0.0299,-2.81,-1.52e-05,-5.82e-05,3.46e-06,0.0001,-0.000361,-0.0011,-0.202,-0.0311,0.435,0,0,0,0,0,7.73e-05,7.63e-05,7.64e-05,0.000326,0.00707,0.00712,0.00594,0.0712,0.0712,0.0261,3.34e-11,3.34e-11,1.89e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27190000,-0.253,0.0126,-0.00754,0.967,0.0598,-0.0687,-0.0337,0.0313,-0.0286,-2.81,-1.49e-05,-5.8e-05,3.4e-06,9.94e-05,-0.000361,-0.00111,-0.202,-0.0311,0.435,0,0,0,0,0,7.71e-05,7.61e-05,7.62e-05,0.000325,0.00651,0.00655,0.00577,0.071,0.071,0.0258,3.28e-11,3.27e-11,1.87e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27290000,-0.253,0.0136,-0.00764,0.967,0.0665,-0.0751,0.0805,0.0376,-0.0359,-2.81,-1.49e-05,-5.8e-05,3.36e-06,9.94e-05,-0.000361,-0.00111,-0.202,-0.0311,0.435,0,0,0,0,0,7.68e-05,7.63e-05,7.64e-05,0.000325,0.00701,0.00705,0.00595,0.0728,0.0728,0.0261,3.29e-11,3.28e-11,1.84e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27390000,-0.253,0.0162,-0.00906,0.967,0.0652,-0.0689,0.398,0.026,-0.0195,-2.8,-1.46e-05,-5.8e-05,3.32e-06,0.000101,-0.000368,-0.00109,-0.202,-0.0311,0.435,0,0,0,0,0,7.65e-05,7.63e-05,7.63e-05,0.000325,0.00617,0.00621,0.00576,0.0566,0.0566,0.0257,3.23e-11,3.22e-11,1.82e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27490000,-0.253,0.0182,-0.0103,0.967,0.0687,-0.0754,0.71,0.0327,-0.0267,-2.74,-1.46e-05,-5.8e-05,3.16e-06,0.0001,-0.000367,-0.00109,-0.202,-0.0311,0.435,0,0,0,0,0,7.62e-05,7.64e-05,7.65e-05,0.000325,0.00665,0.00669,0.00594,0.058,0.058,0.026,3.24e-11,3.23e-11,1.79e-10,2.68e-06,2.68e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27590000,-0.253,0.0171,-0.0104,0.967,0.0532,-0.0728,0.781,0.0212,-0.0197,-2.71,-1.43e-05,-5.79e-05,3.15e-06,9.89e-05,-0.000373,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,7.6e-05,7.66e-05,7.67e-05,0.000324,0.00604,0.00608,0.00577,0.0474,0.0474,0.0257,3.19e-11,3.18e-11,1.77e-10,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27690000,-0.253,0.0141,-0.00935,0.967,0.048,-0.0704,0.685,0.0262,-0.027,-2.63,-1.43e-05,-5.79e-05,3.16e-06,9.88e-05,-0.000373,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,7.57e-05,7.67e-05,7.68e-05,0.000324,0.00656,0.0066,0.00594,0.0486,0.0486,0.0261,3.2e-11,3.19e-11,1.75e-10,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27790000,-0.253,0.0125,-0.00809,0.967,0.0404,-0.0634,0.689,0.0194,-0.0219,-2.55,-1.41e-05,-5.78e-05,3.18e-06,8.88e-05,-0.000341,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.54e-05,7.68e-05,7.69e-05,0.000324,0.00601,0.00604,0.00575,0.0411,0.0411,0.0256,3.15e-11,3.14e-11,1.73e-10,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27890000,-0.253,0.0126,-0.00772,0.967,0.0469,-0.07,0.728,0.0237,-0.0285,-2.47,-1.41e-05,-5.78e-05,3.15e-06,8.87e-05,-0.000341,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.53e-05,7.69e-05,7.7e-05,0.000324,0.00652,0.00656,0.00595,0.0422,0.0422,0.0262,3.16e-11,3.15e-11,1.71e-10,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27990000,-0.253,0.013,-0.00818,0.967,0.0438,-0.0675,0.714,0.0233,-0.0286,-2.4,-1.38e-05,-5.78e-05,3.13e-06,8.73e-05,-0.00033,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,7.5e-05,7.71e-05,7.72e-05,0.000324,0.0061,0.00612,0.00576,0.0425,0.0425,0.0257,3.11e-11,3.1e-11,1.68e-10,2.67e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28090000,-0.253,0.013,-0.00844,0.967,0.046,-0.0681,0.721,0.0278,-0.0354,-2.33,-1.38e-05,-5.78e-05,3.24e-06,8.68e-05,-0.000329,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.47e-05,7.72e-05,7.73e-05,0.000324,0.00662,0.00665,0.00594,0.0437,0.0437,0.0261,3.12e-11,3.11e-11,1.66e-10,2.67e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28190000,-0.253,0.0133,-0.0079,0.967,0.039,-0.0615,0.728,0.024,-0.0349,-2.25,-1.36e-05,-5.77e-05,3.22e-06,8.12e-05,-0.000316,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.46e-05,7.73e-05,7.74e-05,0.000323,0.00616,0.00618,0.00576,0.044,0.044,0.0258,3.07e-11,3.06e-11,1.64e-10,2.67e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28290000,-0.253,0.0135,-0.00737,0.967,0.043,-0.0646,0.728,0.0281,-0.0413,-2.18,-1.36e-05,-5.77e-05,3.32e-06,8.14e-05,-0.000316,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.43e-05,7.74e-05,7.75e-05,0.000323,0.00669,0.00671,0.00594,0.0453,0.0453,0.0261,3.08e-11,3.07e-11,1.62e-10,2.67e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28390000,-0.253,0.0141,-0.00741,0.967,0.0414,-0.06,0.733,0.0273,-0.0376,-2.1,-1.33e-05,-5.77e-05,3.37e-06,8.04e-05,-0.000306,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.41e-05,7.75e-05,7.76e-05,0.000323,0.00622,0.00624,0.00575,0.0455,0.0455,0.0257,3.03e-11,3.02e-11,1.6e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28490000,-0.253,0.0146,-0.00768,0.967,0.0419,-0.0639,0.734,0.0314,-0.0437,-2.03,-1.33e-05,-5.77e-05,3.35e-06,8.03e-05,-0.000305,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.39e-05,7.77e-05,7.77e-05,0.000323,0.00675,0.00677,0.00594,0.0469,0.0469,0.0262,3.04e-11,3.03e-11,1.59e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28590000,-0.253,0.0146,-0.00773,0.967,0.0316,-0.06,0.735,0.0283,-0.0444,-1.95,-1.32e-05,-5.76e-05,3.42e-06,7.78e-05,-0.0003,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.37e-05,7.76e-05,7.77e-05,0.000323,0.00626,0.00628,0.00575,0.0471,0.0471,0.0257,2.99e-11,2.98e-11,1.57e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28690000,-0.253,0.0139,-0.00753,0.967,0.0302,-0.061,0.736,0.0315,-0.0505,-1.87,-1.32e-05,-5.76e-05,3.37e-06,7.75e-05,-0.0003,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.34e-05,7.78e-05,7.79e-05,0.000323,0.00679,0.0068,0.00593,0.0485,0.0485,0.0261,3e-11,2.99e-11,1.55e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28790000,-0.253,0.0136,-0.007,0.967,0.0266,-0.0533,0.735,0.0308,-0.0441,-1.8,-1.29e-05,-5.77e-05,3.46e-06,7.78e-05,-0.0003,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.32e-05,7.77e-05,7.78e-05,0.000323,0.0063,0.0063,0.00574,0.0487,0.0487,0.0256,2.95e-11,2.94e-11,1.53e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28890000,-0.253,0.0134,-0.00686,0.967,0.0294,-0.0545,0.734,0.0336,-0.0495,-1.73,-1.29e-05,-5.77e-05,3.54e-06,7.8e-05,-0.0003,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.3e-05,7.79e-05,7.8e-05,0.000323,0.00683,0.00683,0.00593,0.0502,0.0502,0.0261,2.96e-11,2.95e-11,1.51e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28990000,-0.253,0.0135,-0.00666,0.967,0.0265,-0.0488,0.734,0.0329,-0.0469,-1.66,-1.27e-05,-5.77e-05,3.53e-06,7.78e-05,-0.000302,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.28e-05,7.78e-05,7.78e-05,0.000323,0.00632,0.00632,0.00574,0.0502,0.0502,0.0257,2.91e-11,2.9e-11,1.49e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29090000,-0.253,0.0136,-0.0065,0.967,0.0278,-0.0504,0.734,0.0357,-0.0518,-1.58,-1.27e-05,-5.77e-05,3.55e-06,7.76e-05,-0.000301,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.25e-05,7.79e-05,7.8e-05,0.000323,0.00685,0.00685,0.00592,0.0518,0.0518,0.026,2.92e-11,2.91e-11,1.47e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29190000,-0.253,0.0137,-0.00651,0.967,0.0282,-0.045,0.729,0.037,-0.0475,-1.51,-1.26e-05,-5.78e-05,3.63e-06,7.72e-05,-0.000306,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.24e-05,7.78e-05,7.78e-05,0.000323,0.00634,0.00634,0.00575,0.0518,0.0518,0.0258,2.88e-11,2.86e-11,1.46e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29290000,-0.253,0.0137,-0.00677,0.967,0.0295,-0.0503,0.732,0.0398,-0.0523,-1.43,-1.26e-05,-5.78e-05,3.68e-06,7.71e-05,-0.000306,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.22e-05,7.79e-05,7.8e-05,0.000323,0.00686,0.00687,0.00592,0.0534,0.0534,0.0261,2.89e-11,2.87e-11,1.44e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29390000,-0.253,0.0132,-0.00737,0.967,0.025,-0.0426,0.736,0.0371,-0.0457,-1.36,-1.23e-05,-5.78e-05,3.74e-06,7.58e-05,-0.000311,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.19e-05,7.77e-05,7.78e-05,0.000323,0.00634,0.00635,0.00573,0.0534,0.0534,0.0257,2.84e-11,2.83e-11,1.42e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29490000,-0.253,0.013,-0.00738,0.967,0.0264,-0.0424,0.738,0.0397,-0.05,-1.28,-1.23e-05,-5.78e-05,3.88e-06,7.6e-05,-0.000311,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.18e-05,7.79e-05,7.8e-05,0.000323,0.00687,0.00687,0.00593,0.0551,0.0551,0.0262,2.85e-11,2.84e-11,1.41e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29590000,-0.252,0.013,-0.00734,0.968,0.0228,-0.0376,0.743,0.037,-0.0459,-1.2,-1.22e-05,-5.78e-05,4.01e-06,7.51e-05,-0.000314,-0.00107,-0.202,-0.0311,0.435,0,0,0,0,0,7.16e-05,7.76e-05,7.77e-05,0.000323,0.00635,0.00635,0.00574,0.055,0.055,0.0257,2.81e-11,2.79e-11,1.39e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29690000,-0.252,0.0128,-0.0074,0.968,0.0254,-0.0351,0.74,0.0394,-0.0496,-1.12,-1.22e-05,-5.78e-05,4.14e-06,7.54e-05,-0.000314,-0.00107,-0.202,-0.0311,0.435,0,0,0,0,0,7.14e-05,7.78e-05,7.79e-05,0.000323,0.00687,0.00687,0.00591,0.0567,0.0567,0.0261,2.82e-11,2.8e-11,1.38e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29790000,-0.252,0.0133,-0.00726,0.968,0.0226,-0.0255,0.737,0.037,-0.0441,-1.05,-1.2e-05,-5.78e-05,4.26e-06,7.55e-05,-0.000322,-0.00107,-0.202,-0.0311,0.435,0,0,0,0,0,7.13e-05,7.75e-05,7.76e-05,0.000323,0.00635,0.00635,0.00574,0.0566,0.0566,0.0258,2.77e-11,2.76e-11,1.36e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29890000,-0.252,0.0136,-0.00672,0.968,0.022,-0.0259,0.735,0.0391,-0.0466,-0.977,-1.2e-05,-5.78e-05,4.38e-06,7.59e-05,-0.000322,-0.00107,-0.202,-0.0311,0.435,0,0,0,0,0,7.1e-05,7.77e-05,7.78e-05,0.000323,0.00687,0.00687,0.00592,0.0583,0.0583,0.0261,2.78e-11,2.77e-11,1.35e-10,2.66e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29990000,-0.252,0.0137,-0.00687,0.968,0.0169,-0.0232,0.731,0.0348,-0.0458,-0.908,-1.19e-05,-5.78e-05,4.42e-06,7.95e-05,-0.000328,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.08e-05,7.74e-05,7.75e-05,0.000323,0.00635,0.00635,0.00573,0.0582,0.0582,0.0257,2.74e-11,2.73e-11,1.33e-10,2.66e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30090000,-0.252,0.0138,-0.00697,0.968,0.0161,-0.0233,0.73,0.0365,-0.0482,-0.833,-1.19e-05,-5.78e-05,4.3e-06,7.9e-05,-0.000328,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.06e-05,7.75e-05,7.76e-05,0.000323,0.00687,0.00687,0.0059,0.0599,0.0599,0.026,2.75e-11,2.74e-11,1.32e-10,2.66e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30190000,-0.252,0.0137,-0.00708,0.968,0.0118,-0.0146,0.731,0.0327,-0.0395,-0.76,-1.17e-05,-5.78e-05,4.2e-06,7.78e-05,-0.000338,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.05e-05,7.72e-05,7.73e-05,0.000322,0.00634,0.00634,0.00573,0.0598,0.0598,0.0257,2.71e-11,2.7e-11,1.3e-10,2.66e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30290000,-0.252,0.0137,-0.00709,0.968,0.00959,-0.0141,0.731,0.0337,-0.041,-0.689,-1.17e-05,-5.78e-05,4.25e-06,7.81e-05,-0.000338,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.03e-05,7.74e-05,7.75e-05,0.000322,0.00686,0.00686,0.00591,0.0616,0.0616,0.0261,2.72e-11,2.71e-11,1.29e-10,2.66e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30390000,-0.252,0.0135,-0.00715,0.968,0.00868,-0.00638,0.729,0.0348,-0.0351,-0.621,-1.16e-05,-5.78e-05,4.42e-06,7.58e-05,-0.000345,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,7.01e-05,7.7e-05,7.71e-05,0.000322,0.00633,0.00634,0.00572,0.0614,0.0614,0.0256,2.69e-11,2.67e-11,1.28e-10,2.66e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30490000,-0.252,0.0137,-0.00713,0.968,0.0103,-0.005,0.731,0.0358,-0.0357,-0.547,-1.16e-05,-5.78e-05,4.53e-06,7.6e-05,-0.000345,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,6.99e-05,7.72e-05,7.73e-05,0.000322,0.00685,0.00685,0.00591,0.0632,0.0632,0.0261,2.7e-11,2.68e-11,1.26e-10,2.66e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30590000,-0.252,0.0139,-0.00743,0.968,0.0102,-0.00262,0.731,0.0348,-0.033,-0.474,-1.15e-05,-5.78e-05,4.67e-06,7.66e-05,-0.000349,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,6.97e-05,7.69e-05,7.69e-05,0.000322,0.00632,0.00633,0.00573,0.063,0.063,0.0257,2.66e-11,2.65e-11,1.25e-10,2.66e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30690000,-0.252,0.0141,-0.00779,0.968,0.00697,-0.000769,0.731,0.0357,-0.0332,-0.402,-1.15e-05,-5.78e-05,4.71e-06,7.68e-05,-0.000349,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,6.95e-05,7.7e-05,7.71e-05,0.000322,0.00684,0.00684,0.0059,0.0648,0.0648,0.026,2.67e-11,2.66e-11,1.24e-10,2.66e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30790000,-0.252,0.0137,-0.00766,0.968,0.000431,0.0111,0.73,0.0306,-0.0224,-0.331,-1.14e-05,-5.78e-05,4.74e-06,7.66e-05,-0.00036,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.94e-05,7.67e-05,7.67e-05,0.000322,0.00631,0.00632,0.00573,0.0646,0.0646,0.0258,2.63e-11,2.62e-11,1.22e-10,2.65e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30890000,-0.252,0.0136,-0.00703,0.968,-0.000683,0.0153,0.728,0.0305,-0.0211,-0.259,-1.14e-05,-5.78e-05,4.69e-06,7.65e-05,-0.00036,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.92e-05,7.68e-05,7.69e-05,0.000322,0.00683,0.00684,0.00591,0.0664,0.0664,0.0261,2.64e-11,2.63e-11,1.21e-10,2.65e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30990000,-0.252,0.0135,-0.00709,0.968,-0.00209,0.0146,0.731,0.0306,-0.0229,-0.188,-1.14e-05,-5.78e-05,4.71e-06,7.82e-05,-0.000358,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.89e-05,7.64e-05,7.65e-05,0.000322,0.0063,0.00631,0.00572,0.0662,0.0662,0.0257,2.61e-11,2.6e-11,1.2e-10,2.65e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31090000,-0.252,0.0136,-0.00722,0.968,-0.00406,0.0166,0.731,0.0303,-0.0213,-0.113,-1.14e-05,-5.78e-05,4.68e-06,7.8e-05,-0.000357,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.89e-05,7.66e-05,7.66e-05,0.000322,0.00681,0.00682,0.00591,0.068,0.068,0.0262,2.62e-11,2.61e-11,1.19e-10,2.65e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31190000,-0.252,0.0136,-0.00737,0.968,-0.00487,0.0197,0.735,0.0286,-0.0187,-0.0397,-1.14e-05,-5.78e-05,4.85e-06,7.89e-05,-0.000359,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.87e-05,7.62e-05,7.63e-05,0.000322,0.00629,0.0063,0.00572,0.0677,0.0677,0.0257,2.58e-11,2.57e-11,1.17e-10,2.65e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31290000,-0.252,0.0137,-0.0076,0.968,-0.00827,0.0231,0.74,0.0279,-0.0167,0.0332,-1.14e-05,-5.78e-05,4.95e-06,7.92e-05,-0.000359,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.84e-05,7.64e-05,7.64e-05,0.000322,0.00679,0.00681,0.0059,0.0696,0.0696,0.0261,2.59e-11,2.58e-11,1.16e-10,2.65e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31390000,-0.252,0.0135,-0.00731,0.968,-0.012,0.0249,0.738,0.0244,-0.017,0.106,-1.14e-05,-5.78e-05,4.89e-06,8.29e-05,-0.000358,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.82e-05,7.6e-05,7.61e-05,0.000322,0.00628,0.00629,0.00571,0.0693,0.0693,0.0256,2.56e-11,2.55e-11,1.15e-10,2.65e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31490000,-0.252,0.0138,-0.00701,0.968,-0.013,0.0287,0.736,0.0232,-0.0143,0.18,-1.14e-05,-5.78e-05,4.89e-06,8.28e-05,-0.000358,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.81e-05,7.62e-05,7.62e-05,0.000322,0.00678,0.0068,0.0059,0.0711,0.0711,0.0261,2.57e-11,2.56e-11,1.14e-10,2.65e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31590000,-0.252,0.0141,-0.00679,0.968,-0.00962,0.0288,0.74,0.0248,-0.0132,0.252,-1.14e-05,-5.78e-05,4.99e-06,8.19e-05,-0.000355,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.79e-05,7.58e-05,7.58e-05,0.000322,0.00627,0.00628,0.00572,0.0709,0.0709,0.0257,2.54e-11,2.53e-11,1.13e-10,2.65e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31690000,-0.252,0.0146,-0.00675,0.968,-0.00814,0.0312,0.737,0.0239,-0.0102,0.324,-1.14e-05,-5.78e-05,5.12e-06,8.24e-05,-0.000356,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.77e-05,7.6e-05,7.6e-05,0.000322,0.00677,0.00679,0.00589,0.0727,0.0727,0.026,2.55e-11,2.54e-11,1.12e-10,2.65e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31790000,-0.251,0.0151,-0.00698,0.968,-0.0106,0.0371,0.738,0.0248,-0.0028,0.396,-1.14e-05,-5.78e-05,5.2e-06,7.94e-05,-0.000358,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.76e-05,7.56e-05,7.56e-05,0.000322,0.00626,0.00627,0.00572,0.0725,0.0725,0.0257,2.52e-11,2.51e-11,1.11e-10,2.64e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31890000,-0.251,0.0149,-0.00673,0.968,-0.0143,0.04,0.737,0.0235,0.0011,0.467,-1.14e-05,-5.78e-05,5.28e-06,7.97e-05,-0.000358,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,6.74e-05,7.57e-05,7.57e-05,0.000322,0.00676,0.00678,0.0059,0.0743,0.0743,0.0261,2.53e-11,2.52e-11,1.09e-10,2.64e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31990000,-0.251,0.0143,-0.00698,0.968,-0.0148,0.0392,0.734,0.0251,0.00297,0.534,-1.14e-05,-5.79e-05,5.24e-06,7.88e-05,-0.000355,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,6.72e-05,7.54e-05,7.54e-05,0.000322,0.00625,0.00626,0.00571,0.0741,0.0741,0.0256,2.5e-11,2.49e-11,1.08e-10,2.64e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32090000,-0.251,0.014,-0.00737,0.968,-0.0147,0.0437,0.737,0.0236,0.00705,0.607,-1.14e-05,-5.79e-05,5.26e-06,7.89e-05,-0.000355,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,6.71e-05,7.55e-05,7.55e-05,0.000322,0.00675,0.00677,0.0059,0.0759,0.0759,0.0261,2.51e-11,2.5e-11,1.07e-10,2.64e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32190000,-0.251,0.0142,-0.00757,0.968,-0.0154,0.0494,0.737,0.0231,0.0128,0.675,-1.14e-05,-5.79e-05,5.24e-06,7.82e-05,-0.000355,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.69e-05,7.52e-05,7.52e-05,0.000321,0.00623,0.00625,0.00572,0.0757,0.0757,0.0257,2.48e-11,2.47e-11,1.06e-10,2.64e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32290000,-0.251,0.0145,-0.00746,0.968,-0.0173,0.053,0.736,0.0215,0.018,0.746,-1.14e-05,-5.79e-05,5.32e-06,7.86e-05,-0.000356,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.67e-05,7.53e-05,7.53e-05,0.000321,0.00673,0.00676,0.00589,0.0775,0.0775,0.026,2.49e-11,2.48e-11,1.05e-10,2.64e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32390000,-0.251,0.0145,-0.0075,0.968,-0.0184,0.0518,0.733,0.0213,0.0184,0.816,-1.15e-05,-5.79e-05,5.29e-06,8.02e-05,-0.00035,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.66e-05,7.5e-05,7.5e-05,0.000321,0.00623,0.00625,0.00572,0.0772,0.0772,0.0258,2.46e-11,2.45e-11,1.04e-10,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32490000,-0.251,0.0126,-0.0105,0.968,-0.0528,0.115,-0.139,0.0169,0.0287,0.821,-1.15e-05,-5.79e-05,5.26e-06,8.02e-05,-0.00035,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.64e-05,7.51e-05,7.51e-05,0.000321,0.00806,0.00813,0.00577,0.0791,0.0791,0.0261,2.47e-11,2.46e-11,1.03e-10,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32590000,-0.251,0.0123,-0.00978,0.968,-0.0412,0.104,-0.137,0.0231,0.0199,0.81,-1.18e-05,-5.79e-05,5.33e-06,8.02e-05,-0.00035,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.62e-05,7.22e-05,7.21e-05,0.000321,0.0083,0.00835,0.00541,0.0788,0.0788,0.0256,2.43e-11,2.43e-11,1.02e-10,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32690000,-0.251,0.0122,-0.00977,0.968,-0.0368,0.11,-0.138,0.0192,0.0307,0.796,-1.18e-05,-5.79e-05,5.3e-06,8.02e-05,-0.00035,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.6e-05,7.23e-05,7.22e-05,0.000321,0.0105,0.0105,0.0054,0.0807,0.0807,0.0259,2.44e-11,2.44e-11,1.01e-10,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32790000,-0.251,0.0121,-0.00861,0.968,-0.0249,0.0942,-0.135,0.0234,0.0227,0.787,-1.21e-05,-5.78e-05,5.34e-06,8.02e-05,-0.00035,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.59e-05,6.52e-05,6.51e-05,0.00032,0.0105,0.0105,0.00511,0.0804,0.0804,0.0257,2.41e-11,2.4e-11,1e-10,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32890000,-0.251,0.0121,-0.00857,0.968,-0.0237,0.0985,-0.136,0.0209,0.0323,0.773,-1.21e-05,-5.78e-05,5.32e-06,8.02e-05,-0.00035,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.57e-05,6.53e-05,6.52e-05,0.00032,0.0132,0.0132,0.00511,0.0822,0.0822,0.0259,2.42e-11,2.41e-11,9.95e-11,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32990000,-0.251,0.0121,-0.00724,0.968,-0.013,0.0733,-0.131,0.0235,0.0217,0.767,-1.24e-05,-5.77e-05,5.32e-06,8.02e-05,-0.00035,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.55e-05,5.54e-05,5.53e-05,0.00032,0.0123,0.0123,0.00484,0.082,0.082,0.0255,2.39e-11,2.39e-11,9.86e-11,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33090000,-0.251,0.0121,-0.0072,0.968,-0.00746,0.074,-0.129,0.0225,0.029,0.757,-1.24e-05,-5.77e-05,5.22e-06,8.02e-05,-0.00035,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.54e-05,5.55e-05,5.53e-05,0.00032,0.0152,0.0153,0.00485,0.0838,0.0838,0.0259,2.4e-11,2.4e-11,9.78e-11,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33190000,-0.251,0.0122,-0.00609,0.968,0.000446,0.049,-0.124,0.0234,0.0192,0.753,-1.25e-05,-5.76e-05,5.05e-06,7.16e-05,-0.000368,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.52e-05,4.51e-05,4.49e-05,0.00032,0.0138,0.0138,0.00462,0.0836,0.0836,0.0254,2.39e-11,2.39e-11,9.68e-11,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33290000,-0.251,0.0123,-0.00613,0.968,0.0055,0.0454,-0.125,0.0237,0.024,0.74,-1.25e-05,-5.76e-05,5.03e-06,7.16e-05,-0.000368,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.51e-05,4.52e-05,4.5e-05,0.00032,0.0175,0.0175,0.00465,0.0854,0.0854,0.0256,2.4e-11,2.4e-11,9.59e-11,2.64e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33390000,-0.251,0.0124,-0.00589,0.968,0.00929,0.0331,-0.121,0.0232,0.0233,0.734,-1.25e-05,-5.76e-05,4.95e-06,5.08e-05,-0.000387,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.5e-05,3.62e-05,3.6e-05,0.00032,0.0153,0.0153,0.00448,0.0852,0.0852,0.0254,2.4e-11,2.4e-11,9.52e-11,2.57e-06,2.57e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33490000,-0.251,0.0124,-0.00587,0.968,0.0152,0.0295,-0.121,0.0245,0.0264,0.72,-1.25e-05,-5.76e-05,4.85e-06,5.08e-05,-0.000387,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.48e-05,3.63e-05,3.61e-05,0.00032,0.0192,0.0192,0.00453,0.087,0.087,0.0255,2.41e-11,2.41e-11,9.43e-11,2.57e-06,2.57e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33590000,-0.251,0.0126,-0.0056,0.968,0.0146,0.0177,-0.114,0.0232,0.0235,0.717,-1.26e-05,-5.76e-05,4.8e-06,5.64e-06,-0.000412,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.46e-05,2.98e-05,2.96e-05,0.00032,0.0161,0.0161,0.00438,0.0868,0.0868,0.0251,2.41e-11,2.41e-11,9.34e-11,2.43e-06,2.43e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33690000,-0.251,0.0125,-0.00559,0.968,0.0199,0.0135,-0.117,0.0249,0.0251,0.705,-1.26e-05,-5.76e-05,4.72e-06,5.61e-06,-0.000412,-0.00103,-0.202,-0.0311,0.435,0,0,0,0,0,6.45e-05,2.99e-05,2.97e-05,0.00032,0.0198,0.0198,0.00447,0.0886,0.0886,0.0254,2.42e-11,2.42e-11,9.27e-11,2.43e-06,2.43e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33790000,-0.251,0.0127,-0.00557,0.968,0.0184,0.00602,-0.108,0.0232,0.0238,0.701,-1.26e-05,-5.76e-05,4.58e-06,-3.89e-05,-0.000411,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,6.43e-05,2.59e-05,2.57e-05,0.00032,0.0161,0.0161,0.00435,0.0884,0.0884,0.025,2.43e-11,2.43e-11,9.19e-11,2.26e-06,2.26e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33890000,-0.252,0.0126,-0.00559,0.968,0.023,-0.000356,-0.109,0.0253,0.0241,0.69,-1.26e-05,-5.76e-05,4.54e-06,-3.89e-05,-0.000411,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,6.42e-05,2.6e-05,2.58e-05,0.00032,0.0195,0.0195,0.00445,0.0902,0.0902,0.0252,2.44e-11,2.44e-11,9.1e-11,2.26e-06,2.26e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33990000,-0.252,0.0127,-0.00572,0.968,0.0221,0.00307,-0.103,0.0252,0.0279,0.687,-1.26e-05,-5.76e-05,4.4e-06,-4.55e-05,-0.000367,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,6.4e-05,2.37e-05,2.35e-05,0.00032,0.0156,0.0156,0.00434,0.09,0.09,0.0248,2.45e-11,2.45e-11,9.02e-11,2.09e-06,2.09e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34090000,-0.252,0.0127,-0.00567,0.968,0.0262,0.000657,-0.104,0.0276,0.0281,0.676,-1.26e-05,-5.76e-05,4.31e-06,-4.56e-05,-0.000367,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,6.39e-05,2.37e-05,2.35e-05,0.00032,0.0186,0.0186,0.00447,0.0917,0.0917,0.0251,2.46e-11,2.46e-11,8.95e-11,2.09e-06,2.09e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34190000,-0.252,0.0128,-0.00581,0.968,0.0219,0.000727,-0.101,0.0253,0.0299,0.67,-1.26e-05,-5.75e-05,4.27e-06,-7.83e-05,-0.00033,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,6.38e-05,2.25e-05,2.23e-05,0.00032,0.0149,0.0149,0.00439,0.0916,0.0916,0.0247,2.47e-11,2.47e-11,8.87e-11,1.93e-06,1.93e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34290000,-0.252,0.0128,-0.00567,0.968,0.0218,-0.00225,-0.101,0.0275,0.0299,0.66,-1.26e-05,-5.75e-05,4.22e-06,-7.83e-05,-0.00033,-0.00104,-0.202,-0.0311,0.435,0,0,0,0,0,6.36e-05,2.26e-05,2.24e-05,0.00032,0.0174,0.0174,0.00452,0.0933,0.0933,0.0248,2.48e-11,2.48e-11,8.8e-11,1.93e-06,1.93e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34390000,-0.252,0.0128,-0.00574,0.968,0.0183,-0.00206,-0.0927,0.0256,0.0319,0.659,-1.26e-05,-5.75e-05,4.16e-06,-0.000104,-0.000292,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.35e-05,2.2e-05,2.18e-05,0.00032,0.014,0.014,0.00446,0.0932,0.0932,0.0246,2.49e-11,2.49e-11,8.73e-11,1.79e-06,1.79e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34490000,-0.252,0.0128,-0.00581,0.968,0.0202,-0.0042,-0.0929,0.0275,0.0316,0.649,-1.26e-05,-5.75e-05,4.14e-06,-0.000104,-0.000292,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.34e-05,2.2e-05,2.19e-05,0.00032,0.0162,0.0162,0.00461,0.0949,0.0949,0.0247,2.5e-11,2.5e-11,8.65e-11,1.79e-06,1.79e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34590000,-0.252,0.0126,-0.00583,0.968,0.0142,-0.0055,0.705,0.0256,0.0318,0.679,-1.26e-05,-5.75e-05,4.07e-06,-0.000132,-0.000269,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,6.32e-05,2.18e-05,2.16e-05,0.00032,0.013,0.013,0.00454,0.0948,0.0948,0.0244,2.51e-11,2.51e-11,8.58e-11,1.67e-06,1.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34690000,-0.252,0.0123,-0.00584,0.968,0.0147,-0.00854,1.7,0.0271,0.0311,0.799,-1.26e-05,-5.75e-05,4.01e-06,-0.000132,-0.000269,-0.00106,-0.202,-0.0311,0.435,0,0,0,0,0,6.31e-05,2.18e-05,2.17e-05,0.00032,0.0147,0.0147,0.00471,0.0965,0.0965,0.0247,2.52e-11,2.52e-11,8.52e-11,1.67e-06,1.67e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34790000,-0.252,0.012,-0.00585,0.968,0.0109,-0.00906,2.69,0.0257,0.0318,1.02,-1.26e-05,-5.75e-05,3.94e-06,-0.000146,-0.000245,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.3e-05,2.19e-05,2.17e-05,0.00032,0.0123,0.0123,0.00488,0.0964,0.0964,0.0248,2.53e-11,2.53e-11,8.44e-11,1.52e-06,1.52e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34890000,-0.252,0.0117,-0.00585,0.968,0.0112,-0.012,3.67,0.0268,0.0308,1.32,-1.26e-05,-5.75e-05,3.87e-06,-0.000144,-0.000246,-0.00105,-0.202,-0.0311,0.435,0,0,0,0,0,6.28e-05,2.19e-05,2.18e-05,0.00032,0.0141,0.0141,0.00505,0.0981,0.0981,0.025,2.54e-11,2.54e-11,8.37e-11,1.52e-06,1.52e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
|
||||
|
@@ -15,9 +15,9 @@ Gps::~Gps()
|
||||
|
||||
void Gps::send(const uint64_t time)
|
||||
{
|
||||
const float dt = static_cast<float>(time - _gps_data.time_usec) * 1e-6f;
|
||||
const float dt = static_cast<float>(time - _gps_data.time_us) * 1e-6f;
|
||||
|
||||
_gps_data.time_usec = time;
|
||||
_gps_data.time_us = time;
|
||||
|
||||
if (fabsf(_gps_pos_rate(0)) > FLT_EPSILON || fabsf(_gps_pos_rate(1)) > FLT_EPSILON) {
|
||||
stepHorizontalPositionByMeters(Vector2f(_gps_pos_rate) * dt);
|
||||
@@ -30,29 +30,29 @@ void Gps::send(const uint64_t time)
|
||||
_ekf->setGpsData(_gps_data);
|
||||
}
|
||||
|
||||
void Gps::setData(const gpsMessage &gps)
|
||||
void Gps::setData(const gpsSample &gps)
|
||||
{
|
||||
_gps_data = gps;
|
||||
}
|
||||
|
||||
void Gps::setAltitude(const int32_t alt)
|
||||
void Gps::setAltitude(const float alt)
|
||||
{
|
||||
_gps_data.alt = alt;
|
||||
}
|
||||
|
||||
void Gps::setLatitude(const int32_t lat)
|
||||
void Gps::setLatitude(const double lat)
|
||||
{
|
||||
_gps_data.lat = lat;
|
||||
}
|
||||
|
||||
void Gps::setLongitude(const int32_t lon)
|
||||
void Gps::setLongitude(const double lon)
|
||||
{
|
||||
_gps_data.lon = lon;
|
||||
}
|
||||
|
||||
void Gps::setVelocity(const Vector3f &vel)
|
||||
{
|
||||
_gps_data.vel_ned = vel;
|
||||
_gps_data.vel = vel;
|
||||
}
|
||||
|
||||
void Gps::setYaw(const float yaw)
|
||||
@@ -87,7 +87,7 @@ void Gps::setPositionRateNED(const Vector3f &rate)
|
||||
|
||||
void Gps::stepHeightByMeters(const float hgt_change)
|
||||
{
|
||||
_gps_data.alt += hgt_change * 1e3f;
|
||||
_gps_data.alt += hgt_change;
|
||||
}
|
||||
|
||||
void Gps::stepHorizontalPositionByMeters(const Vector2f hpos_change)
|
||||
@@ -95,35 +95,32 @@ void Gps::stepHorizontalPositionByMeters(const Vector2f hpos_change)
|
||||
float hposN_curr {0.f};
|
||||
float hposE_curr {0.f};
|
||||
|
||||
double lat_new {0.0};
|
||||
double lon_new {0.0};
|
||||
|
||||
_ekf->global_origin().project(_gps_data.lat * 1e-7, _gps_data.lon * 1e-7, hposN_curr, hposE_curr);
|
||||
_ekf->global_origin().project(_gps_data.lat, _gps_data.lon, hposN_curr, hposE_curr);
|
||||
|
||||
Vector2f hpos_new = Vector2f{hposN_curr, hposE_curr} + hpos_change;
|
||||
|
||||
double lat_new {0.0};
|
||||
double lon_new {0.0};
|
||||
_ekf->global_origin().reproject(hpos_new(0), hpos_new(1), lat_new, lon_new);
|
||||
|
||||
_gps_data.lon = static_cast<int32_t>(lon_new * 1e7);
|
||||
_gps_data.lat = static_cast<int32_t>(lat_new * 1e7);
|
||||
_gps_data.lat = lat_new;
|
||||
_gps_data.lon = lon_new;
|
||||
}
|
||||
|
||||
gpsMessage Gps::getDefaultGpsData()
|
||||
gpsSample Gps::getDefaultGpsData()
|
||||
{
|
||||
gpsMessage gps_data{};
|
||||
gps_data.time_usec = 0;
|
||||
gps_data.lat = 473566094;
|
||||
gps_data.lon = 85190237;
|
||||
gps_data.alt = 422056;
|
||||
gpsSample gps_data{};
|
||||
gps_data.time_us = 0;
|
||||
gps_data.lat = 47.3566094;
|
||||
gps_data.lon = 85.190237;
|
||||
gps_data.alt = 422.056;
|
||||
gps_data.yaw = NAN;
|
||||
gps_data.yaw_offset = 0.0f;
|
||||
gps_data.fix_type = 3;
|
||||
gps_data.eph = 0.5f;
|
||||
gps_data.epv = 0.8f;
|
||||
gps_data.hacc = 0.5f;
|
||||
gps_data.vacc = 0.8f;
|
||||
gps_data.sacc = 0.2f;
|
||||
gps_data.vel_m_s = 0.0;
|
||||
gps_data.vel_ned.setZero();
|
||||
gps_data.vel_ned_valid = 1;
|
||||
gps_data.vel.setZero();
|
||||
gps_data.nsats = 16;
|
||||
gps_data.pdop = 0.0f;
|
||||
|
||||
|
||||
@@ -51,13 +51,13 @@ public:
|
||||
Gps(std::shared_ptr<Ekf> ekf);
|
||||
~Gps();
|
||||
|
||||
void setData(const gpsMessage &gps);
|
||||
void setData(const gpsSample &gps);
|
||||
void stepHeightByMeters(const float hgt_change);
|
||||
void stepHorizontalPositionByMeters(const Vector2f hpos_change);
|
||||
void setPositionRateNED(const Vector3f &rate);
|
||||
void setAltitude(const int32_t alt);
|
||||
void setLatitude(const int32_t lat);
|
||||
void setLongitude(const int32_t lon);
|
||||
void setAltitude(const float alt);
|
||||
void setLatitude(const double lat);
|
||||
void setLongitude(const double lon);
|
||||
void setVelocity(const Vector3f &vel);
|
||||
void setYaw(const float yaw);
|
||||
void setYawOffset(const float yaw);
|
||||
@@ -65,12 +65,12 @@ public:
|
||||
void setNumberOfSatellites(const int num_satellites);
|
||||
void setPdop(const float pdop);
|
||||
|
||||
gpsMessage getDefaultGpsData();
|
||||
gpsSample getDefaultGpsData();
|
||||
|
||||
private:
|
||||
void send(uint64_t time) override;
|
||||
|
||||
gpsMessage _gps_data{};
|
||||
gpsSample _gps_data{};
|
||||
Vector3f _gps_pos_rate{};
|
||||
};
|
||||
|
||||
|
||||
@@ -251,9 +251,9 @@ void SensorSimulator::setSingleReplaySample(const sensor_info &sample)
|
||||
_baro.setData((float) sample.sensor_data[0]);
|
||||
|
||||
} else if (sample.sensor_type == sensor_info::measurement_t::GPS) {
|
||||
_gps.setAltitude((int32_t) sample.sensor_data[0]);
|
||||
_gps.setLatitude((int32_t) sample.sensor_data[1]);
|
||||
_gps.setLongitude((int32_t) sample.sensor_data[2]);
|
||||
_gps.setAltitude(sample.sensor_data[0]);
|
||||
_gps.setLatitude(sample.sensor_data[1]);
|
||||
_gps.setLongitude(sample.sensor_data[2]);
|
||||
_gps.setVelocity(Vector3f((float) sample.sensor_data[3],
|
||||
(float) sample.sensor_data[4],
|
||||
(float) sample.sensor_data[5]));
|
||||
@@ -389,20 +389,17 @@ void SensorSimulator::setSensorDataFromTrajectory()
|
||||
|
||||
void SensorSimulator::setGpsLatitude(const double latitude)
|
||||
{
|
||||
int32_t lat = static_cast<int32_t>(latitude * 1e7);
|
||||
_gps.setLatitude(lat);
|
||||
_gps.setLatitude(latitude);
|
||||
}
|
||||
|
||||
void SensorSimulator::setGpsLongitude(const double longitude)
|
||||
{
|
||||
int32_t lon = static_cast<int32_t>(longitude * 1e7);
|
||||
_gps.setLongitude(lon);
|
||||
_gps.setLongitude(longitude);
|
||||
}
|
||||
|
||||
void SensorSimulator::setGpsAltitude(const float altitude)
|
||||
{
|
||||
int32_t alt = static_cast<int32_t>(altitude * 1e3f);
|
||||
_gps.setAltitude(alt);
|
||||
_gps.setAltitude(altitude);
|
||||
}
|
||||
|
||||
void SensorSimulator::setImuBias(Vector3f accel_bias, Vector3f gyro_bias)
|
||||
|
||||
@@ -162,6 +162,8 @@ TEST_F(EkfFusionLogicTest, rejectGpsSignalJump)
|
||||
pos_new = _ekf->getPosition();
|
||||
vel_new = _ekf->getVelocity();
|
||||
accel_bias_new = _ekf->getAccelBias();
|
||||
pos_new.print();
|
||||
pos_old.print();
|
||||
EXPECT_TRUE(matrix::isEqual(pos_new, pos_old + pos_step, 0.01f));
|
||||
EXPECT_TRUE(matrix::isEqual(vel_new, vel_old, 0.01f));
|
||||
EXPECT_TRUE(matrix::isEqual(accel_bias_new, accel_bias_old, 0.01f));
|
||||
|
||||
Reference in New Issue
Block a user